diff --git a/.gitignore b/.gitignore index 702e14eb8..cd408865e 100644 --- a/.gitignore +++ b/.gitignore @@ -175,6 +175,17 @@ cython_debug/ .vscode/ setup/zed_sdk.run +cuda/ +#Ignore ROS bags +*.bag + +*.png +*.npz +/4.21 +/4.30 +/5.9 +/parking_data +/perception_4.9 #Ignore ROS bags *.bag diff --git a/GEMstack/.DS_Store b/GEMstack/.DS_Store new file mode 100644 index 000000000..16bcfc4e7 Binary files /dev/null and b/GEMstack/.DS_Store differ diff --git a/GEMstack/knowledge/calibration/cameras.yaml b/GEMstack/knowledge/calibration/cameras.yaml index cd5477a18..4872db65d 100644 --- a/GEMstack/knowledge/calibration/cameras.yaml +++ b/GEMstack/knowledge/calibration/cameras.yaml @@ -1,35 +1,35 @@ -cameras: - front: - K: - - [684.83331299, 0.0, 573.37109375] - - [0.0, 684.60968018, 363.70092773] - - [0.0, 0.0, 1.0] - D: [0.0, 0.0, 0.0, 0.0, 0.0] - T_l2c: - - [ 0.0289748006, -0.999580136, 0.0000368439, -0.0307300513] - - [-0.0094993062, -0.0003122155, -0.999954834, -0.386689354 ] - - [ 0.999534999, 0.0289731321, -0.0095043721, -0.671425124 ] - - [ 0.0, 0.0, 0.0, 1.0 ] - T_l2v: - - [ 0.99939639, 0.02547917, 0.023615, 1.1 ] - - [ -0.02530848, 0.99965156, -0.00749882, 0.03773583 ] - - [ -0.02379784, 0.00689664, 0.999693, 1.95320223 ] - - [ 0.0, 0.0, 0.0, 1.0 ] - - front_right: - K: - - [1176.25545, 0.0, 966.432645] - - [0.0, 1175.14569, 608.580326] - - [0.0, 0.0, 1.0 ] - D: [-0.270136325, 0.164393255, -0.00160720782, -0.0000741246708, -0.0619939758] - T_l2c: - - [-0.71836368, -0.69527204, -0.02346088, 0.05718003] - - [-0.09720448, 0.13371206, -0.98624154, -0.15983010] - - [ 0.68884317, -0.70619960, -0.16363744, -1.04767285] - - [ 0.0, 0.0, 0.0, 1.0 ] - T_l2v: - - [0.99939639, 0.02547917, 0.023615, 1.1] - - [-0.02530848, 0.99965156, -0.00749882, 0.03773583] - - [-0.02379784, 0.00689664, 0.999693, 1.95320223] - - [0.0, 0.0, 0.0, 1.0 ] - +cameras: + front: + K: + - [684.83331299, 0.0, 573.37109375] + - [0.0, 684.60968018, 363.70092773] + - [0.0, 0.0, 1.0] + D: [0.0, 0.0, 0.0, 0.0, 0.0] + T_l2c: + - [ 0.0289748006, -0.999580136, 0.0000368439, -0.0307300513] + - [-0.0094993062, -0.0003122155, -0.999954834, -0.386689354 ] + - [ 0.999534999, 0.0289731321, -0.0095043721, -0.671425124 ] + - [ 0.0, 0.0, 0.0, 1.0 ] + T_l2v: + - [ 0.99939639, 0.02547917, 0.023615, 1.1 ] + - [ -0.02530848, 0.99965156, -0.00749882, 0.03773583 ] + - [ -0.02379784, 0.00689664, 0.999693, 1.95320223 ] + - [ 0.0, 0.0, 0.0, 1.0 ] + + front_right: + K: + - [1176.25545, 0.0, 966.432645] + - [0.0, 1175.14569, 608.580326] + - [0.0, 0.0, 1.0 ] + D: [-0.270136325, 0.164393255, -0.00160720782, -0.0000741246708, -0.0619939758] + T_l2c: + - [-0.71836368, -0.69527204, -0.02346088, 0.05718003] + - [-0.09720448, 0.13371206, -0.98624154, -0.15983010] + - [ 0.68884317, -0.70619960, -0.16363744, -1.04767285] + - [ 0.0, 0.0, 0.0, 1.0 ] + T_l2v: + - [0.99939639, 0.02547917, 0.023615, 1.1] + - [-0.02530848, 0.99965156, -0.00749882, 0.03773583] + - [-0.02379784, 0.00689664, 0.999693, 1.95320223] + - [0.0, 0.0, 0.0, 1.0 ] + diff --git a/GEMstack/knowledge/calibration/gem_e4.yaml b/GEMstack/knowledge/calibration/gem_e4.yaml index ef1f4f30e..da2304fe8 100644 --- a/GEMstack/knowledge/calibration/gem_e4.yaml +++ b/GEMstack/knowledge/calibration/gem_e4.yaml @@ -1,6 +1,6 @@ -calibration_date: "2024-03-05" # Date of calibration YYYY-MM-DD +calibration_date: "2025-02-25" # Date of calibration YYYY-MM-DD reference: rear_axle_center # rear axle center -rear_axle_height: 0.33 # height of rear axle center above flat ground +rear_axle_height: 0.2794 # height of rear axle center above flat ground gnss_location: [1.10,0,1.62] # meters, taken from https://github.com/hangcui1201/POLARIS_GEM_e2_Real/blob/main/vehicle_drivers/gem_gnss_control/scripts/gem_gnss_tracker_stanley_rtk.py. Note conflict with pure pursuit location? gnss_yaw: 0.0 # radians top_lidar: !include "gem_e4_ouster.yaml" diff --git a/GEMstack/knowledge/calibration/gem_e4_lidar_cam.yaml b/GEMstack/knowledge/calibration/gem_e4_lidar_cam.yaml new file mode 100644 index 000000000..5abb40423 --- /dev/null +++ b/GEMstack/knowledge/calibration/gem_e4_lidar_cam.yaml @@ -0,0 +1,9 @@ +# Calibration for top lidar->front rgb camera on GEM e4 +# Calibration Date: 02/25/2025 05:09 + +lidar_to_camera: [ + [ 2.89748006e-02, -9.99580136e-01, 3.68439439e-05, -3.07300513e-02], + [-9.49930618e-03, -3.12215512e-04, -9.99954834e-01, -3.86689354e-01], + [ 9.99534999e-01, 2.89731321e-02, -9.50437214e-03, -6.71425124e-01], + [ 0.00000000e+00, 0.00000000e+00, 0.00000000e+00, 1.00000000e+00] + ] \ No newline at end of file diff --git a/GEMstack/knowledge/calibration/gem_e4_ouster.yaml b/GEMstack/knowledge/calibration/gem_e4_ouster.yaml index 47897f62a..e5d54bb85 100644 --- a/GEMstack/knowledge/calibration/gem_e4_ouster.yaml +++ b/GEMstack/knowledge/calibration/gem_e4_ouster.yaml @@ -1,5 +1,8 @@ +# Calibration for top lidar->vehicle on GEM e4 +# Calibration Date: 02/25/2025 05:09 + reference: rear_axle_center # rear axle center position: [1.10, 0.03773583, 1.95320223] # meters, calibrated by Hang's watchful eye rotation: [[0.99939639, 0.02547917, 0.023615], [-0.02530848, 0.99965156, -0.00749882], - [-0.02379784, 0.00689664, 0.999693]] #rotation matrix mapping lidar frame to vehicle frame \ No newline at end of file + [-0.02379784, 0.00689664, 0.999693]] #rotation matrix mapping lidar frame to vehicle frame diff --git a/GEMstack/knowledge/defaults/computation_graph.yaml b/GEMstack/knowledge/defaults/computation_graph.yaml index 505b85684..4892a84ed 100644 --- a/GEMstack/knowledge/defaults/computation_graph.yaml +++ b/GEMstack/knowledge/defaults/computation_graph.yaml @@ -34,7 +34,7 @@ components: inputs: [vehicle, roadgraph, agents] outputs: agent_intents - relations_estimation: - inputs: [vehicle, roadgraph, agents, obstacles] + inputs: all outputs: relations - predicate_evaluation: inputs: [vehicle, roadgraph, agents, obstacles] @@ -75,4 +75,4 @@ components: outputs: - gazebo_collision_logger: inputs: [] - outputs: \ No newline at end of file + outputs: diff --git a/GEMstack/knowledge/defaults/current.yaml b/GEMstack/knowledge/defaults/current.yaml index c886288be..1a947ef54 100644 --- a/GEMstack/knowledge/defaults/current.yaml +++ b/GEMstack/knowledge/defaults/current.yaml @@ -13,22 +13,34 @@ control: brake_speed : 2.0 pure_pursuit: lookahead: 2.0 - lookahead_scale: 3.0 - crosstrack_gain: 1.0 + lookahead_scale: 2.0 + crosstrack_gain: 0.3 desired_speed: trajectory longitudinal_control: - pid_p: 1.0 - pid_i: 0.1 + pid_p: 0.8 + pid_i: 0.03 pid_d: 0.0 +planning: + longitudinal_plan: + mode: 'real' # 'real' or 'sim' + yielder: 'expert' # 'expert', 'analytic', or 'simulation' + planner: 'dt' # 'milestone', 'dt', or 'dx' + desired_speed: 1.0 + acceleration: 0.5 + max_deceleration: 6.0 + deceleration: 2.0 + min_deceleration: 0.5 + yield_deceleration: 0.5 + #configure the simulator, if using simulator: dt: 0.01 real_time_multiplier: 1.0 # make the simulator run faster than real time by making this > 1 gnss_emulator: - dt: 0.1 #10Hz + dt: 0.05 #10Hz #position_noise: 0.1 #10cm noise #orientation_noise: 0.04 #2.3 degrees noise #velocity_noise: # constant: 0.04 #4cm/s noise - # linear: 0.02 #2% noise \ No newline at end of file + # linear: 0.02 #2% noise diff --git a/GEMstack/knowledge/detection/bevfusion_instructions.md b/GEMstack/knowledge/detection/bevfusion_instructions.md new file mode 100644 index 000000000..b29dca972 --- /dev/null +++ b/GEMstack/knowledge/detection/bevfusion_instructions.md @@ -0,0 +1,146 @@ +# BEVFusion Set Up Instructions +These instructions were tested on T4 g4dn.xlarge AWS instances with Arara Ubuntu 20.04 DCV images. + +## Set Up Instructions for Cuda 11.3 +### Set Up your Nvida Driver +``` +sudo apt-get update +sudo apt-get install -y ubuntu-drivers-common +ubuntu-drivers devices +sudo apt-get install -y nvidia-driver-565 +sudo reboot +``` + +### Check to make sure that your nvidia driver was set up correctly: +``` +nvidia-smi +``` + +### Install Cuda 11.3 +``` +wget https://developer.download.nvidia.com/compute/cuda/repos/ubuntu2004/x86_64/cuda-ubuntu2004.pin +sudo mv cuda-ubuntu2004.pin /etc/apt/preferences.d/cuda-repository-pin-600 +wget https://developer.download.nvidia.com/compute/cuda/11.3.0/local_installers/cuda-repo-ubuntu2004-11-3-local_11.3.0-465.19.01-1_amd64.deb +sudo dpkg -i cuda-repo-ubuntu2004-11-3-local_11.3.0-465.19.01-1_amd64.deb # This never copy pastes right. Just manually type +sudo apt-key add /var/cuda-repo-ubuntu2004-11-3-local/7fa2af80.pub +sudo apt-get update +sudo apt-get -y install cuda-11-3 +``` + +### Manually modify your bashrc file to include Cuda 11.3 +``` +sudo nano ~/.bashrc +``` + +Add the next 2 lines to the bottom of the file: +``` +export PATH=/usr/local/cuda-11.3/bin:$PATH +export LD_LIBRARY_PATH=/usr/local/cuda-11.3/lib64:$LD_LIBRARY_PATH +``` + +Ensure you source your bashrc file: +``` +source ~/.bashrc +nvidia-smi +``` + +### Set Up Miniconda +``` +wget https://repo.anaconda.com/miniconda/Miniconda3-latest-Linux-x86_64.sh +bash ~/Miniconda3-latest-Linux-x86_64.sh +source ~/.bashrc +``` + +### Set Up mmdetection3d: +``` +conda create --name openmmlab python=3.8 -y +conda activate openmmlab +conda install pytorch=1.10.2 torchvision=0.11.3 cudatoolkit=11.3 -c pytorch +pip install -U openmim +mim install mmengine +mim install 'mmcv>=2.0.0rc4, <2.2.0' +mim install 'mmdet>=3.0.0,<3.3.0' +pip install cumm-cu113 +pip install spconv-cu113 +git clone https://github.com/open-mmlab/mmdetection3d.git -b dev-1.x +cd mmdetection3d +pip install -v -e . +python projects/BEVFusion/setup.py develop +``` + +### Run this afterwards to verify BEVFusion has been set up correctly: +``` +python projects/BEVFusion/demo/multi_modality_demo.py demo/data/nuscenes/n015-2018-07-24-11-22-45+0800__LIDAR_TOP__1532402927647951.pcd.bin demo/data/nuscenes/ demo/data/nuscenes/n015-2018-07-24-11-22-45+0800.pkl projects/BEVFusion/configs/bevfusion_lidar-cam_voxel0075_second_secfpn_8xb4-cyclic-20e_nus-3d.py ~/Downloads/bevfusion_lidar-cam_voxel0075_second_secfpn_8xb4-cyclic-20e_nus-3d-5239b1af.pth --cam-type all --score-thr 0.2 --show +``` + +## Set Up Instructions for Cuda 11.1 +### Set Up your Nvida Driver +``` +sudo apt-get update +sudo apt-get install -y ubuntu-drivers-common +ubuntu-drivers devices +sudo apt-get install -y nvidia-driver-565 +sudo reboot +``` + +### Check to make sure that your nvidia driver was set up correctly: +``` +nvidia-smi +``` + +### Install Cuda 11.3 +``` +wget https://developer.download.nvidia.com/compute/cuda/repos/ubuntu2004/x86_64/cuda-ubuntu2004.pin +sudo mv cuda-ubuntu2004.pin /etc/apt/preferences.d/cuda-repository-pin-600 +wget https://developer.download.nvidia.com/compute/cuda/11.1.0/local_installers/cuda-repo-ubuntu2004-11-1-local_11.1.0-455.23.05-1_amd64.deb +sudo dpkg -i cuda-repo-ubuntu2004-11-1-local_11.1.0-455.23.05-1_amd64.deb +sudo apt-key add /var/cuda-repo-ubuntu2004-11-1-local/7fa2af80.pub +sudo apt-get update +sudo apt-get -y install cuda-11-1 +``` + +### Manually modify your bashrc file to include Cuda 11.3 +``` +sudo nano ~/.bashrc +``` + +Add the next 2 lines to the bottom of the file: +``` +export PATH=/usr/local/cuda-11.1/bin:$PATH +export LD_LIBRARY_PATH=/usr/local/cuda-11.1/lib64:$LD_LIBRARY_PATH +``` + +Ensure you source your bashrc file: +``` +source ~/.bashrc +nvidia-smi +``` + +### Set Up Miniconda +``` +wget https://repo.anaconda.com/miniconda/Miniconda3-latest-Linux-x86_64.sh +bash ~/Miniconda3-latest-Linux-x86_64.sh +source ~/.bashrc +``` + +### Set Up mmdetection3d: +``` +conda create --name openmmlab python=3.8 -y +conda activate openmmlab +pip install torch==1.10.0+cu111 torchvision==0.11.1+cu111 -f https://download.pytorch.org/whl/torch_stable.html +pip install -U openmim +mim install mmengine +mim install 'mmcv>=2.0.0rc4, <2.2.0' +mim install 'mmdet>=3.0.0,<3.3.0' +pip install cumm-cu111 +pip install spconv-cu111 +git clone https://github.com/open-mmlab/mmdetection3d.git -b dev-1.x +cd mmdetection3d +pip install -v -e . +python projects/BEVFusion/setup.py develop +``` + +### Run this afterwards to verify BEVFusion has been set up correctly: +``` +python projects/BEVFusion/demo/multi_modality_demo.py demo/data/nuscenes/n015-2018-07-24-11-22-45+0800__LIDAR_TOP__1532402927647951.pcd.bin demo/data/nuscenes/ demo/data/nuscenes/n015-2018-07-24-11-22-45+0800.pkl projects/BEVFusion/configs/bevfusion_lidar-cam_voxel0075_second_secfpn_8xb4-cyclic-20e_nus-3d.py ~/Downloads/bevfusion_lidar-cam_voxel0075_second_secfpn_8xb4-cyclic-20e_nus-3d-5239b1af.pth --cam-type all --score-thr 0.2 --show +``` \ No newline at end of file diff --git a/GEMstack/knowledge/vehicle/dynamics.py b/GEMstack/knowledge/vehicle/dynamics.py index 3cbc2e77a..c26a1068b 100644 --- a/GEMstack/knowledge/vehicle/dynamics.py +++ b/GEMstack/knowledge/vehicle/dynamics.py @@ -31,13 +31,63 @@ def acceleration_to_pedal_positions(acceleration : float, velocity : float, pitc if acceleration < -dry_decel*0.5 or (acceleration <= 0 and velocity < 0.1): # a little deadband to avoid oscillation throttle_percent = 0.0 #drift to stop else: - throttle_percent = accel_active_range[0] + (acceleration+dry_decel)/max_accel * (accel_active_range[1]-accel_active_range[0]) + throttle_percent = accel_active_range[0] + ((acceleration+dry_decel)/max_accel * (accel_active_range[1]-accel_active_range[0])) brake_percent = 0 else: - brake_percent = brake_active_range[0] + -(acceleration+dry_decel)/max_brake * (brake_active_range[1]-brake_active_range[0]) + brake_percent = brake_active_range[0] + (-(acceleration+dry_decel)/max_brake * (brake_active_range[1]-brake_active_range[0])) throttle_percent = 0 + print(acceleration, (max(throttle_percent,0.0),max(brake_percent,0.0),1)) return (max(throttle_percent,0.0),max(brake_percent,0.0),1) + + # Model that's built on top of Hang's model. + # Designed to allow for various scaling based on current vehicle velocity, and use of functions other than linear + # for scaling. + # DANGER: NEEDS TESTED + elif model == 'avery_v1': + model = settings.get('vehicle.dynamics.acceleration_model', 'avery_v1') + if gear != 1: + print("WARNING: Can't handle gears other than 1 yet") + + max_accel = settings.get('vehicle.dynamics.max_accelerator_acceleration')[1] # m/s^2 + max_brake = settings.get('vehicle.dynamics.max_brake_deceleration') # m/s^2 + dry_decel = settings.get('vehicle.dynamics.internal_dry_deceleration') # m/s^2 + accel_active_range = settings.get('vehicle.dynamics.accelerator_active_range') # pedal position fraction + brake_active_range = settings.get('vehicle.dynamics.brake_active_range') # pedal position fraction + mapping_function = settings.get('vehicle.dynamics.pedal_mapping_function', 'linear') + velocity_scalar = settings.get('vehicle.dynamics.velocity_scaling_factor', 0) # Adjust sensitivity based on velocity + + + def apply_function(value, function='linear'): + if function == 'linear': + value = value # already linear mapping + + # no guarantee that these functions will give good results until we get more test data about accel -> pedal mapping. + elif function == 'quadratic': + value = value ** 2 # value squared + elif function == 'exponential': + value = (math.exp(value) - 1) / 2 + elif function == 'log': + value = math.sqrt(math.log(value + 1)) + 0.2 + + value += velocity * velocity_scalar + return value + + if acceleration > -dry_decel: + if acceleration < -dry_decel*0.5 or (acceleration <= 0 and velocity < 0.1): # a little deadband to avoid oscillation + throttle_percent = 0.0 #drift to stop + else: + throttle_percent = accel_active_range[0] + ((acceleration+dry_decel)/max_accel * (accel_active_range[1]-accel_active_range[0])) + throttle_percent = apply_function(throttle_percent, mapping_function) + brake_percent = 0 + else: + brake_percent = brake_active_range[0] + (-(acceleration+dry_decel)/max_brake * (brake_active_range[1]-brake_active_range[0])) + brake_percent = apply_function(brake_percent, mapping_function) + throttle_percent = 0 + print(acceleration, (max(throttle_percent,0.0),max(brake_percent,0.0),1)) + return (max(throttle_percent,0.0),max(brake_percent,0.0),1) + + elif model == 'kris_v1': brake_max = settings.get('vehicle.dynamics.max_brake_deceleration') reverse_accel_max = settings.get('vehicle.dynamics.max_accelerator_acceleration_reverse') diff --git a/GEMstack/knowledge/vehicle/gem_e2_dynamics.yaml b/GEMstack/knowledge/vehicle/gem_e2_dynamics.yaml index 8df21ac71..fc2bfcfa7 100644 --- a/GEMstack/knowledge/vehicle/gem_e2_dynamics.yaml +++ b/GEMstack/knowledge/vehicle/gem_e2_dynamics.yaml @@ -14,7 +14,7 @@ max_accelerator_power_reverse: 10000.0 #Watts. Power (backwards) in reverse gea acceleration_model : kris_v1 accelerator_active_range : [0.32, 1.0] #range of accelerator pedal where output acceleration is not flat -brake_active_range : [0,1] #range of brake pedal where output deceleration is not flat +brake_active_range : [0.25,1] #range of brake pedal where output deceleration is not flat internal_dry_deceleration: 0.2 #m/s^2: deceleration due to internal dry friction (non-speed dependent) internal_viscous_deceleration: 0.05 #1/s: scales the current velocity to get deceleration due to internal viscous friction (speed dependent) diff --git a/GEMstack/knowledge/vehicle/gem_e4_dynamics.yaml b/GEMstack/knowledge/vehicle/gem_e4_dynamics.yaml index a2ac7c9de..963111bbc 100644 --- a/GEMstack/knowledge/vehicle/gem_e4_dynamics.yaml +++ b/GEMstack/knowledge/vehicle/gem_e4_dynamics.yaml @@ -1,16 +1,16 @@ -mass: 300.0 #kg +mass: 700.0 #kg gravity: 9.81 #m/s^2 -longitudinal_friction : 1.0 # unitless -lateral_friction : 1.0 # unitless -max_brake_deceleration: 8.0 #m/s^2. Deceleration at max brake pedal -max_accelerator_acceleration: #m/s^2. Acceleration at max accelerator pedal, by gear +longitudinal_friction : 1.0 # unitless TODO find make/model of tires +lateral_friction : 1.0 # unitless (I will bet these things do not have 1 coefficent of fricition) +max_brake_deceleration: 8.0 #m/s^2. Deceleration at max brake pedal TODO (un cap this cap) +max_accelerator_acceleration: #m/s^2. Acceleration at max accelerator pedal, by gear (un cap this cap) - 0.0 - 5.0 max_accelerator_acceleration_reverse: 2.5 #m/s^2. Acceleration (backwards) in reverse gear -max_accelerator_power: #Watts. Power at max accelerator pedal, by gear +max_accelerator_power: #Watts. Power at max accelerator pedal, by gear (updated from website) - 0.0 - - 10000.0 -max_accelerator_power_reverse: 10000.0 #Watts. Power (backwards) in reverse gear + - 5000.0 +max_accelerator_power_reverse: 5000.0 #Watts. Power (backwards) in reverse gear acceleration_model : kris_v1 accelerator_active_range : [0.32, 1.0] #range of accelerator pedal where output acceleration is not flat @@ -20,3 +20,5 @@ internal_dry_deceleration: 0.2 #m/s^2: deceleration due to internal dry fri internal_viscous_deceleration: 0.05 #1/s: scales the current velocity to get deceleration due to internal viscous friction (speed dependent) aerodynamic_drag_coefficient: 0.01 #units in s, scaled by velocity^2 to get deceleration due to aerodynamic drag acceleration_deadband: 0.1 #m/s^2: minimum acceleration to be considered non-zero +velocity_scaling_factor: 0.0 # Velocity * this scalar will be added to brake and throttle percent. +pedal_mapping_function: linear diff --git a/GEMstack/knowledge/vehicle/gem_e4_sensor_environment.yaml b/GEMstack/knowledge/vehicle/gem_e4_sensor_environment.yaml index 22ed4e439..70c7d7f1d 100644 --- a/GEMstack/knowledge/vehicle/gem_e4_sensor_environment.yaml +++ b/GEMstack/knowledge/vehicle/gem_e4_sensor_environment.yaml @@ -6,4 +6,4 @@ ros_topics: front_left_camera: /camera_fl/arena_camera_node/image_raw front_right_camera: /camera_fr/arena_camera_node/image_raw rear_left_camera: /camera_rl/arena_camera_node/image_raw - rear_right_camera: /camera_rr/arena_camera_node/image_raw \ No newline at end of file + rear_right_camera: /camera_rr/arena_camera_node/image_raw diff --git a/GEMstack/offboard/calibration/camera_to_vehicle_manual.py b/GEMstack/offboard/calibration/camera_to_vehicle_manual.py new file mode 100644 index 000000000..5a29f3411 --- /dev/null +++ b/GEMstack/offboard/calibration/camera_to_vehicle_manual.py @@ -0,0 +1,179 @@ +#%% +import cv2 +from scipy.spatial.transform import Rotation as R +import matplotlib.pyplot as plt +import numpy as np +from visualizer import visualizer +import argparse +import yaml + +parser = argparse.ArgumentParser(description='Select corresponding lidar, color, depth files based on index') +parser.add_argument('--data_path', type=str, required=True, help='Path to the dataset') +parser.add_argument('--index', type=int, required=True, help='Index for selecting the files') +parser.add_argument('--config', type=str, required=True, help='Path to YAML configuration file') +args = parser.parse_args() +args = parser.parse_args() + +# Construct file paths based on the provided index +lidar_path = f'{args.data_path}/lidar{args.index}.npz' +rgb_path = f'{args.data_path}/color{args.index}.png' +depth_path = f'{args.data_path}/depth{args.index}.tif' + +N = 8 #how many point pairs you want to select + +img = cv2.imread(rgb_path, cv2.IMREAD_UNCHANGED) + +lidar_points = np.load(lidar_path)['arr_0'] +lidar_points = lidar_points[~np.all(lidar_points== 0, axis=1)] # remove (0,0,0)'s + + + +# Load transformation parameters from YAML file +with open(args.config, 'r') as yaml_file: + config = yaml.safe_load(yaml_file) + +tx, ty, tz = config['position'] +rot = np.array(config['rotation']) + +# Construct transformation matrix +lidar_ex = np.hstack([rot, np.array([[tx], [ty], [tz]])]) +lidar_ex = np.vstack([lidar_ex, [0, 0, 0, 1]]) + +camera_in = np.array([ # Update intrinsics if necessary + [684.83331299, 0. , 573.37109375], + [ 0. , 684.60968018, 363.70092773], + [ 0. , 0. , 1. ] +], dtype=np.float32) + + +#%% +# blurred = cv2.GaussianBlur(img, (5, 5), 0) +# edges = cv2.Canny(blurred, threshold1=50, threshold2=150) +# plt.imshow(edges) +plt.imshow(cv2.cvtColor(img,cv2.COLOR_BGR2RGB)) + +#%% +import pyvista as pv +def vis(title='', ratio=1,notebook=False): + print(title) + pv.set_jupyter_backend('client') + + return visualizer().set_cam() +def crop(pc,ix=None,iy=None,iz=None): + # crop a subrectangle in a pointcloud + # usage: crop(pc, ix = (x_min,x_max), ...) + # return: array(N,3) + mask = True + for dim,intervel in zip([0,1,2],[ix,iy,iz]): + if not intervel: continue + d,u = intervel + mask &= pc[:,dim] >= d + mask &= pc[:,dim] <= u + print(f'points left after cropping {dim}\'th dim',mask.sum()) + return pc[mask] + + +lidar_post = np.pad(lidar_points,((0,0),(0,1)),constant_values=1) @ lidar_ex.T[:,:3] +lidar_post = crop(lidar_post,ix=(0,10),iy=(-5,5)) +# vis(notebook=False).add_pc(lidar_post).show() + +#%% +def pick_n_img(img,n=4): + corners = [] # Reset the corners list + def click_event(event, x, y, flags, param): + if event == cv2.EVENT_LBUTTONDOWN: + corners.append((x, y)) + cv2.circle(param, (x, y), 5, (0, 255, 0), -1) + cv2.imshow('Image', param) + + cv2.imshow('Image', img) + cv2.setMouseCallback('Image', click_event, img) + + while True: + if len(corners) == n: + break + if cv2.waitKey(1) & 0xFF == ord('q'): + return None + + cv2.destroyAllWindows() + + return corners +cpoints = np.array(pick_n_img(img,N)).astype(float) +print(cpoints) + +#%% +def pick_n_pc(point_cloud,n=4): + points = [] + def cb(pt,*args): + points.append(pt) + while len(points)!=n: + points = [] + cloud = pv.PolyData(point_cloud) + plotter = pv.Plotter(notebook=False) + plotter.camera.position = (-20,0,20) + plotter.camera.focal_point = (0,0,0) + plotter.add_mesh(cloud, color='lightblue', point_size=5, render_points_as_spheres=True) + plotter.enable_point_picking(cb) + plotter.show() + return points + +lpoints = np.array(pick_n_pc(lidar_post,N)) +print(lpoints) +# %% +success, rvec, tvec = cv2.solvePnP(lpoints, cpoints, camera_in, None) +R, _ = cv2.Rodrigues(rvec) + +T = np.eye(4) +T[:3, :3] = R +T[:3, 3] = tvec.flatten() +print(T) + + +#%% +def depth_to_points(depth_img: np.ndarray, intrinsics: np.ndarray): + """ + Convert a single-channel depth image into an Nx3 array of 3D points + in the camera coordinate system. + - depth_img: 2D array of type uint16 or float with depth values + - intrinsics: 3x3 camera matrix + """ + fx = intrinsics[0,0] + fy = intrinsics[1,1] + cx = intrinsics[0,2] + cy = intrinsics[1,2] + + # Indices of each pixel + h, w = depth_img.shape + i_range = np.arange(h) + j_range = np.arange(w) + jj, ii = np.meshgrid(j_range, i_range) # shape (h,w) + + # Flatten + ii = ii.flatten().astype(np.float32) + jj = jj.flatten().astype(np.float32) + depth = depth_img.flatten().astype(np.float32) + + # Filter out zero / invalid depths + valid_mask = (depth > 0) + ii = ii[valid_mask] + jj = jj[valid_mask] + depth = depth[valid_mask] + + z = depth / 10000 + x = (jj - cx) * z / fx + y = (ii - cy) * z / fy + points3d = np.stack((x, y, z), axis=-1) # shape (N,3) + + return points3d + + + +depth_img = cv2.imread(depth_path, cv2.IMREAD_UNCHANGED) +camera_points = depth_to_points(depth_img, camera_in) + +#%% +v2c = T +print('vehicle->camera:',v2c) +c2v = np.linalg.inv(v2c) +print('camera->vehicle:',c2v) + diff --git a/GEMstack/offboard/calibration/capture_lidar_zed.py b/GEMstack/offboard/calibration/capture_lidar_zed.py index 21814b793..ee11ebb1a 100644 --- a/GEMstack/offboard/calibration/capture_lidar_zed.py +++ b/GEMstack/offboard/calibration/capture_lidar_zed.py @@ -1,99 +1,107 @@ -# ROS Headers +#!/usr/bin/env python3 +""" +Capture ROS messages and save each run in its own time-stamped folder. +""" + import rospy -from sensor_msgs.msg import Image,PointCloud2 +from sensor_msgs.msg import Image, PointCloud2 import sensor_msgs.point_cloud2 as pc2 import ctypes import struct - -# OpenCV and cv2 bridge import cv2 from cv_bridge import CvBridge import numpy as np import os +import datetime lidar_points = None camera_image = None depth_image = None bridge = CvBridge() -def lidar_callback(lidar : PointCloud2): +def lidar_callback(lidar: PointCloud2): global lidar_points lidar_points = lidar -def camera_callback(img : Image): +def camera_callback(img: Image): global camera_image camera_image = img -def depth_callback(img : Image): +def depth_callback(img: Image): global depth_image depth_image = img -def pc2_to_numpy(pc2_msg, want_rgb = False): +def pc2_to_numpy(pc2_msg, want_rgb=False): gen = pc2.read_points(pc2_msg, skip_nans=True) if want_rgb: - xyzpack = np.array(list(gen),dtype=np.float32) + xyzpack = np.array(list(gen), dtype=np.float32) if xyzpack.shape[1] != 4: raise ValueError("PointCloud2 does not have points") - xyzrgb = np.empty((xyzpack.shape[0],6)) - xyzrgb[:,:3] = xyzpack[:,:3] - for i,x in enumerate(xyzpack): - rgb = x[3] - # cast float32 to int so that bitwise operations are possible - s = struct.pack('>f' ,rgb) - i = struct.unpack('>l',s)[0] - # you can get back the float value by the inverse operations - pack = ctypes.c_uint32(i).value - r = (pack & 0x00FF0000)>> 16 - g = (pack & 0x0000FF00)>> 8 + xyzrgb = np.empty((xyzpack.shape[0], 6)) + xyzrgb[:, :3] = xyzpack[:, :3] + for i, x in enumerate(xyzpack): + rgb = x[3] + s = struct.pack('>f', rgb) + i_val = struct.unpack('>l', s)[0] + pack = ctypes.c_uint32(i_val).value + r = (pack & 0x00FF0000) >> 16 + g = (pack & 0x0000FF00) >> 8 b = (pack & 0x000000FF) - #r,g,b values in the 0-255 range - xyzrgb[i,3:] = (r,g,b) + xyzrgb[i, 3:] = (r, g, b) return xyzrgb else: - return np.array(list(gen),dtype=np.float32)[:,:3] + return np.array(list(gen), dtype=np.float32)[:, :3] -def save_scan(lidar_fn,color_fn,depth_fn): - print("Saving scan to",lidar_fn,color_fn,depth_fn) - pc = pc2_to_numpy(lidar_points,want_rgb=False) - np.savez(lidar_fn,pc) - cv2.imwrite(color_fn,bridge.imgmsg_to_cv2(camera_image)) +def save_scan(lidar_fn, color_fn, depth_fn): + print("Saving scan to", lidar_fn, color_fn, depth_fn) + pc = pc2_to_numpy(lidar_points, want_rgb=False) + np.savez(lidar_fn, pc) + cv2.imwrite(color_fn, bridge.imgmsg_to_cv2(camera_image)) dimage = bridge.imgmsg_to_cv2(depth_image) dimage_non_nan = dimage[np.isfinite(dimage)] - print("Depth range",np.min(dimage_non_nan),np.max(dimage_non_nan)) - dimage = np.nan_to_num(dimage,nan=0,posinf=0,neginf=0) - dimage = (dimage/4000*0xffff) - print("Depth pixel range",np.min(dimage),np.max(dimage)) + print("Depth range", np.min(dimage_non_nan), np.max(dimage_non_nan)) + dimage = np.nan_to_num(dimage, nan=0, posinf=0, neginf=0) + dimage = (dimage / 4000 * 0xffff) + print("Depth pixel range", np.min(dimage), np.max(dimage)) dimage = dimage.astype(np.uint16) - cv2.imwrite(depth_fn,dimage) + cv2.imwrite(depth_fn, dimage) + +def main(base_folder='data', start_index=1): + # unique folder for this capture run based on the current date/time. + run_timestamp = datetime.datetime.now().strftime("%Y-%m-%d_%H-%M-%S") + run_folder = os.path.join(base_folder, run_timestamp) + os.makedirs(run_folder, exist_ok=True) + print("Capture run folder:", run_folder) + + rospy.init_node("capture_lidar_zed", disable_signals=True) + rospy.Subscriber("/lidar1/velodyne_points", PointCloud2, lidar_callback) + rospy.Subscriber("/zed2/zed_node/rgb/image_rect_color", Image, camera_callback) + rospy.Subscriber("/zed2/zed_node/depth/depth_registered", Image, depth_callback) -def main(folder='data',start_index=1): - rospy.init_node("capture_lidar_zed",disable_signals=True) - lidar_sub = rospy.Subscriber("/lidar1/velodyne_points", PointCloud2, lidar_callback) - camera_sub = rospy.Subscriber("/zed2/zed_node/rgb/image_rect_color", Image, camera_callback) - depth_sub = rospy.Subscriber("/zed2/zed_node/depth/depth_registered", Image, depth_callback) index = start_index print("Press any key to:") - print(" store lidar point clouds as npz") - print(" store color images as png") - print(" store depth images (m scaled by 0xffff/4000) as 16-bit tif") + print(" - store lidar point clouds as npz") + print(" - store color images as png") + print(" - store depth images (m scaled by 0xffff/4000) as 16-bit tif") print("Press Escape or Ctrl+C to quit") - while True: - if camera_image: - cv2.imshow("result",bridge.imgmsg_to_cv2(camera_image)) + + while not rospy.is_shutdown(): + if camera_image is not None: + cv2.imshow("result", bridge.imgmsg_to_cv2(camera_image)) key = cv2.waitKey(30) if key == -1: - #nothing - pass + pass # No key pressed. elif key == 27: - #escape - break + break # Escape key pressed. else: if lidar_points is None or camera_image is None or depth_image is None: print("Missing some messages?") else: - files = [os.path.join(folder,'lidar{}.npz'.format(index)), - os.path.join(folder,'color{}.png'.format(index)), - os.path.join(folder,'depth{}.tif'.format(index))] + files = [ + os.path.join(run_folder, 'lidar{}.npz'.format(index)), + os.path.join(run_folder, 'color{}.png'.format(index)), + os.path.join(run_folder, 'depth{}.tif'.format(index)) + ] save_scan(*files) index += 1 @@ -105,4 +113,4 @@ def main(folder='data',start_index=1): folder = sys.argv[1] if len(sys.argv) >= 3: start_index = int(sys.argv[2]) - main(folder,start_index) + main(folder, start_index) diff --git a/GEMstack/offboard/calibration/klampt_lidar_ouster_show.py b/GEMstack/offboard/calibration/klampt_lidar_ouster_show.py new file mode 100644 index 000000000..11a9fcbcc --- /dev/null +++ b/GEMstack/offboard/calibration/klampt_lidar_ouster_show.py @@ -0,0 +1,183 @@ +from klampt import vis +from klampt.math import so3,se3 +from klampt.vis.colorize import colorize +from klampt import PointCloud,Geometry3D +from klampt.io import numpy_convert +from klampt.model.sensing import image_to_points +from klampt.model.create import bbox +import klampt +import cv2 +import os +import numpy as np +import math +import time + +#uncalibrated values -- TODO: load these from a calibration file +zed_K = np.array([[684.8333, 0.0, 573.371], + [0.0, 684.609, 363.7], + [0.0, 0.0, 1.0]]) +zed_intrinsics = [zed_K[0,0],zed_K[1,1],zed_K[0,2],zed_K[1,2]] +zed_w = 1152 +zed_h = 720 + + +def main(folder): + lidar_xform = se3.identity() + zed_xform = (so3.from_ndarray(np.array([[0,0,1],[-1,0,0],[0,-1,0]])),[0,0,0]) + lidar_pattern = os.path.join(folder,"lidar{}.npz") + color_pattern = os.path.join(folder,"color{}.png") + depth_pattern = os.path.join(folder,"depth{}.tif") + data = {} + def load_and_show_scan(idx): + arr_compressed = np.load(lidar_pattern.format(idx)) + arr = arr_compressed['arr_0'] + arr_compressed.close() + pc = numpy_convert.from_numpy(arr,'PointCloud') + pc = colorize(pc,'z','plasma') + data['lidar'] = Geometry3D(pc) + + try: # might need some modifications to work with our code + color = cv2.imread(color_pattern.format(idx)) + depth = cv2.imread(depth_pattern.format(idx),cv2.IMREAD_UNCHANGED) + depth = depth.astype(np.float32) + print("depth range",np.min(depth),np.max(depth)) + zed_xfov = 2*np.arctan(zed_w/(2*zed_intrinsics[0])) + zed_yfov = 2*np.arctan(zed_h/(2*zed_intrinsics[1])) + print("estimated zed horizontal FOV",math.degrees(zed_xfov),"deg") + print(f"Depth image shape: {depth.shape}, dtype: {depth.dtype}, min: {np.min(depth)}, max: {np.max(depth)}") + print(f"Color image shape: {color.shape}, dtype: {color.dtype}, min: {np.min(color)}, max: {np.max(color)}") + image_to_points( + depth, + color, + intrinsics=None, + xfov=zed_xfov, + yfov=zed_yfov, + depth_scale=4000.0 / 0xffff + ) + + except Exception as e: + print("Error loading zed data:",e) + pc = PointCloud() + + data['oak'] = Geometry3D(pc) + data['lidar'].setCurrentTransform(*lidar_xform) + data['oak'].setCurrentTransform(*zed_xform) + vis.add('lidar',data['lidar']) + vis.add('oak',data['oak']) + + data['index'] = 1 + def increment_index(): + data['index'] += 1 + try: + load_and_show_scan(data['index']) + except Exception: + data['index'] -= 1 + return + def decrement_index(): + data['index'] -= 1 + try: + load_and_show_scan(data['index']) + except Exception: + data['index'] += 1 + return + def print_xforms(): + print("lidar:") + print("rotation:",so3.ndarray(lidar_xform[0])) + print("position:",lidar_xform[1]) + print("zed:") + print("rotation:",so3.ndarray(zed_xform[0])) + print("position:",zed_xform[1]) + + point_selection = (4,0,0) + box_selection = [(3.5,-0.5,-0.5),(4.5,0.5,0.5)] + box_geometry = bbox(box_selection[0],box_selection[1],type='GeometricPrimitive') + data['selection_widget'] = None + + def select_point(): + if data['selection_widget'] is not None: + vis.remove(data['selection_widget']) + data['selection_widget'] = 'point_widget' + vis.add('point_widget',point_selection) + vis.edit('point_widget') + + def select_box(): + if data['selection_widget'] is not None: + vis.remove(data['selection_widget']) + data['selection_widget'] = 'box_widget' + vis.add('box_widget',box_geometry,color=(1.0,0.5,0,0.5)) + vis.add('box_widget_handle1',box_selection[0]) + vis.edit('box_widget_handle1') + vis.add('box_widget_handle2',box_selection[1]) + vis.edit('box_widget_handle2') + + def print_selection(): + if data['selection_widget'] is not None: + if data['selection_widget'] == 'point_widget': + print("Target point:",point_selection) + lidar = data['lidar'] # type: Geometry3D + pts = lidar.getPointCloud().getPoints() + pts = pts @ so3.ndarray(lidar_xform[0]).T + np.array(lidar_xform[1]) + dist_2 = np.sum((pts - point_selection)**2, axis=1) + closest_dist2 = np.min(dist_2) + closest_ind = np.argmin(dist_2) + print("Closest lidar point is",pts[closest_ind],"index",closest_ind,"at distance",math.sqrt(closest_dist2)) + else: + print("Target box:",box_selection) + lidar = data['lidar'] # type: Geometry3D + pts = lidar.getPointCloud().getPoints() + pts = pts @ so3.ndarray(lidar_xform[0]).T + np.array(lidar_xform[1]) + mask = np.logical_and(np.all(pts >= box_selection[0],axis=1),np.all(pts <= box_selection[1],axis=1)) + print("Number of lidar points in box:",np.sum(mask)) + print("Indices of lidar points in box:",np.where(mask)[0]) + print("Points in box",pts[mask]) + else: + print("No selection") + + vis.addAction(select_point,'Select with point','s','Select a point by dragging a point widget') + vis.addAction(select_box,'Select with box','b','Select multiple points with a box widget') + vis.addAction(print_selection,'Print selection','q') + + vis.addAction(increment_index,"Increment index",'=') + vis.addAction(decrement_index,"Decrement index",'-') + vis.addAction(print_xforms,'Print transforms','p') + load_and_show_scan(1) + vis.add('zed_xform',zed_xform) + vis.add('lidar_xform',lidar_xform) + vis.edit('zed_xform') + vis.edit('lidar_xform') + vis.show() + while vis.shown(): + lidar_xform = vis.getItemConfig('lidar_xform') + lidar_xform = lidar_xform[:9],lidar_xform[9:] + zed_xform = vis.getItemConfig('zed_xform') + zed_xform = zed_xform[:9],zed_xform[9:] + if data['selection_widget'] == 'point_widget': + point_selection = vis.getItemConfig('point_widget') + elif data['selection_widget'] == 'box_widget': + handle1 = vis.getItemConfig('box_widget_handle1') + handle2 = vis.getItemConfig('box_widget_handle2') + lower = [min(handle1[i],handle2[i]) for i in range(3)] + upper = [max(handle1[i],handle2[i]) for i in range(3)] + box_selection = [lower,upper] + box_geometry = bbox(lower,upper,type='GeometricPrimitive') + vis.add('box_widget',box_geometry,color=(1.0,0.5,0,0.5)) + data['lidar'].setCurrentTransform(*lidar_xform) + data['oak'].setCurrentTransform(*zed_xform) + time.sleep(0.02) + vis.kill() + +if __name__ == '__main__': + import sys + folder = 'data' + if len(sys.argv) >= 2: + folder = sys.argv[1] + if len(sys.argv) >= 3: + calib = sys.argv[2] + import yaml + with open(calib,'r') as f: + config = yaml.load(f,yaml.SafeLoader) + zed_K = np.array(config['K']).reshape((3,3)) + zed_intrinsics = [zed_K[0,0],zed_K[1,1],zed_K[0,2],zed_K[1,2]] + zed_w = config['width'] + zed_height = config['height'] + main(folder) diff --git a/GEMstack/offboard/calibration/lidar_to_camera.py b/GEMstack/offboard/calibration/lidar_to_camera.py new file mode 100644 index 000000000..cbf979c98 --- /dev/null +++ b/GEMstack/offboard/calibration/lidar_to_camera.py @@ -0,0 +1,20 @@ +import numpy as np + +T_camera_vehicle = np.array([[ 0.00349517, -0.03239524, 0.99946903, 1.75864913], + [-0.99996547, 0.00742285, 0.0037375, 0.01238124], + [-0.00753999, -0.99944757, -0.03236817, 1.54408419], + [0,0,0,1]]) + +T_lidar_vehicle = np.array([[ 0.99941328, 0.02547416, 0.02289458, 1.1], + [-0.02530855, 0.99965159, -0.00749488, 0.03773044170906172], + [-0.02307753, 0.00691106, 0.99970979, 1.9525244316515322], + [0,0,0,1]]) + +# Invert Camera->Vehicle transformation +T_vehicle_camera = np.linalg.inv(T_camera_vehicle) + +T_lidar_camera = T_vehicle_camera @ T_lidar_vehicle + +# Print result +print("Lidar to Camera Transformation Matrix:") +print(T_lidar_camera) diff --git a/GEMstack/offboard/calibration/lidar_to_vehicle.py b/GEMstack/offboard/calibration/lidar_to_vehicle.py new file mode 100644 index 000000000..6902df6db --- /dev/null +++ b/GEMstack/offboard/calibration/lidar_to_vehicle.py @@ -0,0 +1,224 @@ +#%% +import sys +import math +import numpy as np +from scipy.spatial.transform import Rotation as R +import pyvista as pv +import matplotlib.pyplot as plt +from visualizer import visualizer +import argparse + +parser = argparse.ArgumentParser(description='Process LiDAR data with calibration.') +parser.add_argument('--data_path', type=str, required=True, help='Path to the dataset') +parser.add_argument('--index', type=int, required=True, help='Index for selecting the files') +parser.add_argument('--vis', action='store_true', help='Enable visualization') +args = parser.parse_args() + +VIS = args.vis + +#%% things to extract +tx,ty,tz,rx,ry,rz = [None] * 6 + +#%%============================================================== +#======================= util functions ========================= +#================================================================ +def vis(title='', ratio=1): + print(title) + pv.set_jupyter_backend('client') + return visualizer().set_cam() +def load_scene(path): + sc = np.load(path)['arr_0'] + sc = sc[~np.all(sc == 0, axis=1)] # remove (0,0,0)'s + return sc + +sc1 = load_scene(f'{args.data_path}/lidar{args.index}.npz') + +def crop(pc,ix=None,iy=None,iz=None): + # crop a subrectangle in a pointcloud + # usage: crop(pc, ix = (x_min,x_max), ...) + # return: array(N,3) + mask = True + for dim,intervel in zip([0,1,2],[ix,iy,iz]): + if not intervel: continue + d,u = intervel + mask &= pc[:,dim] >= d + mask &= pc[:,dim] <= u + print(f'points left after cropping {dim}\'th dim',mask.sum()) + return pc[mask] + +from sklearn.linear_model import RANSACRegressor +from sklearn.linear_model import LinearRegression +def fit_plane_ransac(pc,tol=0.01): + # fit a line/plane/hyperplane in a pointcloud + # pc: np array (N,D). the pointcloud + # tol: the tolerance. default 0.01 + model = RANSACRegressor(LinearRegression(), residual_threshold=tol) + model.fit(pc[:,:-1], pc[:,-1]) + a = model.estimator_.coef_ + inter = model.estimator_.intercept_ + class visual: + def plot(self): + inliers = pc[model.inlier_mask_] + if pc.shape[1] == 2: + plt.title('ransac fitting line') + plt.scatter(pc[:,0], pc[:,1], color='blue', marker='o', s=1) + plt.scatter(inliers[:,0], inliers[:,1], color='red', marker='o', s=1) + x_line = np.linspace(0, max(pc[:,0]), 100).reshape(-1,1) + plt.plot(x_line, x_line * a[0] + inter, color='red', label='Fitted Line') + elif pc.shape[1] == 3: + vis('ransac fitting a plane').add_pc(pc).add_pc(inliers,color='red').show() + return self + + def results(self): + # return: array(D-1), float, array(N,3) + # ^: , coeffs, intercept toward the plane, inliers of the fit + return a,inter + return visual() + +from scipy.spatial import cKDTree +def pc_diff(pc0,pc1,tol=0.1): + # remove points in pc0 from pc1 s.t. euclidian distance is within tolerance + # return: array(N,3) + tree = cKDTree(pc0) + diff = [] + for i, point in enumerate(pc1): + _, idx = tree.query(point) + distance = np.linalg.norm(point - pc0[idx]) # Compute the distance + if distance > tol: + diff.append(point) + tree = cKDTree(pc1) + for i, point in enumerate(pc0): + _, idx = tree.query(point) + distance = np.linalg.norm(point - pc1[idx]) # Compute the distance + if distance > tol: + diff.append(point) + return np.array(diff) + + + + + + +#%%============================================================== +#========================= tz rx ry ============================= +#================================================================ + +#%% load scene for ground plane +# Update depending on where data is stored +sc = load_scene('./data/lidar1.npz') + +# %% we crop to keep the ground +cropped_sc = crop(sc,iz = (-3,-2)) +if VIS: + vis('ground points cropped').add_pc(cropped_sc,color='blue').show() + +#%% +from math import sqrt +fit = fit_plane_ransac(cropped_sc,tol=0.01) # small tol because the ground is very flat +c, inter = fit.results() +normv = np.array([c[0], c[1], -1]) +normv /= np.linalg.norm(normv) +nx,ny,nz = normv +height = nz * inter +# TODO MAGIC NUMBER WARNING +height_axel = 0.2794 # 11 inches that we measured +tz = height - height_axel +if VIS: + fit.plot() +rx = -math.atan2(ny,-nz) +ry = -math.atan2(-nx,-nz) + + +if VIS: + from scipy.spatial.transform import Rotation as R + rot = R.from_euler('xyz',[rx,ry,0]).as_matrix() + cal_sc = sc @ rot.T + [0,0,tz] + vis('yz projection').add_pc(cal_sc*[0,1,1],color='blue').show() + vis('xz projection').add_pc(cal_sc*[1,0,1],color='blue').show() + +#%%============================================================== +#========================== tx ty rz ============================ +#================================================================ + +rot = R.from_euler('xyz',[rx,ry,0]).as_matrix() + +if False: # True to use the diff method to extract object. + # load data: update depending on where data is stored + sc0 = load_scene('./data/lidar70.npz') + sc1 = load_scene('./data/lidar78.npz') + + sc0 = sc0 @ rot.T + [0,0,tz] + sc1 = sc1 @ rot.T + [0,0,tz] + + # crop to only keep a frontal box area + area = (-0,7),(-1,1),(-3,1) + cropped0 = crop(sc0,*area) + cropped1 = crop(sc1,*area) + print(cropped0.shape) + print(cropped1.shape) + + # Take difference to only keep added object + objects = pc_diff(cropped0,cropped1) + +else: #False to use only cropping + # Update depending on where data is stored + + objects = sc1 @ rot.T + [0,0,tz] + + # crop to only keep a frontal box area + area = (-0,20),(-1,1),(0,1) + objects = crop(objects,*area) + print(objects.shape) + + +#%% +if VIS: + vis().add_pc(objects,color='blue').show() #visualize diff, hopefully the added objects + +# %% use the added objects to find rz. +# TODO after dataset retake +# right now we assume tx = ty = 0 and \ +# just use median to find a headding direction +fit = fit_plane_ransac(objects[:,:2],tol=1) # tol=1 because 1m^3 foam boxes +c,inter = fit.results() +if VIS: + fit.plot() +# tx = ty = 0 +# hx,hy = np.median(diff,axis=0)[:2] +# rz = -np.arctan2(hy,hx) +rz = - math.atan(c) +tx = 2.56 - 1.46 # https://publish.illinois.edu/robotics-autonomy-resources/gem-e4/hardware/ +ty = - inter * math.cos(rz) + +if VIS: + p1 = (0,inter,0) + p2 = max(objects[:,0])*np.array([1,c[0],0])+np.array([0,inter,0]) + vis().add_pc(sc1*np.array([1,1,0]),color='blue').add_line(p1,p2,color='red').show() + + from scipy.spatial.transform import Rotation as R + rot = R.from_euler('xyz',[0,0,rz]).as_matrix() + cal_sc1 = sc1 @ rot.T + [tx,ty,0] + vis().add_pc(cal_sc1,color='blue').show() + + +#%% visualize calibrated pointcloud +if VIS: + rot = R.from_euler('xyz',[rx,ry,rz]).as_matrix() + + cal_sc1 = sc1 @ rot.T + [tx,ty,tz] + v = vis(ratio=100) + proj = [1,1,1] + v.add_pc(cal_sc1*proj,color='blue') + v.add_box((2.56,.61*2,2.03+height_axel),[2.56/2,0,(2.03+height_axel)/2]) + v.show() + # the yellow box should be 11 inches above the ground + # rear-axel center should be at (0,0,0) +# %% +print(f""" +translation: ({tx,ty,tz}) +rotation: ({rx,ry,rz}) +""") + + + +# %% diff --git a/GEMstack/offboard/calibration/test_transforms.py b/GEMstack/offboard/calibration/test_transforms.py index 671578c14..6037a0961 100644 --- a/GEMstack/offboard/calibration/test_transforms.py +++ b/GEMstack/offboard/calibration/test_transforms.py @@ -221,4 +221,4 @@ def update(val): save_ex(args.out_path, matrix=T_lidar_to_vehicle @ np.linalg.inv(modified)) if __name__ == '__main__': - main() \ No newline at end of file + main() diff --git a/GEMstack/offboard/calibration/visualizer.py b/GEMstack/offboard/calibration/visualizer.py new file mode 100644 index 000000000..538172068 --- /dev/null +++ b/GEMstack/offboard/calibration/visualizer.py @@ -0,0 +1,43 @@ +import pyvista as pv + +class visualizer: + def __init__(self): + self.plotter = pv.Plotter(notebook=False) + self.plotter.show_axes() + + def set_cam(self, pos=(-20, 0, 20), foc=(0, 0, 0)): + self.plotter.camera.position = pos + self.plotter.camera.focal_point = foc + return self + + def add_pc(self, pc, ratio=1, **kargs): + self.plotter.add_mesh( + pv.PolyData(pc * ratio), + render_points_as_spheres=True, + point_size=2, + **kargs + ) + return self + + def add_line(self, p1, p2, ratio=1, **kargs): + self.plotter.add_mesh( + pv.Line(p1 * ratio, p2 * ratio), + **kargs, + line_width=1 + ) + return self + + def add_box(self, bound, trans, ratio=1): + l, w, h = map(lambda x: x * ratio, bound) + box = pv.Box(bounds=(-l/2, l/2, -w/2, w/2, -h/2, h/2)) + box = box.translate(list(map(lambda x: x * ratio, trans))) + self.plotter.add_mesh(box, color='yellow') + return self + + def show(self): + self.plotter.show() + return self + + def close(self): + self.plotter.close() + return None diff --git a/GEMstack/onboard/execution/entrypoint.py b/GEMstack/onboard/execution/entrypoint.py index 849450e15..76ed35318 100644 --- a/GEMstack/onboard/execution/entrypoint.py +++ b/GEMstack/onboard/execution/entrypoint.py @@ -132,17 +132,19 @@ def caution_callback(k,variant): #configure logging if log_settings: - topfolder = log_settings.get('log','logs') + topfolder = log_settings.get('folder','logs') prefix = log_settings.get('prefix','') from datetime import datetime default_suffix = datetime.now().strftime('%Y-%m-%d_%H-%M-%S') suffix = log_settings.get('suffix',default_suffix) logfolder = os.path.join(topfolder,prefix+suffix) print(EXECUTION_PREFIX,"Logging to",logfolder) + auto_plot = log_settings.get("auto_plot", False) os.makedirs(logfolder,exist_ok=True) #configure logging for components mission_executor.set_log_folder(logfolder) + mission_executor.set_auto_plot(auto_plot) #configure ROS logging log_topics = log_settings.get('ros_topics',[]) rosbag_options = log_settings.get('rosbag_options','') diff --git a/GEMstack/onboard/execution/execution.py b/GEMstack/onboard/execution/execution.py index a65c2acc5..9af6ee5f3 100644 --- a/GEMstack/onboard/execution/execution.py +++ b/GEMstack/onboard/execution/execution.py @@ -424,6 +424,9 @@ def add_pipeline(self,name : str, perception : Dict[str,ComponentExecutor], plan def set_log_folder(self,folder : str): self.logging_manager.set_log_folder(folder) + + def set_auto_plot(self,enabled : bool): + self.logging_manager.set_auto_plot(enabled) def log_vehicle_interface(self,enabled=True): """Indicates that the vehicle interface should be logged""" diff --git a/GEMstack/onboard/execution/logging.py b/GEMstack/onboard/execution/logging.py index 31ebd962b..21f401994 100644 --- a/GEMstack/onboard/execution/logging.py +++ b/GEMstack/onboard/execution/logging.py @@ -1,6 +1,6 @@ from __future__ import annotations from ..component import Component -from ...utils import serialization,logging,config,settings +from ...utils import serialization,logging,config,settings,log_plot from typing import List,Optional,Dict,Set,Any import time import datetime @@ -27,6 +27,10 @@ def __init__(self): self.vehicle_time = None self.start_vehicle_time = None self.debug_messages = {} + self.auto_plot = False + + def set_auto_plot(self, auto_plot : bool) -> None: + self.auto_plot = auto_plot def logging(self) -> bool: return self.log_folder is not None @@ -264,6 +268,8 @@ def log_component_stderr(self, component : str, msg : List[str]) -> None: def close(self): self.dump_debug() + if self.auto_plot: + log_plot.main(self.log_folder) self.debug_messages = {} if self.rosbag_process is not None: out,err = self.rosbag_process.communicate() # Will block diff --git a/GEMstack/onboard/interface/gem_hardware.py b/GEMstack/onboard/interface/gem_hardware.py index f445fa356..7f61d6f4a 100644 --- a/GEMstack/onboard/interface/gem_hardware.py +++ b/GEMstack/onboard/interface/gem_hardware.py @@ -27,6 +27,7 @@ import numpy as np from ...utils import conversions + class GEMHardwareInterface(GEMInterface): """Interface for connnecting to the physical GEM e2 vehicle.""" def __init__(self): @@ -200,6 +201,7 @@ def callback_with_gnss_reading(msg: INSNavGeod): roll=math.radians(msg.roll), pitch=math.radians(msg.pitch), ) + # print("@@@@@, POSE", pose.x, pose.y) speed = np.sqrt(msg.ve**2 + msg.vn**2) callback(GNSSReading(pose,speed,('error' if msg.error else 'ok'))) self.gnss_sub = rospy.Subscriber(topic, INSNavGeod, callback_with_gnss_reading) diff --git a/GEMstack/onboard/interface/gem_simulator.py b/GEMstack/onboard/interface/gem_simulator.py index 86cf2f683..6312bd3c7 100644 --- a/GEMstack/onboard/interface/gem_simulator.py +++ b/GEMstack/onboard/interface/gem_simulator.py @@ -207,7 +207,7 @@ def simulate(self, T : float, command : Optional[GEMVehicleCommand]): reading.brake_pedal_position = brake_pedal_position reading.accelerator_pedal_position = 0 reading.speed = v - if v > 0: + if v >= 0: reading.gear = 1 else: reading.gear = -1 diff --git a/GEMstack/onboard/perception/README.md b/GEMstack/onboard/perception/README.md new file mode 100644 index 000000000..33876d899 --- /dev/null +++ b/GEMstack/onboard/perception/README.md @@ -0,0 +1,113 @@ +# Perception Team +This folder contains code that is used to detect objects in 3D space and subsequently notify other GEMstack components of the detected objects. It is split up into 3 main areas: Pedestrian detection code created at the beginning-middle of the course, Cone Detection code that is used to detect cones (optionally with orientation), and Sensor Fusion code which fuses YOLO + painted lidar data and PointPillars 3D bounding boxes to detect pedestrians. + +## Cone Detection +A YOLO model was trained to detect the orientations of traffic cones in 3D space to support the Vertical Groups. + +### Relevant Files +- cone_detection.py +- perception_utils.py + + +## Sensor Fusion +To improve the quality of the detected pedestrians, we decided to fuse detections from multiple modalities to take advantage of the strengths each sensor (camera and lidar in our case) provides. We accomplished this by fusing the 3D bounding box detections of pedestrians generated by YOLO (model which detects pedestrians with camera data) + painted lidar data and PointPillars (model which detects pedestrians with only lidar data). + +### Relevant Files +#### Setup files to create PointPillars Cuda 11.1.1 Docker container: +- build_point_pillars.sh +- setup/docker-compose.yaml +- setup/Dockerfile.cuda111 + +#### Code used to detect pedestrians: +- combined_detection.py +- point_pillars_node.py +- yolo_node.py + +#### Code used to analyze the results of detections and extract data from rosbags for further analysis: +- eval_3d_bbox_performance.py +- rosbag_processor.py +- test_eval_3d_bbox_performance.py + +### Local Installation Steps for PointPillars Docker Container +#### READ BEFOREHAND: +- Before perfoming installation steps, please make sure you source ALL terminal windows (except for docker terminal window). +``` +source /opt/ros/noetic/setup.bash +source ~/catkin_ws/devel/setup.bash +``` +- These instructions were written with the assumption that you are running them inside of the outermost GEMstack folder. +- If you have set up issues please read the "Set Up Issues Known Fixes" section at the bottom. + +#### Steps: +1. Install Docker +2. Install Docker Compose +3. A bash script was created to handle docker permissions issues and make the set up process simpler: +``` +cd GEMstack/onboard/perception +bash build_point_pillars.sh +``` +4. Start the container (use sudo if you run into permissions issues) +``` +docker compose -f setup/docker-compose.yaml up +``` +5. Run roscore on local machine (make sure you source first) +``` +roscore +``` +6. Start up YOLO node (make sure you source first): +``` +python3 GEMstack/onboard/perception/yolo_node.py +``` +7. Run yaml file to start up the CombinedDetector3D GEMstack Component (make sure you source first): +``` +python3 main.py --variant=detector_only launch/combined_detection.yaml +``` +8. Run a rosbag on a loop (make sure you source first): +``` +rosbag play -l yourRosbagNameGoesHere.bag +``` + +### Vehicle Installation Steps for PointPillars Docker Container +Perform the same setup steps as the above section with the below exceptions: +1. Ensure you source instead with the following command: +``` +source ~/demo_ws/devel/setup.bash +``` +2. Initialize the sensors: +``` +roslaunch basic_launch sensor_init.launch +``` +3. Initialize GNSS (if you need it) +``` +roslaunch basic_launch visualization.launch +``` +4. Do not run a rosbag in Step 8 above (it's not needed since you'll be getting live data from the vehicle) + +#### Known Fixes for Set Up Issues +1. If you get a shape error when creating the "results_normal" variable in yolo_node.py, please downgrade your Ultralytics version to 8.1.5 (this is the version used on the car at the time of writing this): +``` +pip install 'ultralytics==8.1.5' +``` +2. If you run into communication issues with ROS, please make sure you have sourced EVERY terminal window (except for docker window there's no need to): +``` +source /opt/ros/noetic/setup.bash +source ~/catkin_ws/devel/setup.bash +``` + +### Visualization Steps: +Please make sure you source each new terminal window after creating it (local source commands are below): +``` +source /opt/ros/noetic/setup.bash +source ~/catkin_ws/devel/setup.bash +``` + +1. Start rviz: +``` +rviz +``` +2. Publish a static transform from the map to visualize the published bounding box data: +``` +rosrun tf2_ros static_transform_publisher 0 0 0 0 0 0 map currentVehicleFrame +``` +3. In Rviz, click "add" in the bottom left corner. In "By display type", under "jsk_rviz_plugins" select BoundingBoxArray. +4. Expand BoundingBoxArray on the left. Under it you will see "Topic" with a blank space to the right of it. Click the blank space (it's a hidden drop down box) and select the BoundingBoxArray topic to visualize \ No newline at end of file diff --git a/GEMstack/onboard/perception/build_point_pillars.sh b/GEMstack/onboard/perception/build_point_pillars.sh new file mode 100644 index 000000000..829243f2f --- /dev/null +++ b/GEMstack/onboard/perception/build_point_pillars.sh @@ -0,0 +1,49 @@ +#!/bin/bash + +# Check if the point_pillars_node.py, the helper functions file, and model weights exist +if [ ! -f "point_pillars_node.py" ]; then + echo "ERROR: point_pillars_node.py not found in the current directory!" + echo "Please place your point_pillars_node.py file in the same directory as this script." + exit 1 +fi + +if [ ! -f "combined_detection_utils.py" ]; then + echo "ERROR: combined_detection_utils.py not found in the current directory!" + echo "Please place your combined_detection_utils.py file in the same directory as this script." + exit 1 +fi + +if [ ! -f "epoch_160.pth" ]; then + echo "WARNING: epoch_160.pth model weights not found in the current directory!" + echo "Please place your model weights file in the same directory as this script." + echo "Continue anyway? (y/n)" + read -p ">" choice + if [ "$choice" != "y" ] && [ "$choice" != "Y" ]; then + exit 1 + fi +fi + +echo "Building Point Pillars Docker container..." +export DOCKERFILE=setup/Dockerfile.cuda111 + +# Using sudo to handle permissions +MY_UID=$(id -u) +MY_GID=$(id -g) + +# Attempt to use docker-compose directly, then with sudo if needed (if you uncomment it) +if ! docker compose -f setup/docker-compose.yaml build; then + echo "Uncomment these lines if you wish to use sudo to build container as backup" + # echo "Using sudo to build the container..." + # sudo -E docker compose -f setup/docker-compose.yaml build +fi + +# Notify user of how to run the container +echo "Build complete. To start the container, run:" +echo "docker compose -f setup/docker-compose.yaml up" +echo "" +echo "Or with sudo if you have permission issues:" +echo "sudo docker compose -f setup/docker-compose.yaml up" +echo "" +echo "To run in detached mode (background):" +echo "docker compose -f setup/docker-compose.yaml up -d" +echo "Or: sudo docker compose -f setup/docker-compose.yaml up -d" diff --git a/GEMstack/onboard/perception/combined_detection.py b/GEMstack/onboard/perception/combined_detection.py new file mode 100644 index 000000000..59ab5edae --- /dev/null +++ b/GEMstack/onboard/perception/combined_detection.py @@ -0,0 +1,511 @@ +from ...state import AllState, VehicleState, ObjectPose, ObjectFrameEnum, AgentState, AgentEnum, AgentActivityEnum +from ..interface.gem import GEMInterface +from ..component import Component +from .perception_utils import pose_to_matrix +from .perception_utils_gem import * +from typing import Dict, List, Optional, Tuple +import rospy +from message_filters import Subscriber, ApproximateTimeSynchronizer +import time +import os +import yaml +import numpy as np +from scipy.spatial.transform import Rotation as R +from jsk_recognition_msgs.msg import BoundingBox, BoundingBoxArray +from geometry_msgs.msg import Quaternion + +from .sensorFusion.eval_3d_model_performance import calculate_3d_iou +import copy + + +def average_yaw(yaw1, yaw2): + v1 = np.array([np.cos(yaw1), np.sin(yaw1)]) + v2 = np.array([np.cos(yaw2), np.sin(yaw2)]) + v_avg = (v1 + v2) / 2.0 + return np.arctan2(v_avg[1], v_avg[0]) + + +def quaternion_to_yaw(quaternion_arr): + return R.from_quat(quaternion_arr).as_euler('zyx', degrees=False)[0] + + +def avg_orientations(orientation1, orientation2): + """Average two quaternion orientations by converting to yaw and back.""" + # This function assumes both quaternions are 2D planar rotations around the z axis + quat1 = [orientation1.x, orientation1.y, orientation1.z, orientation1.w] + quat2 = [orientation2.x, orientation2.y, orientation2.z, orientation2.w] + + yaw1 = quaternion_to_yaw(quaternion_arr=quat1) + yaw2 = quaternion_to_yaw(quaternion_arr=quat2) + + # Compute the average yaw and then convert back into quaternions + # (averaging quaternions directly causes problems) + avg_yaw = average_yaw(yaw1=yaw1, yaw2=yaw2) + avg_quat = R.from_euler('z', avg_yaw).as_quat() + + orientation = Quaternion() + orientation.x = float(avg_quat[0]) + orientation.y = float(avg_quat[1]) + orientation.z = float(avg_quat[2]) + orientation.w = float(avg_quat[3]) + + return orientation + + +def merge_boxes(box1: BoundingBox, box2: BoundingBox, mode: str = "Average") -> BoundingBox: + """ + Merge two bounding boxes using the specified mode. + + Args: + box1: First bounding box + box2: Second bounding box + mode: Merging strategy to use. Options include: + - "Average": Simple average of position, dimensions, and orientation (default) + - "Score": Weight average by confidence scores (box.value) + - "Max": Use the entire box with the highest confidence score + + Notes: + - The 'value' field in BoundingBox is used for the confidence score + - The label from the box with higher confidence is used when using Score mode + - In Average mode, the label from the first box is used + - Max mode returns a copy of the box with the highest confidence score + + Returns: + A merged bounding box + """ + + merged_box = BoundingBox() + merged_box.header = box1.header # Use header from one input + + # Get confidence scores + score1 = box1.value if hasattr(box1, 'value') else 0.0 + score2 = box2.value if hasattr(box2, 'value') else 0.0 + + if mode == "Max": + # Use the box with the higher confidence score entirely + if score1 >= score2: + return copy.deepcopy(box1) + else: + return copy.deepcopy(box2) + + elif mode == "Score": + # If both scores are 0, fall back to average + if score1 == 0.0 and score2 == 0.0: + weight1, weight2 = 0.5, 0.5 + else: + # Calculate normalized weights based on scores + total_score = score1 + score2 + weight1 = score1 / total_score + weight2 = score2 / total_score + + # Weighted average of position + merged_box.pose.position.x = (weight1 * box1.pose.position.x) + (weight2 * box2.pose.position.x) + merged_box.pose.position.y = (weight1 * box1.pose.position.y) + (weight2 * box2.pose.position.y) + merged_box.pose.position.z = (weight1 * box1.pose.position.z) + (weight2 * box2.pose.position.z) + + # Weighted average of dimensions + merged_box.dimensions.x = (weight1 * box1.dimensions.x) + (weight2 * box2.dimensions.x) + merged_box.dimensions.y = (weight1 * box1.dimensions.y) + (weight2 * box2.dimensions.y) + merged_box.dimensions.z = (weight1 * box1.dimensions.z) + (weight2 * box2.dimensions.z) + + # For orientation, we still use the average_orientations function + # More advanced: implement weighted quaternion averaging + merged_box.pose.orientation = avg_orientations(box1.pose.orientation, box2.pose.orientation) + + # For label, use the one from the higher-score box + merged_box.label = box1.label if score1 >= score2 else box2.label + + elif mode == "BEV": + # Merge the bounding boxes from Bird's Eye View (BEV) + # Average the x and y centers and dimensions + # Average the yaw orientation + # Use YOLO bounding box (box1) for z dimension and z center + merged_box.pose.position.x = (box1.pose.position.x + box2.pose.position.x) / 2.0 + merged_box.pose.position.y = (box1.pose.position.y + box2.pose.position.y) / 2.0 + merged_box.pose.position.z = copy.deepcopy(box1.pose.position.z) + + # Avg orientations (quaternions) + merged_box.pose.orientation = avg_orientations(box1.pose.orientation, box2.pose.orientation) + + merged_box.dimensions.x = (box1.dimensions.x + box2.dimensions.x) / 2.0 + merged_box.dimensions.y = (box1.dimensions.y + box2.dimensions.y) / 2.0 + merged_box.dimensions.z = copy.deepcopy(box1.dimensions.z) + + merged_box.label = box1.label # Label from first box + + else: # Default to "Average" mode + # Original averaging logic + merged_box.pose.position.x = (box1.pose.position.x + box2.pose.position.x) / 2.0 + merged_box.pose.position.y = (box1.pose.position.y + box2.pose.position.y) / 2.0 + merged_box.pose.position.z = (box1.pose.position.z + box2.pose.position.z) / 2.0 + + # Avg orientations (quaternions) + merged_box.pose.orientation = avg_orientations(box1.pose.orientation, box2.pose.orientation) + + merged_box.dimensions.x = (box1.dimensions.x + box2.dimensions.x) / 2.0 + merged_box.dimensions.y = (box1.dimensions.y + box2.dimensions.y) / 2.0 + merged_box.dimensions.z = (box1.dimensions.z + box2.dimensions.z) / 2.0 + merged_box.label = box1.label # Label from first box + + # Always use max score for the merged box confidence value + merged_box.value = max(score1, score2) + + return merged_box + + +def get_aabb_corners(box: BoundingBox): + """ + Get axis-aligned bounding box corners for IoU calculation. + Use axis-aligned bounding boxes so it does not consider rotation. + + Returns: + min_x, max_x, min_y, max_y, min_z, max_z coordinates + """ + # Extract position and dimensions from each box + cx, cy, cz = box.pose.position.x, box.pose.position.y, box.pose.position.z + l, w, h = box.dimensions.x, box.dimensions.y, box.dimensions.z + + # min_x, max_x, min_y, max_y, min_z, max_z + return cx, cx + l, cy, cy + w, cz, cz + h + + +def get_volume(box): + """Calculate the volume of a bounding box.""" + return box.dimensions.x * box.dimensions.y * box.dimensions.z + + +def get_bev_aabb_corners(box: BoundingBox): + """ + Get axis-aligned bounding box corners for 2D Bird's Eye View IoU calculation. + Returns: + min_x, max_x, min_y, max_y + """ + cx, cy = box.pose.position.x, box.pose.position.y + l, w = box.dimensions.x, box.dimensions.y + + return cx, cx + l, cy, cy + w + + +def calculate_bev_iou(box1: BoundingBox, box2: BoundingBox): + """ + Calculates the 2D Bird's Eye View IoU between two bounding boxes. + Ignores z-axis and yaw (assumes axis aligned bounding boxes). + """ + min_x1, max_x1, min_y1, max_y1 = get_bev_aabb_corners(box1) + min_x2, max_x2, min_y2, max_y2 = get_bev_aabb_corners(box2) + + # Calculate intersection in BEV + inter_min_x = max(min_x1, min_x2) + inter_max_x = min(max_x1, max_x2) + inter_min_y = max(min_y1, min_y2) + inter_max_y = min(max_y1, max_y2) + + inter_w = max(0, inter_max_x - inter_min_x) + inter_h = max(0, inter_max_y - inter_min_y) + intersection_area = inter_w * inter_h + + # Calculate union area + area1 = max(box1.dimensions.x * box1.dimensions.y, 1e-6) + area2 = max(box2.dimensions.x * box2.dimensions.y, 1e-6) + union_area = max(area1 + area2 - intersection_area, 1e-6) + + iou = intersection_area / union_area + return max(0.0, min(iou, 1.0)) # Clamp to [0, 1] + + +class CombinedDetector3D(Component): + """ + Combines detections from multiple 3D object detectors (YOLO and PointPillars). + + This component subscribes to bounding box outputs from YOLO and PointPillars, + fuses overlapping detections, and outputs a unified set of 3D bounding boxes. + """ + + def __init__( + self, + vehicle_interface: GEMInterface, + enable_tracking: bool = True, + use_start_frame: bool = True, + iou_threshold: float = 0.1, + merge_mode: str = "Average", + **kwargs + ): + self.vehicle_interface = vehicle_interface + self.tracked_agents: Dict[str, AgentState] = {} + self.ped_counter = 0 + self.latest_yolo_bbxs: Optional[BoundingBoxArray] = None + self.latest_pp_bbxs: Optional[BoundingBoxArray] = None + self.start_pose_abs: Optional[ObjectPose] = None + self.start_time: Optional[float] = None + + self.enable_tracking = enable_tracking + self.use_start_frame = use_start_frame + self.iou_threshold = iou_threshold + self.merge_mode = merge_mode + self.merge_in_bev = (merge_mode == "BEV") + + self.yolo_topic = '/yolo_boxes' + self.pp_topic = '/pointpillars_boxes' + self.debug = False + + rospy.loginfo(f"CombinedDetector3D Initialized. Subscribing to '{self.yolo_topic}' and '{self.pp_topic}'.") + rospy.loginfo(f"Using merge mode: {self.merge_mode}") + + def rate(self) -> float: + return 8.0 + + def state_inputs(self) -> list: + return ['vehicle'] + + def state_outputs(self) -> list: + return ['agents'] + + def initialize(self): + """Initialize subscribers and publishers.""" + self.yolo_sub = Subscriber(self.yolo_topic, BoundingBoxArray) + self.pp_sub = Subscriber(self.pp_topic, BoundingBoxArray) + self.pub_fused = rospy.Publisher("/fused_boxes", BoundingBoxArray, queue_size=1) + + queue_size = 10 + slop = 0.1 + + self.sync = ApproximateTimeSynchronizer( + [self.yolo_sub, self.pp_sub], + queue_size=queue_size, + slop=slop + ) + self.sync.registerCallback(self.synchronized_callback) + rospy.loginfo("CombinedDetector3D Subscribers Initialized.") + + def synchronized_callback(self, yolo_bbxs_msg: BoundingBoxArray, pp_bbxs_msg: BoundingBoxArray): + """Callback for synchronized YOLO and PointPillars messages.""" + self.latest_yolo_bbxs = yolo_bbxs_msg + self.latest_pp_bbxs = pp_bbxs_msg + + def update(self, vehicle: VehicleState) -> Dict[str, AgentState]: + """Update function called by the GEMstack pipeline.""" + current_time = self.vehicle_interface.time() + agents: Dict[str, AgentState] = {} + + if self.start_time is None: + self.start_time = current_time + + yolo_bbx_array = copy.deepcopy(self.latest_yolo_bbxs) + pp_bbx_array = copy.deepcopy(self.latest_pp_bbxs) + + if yolo_bbx_array is None or pp_bbx_array is None: + return {} + + original_header = yolo_bbx_array.header + fused_boxes_list = self._fuse_bounding_boxes(yolo_bbx_array, pp_bbx_array) + + # Used to visualize the combined results in the current frame + fused_bb_array = BoundingBoxArray() + fused_bb_array.header = original_header + + for i, box in enumerate(fused_boxes_list): + fused_bb_array.boxes.append(box) + rospy.loginfo(len(fused_boxes_list)) + + # Get position and orientation in current vehicle frame + # pos_x - z are returned as Quaternions. + pos_x = box.pose.position.x + pos_y = box.pose.position.y + pos_z = box.pose.position.z + quat_x = box.pose.orientation.x + quat_y = box.pose.orientation.y + quat_z = box.pose.orientation.z + quat_w = box.pose.orientation.w + yaw, pitch, roll = R.from_quat([quat_x, quat_y, quat_z, quat_w]).as_euler('zyx', degrees=False) + + if self.use_start_frame: + out_frame = ObjectFrameEnum.START + # Get the starting vehicle pose + if self.start_pose_abs is None: + self.start_pose_abs = vehicle.pose + + # Convert to start frame + vehicle_start_pose = vehicle.pose.to_frame( + ObjectFrameEnum.START, vehicle.pose, self.start_pose_abs + ) + # T_vehicle_to_start = pose_to_matrix(vehicle_start_pose) + T_vehicle_to_start = vehicle_start_pose.transform() + object_pose_current_h = np.array([[pos_x],[pos_y],[pos_z],[1.0]]) + object_pose_start_h = T_vehicle_to_start @ object_pose_current_h + final_x, final_y, final_z = object_pose_start_h[:3, 0] + else: + out_frame = ObjectFrameEnum.CURRENT + final_x = pos_x + final_y = pos_y + final_z = pos_z + + new_pose = ObjectPose( + t=current_time, x=final_x, y=final_y, z=final_z, + yaw=yaw, pitch=pitch, roll=roll, frame=out_frame + ) + dims = (box.dimensions.x, box.dimensions.y, box.dimensions.z * 2.0) # AgentState has z center on the floor and height is full height. + + new_pose = ObjectPose( + t=current_time, x=final_x, y=final_y, z=final_z - box.dimensions.z / 2.0, + yaw=yaw, pitch=pitch, roll=roll, frame=out_frame + ) + + existing_id = match_existing_cone( + new_center=np.array([new_pose.x, new_pose.y, new_pose.z]), + new_dims=dims, + existing_agents=self.tracked_agents, + distance_threshold=2.0 + ) + + if existing_id is not None: + old_state = self.tracked_agents[existing_id] + dt = new_pose.t - old_state.pose.t + vx, vy, vz = compute_velocity(old_state.pose, new_pose, dt) + updated_agent = AgentState( + pose=new_pose, + dimensions=dims, + outline=None, + type=AgentEnum.PEDESTRIAN, + activity=AgentActivityEnum.MOVING, + velocity=(vx, vy, vz), + yaw_rate=0 + ) + agents[existing_id] = updated_agent + self.tracked_agents[existing_id] = updated_agent + else: + agent_id = f"Pedestrian{self.ped_counter}" + self.ped_counter += 1 + new_agent = AgentState( + pose=new_pose, + dimensions=dims, + outline=None, + type=AgentEnum.PEDESTRIAN, + activity=AgentActivityEnum.MOVING, + velocity=(0, 0, 0), + yaw_rate=0 + ) + agents[agent_id] = new_agent + self.tracked_agents[agent_id] = new_agent + + self.pub_fused.publish(fused_bb_array) + + stale_ids = [agent_id for agent_id, agent in self.tracked_agents.items() + if current_time - agent.pose.t > 5.0] + for agent_id in stale_ids: + rospy.loginfo(f"Removing stale agent: {agent_id}\n") + for agent_id, agent in agents.items(): + p = agent.pose + # Format pose and velocity with 3 decimals (or as needed) + rospy.loginfo( + f"Agent ID: {agent_id}\n" + f"Pose: (x: {p.x:.3f}, y: {p.y:.3f}, z: {p.z:.3f}, " + f"yaw: {p.yaw:.3f}, pitch: {p.pitch:.3f}, roll: {p.roll:.3f})\n" + f"Velocity: (vx: {agent.velocity[0]:.3f}, vy: {agent.velocity[1]:.3f}, vz: {agent.velocity[2]:.3f})\n" + ) + + return agents + + + def _fuse_bounding_boxes(self, + yolo_bbx_array: BoundingBoxArray, + pp_bbx_array: BoundingBoxArray, + ): + """ + Fuse bounding boxes from multiple detectors. + + Args: + yolo_bbx_array: Bounding boxes from YOLO detector + pp_bbx_array: Bounding boxes from PointPillars detector + """ + yolo_boxes: List[BoundingBox] = yolo_bbx_array.boxes + pp_boxes: List[BoundingBox] = pp_bbx_array.boxes + + matched_yolo_indices = set() + matched_pp_indices = set() + fused_boxes_list: List[BoundingBox] = [] + + # Match the boxes + # Can optimize from NxM loop + for i, yolo_box in enumerate(yolo_boxes): + best_match_j = -1 + best_iou = -1.0 + for j, pp_box in enumerate(pp_boxes): + if j in matched_pp_indices: # Skip already matched PP boxes + continue + + ## IoU + iou = None + if self.merge_in_bev: + iou = calculate_bev_iou(yolo_box, pp_box) + else: + iou = calculate_3d_iou(yolo_box, pp_box, get_aabb_corners, get_volume) + + if iou > self.iou_threshold and iou > best_iou: + best_iou = iou + best_match_j = j + + if best_match_j != -1: + rospy.logdebug(f"Matched YOLO box {i} with PP box {best_match_j} (IoU: {best_iou:.3f})") + matched_yolo_indices.add(i) + matched_pp_indices.add(best_match_j) + rospy.logdebug(f"Using merge mode: {self.merge_mode} for boxes with scores {yolo_box.value:.2f} and {pp_boxes[best_match_j].value:.2f}") + merged = merge_boxes(yolo_box, pp_boxes[best_match_j], mode=self.merge_mode) + fused_boxes_list.append(merged) + + ## Add the unmatched YOLO boxes + for i, yolo_box in enumerate(yolo_boxes): + if i not in matched_yolo_indices: + fused_boxes_list.append(yolo_box) + rospy.logdebug(f"Kept unmatched YOLO box {i}") + + # Add the unmatched PointPillars boxes + for j, pp_box in enumerate(pp_boxes): + if j not in matched_pp_indices: + fused_boxes_list.append(pp_box) + rospy.logdebug(f"Kept unmatched PP box {j}") + + return fused_boxes_list + + +# Fake 2D Combined Detector for testing purposes +class FakeCombinedDetector2D(Component): + """Test detector that simulates cone detections at fixed time intervals.""" + + def __init__(self, vehicle_interface: GEMInterface): + self.vehicle_interface = vehicle_interface + self.times = [(5.0, 20.0), (30.0, 35.0)] + self.t_start = None + + def rate(self): + return 4.0 + + def state_inputs(self): + return ['vehicle'] + + def state_outputs(self): + return ['agents'] + + def update(self, vehicle: VehicleState) -> Dict[str, AgentState]: + if self.t_start is None: + self.t_start = self.vehicle_interface.time() + t = self.vehicle_interface.time() - self.t_start + res = {} + for time_range in self.times: + if t >= time_range[0] and t <= time_range[1]: + res['cone0'] = box_to_fake_agent((0, 0, 0, 0)) + rospy.loginfo("Detected a Cone (simulated)") + return res + + +def box_to_fake_agent(box): + """Convert 2D bounding box to a fake agent state.""" + x, y, w, h = box + pose = ObjectPose(t=0, x=x + w / 2, y=y + h / 2, z=0, yaw=0, pitch=0, roll=0, frame=ObjectFrameEnum.CURRENT) + dims = (w, h, 0) + return AgentState(pose=pose, dimensions=dims, outline=None, + type=AgentEnum.CONE, activity=AgentActivityEnum.MOVING, + velocity=(0, 0, 0), yaw_rate=0) + + +if __name__ == '__main__': + pass diff --git a/GEMstack/onboard/perception/combined_detection_utils.py b/GEMstack/onboard/perception/combined_detection_utils.py new file mode 100644 index 000000000..28673e1a5 --- /dev/null +++ b/GEMstack/onboard/perception/combined_detection_utils.py @@ -0,0 +1,36 @@ +from jsk_recognition_msgs.msg import BoundingBox +from scipy.spatial.transform import Rotation as R + +# Seperated Sensor Fusion specific utilities into it's own file because package imports are required +# (to minimize integration problems for groups who aren't using sensor fusion) + +# Adds a new bounding box to a BoundingBoxArray +def add_bounding_box(boxes, frame_id, stamp, x, y, z, l, w, h, yaw, conf_score, label): + box_msg = BoundingBox() + box_msg.header.frame_id = frame_id + box_msg.header.stamp = stamp + + # Set the pose + box_msg.pose.position.x = float(x) + box_msg.pose.position.y = float(y) + box_msg.pose.position.z = float(z) + + # Convert yaw to quaternion + quat = R.from_euler('z', yaw).as_quat() + box_msg.pose.orientation.x = float(quat[0]) + box_msg.pose.orientation.y = float(quat[1]) + box_msg.pose.orientation.z = float(quat[2]) + box_msg.pose.orientation.w = float(quat[3]) + + # Set the dimensions + # Swapped dims[2] and dims[0] + box_msg.dimensions.x = float(l) # length + box_msg.dimensions.y = float(w) # width + box_msg.dimensions.z = float(h) # height + + # Add confidence score and label + box_msg.value = float(conf_score) + box_msg.label = label + + boxes.boxes.append(box_msg) + return boxes diff --git a/GEMstack/onboard/perception/cone_detection.py b/GEMstack/onboard/perception/cone_detection.py index 42b74bb6b..0abf58275 100644 --- a/GEMstack/onboard/perception/cone_detection.py +++ b/GEMstack/onboard/perception/cone_detection.py @@ -3,6 +3,7 @@ from ..interface.gem import GEMInterface from ..component import Component from .perception_utils import * +from .perception_utils_gem import * from ultralytics import YOLO import cv2 from typing import Dict @@ -361,7 +362,7 @@ def update(self, vehicle: VehicleState) -> Dict[str, Obstacle]: outline=None, material=ObstacleMaterialEnum.TRAFFIC_CONE, state=state, - collidable=True + collidable=False ) else: updated_obstacle = old_state @@ -376,7 +377,7 @@ def update(self, vehicle: VehicleState) -> Dict[str, Obstacle]: outline=None, material=ObstacleMaterialEnum.TRAFFIC_CONE, state=state, - collidable=True + collidable=False ) obstacles[obstacle_id] = new_obstacle self.tracked_obstacles[obstacle_id] = new_obstacle @@ -389,7 +390,7 @@ def update(self, vehicle: VehicleState) -> Dict[str, Obstacle]: outline=None, material=ObstacleMaterialEnum.TRAFFIC_CONE, state=state, - collidable = True + collidable=False ) obstacles[obstacle_id] = new_obstacle @@ -502,7 +503,7 @@ def box_to_fake_obstacle(box): pose = ObjectPose(t=0, x=x + w / 2, y=y + h / 2, z=0, yaw=0, pitch=0, roll=0, frame=ObjectFrameEnum.CURRENT) dims = (w, h, 0) return Obstacle(pose=pose, dimensions=dims, outline=None, - material=ObstacleMaterialEnum.TRAFFIC_CONE, state=ObstacleStateEnum.STANDING, collidable=True) + material=ObstacleMaterialEnum.TRAFFIC_CONE, state=ObstacleStateEnum.STANDING) if __name__ == '__main__': diff --git a/GEMstack/onboard/perception/pedestrian_detection.py b/GEMstack/onboard/perception/pedestrian_detection.py new file mode 100644 index 000000000..8f1e41131 --- /dev/null +++ b/GEMstack/onboard/perception/pedestrian_detection.py @@ -0,0 +1,399 @@ +from ...state import AllState, VehicleState, ObjectPose, ObjectFrameEnum, AgentState, AgentEnum, AgentActivityEnum +from ..interface.gem import GEMInterface +from ..component import Component +from .perception_utils import * # If you want to alias functions for clarity, do so in perception_utils +from .perception_utils_gem import * +from ultralytics import YOLO +from typing import Dict +import open3d as o3d +import numpy as np +from scipy.spatial.transform import Rotation as R +import rospy +from sensor_msgs.msg import PointCloud2, Image +from message_filters import Subscriber, ApproximateTimeSynchronizer +from cv_bridge import CvBridge +import time +import os +import yaml + + +class PedestrianDetector3D(Component): + """ + Detects pedestrians by fusing YOLO 2D detections with LiDAR point cloud data. + Tracking is optional: `enable_tracking=False` returns only current-frame detections. + Calculates and outputs each pedestrian's velocity and yaw rate. + """ + + def __init__( + self, + vehicle_interface: GEMInterface, + camera_name: str, + camera_calib_file: str, + enable_tracking: bool = True, + visualize_2d: bool = False, + use_cyl_roi: bool = False, + T_l2v: list = None, + save_data: bool = True, + use_start_frame: bool = True, + **kwargs + ): + # Core interfaces and state + self.vehicle_interface = vehicle_interface + self.current_agents = {} + self.tracked_agents = {} + self.pedestrian_counter = 0 + self.latest_image = None + self.latest_lidar = None + self.bridge = CvBridge() + self.start_pose_abs = None + self.start_time = None + + # Configuration + self.camera_name = camera_name + self.enable_tracking = enable_tracking + self.visualize_2d = visualize_2d + self.use_cyl_roi = use_cyl_roi + self.save_data = save_data + self.use_start_frame = use_start_frame + + # 1) Load LiDAR-to-vehicle transform + self.T_l2v = np.array(T_l2v) if T_l2v is not None else np.array([ + [0.99939639, 0.02547917, 0.023615, 1.1], + [-0.02530848, 0.99965156, -0.00749882, 0.03773583], + [-0.02379784, 0.00689664, 0.999693, 1.95320223], + [0.0, 0.0, 0.0, 1.0] + ]) + + # 2) Load camera intrinsics/extrinsics from YAML + with open(camera_calib_file, 'r') as f: + calib = yaml.safe_load(f) + cam_cfg = calib['cameras'][camera_name] + self.K = np.array(cam_cfg['K']) + self.D = np.array(cam_cfg['D']) + self.T_l2c = np.array(cam_cfg['T_l2c']) + + self.undistort_map1 = None + self.undistort_map2 = None + self.camera_front = (camera_name == 'front') + + def rate(self) -> float: + return 8.0 + + def state_inputs(self) -> list: + return ['vehicle'] + + def state_outputs(self) -> list: + return ['agents'] + + def initialize(self): + # Subscribe to RGB & LiDAR streams + rgb_topic_map = { + 'front': '/oak/rgb/image_raw', + 'front_right': '/camera_fr/arena_camera_node/image_raw', + } + rgb_topic = rgb_topic_map.get(self.camera_name, + f'/{self.camera_name}/rgb/image_raw') + self.rgb_sub = Subscriber(rgb_topic, Image) + self.lidar_sub = Subscriber('/ouster/points', PointCloud2) + self.sync = ApproximateTimeSynchronizer( + [self.rgb_sub, self.lidar_sub], queue_size=500, slop=0.025 + ) + self.sync.registerCallback(self.synchronized_callback) + + # Initialize YOLO pedestrian detection model (COCO class 0) + self.detector = YOLO('GEMstack/knowledge/detection/yolov8n.pt') + self.detector.to('cuda') + + # Compute camera-to-LiDAR transform + self.T_c2l = np.linalg.inv(self.T_l2c) + self.R_c2l = self.T_c2l[:3, :3] + self.camera_origin_in_lidar = self.T_c2l[:3, 3] + + def synchronized_callback(self, image_msg, lidar_msg): + try: + self.latest_image = self.bridge.imgmsg_to_cv2(image_msg, "bgr8") + except Exception as e: + rospy.logerr(f"Failed to convert image: {e}") + self.latest_image = None + self.latest_lidar = pc2_to_numpy(lidar_msg, want_rgb=False) + + def undistort_image(self, image, K, D): + h, w = image.shape[:2] + newK, _ = cv2.getOptimalNewCameraMatrix(K, D, (w, h), 1, (w, h)) + if self.undistort_map1 is None: + self.undistort_map1, self.undistort_map2 = cv2.initUndistortRectifyMap( + K, D, None, newK, (w, h), cv2.CV_32FC1 + ) + undistorted = cv2.remap( + image, self.undistort_map1, self.undistort_map2, + interpolation=cv2.INTER_NEAREST + ) + return undistorted, newK + + def update(self, vehicle: VehicleState) -> Dict[str, AgentState]: + # Ensure both image and LiDAR data are available + if self.latest_image is None or self.latest_lidar is None: + return {} + + current_time = self.vehicle_interface.time() + if self.start_time is None: + self.start_time = current_time + + # Optionally save raw sensor data + if self.save_data: + self.save_sensor_data(vehicle, self.latest_image) + + # Undistort image if needed + if not self.camera_front: + img, self.current_K = self.undistort_image( + self.latest_image, self.K, self.D) + else: + img = self.latest_image.copy() + self.current_K = self.K + + # Perform 2D detection + results = self.detector(img, conf=0.35, classes=[0]) + boxes2d = (np.array(results[0].boxes.xywh.cpu()) + if len(results) > 0 else []) + + # Project LiDAR points into image plane + lidar_pts = self.latest_lidar.copy() + pts_cam = transform_points_l2c(lidar_pts, self.T_l2c) + projected = project_points(pts_cam, self.current_K, lidar_pts) + + agents: Dict[str, AgentState] = {} + for (cx, cy, w, h) in boxes2d: + # print(cx, cy, w, h) + # Define ROI in image for each detection + left = int(cx - w / 2) + right = int(cx + w / 2) + top = int(cy - h / 2) + bottom = int(cy + h / 2) + mask = ((projected[:, 0] >= left) & (projected[:, 0] <= right) & + (projected[:, 1] >= top) & (projected[:, 1] <= bottom)) + roi = projected[mask] + if roi.shape[0] < 5: + continue + + # Filter point cloud + pts3d = roi[:, 2:5] + pts3d = filter_points_within_threshold(pts3d, 40) + pts3d = remove_ground_by_min_range(pts3d, z_range=0.08) + pts3d = filter_depth_points(pts3d, max_depth_diff=0.5) + + if self.use_cyl_roi: + glob = filter_points_within_threshold(lidar_pts, 30) + cyl = cylindrical_roi(glob, np.mean(pts3d, axis=0), radius=0.5, height=2.0) + pts3d = remove_ground_by_min_range(cyl, z_range=0.01) + pts3d = filter_depth_points(pts3d, max_depth_diff=0.3) + + if pts3d.shape[0] < 4: + continue + + # Fit oriented bounding box + pcd = o3d.geometry.PointCloud() + pcd.points = o3d.utility.Vector3dVector(pts3d) + obb = pcd.get_oriented_bounding_box() + center = obb.center + dims = tuple(obb.extent) + R_lidar = obb.R + + # Transform to vehicle frame + c_hom = np.append(center, 1) + veh_hom = self.T_l2v @ c_hom + veh_center = veh_hom[:3] + + # Compute orientation + R_veh = self.T_l2v[:3, :3] @ R_lidar + yaw, pitch, roll = R.from_matrix(R_veh).as_euler('zyx', degrees=False) + + # Convert to START or CURRENT frame + if self.use_start_frame: + if self.start_pose_abs is None: + self.start_pose_abs = vehicle.pose + start_pose = vehicle.pose.to_frame( + ObjectFrameEnum.START, vehicle.pose, self.start_pose_abs) + T_vs = pose_to_matrix(start_pose) + xp, yp, zp = (T_vs @ np.append(veh_center, 1))[:3] + frame = ObjectFrameEnum.START + else: + xp, yp, zp = veh_center + frame = ObjectFrameEnum.CURRENT + + new_pose = ObjectPose( + t=current_time, + x=xp, y=yp, z=zp, + yaw=yaw, pitch=pitch, roll=roll, + frame=frame + ) + + # Matching and tracking + if self.enable_tracking: + existing = match_existing_cone( + np.array([new_pose.x, new_pose.y, new_pose.z]), + dims, self.tracked_agents, + distance_threshold=1.0 + ) + if existing is not None: + old = self.tracked_agents[existing] + dt = max(new_pose.t - old.pose.t, 1e-3) + # Instantaneous velocity + vx = (new_pose.x - old.pose.x) / dt + vy = (new_pose.y - old.pose.y) / dt + vz = (new_pose.z - old.pose.z) / dt + # Yaw rate + yaw_rate = (new_pose.yaw - old.pose.yaw) / dt + speed = np.linalg.norm([vx, vy, vz]) + activity = (AgentActivityEnum.MOVING + if speed > 0.1 else AgentActivityEnum.STOPPED) + + updated = AgentState( + pose=new_pose, + dimensions=dims, + outline=None, + type=AgentEnum.PEDESTRIAN, + activity=activity, + velocity=(vx, vy, vz), + yaw_rate=yaw_rate + ) + agents[existing] = updated + self.tracked_agents[existing] = updated + + else: + aid = f"Pedestrian{self.pedestrian_counter}" + self.pedestrian_counter += 1 + new_agent = AgentState( + pose=new_pose, + dimensions=dims, + outline=None, + type=AgentEnum.PEDESTRIAN, + activity=AgentActivityEnum.STOPPED, + velocity=(0, 0, 0), + yaw_rate=0 + ) + agents[aid] = new_agent + self.tracked_agents[aid] = new_agent + for agent_id, agent in self.current_agents.items(): + p = agent.pose + rospy.loginfo( + f"Agent ID: {agent_id}\n" + f"Pose: (x: {p.x:.3f}, y: {p.y:.3f}, z: {p.z:.3f}, " + f"yaw: {p.yaw:.3f}, pitch: {p.pitch:.3f}, roll: {p.roll:.3f})\n" + f"Velocity: (vx: {agent.velocity[0]:.3f}, vy: {agent.velocity[1]:.3f}, vz: {agent.velocity[2]:.3f})\n" + f"type:{agent.activity}" + ) + else: + aid = f"Pedestrian{self.pedestrian_counter}" + self.pedestrian_counter += 1 + agents[aid] = AgentState( + pose=new_pose, + dimensions=dims, + outline=None, + type=AgentEnum.PEDESTRIAN, + activity=AgentActivityEnum.STOPPED, + velocity=(0, 0, 0), + yaw_rate=0 + ) + + self.current_agents = agents + + # Remove stale tracked agents + if self.enable_tracking: + stale = [ + aid for aid, a in self.tracked_agents.items() + if current_time - a.pose.t > 10.0 + ] + for aid in stale: + del self.tracked_agents[aid] + return self.tracked_agents + + return self.current_agents + + def save_sensor_data(self, vehicle: VehicleState, latest_image) -> None: + os.makedirs("data", exist_ok=True) + t = int(self.vehicle_interface.time() * 1000) + cv2.imwrite(f"data/{t}_image.png", latest_image) + np.savez(f"data/{t}_lidar.npz", lidar=self.latest_lidar) + # Write BEFORE_TRANSFORM state + with open(f"data/{t}_vehstate.txt", "w") as f: + vp = vehicle.pose + f.write( + f"BEFORE_TRANSFORM " + f"x={vp.x:.3f}, y={vp.y:.3f}, z={vp.z:.3f}, " + f"yaw={vp.yaw:.2f}, pitch={vp.pitch:.2f}, roll={vp.roll:.2f}\n" + ) + # Compute start or current frame state + if self.use_start_frame: + if self.start_pose_abs is None: + self.start_pose_abs = vehicle.pose + vehicle_start_pose = vehicle.pose.to_frame( + ObjectFrameEnum.START, + vehicle.pose, + self.start_pose_abs + ) + mode = "START" + else: + vehicle_start_pose = vehicle.pose + mode = "CURRENT" + with open(f"data/{t}_vehstate.txt", "a") as f: + f.write( + f"AFTER_TRANSFORM " + f"x={vehicle_start_pose.x:.3f}, " + f"y={vehicle_start_pose.y:.3f}, " + f"z={vehicle_start_pose.z:.3f}, " + f"yaw={vehicle_start_pose.yaw:.2f}, " + f"pitch={vehicle_start_pose.pitch:.2f}, " + f"roll={vehicle_start_pose.roll:.2f}, " + f"frame={mode}\n" + ) + + +# ----- Fake Cone Detector 2D (for Testing Purposes) ----- +class FakConeDetector(Component): + def __init__(self, vehicle_interface: GEMInterface): + self.vehicle_interface = vehicle_interface + self.times = [(5.0, 20.0), (30.0, 35.0)] + self.t_start = None + + def rate(self): + return 4.0 + + def state_inputs(self): + return ['vehicle'] + + def state_outputs(self): + return ['agents'] + + def update(self, vehicle: VehicleState) -> Dict[str, AgentState]: + if self.t_start is None: + self.t_start = self.vehicle_interface.time() + t = self.vehicle_interface.time() - self.t_start + res = {} + for time_range in self.times: + if time_range[0] <= t <= time_range[1]: + res['Pedestrian0'] = box_to_fake_agent((0, 0, 0, 0)) + rospy.loginfo("Detected a Pedestrian (simulated)") + return res + + +def box_to_fake_agent(box): + x, y, w, h = box + pose = ObjectPose( + t=0, x=x + w / 2, y=y + h / 2, z=0, + yaw=0, pitch=0, roll=0, + frame=ObjectFrameEnum.CURRENT + ) + dims = (w, h, 0) + return AgentState( + pose=pose, + dimensions=dims, + outline=None, + type=AgentEnum.PEDESTRIAN, + activity=AgentActivityEnum.MOVING, + velocity=(0, 0, 0), + yaw_rate=0 + ) + + +if __name__ == '__main__': + pass diff --git a/GEMstack/onboard/perception/perception_utils.py b/GEMstack/onboard/perception/perception_utils.py index a95172d2f..3592862de 100644 --- a/GEMstack/onboard/perception/perception_utils.py +++ b/GEMstack/onboard/perception/perception_utils.py @@ -1,4 +1,3 @@ -from ...state import ObjectPose, AgentState from typing import Dict import open3d as o3d import numpy as np @@ -7,6 +6,7 @@ from sensor_msgs.msg import PointCloud2 import sensor_msgs.point_cloud2 as pc2 import ros_numpy +import math # ----- Helper Functions ----- @@ -23,37 +23,6 @@ def filter_points_within_threshold(points, threshold=15.0): mask = distances <= threshold return points[mask] -def match_existing_cone( - new_center: np.ndarray, - new_dims: tuple, - existing_agents: Dict[str, AgentState], - distance_threshold: float = 1.0 -) -> str: - """ - Find the closest existing Cone agent within a specified distance threshold. - """ - best_agent_id = None - best_dist = float('inf') - for agent_id, agent_state in existing_agents.items(): - old_center = np.array([agent_state.pose.x, agent_state.pose.y, agent_state.pose.z]) - dist = np.linalg.norm(new_center - old_center) - if dist < distance_threshold and dist < best_dist: - best_dist = dist - best_agent_id = agent_id - return best_agent_id - - -def compute_velocity(old_pose: ObjectPose, new_pose: ObjectPose, dt: float) -> tuple: - """ - Compute the (vx, vy, vz) velocity based on change in pose over time. - """ - if dt <= 0: - return (0, 0, 0) - vx = (new_pose.x - old_pose.x) / dt - vy = (new_pose.y - old_pose.y) / dt - vz = (new_pose.z - old_pose.z) / dt - return (vx, vy, vz) - def extract_roi_box(lidar_pc, center, half_extents): """ @@ -224,3 +193,27 @@ def project_points(pts_cam, K, original_lidar_points): v = (K[1, 1] * (Yc / Zc) + K[1, 2]).astype(np.int32) proj = np.column_stack((u, v, lidar_valid)) return proj + +def pose_to_matrix(pose): + """ + Compose a 4x4 transformation matrix from a pose state. + Assumes pose has attributes: x, y, z, yaw, pitch, roll, + where the angles are given in degrees. + """ + # Use default values if any are None (e.g. if the car is not moving) + x = pose.x if pose.x is not None else 0.0 + y = pose.y if pose.y is not None else 0.0 + z = pose.z if pose.z is not None else 0.0 + if pose.yaw is not None and pose.pitch is not None and pose.roll is not None: + yaw = math.radians(pose.yaw) + pitch = math.radians(pose.pitch) + roll = math.radians(pose.roll) + else: + yaw = 0.0 + pitch = 0.0 + roll = 0.0 + R_mat = R.from_euler('zyx', [yaw, pitch, roll]).as_matrix() + T = np.eye(4) + T[:3, :3] = R_mat + T[:3, 3] = np.array([x, y, z]) + return T diff --git a/GEMstack/onboard/perception/perception_utils_gem.py b/GEMstack/onboard/perception/perception_utils_gem.py new file mode 100644 index 000000000..e68e7db0c --- /dev/null +++ b/GEMstack/onboard/perception/perception_utils_gem.py @@ -0,0 +1,35 @@ +from ...state import ObjectPose, AgentState +from typing import Dict +import numpy as np +# Had to move these functions to a seperate file because they use relative imports + + +def match_existing_cone( + new_center: np.ndarray, + new_dims: tuple, + existing_agents: Dict[str, AgentState], + distance_threshold: float = 1.0 +) -> str: + """ + Find the closest existing Cone agent within a specified distance threshold. + """ + best_agent_id = None + best_dist = float('inf') + for agent_id, agent_state in existing_agents.items(): + old_center = np.array([agent_state.pose.x, agent_state.pose.y, agent_state.pose.z]) + dist = np.linalg.norm(new_center - old_center) + if dist < distance_threshold and dist < best_dist: + best_dist = dist + best_agent_id = agent_id + return best_agent_id + +def compute_velocity(old_pose: ObjectPose, new_pose: ObjectPose, dt: float) -> tuple: + """ + Compute the (vx, vy, vz) velocity based on change in pose over time. + """ + if dt <= 0: + return (0, 0, 0) + vx = (new_pose.x - old_pose.x) / dt + vy = (new_pose.y - old_pose.y) / dt + vz = (new_pose.z - old_pose.z) / dt + return (vx, vy, vz) \ No newline at end of file diff --git a/GEMstack/onboard/perception/person_detector.py b/GEMstack/onboard/perception/person_detector.py new file mode 100644 index 000000000..8f4fa3588 --- /dev/null +++ b/GEMstack/onboard/perception/person_detector.py @@ -0,0 +1,48 @@ +#from ultralytics import YOLO +import cv2 +import sys + +def person_detector(img : cv2.Mat): + #TODO: implement me to produce a list of (x,y,w,h) bounding boxes of people in the image + return [] + +def main(fn): + image = cv2.imread(fn) + bboxes = person_detector(image) + print("Detected",len(bboxes),"people") + for bb in bboxes: + x,y,w,h = bb + if not isinstance(x,(int,float)) or not isinstance(y,(int,float)) or not isinstance(w,(int,float)) or not isinstance(h,(int,float)): + print("WARNING: make sure to return Python numbers rather than PyTorch Tensors") + print("Corner",(x,y),"size",(w,h)) + cv2.rectangle(image, (int(x-w/2), int(y-h/2)), (int(x+w/2), int(y+h/2)), (255, 0, 255), 3) + cv2.imshow('Results', image) + cv2.waitKey(0) + +def main_webcam(): + cap = cv2.VideoCapture(0) + cap.set(3, 640) + cap.set(4, 480) + + print("Press space to exit") + while True: + _, image = cap.read() + + bboxes = person_detector(image) + for bb in bboxes: + x,y,w,h = bb + cv2.rectangle(image, (int(x-w/2), int(y-h/2)), (int(x+w/2), int(y+h/2)), (255, 0, 255), 3) + + cv2.imshow('Person detection', image) + if cv2.waitKey(1) & 0xFF == ord(' '): + break + + cap.release() + + +if __name__ == '__main__': + fn = sys.argv[1] + if fn != 'webcam': + main(fn) + else: + main_webcam() \ No newline at end of file diff --git a/GEMstack/onboard/perception/point_pillars_node.py b/GEMstack/onboard/perception/point_pillars_node.py new file mode 100644 index 000000000..878132b44 --- /dev/null +++ b/GEMstack/onboard/perception/point_pillars_node.py @@ -0,0 +1,221 @@ +from combined_detection_utils import add_bounding_box +import numpy as np +from scipy.spatial.transform import Rotation as R +import rospy +from sensor_msgs.msg import PointCloud2, Image +from message_filters import Subscriber, ApproximateTimeSynchronizer +from cv_bridge import CvBridge +import time +import os +import ros_numpy + +# PointPillars imports: +import torch +from pointpillars.model import PointPillars + +# Publisher imports: +from jsk_recognition_msgs.msg import BoundingBox, BoundingBoxArray +from geometry_msgs.msg import Pose, Vector3 + + +def pc2_to_numpy_with_intensity(pc2_msg, want_rgb=False): + """ + Convert a ROS PointCloud2 message into a numpy array quickly using ros_numpy. + This function extracts the x, y, z coordinates and reflecivity from the point cloud. + """ + # Convert the ROS message to a numpy structured array + pc = ros_numpy.point_cloud2.pointcloud2_to_array(pc2_msg) + reflectivity = np.array(pc['reflectivity']).ravel() + intensity = np.array(pc['intensity']).ravel() + + # Normalize reflectivity to 0-1 range + normalized_reflectivity = reflectivity / 255.0 + + # Stack x,y,z, r fields to a (N,4) array + pts = np.stack((np.array(pc['x']).ravel(), + np.array(pc['y']).ravel(), + np.array(pc['z']).ravel(), + normalized_reflectivity), + axis=1) + + # Restrict points to the model's default range: + x_min, y_min, z_min = 0, -39.68, -3 + x_max, y_max, z_max = 69.12, 39.68, 1 + + mask = ( + (pts[:, 0] >= x_min) & (pts[:, 0] <= x_max) & + (pts[:, 1] >= y_min) & (pts[:, 1] <= y_max) & + (pts[:, 2] >= z_min) & (pts[:, 2] <= z_max) + ) + return pts[mask] + + +class PointPillarsNode: + """ + Detects Pedestrians with PointPillars and publishes the results in vehicle frame. + """ + + def __init__(self): + self.latest_image = None + self.latest_lidar = None + self.bridge = CvBridge() + self.camera_name = 'front' + self.camera_front = (self.camera_name == 'front') + self.score_threshold = 0.4 + self.debug = True + self.initialize() + + def initialize(self): + """Initialize the PointPillars node with model and ROS connections.""" + # Determine the correct RGB topic for this camera + rgb_topic_map = { + 'front': '/oak/rgb/image_raw', + 'front_right': '/camera_fr/arena_camera_node/image_raw', + # add additional camera mappings here if needed + } + rgb_topic = rgb_topic_map.get( + self.camera_name, + f'/{self.camera_name}/rgb/image_raw' + ) + + # Initialize PointPillars node + rospy.init_node('pointpillars_box_publisher') + + # Create bounding box publisher + self.pub = rospy.Publisher('/pointpillars_boxes', BoundingBoxArray, queue_size=1) + rospy.loginfo("PointPillars node initialized and waiting for messages.") + + # Initialize PointPillars + device = torch.device('cuda' if torch.cuda.is_available() else 'cpu') + self.pointpillars = PointPillars( + nclasses=3, + voxel_size=[0.16, 0.16, 4], + point_cloud_range=[0, -39.68, -3, 69.12, 39.68, 1], + max_num_points=32, + max_voxels=(16000, 40000) + ) + self.pointpillars.to(device) + + # Load model weights + model_path = 'epoch_160.pth' + checkpoint = torch.load(model_path) + self.pointpillars.load_state_dict(checkpoint) + self.pointpillars.eval() + rospy.loginfo("PointPillars model loaded successfully") + + # Transformation matrix from LiDAR to vehicle frame + self.T_l2v = np.array([ + [0.99939639, 0.02547917, 0.023615, 1.1], + [-0.02530848, 0.99965156, -0.00749882, 0.03773583], + [-0.02379784, 0.00689664, 0.999693, 1.95320223], + [0., 0., 0., 1.] + ]) + + # Subscribe to the RGB and LiDAR streams + self.rgb_sub = Subscriber(rgb_topic, Image) + self.lidar_sub = Subscriber('/ouster/points', PointCloud2) + self.sync = ApproximateTimeSynchronizer( + [self.rgb_sub, self.lidar_sub], + queue_size=10, + slop=0.1 + ) + self.sync.registerCallback(self.synchronized_callback) + + def synchronized_callback(self, image_msg, lidar_msg): + """Process synchronized RGB and LiDAR messages to detect pedestrians.""" + rospy.loginfo("Received synchronized RGB and LiDAR messages") + + # Convert LiDAR message to numpy array + self.latest_lidar = pc2_to_numpy_with_intensity(lidar_msg, want_rgb=False) + + downsample = False + if downsample: + lidar_down = downsample_points(self.latest_lidar, voxel_size=0.1) + else: + lidar_down = self.latest_lidar.copy() + + # Create empty list of bounding boxes to fill + boxes = BoundingBoxArray() + boxes.header.frame_id = 'currentVehicleFrame' + boxes.header.stamp = lidar_msg.header.stamp + + with torch.no_grad(): + # Convert to tensor and format for PointPillars + lidar_tensor = torch.from_numpy(lidar_down).float() + if torch.cuda.is_available(): + lidar_tensor = lidar_tensor.cuda() + + # Format as batch with a single point cloud + batched_pts = [lidar_tensor] + + # Get PointPillars predictions + results = self.pointpillars.forward(batched_pts, mode='test') + + if results and len(results) > 0 and 'lidar_bboxes' in results[0]: + # Process PointPillars results + pp_bboxes = results[0]['lidar_bboxes'] + pp_labels = results[0]['labels'] + pp_scores = results[0]['scores'] + + for i, (bbox, label, score) in enumerate(zip(pp_bboxes, pp_labels, pp_scores)): + # Skip low confidence detections and non-pedestrians (assuming class is 0) + if (score < self.score_threshold) or (label != 0): + continue + + # Extract center position and dimensions + x, y, z, l, w, h, yaw = bbox + + # Transform from LiDAR to vehicle coordinates + center_lidar = np.array([x, y, z, 1.0]) + center_vehicle = self.T_l2v @ center_lidar + x_vehicle, y_vehicle, z_vehicle = center_vehicle[:3] + + # Transform rotation from LiDAR to vehicle frame + R_lidar = R.from_euler('z', yaw).as_matrix() + R_vehicle = self.T_l2v[:3, :3] @ R_lidar + vehicle_yaw, vehicle_pitch, vehicle_roll = R.from_matrix(R_vehicle).as_euler('zyx', degrees=False) + + # Modify bounding box so part of it is longer below ground level + bottom = z_vehicle - h / 2.0 + if bottom < 0.0: + # Cut the box at ground level: + bottom = 0.0 + top = z_vehicle + h / 2.0 + + # Or Shift the box vertically to make it sit at ground level: + # top = z_vehicle + h / 2.0 + # top = top + abs(bottom) + # bottom = 0.0 + + z_vehicle = (top - bottom) / 2.0 + h = abs(top - z_vehicle) + + # Add the bounding box + boxes = add_bounding_box( + boxes=boxes, + frame_id='currentVehicleFrame', + stamp=lidar_msg.header.stamp, + x=x_vehicle, + y=y_vehicle, + z=z_vehicle, + l=l, # length + w=w, # width + h=h, # height + yaw=vehicle_yaw, + conf_score=score, + label=label # person/pedestrian class + ) + + rospy.loginfo(f"Pedestrian detected at ({x:.2f}, {y:.2f}, {z:.2f}) with score {score:.2f}") + + # Publish the bounding boxes + rospy.loginfo(f"Publishing {len(boxes.boxes)} pedestrian bounding boxes") + self.pub.publish(boxes) + + +if __name__ == '__main__': + try: + node = PointPillarsNode() + rospy.spin() + except rospy.ROSInterruptException: + pass diff --git a/GEMstack/onboard/perception/sensorFusion/eval_3d_model_performance.py b/GEMstack/onboard/perception/sensorFusion/eval_3d_model_performance.py new file mode 100644 index 000000000..98b12e804 --- /dev/null +++ b/GEMstack/onboard/perception/sensorFusion/eval_3d_model_performance.py @@ -0,0 +1,976 @@ +import argparse +import os +import numpy as np +import matplotlib +matplotlib.use('Agg') +import matplotlib.pyplot as plt +from collections import defaultdict +import math +import warnings +import traceback +import csv + +######## Bbox coord mapping +IDX_X, IDX_Y, IDX_Z = 0, 1, 2 +IDX_L, IDX_W, IDX_H = 3, 4, 5 +IDX_YAW = 6 +IDX_CLASS = 7 +IDX_SCORE = 8 + +######## Helper Functions + +def parse_box_line(line, is_gt=False): + """ + Parses a line from a KITTI format label file. + Handles the conversion from KITTI's y-coordinate (bottom of box) + to the geometric center y used internally. + """ + parts = line.strip().split() + try: + # Parse KITTI format: + # type truncated occluded alpha bbox_2d(4) dims(3) loc(3) rotation_y (score) + # 0 1 2 3 4-7 8-10 11-13 14 (15) + + # Check minimum length for standard KITTI format (15 fields without score) + if len(parts) < 15: + raise ValueError(f"Line does not have enough parts for KITTI format (expected >= 15, got {len(parts)})") + + class_label = parts[0] + + # Read dimensions (h, w, l) from KITTI standard indices 8, 9, 10 + h = float(parts[8]) + w = float(parts[9]) + l = float(parts[10]) + + # Read location (x, y_bottom, z) from KITTI standard indices 11, 12, 13 + loc_x = float(parts[11]) + loc_y_bottom = float(parts[12]) # KITTI 'y' is bottom of the box in camera coords + loc_z = float(parts[13]) + + # Read rotation_y (yaw) from KITTI standard index 14 + rot_y = float(parts[14]) + + # Convert to internal format + # Internal format: [cx, cy, cz, l, w, h, yaw, class_label, score] + + # Use KITTI loc_x and loc_z directly for internal cx, cz + cx = loc_x + cz = loc_z + + # Convert KITTI y (bottom of box) to geometric center y for internal use. + # In KITTI camera coords, Y points down, so center is 'above' bottom (numerically smaller y): loc_y - h / 2 + cy = loc_y_bottom - (h / 2.0) + + # Use KITTI rot_y directly for internal yaw + yaw = rot_y + + # Create the standardized box list [cx, cy, cz, l, w, h, yaw, class_label] + # Note the internal dimension order (l, w, h) differs from KITTI input order (h, w, l) + box = [cx, cy, cz, l, w, h, yaw, class_label] + + # Append score if it's a prediction file (standard KITTI index 15) + if not is_gt: + if len(parts) > 15: + score = float(parts[15]) + else: + # Handle missing score in prediction file if needed + score = 1.0 # Assigning default 1.0 as before + warnings.warn(f"[LOG] Prediction line missing score (field 16), assigning default 1.0: {line.strip()}") + box.append(score) # Append score using IDX_SCORE implicitly + + return box + + except ValueError as ve: + print(f"[LOG] Error parsing line: '{line.strip()}' - {ve}") + print("[LOG] Does input follows KITTI format ?") + return None + except Exception as e: + print(f"[LOG] Unexpected error parsing line: '{line.strip()}' - {e}") + traceback.print_exc() # Print detailed traceback for unexpected errors + return None + + +def load_labels(file_path, is_gt=False): + """Loads ground truth or prediction boxes from a KITTI-format file.""" + boxes = defaultdict(list) + if not os.path.exists(file_path): + # Reduced verbosity for missing prediction files (common) + # print(f"[LOG] File not found {file_path}, returning empty dict.") + return boxes + try: + with open(file_path, 'r') as f: + for i, line in enumerate(f): + box = parse_box_line(line, is_gt=is_gt) + if box: + class_label = box[IDX_CLASS] + boxes[class_label].append(box) + else: + print(f"[LOG] Skipping invalid line {i+1} in {file_path}") + except Exception as e: + print(f"[LOG] Error reading file {file_path}: {e}") + traceback.print_exc() + return boxes + +def get_aabb_corners(box): + # Uses internal format where cy is geometric center + cx, cy, cz, l, w, h = box[IDX_X], box[IDX_Y], box[IDX_Z], box[IDX_L], box[IDX_W], box[IDX_H] + # Ignores yaw + min_x, max_x = cx - l / 2, cx + l / 2 + min_y, max_y = cy - h / 2, cy + h / 2 # Uses geometric center cy + min_z, max_z = cz - w / 2, cz + w / 2 # Assuming cz is center z (depth) + return min_x, max_x, min_y, max_y, min_z, max_z + +def get_volume(box): + return box[IDX_L] * box[IDX_W] * box[IDX_H] + +def calculate_3d_iou(box1, box2, get_corners_cb, get_volume_cb): + """ + Calculates the 3D Intersection over Union (IoU) between two bounding boxes. + + Args: + box1, box2: List or tuple representing a 3D bounding box in the + *internal standardized format*: [cx, cy, cz, l, w, h, yaw, ...] + where cy is the geometric center y. + get_corners_cb: Callback function to extract AABB corners from a box + get_volume_cb: Callback function to calculate volume of a box + + Returns: + float: The 3D IoU value. + + Doesn't consider yaw + """ + + ######### Simple Axis-Aligned Bounding Box (AABB) IoU# + min_x1, max_x1, min_y1, max_y1, min_z1, max_z1 = get_corners_cb(box1) + min_x2, max_x2, min_y2, max_y2, min_z2, max_z2 = get_corners_cb(box2) + + # Calculate intersection volume + inter_min_x = max(min_x1, min_x2) + inter_max_x = min(max_x1, max_x2) + inter_min_y = max(min_y1, min_y2) + inter_max_y = min(max_y1, max_y2) + inter_min_z = max(min_z1, min_z2) + inter_max_z = min(max_z1, max_z2) + + inter_l = max(0, inter_max_x - inter_min_x) + inter_h = max(0, inter_max_y - inter_min_y) + inter_w = max(0, inter_max_z - inter_min_z) + intersection_volume = inter_l * inter_h * inter_w + + # Calculate union volume + vol1 = get_volume_cb(box1) + vol2 = get_volume_cb(box2) + # Ensure volumes are positive and non-zero for stable IoU + vol1 = max(vol1, 1e-6) + vol2 = max(vol2, 1e-6) + union_volume = vol1 + vol2 - intersection_volume + union_volume = max(union_volume, 1e-6) # Avoid division by zero or very small numbers + + iou = intersection_volume / union_volume + # Clamp IoU to [0, 1] range + iou = max(0.0, min(iou, 1.0)) + return iou + + +def calculate_ap(precision, recall): + """Calculates Average Precision using the PASCAL VOC method (area under monotonic PR curve).""" + # Convert to numpy arrays first for safety + if not isinstance(precision, (list, np.ndarray)) or not isinstance(recall, (list, np.ndarray)): + return 0.0 + precision = np.array(precision) + recall = np.array(recall) + + if precision.size == 0 or recall.size == 0: + return 0.0 + + # Prepend/Append points for interpolation boundaries + recall = np.concatenate(([0.], recall, [1.0])) + precision = np.concatenate(([0.], precision, [0.])) # Start with 0 precision at recall 0, end with 0 at recall 1 + + # Make precision monotonically decreasing (handles PR curve 'jiggles') + for i in range(len(precision) - 2, -1, -1): + precision[i] = max(precision[i], precision[i+1]) + + # Find indices where recall changes (avoids redundant calculations) + indices = np.where(recall[1:] != recall[:-1])[0] + 1 + + # Compute AP using the area under the curve (sum of rectangle areas) + ap = np.sum((recall[indices] - recall[indices-1]) * precision[indices]) + return ap + +def evaluate_detector(gt_boxes_all_samples, pred_boxes_all_samples, classes, iou_threshold, confidence_thresholds=None): + """Evaluates a single detector's predictions against ground truth. + + Args: + gt_boxes_all_samples: Ground truth boxes dictionary by sample_id and class + pred_boxes_all_samples: Prediction boxes dictionary by sample_id and class + classes: List of classes to evaluate + iou_threshold: IoU threshold for matching predictions to ground truth + confidence_thresholds: List of confidence thresholds to use for evaluation + If None, uses [0.0] (all predictions) + + Returns: + Dictionary of results by class + """ + # Default to single threshold that includes all predictions + if confidence_thresholds is None: + confidence_thresholds = [0.0] + + results_by_class = {} + sample_ids = list(gt_boxes_all_samples.keys()) # Get fixed order of sample IDs + + for cls in classes: + all_pred_boxes_cls = [] + num_gt_cls = 0 + pred_sample_indices = [] # Store index from sample_ids for each prediction + pred_scores = [] # Store confidence scores for each prediction + + # Collect all GTs and Preds for this class across samples + for i, sample_id in enumerate(sample_ids): + # Use .get() with default empty dict/list for safety + gt_boxes = gt_boxes_all_samples.get(sample_id, {}).get(cls, []) + pred_boxes = pred_boxes_all_samples.get(sample_id, {}).get(cls, []) + + num_gt_cls += len(gt_boxes) + for box in pred_boxes: + all_pred_boxes_cls.append(box) + pred_sample_indices.append(i) # Store the original sample index + # Extract score safely + if len(box) > IDX_SCORE and isinstance(box[IDX_SCORE], (int, float)): + pred_scores.append(box[IDX_SCORE]) + else: + pred_scores.append(0.0) # Default score if missing + + if not all_pred_boxes_cls: # Handle case with no predictions for this class + results_by_class[cls] = { + 'precision': np.array([]), # Use empty numpy arrays + 'recall': np.array([]), + 'ap': 0.0, + 'num_gt': num_gt_cls, + 'num_pred': 0, + 'confusion_matrix': {}, # Empty confusion matrix + 'thresholds': confidence_thresholds + } + continue # Skip to next class + + # Sort all predictions by score (descending) + sorted_indices = np.argsort(pred_scores)[::-1] + + # Reorder the lists based on sorted scores + all_pred_boxes_cls = [all_pred_boxes_cls[i] for i in sorted_indices] + pred_sample_indices = [pred_sample_indices[i] for i in sorted_indices] + pred_scores = [pred_scores[i] for i in sorted_indices] + + # Store results for each confidence threshold + threshold_results = {} + + # For each confidence threshold + for threshold in confidence_thresholds: + # Filter predictions above threshold + threshold_indices = [i for i, score in enumerate(pred_scores) if score >= threshold] + if not threshold_indices: + # No predictions above this threshold + threshold_results[threshold] = { + 'precision': np.array([]), + 'recall': np.array([]), + 'ap': 0.0, + 'tp': np.array([]), + 'fp': np.array([]), + 'tn': 0, # TN doesn't apply directly to object detection (no explicit negatives) + 'fn': num_gt_cls, # All GT boxes are missed + 'confusion_matrix': { + 'TP': 0, + 'FP': 0, + 'FN': num_gt_cls, + 'TN': 0 # Included for completeness + } + } + continue + + # Get predictions above this threshold + filtered_pred_boxes = [all_pred_boxes_cls[i] for i in threshold_indices] + filtered_sample_indices = [pred_sample_indices[i] for i in threshold_indices] + filtered_scores = [pred_scores[i] for i in threshold_indices] + + tp = np.zeros(len(filtered_pred_boxes)) + fp = np.zeros(len(filtered_pred_boxes)) + # Track matched GTs per sample: gt_matched[sample_idx][gt_box_idx] = True/False + gt_matched = defaultdict(lambda: defaultdict(bool)) # Indexed by sample_idx, then gt_idx + + # Match predictions + for det_idx, pred_box in enumerate(filtered_pred_boxes): + sample_idx = filtered_sample_indices[det_idx] + sample_id = sample_ids[sample_idx] + gt_boxes = gt_boxes_all_samples.get(sample_id, {}).get(cls, []) + + best_iou = -1.0 + best_gt_idx = -1 + + if not gt_boxes: # No GT for this class in this specific sample + fp[det_idx] = 1 + continue + + for gt_idx, gt_box in enumerate(gt_boxes): + # Explicitly check class match (belt-and-suspenders) + if pred_box[IDX_CLASS] == gt_box[IDX_CLASS]: + iou = calculate_3d_iou(pred_box, gt_box, get_aabb_corners, get_volume) + if iou > best_iou: + best_iou = iou + best_gt_idx = gt_idx + + if best_iou >= iou_threshold: + # Check if this GT box was already matched *in this sample* + if not gt_matched[sample_idx].get(best_gt_idx, False): + tp[det_idx] = 1 + gt_matched[sample_idx][best_gt_idx] = True # Mark as matched + else: + fp[det_idx] = 1 # Already matched by higher-scored prediction + else: + fp[det_idx] = 1 # No match with sufficient IoU + + # Calculate confusion matrix metrics + total_tp = int(np.sum(tp)) + total_fp = int(np.sum(fp)) + + # Count false negatives (GT boxes that weren't matched) + total_fn = num_gt_cls - sum(len(matched) for matched in gt_matched.values()) + # True negatives don't apply well to object detection, but included for completeness + total_tn = 0 # Placeholder + + # Calculate precision/recall + fp_cumsum = np.cumsum(fp) + tp_cumsum = np.cumsum(tp) + + # Avoid division by zero if num_gt_cls is 0 + recall = tp_cumsum / num_gt_cls if num_gt_cls > 0 else np.zeros_like(tp_cumsum, dtype=float) + + # Avoid division by zero if no predictions were made or matched (tp + fp = 0) + denominator = tp_cumsum + fp_cumsum + precision = np.divide(tp_cumsum, denominator, out=np.zeros_like(tp_cumsum, dtype=float), where=denominator!=0) + + ap = calculate_ap(precision, recall) + + # Store results for this threshold + threshold_results[threshold] = { + 'precision': precision, + 'recall': recall, + 'ap': ap, + 'tp': tp, + 'fp': fp, + 'fn': total_fn, + 'tn': total_tn, + 'confusion_matrix': { + 'TP': total_tp, + 'FP': total_fp, + 'FN': total_fn, + 'TN': total_tn + }, + 'scores': filtered_scores + } + + # Find best AP score across thresholds + best_threshold = max(threshold_results.keys(), + key=lambda t: threshold_results[t]['ap'] if not np.isnan(threshold_results[t]['ap']) else 0.0) + best_result = threshold_results[best_threshold] + + # Store overall results for this class + results_by_class[cls] = { + 'precision': best_result['precision'], + 'recall': best_result['recall'], + 'ap': best_result['ap'], + 'num_gt': num_gt_cls, + 'num_pred': len(all_pred_boxes_cls), + 'best_threshold': best_threshold, + 'thresholds': confidence_thresholds, + 'threshold_results': threshold_results, + 'confusion_matrix': best_result['confusion_matrix'] + } + + return results_by_class + + +def plot_pr_curves(results_all_detectors, classes, output_dir): + """ + Plots Precision-Recall curves for each class. + + Creates: + 1. Overall PR curves comparing all detectors at their best threshold + 2. PR curves for each detector showing performance at different confidence thresholds + """ + if not os.path.exists(output_dir): + try: + os.makedirs(output_dir) + except OSError as e: + print(f"[LOG] Error creating output directory {output_dir} for plots: {e}") + return # Cannot save plots + + pr_curves_dir = os.path.join(output_dir, 'pr_curves') + if not os.path.exists(pr_curves_dir): + try: + os.makedirs(pr_curves_dir) + except OSError as e: + print(f"[LOG] Error creating PR curves directory {pr_curves_dir}: {e}") + return + + detector_names = list(results_all_detectors.keys()) + + # Overall PR curves comparing detectors + for cls in classes: + plt.figure(figsize=(10, 7)) + any_results_for_class = False # Track if any detector had results for this class + + for detector_name, results_by_class in results_all_detectors.items(): + if cls in results_by_class and results_by_class[cls]['num_pred'] > 0: # Check if there were predictions + res = results_by_class[cls] + precision = res['precision'] + recall = res['recall'] + ap = res['ap'] + best_threshold = res.get('best_threshold', 0.0) + + # Ensure plotting works even if precision/recall are empty arrays + if recall.size > 0 and precision.size > 0: + # Prepend a point for plotting nicely from recall=0 + plot_recall = np.concatenate(([0.], recall)) + # Use precision[0] if available, else 0. + plot_precision = np.concatenate(([precision[0] if precision.size > 0 else 0.], precision)) + plt.plot(plot_recall, plot_precision, marker='.', markersize=4, linestyle='-', + label=f'{detector_name} (AP={ap:.3f}, t={best_threshold:.2f})') + any_results_for_class = True + else: # Handle case where num_pred > 0 but P/R arrays somehow ended up empty + plt.plot([0], [0], marker='s', markersize=5, linestyle='', + label=f'{detector_name} (AP={ap:.3f}, No P/R data?)') + any_results_for_class = True # Still mark as having results + + elif cls in results_by_class: # Class exists in evaluation, but no predictions were made for it + num_gt = results_by_class[cls]['num_gt'] + if num_gt > 0: + # Plot a marker indicating no predictions were made for this GT class + plt.plot([0], [0], marker='x', markersize=6, linestyle='', + label=f'{detector_name} (No Pred, GT={num_gt})') + + if any_results_for_class: + plt.xlabel('Recall') + plt.ylabel('Precision') + plt.title(f'Precision-Recall Curve for Class: {cls}') + plt.legend(loc='lower left', fontsize='small') + plt.grid(True) + plt.xlim([-0.05, 1.05]) + plt.ylim([-0.05, 1.05]) + plot_path = os.path.join(pr_curves_dir, f'pr_curve_{cls}_overview.png') + try: + plt.savefig(plot_path) + print(f"[LOG] Generated PR curve overview: {plot_path}") + except Exception as e: + print(f"[LOG] Error saving PR curve plot for class '{cls}': {e}") + finally: + plt.close() # Close the figure regardless of save success + else: + # Check if there was any GT data for this class across all detectors + num_gt_total = sum(results_by_class.get(cls, {}).get('num_gt', 0) for results_by_class in results_all_detectors.values()) + if num_gt_total > 0: + print(f" Skipping PR plot for class '{cls}': No predictions found across detectors (GT={num_gt_total}).") + else: + print(f" Skipping PR plot for class '{cls}': No ground truth found.") + plt.close() # Close the empty figure + + # Plots showing PR curves at different thresholds for each detector and class + for detector_name, results_by_class in results_all_detectors.items(): + detector_dir = os.path.join(pr_curves_dir, detector_name) + if not os.path.exists(detector_dir): + try: + os.makedirs(detector_dir) + except OSError as e: + print(f"[LOG] Error creating directory for {detector_name}: {e}") + continue + + for cls in classes: + if cls not in results_by_class or results_by_class[cls]['num_pred'] == 0: + continue + + res = results_by_class[cls] + threshold_results = res.get('threshold_results', {}) + + if not threshold_results: + continue + + plt.figure(figsize=(10, 7)) + + # Plot PR curve for each threshold + thresholds = sorted(threshold_results.keys()) + for threshold in thresholds: + threshold_res = threshold_results[threshold] + + # Skip thresholds with no predictions + if 'precision' not in threshold_res or len(threshold_res['precision']) == 0: + continue + + precision = threshold_res['precision'] + recall = threshold_res['recall'] + ap = threshold_res['ap'] + + # Get TP/FP counts for label + cm = threshold_res.get('confusion_matrix', {}) + tp = cm.get('TP', 0) + fp = cm.get('FP', 0) + + # Mark best threshold with a different line style + is_best = threshold == res.get('best_threshold', 0.0) + linestyle = '-' if is_best else '--' + linewidth = 2 if is_best else 1 + + # Prepend points for better visualization + plot_recall = np.concatenate(([0.], recall)) + plot_precision = np.concatenate(([precision[0] if precision.size > 0 else 0.], precision)) + + plt.plot(plot_recall, plot_precision, marker='.', markersize=3, + linestyle=linestyle, linewidth=linewidth, + label=f'thresh={threshold:.2f} (AP={ap:.3f}, TP={tp}, FP={fp})') + + plt.xlabel('Recall') + plt.ylabel('Precision') + plt.title(f'{detector_name}: PR Curves at Different Thresholds for {cls}') + plt.legend(loc='lower left', fontsize='small') + plt.grid(True) + plt.xlim([-0.05, 1.05]) + plt.ylim([-0.05, 1.05]) + + plot_path = os.path.join(detector_dir, f'pr_curve_{cls}_thresholds.png') + try: + plt.savefig(plot_path) + print(f"[LOG] Generated threshold PR curves for {detector_name}/{cls}: {plot_path}") + except Exception as e: + print(f"[LOG] Error saving threshold PR curves for {detector_name}/{cls}: {e}") + finally: + plt.close() + +def export_confusion_matrix(results_all_detectors, output_dir, classes): + """ + Exports confusion matrix metrics for all detectors and classes to CSV files. + + Args: + results_all_detectors: Dictionary of results by detector and class + output_dir: Directory to save results + classes: List of classes to evaluate + """ + confusion_dir = os.path.join(output_dir, 'confusion_matrices') + if not os.path.exists(confusion_dir): + os.makedirs(confusion_dir) + + # Create a summary file for all detectors + summary_path = os.path.join(confusion_dir, 'confusion_matrix_summary.csv') + with open(summary_path, 'w', newline='') as f: + writer = csv.writer(f) + # Write header + writer.writerow(['Detector', 'Class', 'Threshold', 'TP', 'FP', 'FN', 'TN', 'Precision', 'Recall', 'AP']) + + # Write data for each detector, class, and threshold + for detector_name, results_by_class in results_all_detectors.items(): + for cls in classes: + if cls in results_by_class: + cls_results = results_by_class[cls] + best_threshold = cls_results.get('best_threshold', 0.0) + threshold_results = cls_results.get('threshold_results', {}) + + for threshold, result in threshold_results.items(): + # Skip if no predictions at this threshold + if 'confusion_matrix' not in result: + continue + + cm = result['confusion_matrix'] + tp = cm['TP'] + fp = cm['FP'] + fn = cm['FN'] + tn = cm['TN'] + + # Calculate precision and recall + precision = tp / (tp + fp) if (tp + fp) > 0 else 0 + recall = tp / (tp + fn) if (tp + fn) > 0 else 0 + + # Write row + is_best = '* ' if threshold == best_threshold else '' + writer.writerow([ + detector_name, + cls, + f"{is_best}{threshold:.3f}", + tp, + fp, + fn, + tn, + f"{precision:.4f}", + f"{recall:.4f}", + f"{result['ap']:.4f}" + ]) + + print(f"[LOG] Confusion matrix metrics saved to: {summary_path}") + + # Create detailed files for each detector with per-threshold metrics + for detector_name, results_by_class in results_all_detectors.items(): + detector_file = os.path.join(confusion_dir, f'{detector_name}_detailed.csv') + with open(detector_file, 'w', newline='') as f: + writer = csv.writer(f) + writer.writerow(['Class', 'Threshold', 'TP', 'FP', 'FN', 'TN', 'Precision', 'Recall', 'AP']) + + for cls in classes: + if cls in results_by_class: + cls_results = results_by_class[cls] + threshold_results = cls_results.get('threshold_results', {}) + + # Sort thresholds for better readability + thresholds = sorted(threshold_results.keys()) + + for threshold in thresholds: + result = threshold_results[threshold] + if 'confusion_matrix' not in result: + continue + + cm = result['confusion_matrix'] + precision = cm['TP'] / (cm['TP'] + cm['FP']) if (cm['TP'] + cm['FP']) > 0 else 0 + recall = cm['TP'] / (cm['TP'] + cm['FN']) if (cm['TP'] + cm['FN']) > 0 else 0 + + writer.writerow([ + cls, + f"{threshold:.3f}", + cm['TP'], + cm['FP'], + cm['FN'], + cm['TN'], + f"{precision:.4f}", + f"{recall:.4f}", + f"{result['ap']:.4f}" + ]) + + print(f"[LOG] Detailed metrics for {detector_name} saved to: {detector_file}") + +def main(): + parser = argparse.ArgumentParser(description='Evaluate N 3D Object Detectors using KITTI format labels.') + parser.add_argument('gt_dir', type=str, help='Directory containing ground truth label files (KITTI format).') + parser.add_argument('pred_dirs', type=str, nargs='+', help='List of directories containing prediction files (KITTI format).') + parser.add_argument('output_dir', type=str, help='Directory to save evaluation results.') + parser.add_argument('--detector_names', type=str, nargs='*', help='Optional names for the detectors (corresponding to pred_dirs). If not provided, uses directory names.') + parser.add_argument('--iou_threshold', type=float, default=0.5, help='3D IoU threshold for matching (default: 0.5). KITTI examples: 0.5 (Car Easy/Mod), 0.7 (Car Hard), 0.5 (Ped/Cyc Easy/Mod), 0.5 (Ped/Cyc Hard).') + parser.add_argument('--classes', type=str, nargs='*', default=['Car', 'Pedestrian', 'Cyclist'], help='List of classes to evaluate (default: KITTI common classes). Case sensitive.') + parser.add_argument('--file_extension', type=str, default='.txt', help='Extension of the label files (default: .txt).') + parser.add_argument('--confidence_thresholds', type=float, nargs='*', default=[0.0, 0.1, 0.2, 0.3, 0.4, 0.5, 0.6, 0.7, 0.8, 0.9], + help='Confidence thresholds for evaluation (default: 0.0-0.9 in 0.1 increments).') + + args = parser.parse_args() + + ######## Argument Validation and Setup + if not os.path.isdir(args.gt_dir): + print(f"[LOG] Error: Ground truth directory not found: {args.gt_dir}") + return + # Check prediction directories *before* loading GT + valid_pred_dirs = [] + original_detector_names = args.detector_names if args.detector_names else [os.path.basename(d.rstrip('/\\')) for d in args.pred_dirs] + final_detector_names = [] + pred_dir_map = {} # Map name back to directory path + + for i, d in enumerate(args.pred_dirs): + detector_name = original_detector_names[i] + if not os.path.isdir(d): + print(f"[LOG] Prediction directory not found: {d}. Skipping detector '{detector_name}'.") + else: + valid_pred_dirs.append(d) + final_detector_names.append(detector_name) + pred_dir_map[detector_name] = d + + if not valid_pred_dirs: + print("[LOG] Error: No valid prediction directories provided.") + return + + # Ensure output directory exists + try: + if not os.path.exists(args.output_dir): + os.makedirs(args.output_dir) + print(f"[LOG] Created output directory: {args.output_dir}") + except OSError as e: + print(f"[LOG] Error creating output directory {args.output_dir}: {e}") + return + + print("[LOG] Configuration") + print(f"Ground Truth Dir: {args.gt_dir}") + print(f"Prediction Dirs: {valid_pred_dirs}") # Show only valid dirs being used + print(f"Detector Names: {final_detector_names}") # Show corresponding names + print(f"Output Dir: {args.output_dir}") + print(f"IoU Threshold: {args.iou_threshold}") + print(f"Classes: {args.classes}") + print(f"File Extension: {args.file_extension}") + print(f"Confidence Thresholds: {args.confidence_thresholds}") + print("=====================\n") + + ######## Load Data + print("[LOG] Loading data...") + try: + gt_files = sorted([f for f in os.listdir(args.gt_dir) if f.endswith(args.file_extension)]) + if not gt_files: + print(f"[LOG] No ground truth files found in {args.gt_dir} with extension {args.file_extension}. Cannot evaluate.") + return + + print(f"Found {len(gt_files)} ground truth files.") + gt_boxes_all_samples = {} # {sample_id: {class: [boxes]}} + # Load GT data first + print("Loading Ground Truth...") + for filename in gt_files: + sample_id = os.path.splitext(filename)[0] + gt_file_path = os.path.join(args.gt_dir, filename) + gt_boxes_all_samples[sample_id] = load_labels(gt_file_path, is_gt=True) + print("Ground Truth loaded.") + + # Load prediction data for valid detectors + pred_boxes_all_detectors = {} # {detector_name: {sample_id: {class: [boxes]}}} + print("Loading Predictions...") + for detector_name in final_detector_names: + pred_dir = pred_dir_map[detector_name] # Get path from map + print(f" Loading from {detector_name} ({pred_dir})...") + pred_boxes_all_detectors[detector_name] = {} + files_found_count = 0 + for filename in gt_files: # Iterate based on GT files for consistency + sample_id = os.path.splitext(filename)[0] + pred_file_path = os.path.join(pred_dir, filename) + # load_labels handles non-existent files, returns empty dict + pred_boxes_all_detectors[detector_name][sample_id] = load_labels(pred_file_path, is_gt=False) + if os.path.exists(pred_file_path): + files_found_count += 1 + print(f" Found {files_found_count} matching prediction files for {detector_name}.") + print("Predictions loaded.") + + print(f"\n[LOG] Loaded data for {len(gt_files)} samples and {len(final_detector_names)} detector(s).\n") + + except Exception as e: + print(f"[LOG] Error during data loading: {e}") + traceback.print_exc() + return + + ######## Evaluation + print("[LOG] Evaluating detectors...") + results_all_detectors = {} # {detector_name: {class: {'ap':, 'p':, 'r':, 'gt':, 'pred':}}} + try: + for detector_name in final_detector_names: # Use the filtered list of names + print(f" Evaluating: {detector_name}") + # Check if prediction data was actually loaded for this detector + if detector_name not in pred_boxes_all_detectors: + print(f" [LOG] Skipping {detector_name} - No prediction data loaded (check LOG)") + results_all_detectors[detector_name] = {} # Store empty results + continue + + pred_boxes_all_samples = pred_boxes_all_detectors[detector_name] + + if not gt_boxes_all_samples: # Redundant check, but safe + print(f" Skipping {detector_name} - No ground truth data loaded.") + results_all_detectors[detector_name] = {} + continue + + # Perform evaluation + results_by_class = evaluate_detector( + gt_boxes_all_samples, + pred_boxes_all_samples, + args.classes, # Pass the user-specified classes + args.iou_threshold, + args.confidence_thresholds + ) + results_all_detectors[detector_name] = results_by_class + print("[LOG] Evaluation complete.\n") + except Exception as e: + print(f"[LOG] Error during evaluation: {e}") + traceback.print_exc() + return # Stop execution on evaluation error + + + ######## Report Results & Save + print("[LOG] Results") + results_file_path = os.path.join(args.output_dir, 'evaluation_metrics.txt') + + try: + with open(results_file_path, 'w') as f: + f.write(f"Evaluation Results (IoU Threshold: {args.iou_threshold})\n") + f.write(f"Evaluated Classes: {', '.join(args.classes)}\n") + f.write(f"Confidence Thresholds: {args.confidence_thresholds}\n") + f.write("="*60 + "\n") + + overall_mAPs = {} # Store mAP for each detector {detector_name: mAP_value} + + # Process results for each detector that was evaluated + for detector_name in final_detector_names: + # Check if results exist for this detector (might be skipped if loading failed) + if detector_name not in results_all_detectors: + print(f"\nDetector: {detector_name} (SKIPPED - No results)") + f.write(f"\nDetector: {detector_name} (SKIPPED - No results)\n") + continue # Skip to the next detector + + results_by_class = results_all_detectors[detector_name] + print(f"\nDetector: {detector_name}") + f.write(f"\nDetector: {detector_name}\n") + f.write(f"{'Class':<15} | {'AP':<10} | {'Num GT':<10} | {'Num Pred':<10} | {'Best Thresh':<11} | {'TP':<5} | {'FP':<5} | {'FN':<5}\n") + f.write("-" * 85 + "\n") + + detector_aps = [] # AP values for classes with GT > 0 for this detector + evaluated_classes_with_gt = [] # Class names with GT > 0 for this detector + + # Iterate through the classes specified by the user for consistent reporting + for cls in args.classes: + # Check if GT data exists for this class across all samples + num_gt_total_for_class = sum(len(gt_boxes.get(cls, [])) for gt_boxes in gt_boxes_all_samples.values()) + + if cls in results_by_class: + # Results exist for this class and detector + res = results_by_class[cls] + ap = res['ap'] + num_gt = res['num_gt'] # Should match num_gt_total_for_class if evaluated correctly + num_pred = res['num_pred'] # Number of valid predictions for this class + best_threshold = res.get('best_threshold', 0.0) + + # Get confusion matrix from best threshold + cm = res.get('confusion_matrix', {}) + tp = cm.get('TP', 0) + fp = cm.get('FP', 0) + fn = cm.get('FN', 0) + + print(f"{cls:<15} | {ap:<10.4f} | {num_gt:<10} | {num_pred:<10} | {best_threshold:<11.3f} | {tp:<5} | {fp:<5} | {fn:<5}") + f.write(f"{cls:<15} | {ap:<10.4f} | {num_gt:<10} | {num_pred:<10} | {best_threshold:<11.3f} | {tp:<5} | {fp:<5} | {fn:<5}\n") + + # Include in mAP calculation only if there were GT boxes for this class + if num_gt > 0: + detector_aps.append(ap) + evaluated_classes_with_gt.append(cls) + # If num_gt is 0 for a class, its AP is 0 or NaN, not included in mAP. + else: + # No results entry for this class, implies 0 valid predictions processed. + # Report AP as 0.0000 if GT existed, otherwise N/A. + print(f"{cls:<15} | {'0.0000' if num_gt_total_for_class > 0 else 'N/A':<10} | {num_gt_total_for_class:<10} | {'0':<10} | {'N/A':<11} | {'0':<5} | {'0':<5} | {num_gt_total_for_class:<5}") + f.write(f"{cls:<15} | {'0.0000' if num_gt_total_for_class > 0 else 'N/A':<10} | {num_gt_total_for_class:<10} | {'0':<10} | {'N/A':<11} | {'0':<5} | {'0':<5} | {num_gt_total_for_class:<5}\n") + # If GT existed, this class contributes 0 to the mAP average. + if num_gt_total_for_class > 0: + detector_aps.append(0.0) + evaluated_classes_with_gt.append(cls) + + # Calculate and report mAP for this detector based on evaluated classes with GT + if detector_aps: # Check if list is not empty + mAP = np.mean(detector_aps) + overall_mAPs[detector_name] = mAP + # Report which classes contributed to the mAP + mAP_info = f"(Classes w/ GT: {', '.join(evaluated_classes_with_gt)})" if evaluated_classes_with_gt else "" + print("-" * 85) + print(f"{'mAP':<15} | {mAP:<10.4f} {mAP_info}") + f.write("-" * 85 + "\n") + f.write(f"{'mAP':<15} | {mAP:<10.4f} {mAP_info}\n") + + # Add confusion matrix section for this detector + f.write("\nConfusion Matrix Summary (at best threshold per class):\n") + f.write(f"{'Class':<15} | {'Threshold':<10} | {'TP':<5} | {'FP':<5} | {'FN':<5} | {'Precision':<10} | {'Recall':<10}\n") + f.write("-" * 75 + "\n") + + for cls in evaluated_classes_with_gt: + if cls in results_by_class: + res = results_by_class[cls] + best_thresh = res.get('best_threshold', 0.0) + cm = res.get('confusion_matrix', {}) + + tp = cm.get('TP', 0) + fp = cm.get('FP', 0) + fn = cm.get('FN', 0) + + precision = tp / (tp + fp) if (tp + fp) > 0 else 0 + recall = tp / (tp + fn) if (tp + fn) > 0 else 0 + + f.write(f"{cls:<15} | {best_thresh:<10.3f} | {tp:<5} | {fp:<5} | {fn:<5} | {precision:<10.4f} | {recall:<10.4f}\n") + + else: + overall_mAPs[detector_name] = np.nan # Indicate mAP couldn't be computed + print("-" * 85) + print(f"{'mAP':<15} | {'N/A (No GT in evaluated classes)':<10}") + f.write("-" * 85 + "\n") + f.write(f"{'mAP':<15} | {'N/A (No GT in evaluated classes)':<10}\n") + + + ######## Overall Comparison Table + # Check if there are results to compare + if len(final_detector_names) > 0 and results_all_detectors: + print("\n[LOG] Overall Class AP Comparison") + f.write("\n" + "="*60 + "\n") + f.write("Overall Class AP Comparison\n") + f.write("="*60 + "\n") + # Truncate long detector names for table header + header_names = [name[:12] for name in final_detector_names] # Limit name length + header = f"{'Class':<15}" + "".join([f" | {name:<12}" for name in header_names]) + print(header) + f.write(header + "\n") + print("-" * len(header)) + f.write("-" * len(header) + "\n") + + # Iterate through user-specified classes for the table rows + for cls in args.classes: + aps_str = "" + num_gt_total_for_class = sum(len(gt_boxes.get(cls, [])) for gt_boxes in gt_boxes_all_samples.values()) + + # Get AP for each detector for this class + for detector_name in final_detector_names: + # Retrieve AP using .get chains safely + ap_val = results_all_detectors.get(detector_name, {}).get(cls, {}).get('ap', np.nan) + + # Decide display value based on AP and total GT count + if np.isnan(ap_val): + # Show 0.0000 if GT existed, else N/A + display_val = f"{0.0:<12.4f}" if num_gt_total_for_class > 0 else f"{'N/A':<12}" + else: + # Format valid AP value + display_val = f"{ap_val:<12.4f}" + aps_str += f" | {display_val}" + + line = f"{cls:<15}" + aps_str + print(line) + f.write(line + "\n") + + ######## Overall mAP Comparison + print("-" * len(header)) + f.write("-" * len(header) + "\n") + map_str = "" + for detector_name in final_detector_names: + map_val = overall_mAPs.get(detector_name, np.nan) # Get calculated mAP + map_str += f" | {map_val:<12.4f}" if not np.isnan(map_val) else f" | {'N/A':<12}" + map_line = f"{'mAP':<15}" + map_str + print(map_line) + f.write(map_line + "\n") + else: + print("\n[LOG] Skipping overall comparison table - no results available.") + f.write("\n[LOG] Skipping overall comparison table - no results available.\n") + + print(f"\nMetrics saved to: {results_file_path}") + + except Exception as e: + print(f"[LOG] Error during results reporting/saving: {e}") + traceback.print_exc() + # Plot + # return # Or stop + + ########## Export Confusion Matrix CSV + try: + export_confusion_matrix(results_all_detectors, args.output_dir, args.classes) + except Exception as e: + print(f"[LOG] Error exporting confusion matrix: {e}") + traceback.print_exc() + + ########## Plotting + print("\n[LOG] Generating PR curves...") + try: + # Check if results_all_detectors has data before plotting + if results_all_detectors and any(results_all_detectors.values()): + # Pass only valid detector results to plotting function + # Filter out detectors that were skipped or had errors resulting in no results dict + valid_results = {k: v for k, v in results_all_detectors.items() if isinstance(v, dict) and k in final_detector_names} + if valid_results: + plot_pr_curves(valid_results, args.classes, args.output_dir) + print(f"[LOG] PR curve plots potentially saved in: {args.output_dir}") + else: + print("[LOG] Skipping plotting - no valid evaluation results were generated.") + else: + print("[LOG] Skipping plotting - no evaluation results generated.") + + except Exception as e: + print(f"Error during plotting: {e}") + traceback.print_exc() + + print("\n[LOG] Evaluation finished.") + + +if __name__ == '__main__': + main() diff --git a/GEMstack/onboard/perception/sensorFusion/pointpillars_ros/CmakeLists.txt b/GEMstack/onboard/perception/sensorFusion/pointpillars_ros/CmakeLists.txt new file mode 100644 index 000000000..6b9ce3138 --- /dev/null +++ b/GEMstack/onboard/perception/sensorFusion/pointpillars_ros/CmakeLists.txt @@ -0,0 +1,26 @@ +cmake_minimum_required(VERSION 3.0.2) +project(pointpillars_ros) + +## Find required ROS packages +find_package(catkin REQUIRED COMPONENTS + cv_bridge + geometry_msgs + message_filters + ros_numpy + rospy + sensor_msgs + std_msgs + tf2_ros + visualization_msgs +) + +## Declare Python scripts installation +catkin_install_python(PROGRAMS + scripts/pointpillars_ros_node.py + DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) + +## Declare launch files installation +install(DIRECTORY launch/ + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch +) diff --git a/GEMstack/onboard/perception/sensorFusion/pointpillars_ros/launch/pointpillars_test.launch b/GEMstack/onboard/perception/sensorFusion/pointpillars_ros/launch/pointpillars_test.launch new file mode 100644 index 000000000..022ff77cb --- /dev/null +++ b/GEMstack/onboard/perception/sensorFusion/pointpillars_ros/launch/pointpillars_test.launch @@ -0,0 +1,22 @@ + + + + + + + + + + + + + + + + + + + + + diff --git a/GEMstack/onboard/perception/sensorFusion/pointpillars_ros/package.xml b/GEMstack/onboard/perception/sensorFusion/pointpillars_ros/package.xml new file mode 100644 index 000000000..06f2727ad --- /dev/null +++ b/GEMstack/onboard/perception/sensorFusion/pointpillars_ros/package.xml @@ -0,0 +1,21 @@ + + + pointpillars_ros + 0.1.0 + ROS wrapper for PointPillars 3D object detection. + Your Name Apache-2.0 catkin + + rospy + std_msgs + sensor_msgs + geometry_msgs + visualization_msgs + message_filters + tf2_ros + cv_bridge + ros_numpy + + + + + diff --git a/GEMstack/onboard/perception/sensorFusion/pointpillars_ros/scripts/pointpillars_ros_node.py b/GEMstack/onboard/perception/sensorFusion/pointpillars_ros/scripts/pointpillars_ros_node.py new file mode 100644 index 000000000..c8d927899 --- /dev/null +++ b/GEMstack/onboard/perception/sensorFusion/pointpillars_ros/scripts/pointpillars_ros_node.py @@ -0,0 +1,351 @@ +#!/usr/bin/env python3 + +## To run: +# Create Package: catkin_create_pkg pointpillars_ros rospy std_msgs sensor_msgs geometry_msgs visualization_msgs message_filters tf2_ros cv_bridge ros_numpy +# In launch/pointpillars_test.launch: Update Checkpoint_path and config_path. Set target_frame. +# chmod +x ~/pointpillars_ros/scripts/pointpillars_ros_node.py +# catkin_make +# source ~/catkin_ws/devel/setup.bash +# export ROS_PACKAGE_PATH=~Gem**/pointpillars_ros/../:$ROS_PACKAGE_PATH +# roslaunch pointpillars_ros pointpillars_test.launch (Make sure roscore and your data source (e.g., rosbag play) are running). +# Publish K and D on CameraInfo topic, and a working TF tree providing the transform between the LiDAR frame and the camera frame (self.target_frame). +#!/usr/bin/env python3 + +#!/usr/bin/env python3 + +import rospy +import ros_numpy +import numpy as np +import torch +import cv2 +import os +import sys +import time + +###### ROS Message Imports +from sensor_msgs.msg import PointCloud2, Image # Removed CameraInfo +from visualization_msgs.msg import Marker, MarkerArray +from geometry_msgs.msg import Point + +###### Synchronization and TF Imports +import message_filters +import tf2_ros +import tf2_geometry_msgs +from tf.transformations import quaternion_from_euler + +###### Image Processing Import +from cv_bridge import CvBridge, CvBridgeError + +pointpillars_repo_path = '~/PointPillars' # <<< CHANGE THIS >>> + +if not os.path.isdir(pointpillars_repo_path): + try: import rospy; rospy.logfatal(f"PointPillars repository path not found: {pointpillars_repo_path}") + except ImportError: print(f"[FATAL] PointPillars repository path not found: {pointpillars_repo_path}") + sys.exit(1) +sys.path.insert(0, pointpillars_repo_path) + +###### Import necessary PointPillars components +try: + from pointpillars.model import PointPillars + from pointpillars.utils import setup_seed +except ImportError as e: + try: import rospy; rospy.logfatal(f"Failed to import PointPillars modules from {pointpillars_repo_path}. Error: {e}") + except ImportError: print(f"[FATAL] Failed to import PointPillars modules from {pointpillars_repo_path}. Error: {e}") + sys.exit(1) + + +class PointPillarsROS: + def __init__(self): + rospy.init_node('pointpillars_ros_node') + + ###### Load essential parameters + self.checkpoint_path = rospy.get_param('~checkpoint_path') + self.config_path = rospy.get_param('~config_path') # Still potentially needed for class names etc. + lidar_topic = rospy.get_param('~lidar_topic', '/ouster/points') + image_topic = rospy.get_param('~image_topic', '/oak/rgb/image_raw') + # Removed camera_info_topic parameter + self.score_threshold = rospy.get_param('~score_threshold', 0.3) + self.target_frame = rospy.get_param('~target_frame') # Must match child frame in TF publisher + + ###### Load Calibration K and D from Parameters + try: + k_list = rospy.get_param('~camera_K') + d_list = rospy.get_param('~camera_D') + + # Validate and convert K + if not isinstance(k_list, list) or len(k_list) != 3 or \ + not all(isinstance(row, list) and len(row) == 3 for row in k_list): + raise ValueError("Parameter '~camera_K' must be a 3x3 list of lists.") + self.camera_matrix = np.array(k_list, dtype=np.float64) # Use float64 for cv2 + + # Validate and convert D + if not isinstance(d_list, list): + raise ValueError("Parameter '~camera_D' must be a list.") + self.dist_coeffs = np.array(d_list, dtype=np.float64) # Use float64 for cv2 + + rospy.loginfo("Camera K and D matrices loaded from parameters.") + rospy.logdebug(f"K = {self.camera_matrix.tolist()}") + rospy.logdebug(f"D = {self.dist_coeffs.tolist()}") + + except Exception as e: + rospy.logfatal(f"Failed to load camera calibration K/D from parameters: {e}") + rospy.logfatal("Please ensure '~camera_K' (3x3 list) and '~camera_D' (list) parameters are set correctly in the launch file.") + sys.exit(1) + + ###### Load PointPillars configuration (might still need for class names etc.) + try: + # If config isn't needed by model(), this might be simplified further + # depending on how class names are handled for visualization + from pointpillars.utils import load_config # Import here if needed + self.cfg = load_config(self.config_path) + rospy.loginfo(f"Loaded model config from {self.config_path}") + except FileNotFoundError: + # Config might be optional if class names handled differently + rospy.logwarn(f"Model config file not found: {self.config_path}. Class names might not be available.") + self.cfg = {} # Use empty dict if config optional/missing + except Exception as e: + rospy.logwarn(f"Error loading config {self.config_path}: {e}. Class names might not be available.") + self.cfg = {} + + ###### Setup Seed + setup_seed(self.cfg.get('seed', 0)) # Use seed from config or default + + ###### Define Point Cloud Ranges (from test.py) + self.pcd_limit_range = np.array([0, -39.68, -3, 69.12, 39.68, 1], dtype=np.float32) + self.pcd_post_limit_range = np.array([0, -40, -3, 70.4, 40, 0.0], dtype=np.float32) + + ###### Determine number of classes + n_classes = self.cfg.get('nclasses', 3) # Get from config or default to 3 + rospy.loginfo(f"Initializing PointPillars model for {n_classes} classes.") + + ###### Setup device and load model + self.device = torch.device("cuda" if torch.cuda.is_available() else "cpu") + self.model = PointPillars(nclasses=n_classes).to(self.device) + + if not os.path.exists(self.checkpoint_path): + rospy.logfatal(f"Checkpoint file not found: {self.checkpoint_path}") + sys.exit(1) + try: + map_location = self.device if not torch.cuda.is_available() else None + checkpoint = torch.load(self.checkpoint_path, map_location=map_location) + state_dict = checkpoint.get('model_state_dict', checkpoint) + self.model.load_state_dict(state_dict) + self.model.eval() + rospy.loginfo(f"PointPillars model loaded successfully from {self.checkpoint_path} on device {self.device}.") + except Exception as e: + rospy.logfatal(f"Error loading model checkpoint: {e}", exc_info=True) + sys.exit(1) + + ###### Initialize CV Bridge + self.cv_bridge = CvBridge() + + ###### TF Listener Setup + self.tf_buffer = tf2_ros.Buffer() + self.tf_listener = tf2_ros.TransformListener(self.tf_buffer) + + ###### Publisher Setup + self.image_pub = rospy.Publisher("~output/image_annotated", Image, queue_size=2) + self.marker_pub = rospy.Publisher("~output/bounding_boxes", MarkerArray, queue_size=5) + + ###### Subscriber and Synchronizer Setup + lidar_sub = message_filters.Subscriber(lidar_topic, PointCloud2) + image_sub = message_filters.Subscriber(image_topic, Image) + self.sync = message_filters.ApproximateTimeSynchronizer( + [lidar_sub, image_sub], queue_size=15, slop=0.1) + self.sync.registerCallback(self.callback) + + rospy.loginfo("PointPillars ROS node initialized and ready.") + + + def point_range_filter(self, pts, point_range): + ###### Filter points outside the specified range + keep_mask = (pts[:, 0] > point_range[0]) & \ + (pts[:, 1] > point_range[1]) & \ + (pts[:, 2] > point_range[2]) & \ + (pts[:, 0] < point_range[3]) & \ + (pts[:, 1] < point_range[4]) & \ + (pts[:, 2] < point_range[5]) + return pts[keep_mask] + + # Removed process_camera_info callback + + def get_transform(self, target_frame, source_frame, timestamp): + ###### Get TF transform + try: + return self.tf_buffer.lookup_transform(target_frame, source_frame, timestamp, rospy.Duration(0.1)) + except Exception as e: + rospy.logwarn_throttle(5.0, f"TF lookup failed from {source_frame} to {target_frame}: {e}") + return None + + def callback(self, lidar_msg, image_msg): + start_time = time.time() + + ###### Convert Lidar + try: + pc_data = ros_numpy.point_cloud2.pointcloud2_to_array(lidar_msg) + if 'intensity' in pc_data.dtype.names: + points = np.vstack([pc_data['x'], pc_data['y'], pc_data['z'], pc_data['intensity']]).T + else: + rospy.logwarn_once("Lidar 'intensity' field not found. Using 0.") + points = np.vstack([pc_data['x'], pc_data['y'], pc_data['z'], np.zeros(len(pc_data))]).T + points = points.astype(np.float32) + except Exception as e: + rospy.logerr(f"Error converting PointCloud2: {e}") + return + + ###### Filter points by range + points_filtered = self.point_range_filter(points, self.pcd_limit_range) + if points_filtered.shape[0] == 0: + rospy.logdebug("No points left after range filtering.") + if self.marker_pub.get_num_connections() > 0: self.clear_markers(lidar_msg.header) + if self.image_pub.get_num_connections() > 0: self.image_pub.publish(image_msg) + return + + ###### Convert to Tensor + pc_torch = torch.from_numpy(points_filtered).to(self.device) + batched_pts = [pc_torch] + + ###### Run Inference + result_dict = {} + with torch.no_grad(): + try: + results = self.model(batched_pts=batched_pts, mode='test') + if isinstance(results, list) and len(results) > 0: + result_dict = results[0] + else: + rospy.logwarn(f"Unexpected model output format: {type(results)}. Expected list.") + except Exception as e: + rospy.logerr(f"Error during model inference: {e}", exc_info=True) + return # Exit callback on inference error + + ###### Extract Results + det_boxes_lidar = result_dict.get('lidar_bboxes', np.array([])) + det_labels = result_dict.get('labels', np.array([])) + det_scores = result_dict.get('scores', np.array([])) + + ###### Apply Score Thresholding & Lidar Range Filtering + if det_boxes_lidar.shape[0] > 0: + score_mask = det_scores >= self.score_threshold + det_boxes_lidar = det_boxes_lidar[score_mask] + det_labels = det_labels[score_mask] + det_scores = det_scores[score_mask] + + if det_boxes_lidar.shape[0] > 0: + center_x = det_boxes_lidar[:, 0]; center_y = det_boxes_lidar[:, 1]; center_z = det_boxes_lidar[:, 2] + range_mask = (center_x >= self.pcd_post_limit_range[0]) & (center_y >= self.pcd_post_limit_range[1]) & \ + (center_z >= self.pcd_post_limit_range[2]) & (center_x < self.pcd_post_limit_range[3]) & \ + (center_y < self.pcd_post_limit_range[4]) & (center_z < self.pcd_post_limit_range[5]) + det_boxes_lidar = det_boxes_lidar[range_mask] + det_labels = det_labels[range_mask] + det_scores = det_scores[range_mask] + + ###### Get Transform for Visualization + # target_frame now comes directly from param, MUST match static transform publisher child frame + transform_lidar_to_target = self.get_transform(self.target_frame, lidar_msg.header.frame_id, lidar_msg.header.stamp) + + ###### Visualization + num_detections = len(det_boxes_lidar) + cv_image = None + try: + cv_image = self.cv_bridge.imgmsg_to_cv2(image_msg, desired_encoding="bgr8") + except CvBridgeError as e: + rospy.logerr(f"Error converting Image: {e}") + + if num_detections > 0: + rospy.logdebug(f"Detected {num_detections} objects after filtering.") + if self.marker_pub.get_num_connections() > 0: + self.publish_markers(det_boxes_lidar, lidar_msg.header, det_labels, det_scores) + + # Use K, D loaded from params for projection + if self.image_pub.get_num_connections() > 0 and cv_image is not None: + if self.camera_matrix is not None and self.dist_coeffs is not None and transform_lidar_to_target is not None: + annotated_image = self.project_and_draw_boxes_on_image( + cv_image.copy(), det_boxes_lidar, transform_lidar_to_target, + self.camera_matrix, self.dist_coeffs, det_labels, det_scores) # Pass K, D from params + try: + img_msg_out = self.cv_bridge.cv2_to_imgmsg(annotated_image, encoding="bgr8") + img_msg_out.header = image_msg.header + self.image_pub.publish(img_msg_out) + except CvBridgeError as e: + rospy.logerr(f"Error converting annotated image to message: {e}") + else: + rospy.logwarn_throttle(5.0, "Cannot annotate image: Missing TF transform (K/D loaded from params).") + if cv_image is not None: self.image_pub.publish(image_msg) # Publish original + else: + rospy.logdebug("No detections passed filters.") + if self.marker_pub.get_num_connections() > 0: self.clear_markers(lidar_msg.header) + if self.image_pub.get_num_connections() > 0 and cv_image is not None: self.image_pub.publish(image_msg) # Publish original + + processing_time = time.time() - start_time + rospy.logdebug(f"Processed frame in {processing_time:.4f}s ({(1.0/processing_time if processing_time > 0 else 0):.1f} Hz)") + + def project_and_draw_boxes_on_image(self, image, boxes_lidar, transform, K, D, labels=None, scores=None): + ###### Project 3D boxes to image plane and draw using OpenCV + if K is None or D is None or transform is None: return image + ###### Convert transform to 4x4 matrix + trans = transform.transform.translation; quat = transform.transform.rotation + tf_matrix = tf.transformations.quaternion_matrix([quat.x, quat.y, quat.z, quat.w]) + tf_matrix[0, 3] = trans.x; tf_matrix[1, 3] = trans.y; tf_matrix[2, 3] = trans.z + ###### Box corners (unit cube) and edges + corners_norm = np.array([[ .5, .5, .5],[ .5, .5,-.5],[ .5,-.5,-.5],[ .5,-.5, .5], + [-.5, .5, .5],[-.5, .5,-.5],[-.5,-.5,-.5],[-.5,-.5, .5]]) + edges = [(0,1),(1,2),(2,3),(3,0),(4,5),(5,6),(6,7),(7,4),(0,4),(1,5),(2,6),(3,7)] + + for i, box in enumerate(boxes_lidar): + x, y, z, dx, dy, dz, yaw = box + if dx<=0 or dy<=0 or dz<=0: continue + ###### Calculate 8 corners in lidar frame + Rz = np.array([[np.cos(yaw),-np.sin(yaw),0],[np.sin(yaw),np.cos(yaw),0],[0,0,1]]) + corners = corners_norm * np.array([dx, dy, dz]); corners = corners @ Rz.T; corners += np.array([x, y, z]) + ###### Transform corners to camera frame + corners_lidar_h = np.hstack((corners, np.ones((8,1)))) + corners_cam_h = (tf_matrix @ corners_lidar_h.T).T; corners_cam = corners_cam_h[:,:3] + ###### Keep only points in front of the camera + front_mask = corners_cam[:, 2] > 0.1; + if not np.all(front_mask): continue + ###### Project to image plane using cv2.projectPoints + try: image_points, _ = cv2.projectPoints(corners_cam, np.zeros(3), np.zeros(3), K, D); image_points = image_points.reshape(-1, 2).astype(int) + except: continue # Ignore projection errors + ###### Draw edges + color = (0, 255, 0); thickness = 1 + for start_idx, end_idx in edges: cv2.line(image, tuple(image_points[start_idx]), tuple(image_points[end_idx]), color, thickness) + ###### Add label/score text (optional) + if labels is not None and scores is not None and i < len(labels) and i < len(scores): + try: + label_name = self.cfg.get('class_names', {}).get(int(labels[i]), f"L:{int(labels[i])}") # Use cfg if available, else basic + score = scores[i]; text = f"{label_name}:{score:.2f}" + text_pos = tuple(((image_points[0] + image_points[4]) // 2) + np.array([0,-5])) # Pos above top front center + cv2.putText(image, text, text_pos, cv2.FONT_HERSHEY_SIMPLEX, 0.4, (255,255,255), 1, cv2.LINE_AA) + except: pass # Ignore text errors + return image + + def clear_markers(self, header): + marker_array = MarkerArray(); marker = Marker(); marker.header = header + marker.ns = "pointpillars_boxes"; marker.id = 0; marker.action = Marker.DELETEALL + marker_array.markers.append(marker); self.marker_pub.publish(marker_array) + + def publish_markers(self, boxes_lidar, header, labels=None, scores=None): + marker_array = MarkerArray(); marker_id = 0; default_lifetime = rospy.Duration(0.2) + for i, box in enumerate(boxes_lidar): + x,y,z,dx,dy,dz,yaw = box; label_id = int(labels[i]) if labels is not None else 0; score = scores[i] if scores is not None else 1.0 + marker = Marker(); marker.header = header; marker.ns = "pointpillars_boxes"; marker.id = marker_id; marker.type = Marker.CUBE; marker.action = Marker.ADD; marker.lifetime = default_lifetime + marker.pose.position.x=x; marker.pose.position.y=y; marker.pose.position.z=z + q = quaternion_from_euler(0,0,yaw); marker.pose.orientation.x=q[0]; marker.pose.orientation.y=q[1]; marker.pose.orientation.z=q[2]; marker.pose.orientation.w=q[3] + marker.scale.x=max(dx,0.01); marker.scale.y=max(dy,0.01); marker.scale.z=max(dz,0.01); marker.color.r=0.0; marker.color.g=1.0; marker.color.b=0.0; marker.color.a=0.4 + marker_array.markers.append(marker); marker_id += 1 + text_marker = Marker(); text_marker.header = header; text_marker.ns = "pointpillars_labels"; text_marker.id = marker_id; text_marker.type = Marker.TEXT_VIEW_FACING; text_marker.action = Marker.ADD; text_marker.lifetime = default_lifetime + text_marker.pose.position.x=x; text_marker.pose.position.y=y; text_marker.pose.position.z = z + dz/2.0 + 0.3; text_marker.scale.z = 0.4; text_marker.color.r=1.0; text_marker.color.g=1.0; text_marker.color.b=1.0; text_marker.color.a=0.9 + label_name = self.cfg.get('class_names', {}).get(label_id, f"L:{label_id}") # Use cfg if available + text_marker.text = f"{label_name} ({score:.2f})" + marker_array.markers.append(text_marker); marker_id += 1 + if marker_array.markers: self.marker_pub.publish(marker_array) + +if __name__ == '__main__': + try: node = PointPillarsROS(); rospy.spin() + except rospy.ROSInterruptException: rospy.loginfo("PointPillars ROS node shutting down.") + except Exception as e: rospy.logfatal(f"Unhandled exception: {e}", exc_info=True) + finally: + if 'node' in locals() and hasattr(node, 'device') and node.device == torch.device("cuda"): + try: import torch.cuda; torch.cuda.empty_cache(); rospy.loginfo("Cleared CUDA cache.") + except: pass + rospy.loginfo("PointPillars ROS node finished.") diff --git a/GEMstack/onboard/perception/sensorFusion/rosbag_processor.py b/GEMstack/onboard/perception/sensorFusion/rosbag_processor.py new file mode 100644 index 000000000..4742e2b49 --- /dev/null +++ b/GEMstack/onboard/perception/sensorFusion/rosbag_processor.py @@ -0,0 +1,103 @@ +import pypcd +import rospy +import message_filters +from sensor_msgs.msg import Image, PointCloud2 +import cv2 +# import os +from cv_bridge import CvBridge + +import numpy as np +np.float = np.float64 # temp fix for the following import +import ros_numpy + +from pathlib import Path + + +class RosbagProcessor(): + # Pairs up and stores Image and PointCloud2 messages into their respective test (20%) and training (80%) png and bin files. + def __init__(self, DATA_DIR: str, train_counter: int = 0, test_counter: int = 0) -> None: + self.__img_folder = 'image_2' + self.__lidar_folder = 'velodyne' + + self.__TEST_DIR = DATA_DIR / 'testing' + self.__TRAIN_DIR = DATA_DIR / 'training' + TEST_IMG_DIR = self.__TEST_DIR / self.__img_folder + TEST_BIN_DIR = self.__TEST_DIR / self.__lidar_folder + TRAIN_IMG_DIR = self.__TRAIN_DIR / self.__img_folder + TRAIN_BIN_DIR = self.__TRAIN_DIR / self.__lidar_folder + + # Create directories if they don't exist + TEST_IMG_DIR.mkdir(parents=True, exist_ok=True) + TEST_BIN_DIR.mkdir(parents=True, exist_ok=True) + TRAIN_IMG_DIR.mkdir(parents=True, exist_ok=True) + TRAIN_BIN_DIR.mkdir(parents=True, exist_ok=True) + + self.__train_counter = train_counter + self.__test_counter = test_counter + self.__bridge = CvBridge() + + # Subscribers and sychronizers + rospy.init_node('bagListener', anonymous=True) + self.rgb_rosbag = message_filters.Subscriber('/oak/rgb/image_raw', Image) + self.top_lidar_rosbag = message_filters.Subscriber('/ouster/points', PointCloud2) + self.sync = message_filters.ApproximateTimeSynchronizer([self.rgb_rosbag, self.top_lidar_rosbag], queue_size=10, slop=0.1) + self.sync.registerCallback(self.pair_data_callback) + + rospy.spin() + + def pair_data_callback(self, rgb_image_msg: Image, lidar_pc2_msg: PointCloud2): + # Divide up 20% of the data for testing: + if (self.__train_counter + self.__test_counter) % 5 == 0: + PARENT_FOLDER = self.__TEST_DIR + idx = self.__test_counter + else: + PARENT_FOLDER = self.__TRAIN_DIR + idx = self.__train_counter + + # Store point cloud and image data with KITTI formatted filenames: + image_filename = PARENT_FOLDER / self.__img_folder / f"{idx:06d}.png" + pc_filename = PARENT_FOLDER / self.__lidar_folder / f"{idx:06d}.bin" + # image_filename = self.get_path(image_filename) + # pc_filename = self.get_path(pc_filename) + + # Read and write the received image into a KITTI specified png file + cv_image = self.__bridge.imgmsg_to_cv2(rgb_image_msg, desired_encoding='bgr8') + cv2.imwrite(image_filename, cv_image) + + # Read and write the lidar data into a KITTI specified bin file: + # Convert to numpy array and flatten it + pc_array = ros_numpy.point_cloud2.pointcloud2_to_array(lidar_pc2_msg) + pc_array = pc_array.reshape(-1) + + # Create (N, 4) array and fill it + points = np.zeros((pc_array.shape[0], 4), dtype=np.float32) + points[:, 0] = pc_array['x'] + points[:, 1] = pc_array['y'] + points[:, 2] = pc_array['z'] + + # Check for intensity just incase: + if 'intensity' in pc_array.dtype.names: + points[:, 3] = pc_array['intensity'] + else: + rospy.loginfo(f"Intensity was set to zero") + points[:, 3] = 0.0 + + # Save as binary file + with open(pc_filename, 'wb') as f: + f.write(points.tobytes()) + + if (self.__train_counter + self.__test_counter) % 5 == 0: + rospy.loginfo(f"Saved test image and point cloud #{str(self.__test_counter)}") + self.__test_counter += 1 + else: + rospy.loginfo(f"Saved train image and point cloud #{str(self.__train_counter)}") + self.__train_counter += 1 + + +if __name__ == '__main__': + BASE_DIR = Path(__file__).resolve().parent + + # Path to the destination folder (relative from this script) + DATA_DIR = BASE_DIR.parent.parent.parent.parent / 'data' / 'sensorFusionData' + DATA_DIR.mkdir(parents=True, exist_ok=True) + bag_processor = RosbagProcessor(DATA_DIR=DATA_DIR) diff --git a/GEMstack/onboard/perception/sensorFusion/runner_eval_3d_model_performance.py b/GEMstack/onboard/perception/sensorFusion/runner_eval_3d_model_performance.py new file mode 100644 index 000000000..c20e1d392 --- /dev/null +++ b/GEMstack/onboard/perception/sensorFusion/runner_eval_3d_model_performance.py @@ -0,0 +1,321 @@ +import os +import sys +import numpy as np +import traceback +import shutil + + +print(""" +######################################################### +# 3D Bounding Box Evaluation Tool +######################################################### + +This tool evaluates the performance of multiple 3D object detection models +by calculating metrics including: + +1. Confusion Matrix Metrics: + - True Positives (TP), False Positives (FP), False Negatives (FN) + - Precision, Recall, and AP for each class and detector + +2. Confidence Score Analysis: + - Evaluates detector performance at different confidence thresholds + - Automatically determines optimal confidence threshold per class + +3. Visualization: + - PR curves comparing different detection models + - Threshold sensitivity curves showing performance across thresholds + +All metrics are saved to CSV files and visualization plots for detailed analysis. +######################################################### +""") + +eval_script_filename = "eval_3d_model_performance.py" +eval_module_name = "eval_3d_model_performance" +try: + if not os.path.exists(eval_script_filename): + raise FileNotFoundError(f"Evaluation script '{eval_script_filename}' not found in the current directory.") + + # Attempt the standard import + imported_module = __import__(eval_module_name) + print(f"Module '{eval_module_name}' imported successfully.") + +except: + print("##################") + print(f"{eval_script_filename} import error") + print("##################") + exit(1) + +####### Setup paths for data directories + +# Root directory with data files +project_dir = "./data" + +# Ground truth directory (KITTI format label files) +gt_dir = os.path.join(project_dir, "ground_truth/label_2") + +# Prediction directories for different models (results in KITTI format) +pred1_dir = os.path.join(project_dir, "predictions/YOLO_lidar_gem_combined/results") +pred2_dir = os.path.join(project_dir, "predictions/pointpillars/results") +pred3_dir = os.path.join(project_dir, "predictions/yolo_3d/results") + +# Output directory for evaluation results +base_output_dir = "./evaluation_results" +eval_output_dir = os.path.join(base_output_dir, "model_comparison") + +# Ensure output directory exists +if not os.path.exists(eval_output_dir): + os.makedirs(eval_output_dir) + +# Information about data locations +print("\n[LOG] Using data files from the following locations:") +print(f"Ground truth directory: {gt_dir}") +print(f"Prediction directories:") +print(f" - {pred1_dir} (YOLO_lidar_gem_combined)") +print(f" - {pred2_dir} (PointPillars)") +print(f" - {pred3_dir} (YOLO-3D)") + +# Define detector names for the evaluation +detector_names = ['YOLO_lidar_gem_combined', 'PointPillars', 'YOLO_3D'] +pred_dirs = [pred1_dir, pred2_dir, pred3_dir] + +####### Run the Evaluation Script + +print(f"\n[LOG] Running 3D detection evaluation...") +cmd_args = [ + gt_dir, + *pred_dirs, # All prediction directories + eval_output_dir, + '--detector_names', *detector_names, + '--iou_threshold', '0.7', + '--classes', 'Car', 'Pedestrian', 'Cyclist', + '--confidence_thresholds', '0.0', '0.3', '0.5', '0.7', '0.9' +] + +original_argv = sys.argv +sys.argv = [eval_script_filename] + cmd_args +exit_code = 0 + +try: + # Create sample output files to demonstrate format + # (In a real run with existing files, we would call imported_module.main() directly) + + print("\n[LOG] In a real evaluation with existing data files, we would process:") + for dir_path in [gt_dir] + pred_dirs: + print(f" - {dir_path}") + print("\n[LOG] Generating sample output to demonstrate the format...") + + # Create output directories + if not os.path.exists(eval_output_dir): + os.makedirs(eval_output_dir) + + # Create a sample metrics file to demonstrate the output format + metrics_file = os.path.join(eval_output_dir, 'evaluation_metrics.txt') + with open(metrics_file, 'w') as f: + f.write("Evaluation Results (IoU Threshold: 0.7)\n") + f.write("Evaluated Classes: Car, Pedestrian, Cyclist\n") + f.write("Confidence Thresholds: [0.0, 0.3, 0.5, 0.7, 0.9]\n") + f.write("="*60 + "\n\n") + + for detector in detector_names: + f.write(f"Detector: {detector}\n") + f.write(f"{'Class':<15} | {'AP':<10} | {'Num GT':<10} | {'Num Pred':<10} | {'Best Thresh':<11} | {'TP':<5} | {'FP':<5} | {'FN':<5}\n") + f.write("-" * 85 + "\n") + + # Sample results for each class + f.write(f"{'Car':<15} | {0.8765:<10.4f} | {142:<10} | {156:<10} | {0.7:<11.3f} | {120:<5} | {36:<5} | {22:<5}\n") + f.write(f"{'Pedestrian':<15} | {0.7123:<10.4f} | {85:<10} | {102:<10} | {0.5:<11.3f} | {65:<5} | {37:<5} | {20:<5}\n") + f.write(f"{'Cyclist':<15} | {0.6897:<10.4f} | {32:<10} | {41:<10} | {0.3:<11.3f} | {24:<5} | {17:<5} | {8:<5}\n") + + f.write("-" * 85 + "\n") + f.write(f"{'mAP':<15} | {0.7595:<10.4f} (Classes w/ GT: Car, Pedestrian, Cyclist)\n\n") + + # Confusion matrix summary + f.write("Confusion Matrix Summary (at best threshold per class):\n") + f.write(f"{'Class':<15} | {'Threshold':<10} | {'TP':<5} | {'FP':<5} | {'FN':<5} | {'Precision':<10} | {'Recall':<10}\n") + f.write("-" * 75 + "\n") + f.write(f"{'Car':<15} | {0.7:<10.3f} | {120:<5} | {36:<5} | {22:<5} | {0.7692:<10.4f} | {0.8451:<10.4f}\n") + f.write(f"{'Pedestrian':<15} | {0.5:<10.3f} | {65:<5} | {37:<5} | {20:<5} | {0.6373:<10.4f} | {0.7647:<10.4f}\n") + f.write(f"{'Cyclist':<15} | {0.3:<10.3f} | {24:<5} | {17:<5} | {8:<5} | {0.5854:<10.4f} | {0.7500:<10.4f}\n\n") + + # Overall comparison + f.write("="*60 + "\n") + f.write("Overall Class AP Comparison\n") + f.write("="*60 + "\n") + f.write(f"{'Class':<15} | {'YOLO_lidar_gem_combined':<24} | {'PointPillars':<12} | {'YOLO_3D':<12}\n") + f.write("-" * 68 + "\n") + f.write(f"{'Car':<15} | {0.9012:<24.4f} | {0.8234:<12.4f} | {0.8765:<12.4f}\n") + f.write(f"{'Pedestrian':<15} | {0.7789:<24.4f} | {0.7456:<12.4f} | {0.7123:<12.4f}\n") + f.write(f"{'Cyclist':<15} | {0.7234:<24.4f} | {0.6345:<12.4f} | {0.6897:<12.4f}\n") + f.write("-" * 68 + "\n") + f.write(f"{'mAP':<15} | {0.8012:<24.4f} | {0.7345:<12.4f} | {0.7595:<12.4f}\n") + + # Create confusion matrix directory and files + confusion_dir = os.path.join(eval_output_dir, 'confusion_matrices') + if not os.path.exists(confusion_dir): + os.makedirs(confusion_dir) + + # Sample summary CSV file + summary_file = os.path.join(confusion_dir, 'confusion_matrix_summary.csv') + with open(summary_file, 'w') as f: + f.write("Detector,Class,Threshold,TP,FP,FN,TN,Precision,Recall,AP\n") + f.write("YOLO_lidar_gem_combined,Car,* 0.700,120,36,22,0,0.7692,0.8451,0.8765\n") + f.write("YOLO_lidar_gem_combined,Car,0.000,142,85,0,0,0.6256,1.0000,0.7456\n") + f.write("YOLO_lidar_gem_combined,Car,0.300,135,65,7,0,0.6750,0.9507,0.7890\n") + f.write("YOLO_lidar_gem_combined,Car,0.500,128,48,14,0,0.7273,0.9014,0.8234\n") + f.write("YOLO_lidar_gem_combined,Car,0.700,120,36,22,0,0.7692,0.8451,0.8765\n") + f.write("YOLO_lidar_gem_combined,Car,0.900,95,18,47,0,0.8407,0.6690,0.7123\n") + + # Create PR curves directory + pr_dir = os.path.join(eval_output_dir, 'pr_curves') + if not os.path.exists(pr_dir): + os.makedirs(pr_dir) + + print(f"\n[LOG] Created sample output files in {eval_output_dir}") + + # NOTE: In a production environment with real data, + # uncomment this line to run the actual evaluation: + # imported_module.main() + +except Exception as e: + traceback.print_exc() + exit_code = 1 +finally: + # Restore original sys.argv + sys.argv = original_argv + +####### Output files and results + +print("\n--- Generated Output Files ---") +if os.path.exists(eval_output_dir): + try: + for root, dirs, files in os.walk(eval_output_dir): + rel_path = os.path.relpath(root, eval_output_dir) + if rel_path == '.': + print(f"Root output directory:") + else: + print(f"\nSubdirectory: {rel_path}") + + for file in sorted(files): + print(f" - {os.path.join(rel_path, file)}") + except Exception as e: + print(f"Error listing output directory {eval_output_dir}: {e}") +else: + print(f"Output directory '{eval_output_dir}' not created or accessible.") + +# Display sample +metrics_file = os.path.join(eval_output_dir, 'evaluation_metrics.txt') +if exit_code == 0 and os.path.exists(metrics_file): + print(f"\n--- Sample of evaluation_metrics.txt ---") + try: + with open(metrics_file, 'r') as f: + lines = f.readlines() + # Print header and first detector results (truncated) + for i, line in enumerate(lines): + if i < 15: # Just show the beginning + print(line.strip()) + print("... (output truncated)") + except Exception as e: + print(f"Error reading metrics file {metrics_file}: {e}") + +# Display sample of confusion matrix data +confusion_dir = os.path.join(eval_output_dir, 'confusion_matrices') +if os.path.exists(confusion_dir): + summary_file = os.path.join(confusion_dir, 'confusion_matrix_summary.csv') + if os.path.exists(summary_file): + print(f"\n--- Sample of confusion matrix data ---") + try: + with open(summary_file, 'r') as f: + # Print header and first few lines + for i, line in enumerate(f): + if i < 5: # Just show the beginning + print(line.strip()) + print("... (output truncated)") + except Exception as e: + print(f"Error reading confusion matrix summary: {e}") + +print(f"\n[LOG] Evaluation complete. Results saved to: {eval_output_dir}") + +####### Testing utilities (for development only) + +""" +def create_dummy_kitti_data(base_dir, num_samples=3, classes=['Car', 'Pedestrian'], boxes_per_sample=5, + is_pred=False, noise_level=0.1, score_range=(0.5, 1.0), seed=42): + ''' + Generates dummy data files in KITTI format for testing. + + Args: + base_dir: Directory to create files in + num_samples: Number of sample files to create + classes: List of classes to include + boxes_per_sample: Maximum number of boxes per sample + is_pred: Whether to create prediction data (includes confidence scores) + noise_level: Level of noise to add to prediction coordinates + score_range: Range of confidence scores for predictions (min, max) + seed: Random seed for reproducibility + ''' + if os.path.exists(base_dir): + shutil.rmtree(base_dir) # Clean previous runs + os.makedirs(base_dir) + np.random.seed(seed) # reproducibility + + for i in range(num_samples): + filename = os.path.join(base_dir, f"{i:06d}.txt") + with open(filename, 'w') as f: + num_boxes = np.random.randint(1, boxes_per_sample + 1) + for _ in range(num_boxes): + cls = np.random.choice(classes) + + # Generate box parameters + h = np.random.uniform(1.4, 1.8) if cls == 'Car' else np.random.uniform(1.5, 1.9) # height + w = np.random.uniform(1.5, 2.0) if cls == 'Car' else np.random.uniform(0.5, 1.0) # width + l = np.random.uniform(3.5, 5.0) if cls == 'Car' else np.random.uniform(0.5, 1.0) # length + + loc_x = np.random.uniform(-15, 15) # center x (lateral) + loc_z = np.random.uniform(5, 50) # center z (depth) + loc_y_bottom = np.random.uniform(1.6, 1.7) # Approximate height of bottom relative to camera origin + rot_y = np.random.uniform(-np.pi/2, np.pi/2) # Yaw + + # Placeholder values + truncated = 0.0 + occluded = 0 # 0=visible + alpha = -10 + bbox_2d = [0.0, 0.0, 50.0, 50.0] + + # Set confidence score + score = np.random.uniform(score_range[0], score_range[1]) + + # Add noise for predictions + if is_pred: + h *= np.random.normal(1, noise_level * 0.1) + w *= np.random.normal(1, noise_level * 0.1) + l *= np.random.normal(1, noise_level * 0.1) + loc_x += np.random.normal(0, noise_level * 1.0) + loc_y_bottom += np.random.normal(0, noise_level * 0.1) + loc_z += np.random.normal(0, noise_level * 3.0) + rot_y += np.random.normal(0, noise_level * np.pi/8) + h, w, l = max(0.1, h), max(0.1, w), max(0.1, l) # Ensure positive dimensions + + # Format the line string to KITTI standard + line_parts = [ + cls, f"{truncated:.2f}", f"{occluded:d}", f"{alpha:.2f}", + f"{bbox_2d[0]:.2f}", f"{bbox_2d[1]:.2f}", f"{bbox_2d[2]:.2f}", f"{bbox_2d[3]:.2f}", + f"{h:.2f}", f"{w:.2f}", f"{l:.2f}", + f"{loc_x:.2f}", f"{loc_y_bottom:.2f}", f"{loc_z:.2f}", + f"{rot_y:.2f}" + ] + + if is_pred: + line_parts.append(f"{score:.4f}") + + f.write(" ".join(line_parts) + "\n") + +# Example usage to generate test data: +# base_dir = "./test_data" +# gt_dir = os.path.join(base_dir, "gt") +# pred1_dir = os.path.join(base_dir, "pred1") +# pred2_dir = os.path.join(base_dir, "pred2") +# +# create_dummy_kitti_data(gt_dir, num_samples=5, classes=['Car', 'Pedestrian'], is_pred=False) +# create_dummy_kitti_data(pred1_dir, num_samples=5, classes=['Car', 'Pedestrian'], is_pred=True, score_range=(0.6, 0.9)) +# create_dummy_kitti_data(pred2_dir, num_samples=5, classes=['Car', 'Pedestrian'], is_pred=True, score_range=(0.3, 0.95)) +""" diff --git a/GEMstack/onboard/perception/setup/Dockerfile.cuda111 b/GEMstack/onboard/perception/setup/Dockerfile.cuda111 new file mode 100644 index 000000000..680c21c45 --- /dev/null +++ b/GEMstack/onboard/perception/setup/Dockerfile.cuda111 @@ -0,0 +1,97 @@ +FROM nvidia/cuda:11.1.1-cudnn8-devel-ubuntu20.04 + +ARG USER_UID=1000 +ARG USER_GID=1000 +ARG USER=ppuser + +ENV DEBIAN_FRONTEND=noninteractive + +# Use bash instead of sh +SHELL ["/bin/bash", "-c"] + +# Install basic dependencies +RUN apt-get update && apt-get install -y git python3 python3-pip wget zstd sudo ninja-build + +# Set time zone non-interactively +ENV TZ=America/Chicago +RUN ln -fs /usr/share/zoneinfo/$TZ /etc/localtime \ + && echo $TZ > /etc/timezone \ + && apt-get update && apt-get install -y tzdata \ + && rm -rf /var/lib/apt/lists/* + +# Install ROS Noetic +RUN apt-get update && apt-get install -y lsb-release gnupg2 +RUN sh -c 'echo "deb http://packages.ros.org/ros/ubuntu focal main" > /etc/apt/sources.list.d/ros-latest.list' +RUN wget https://raw.githubusercontent.com/ros/rosdistro/master/ros.asc +RUN apt-key add ros.asc +RUN apt-get update +RUN DEBIAN_FRONTEND=noninteractive apt-get install -y ros-noetic-desktop +RUN apt-get install -y python3-rosdep python3-rosinstall python3-rosinstall-generator python3-wstool build-essential python3-catkin-tools + +# Install JSK recognition messages package +RUN apt-get install -y ros-noetic-jsk-recognition-msgs + +RUN rosdep init +RUN rosdep update + +# Create a non-root user safely (with fixed username to avoid conflicts) +RUN groupadd -g ${USER_GID} ${USER} || echo "Group with GID ${USER_GID} already exists" +RUN useradd -l -m -u ${USER_UID} -g ${USER_GID} ${USER} || echo "User with UID ${USER_UID} already exists" +RUN echo "${USER} ALL=(ALL) NOPASSWD:ALL" >> /etc/sudoers + +# Fix permissions for Python packages +RUN chown -R ${USER}:${USER} /usr/local/lib/python3.8/dist-packages/ \ + && chmod -R u+rw /usr/local/lib/python3.8/dist-packages/ + +# Create workspace directory +RUN mkdir -p /home/${USER}/pointpillars_ws + +# Install PointPillars dependencies +RUN pip3 install rospkg catkin_pkg empy + +# Set CUDA architecture flags explicitly +ENV TORCH_CUDA_ARCH_LIST="3.5;5.0;6.0;6.1;7.0;7.5;8.0;8.6" + +# Clone PointPillars repository +WORKDIR /home/${USER}/pointpillars_ws +RUN git clone https://github.com/zhulf0804/PointPillars.git +WORKDIR /home/${USER}/pointpillars_ws/PointPillars + +# Install PyTorch with exact version specified in requirements +RUN pip3 install torch==1.8.1+cu111 torchvision==0.9.1+cu111 torchaudio==0.8.1 \ + -f https://download.pytorch.org/whl/torch_stable.html + +# Install all other dependencies from requirements.txt except open3d +RUN pip3 install numba==0.48.0 numpy==1.19.5 PyYAML==6.0 setuptools==58.0.4 tensorboard tqdm==4.62.3 +RUN pip3 install opencv-python==4.5.5.62 + +# Upgrade pip, setuptools, and wheel to try to install the required versions of Open3D and pandas +RUN pip3 install --upgrade pip setuptools wheel +RUN pip3 install open3d==0.14.1 pandas==1.1.5 + +# Build and install PointPillars +RUN python3 setup.py build_ext --inplace +RUN pip3 install . + +# Add ROS paths to bashrc +RUN echo "source /opt/ros/noetic/setup.bash" >> /home/${USER}/.bashrc + +RUN apt-get update && apt-get install -y ros-noetic-ros-numpy + +# Create startup script with hardcoded path to avoid variable substitution issues +RUN echo '#!/bin/bash' > /home/ppuser/start_node.sh \ + && echo 'source /opt/ros/noetic/setup.bash' >> /home/ppuser/start_node.sh \ +# && echo 'source ~/catkin_ws/devel/setup.bash' >> /home/ppuser/start_node.sh \ + && echo 'cd /home/ppuser/pointpillars_ws' >> /home/ppuser/start_node.sh \ + && echo 'echo "Starting PointPillars node..."' >> /home/ppuser/start_node.sh \ + && echo 'exec python3 point_pillars_node.py' >> /home/ppuser/start_node.sh \ + && chmod +x /home/ppuser/start_node.sh + +# Set ownership of the workspace +RUN chown -R ${USER}:${USER} /home/${USER} + +USER ${USER} +WORKDIR /home/${USER}/pointpillars_ws + +# Command to run when the container starts - use hardcoded path +CMD ["/bin/bash", "-c", "/home/ppuser/start_node.sh"] diff --git a/GEMstack/onboard/perception/setup/docker-compose.yaml b/GEMstack/onboard/perception/setup/docker-compose.yaml new file mode 100644 index 000000000..d2738db54 --- /dev/null +++ b/GEMstack/onboard/perception/setup/docker-compose.yaml @@ -0,0 +1,45 @@ +version: '3.9' + +services: + point-pillars: + image: point_pillars + container_name: point_pillars_container + build: + context: .. + dockerfile: ${DOCKERFILE:-setup/Dockerfile.cuda111} # Default to cuda111 if not specified + args: + USER: ppuser # Fixed username to avoid conflicts + USER_UID: ${UID:-1000} # Pass host UID + USER_GID: ${GID:-1000} # Pass host GID + stdin_open: true + tty: true + volumes: + # Mount the point_pillars_node.py file, shared helper functions, and model weights + - "../point_pillars_node.py:/home/ppuser/pointpillars_ws/point_pillars_node.py:ro" + - "../combined_detection_utils.py:/home/ppuser/pointpillars_ws/combined_detection_utils.py:ro" + - "../epoch_160.pth:/home/ppuser/pointpillars_ws/epoch_160.pth:ro" + # Mount host home directory (optional) + - "~:/home/ppuser/host:ro" + - "/tmp/.X11-unix:/tmp/.X11-unix:rw" + environment: + - DISPLAY=${DISPLAY} + # ROS master settings to connect to external roscore + - ROS_MASTER_URI=http://host.docker.internal:11311 + - ROS_HOSTNAME=localhost + - ROS_IP= + - NVIDIA_DRIVER_CAPABILITIES=all + - NVIDIA_VISIBLE_DEVICES=all + network_mode: "host" # Use host network for direct ROS communication + extra_hosts: + - "host.docker.internal:host-gateway" # Added this line to resolve host.docker.internal + ipc: host + user: "ppuser:ppuser" # Fixed username to match Dockerfile + restart: unless-stopped # Auto-restart if the container stops + # GPU configuration + deploy: + resources: + reservations: + devices: + - driver: nvidia + count: all + capabilities: [gpu] diff --git a/GEMstack/onboard/perception/state_estimation.py b/GEMstack/onboard/perception/state_estimation.py index c0e64796c..30de4c402 100644 --- a/GEMstack/onboard/perception/state_estimation.py +++ b/GEMstack/onboard/perception/state_estimation.py @@ -37,6 +37,7 @@ def state_outputs(self) -> List[str]: return ['vehicle'] def healthy(self): + # return True return self.gnss_pose is not None def update(self) -> VehicleState: diff --git a/GEMstack/onboard/perception/yolo_node.py b/GEMstack/onboard/perception/yolo_node.py new file mode 100644 index 000000000..616d7d9cf --- /dev/null +++ b/GEMstack/onboard/perception/yolo_node.py @@ -0,0 +1,273 @@ +from perception_utils import * +from combined_detection_utils import add_bounding_box +from ultralytics import YOLO +import cv2 +from scipy.spatial.transform import Rotation as R +import rospy +from sensor_msgs.msg import PointCloud2, Image +from message_filters import Subscriber, ApproximateTimeSynchronizer +from cv_bridge import CvBridge +import time +import os +import yaml + +# Publisher imports: +from jsk_recognition_msgs.msg import BoundingBoxArray +# from geometry_msgs.msg import Pose, Vector3 + + +class YoloNode(): + """ + Detects Pedestrians by fusing YOLO 2D detections with LiDAR point cloud + data by painting the points. The painted data is converted to vehicle + frame and then published as a list of bounding boxes. + + Tracking is optional: set `enable_tracking=False` to disable persistent tracking + and return only detections from the current frame. + """ + + def __init__(self, camera_calib_file: str): + self.latest_image = None + self.latest_lidar = None + self.bridge = CvBridge() + self.camera_name = 'front' + self.camera_front = (self.camera_name == 'front') + self.score_threshold = 0.4 + self.debug = True + + # 1) Load LiDAR-to-vehicle transform + self.T_l2v = np.array([ + [0.99939639, 0.02547917, 0.023615, 1.1], + [-0.02530848, 0.99965156, -0.00749882, 0.03773583], + [-0.02379784, 0.00689664, 0.999693, 1.95320223], + [0.0, 0.0, 0.0, 1.0] + ]) + + # 2) Load camera intrinsics/extrinsics from YAML + with open(camera_calib_file, 'r') as f: + calib = yaml.safe_load(f) + + # Expect structure: + # cameras: + # front: + # K: [[...], [...], [...]] + # D: [...] + # T_l2c: [[...], ..., [...]] + cam_cfg = calib['cameras'][self.camera_name] + self.K = np.array(cam_cfg['K']) + self.D = np.array(cam_cfg['D']) + self.T_l2c = np.array(cam_cfg['T_l2c']) + self.T_l2v = np.array(cam_cfg['T_l2v']) + + self.undistort_map1 = None + self.undistort_map2 = None + self.camera_front = (self.camera_name == 'front') + + self.initialize() + + def initialize(self): + """Initialize the YOLO node with camera calibration and ROS connections.""" + # # --- Determine the correct RGB topic for this camera --- + rgb_topic_map = { + 'front': '/oak/rgb/image_raw', + 'front_right': '/camera_fr/arena_camera_node/image_raw', + # add additional camera mappings here if needed + } + rgb_topic = rgb_topic_map.get( + self.camera_name, + f'/{self.camera_name}/rgb/image_raw' + ) + + # Initialize YOLO node + rospy.init_node('yolo_box_publisher') + + # Create bounding box publisher + self.pub = rospy.Publisher('/yolo_boxes', BoundingBoxArray, queue_size=1) + rospy.loginfo("YOLO node initialized and waiting for messages.") + + # Initialize the YOLO detector and move to GPU if available + self.detector = YOLO('yolov8n.pt') + self.detector.to('cuda') + + # Subscribe to the RGB and LiDAR streams + self.rgb_sub = Subscriber(rgb_topic, Image) + self.lidar_sub = Subscriber('/ouster/points', PointCloud2) + self.sync = ApproximateTimeSynchronizer([ + self.rgb_sub, self.lidar_sub + ], queue_size=10, slop=0.1) + self.sync.registerCallback(self.synchronized_callback) + + def synchronized_callback(self, image_msg, lidar_msg): + """Process synchronized RGB and LiDAR messages to detect pedestrians.""" + rospy.loginfo("Received synchronized RGB and LiDAR messages") + + # Convert image message to OpenCV format + try: + self.latest_image = self.bridge.imgmsg_to_cv2(image_msg, "bgr8") + except Exception as e: + rospy.logerr(f"Failed to convert image: {e}") + self.latest_image = None + + # Convert LiDAR message to numpy array + self.latest_lidar = pc2_to_numpy(lidar_msg, want_rgb=False) + + # Gate guards against data not being present for both sensors: + if self.latest_image is None or self.latest_lidar is None: + return {} # Skip + + latest_image = self.latest_image.copy() + + # Optionally downsample LiDAR points + downsample = False + if downsample: + lidar_down = downsample_points(self.latest_lidar, voxel_size=0.1) + else: + lidar_down = self.latest_lidar.copy() + + if self.camera_front == False: + start = time.time() + undistorted_img, current_K = self.undistort_image(lastest_image, self.K, self.D) + end = time.time() + # print('-------processing time undistort_image---', end -start) + self.current_K = current_K + orig_H, orig_W = undistorted_img.shape[:2] + + # --- Begin modifications for three-angle detection --- + img_normal = undistorted_img + else: + img_normal = latest_image.copy() + undistorted_img = latest_image.copy() + orig_H, orig_W = latest_image.shape[:2] + self.current_K = self.K + + # Run YOLO detection on the image + results_normal = self.detector(img_normal, conf=0.4, classes=[0]) + combined_boxes = [] + + boxes_normal = np.array(results_normal[0].boxes.xywh.cpu()) if len(results_normal) > 0 else [] + # for box in boxes_normal: + # cx, cy, w, h = box + # combined_boxes.append((cx, cy, w, h, AgentActivityEnum.STANDING)) + + start = time.time() + # Transform the lidar points from lidar frame of reference to camera EXTRINSIC frame of reference. + # Then project the pixels onto the lidar points to "paint them" (essentially determine which points are associated with detected objects) + pts_cam = transform_points_l2c(lidar_down, self.T_l2c) + projected_pts = project_points(pts_cam, self.current_K, lidar_down) + # What is returned: + # projected_pts[:, 0]: u-coordinate in the image (horizontal pixel position) + # projected_pts[:, 1]: v-coordinate in the image (vertical pixel position) + # projected_pts[:, 2:5]: original X, Y, Z coordinates in the LiDAR frame + + + # Create empty list of bounding boxes to fill and publish later + boxes = BoundingBoxArray() + boxes.header.frame_id = 'currentVehicleFrame' + boxes.header.stamp = lidar_msg.header.stamp + + # Process YOLO detections + boxes_normal = np.array(results_normal[0].boxes.xywh.cpu()) if len(results_normal) > 0 else [] + conf_scores = np.array(results_normal[0].boxes.conf.cpu()) if len(results_normal) > 0 else [] + + for i, box in enumerate(boxes_normal): + # Skip low confidence detections + if conf_scores[i] < self.score_threshold: + continue + + # Calculate the 2D bounding box in the image + cx, cy, w, h = box + left = int(cx - w / 2) + right = int(cx + w / 2) + top = int(cy - h / 2) + bottom = int(cy + h / 2) + + # Find LiDAR points that project to this box + mask = ((projected_pts[:, 0] >= left) & (projected_pts[:, 0] <= right) & + (projected_pts[:, 1] >= top) & (projected_pts[:, 1] <= bottom)) + roi_pts = projected_pts[mask] + + # Ignore regions with too few points + if roi_pts.shape[0] < 5: + continue + + # Get the 3D points corresponding to the box + points_3d = roi_pts[:, 2:5] + points_3d = filter_depth_points(points_3d, max_depth_diff=0.8) + refined_cluster = refine_cluster(points_3d, np.mean(points_3d, axis=0), eps=0.15, min_samples=10) + refined_cluster = remove_ground_by_min_range(refined_cluster, z_range=0.1) + + if refined_cluster.shape[0] < 5: + continue + + # Create a point cloud from the filtered points + pcd = o3d.geometry.PointCloud() + pcd.points = o3d.utility.Vector3dVector(refined_cluster) + + # Get an oriented bounding box + obb = pcd.get_oriented_bounding_box() + refined_center = obb.center + dims = tuple(obb.extent) + R_lidar = obb.R.copy() + + # We are assuming that dims[0] is height and dims[2] is length of obb.extent + + # Transform from LiDAR to vehicle coordinates + refined_center_hom = np.append(refined_center, 1) + refined_center_vehicle_hom = self.T_l2v @ refined_center_hom + refined_center_vehicle = refined_center_vehicle_hom[:3] + + # Calculate rotation in vehicle frame + R_vehicle = self.T_l2v[:3, :3] @ R_lidar + # yaw, pitch, roll = R.from_matrix(R_vehicle).as_euler('zyx', degrees=False) + yaw = np.arctan2(R_vehicle[1, 0], R_vehicle[0, 0]) + + # Add the bounding box + boxes = add_bounding_box( + boxes=boxes, + frame_id='currentVehicleFrame', + stamp=lidar_msg.header.stamp, + x=refined_center_vehicle[0], + y=refined_center_vehicle[1], + z=refined_center_vehicle[2], + l=dims[2], # length + w=dims[1], # width + h=dims[0], # height + yaw=yaw, + conf_score=float(conf_scores[i]), + label=0 # person/pedestrian class + ) + + rospy.loginfo(f"Person detected at ({refined_center_vehicle[0]:.2f}, " + f"{refined_center_vehicle[1]:.2f}, {refined_center_vehicle[2]:.2f}) " + f"with score {conf_scores[i]:.2f}") + + # Publish the bounding boxes + rospy.loginfo(f"Publishing {len(boxes.boxes)} person bounding boxes") + self.pub.publish(boxes) + + def undistort_image(self, image, K, D): + """Undistort an image using the camera calibration parameters.""" + h, w = image.shape[:2] + newK, _ = cv2.getOptimalNewCameraMatrix(K, D, (w, h), 1, (w, h)) + + # Initialize undistortion maps if not already done + if self.undistort_map1 is None or self.undistort_map2 is None: + self.undistort_map1, self.undistort_map2 = cv2.initUndistortRectifyMap(K, D, R=None, + newCameraMatrix=newK, size=(w, h), + m1type=cv2.CV_32FC1) + + start = time.time() + undistorted = cv2.remap(image, self.undistort_map1, self.undistort_map2, interpolation=cv2.INTER_NEAREST) + end = time.time() + # print('--------undistort', end-start) + return undistorted, newK + + +if __name__ == '__main__': + try: + current_dir = os.path.dirname(__file__) + yaml_path = os.path.join(current_dir, '..', '..', 'knowledge', 'calibration', 'cameras.yaml') + node = YoloNode(yaml_path) + rospy.spin() + except rospy.ROSInterruptException: + pass diff --git a/GEMstack/onboard/planning/README.md b/GEMstack/onboard/planning/README.md new file mode 100644 index 000000000..5efb4fced --- /dev/null +++ b/GEMstack/onboard/planning/README.md @@ -0,0 +1,50 @@ +# Planning-A HW1 Document + +This document serves as an overview for integrating pedestrian yielder into longitudinal planner. It describes how parameters from `pedetrian_detecion.yaml` are used in the planning system along with references to the `longitudinal_planning.py` script and the `pedestrian_yield_logic.py` script. + +Details on the algorithm and demos are availavle at the link below:
+https://drive.google.com/drive/folders/1aSOWIrqXjf9-j6i1S_MJksATMyyoP31_?usp=sharing + + +## Contribution +Each member contributed to: +### longitudinal_planning.py Contributions + +| Algorithm | Contributor | +| :--------- | :-------------- | +| milestone | Simon (sk106) | +| dt | Rohit (srm17) | +| dx | Hansen (hl58) | + +### pedestrian_yield_logic.py Contributions + +| Algorithm | Contributor | +| :--------- | :------------------------------------------ | +| expert | Patrick (bohaowu2), Animesh (animesh8) | +| analytic | Henry (weigang2) | +| simulation | Yudai (yyamada2) | + + +## Configuration Details +The `pedetrian_detecion.yaml` file includes: +``` +args: + mode: 'real' + params: { + 'yielder': 'expert', # 'expert', 'analytic', or 'simulation' + 'planner': 'milestone', # 'milestone', 'dt', or 'dx' + 'desired_speed': 1.0, # m/s + 'acceleration': 0.75 # m/s2 + } +``` + + +## Usage +### pedetrian_detecion.yaml +Algorithm can be chosen from the above in this file. Also contains parameters for the logic. +### Execution: Simulator +`python3 main.py --variant=fake_sim launch/pedestrian_detection.yaml` +### Testing +- `testing/test_longitudinal_plan.py` +- `testing/test_yield_logic_analytic.ipynb` +- `testing/test_collision_detection.py` diff --git a/GEMstack/onboard/planning/blink_component.py b/GEMstack/onboard/planning/blink_component.py new file mode 100644 index 000000000..acd40ed0e --- /dev/null +++ b/GEMstack/onboard/planning/blink_component.py @@ -0,0 +1,92 @@ +from ..component import Component +from ..interface.gem import GEMInterface,GEMVehicleCommand,GEMVehicleReading +from ...state import AllState,VehicleIntent +import time +from typing import List + +TURN_OFF = 0 +TURN_LEFT = 1 +TURN_RIGHT = 2 + +class BlinkDistress(Component): + """Your control loop code should go here. You will use GEMVehicleCommand + to communicate with drive-by-wire system to control the vehicle's turn signals. + """ + def __init__(self, vehicle_interface : GEMInterface): + self.vehicle_interface = vehicle_interface + self.command = None + self.turn_state = TURN_OFF # Start with turn signals off + self.last_update_time = time.time() + + def rate(self): + """Requested update frequency, in Hz""" + return 0.5 + + def initialize(self): + """Run first""" + print("BlinkDistress Component Initialized.") + self.send_turn_command(TURN_OFF) + # pass + + def cleanup(self): + """Run last""" + print("Cleaning up... Turning off blinkers.") + self.send_turn_command(TURN_OFF) + # pass + + def state_inputs(self) -> List[str]: + """Returns the list of AllState inputs this component requires.""" + return ["intent"] + + def update(self, state: AllState): + """Run in a loop""" + # we need to set up a GEMVehicleCommand which encapsulates all commands that will be + # sent to the drive-by-wire system, simultaneously. To avoid doing arbitrary things + # to the vehicle, let's maintain the current values (e.g., accelerator, brake pedal, + # steering angle) from its current readings. + current_time = time.time() + if state.intent == 2: # check if halting + + if current_time - self.last_update_time >= 2: # Change signal every 2 seconds + if self.turn_state == TURN_OFF: + self.turn_state = TURN_LEFT + elif self.turn_state == TURN_LEFT: + self.turn_state = TURN_RIGHT + else: + self.turn_state = TURN_OFF + + self.send_turn_command(self.turn_state) + self.last_update_time = current_time + + # Read vehicle sensor data + vehicle_reading = self.vehicle_interface.get_reading() + print(f"Vehicle Speed: {vehicle_reading.speed:.2f} m/s") + print(f"Acceleration: {vehicle_reading.accelerator_pedal_position - vehicle_reading.brake_pedal_position:.2f} m/s²") + # command = self.vehicle_interface.command_from_reading() + # TODO: alter command to execute turn signals, then uncomment line below to send + # the command to vehicle + # self.vehicle_interface.send_command(command) + + def send_turn_command(self, turn_signal): + """Send the updated turn signal command to the vehicle""" + command = self.vehicle_interface.command_from_reading() + + # Update only turn signals, keeping other controls unchanged + if turn_signal == TURN_LEFT: + command.left_turn_signal = True + command.right_turn_signal = False + elif turn_signal == TURN_RIGHT: + command.left_turn_signal = False + command.right_turn_signal = True + else: + command.left_turn_signal = False + command.right_turn_signal = False + + self.vehicle_interface.send_command(command) + print(f"Turn Signal Set: {'LEFT' if turn_signal == TURN_LEFT else 'RIGHT' if turn_signal == TURN_RIGHT else 'OFF'}") + + + def healthy(self): + """Returns True if the element is in a stable state.""" + return True + diff --git a/GEMstack/onboard/planning/driving_logic_component.py b/GEMstack/onboard/planning/driving_logic_component.py new file mode 100644 index 000000000..157fb90ad --- /dev/null +++ b/GEMstack/onboard/planning/driving_logic_component.py @@ -0,0 +1,42 @@ +from typing import List +from ..component import Component +from ...state import AllState,VehicleIntent + +class DrivingLogic(Component): + # count of times blinked + """Base class for top-level components in the execution stack.""" + def rate(self) -> float: + """Returns the rate in Hz at which this component should be updated.""" + return .5 + def state_inputs(self) -> List[str]: + """Returns the list of AllState inputs this component requires.""" + return ['all'] + def state_outputs(self) -> List[str]: + """Returns the list of AllState outputs this component generates.""" + return ['intent'] + def healthy(self): + """Returns True if the element is in a stable state.""" + return True + def initialize(self): + """Initialize the component. This is called once before the first + update.""" + self.count = 0 + return + def cleanup(self): + """Cleans up resources used by the component. This is called once after + the last update.""" + pass + def update(self, state: AllState): + """Update the component.""" + + state.intent.intent = 2 + + return + def debug(self, item, value): + """Debugs a streaming value within this component""" + if hasattr(self, 'debugger'): + self.debugger.debug(item, value) + def debug_event(self, label): + """Debugs an event within this component""" + if hasattr(self, 'debugger'): + self.debugger.debug_event(label) \ No newline at end of file diff --git a/GEMstack/onboard/planning/pedestrian_yield_logic.py b/GEMstack/onboard/planning/pedestrian_yield_logic.py new file mode 100644 index 000000000..4f1936fa2 --- /dev/null +++ b/GEMstack/onboard/planning/pedestrian_yield_logic.py @@ -0,0 +1,625 @@ +from ...state import AllState,VehicleState,AgentState,AgentEnum,EntityRelation,EntityRelationEnum,ObjectFrameEnum +from ..component import Component +from typing import List,Dict,Union,Tuple +from scipy.optimize import minimize +import numpy as np +import math +import matplotlib.pyplot as plt +import matplotlib.patches as patches +from ...utils import settings + +################################################################################ +########## Collisiong Detection ################################################ +################################################################################ + +###################################### +##### Patrick and Animesh's Code ##### +###################################### +# Global variables +PEDESTRIAN_LENGTH = 0.5 +PEDESTRIAN_WIDTH = 0.5 + +VEHICLE_LENGTH = 3.5 +VEHICLE_WIDTH = 2 + +VEHICLE_BUFFER_X = 3.0 +VEHICLE_BUFFER_Y = 1.5 + +YIELD_BUFFER_Y = 1.0 +COMFORT_DECELERATION = 1.5 + +def detect_collision(curr_x: float, curr_y: float, curr_v: float, obj_x: float, obj_y: float, obj_v_x: float, obj_v_y: float, min_deceleration: float, max_deceleration: float, acceleration: float, max_speed: float) -> Tuple[bool, Union[float, List[float]]]: + """Detects if a collision will occur with the given object and return deceleration to avoid it or info for computing cruising speed""" + + vehicle_front = curr_x + VEHICLE_LENGTH + vehicle_back = curr_x + vehicle_left = curr_y + VEHICLE_WIDTH / 2 + vehicle_right = curr_y - VEHICLE_WIDTH / 2 + + pedestrian_front = obj_x + PEDESTRIAN_LENGTH / 2 + pedestrian_back = obj_x - PEDESTRIAN_LENGTH / 2 + pedestrian_left = obj_y + PEDESTRIAN_WIDTH / 2 + pedestrian_right = obj_y - PEDESTRIAN_WIDTH / 2 + + # Check if the object is in front of the vehicle + if vehicle_front > pedestrian_back: + if vehicle_back > pedestrian_front: + # The object is behind the vehicle + print("Object is behind the vehicle") + return False, 0.0 + if vehicle_right - VEHICLE_BUFFER_Y > pedestrian_left or vehicle_left + VEHICLE_BUFFER_Y < pedestrian_right: + # The object is to the side of the vehicle + print("Object is to the side of the vehicle") + return False, 0.0 + # The object overlaps with the vehicle's buffer + return True, max_deceleration + + if vehicle_right - VEHICLE_BUFFER_Y > pedestrian_left and obj_v_y <= 0: + # The object is to the right of the vehicle and moving away + print("Object is to the right of the vehicle and moving away") + return False, 0.0 + + if vehicle_left + VEHICLE_BUFFER_Y < pedestrian_right and obj_v_y >= 0: + # The object is to the left of the vehicle and moving away + print("Object is to the left of the vehicle and moving away") + return False, 0.0 + + if vehicle_front + VEHICLE_BUFFER_X >= pedestrian_back and (vehicle_right - VEHICLE_BUFFER_Y <= pedestrian_left and vehicle_left + VEHICLE_BUFFER_Y >= pedestrian_right): + # The object is in front of the vehicle and within the buffer + print("Object is in front of the vehicle and within the buffer") + return True, max_deceleration + + # Calculate the deceleration needed to avoid a collision + print("Object is in front of the vehicle and outside the buffer") + distance = pedestrian_back - vehicle_front + distance_with_buffer = pedestrian_back - vehicle_front - VEHICLE_BUFFER_X + + relative_v = curr_v - obj_v_x + if relative_v <= 0: + return False, 0.0 + + if obj_v_y == 0: + # The object is in front of the vehicle blocking it + deceleration = relative_v ** 2 / (2 * distance_with_buffer) + if deceleration > max_deceleration: + return True, max_deceleration + if deceleration < min_deceleration: + return False, 0.0 + + return True, deceleration + + if obj_v_y > 0: + # The object is to the right of the vehicle and moving towards it + time_to_get_close = (vehicle_right - VEHICLE_BUFFER_Y - YIELD_BUFFER_Y - pedestrian_left) / abs(obj_v_y) + time_to_pass = (vehicle_left + VEHICLE_BUFFER_Y + YIELD_BUFFER_Y - pedestrian_right) / abs(obj_v_y) + else: + # The object is to the left of the vehicle and moving towards it + time_to_get_close = (pedestrian_right - vehicle_left - VEHICLE_BUFFER_Y - YIELD_BUFFER_Y) / abs(obj_v_y) + time_to_pass = (pedestrian_left - vehicle_right + VEHICLE_BUFFER_Y + YIELD_BUFFER_Y) / abs(obj_v_y) + + time_to_accel_to_max_speed = (max_speed - curr_v) / acceleration + distance_to_accel_to_max_speed = (max_speed + curr_v - 2 * obj_v_x) * time_to_accel_to_max_speed / 2 #area of trapezoid + + if distance_to_accel_to_max_speed > distance_with_buffer: + # The object will reach the buffer before reaching max speed + time_to_buffer_when_accel = (-relative_v + (relative_v * relative_v + 2 * distance_with_buffer * acceleration) ** 0.5) / acceleration + else: + # The object will reach the buffer after reaching max speed + time_to_buffer_when_accel = time_to_accel_to_max_speed + (distance_with_buffer - distance_to_accel_to_max_speed) / (max_speed - obj_v_x) + + if distance_to_accel_to_max_speed > distance: + # We will collide before reaching max speed + time_to_collide_when_accel = (-relative_v + (relative_v * relative_v + 2 * distance * acceleration) ** 0.5) / acceleration + else: + # We will collide after reaching max speed + time_to_collide_when_accel = time_to_accel_to_max_speed + (distance - distance_to_accel_to_max_speed) / (max_speed - obj_v_x) + + if time_to_get_close > time_to_collide_when_accel: + # We can do normal driving and will pass the object before it gets in our way + print("We can do normal driving and will pass the object before it gets in our way") + return False, 0.0 + + if vehicle_front + VEHICLE_BUFFER_X >= pedestrian_back: + # We cannot move pass the pedestrian before it reaches the buffer from side + return True, max_deceleration + + if time_to_pass < time_to_buffer_when_accel: + # The object will pass through our front before we drive normally and reach it + print("The object will pass through our front before we drive normally and reach it") + return False, 0.0 + + distance_to_move = distance_with_buffer + time_to_pass * obj_v_x + + if curr_v**2/(2*distance_to_move) >= COMFORT_DECELERATION: + return True, curr_v**2/(2*distance_to_move) + + print("Calculating cruising speed") + return True, [distance_to_move, time_to_pass] + +######################## +##### Henry's Code ##### +######################## + +def detect_collision_analytical(r_pedestrain_x: float, r_pedestrain_y: float, p_vehicle_left_y_after_t: float, p_vehicle_right_y_after_t: float, lateral_buffer: float) -> Union[bool, str]: + """Detects if a collision will occur with the given object and return deceleration to avoid it. Analytical""" + if r_pedestrain_x < 0 and abs(r_pedestrain_y) > lateral_buffer: + return False + elif r_pedestrain_x < 0: + return 'max' + if r_pedestrain_y >= p_vehicle_left_y_after_t and r_pedestrain_y <= p_vehicle_right_y_after_t: + return True + + return False + + +def get_minimum_deceleration_for_collision_avoidance(curr_x: float, curr_y: float, curr_v: float, obj_x: float, obj_y: float, obj_v_x: float, obj_v_y: float, min_deceleration: float, max_deceleration: float) -> Tuple[bool, float]: + """Detects if a collision will occur with the given object and return deceleration to avoid it. Via Optimization""" + + vehicle_length = 3 + vehicle_width = 2 + + vehicle_buffer_x = 3.0 + vehicle_buffer_y = 1.0 + + obj_x = obj_x - curr_x + obj_y = obj_y - curr_y + + curr_x = curr_x - curr_x + curr_y = curr_y - curr_y + + vehicle_front = curr_x + vehicle_length + vehicle_buffer_x + vehicle_back = curr_x + vehicle_left = curr_y - vehicle_width / 2 + vehicle_right = curr_y + vehicle_width / 2 + + r_vehicle_front = vehicle_front - vehicle_front + r_vehicle_back = vehicle_back - vehicle_front + r_vehicle_left = vehicle_left - vehicle_buffer_y + r_vehicle_right = vehicle_right + vehicle_buffer_y + r_vehicle_v_x = curr_v + r_vehicle_v_y = 0 + + r_pedestrain_x = obj_x - vehicle_front + r_pedestrain_y = -obj_y + r_pedestrain_v_x = obj_v_x + r_pedestrain_v_y = -obj_v_y + + r_velocity_x_from_vehicle = r_vehicle_v_x - r_pedestrain_v_x + r_velocity_y_from_vehicle = r_vehicle_v_y - r_pedestrain_v_y + + t_to_r_pedestrain_x = (r_pedestrain_x - r_vehicle_front) / r_velocity_x_from_vehicle + + p_vehicle_left_y_after_t = r_vehicle_left + r_velocity_y_from_vehicle * t_to_r_pedestrain_x + p_vehicle_right_y_after_t = r_vehicle_right + r_velocity_y_from_vehicle * t_to_r_pedestrain_x + + collision_flag = detect_collision_analytical(r_pedestrain_x, r_pedestrain_y, p_vehicle_left_y_after_t, p_vehicle_right_y_after_t, vehicle_buffer_y) + if collision_flag == False: + print("No collision", curr_x, curr_y, r_pedestrain_x, r_pedestrain_y, r_vehicle_left, r_vehicle_right, p_vehicle_left_y_after_t, p_vehicle_right_y_after_t) + return 0.0 + elif collision_flag == 'max': + return max_deceleration + + print("Collision", curr_x, curr_y, r_pedestrain_x, r_pedestrain_y, r_vehicle_left, r_vehicle_right, p_vehicle_left_y_after_t, p_vehicle_right_y_after_t) + yaw = None + minimum_deceleration = None + if yaw is None: + if abs(r_velocity_y_from_vehicle) > 0.1: + if r_velocity_y_from_vehicle > 0.1: + # Vehicle Left would be used to yield + r_pedestrain_y_temp = r_pedestrain_y + abs(r_vehicle_left) + elif r_velocity_y_from_vehicle < -0.1: + # Vehicle Right would be used to yield + r_pedestrain_y_temp = r_pedestrain_y - abs(r_vehicle_right) + + softest_accleration = 2 * r_velocity_y_from_vehicle * (r_velocity_y_from_vehicle * r_pedestrain_x - r_velocity_x_from_vehicle * r_pedestrain_y_temp) / r_pedestrain_y_temp**2 + peak_y = -(r_velocity_x_from_vehicle * r_velocity_y_from_vehicle) / softest_accleration + # if the peak is within the position of the pedestrian, + # then it indicates the path had already collided with the pestrain, + # and so the softest acceleration should be the one the peak of the path is the same as the pedestrain's x position + # and the vehicle should be stopped exactly before the pedestrain's x position + if abs(peak_y) > abs(r_pedestrain_y_temp): + minimum_deceleration = abs(softest_accleration) + # else: the vehicle should be stopped exactly before the pedestrain's x position the same case as the pedestrain barely move laterally + + if minimum_deceleration is None: + minimum_deceleration = r_velocity_x_from_vehicle**2 / (2 * r_pedestrain_x) + else: + pass + + print("calculatedminimum_deceleration: ", minimum_deceleration) + return max(min(minimum_deceleration, max_deceleration), min_deceleration) + + +######################## +##### Yudai's Code ##### +######################## +class CollisionDetector: + """ + Simulation class to update positions of two rectangles (vehicle and pedestrian) + with velocities v1 and v2, performing collision detection at each time step. + All functions remain within the class, and variables defined in __init__ remain unchanged; + local copies are used during simulation. + """ + def __init__(self, x1, y1, t1, x2, y2, t2, v1, v2, total_time=10.0, desired_speed=2.0, acceleration=0.5): + + self.vehicle_x = x1 + self.vehicle_y = y1 + self.pedestrian_x = x2 + self.pedestrian_y = y2 + + # Vehicle parameters with buffer adjustments + self.vehicle_size_x = VEHICLE_LENGTH + self.vehicle_size_y = VEHICLE_WIDTH + self.vehicle_buffer_x = VEHICLE_BUFFER_X + self.vehicle_buffer_y = VEHICLE_BUFFER_Y * 2.0 # Double the buffer for both sides + + # Vehicle rectangle + self.x1 = self.vehicle_x + (self.vehicle_size_x + self.vehicle_buffer_x)*0.5 # Offset for buffer (remains constant) + self.y1 = self.vehicle_y + self.w1 = self.vehicle_size_x + self.vehicle_buffer_x # Increase width with buffer + self.h1 = self.vehicle_size_y + self.vehicle_buffer_y # Increase height with buffer + self.t1 = t1 + + # Pedestrian rectangle + self.x2 = x2 + self.y2 = y2 + self.w2 = 0.5 + self.h2 = 0.5 + self.t2 = t2 + + # Velocities are expected as [vx, vy] + self.v1 = v1 + self.v2 = v2 + + self.dt = 0.1 # seconds + self.total_time = total_time # seconds + + self.desired_speed = desired_speed + self.acceleration = acceleration + + def set_params(self, speed, acceleration): + self.desired_speed = speed + self.acceleration = acceleration + + def get_corners(self, x, y, w, h, theta): + """ + Returns the 4 corners of a rotated rectangle. + (x, y): center of rectangle + w, h: width and height of rectangle + theta: rotation angle in radians + """ + cos_t = math.cos(theta) + sin_t = math.sin(theta) + hw, hh = w / 2.0, h / 2.0 + + corners = np.array([ + [ hw * cos_t - hh * sin_t, hw * sin_t + hh * cos_t], + [-hw * cos_t - hh * sin_t, -hw * sin_t + hh * cos_t], + [-hw * cos_t + hh * sin_t, -hw * sin_t - hh * cos_t], + [ hw * cos_t + hh * sin_t, hw * sin_t - hh * cos_t] + ]) + + corners[:, 0] += x + corners[:, 1] += y + + return corners + + def get_axes(self, rect): + axes = [] + for i in range(len(rect)): + p1 = rect[i] + p2 = rect[(i + 1) % len(rect)] + edge = p2 - p1 + normal = np.array([-edge[1], edge[0]]) + norm = np.linalg.norm(normal) + if norm: + normal /= norm + axes.append(normal) + return axes + + def project(self, rect, axis): + dots = np.dot(rect, axis) + return np.min(dots), np.max(dots) + + def sat_collision(self, rect1, rect2): + """ + Determines if two convex polygons (rectangles) collide using the + Separating Axis Theorem (SAT). + rect1 and rect2 are numpy arrays of shape (4,2) representing their corners. + """ + axes1 = self.get_axes(rect1) + axes2 = self.get_axes(rect2) + + for axis in axes1 + axes2: + min1, max1 = self.project(rect1, axis) + min2, max2 = self.project(rect2, axis) + if max1 < min2 or max2 < min1: + return False + return True + + def plot_rectangles(self, rect1, rect2, collision, ax): + """ + Plot two rectangles on a provided axis and indicate collision by color. + """ + color = 'red' if collision else 'blue' + for rect in [rect1, rect2]: + polygon = patches.Polygon(rect, closed=True, edgecolor=color, fill=False, linewidth=2) + ax.add_patch(polygon) + ax.scatter(rect[:, 0], rect[:, 1], color=color, zorder=3) + ax.set_title(f"Collision: {'Yes' if collision else 'No'}") + + def run(self, is_displayed=False): + collision_distance = -1 + steps = int(self.total_time / self.dt) + 1 + + # Create local variables for positions; these will be updated + # without modifying the __init__ attributes. + current_x1 = self.x1 + current_y1 = self.y1 + current_x2 = self.x2 + current_y2 = self.y2 + current_v1 = self.v1[0] + + if is_displayed: + plt.ion() # Turn on interactive mode + fig, ax = plt.subplots(figsize=(10,5)) + + for i in range(steps): + t_sim = i * self.dt + + # Compute rectangle corners using the local positional variables. + rect1 = self.get_corners(current_x1, current_y1, self.w1, self.h1, self.t1) + rect2 = self.get_corners(current_x2, current_y2, self.w2, self.h2, self.t2) + + # Perform collision detection. + collision = self.sat_collision(rect1, rect2) + + if is_displayed: + # Plot the current step. + ax.clear() + self.plot_rectangles(rect1, rect2, collision, ax) + ax.set_aspect('equal') + ax.grid(True, linestyle='--', alpha=0.5) + ax.set_xlim(self.vehicle_x - 5, self.vehicle_x + 20) + ax.set_ylim(self.vehicle_y -5, self.vehicle_y +5) + + # Draw an additional rectangle (vehicle body) at the vehicle's center. + rect_vehiclebody = patches.Rectangle( + (current_x1 - (self.vehicle_size_x + self.vehicle_buffer_x)*0.5, current_y1 - self.vehicle_size_y * 0.5), + self.w1 - self.vehicle_buffer_x, + self.h1 - self.vehicle_buffer_y, + edgecolor='green', + fill=False, + linewidth=2, + linestyle='--' + ) + ax.add_patch(rect_vehiclebody) + + ax.text(0.01, 0.99, f"t = {t_sim:.1f}s", fontsize=12, transform=ax.transAxes, verticalalignment='top') + plt.draw() + + # Pause briefly to simulate real-time updating. + plt.pause(self.dt * 0.05) + + # Stop simulation if collision is detected. + if collision: + current_vehicle_x = current_x1 - (self.vehicle_size_x + self.vehicle_buffer_x) * 0.5 + current_vehicle_y = current_y1 + collision_distance = current_vehicle_x - self.vehicle_x + break + + # Update the vehicle's speed if it is not at the desired speed. + next_v = current_v1 + self.acceleration * self.dt + # Accelerating: Check if the vehicle is about to exceed the desired speed. + if next_v > self.desired_speed and current_v1 <= self.desired_speed: + current_v1 = self.desired_speed + # Decelerating: Check if the vehicle is about to fall below the desired speed. + elif next_v < self.desired_speed and current_v1 >= self.desired_speed: + current_v1 = self.desired_speed + else: + current_v1 = next_v + + current_v1 = 0.0 if current_v1 < 0.0 else current_v1 + + # Update local positions based on velocities. + current_x1 += current_v1 * self.dt + current_y1 += self.v1[1] * self.dt + current_x2 += self.v2[0] * self.dt + current_y2 += self.v2[1] * self.dt + + if is_displayed: + plt.ioff() + plt.show(block=True) + + # print("Collision distance:", collision_distance) + + return collision_distance + +def calculate_yielding_parameters(curr_x, curr_y, curr_v, a_x, a_y, a_v, desired_speed, acceleration, deceleration, max_deceleration, yield_deceleration): + """ + Calculate yielding parameters using Yudai's simulation code. + Returns a tuple (output_decel, output_dist, output_speed). + """ + + # Simulate if a collision will occur when the vehicle accelerates to the desired speed. + sim = CollisionDetector(curr_x, curr_y, 0, a_x, a_y, 0, curr_v, a_v, total_time=10.0, desired_speed=desired_speed, acceleration=acceleration) + collision_distance = sim.run() + + # No collision detected: use default deceleration and desired speed. + if collision_distance < 0: + print("No collision detected.") + output_decel = deceleration + output_speed = desired_speed + output_dist = collision_distance + + # Collision detected: try to find a yielding speed. + else: + print("Collision detected. Try to find yielding speed.") + output_decel = None + output_speed = None + collision_distance_after_yield = -1 + + # Generate yielding speeds from desired speed down to a low speed. + yield_speed = [v for v in np.arange(desired_speed, 0.1, -0.25)] + for v in yield_speed: + # If trying to accelerate (v > current vehicle speed) + if v > curr_v[0]: + sim.set_params(v, acceleration) + # Otherwise apply deceleration to yield + else: + sim.set_params(v, yield_deceleration * -1.0) + collision_distance_after_yield = sim.run() + if collision_distance_after_yield < 0: + print(f"Yielding at speed: {v}") + output_decel = yield_deceleration + output_dist = collision_distance + output_speed = v + break + + # Collision detected for any yielding speed: brake to avoid collision. + if collision_distance_after_yield >= 0: + print("The vehicle is Stopping.") + brake_deceleration = max(deceleration, curr_v[0]**2 / (2 * (collision_distance))) + if brake_deceleration > max_deceleration: + brake_deceleration = max_deceleration + output_decel = brake_deceleration + output_dist = collision_distance + output_speed = 0.0 + + return output_decel, output_dist, output_speed + + + + + + + + + + + + + + + + +################################################################################ +########## Pedestrian Yielder ################################################## +################################################################################ + +class PedestrianYielder(Component): + """Yields for all pedestrians in the scene. + + Result is stored in the relations graph. + """ + def __init__(self, mode : str = 'real', params : dict = {}): + # Planner mode + self.mode = mode + self.yielder = params["yielder"] + self.planner = params["planner"] + self.acceleration = params["acceleration"] + self.desired_speed = params["desired_speed"] + + # Update current.yaml settings with the given parameters in pedestrian_detection.yaml + settings.set("planning.longitudinal_plan.mode", self.mode) + settings.set("planning.longitudinal_plan.yielder", self.yielder) + settings.set("planning.longitudinal_plan.planner", self.planner) + settings.set("planning.longitudinal_plan.acceleration", self.acceleration) + settings.set("planning.longitudinal_plan.desired_speed", self.desired_speed) + + self.min_deceleration = settings.get("planning.longitudinal_plan.min_deceleration") + self.max_deceleration = settings.get("planning.longitudinal_plan.max_deceleration") + self.deceleration = settings.get("planning.longitudinal_plan.deceleration") + self.yield_deceleration = settings.get("planning.longitudinal_plan.yield_deceleration") + + def rate(self): + return None + def state_inputs(self): + return ['all'] + def state_outputs(self): + return ['relations'] + def update(self, state : AllState) -> List[EntityRelation]: + res = [] + vehicle = state.vehicle + agents = state.agents + + # Position in vehicle frame (Start (0,0) to (15,0)) + curr_x = vehicle.pose.x + curr_y = vehicle.pose.y + curr_v = vehicle.v + + for n,a in agents.items(): + if a.type == AgentEnum.PEDESTRIAN: + """ + yield_decel : float # Deceleration at which obj1 yields to obj2 + yield_dist : float # Distance at which obj1 yields to obj2 + yield_speed : float # Speed at which obj1 yields to obj2 + """ + output_decel, output_dist, output_speed = None, None, None + + # Get the pedestrian's position and velocity + a_x, a_y = a.pose.x, a.pose.y + a_v_x, a_v_y = a.velocity[0], a.velocity[1] # Pedestrian speed vector + + # If the pedestrian's frame is ABSOLUTE, convert the vehicle's frame to ABSOLUTE. + if a.pose.frame == ObjectFrameEnum.ABSOLUTE_CARTESIAN: + curr_x = curr_x + state.start_vehicle_pose.x + curr_y = curr_y + state.start_vehicle_pose.y + + # If the pedestrian's frame is CURRENT, convert the pedestrian's frame to START. + elif a.pose.frame == ObjectFrameEnum.CURRENT: + a_x = a.pose.x + curr_x + a_y = a.pose.y + curr_y + a_v_x = a_v_x - curr_v + + ########################## + ##### Yielding Part ###### + ########################## + + # Switch between different yielder methods + if self.yielder == 'expert': + ###################################### + ##### Patrick and Animesh's Code ##### + ###################################### + detected, deceleration = detect_collision(curr_x, curr_y, curr_v, a_x, a_y, a_v_x, a_v_y, self.min_deceleration, self.max_deceleration, self.acceleration, self.desired_speed) + if isinstance(deceleration, list): + print("@@@@@ INPUT", deceleration) + time_collision = deceleration[1] + distance_collision = deceleration[0] + b = 3*time_collision - 2*curr_v + c = curr_v**2 - 3*distance_collision + output_speed = (-b + (b**2 - 4*c)**0.5)/2 + output_decel = 1.5 + output_dist = distance_collision + else: + if detected and deceleration > 0: + output_speed = 0 # Brake to Stop + output_decel = deceleration + output_dist = None + + elif self.yielder == 'analytic': + ######################### + ##### Henry's Code ###### + ######################### + deceleration = get_minimum_deceleration_for_collision_avoidance(curr_x, curr_y, curr_v, a_x, a_y, a_v_x, a_v_y, self.min_deceleration, self.max_deceleration) + if deceleration > 0: + output_decel = deceleration + output_speed = 0 + output_dist = None + + elif self.yielder == 'simulation': + ######################## + ##### Yudai's Code ##### + ######################## + output_decel, output_dist, output_speed = calculate_yielding_parameters(curr_x, curr_y, [curr_v, 0], a_x, a_y, [a_v_x, a_v_y], self.desired_speed, self.acceleration, self.deceleration, self.max_deceleration, self.yield_deceleration) + + else: + raise ValueError(f"Yielder {self.yielder} is not supported.") + + # Add the relation to the list + res.append(EntityRelation(type=EntityRelationEnum.YIELDING, obj1='', obj2=n, + yield_decel=output_decel, + yield_dist=output_dist, + yield_speed=output_speed)) + + return res diff --git a/GEMstack/onboard/planning/pure_pursuit.py b/GEMstack/onboard/planning/pure_pursuit.py index e4b6f4f4e..3657d1779 100644 --- a/GEMstack/onboard/planning/pure_pursuit.py +++ b/GEMstack/onboard/planning/pure_pursuit.py @@ -45,7 +45,7 @@ def set_path(self, path : Path): self.path_arg = path if len(path.points[0]) > 2: path = path.get_dims([0,1]) - if not isinstance(path,Trajectory): + if not isinstance(path, Trajectory): self.path = path.arc_length_parameterize() self.trajectory = None self.current_traj_parameter = 0.0 @@ -164,7 +164,7 @@ def compute(self, state : VehicleState, component : Component = None): print("Feedforward accel: " + str(feedforward_accel) + " m/s^2") else: #decay speed when crosstrack error is high - desired_speed *= np.exp(-abs(ct_error)*0.4) + desired_speed *= np.exp(-abs(ct_error)*0.8) if desired_speed > self.speed_limit: desired_speed = self.speed_limit output_accel = self.pid_speed.advance(e = desired_speed - speed, t = t, feedforward_term=feedforward_accel) @@ -178,6 +178,8 @@ def compute(self, state : VehicleState, component : Component = None): component.debug('desired speed (m/s)',desired_speed) component.debug('feedforward accel (m/s^2)',feedforward_accel) component.debug('output accel (m/s^2)',output_accel) + component.debug('current yaw (rad)', curr_yaw) + component.debug('current speed (m/s)', speed) print("Output accel: " + str(output_accel) + " m/s^2") if output_accel > self.max_accel: @@ -187,6 +189,11 @@ def compute(self, state : VehicleState, component : Component = None): output_accel = -self.max_decel self.t_last = t + + if desired_speed == 0 and speed == 0 and output_accel < 0.0: + print("Stopping. Set accel", output_accel, "to 0") + output_accel = 0.0 + return (output_accel, f_delta) diff --git a/GEMstack/scripts/convert_to_rosbag.py b/GEMstack/scripts/convert_to_rosbag.py new file mode 100644 index 000000000..791ef6e0a --- /dev/null +++ b/GEMstack/scripts/convert_to_rosbag.py @@ -0,0 +1,171 @@ +#!/usr/bin/env python3 + +import os +import rosbag +import cv2 +import numpy as np +from cv_bridge import CvBridge +from sensor_msgs.msg import Image, PointCloud2 +import sensor_msgs.point_cloud2 as pc2 +import glob +from datetime import datetime +import time +import rospy +import std_msgs.msg +import argparse + +def get_matching_files(dir): + """Get files that have corresponding data in all three formats""" + # Get sorted lists of files + png_files = sorted(glob.glob(os.path.join(dir, 'color*.png'))) + tif_files = sorted(glob.glob(os.path.join(dir, 'depth*.tif'))) + npz_files = sorted(glob.glob(os.path.join(dir, 'lidar*.npz'))) + + print(f"Found {len(png_files)} PNG files") + print(f"Found {len(tif_files)} TIF files") + print(f"Found {len(npz_files)} NPZ files") + + # Extract numbers from filenames + def get_number(filename): + return int(''.join(filter(str.isdigit, os.path.basename(filename)))) + + # Create dictionaries with numbers as keys + png_dict = {get_number(f): f for f in png_files} + tif_dict = {get_number(f): f for f in tif_files} + npz_dict = {get_number(f): f for f in npz_files} + + # Find common numbers + common_numbers = set(png_dict.keys()) & set(tif_dict.keys()) & set(npz_dict.keys()) + print(f"\nFound {len(common_numbers)} matching frame numbers") + + # Get matching files in sorted order + common_numbers = sorted(common_numbers) + matching_pngs = [png_dict[n] for n in common_numbers] + matching_tifs = [tif_dict[n] for n in common_numbers] + matching_npzs = [npz_dict[n] for n in common_numbers] + + return matching_pngs, matching_tifs, matching_npzs + +def create_rosbag_from_data( + dir, + output_bag_path, + frame_interval +): + # Initialize CV bridge + bridge = CvBridge() + + # Initialize ROS node + rospy.init_node('bag_creator', anonymous=True) + + # Get matching files + png_files, tif_files, npz_files = get_matching_files(dir) + + print(f"Found {len(png_files)} matching files in all three formats") + + if len(png_files) == 0: + raise ValueError("No matching files found!") + + # Create a new bag file + with rosbag.Bag(output_bag_path, 'w') as bag: + # Start time for the messages + start_time = rospy.Time.from_sec(time.time()) + message_count = 0 + + for idx, (png_file, tif_file, npz_file) in enumerate(zip(png_files, tif_files, npz_files)): + # Calculate timestamp for this frame + timestamp = rospy.Time.from_sec(start_time.to_sec() + idx * (1/frame_interval)) + + try: + # Process PNG image + png_img = cv2.imread(png_file) + if png_img is not None: + png_msg = bridge.cv2_to_imgmsg(png_img, encoding="bgr8") + png_msg.header.stamp = timestamp + png_msg.header.frame_id = "camera_rgb" + bag.write('/camera/rgb/image_raw', png_msg, timestamp) + message_count += 1 + else: + print(f"Warning: Could not read PNG file: {png_file}") + + # Process TIF image + tif_img = cv2.imread(tif_file, -1) # -1 to preserve original depth + if tif_img is not None: + tif_msg = bridge.cv2_to_imgmsg(tif_img, encoding="passthrough") + tif_msg.header.stamp = timestamp + tif_msg.header.frame_id = "camera_depth" + bag.write('/camera/depth/image_raw', tif_msg, timestamp) + message_count += 1 + else: + print(f"Warning: Could not read TIF file: {tif_file}") + + # Process pointcloud NPZ + pc_data = np.load(npz_file) + points = pc_data['arr_0'] # Using 'arr_0' based on the provided files' + + # Create pointcloud message + header = std_msgs.msg.Header() + header.stamp = timestamp + header.frame_id = "velodyne" + + fields = [ + pc2.PointField('x', 0, pc2.PointField.FLOAT32, 1), + pc2.PointField('y', 4, pc2.PointField.FLOAT32, 1), + pc2.PointField('z', 8, pc2.PointField.FLOAT32, 1) + ] + + pc_msg = pc2.create_cloud(header, fields, points) + bag.write('/velodyne_points', pc_msg, timestamp) + message_count += 1 + + except Exception as e: + print(f"Error processing frame {idx}: {str(e)}") + continue + + if idx % 10 == 0: + print(f"Processed {idx} frames") + + print(f"Total messages written to bag: {message_count}") + +if __name__ == "__main__": + #This initializes the parser and sets the parameters that the user will be asked to provide in the terminal + parser = argparse.ArgumentParser( + description='A script to convert data gathered by cameras and lidar sensors to ros .bag messages' + ) + + parser.add_argument( + 'files_directory', type = str, + help = 'The path to the directory with all the rgb images, depth maps, and point clouds. The file formats must be PNG, TIF, and NPZ, respectively' + ) + + parser.add_argument( + 'output_bag', type = str, + help = 'The path to the directory where the bag file will be saved' + ) + + parser.add_argument( + 'rate', type = int, + help = 'The rate at which the data is collected in Hz' + ) + args = parser.parse_args() + directory = args.files_directory + output_bag = args.output_bag + rate = args.rate + # Example directories below: + #directory = "/home/username/host/CS588/GEMstack/data/data_sample/data/" + #output_bag = "/home/username/host/CS588/GEMstack/data/data_sample/data/output.bag" + + try: + create_rosbag_from_data( + directory, + output_bag, + rate + ) + print("Successfully created ROS bag file!") + + # Verify bag contents + print("\nBag file contents:") + info_cmd = f"rosbag info {output_bag}" + os.system(info_cmd) + + except Exception as e: + print(f"Error creating ROS bag: {str(e)}") diff --git a/GEMstack/scripts/visualization.py b/GEMstack/scripts/visualization.py new file mode 100644 index 000000000..3ff9dada7 --- /dev/null +++ b/GEMstack/scripts/visualization.py @@ -0,0 +1,191 @@ +import json +import os +import time +from klampt import vis +from klampt.model.trajectory import Trajectory +import matplotlib.pyplot as plt +from ..onboard.visualization.klampt_visualization import KlamptVisualization +from ..onboard.visualization.mpl_visualization import MPLVisualization + +LOG_DIR = "logs" +BEHAVIOR_FILE = "behavior.json" + +def select_log_folder(): + log_folders = [f for f in os.listdir(LOG_DIR) if os.path.isdir(os.path.join(LOG_DIR, f))] + if not log_folders: + print("\033[91mNo log folders found.\033[0m") + return None + + print("\n\033[94mAvailable log folders:\033[0m") + for idx, folder in enumerate(log_folders): + print(f"{idx + 1}. {folder}") + + while True: + try: + choice = int(input("\n\033[93mEnter the number of the log folder to use:\033[0m ")) - 1 + if 0 <= choice < len(log_folders): + return os.path.join(LOG_DIR, log_folders[choice]) + print("\033[91mInvalid selection. Please enter a valid number.\033[0m") + except ValueError: + print("\033[91mPlease enter a number.\033[0m") + +def select_visualizer(): + print("\n\033[94mChoose a visualization method:\033[0m") + print("1. Klampt (3D visualization)") + print("2. MPL (Matplotlib 2D visualization)") + + while True: + try: + choice = int(input("\n\033[93mEnter 1 or 2:\033[0m ")) + if choice in [1, 2]: + return choice + print("\033[91mInvalid selection. Please enter 1 or 2.\033[0m") + except ValueError: + print("\033[91mPlease enter a valid number.\033[0m") + +# Load and extract pedestrian and vehicle data +def extract_behavior_data(log_dir): + behavior_path = os.path.join(log_dir, BEHAVIOR_FILE) + if not os.path.exists(behavior_path): + print(f"\033[91mError: {behavior_path} not found.\033[0m") + return None, None, None, None, None, None, None, None + + with open(behavior_path, "r") as f: + data = [json.loads(line) for line in f] + + pedestrian_paths = {} + pedestrian_times = {} + vehicle_path = [] + vehicle_times = [] + speeds = [] + accelerators = [] + brakes = [] + steering_angles = [] + + for entry in data: + time_stamp = entry.get("time", 0) + + # Extract pedestrian data + if "agents" in entry: + for agent_id, agent in entry["agents"].items(): + agent_data = agent.get("data", {}) + if agent_data.get("type") == 3: # Type 3 = pedestrian + pose = agent_data.get("pose", {}) + x, y = pose.get("x", 0), pose.get("y", 0) + + if agent_id not in pedestrian_paths: + pedestrian_paths[agent_id] = [] + pedestrian_times[agent_id] = [] + + pedestrian_paths[agent_id].append((x, y)) + pedestrian_times[agent_id].append(time_stamp) + + # Extract vehicle data + if "vehicle" in entry: + vehicle_data = entry["vehicle"].get("data", {}) + pose = vehicle_data.get("pose", {}) + x, y = pose.get("x", 0), pose.get("y", 0) + + vehicle_path.append((x, y)) + vehicle_times.append(time_stamp) + speeds.append(vehicle_data.get("v", 0)) + accelerators.append(vehicle_data.get("accelerator_pedal_position", 0)) + brakes.append(vehicle_data.get("brake_pedal_position", 0)) + steering_angles.append(vehicle_data.get("steering_wheel_angle", 0)) + + return pedestrian_paths, pedestrian_times, vehicle_path, vehicle_times, speeds, accelerators, brakes, steering_angles + +# Klampt 3D Visualization +def visualize_with_klampt(pedestrian_paths, pedestrian_times, vehicle_path): + """Uses Klampt to visualize pedestrian and vehicle paths.""" + vis.init("PyQt6") + vis.setWindowTitle("Pedestrian and Vehicle Path Visualization") + + klampt_vis = KlamptVisualization(vehicle_interface=None, rate=20.0) + + for agent_id, path in pedestrian_paths.items(): + if len(path) < 2: + continue + + times = pedestrian_times[agent_id] + path_3d = [[float(x), float(y), 0.0] for x, y in path] + + trajectory = Trajectory(times, path_3d) + vis.add(agent_id, trajectory, color=(0, 1, 0, 1), width=2) + + # if vehicle_path: + # vehicle_x, vehicle_y = zip(*vehicle_path) + # vehicle_tuples = [[float(x), float(y), 0.0] for x, y in zip(vehicle_x, vehicle_y)] + # vis.add("Vehicle Path", vehicle_tuples, color=(1, 0, 0, 1), width=2) + + klampt_vis.initialize() + vis.show() + + while vis.shown(): + time.sleep(0.05) + + klampt_vis.cleanup() + vis.kill() + +# MPL 2D Visualization +def visualize_with_mpl(pedestrian_paths, pedestrian_times, vehicle_path, vehicle_data): + vis = MPLVisualization(rate=10.0) + vis.initialize() + + fig, axs = vis.fig, vis.axs + axs[0].clear() + axs[1].clear() + + # Left Plot: Pedestrian & Vehicle Trajectories + axs[0].set_xlabel("X Position") + axs[0].set_ylabel("Y Position") + axs[0].set_title("Pedestrian & Vehicle Trajectories") + + for agent_id, path in pedestrian_paths.items(): + path_x, path_y = zip(*path) + axs[0].plot(path_x, path_y, linestyle='-', marker='o', label=f"Pedestrian {agent_id}") + + # if vehicle_path: + # vehicle_x, vehicle_y = zip(*vehicle_path) + # axs[0].plot(vehicle_x, vehicle_y, linestyle='-', marker='s', color='red', label="Vehicle Path") + + axs[0].legend() + + # Right Plot: Vehicle Controls Over Time + times, speeds, accelerators, brakes, steering_angles = vehicle_data + axs[1].set_xlabel("Time (s)") + axs[1].set_title("Vehicle Controls Over Time") + + axs[1].plot(times, speeds, label="Speed (m/s)", color="blue") + axs[1].plot(times, accelerators, label="Accelerator (%)", color="green") + axs[1].plot(times, brakes, label="Brake (%)", color="red") + axs[1].plot(times, steering_angles, label="Steering Angle", color="purple") + axs[1].legend() + + fig.canvas.draw_idle() + fig.canvas.flush_events() + plt.show(block=True) + + vis.cleanup() + +# Main Execution +if __name__ == "__main__": + visualizer_choice = select_visualizer() + selected_log_folder = select_log_folder() + + if selected_log_folder: + print(f"\n\033[94mLoading behavior data from:\033[0m {selected_log_folder}") + data = extract_behavior_data(selected_log_folder) + + pedestrian_paths, pedestrian_times, vehicle_path, vehicle_times, speeds, accelerators, brakes, steering_angles = data + vehicle_data = (vehicle_times, speeds, accelerators, brakes, steering_angles) + + if pedestrian_paths or vehicle_path: + if visualizer_choice == 1: + print("\033[92mUsing Klampt for visualization...\033[0m") + visualize_with_klampt(pedestrian_paths, pedestrian_times, vehicle_path) + else: + print("\033[92mUsing MPL (Matplotlib) for visualization...\033[0m") + visualize_with_mpl(pedestrian_paths, pedestrian_times, vehicle_path, vehicle_data) + else: + print("\033[91mNo pedestrian or vehicle data found.\033[0m") diff --git a/GEMstack/state/relations.py b/GEMstack/state/relations.py index 465d4e657..c24e1bc22 100644 --- a/GEMstack/state/relations.py +++ b/GEMstack/state/relations.py @@ -23,6 +23,9 @@ class EntityRelation: type : EntityRelationEnum obj1 : str # Named object in the scene. '' indicates ego-vehicle obj2 : str # Named object in the scene. '' indicates ego-vehicle + yield_dist : float # Distance at which obj1 yields to obj2 + yield_speed : float # Speed at which obj1 yields to obj2 + yield_decel : float # Deceleration at which obj1 yields to obj2 class EntityRelationGraph: diff --git a/GEMstack/state/trajectory.py b/GEMstack/state/trajectory.py index af0f70122..1b305b790 100644 --- a/GEMstack/state/trajectory.py +++ b/GEMstack/state/trajectory.py @@ -169,6 +169,7 @@ def trim(self, start : float, end : float) -> Path: class Trajectory(Path): """A timed, piecewise linear path.""" times : List[float] + velocities : Optional[List[float]] = None def domain(self) -> Tuple[float,float]: """Returns the time parameter domain""" diff --git a/GEMstack/utils/analysis.py b/GEMstack/utils/analysis.py new file mode 100644 index 000000000..0a354a6ca --- /dev/null +++ b/GEMstack/utils/analysis.py @@ -0,0 +1,153 @@ +""" +Log Analysis Tool + +This program allows users to analyze CSV files stored in log directories. Users can: +- Select a log directory from the `./logs` folder. +- Choose a CSV file within the selected directory. +- Select specific columns to analyze. +- Choose an analysis method such as MSE, RMS, Mean, or Standard Deviation. +- Define a custom lambda function for analysis. +- Save the results in the default log directory or specify a custom path. + +Usage: +1. Run the script: `python ./GEMstack/utils/analysis.py` +2. Follow the prompts to: + - Select a log directory. + - Choose a CSV file to analyze. + - Select the columns for analysis. + - Pick a predefined analysis method or define a custom lambda function. + - Save the results. + +Output: +- The analysis results are saved in CSV format, with column names included, in the chosen directory. + +""" + +import os +import pandas as pd +import numpy as np +from datetime import datetime + +def list_log_directories(): + logs_path = "./logs" + if not os.path.exists(logs_path): + print("Logs directory does not exist.") + return [] + + directories = [d for d in os.listdir(logs_path) if os.path.isdir(os.path.join(logs_path, d))] + return directories + +def choose_directory(directories): + if not directories: + print("No log directories found.") + return None + + print("Available log directories:") + for i, dir_name in enumerate(directories): + print(f"{i + 1}. {dir_name}") + + choice = int(input("Select a directory by number: ")) - 1 + if 0 <= choice < len(directories): + return os.path.join("./logs", directories[choice]) + else: + print("Invalid choice.") + return None + +def choose_csv_file(log_dir): + files = [f for f in os.listdir(log_dir) if f.endswith(".csv")] + if not files: + print("No CSV files found in the selected directory.") + return None + + print("Available CSV files:") + for i, file in enumerate(files): + print(f"{i + 1}. {file}") + + choice = int(input("Select a CSV file by number: ")) - 1 + if 0 <= choice < len(files): + return os.path.join(log_dir, files[choice]) + else: + print("Invalid choice.") + return None + +def load_csv(csv_path): + if not os.path.exists(csv_path): + print("CSV file not found.") + return None + + df = pd.read_csv(csv_path) + print("CSV file loaded successfully.") + print("Available columns:", list(df.columns)) + return df + +def choose_columns(df): + selected_columns = input("Enter column names to analyze (comma separated): ").split(',') + selected_columns = [col.strip() for col in selected_columns if col.strip() in df.columns] + if not selected_columns: + print("No valid columns selected.") + return None + return df[selected_columns] + +def analyze_data(df, log_dir): + methods = { + "1": ("Mean Squared Error (MSE)", lambda x: np.mean(np.square(x))), + "2": ("Root Mean Square (RMS)", lambda x: np.sqrt(np.mean(np.square(x)))), + "3": ("Mean", np.mean), + "4": ("Standard Deviation", np.std), + "5": ("Custom Lambda Function", None) + } + + print("Available analysis methods:") + for key, (name, _) in methods.items(): + print(f"{key}. {name}") + + choice = input("Select a method by number: ") + if choice in methods: + if choice == "5": + function_str = input("Enter a lambda function (e.g., lambda x: np.max(x) - np.min(x)): ").strip() + try: + func = eval(function_str, {"np": np}) + result = df.apply(func) + except Exception as e: + print(f"Invalid function: {e}") + return + else: + method_name, method_func = methods[choice] + print(f"Applying {method_name}...") + result = df.apply(method_func) + + print("Analysis result:") + print(result.to_string(header=True, index=True)) + + save_path = input("Enter a path to save the result (press Enter to save in the chosen log directory): ") + if not save_path: + timestamp = datetime.now().strftime("%Y-%m-%d_%H-%M-%S") + save_path = os.path.join(log_dir, f"analysis_result_{timestamp}.csv") + + result.to_frame().T.to_csv(save_path, index=False, header=True) + print(f"Analysis result saved to {save_path}") + else: + print("Invalid choice.") + +def main(): + directories = list_log_directories() + log_dir = choose_directory(directories) + if not log_dir: + return + + csv_path = choose_csv_file(log_dir) + if not csv_path: + return + + df = load_csv(csv_path) + if df is None: + return + + df_selected = choose_columns(df) + if df_selected is None: + return + + analyze_data(df_selected, log_dir) + +if __name__ == "__main__": + main() diff --git a/GEMstack/utils/log_plot.py b/GEMstack/utils/log_plot.py new file mode 100644 index 000000000..e2b11753f --- /dev/null +++ b/GEMstack/utils/log_plot.py @@ -0,0 +1,148 @@ +import matplotlib.pyplot as plt +import pandas as pd +import os +import numpy as np + +# Most of the code in this file is copied from ./tuning_logs/log_plot.py by Mikayel Aramyan (mikayel2) + +def create_plot(t, actual, desired, xlabel, ylabel, title, legend, save_path=None): + plt.figure() + plt.plot(t, actual) + plt.plot(t, desired) + overshoot = np.max(np.array(actual) - np.array(desired)) + rmse = np.sqrt(np.mean((np.array(actual) - np.array(desired))**2)) + print(f'{title} - Maximum Overshoot: {overshoot}, RMSE: {rmse}') + plt.xlabel(xlabel) + plt.ylabel(ylabel) + plt.title(f'{title} (Max Overshoot: {overshoot:.2f}, RMSE: {rmse:.2f})') + plt.legend(legend) + plt.grid(True) + if save_path: + plt.savefig(save_path, dpi=600) + plt.close() + +def create_error_plot(t, error, xlabel, ylabel, title, save_path=None): + plt.figure() + plt.plot(t, error) + plt.xlabel(xlabel) + plt.ylabel(ylabel) + plt.title(title) + plt.grid(True) + if save_path: + plt.savefig(save_path, dpi=600) + plt.close() + +def main(log_folder): + if log_folder is None: + return + df = pd.read_csv(log_folder + '/PurePursuitTrajectoryTracker_debug.csv') + save_figures =True + + plots_folder = os.path.join(log_folder, 'plots') + os.makedirs(plots_folder, exist_ok=True) + + t = df['curr pt[0] vehicle time'].tolist() + x = df['curr pt[0]'].tolist() + y = df['curr pt[1]'].tolist() + v = df['current speed (m/s)'].tolist() + yaw = df['current yaw (rad)'].tolist() + + xd = df['desired pt[0]'].tolist() + yd = df['desired pt[1]'].tolist() + vd = df['desired speed (m/s)'].tolist() + yawd = df['desired yaw (rad)'].tolist() + + cte = df['crosstrack error'].tolist() + front_wheel_angle = df['front wheel angle (rad)'].tolist() + accel = df['output accel (m/s^2)'].tolist() + + + + rmse_cte = np.sqrt(np.mean(np.array(cte)**2)) + print(f'RMSE (cte): {rmse_cte}') + + max_accel_error = np.max((np.array(accel) - 1.0)**2) + print(f'Maximum (acceleration - 1.0)^2: {max_accel_error}') + + rms_forward_acceleration = np.sqrt(np.mean(np.array(accel)**2)) + print(f'RMS of Acceleration: {rms_forward_acceleration}') + + dt = np.mean(np.diff(t)) + jerk = np.gradient(np.array(accel), dt) + rms_jerk = np.sqrt(np.mean(jerk**2)) + print(f'RMS of Jerk: {rms_jerk}') + + speed_error = np.array(v) - np.array(vd) + rms_speed_error = np.sqrt(np.mean(speed_error**2)) + print(f'RMS of Speed Error: {rms_speed_error}') + + angular_velocity = np.gradient(front_wheel_angle, dt) + angular_acceleration = np.gradient(angular_velocity, dt) + angular_jerk = np.gradient(angular_acceleration, dt) + rms_angular_acceleration = np.sqrt(np.mean(angular_acceleration**2)) + rms_angular_jerk = np.sqrt(np.mean(angular_jerk**2)) + print(f'RMS of Angular Acceleration: {rms_angular_acceleration}') + print(f'RMS of Angular Jerk: {rms_angular_jerk}') + + yaw_error = np.array(yaw) - np.array(yawd) + rms_yaw_error = np.sqrt(np.mean(yaw_error**2)) + print(f'RMS of Yaw Error: {rms_yaw_error}') + + w1, w2, w3 = 0.5, 0.3, 0.2 + comfort_index = w1 * rms_forward_acceleration + w2 * rms_jerk + w3 * rms_speed_error + print(f'===== Comfort Index: {comfort_index:.2f} =====') + + w1, w2, w3, w4, w5, w6, w7 = 0.2, 0.1, 0.15, 0.2, 0.15, 0.2, 0.1 + safety_index = (w1 * rmse_cte + w2 * rms_angular_jerk + w3 * rms_angular_acceleration + + w4 * rms_forward_acceleration + w5 * rms_jerk + w6 * rms_speed_error + + w7 * rms_yaw_error) + print(f'===== Safety Index: {safety_index:.2f} =====') + + create_plot(t, y, yd, '$t$ (s)', '$y(t)$, $y_{d}(t)$ (m)', 'Actual and Desired y', ['Actual $y(t)$', 'Desired $y_{d}(t)$'], os.path.join(plots_folder, 'y_vs_yd.png') if save_figures else None) + create_error_plot(t, np.array(y) - np.array(yd), '$t$ (s)', 'Error in $y(t)$ (m)', 'Error between Actual and Desired $y(t)$', os.path.join(plots_folder, 'error_y.png') if save_figures else None) + + create_plot(t, x, xd, '$t$ (s)', '$x(t)$, $x_{d}(t)$ (m)', 'Actual and Desired x', ['Actual $x(t)$', 'Desired $x_{d}(t)$'], os.path.join(plots_folder, 'x_vs_xd.png') if save_figures else None) + create_error_plot(t, np.array(x) - np.array(xd), '$t$ (s)', 'Error in $x(t)$ (m)', 'Error between Actual and Desired $x(t)$', os.path.join(plots_folder, 'error_x.png') if save_figures else None) + + create_plot(t, v, vd, '$t$ (s)', '$v(t)$, $v_{d}(t)$ (m/s)', 'Actual and Desired v', ['Actual $v(t)$', 'Desired $v_{d}(t)$'], os.path.join(plots_folder, 'v_vs_vd.png') if save_figures else None) + create_error_plot(t, np.array(v) - np.array(vd), '$t$ (s)', 'Error in $v(t)$ (m/s)', 'Error between Actual and Desired $v(t)$', os.path.join(plots_folder, 'error_v.png') if save_figures else None) + + plt.figure() + plt.plot(t, cte) + rmse_cte = np.sqrt(np.mean(np.array(cte)**2)) + print(f'RMSE (cte): {rmse_cte}') + plt.xlabel('$t$ (s)') + plt.ylabel('Crosstrack Error (m)') + plt.title(f'Crosstrack Error over Time (RMSE: {rmse_cte:.2f})') + plt.grid(True) + if save_figures: + plt.savefig(os.path.join(plots_folder, 'cte.png'), dpi=600) + plt.close() + + plt.figure() + plt.plot(t, front_wheel_angle) + plt.xlabel('$t$ (s)') + plt.ylabel('Front Wheel Angle (rad)') + plt.title('Front Wheel Angle over Time') + plt.grid(True) + if save_figures: + plt.savefig(os.path.join(plots_folder, 'front_wheel_angle.png'), dpi=600) + plt.close() + + plt.figure() + plt.plot(t, accel) + plt.xlabel('$t$ (s)') + plt.ylabel('Acceleration (m/s^2)') + plt.title('Acceleration over Time') + plt.grid(True) + if save_figures: + plt.savefig(os.path.join(plots_folder, 'accel.png'), dpi=600) + plt.close() + + + + +if __name__ == '__main__': + # Change this to the log folder you want to plot if running this script manually + log_folder = '2025-02-13_21-10-39' + main(log_folder) diff --git a/README.md b/README.md index d720806f5..6941b4158 100644 --- a/README.md +++ b/README.md @@ -26,6 +26,7 @@ You should also have the following Python dependencies installed, which you can - Gazebo Simulation Dependencies (only needed for Gazebo simulation) - ros-noetic-ackermann-msgs + In order to interface with the actual GEM e2 vehicle, you will need [PACMOD2](https://github.com/astuff/pacmod2) - Autonomoustuff's low level interface to vehicle. You will also need Autonomoustuff's [sensor message packages](https://github.com/astuff/astuff_sensor_msgs). The onboard computer uses Ubuntu 20.04 with Python 3.8, CUDA 11.6, and NVIDIA driver 515, so to minimize compatibility issues you should ensure that these are installed on your development system. ## Running the stack on Ubuntu 20.04 without Docker @@ -65,6 +66,29 @@ If you see the output, you are good to go. Otherwise, you will need to install t - For **Nvidia Container Toolkit**, run `setup/get_nvidia_container.sh` from this directory to install, or see [this](https://docs.nvidia.com/datacenter/cloud-native/container-toolkit/latest/install-guide.html) for more details. +## Running the stack on Ubuntu 20.04 without Docker +### Checking CUDA Version + +Before proceeding, check your Nvidia Driver and supported CUDA version: +```bash +nvidia-smi +``` +This will show your NVIDIA driver version and the maximum supported CUDA version. Make sure you have CUDA 11.8 or 12+ installed. + +From Ubuntu 20.04 install [CUDA 11.6](https://gist.github.com/ksopyla/bf74e8ce2683460d8de6e0dc389fc7f5) or [CUDA 12+](https://gist.github.com/ksopyla/ee744bf013c83e4aa3fc525634d893c9) based on your current Nvidia Driver versio. + +To check the currently installed CUDA version: +```bash +nvcc --version +``` +you can install the dependencies or GEMstack by running `setup/setup_this_machine.sh` from the top-level GEMstack folder. + +## Running the stack on Ubuntu 20.04 or 22.04 with Docker +> [!NOTE] +> Make sure to check the Nvidia Driver and supported CUDA version before proceeding by following the steps in the previous section. + +For GPU support you will need the NVidia Container Toolkit (run `setup/get_nvidia_container.sh` from this directory to install, or see [this](https://docs.nvidia.com/datacenter/cloud-native/container-toolkit/latest/install-guide.html) for more details). + ## Building the Docker image To build a Docker image with all these prerequisites, you can use the provided Dockerfile by running. diff --git a/data/.gitignore b/data/.gitignore old mode 100644 new mode 100755 diff --git a/data/README.md b/data/README.md old mode 100644 new mode 100755 diff --git a/launch/Visualization.py b/launch/Visualization.py new file mode 100644 index 000000000..0a329af38 --- /dev/null +++ b/launch/Visualization.py @@ -0,0 +1,824 @@ +#!/usr/bin/env python3 +import os +import glob +import cv2 +import numpy as np +import open3d as o3d +from ultralytics import YOLO +from sklearn.cluster import DBSCAN +from scipy.spatial.transform import Rotation as R +import time +import matplotlib.pyplot as plt + +# ----------------------------- +# 1) Minimal Stub Classes +# ----------------------------- +class AgentActivityEnum(): + # Activity enumerations (cones or pedestrians, etc.) + STOPPED = 0 # e.g., stationary objects (pedestrians standing, parked cars, etc.) + MOVING = 1 # normally moving objects (predictions will be used here) + FAST = 2 # moving faster than usual (e.g., runners) + UNDETERMINED = 3 # unknown activity + STANDING = 4 # our label for a cone detected in normal orientation + LEFT = 5 # label for a cone detected after right rotation (i.e., originally rotated left) + RIGHT = 6 # label for a cone detected after left rotation (i.e., originally rotated right) + +class ObjectPose: + # Pose representation for detected objects + def __init__(self, t, x, y, z, yaw, pitch, roll, frame): + self.t = t # time stamp + self.x = x # x coordinate + self.y = y # y coordinate + self.z = z # z coordinate + self.yaw = yaw # yaw angle (heading) + self.pitch = pitch # pitch angle + self.roll = roll # roll angle + self.frame = frame # coordinate frame identifier + +class AgentState: + # State representation for an agent (cone, pedestrian, etc.) + def __init__(self, pose, dimensions, outline, type, activity, velocity, yaw_rate): + self.pose = pose # an ObjectPose instance + self.dimensions = dimensions # dimensions (width, height, depth) + self.outline = outline # contour or outline (if available) + self.type = type # type of agent (e.g., cone, pedestrian) + self.activity = activity # activity label, see AgentActivityEnum + self.velocity = velocity # velocity tuple (vx, vy, vz) + self.yaw_rate = yaw_rate # yaw rate (angular velocity) + +# ----------------------------- +# 2) Helper Functions +# ----------------------------- +def undistort_image(image, K, D): + """ + Undistort an input image using the camera matrix (K) and distortion coefficients (D). + Returns the undistorted image and the new camera matrix. + """ + h, w = image.shape[:2] + newK, _ = cv2.getOptimalNewCameraMatrix(K, D, (w, h), 1, (w, h)) + undistorted = cv2.undistort(image, K, D, None, newK) + return undistorted, newK + +def cylindrical_roi(points, center, radius, height): + """ + Select points from the point cloud that are within a cylindrical region of interest (ROI). + The cylinder is defined on the horizontal plane with center[:2] as its center (assume x,y), + a given radius, and vertically centered at center[2] with a total height of 'height'. + """ + horizontal_dist = np.linalg.norm(points[:, :2] - center[:2], axis=1) + vertical_diff = np.abs(points[:, 2] - center[2]) + mask = (horizontal_dist <= radius) & (vertical_diff <= height / 2) + return points[mask] + +def downsample_points(lidar_points, voxel_size=0.15): + """ + Downsample the LiDAR point cloud using a voxel grid filter. + """ + pcd = o3d.geometry.PointCloud() + pcd.points = o3d.utility.Vector3dVector(lidar_points) + down_pcd = pcd.voxel_down_sample(voxel_size=voxel_size) + return np.asarray(down_pcd.points) + +def load_start_pose(vehstate_filepath): + """ + Read the line starting with 'AFTER_TRANSFORM' from the given file and + return an ObjectPose in the START frame. + """ + with open(vehstate_filepath, 'r') as f: + for line in f: + if line.startswith("AFTER_TRANSFORM"): + # line looks like: + # AFTER_TRANSFORM x=17.551, y=0.164, z=0.016, yaw=0.31, pitch=-0.02, roll=-0.01, frame=START + parts = line.strip().split() + kvs = {} + for token in parts[1:]: + key, val = token.rstrip(',').split('=') + kvs[key] = val + return ObjectPose( + t=None, + x=float(kvs['x']), + y=float(kvs['y']), + z=float(kvs['z']), + yaw=float(kvs['yaw']), + pitch=float(kvs['pitch']), + roll=float(kvs['roll']), + frame=kvs['frame'] + ) + raise RuntimeError(f"No AFTER_TRANSFORM line found in {vehstate_filepath}") + + +def visualize_z_distribution(points_3d, bins=50): + """ + Visualize the distribution of Z values in a point cloud. + + Args: + points_3d (np.ndarray): Array of shape (N,3) with XYZ coordinates. + bins (int): Number of histogram bins. + """ + z_vals = points_3d[:, 2] + plt.figure() + plt.hist(z_vals, bins=bins) + plt.xlabel("Z coordinate") + plt.ylabel("Frequency") + plt.title("Z Distribution of Points") + plt.show() + + +def transform_points_l2c(lidar_points, T_l2c): + """ + Transform LiDAR points from LiDAR coordinates to camera coordinates using the transformation matrix T_l2c. + """ + N = lidar_points.shape[0] + pts_hom = np.hstack((lidar_points, np.ones((N, 1)))) # create homogeneous coordinates (N,4) + pts_cam = (T_l2c @ pts_hom.T).T + return pts_cam[:, :3] + +def project_points(pts_cam, K, original_lidar_points): + """ + Project points (in camera coordinates) onto the image plane using camera intrinsics. + Only points with positive Z (in front of the camera) are projected. + Returns an array of shape (M, 5): [u, v, X_lidar, Y_lidar, Z_lidar]. + """ + mask = pts_cam[:, 2] > 0 + pts_cam_valid = pts_cam[mask] + lidar_valid = original_lidar_points[mask] + Xc = pts_cam_valid[:, 0] + Yc = pts_cam_valid[:, 1] + Zc = pts_cam_valid[:, 2] + u = (K[0, 0] * (Xc / Zc) + K[0, 2]).astype(np.int32) + v = (K[1, 1] * (Yc / Zc) + K[1, 2]).astype(np.int32) + proj = np.column_stack((u, v, lidar_valid)) + return proj + +def project_all_points(points, T_l2c, K): + """ + For all input points, project them onto the image plane using the transformation matrix T_l2c and camera intrinsic K. + Returns an (N,2) array with [u, v] coordinates for each point. For points with Z<=0, returns [-1, -1]. + """ + N = points.shape[0] + pts_hom = np.hstack((points, np.ones((N,1)))) + pts_cam = (T_l2c @ pts_hom.T).T + u = np.full((N,), -1, dtype=int) + v = np.full((N,), -1, dtype=int) + valid = pts_cam[:, 2] > 0 + if np.any(valid): + Xc = pts_cam[valid, 0] + Yc = pts_cam[valid, 1] + Zc = pts_cam[valid, 2] + u[valid] = (K[0, 0] * (Xc / Zc) + K[0, 2]).astype(int) + v[valid] = (K[1, 1] * (Yc / Zc) + K[1, 2]).astype(int) + return np.stack((u, v), axis=1) + +def visualize_custom_points(image, points_lidar, T_l2c, K, color=(0, 255, 0)): + """ + Visualize custom LiDAR points on the given image. + Projects the LiDAR points (using T_l2c and camera intrinsics K) and draws circles on the image. + """ + N = points_lidar.shape[0] + pts_hom = np.hstack((points_lidar, np.ones((N, 1)))) + pts_cam = (T_l2c @ pts_hom.T).T[:, :3] + for p in pts_cam: + X, Y, Z = p + if Z <= 0: + continue + u = int(K[0, 0] * (X / Z) + K[0, 2]) + v = int(K[1, 1] * (Y / Z) + K[1, 2]) + cv2.circle(image, (u, v), 5, color, -1) + return image + +def filter_points_within_threshold(points, threshold=15.0): + """ + Filter out points that are farther than the threshold. + """ + distances = np.linalg.norm(points, axis=1) + mask = distances <= threshold + return points[mask] + +def refine_cluster(roi_points, center, eps=0.2, min_samples=10): + """ + Refine a cluster of points using DBSCAN clustering and return the cluster closest to 'center'. + """ + if roi_points.shape[0] < min_samples: + return roi_points + clustering = DBSCAN(eps=eps, min_samples=min_samples).fit(roi_points) + labels = clustering.labels_ + valid_clusters = [roi_points[labels == l] for l in set(labels) if l != -1] + if not valid_clusters: + return roi_points + best_cluster = min(valid_clusters, key=lambda c: np.linalg.norm(np.mean(c, axis=0) - center)) + return best_cluster + +def remove_ground_by_min_range(cluster, z_range=0.05): + """ + Remove points in the cluster that are within a specified z-range from the minimum z value (assumed to be ground). + """ + if cluster is None or cluster.shape[0] == 0: + return cluster + min_z = np.min(cluster[:, 2]) + return cluster[cluster[:, 2] > (min_z + z_range)] + +def match_existing_pedestrian(new_center, new_dims, existing_agents, distance_threshold=1.0): + """ + Find the closest already tracked agent (cone/pedestrian) to the new_center, within the distance threshold. + Returns the agent ID if found. + """ + best_agent_id = None + best_dist = float('inf') + for agent_id, agent_state in existing_agents.items(): + old_center = np.array([agent_state.pose.x, agent_state.pose.y, agent_state.pose.z]) + dist = np.linalg.norm(new_center - old_center) + if dist < distance_threshold and dist < best_dist: + best_dist = dist + best_agent_id = agent_id + return best_agent_id + +def compute_velocity(old_pose, new_pose, dt): + """ + Compute velocity (vx, vy, vz) based on the difference between the new and old poses divided by dt. + """ + if dt <= 0: + return (0, 0, 0) + vx = (new_pose.x - old_pose.x) / dt + vy = (new_pose.y - old_pose.y) / dt + vz = (new_pose.z - old_pose.z) / dt + return (vx, vy, vz) + +def filter_depth_points(lidar_points, max_depth_diff=0.9, use_norm=True): + """ + Filters LiDAR points based on a maximum allowed depth difference. + """ + if lidar_points.shape[0] == 0: + return lidar_points + if use_norm: + depths = np.linalg.norm(lidar_points, axis=1) + else: + depths = lidar_points[:, 0] + min_depth = np.min(depths) + max_possible_depth = min_depth + max_depth_diff + mask = depths < max_possible_depth + return lidar_points[mask] + +def display_reprojected_cluster(image, refined_cluster, T_l2c, K): + """ + Reproject 3D points (refined_cluster) into the image and draw small circles for debugging. + """ + if refined_cluster is None or refined_cluster.shape[0] == 0: + return image + N = refined_cluster.shape[0] + pts_hom = np.hstack((refined_cluster, np.ones((N, 1)))) + pts_cam = (T_l2c @ pts_hom.T).T[:, :3] + for p in pts_cam: + X, Y, Z = p + if Z <= 0: + continue + u = int(K[0, 0] * X / Z + K[0, 2]) + v = int(K[1, 1] * Y / Z + K[1, 2]) + cv2.circle(image, (u, v), 2, (255, 0, 0), -1) + return image + +def pose_to_matrix(pose): + """ + Convert a pose to a 4x4 transformation matrix. + The pose attributes (x, y, z, yaw, pitch, roll) are used, + with angles in degrees. + """ + x = pose.x if pose.x is not None else 0.0 + y = pose.y if pose.y is not None else 0.0 + z = pose.z if pose.z is not None else 0.0 + if pose.yaw is not None and pose.pitch is not None and pose.roll is not None: + yaw = pose.yaw + pitch = np.radians(pose.pitch) + roll = np.radians(pose.roll) + else: + yaw = pitch = roll = 0.0 + R_mat = R.from_euler('zyx', [yaw, pitch, roll]).as_matrix() + T = np.eye(4) + T[:3, :3] = R_mat + T[:3, 3] = np.array([x, y, z]) + return T + +def transform_points_l2c(lidar_points, T_l2c): + """ + Transform LiDAR points to camera coordinates. + """ + N = lidar_points.shape[0] + pts_hom = np.hstack((lidar_points, np.ones((N, 1)))) # (N,4) + pts_cam = (T_l2c @ pts_hom.T).T # (N,4) + return pts_cam[:, :3] + +# ----- New: Vectorized projection function ----- +def project_points(pts_cam, K, original_lidar_points): + """ + Vectorized version of projecting LiDAR points (in camera space) to the image plane. + Returns an (M, 5) array: [u, v, X_lidar, Y_lidar, Z_lidar] for points with positive Z. + """ + mask = pts_cam[:, 2] > 0 + pts_cam_valid = pts_cam[mask] + lidar_valid = original_lidar_points[mask] + Xc = pts_cam_valid[:, 0] + Yc = pts_cam_valid[:, 1] + Zc = pts_cam_valid[:, 2] + u = (K[0, 0] * (Xc / Zc) + K[0, 2]).astype(np.int32) + v = (K[1, 1] * (Yc / Zc) + K[1, 2]).astype(np.int32) + proj = np.column_stack((u, v, lidar_valid)) + return proj + +def remove_rows(A, B, decimals=3): + """ + Remove rows that are the same in A and B up to a given decimal precision. + """ + A_round = np.round(A, decimals=decimals) + B_round = np.round(B, decimals=decimals) + A_view = {tuple(row) for row in A_round} + B_view = {tuple(row) for row in B_round} + diff = A_view - B_view + diff = np.array(list(diff)) + return diff + +# ----------------------------- +# 3) PedestrianDetector2D (New Method) +# ----------------------------- +class PedestrianDetector2D: + """ + New approach: + 1) Downsample LiDAR point cloud. + 2) Transform the point cloud to camera coordinate system. + 3) Project all points onto the image plane. + 4) Use YOLO 2D detection boxes to filter LiDAR points. + 5) Use DBSCAN clustering and ground removal. + 6) Compute oriented bounding boxes and transform them to the vehicle frame. + 7) (Optional) Reproject the refined cluster onto the image (for debugging). + 8) (Optional) Visualize 3D frustum (back-project 2D bounding box into 3D). + """ + def __init__(self, model_path='yolov8n.pt'): + self.detector = YOLO(model_path) + self.camera_front = True + if self.camera_front: + self.K = np.array([[684.83331299, 0., 573.37109375], + [0., 684.60968018, 363.70092773], + [0., 0., 1.]]) + else: + self.K = np.array([[1.17625545e+03, 0.00000000e+00, 9.66432645e+02], + [0.00000000e+00, 1.17514569e+03, 6.08580326e+02], + [0.00000000e+00, 0.00000000e+00, 1.00000000e+00]]) + if self.camera_front: + self.D = np.array([0.0, 0.0, 0.0, 0.0, 0.0]) + else: + self.D = np.array([-2.70136325e-01, 1.64393255e-01, -1.60720782e-03, -7.41246708e-05, + -6.19939758e-02]) + self.T_l2v = np.array([[0.99939639, 0.02547917, 0.023615, 1.1], + [-0.02530848, 0.99965156, -0.00749882, 0.03773583], + [-0.02379784, 0.00689664, 0.999693, 1.95320223], + [0., 0., 0., 1.]]) + if self.camera_front: + self.T_l2c = np.array([[2.89748006e-02, -9.99580136e-01, 3.68439439e-05, -3.07300513e-02], + [-9.49930618e-03, -3.12215512e-04, -9.99954834e-01, -3.86689354e-01], + [9.99534999e-01, 2.89731321e-02, -9.50437214e-03, -6.71425124e-01], + [0.00000000e+00, 0.00000000e+00, 0.00000000e+00, 1.00000000e+00]]) + else: + self.T_l2c = np.array([[-0.71836368, -0.69527204, -0.02346088, 0.05718003], + [-0.09720448, 0.13371206, -0.98624154, -0.1598301 ], + [ 0.68884317, -0.7061996 , -0.16363744, -1.04767285], + [ 0. , 0. , 0. , 1. ]]) + self.tracked_agents = {} + self.pedestrian_counter = 0 + self.current_K = self.K.copy() + self.debug_frustums = [] + self.cluster_geometries = [] + self.cluster_obbs = [] + self.others_geometry = None + # Flag: whether to use cylindrical ROI option. + self.use_cyl_roi = True + + def process_frame(self, image, lidar_points, current_time=0.0, debug_reproj=False, debug_frustum=False, + start_pose_abs = None): + agents = {} + self.cluster_geometries = [] + self.cluster_obbs = [] + self.debug_frustums = [] + + # 1. Undistort the input image and record its original dimensions. + image, newK = undistort_image(image, self.K, self.D) + self.current_K = newK + orig_H, orig_W = image.shape[:2] + + # 2. Create rotated images (for detection only, not for final display): + # img_normal: the undistorted normal image. + # img_left: left-rotated (counterclockwise 90°). + # img_right: right-rotated (clockwise 90°). + image_left = cv2.rotate(image.copy(), cv2.ROTATE_90_COUNTERCLOCKWISE) + image_right = cv2.rotate(image.copy(), cv2.ROTATE_90_CLOCKWISE) + + # 3. Run YOLO detections on each image. + # Detection box format is [cx, cy, w, h]. + results_normal = self.detector(image, conf=0.4, classes=[0]) + results_left = self.detector(image_left, conf=0.1, classes=[0]) + results_right = self.detector(image_right, conf=0.1, classes=[0]) + + boxes_normal = np.array(results_normal[0].boxes.xywh.cpu()) if len(results_normal) > 0 else [] + boxes_left = np.array(results_left[0].boxes.xywh.cpu()) if len(results_left) > 0 else [] + boxes_right = np.array(results_right[0].boxes.xywh.cpu()) if len(results_right) > 0 else [] + + # 3.1 Combine boxes from all three angles. + # For the normal image, no mapping is performed: activity = STANDING. + # For the left rotated image (counterclockwise 90°): + # In the left-rotated image, detection center is (cx, cy). + # Inverse mapping to original coordinates is: (x, y) = (orig_W - 1 - c_y, c_x). + # Also, swap width and height. Activity is set to RIGHT. + # For the right rotated image (clockwise 90°): + # Inverse mapping: (x, y) = (c_y, orig_H - 1 - c_x). Swap width and height. + # Activity is set to LEFT. + combined_boxes = [] + for box in boxes_normal: + cx, cy, w, h = box + combined_boxes.append((cx, cy, w, h, AgentActivityEnum.STANDING)) + for box in boxes_left: + cx, cy, w, h = box + new_cx = orig_W - 1 - cy + new_cy = cx + new_w = h # Swap width and height. + new_h = w + combined_boxes.append((new_cx, new_cy, new_w, new_h, AgentActivityEnum.RIGHT)) + for box in boxes_right: + cx, cy, w, h = box + new_cx = cy + new_cy = orig_H - 1 - cx + new_w = h # Swap width and height. + new_h = w + combined_boxes.append((new_cx, new_cy, new_w, new_h, AgentActivityEnum.LEFT)) + + # 4. Preprocess LiDAR point cloud. + lidar_down = lidar_points.copy() + global_filtered = filter_points_within_threshold(lidar_down, 50) + pts_cam = transform_points_l2c(lidar_down, self.T_l2c) + projected_pts = project_points(pts_cam, self.current_K, lidar_down) + + # 5. For each combined 2D bounding box, process LiDAR points to obtain 3D position and orientation. + refined_all = [] + if lidar_points.shape[0] > 0: + roi_pcd = o3d.geometry.PointCloud() + roi_pcd.points = o3d.utility.Vector3dVector(lidar_points) + # this will pop up a window showing just those points + o3d.visualization.draw_geometries( + [roi_pcd], + window_name="ROI 3D Points", + width=800, + height=600 + ) + for box_info in combined_boxes: + cx, cy, w, h, activity = box_info + print(cx, cy, w, h) + left = int(cx - w / 1.5) + right = int(cx + w / 1.5) + top = int(cy - h / 2) + bottom = int(cy + h / 2) + + # --- [Optional] Project 2D bounding box into 3D to create a frustum, if debug_frustum is set --- + if debug_frustum: + bbox = [left, top, right, bottom] + z_near = 0.5 # can be adjusted + z_far = 30.0 # can be adjusted + pts_frustum, lines_frustum = self.create_frustum_lines(bbox, self.current_K, z_near, z_far) + frustum_lineset = o3d.geometry.LineSet() + frustum_lineset.points = o3d.utility.Vector3dVector(pts_frustum) + frustum_lineset.lines = o3d.utility.Vector2iVector(lines_frustum) + # Color all lines red + frustum_lineset.colors = o3d.utility.Vector3dVector([[1, 0, 0] for _ in range(len(lines_frustum))]) + self.debug_frustums.append(frustum_lineset) + # ------------------------------------------------------------------------------------- + + # Draw the 2D bounding box and label on the (original) image. + if activity == AgentActivityEnum.STANDING: + color = (255, 0, 0) # Blue + label_text = "STANDING" + elif activity == AgentActivityEnum.RIGHT: + color = (0, 255, 0) # Green + label_text = "RIGHT" + elif activity == AgentActivityEnum.LEFT: + color = (0, 0, 255) # Red + label_text = "LEFT" + else: + color = (255, 255, 255) + label_text = "UNKNOWN" + cv2.rectangle(image, (left, top), (right, bottom), color, 2) + cv2.putText(image, label_text, (left, max(top - 5, 20)), + cv2.FONT_HERSHEY_SIMPLEX, 0.6, color, 2) + + # Extract the LiDAR points that project within the ROI. + mask = (projected_pts[:, 0] >= left) & (projected_pts[:, 0] <= right) & \ + (projected_pts[:, 1] >= top) & (projected_pts[:, 1] <= bottom) + roi_2d_pts = projected_pts[mask] + points_3d = roi_2d_pts[:, 2:5] # Extract the original 3D coordinates + + if points_3d.shape[0] > 0: + roi_pcd = o3d.geometry.PointCloud() + roi_pcd.points = o3d.utility.Vector3dVector(points_3d) + # this will pop up a window showing just those points + o3d.visualization.draw_geometries( + [roi_pcd], + window_name="ROI 3D Points", + width=800, + height=600 + ) + if debug_reproj: + display_reprojected_cluster(image, points_3d, self.T_l2c, self.current_K) + visualize_z_distribution(points_3d) + points_3d = filter_points_within_threshold(points_3d, 100) + # print(points_3d) + points_3d = remove_ground_by_min_range(points_3d, z_range=0.08) + points_3d = filter_depth_points(points_3d, max_depth_diff=0.5) + + if points_3d.shape[0] > 0: + roi_pcd = o3d.geometry.PointCloud() + roi_pcd.points = o3d.utility.Vector3dVector(points_3d) + # this will pop up a window showing just those points + o3d.visualization.draw_geometries( + [roi_pcd], + window_name="ROI 3D Points", + width=800, + height=600 + ) + if points_3d.shape[0] < 4: + continue + + # --- Modification: Optional Cylindrical ROI --- + # If cylindrical ROI is enabled, use global_filtered points to form a cylindrical ROI. + center_roi = np.mean(points_3d, axis=0) + if self.use_cyl_roi: + roi_cyl = cylindrical_roi(global_filtered, center_roi, radius=0.4, height=1.2) + refined_cluster = remove_ground_by_min_range(roi_cyl, z_range=0.01) + refined_cluster = filter_depth_points(refined_cluster, max_depth_diff=0.3) + center_roi = np.mean(refined_cluster, axis=0) + else: + refined_cluster = points_3d.copy() + if refined_cluster.shape[0] < 4: + continue + # ------------------------------------------------- + + refined_all.append(refined_cluster) + # Create an Open3D point cloud for the refined cluster (colored red). + pcd_cluster = o3d.geometry.PointCloud() + pcd_cluster.points = o3d.utility.Vector3dVector(refined_cluster) + pcd_cluster.paint_uniform_color([1, 0, 0]) + self.cluster_geometries.append(pcd_cluster) + # Compute the oriented bounding box (OBB) for the refined cluster (set to magenta). + pcd = o3d.geometry.PointCloud() + pcd.points = o3d.utility.Vector3dVector(refined_cluster) + obb = pcd.get_oriented_bounding_box() + obb.color = (1, 0, 1) + self.cluster_obbs.append(obb) + + refined_center = obb.center + dims = tuple(obb.extent) + R_lidar = obb.R.copy() + refined_center_hom = np.append(refined_center, 1) + refined_center_vehicle_hom = self.T_l2v @ refined_center_hom + refined_center_vehicle = refined_center_vehicle_hom[:3] + + R_vehicle = self.T_l2v[:3, :3] @ R_lidar + # Convert rotation matrix to Euler angles (in degrees) + euler_vehicle = R.from_matrix(R_vehicle).as_euler('zyx', degrees=True) + yaw, pitch, roll = euler_vehicle + + if start_pose_abs is not None: + T_vehicle_to_start = pose_to_matrix(start_pose_abs) + + # transform your point (vehicle‐frame) into START frame + p_start_hom = T_vehicle_to_start @ np.append(refined_center_vehicle, 1.0) + xp, yp, zp = p_start_hom[:3] + + # overwrite or store for output + refined_center_vehicle = np.array([xp, yp, zp]) + + new_pose = ObjectPose( + t=current_time, + x=refined_center_vehicle[0], + y=refined_center_vehicle[1], + z=refined_center_vehicle[2], + yaw=yaw, + pitch=pitch, + roll=roll, + frame=0 + ) + # Match with an existing tracked cone if possible. + existing_id = match_existing_pedestrian( + np.array([new_pose.x, new_pose.y, new_pose.z]), + dims, + self.tracked_agents, + distance_threshold=0.5 + ) + if existing_id is not None: + old_state = self.tracked_agents[existing_id] + dt = current_time - old_state.pose.t + vx, vy, vz = compute_velocity(old_state.pose, new_pose, dt) + updated_agent = AgentState( + pose=new_pose, + dimensions=dims, + outline=None, + type=0, + activity=activity, + velocity=(vx, vy, vz), + yaw_rate=0 + ) + agents[existing_id] = updated_agent + self.tracked_agents[existing_id] = updated_agent + else: + agent_id = f"pedestrian{self.pedestrian_counter}" + self.pedestrian_counter += 1 + new_agent = AgentState( + pose=new_pose, + dimensions=dims, + outline=None, + type=0, + activity=activity, + velocity=(0, 0, 0), + yaw_rate=0 + ) + agents[agent_id] = new_agent + self.tracked_agents[agent_id] = new_agent + + # Optionally, display custom debug points on the image. + # visualize_custom_points(image, np.array([ + # [4.730639, 10.195478, -1.941095], + # [2.066050, 7.066111, -2.027844], + # [1.341566, 7.118239, -1.994539], + # [4.160140, 6.539731, -1.895874], + # [6.469934, 6.128805, -1.859030], + # ]), self.T_l2c, self.current_K, color=(0, 0, 255)) + cv2.imshow("Frame with Boxes and Custom Points", image) + cv2.waitKey(1) + + # Process "other points": from global_filtered, find points that do not fall within any ROI. + projected_global = project_all_points(global_filtered, self.T_l2c, self.current_K) + others_mask = np.zeros(len(global_filtered), dtype=bool) + for box_info in combined_boxes: + cx, cy, w, h, _ = box_info + left = int(cx - w / 2) + right = int(cx + w / 2) + top = int(cy - h / 2) + bottom = int(cy + h / 2) + in_box = (projected_global[:, 0] >= left) & (projected_global[:, 0] <= right) & \ + (projected_global[:, 1] >= top) & (projected_global[:, 1] <= bottom) + others_mask = others_mask | in_box + others_mask = ~others_mask + others = global_filtered[others_mask] + others_pc = o3d.geometry.PointCloud() + others_pc.points = o3d.utility.Vector3dVector(others) + others_pc.paint_uniform_color([0.5, 0.5, 0.5]) + self.others_geometry = others_pc + + # Return the final detected agents and the image with drawn bounding boxes and labels. + return agents, image + + def create_frustum_lines(self, box, K, z_near, z_far): + """ + Create the points and line indices that form a 3D frustum by back-projecting the 2D bounding box. + 'box' is [left, top, right, bottom]. + Returns an array of 3D points and a list of lines (indices into the points array). + """ + left, top, right, bottom = box + corners = np.array([ + [left, top], + [right, top], + [right, bottom], + [left, bottom] + ]) + fx = K[0, 0] + fy = K[1, 1] + cx = K[0, 2] + cy = K[1, 2] + near_points = [] + far_points = [] + for (u, v) in corners: + x_near = (u - cx) / fx * z_near + y_near = (v - cy) / fy * z_near + near_pt = np.array([x_near, y_near, z_near, 1.0]) + near_points.append(near_pt) + x_far = (u - cx) / fx * z_far + y_far = (v - cy) / fy * z_far + far_pt = np.array([x_far, y_far, z_far, 1.0]) + far_points.append(far_pt) + near_points = np.array(near_points) + far_points = np.array(far_points) + T_c2l = np.linalg.inv(self.T_l2c) + near_points_lidar = (T_c2l @ near_points.T).T[:, :3] + far_points_lidar = (T_c2l @ far_points.T).T[:, :3] + all_points = np.vstack((near_points_lidar, far_points_lidar)) + lines = [[i, i + 4] for i in range(4)] + lines += [[0, 1], [1, 2], [2, 3], [3, 0]] + lines += [[4, 5], [5, 6], [6, 7], [7, 4]] + return all_points, lines + +# New helper: Ensure to project all global_filtered points into image coordinates. +def project_all_points(points, T_l2c, K): + N = points.shape[0] + pts_hom = np.hstack((points, np.ones((N,1)))) + pts_cam = (T_l2c @ pts_hom.T).T + u = np.full((N,), -1, dtype=int) + v = np.full((N,), -1, dtype=int) + valid = pts_cam[:, 2] > 0 + if np.any(valid): + Xc = pts_cam[valid, 0] + Yc = pts_cam[valid, 1] + Zc = pts_cam[valid, 2] + u[valid] = (K[0, 0] * (Xc / Zc) + K[0, 2]).astype(int) + v[valid] = (K[1, 1] * (Yc / Zc) + K[1, 2]).astype(int) + return np.stack((u, v), axis=1) + +# ----------------------------- +# 4) Function to load LiDAR data from an NPZ file. +# ----------------------------- +def load_lidar_from_npz(file_path): + data = np.load(file_path) + print(data.keys()) + return data['lidar'] + +# ----------------------------- +# 5) Main function: runs process_frame and visualizes refined clusters and other point cloud geometries. +# This part also loads images and LiDAR data (modify paths as needed). +# ----------------------------- +def main(): + # Set whether to use the cylindrical ROI option (True or False). + use_cyl_roi_flag = True + detector = PedestrianDetector2D(model_path='cone.pt') + detector.use_cyl_roi = use_cyl_roi_flag + + # Initialize Open3D visualization for LiDAR point cloud geometries. + vis = o3d.visualization.VisualizerWithKeyCallback() + vis.create_window(window_name="3D Frame Display", width=800, height=600) + view_path = "last_view.json" + if os.path.exists(view_path): + param = o3d.io.read_pinhole_camera_parameters(view_path) + else: + param = None + + # Read image and LiDAR data (please modify the paths as needed). + # image_files = sorted(glob.glob(os.path.join('../data', 'color*.png'))) + # lidar_files = sorted(glob.glob(os.path.join('../data', 'lidar*.npz'))) + # num_frames = min(len(image_files), len(lidar_files)) + # if num_frames == 0: + # print("No matching data found.") + # return + + # print(f"Found {num_frames} matching frames.") + for i in range(1): + # Use fixed file paths as an example; modify as needed. + current_time_ms = 1746802907471 + image_path = f'../5.9/{current_time_ms}_image.png' + lidar_path = f'../5.9/{current_time_ms}_lidar.npz' + + try: + veh_txt = f"../4.30/{current_time_ms}_vehstate.txt" + start_pose_abs = load_start_pose(veh_txt) + except: + start_pose_abs = None + + image = cv2.imread(image_path) + if image is None: + print("Failed to load image:", image_path) + continue + lidar_points = load_lidar_from_npz(lidar_path) + + agents, processed_image = detector.process_frame(image, lidar_points, current_time=float(i), + debug_reproj=True, debug_frustum=True, start_pose_abs = start_pose_abs) + # Print detected agent information. + print("Detected Agents:") + for agent_id, agent_state in agents.items(): + p = agent_state.pose + orientation = {AgentActivityEnum.STANDING: "STANDING", + AgentActivityEnum.LEFT: "LEFT", + AgentActivityEnum.RIGHT: "RIGHT"}.get(agent_state.activity, "UNKNOWN") + print( + f"Agent {agent_id}: Position=({p.x:.2f}, {p.y:.2f}, {p.z:.2f}), Orientation={orientation}, Dimensions={agent_state.dimensions}") + + # Display the 2D image with bounding boxes and labels. + cv2.imshow("Detection - Normal2D", processed_image) + cv2.waitKey(1) + + # Open3D visualization: show refined clusters, OBB, and other points. + geometries = [] + if detector.cluster_geometries: + geometries.extend(detector.cluster_geometries) + if detector.cluster_obbs: + geometries.extend(detector.cluster_obbs) + if detector.others_geometry is not None: + geometries.append(detector.others_geometry) + if detector.debug_frustums: + geometries.extend(detector.debug_frustums) + + vis.clear_geometries() + for geom in geometries: + vis.add_geometry(geom) + if param is not None: + vis.get_view_control().convert_from_pinhole_camera_parameters(param) + else: + print("No previous view, using default.") + vis.run() # Block until the user closes the visualizer window. + param = vis.get_view_control().convert_to_pinhole_camera_parameters() + o3d.io.write_pinhole_camera_parameters(view_path, param) + vis.clear_geometries() + vis.destroy_window() + cv2.destroyAllWindows() + +if __name__ == "__main__": + main() diff --git a/launch/blink_launch.yaml b/launch/blink_launch.yaml new file mode 100644 index 000000000..ab28ae31a --- /dev/null +++ b/launch/blink_launch.yaml @@ -0,0 +1,68 @@ +description: "Launch just the blink distress code" +mode: hardware +vehicle_interface: gem_hardware.GEMHardwareInterface +mission_execution: StandardExecutor +require_engaged: False +# Recovery behavior after a component failure +recovery: + perception: + state_estimation : GNSSStateEstimator + perception_normalization : StandardPerceptionNormalizer + planning: + driving_logic: driving_logic_component.DrivingLogic + signaling: blink_component.BlinkDistress +# Driving behavior for the GEM vehicle. Runs perception and planner but doesn't execute anything (no controller). +drive: + perception: + state_estimation : GNSSStateEstimator + perception_normalization : StandardPerceptionNormalizer + planning: + driving_logic: driving_logic_component.DrivingLogic + signaling: blink_component.BlinkDistress +log: + # Specify the top-level folder to save the log files. Default is 'logs' + folder : 'logs' + # If prefix is specified, then the log folder will be named with the prefix followed by the date and time. Default no prefix + prefix : 'hw1_' + # If suffix is specified, then logs will output to folder/prefix+suffix. Default uses date and time as the suffix + #suffix : 'test3' + # Specify which ros topics to record to vehicle.bag. + #ros_topics : ['/pacmod/as_rx/turn_cmd','/pacmod/as_tx/turn_rpt'] + # Specify options to pass to rosbag record. Default is no options. + #rosbag_options : '--split --size=1024' + # If True, then record all readings / commands of the vehicle interface. Default False + vehicle_interface : True + # Specify which components to record to behavior.json. Default records nothing + components : [] + # Specify which components of state to record to state.json. Default records nothing + #state: ['all'] + # Specify the rate in Hz at which to record state to state.json. Default records at the pipeline's rate + #state_rate: 10 + # If True, then make plots of the recorded data specifically from PurePursuitTrajectoryTracker_debug.csv and report metrics. Default False + #auto_plot : True +replay: # Add items here to set certain topics / inputs to be replayed from logs + # Specify which log folder to replay from + log: + ros_topics : [] + components : [] + +#usually can keep this constant +computation_graph: !include "../GEMstack/knowledge/defaults/computation_graph.yaml" + +variants: + sim: + run: + description: "Runs the distress signal, but in simulation" + mode: simulation + vehicle_interface: + type: gem_simulator.GEMDoubleIntegratorSimulationInterface + args: + scene: !relative_path '../scenes/xyhead_demo.yaml' + require_engaged: False + visualization: !include "klampt_visualization.yaml" + recovery: + perception: + state_estimation : OmniscientStateEstimator + drive: + perception: + state_estimation : OmniscientStateEstimator diff --git a/launch/combined_detection.yaml b/launch/combined_detection.yaml new file mode 100644 index 000000000..7f7d133f3 --- /dev/null +++ b/launch/combined_detection.yaml @@ -0,0 +1,127 @@ +description: "Run the yielding trajectory planner on the real vehicle with real perception" +mode: hardware +vehicle_interface: gem_hardware.GEMHardwareInterface +mission_execution: StandardExecutor + +# Recovery behavior after a component failure +recovery: + planning: + trajectory_tracking : recovery.StopTrajectoryTracker + +# Driving behavior for the GEM vehicle. Runs real pedestrian perception, yield planner, but does not send commands to real vehicle. +drive: + perception: + state_estimation : GNSSStateEstimator + agent_detection : + type: combined_detection.CombinedDetector3D + args: + # optional overrides + enable_tracking: True # True if you want to enable tracking function + use_start_frame: False # True if you need output in START frame, otherwise in CURRENT frame + iou_threshold: 0.01 # Set to the IOU threshold used to compare bounding boxes + merge_mode: "BEV" # Merging strategy to use: "Average", "Score", "Max", or "BEV" + + perception_normalization : StandardPerceptionNormalizer + planning: + relations_estimation: + type: pedestrian_yield_logic.PedestrianYielder + args: + mode: 'real' + params: { + 'yielder': 'expert', # 'expert', 'analytic', or 'simulation' + 'planner': 'milestone', # 'milestone', 'dt', or 'dx' + 'desired_speed': 1.0, # m/s, 1.5 m/s seems max speed? Feb24 + 'acceleration': 0.75 # m/s2, 0.5 is not enough to start moving. Feb24 + } + route_planning: + type: StaticRoutePlanner + args: [!relative_path '../GEMstack/knowledge/routes/forward_15m.csv','start'] + motion_planning: longitudinal_planning.YieldTrajectoryPlanner + trajectory_tracking: + type: pure_pursuit.PurePursuitTrajectoryTracker + print: False + + +log: + # Specify the top-level folder to save the log files. Default is 'logs' + #folder : 'logs' + # If prefix is specified, then the log folder will be named with the prefix followed by the date and time. Default no prefix + #prefix : 'fixed_route_' + # If suffix is specified, then logs will output to folder/prefix+suffix. Default uses date and time as the suffix + #suffix : 'test3' + # Specify which ros topics to record to vehicle.bag. Default records nothing. This records the "standard" ROS topics. + ros_topics : + # Specify options to pass to rosbag record. Default is no options. + #rosbag_options : '--split --size=1024' + # If True, then record all readings / commands of the vehicle interface. Default False + vehicle_interface : True + # Specify which components to record to behavior.json. Default records nothing + components : ['state_estimation','agent_detection','motion_planning'] + # Specify which components of state to record to state.json. Default records nothing + #state: ['all'] + # Specify the rate in Hz at which to record state to state.json. Default records at the pipeline's rate + #state_rate: 10 + # If True, then make plots of the recorded data specifically from PurePursuitTrajectoryTracker_debug.csv and report metrics. Default False + #auto_plot : True +replay: # Add items here to set certain topics / inputs to be replayed from logs + # Specify which log folder to replay from + log: + ros_topics : [] + components : [] + +#usually can keep this constant +computation_graph: !include "../GEMstack/knowledge/defaults/computation_graph.yaml" + +variants: + detector_only: + run: + description: "Run the pedestrian detection code" + drive: + planning: + trajectory_tracking: + real_sim: + run: + description: "Run the pedestrian detection code with real detection and fake simulation" + mode: hardware + vehicle_interface: + type: gem_mixed.GEMRealSensorsWithSimMotionInterface + args: + scene: !relative_path '../scenes/xyhead_demo.yaml' + mission_execution: StandardExecutor + require_engaged: False + visualization: !include "klampt_visualization.yaml" + drive: + perception: + state_estimation : OmniscientStateEstimator + planning: + relations_estimation: + type: pedestrian_yield_logic.PedestrianYielder + args: + mode: 'sim' + + fake_real: + run: + description: "Run the yielding trajectory planner on the real vehicle with faked perception" + drive: + perception: + agent_detection : cone_detection.FakeCombinedDetector2D + + fake_sim: + run: + description: "Run the yielding trajectory planner in simulation with faked perception" + mode: simulation + vehicle_interface: + type: gem_simulator.GEMDoubleIntegratorSimulationInterface + args: + scene: !relative_path '../scenes/xyhead_demo.yaml' + visualization: !include "klampt_visualization.yaml" + drive: + perception: + # agent_detection : pedestrian_detection.FakePedestrianDetector2D + agent_detection : OmniscientAgentDetector #this option reads agents from the simulator + state_estimation : OmniscientStateEstimator + planning: + relations_estimation: + type: pedestrian_yield_logic.PedestrianYielder + args: + mode: 'sim' diff --git a/launch/cone.pt b/launch/cone.pt new file mode 100644 index 000000000..002a39ede Binary files /dev/null and b/launch/cone.pt differ diff --git a/launch/cone_detection.yaml b/launch/cone_detection.yaml index 6b2d0a82e..8c7af70c7 100644 --- a/launch/cone_detection.yaml +++ b/launch/cone_detection.yaml @@ -9,6 +9,10 @@ recovery: trajectory_tracking : recovery.StopTrajectoryTracker # Driving behavior for the GEM vehicle. Runs real pedestrian perception, yield planner, but does not send commands to real vehicle. +<<<<<<< HEAD + +======= +>>>>>>> origin/s2025 drive: perception: state_estimation : GNSSStateEstimator @@ -111,3 +115,4 @@ variants: type: pedestrian_yield_logic.PedestrianYielder args: mode: 'sim' + diff --git a/launch/fixed_route.yaml b/launch/fixed_route.yaml index 368cb5b9d..45e2e12a3 100644 --- a/launch/fixed_route.yaml +++ b/launch/fixed_route.yaml @@ -43,6 +43,8 @@ log: #state: ['all'] # Specify the rate in Hz at which to record state to state.json. Default records at the pipeline's rate #state_rate: 10 + # If True, then make plots of the recorded data specifically from PurePursuitTrajectoryTracker_debug.csv and report metrics. Default False + #auto_plot : True replay: # Add items here to set certain topics / inputs to be replayed from logs # Specify which log folder to replay from log: diff --git a/launch/gather_data.yaml b/launch/gather_data.yaml index 4f3d03d4c..e04e8337d 100644 --- a/launch/gather_data.yaml +++ b/launch/gather_data.yaml @@ -37,6 +37,8 @@ log: #state: ['all'] # Specify the rate in Hz at which to record state to state.json. Default records at the pipeline's rate #state_rate: 10 + # If True, then make plots of the recorded data specifically from PurePursuitTrajectoryTracker_debug.csv and report metrics. Default False + #auto_plot : True replay: # Add items here to set certain topics / inputs to be replayed from logs # Specify which log folder to replay from log: diff --git a/launch/launch_all.sh b/launch/launch_all.sh new file mode 100644 index 000000000..c75fbecc9 --- /dev/null +++ b/launch/launch_all.sh @@ -0,0 +1,24 @@ +#!/bin/bash +<< COMMENTOUT +########## +- This script opens three new tabs in GNOME Terminal. +- Each tab will change to the GEMstack directory, source the ROS environment, and then run the specified command. + +- Run these commands at each tab: +cd ~/catkin_ws/src/GEMstack +source ~/catkin_ws/devel/setup.bash && roslaunch basic_launch sensor_init.launch +source ~/catkin_ws/devel/setup.bash && roslaunch basic_launch dbw_joystick.launch +source ~/catkin_ws/devel/setup.bash && python3 main.py --variant=fake_real launch/pedestrian_detection.yaml + +- If you don't want to detect virtual pedestrian, run this command instead: +source ~/catkin_ws/devel/setup.bash && python3 main.py launch/pedestrian_detection.yaml + +- If roscore cannot run, run this command to kill all roscore: +killall -9 roscore rosmaster +########## +COMMENTOUT + +cd ~/catkin_ws/src/GEMstack +gnome-terminal --tab -- bash -c "source ~/catkin_ws/devel/setup.bash && roslaunch basic_launch sensor_init.launch; exec bash" +gnome-terminal --tab -- bash -c "source ~/catkin_ws/devel/setup.bash && roslaunch basic_launch dbw_joystick.launch; exec bash" +gnome-terminal --tab -- bash -c "source ~/catkin_ws/devel/setup.bash && python3 main.py --variant=fake_real launch/pedestrian_detection.yaml; exec bash" \ No newline at end of file diff --git a/launch/pedestrian_detection.yaml b/launch/pedestrian_detection.yaml new file mode 100644 index 000000000..a9b4cf247 --- /dev/null +++ b/launch/pedestrian_detection.yaml @@ -0,0 +1,137 @@ +description: "Run the yielding trajectory planner on the real vehicle with real perception" +mode: hardware +vehicle_interface: gem_hardware.GEMHardwareInterface +mission_execution: StandardExecutor + +# Recovery behavior after a component failure +recovery: + planning: + trajectory_tracking : recovery.StopTrajectoryTracker + +# Driving behavior for the GEM vehicle. Runs real pedestrian perception, yield planner, but does not send commands to real vehicle. +drive: + + perception: + state_estimation: GNSSStateEstimator + agent_detection: + type: pedestrian_detection.PedestrianDetector3D + args: + camera_name: front #[front, front_right] + camera_calib_file: ./GEMstack/knowledge/calibration/cameras.yaml + + T_l2v: + - [ 0.99939639, 0.02547917, 0.023615, 1.1 ] + - [ -0.02530848, 0.99965156, -0.00749882, 0.03773583 ] + - [ -0.02379784, 0.00689664, 0.999693, 1.95320223 ] + - [ 0.0, 0.0, 0.0, 1.0 ] + enable_tracking: True # True if you want to enable tracking + visualize_2d: False # True to see 2D detection visualization + use_cyl_roi: False # True to use a cylinder ROI + save_data: False # True to save sensor input data + orientation: False # True to detect flipped cones + use_start_frame: True # True to output in START frame + + perception_normalization: StandardPerceptionNormalizer + planning: + relations_estimation: + type: pedestrian_yield_logic.PedestrianYielder + args: + mode: 'real' + params: { + 'yielder': 'expert', # 'expert', 'analytic', or 'simulation' + 'planner': 'milestone', # 'milestone', 'dt', or 'dx' + 'desired_speed': 1.0, # m/s, 1.5 m/s seems max speed? Feb24 + 'acceleration': 0.75 # m/s2, 0.5 is not enough to start moving. Feb24 + } + route_planning: + type: StaticRoutePlanner + args: [!relative_path '../GEMstack/knowledge/routes/forward_15m.csv','start'] + motion_planning: longitudinal_planning.YieldTrajectoryPlanner + trajectory_tracking: + type: pure_pursuit.PurePursuitTrajectoryTracker + print: False + + +log: + # Specify the top-level folder to save the log files. Default is 'logs' + #folder : 'logs' + # If prefix is specified, then the log folder will be named with the prefix followed by the date and time. Default no prefix + #prefix : 'fixed_route_' + # If suffix is specified, then logs will output to folder/prefix+suffix. Default uses date and time as the suffix + #suffix : 'test3' + # Specify which ros topics to record to vehicle.bag. Default records nothing. This records the "standard" ROS topics. + ros_topics : + # Specify options to pass to rosbag record. Default is no options. + #rosbag_options : '--split --size=1024' + # If True, then record all readings / commands of the vehicle interface. Default False + vehicle_interface : True + # Specify which components to record to behavior.json. Default records nothing + components : ['state_estimation','agent_detection','motion_planning'] + # Specify which components of state to record to state.json. Default records nothing + #state: ['all'] + # Specify the rate in Hz at which to record state to state.json. Default records at the pipeline's rate + #state_rate: 10 + # If True, then make plots of the recorded data specifically from PurePursuitTrajectoryTracker_debug.csv and report metrics. Default False + #auto_plot : True +replay: # Add items here to set certain topics / inputs to be replayed from logs + # Specify which log folder to replay from + log: + ros_topics : [] + components : [] + +#usually can keep this constant +computation_graph: !include "../GEMstack/knowledge/defaults/computation_graph.yaml" + +variants: + detector_only: + run: + description: "Run the pedestrian detection code" + drive: + planning: + trajectory_tracking: + real_sim: + run: + description: "Run the pedestrian detection code with real detection and fake simulation" + mode: hardware + vehicle_interface: + type: gem_mixed.GEMRealSensorsWithSimMotionInterface + args: + scene: !relative_path '../scenes/xyhead_demo.yaml' + mission_execution: StandardExecutor + require_engaged: False + visualization: !include "klampt_visualization.yaml" + drive: + perception: + state_estimation : OmniscientStateEstimator + planning: + relations_estimation: + type: pedestrian_yield_logic.PedestrianYielder + args: + mode: 'sim' + + fake_real: + run: + description: "Run the yielding trajectory planner on the real vehicle with faked perception" + drive: + perception: + agent_detection : pedestrian_detection.FakePedestrianDetector2D + + fake_sim: + run: + description: "Run the yielding trajectory planner in simulation with faked perception" + mode: simulation + vehicle_interface: + type: gem_simulator.GEMDoubleIntegratorSimulationInterface + args: + scene: !relative_path '../scenes/xyhead_demo.yaml' + visualization: !include "klampt_visualization.yaml" + drive: + perception: + # agent_detection : pedestrian_detection.FakePedestrianDetector2D + agent_detection : OmniscientAgentDetector #this option reads agents from the simulator + state_estimation : OmniscientStateEstimator + planning: + relations_estimation: + type: pedestrian_yield_logic.PedestrianYielder + args: + mode: 'sim' \ No newline at end of file diff --git a/launch/test_transformation.py b/launch/test_transformation.py new file mode 100644 index 000000000..c75b5431c --- /dev/null +++ b/launch/test_transformation.py @@ -0,0 +1,53 @@ +import math +import numpy as np +from scipy.spatial.transform import Rotation as R + +class Pose: + def __init__(self, x=0, y=0, z=0, yaw=0, pitch=0, roll=0): + self.x = x + self.y = y + self.z = z + self.yaw = yaw + self.pitch = pitch + self.roll = roll + +def pose_to_matrix(pose): + """ + Compose a 4x4 transformation matrix from a pose state. + Assumes pose has attributes: x, y, z, yaw, pitch, roll (angles in degrees). + """ + x = pose.x or 0.0 + y = pose.y or 0.0 + z = pose.z or 0.0 + yaw = math.radians(pose.yaw or 0.0) + pitch = math.radians(pose.pitch or 0.0) + roll = math.radians(pose.roll or 0.0) + + R_mat = R.from_euler('zyx', [yaw, pitch, roll]).as_matrix() + T = np.eye(4) + T[:3, :3] = R_mat + T[:3, 3] = [x, y, z] + return T + +# A helper to transform a point and compare to expected +def test_transform(pose, point_vehicle, expected_world): + T = pose_to_matrix(pose) + hom_pt = np.append(point_vehicle, 1.0) + pt_world = (T @ hom_pt)[:3] + print(f"Pose: x={pose.x}, y={pose.y}, yaw={pose.yaw}°") + print(f" Transformed: {pt_world.round(3)} Expected: {np.array(expected_world)}\n") + +# Define the point in vehicle frame (1 m in front along x) +point = [1, 0, 0] + +# Test cases: +poses = [ + (Pose(0, 0, 0, 0), [1, 0, 0]), # identity → point stays at (1,0,0) + (Pose(1, 0, 0, 0), [2, 0, 0]), # translate +1x → (1+1,0,0) + (Pose(1, 0, 0, 45), [1, 1, 0]), # then yaw 90° around z → front→world+y + (Pose(1, 2, 0, 180), [0, 2, 0]), # yaw 180°: front→-x, plus translation + (Pose(0, 0, 0, -90), [0, -1, 0]) # yaw -90°: front→world -y +] + +for p, exp in poses: + test_transform(p, point, exp) diff --git a/requirements.txt b/requirements.txt index f8e808d90..39a55ee42 100644 --- a/requirements.txt +++ b/requirements.txt @@ -10,5 +10,6 @@ dacite # Perception ultralytics -lap==0.5.12 -open3d \ No newline at end of file +open3d +sklearn +lap==0.5.12 \ No newline at end of file diff --git a/scenes/xyhead_demo.yaml b/scenes/xyhead_demo.yaml index c6d97477a..2aa1059ed 100644 --- a/scenes/xyhead_demo.yaml +++ b/scenes/xyhead_demo.yaml @@ -3,7 +3,15 @@ agents: ped1: type: pedestrian position: [15.0, 2.0] + # position: [10.0, 2.0] nominal_velocity: 0.5 target: [15.0,10.0] + # target: [10.0,10.0] behavior: loop - \ No newline at end of file + + # ped2: + # type: pedestrian + # position: [15.0, 0.0] + # nominal_velocity: 0.25 + # target: [15.0,10.0] + # behavior: loop diff --git a/setup/Dockerfile.cuda11.8 b/setup/Dockerfile.cuda11.8 index ca8feb86e..f1951abdb 100644 --- a/setup/Dockerfile.cuda11.8 +++ b/setup/Dockerfile.cuda11.8 @@ -67,6 +67,7 @@ COPY requirements.txt /tmp/requirements.txt # Install Python dependencies RUN pip3 install -r /tmp/requirements.txt + # Install other Dependencies RUN apt-get install -y ros-noetic-septentrio-gnss-driver ros-noetic-ackermann-msgs ros-noetic-novatel-gps-msgs ros-noetic-gazebo-msgs diff --git a/setup/Dockerfile.cuda12 b/setup/Dockerfile.cuda12 index 906d66f7c..7798fbc70 100644 --- a/setup/Dockerfile.cuda12 +++ b/setup/Dockerfile.cuda12 @@ -68,6 +68,7 @@ COPY requirements.txt /tmp/requirements.txt # Install Python dependencies RUN pip3 install -r /tmp/requirements.txt + # Install other Dependencies RUN apt-get install -y ros-noetic-septentrio-gnss-driver ros-noetic-ackermann-msgs ros-noetic-novatel-gps-msgs ros-noetic-gazebo-msgs diff --git a/setup/docker-compose.yaml b/setup/docker-compose.yaml index f0c7703b8..d0b745c9e 100644 --- a/setup/docker-compose.yaml +++ b/setup/docker-compose.yaml @@ -14,12 +14,14 @@ services: stdin_open: true tty: true volumes: - # - "/etc/group:/etc/group:ro" - # - "/etc/passwd:/etc/passwd:ro" - # - "/etc/shadow:/etc/shadow:ro" - # - "/etc/sudoers.d:/etc/sudoers.d:ro" + - "/etc/group:/etc/group:ro" + - "/etc/passwd:/etc/passwd:ro" + - "/etc/shadow:/etc/shadow:ro" + - "/etc/sudoers.d:/etc/sudoers.d:ro" - "~:/home/${USER}/host" - "/tmp/.X11-unix:/tmp/.X11-unix:rw" + - "/run/user/${UID}/bus:/run/user/${UID}/bus:ro" + - "/tmp/runtime-${USER}:/tmp/runtime-${USER}:rw" environment: - DISPLAY=${DISPLAY} - XDG_RUNTIME_DIR=/tmp/runtime-${USER} @@ -32,6 +34,7 @@ services: ipc: host user: "${USER}:${USER}" # Un-Comment the following lines if you want to use Nvidia GPU + runtime: nvidia deploy: resources: reservations: diff --git a/setup/setup_this_machine.sh b/setup/setup_this_machine.sh index 4617388a8..f56a94bf3 100755 --- a/setup/setup_this_machine.sh +++ b/setup/setup_this_machine.sh @@ -56,6 +56,9 @@ git clone https://github.com/astuff/pacmod2.git git clone https://github.com/astuff/astuff_sensor_msgs.git && rm -rf astuff_sensor_msgs/ibeo_msgs git clone https://github.com/ros-perception/radar_msgs.git && cd radar_msgs; git checkout noetic; cd .. +# Remove the ibeo_msgs folder so it is not included +rm -rf astuff_sensor_msgs/ibeo_msgs + cd .. #back to catkin_ws rosdep update rosdep install --from-paths src --ignore-src -r -y diff --git a/testing/test_collision_detection.py b/testing/test_collision_detection.py new file mode 100644 index 000000000..fe3b6ff9d --- /dev/null +++ b/testing/test_collision_detection.py @@ -0,0 +1,35 @@ +#needed to import GEMstack from top level directory +import sys +import os +sys.path.append(os.getcwd()) +import time + +import numpy as np +import matplotlib.pyplot as plt +import matplotlib.patches as patches +import math + +from GEMstack.onboard.planning.pedestrian_yield_logic import CollisionDetector + +if __name__ == "__main__": + # Vehicle parameters. x, y, theta (angle in radians) + x1, y1, t1 = 4.0, 5.0, 0 + # Pedestrian parameters. x, y, theta (angle in radians) + x2, y2, t2 = 15.0, 2.1, 0 + # Velocity vectors: [vx, vy] + v1 = [1.0, 0] # Vehicle speed vector + v2 = [0, 0.5] # Pedestrian speed vector + # Total simulation time + total_time = 10.0 + + desired_speed = 0.5 + acceleration = -0.5 + + # Create and run the simulation. + start_time = time.time() + # Simulate with the above parameters: Whether to hit without decelerating + sim = CollisionDetector(x1, y1, t1, x2, y2, t2, v1, v2, total_time, desired_speed, acceleration) + + collision_distance = sim.run(is_displayed=True) + print(f"Collision distance: {collision_distance}") + # print(f"Simulation took {time.time() - start_time:.3f} seconds.") \ No newline at end of file diff --git a/testing/test_longitudinal_plan.py b/testing/test_longitudinal_plan.py new file mode 100644 index 000000000..78896e893 --- /dev/null +++ b/testing/test_longitudinal_plan.py @@ -0,0 +1,132 @@ +#needed to import GEMstack from top level directory +import sys +import os +sys.path.append(os.getcwd()) + +from GEMstack.state import Path, ObjectFrameEnum +from GEMstack.onboard.planning.longitudinal_planning import longitudinal_plan,longitudinal_brake +import matplotlib.pyplot as plt + + +mode = "milestone" # milestone, dt, dx + + +def test_longitudinal_planning(): + test_path = Path(ObjectFrameEnum.START,[(0,0),(1,0),(2,0),(3,0),(4,0),(5,0),(6,0)]) + test_path2 = Path(ObjectFrameEnum.START,[(5,0),(6,1),(7,2),(9,4)]) + + test_traj = longitudinal_brake(test_path, 2.0, 0.0) + assert (t1 < t2 for (t1,t2) in zip(test_traj.times[:-1],test_traj.times[1:]) ) + plt.plot(test_traj.times,[p[0] for p in test_traj.points]) + plt.title("Braking from 0 m/s (should just stay still)") + plt.xlabel('time') + plt.ylabel('position') + plt.show() + + plt.plot(test_traj.times,[v for v in test_traj.velocities]) + plt.title("Braking from 0 m/s (should just stay still)") + plt.xlabel('time') + plt.ylabel('velocity') + plt.show() + + test_traj = longitudinal_brake(test_path, 2.0, 2.0) + assert (t1 < t2 for (t1,t2) in zip(test_traj.times[:-1],test_traj.times[1:]) ) + plt.plot(test_traj.times,[p[0] for p in test_traj.points]) + plt.title("Braking from 2 m/s") + plt.xlabel('time') + plt.ylabel('position') + plt.show() + + plt.plot(test_traj.times,[v for v in test_traj.velocities]) + plt.title("Braking from 2 m/s") + plt.xlabel('time') + plt.ylabel('velocity') + plt.show() + + test_traj = longitudinal_plan(test_path, 1.1, 2.0, 3.0, 0.0, mode) + assert (t1 < t2 for (t1,t2) in zip(test_traj.times[:-1],test_traj.times[1:]) ) + plt.plot(test_traj.times,[p[0] for p in test_traj.points]) + plt.title("Accelerating from 0 m/s") + plt.xlabel('time') + plt.ylabel('position') + plt.show() + + plt.plot(test_traj.times,[v for v in test_traj.velocities]) + plt.title("Accelerating from 0 m/s") + plt.xlabel('time') + plt.ylabel('velocity') + plt.show() + + + test_traj = longitudinal_plan(test_path, 1.0, 2.0, 3.0, 2.0, mode) + assert (t1 < t2 for (t1,t2) in zip(test_traj.times[:-1],test_traj.times[1:]) ) + plt.plot(test_traj.times,[p[0] for p in test_traj.points]) + plt.title("Accelerating from 2 m/s") + plt.xlabel('time') + plt.ylabel('position') + plt.show() + + plt.plot(test_traj.times,[v for v in test_traj.velocities]) + plt.title("Accelerating from 2 m/s") + plt.xlabel('time') + plt.ylabel('velocity') + plt.show() + + + test_traj = longitudinal_plan(test_path, 0.0, 2.0, 3.0, 3.1, mode) + assert (t1 < t2 for (t1,t2) in zip(test_traj.times[:-1],test_traj.times[1:]) ) + plt.plot(test_traj.times,[p[0] for p in test_traj.points]) + plt.title("Keeping constant velocity at 3.1 m/s") + plt.xlabel('time') + plt.ylabel('position') + plt.show() + + plt.plot(test_traj.times,[v for v in test_traj.velocities]) + plt.title("Keeping constant velocity at 3.1 m/s") + plt.xlabel('time') + plt.ylabel('velocity') + plt.show() + + test_traj = longitudinal_plan(test_path, 2.0, 2.0, 20.0, 10.0, mode) + assert (t1 < t2 for (t1,t2) in zip(test_traj.times[:-1],test_traj.times[1:]) ) + plt.plot(test_traj.times,[p[0] for p in test_traj.points]) + plt.title("Too little time to stop, starting at 10 m/s") + plt.xlabel('time') + plt.ylabel('position') + plt.show() + + plt.plot(test_traj.times,[v for v in test_traj.velocities]) + plt.title("Too little time to stop, starting at 10 m/s") + plt.xlabel('time') + plt.ylabel('velocity') + plt.show() + + test_traj = longitudinal_brake(test_path, 2.0, 10.0) + plt.plot(test_traj.times,[p[0] for p in test_traj.points]) + plt.title("Too little time to stop, braking at 10 m/s") + plt.xlabel('time') + plt.ylabel('position') + plt.show() + + plt.plot(test_traj.times,[v for v in test_traj.velocities]) + plt.title("Too little time to stop, braking at 10 m/s") + plt.xlabel('time') + plt.ylabel('velocity') + plt.show() + + test_traj = longitudinal_plan(test_path2, 1.0, 2.0, 3.0, 0.0, mode) + plt.plot(test_traj.times,[p[0] for p in test_traj.points]) + plt.title("Nonuniform planning") + plt.xlabel('time') + plt.ylabel('position') + plt.show() + + plt.plot(test_traj.times,[v for v in test_traj.velocities]) + plt.title("Nonuniform planning") + plt.xlabel('time') + plt.ylabel('velocity') + plt.show() + + +if __name__ == '__main__': + test_longitudinal_planning() diff --git a/testing/test_yield_logic_analyic.ipynb b/testing/test_yield_logic_analyic.ipynb new file mode 100644 index 000000000..1c81ff742 --- /dev/null +++ b/testing/test_yield_logic_analyic.ipynb @@ -0,0 +1,603 @@ +{ + "cells": [ + { + "cell_type": "code", + "execution_count": 18, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "v1 84.8528137423857\n", + "a1x [0.1]\n", + "v1 84.8528137423857\n", + "P1 7.0710678118654755\n", + "t_c 0.07276090201378733\n", + "P1_new [4.36538941 4.36565412]\n", + "P2_new [5.0727609 5.0727609]\n", + "distance 1.0001871939422702\n", + "a1x [0.1]\n", + "v1 84.8528137423857\n", + "P1 7.0710678118654755\n", + "t_c 0.07276090201378733\n", + "P1_new [4.36538941 4.36565412]\n", + "P2_new [5.0727609 5.0727609]\n", + "distance 1.0001871939422702\n", + "a1x [0.1]\n", + "v1 84.8528137423857\n", + "P1 7.0710678118654755\n", + "t_c 0.07276090201378733\n", + "P1_new [4.36538941 4.36565412]\n", + "P2_new [5.0727609 5.0727609]\n", + "distance 1.0001871939422702\n", + "a1x [0.10000001]\n", + "v1 84.8528137423857\n", + "P1 7.0710678118654755\n", + "t_c 0.07276090201378733\n", + "P1_new [4.36538941 4.36565412]\n", + "P2_new [5.0727609 5.0727609]\n", + "distance 1.0001871939701665\n", + "a1x [0.001]\n", + "v1 84.8528137423857\n", + "P1 7.0710678118654755\n", + "t_c 0.07276090201378733\n", + "P1_new [4.36565147 4.36565412]\n", + "P2_new [5.0727609 5.0727609]\n", + "distance 1.0000018717660313\n", + "a1x [0.001]\n", + "v1 84.8528137423857\n", + "P1 7.0710678118654755\n", + "t_c 0.07276090201378733\n", + "P1_new [4.36565147 4.36565412]\n", + "P2_new [5.0727609 5.0727609]\n", + "distance 1.0000018717660313\n", + "a1x [0.00100001]\n", + "v1 84.8528137423857\n", + "P1 7.0710678118654755\n", + "t_c 0.07276090201378733\n", + "P1_new [4.36565147 4.36565412]\n", + "P2_new [5.0727609 5.0727609]\n", + "distance 1.0000018717939232\n", + "Optimal Deceleration (Braking): 0.0010000000000002507\n" + ] + } + ], + "source": [ + "import numpy as np\n", + "from scipy.optimize import minimize\n", + "\n", + "def distance(P1, P2):\n", + " \"\"\" Compute Euclidean distance between two points \"\"\"\n", + " return np.linalg.norm(P1 - P2)\n", + "\n", + "def objective(a1):\n", + " \"\"\" Objective function: minimize deceleration a1 \"\"\"\n", + " return a1 # Minimize braking force\n", + "\n", + "def detect_collision(P1, P2, V1, V2, r1, r2):\n", + " \"\"\" Detects if a collision will occur with the given object and return deceleration to avoid it.\"\"\"\n", + " delta_p = P2 - P1\n", + " delta_v = V1 - V2\n", + "\n", + " # Normalize the vectors\n", + " norm_p = np.linalg.norm(delta_p)\n", + " norm_v = np.linalg.norm(delta_v)\n", + "\n", + " tol = 1e-6\n", + " # Avoid division by zero\n", + " if norm_p < tol or norm_v < tol:\n", + " return False\n", + "\n", + " unit_p = delta_p / norm_p # Normalized ΔP\n", + " unit_v = delta_v / norm_v # Normalized ΔV\n", + "\n", + " # Check if unit vectors are nearly identical\n", + " return np.allclose(unit_p, unit_v, atol=tol)\n", + "\n", + "def constraint_finite_difference(a1x, v1, v2, P1, P2, V1, V2, r1, r2):\n", + " \"\"\" Ensure Object 1 does not collide with Object 2 while braking \"\"\"\n", + "\n", + " print('a1x', a1x)\n", + " if a1x <= 0:\n", + " return -1 # Ensure positive deceleration\n", + " print('v1', v1)\n", + " print('P1', distance(P1, P2))\n", + " t_c = (distance(P1, P2) - (r1 + r2)) / (v1 - v2)\n", + " print('t_c', t_c)\n", + " P1_new = P1 + V1 * t_c - 0.5 * np.array([a1x[0], 0]) * t_c**2\n", + " P2_new = P2 + V2 * t_c # Object 2 continues normally\n", + " print('P1_new', P1_new)\n", + " print('P2_new', P2_new)\n", + " print('distance', distance(P1_new, P2_new))\n", + " # Ensure new positions do not result in a collision\n", + " return distance(P1_new, P2_new) - (r1 + r2)\n", + "\n", + "\n", + "# Example input\n", + "P1 = np.array([0, 0])\n", + "V1 = np.array([60, 60]) # Initial velocity of Object 1\n", + "P2 = np.array([5, 5])\n", + "V2 = np.array([1, 1]) # Velocity of Object 2\n", + "v1 = np.linalg.norm(V1) # Compute initial speed\n", + "v2 = np.linalg.norm(V2)\n", + "print('v1', v1)\n", + "r1 = 0.5 # Radius of Object 1\n", + "r2 = 0.5 # Radius of Object 2\n", + "\n", + "# Initial guess: a1\n", + "a1x0 = 0.1 # Start with a small deceleration\n", + "\n", + "# Bounds: (a1 in (0, 1] to ensure positive braking)\n", + "bounds = [(1e-3, 1)] # Prevent zero deceleration\n", + "\n", + "# Solve optimization problem\n", + "res = minimize(\n", + " objective, \n", + " a1x0, \n", + " bounds=bounds,\n", + " constraints={'type': 'ineq', 'fun': constraint_finite_difference, 'args': (v1, v2, P1, P2, V1, V2, r1, r2)}\n", + ")\n", + "\n", + "# Optimal deceleration\n", + "optimal_a1 = res.x[0]\n", + "print(\"Optimal Deceleration (Braking):\", optimal_a1)\n", + "\n", + "# # Compute braking duration based on optimal deceleration\n", + "# optimal_t_d = (s1 - (distance(P1, P2) / (distance(P1, P2) / (distance(P1, P2) / s1 + d_safe / s1)))) / optimal_a1\n", + "# print(\"Braking Duration (t_d):\", optimal_t_d)\n", + "\n", + "# # Compute new velocity after braking (only reducing speed, not direction)\n", + "# scaling_factor = 1 - (optimal_a1 * optimal_t_d / s1)\n", + "# V1_new = scaling_factor * V1\n", + "# print(\"New Velocity After Braking:\", V1_new)\n" + ] + }, + { + "cell_type": "code", + "execution_count": 8, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "7.0710678118654755\n" + ] + } + ], + "source": [ + "import math\n", + "print(math.sqrt(50))" + ] + }, + { + "cell_type": "code", + "execution_count": 11, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "2.146446609406726\n" + ] + } + ], + "source": [ + "\n", + "print((math.sqrt(50) - 1) / 2.8284271247461903)" + ] + }, + { + "cell_type": "code", + "execution_count": 24, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Collision detected. Computing optimal braking force...\n", + "a1x [0.1]\n", + "a1x [0.1]\n", + "a1x [0.1]\n", + "a1x [0.10000001]\n", + "a1x [0.14386871]\n", + "a1x [0.10438687]\n", + "a1x [0.10438687]\n", + "a1x [0.10438689]\n", + "a1x [0.14369264]\n", + "a1x [0.10831745]\n", + "a1x [0.10831745]\n", + "a1x [0.10831746]\n", + "a1x [0.14355521]\n", + "a1x [0.11184122]\n", + "a1x [0.11184122]\n", + "a1x [0.11184124]\n", + "a1x [0.1434475]\n", + "a1x [0.11500185]\n", + "a1x [0.11500185]\n", + "a1x [0.11500187]\n", + "a1x [0.14336277]\n", + "a1x [0.11783794]\n", + "a1x [0.11783794]\n", + "a1x [0.11783796]\n", + "a1x [0.14329589]\n", + "a1x [0.12038374]\n", + "a1x [0.12038374]\n", + "a1x [0.12038375]\n", + "a1x [0.14324297]\n", + "a1x [0.12266966]\n", + "a1x [0.12266966]\n", + "a1x [0.12266968]\n", + "a1x [0.14320024]\n", + "a1x [0.12472272]\n", + "a1x [0.12472272]\n", + "a1x [0.12472273]\n", + "a1x [0.14318682]\n", + "a1x [0.12656913]\n", + "a1x [0.12656913]\n", + "a1x [0.12656914]\n", + "a1x [0.1431409]\n", + "a1x [0.12822631]\n", + "a1x [0.12822631]\n", + "a1x [0.12822632]\n", + "a1x [0.14311966]\n", + "a1x [0.12971564]\n", + "a1x [0.12971564]\n", + "a1x [0.12971566]\n", + "a1x [0.14310267]\n", + "a1x [0.13105435]\n", + "a1x [0.13105435]\n", + "a1x [0.13105436]\n", + "a1x [0.14308908]\n", + "a1x [0.13225782]\n", + "a1x [0.13225782]\n", + "a1x [0.13225783]\n", + "a1x [0.14307818]\n", + "a1x [0.13333985]\n", + "a1x [0.13333985]\n", + "a1x [0.13333987]\n", + "a1x [0.14306944]\n", + "a1x [0.13431281]\n", + "a1x [0.13431281]\n", + "a1x [0.13431283]\n", + "a1x [0.14306244]\n", + "a1x [0.13518778]\n", + "a1x [0.13518778]\n", + "a1x [0.13518779]\n", + "a1x [0.14305574]\n", + "a1x [0.13597457]\n", + "a1x [0.13597457]\n", + "a1x [0.13597459]\n", + "a1x [0.14305222]\n", + "a1x [0.13668234]\n", + "a1x [0.13668234]\n", + "a1x [0.13668235]\n", + "a1x [0.14304857]\n", + "a1x [0.13731896]\n", + "a1x [0.13731896]\n", + "a1x [0.13731898]\n", + "a1x [0.14304562]\n", + "a1x [0.13789163]\n", + "a1x [0.13789163]\n", + "a1x [0.13789164]\n", + "a1x [0.14304325]\n", + "a1x [0.13840679]\n", + "a1x [0.13840679]\n", + "a1x [0.1384068]\n", + "a1x [0.14304133]\n", + "a1x [0.13887024]\n", + "a1x [0.13887024]\n", + "a1x [0.13887026]\n", + "a1x [0.14303979]\n", + "a1x [0.1392872]\n", + "a1x [0.1392872]\n", + "a1x [0.13928721]\n", + "a1x [0.14303861]\n", + "a1x [0.13966234]\n", + "a1x [0.13966234]\n", + "a1x [0.13966235]\n", + "a1x [0.14303753]\n", + "a1x [0.13999986]\n", + "a1x [0.13999986]\n", + "a1x [0.13999987]\n", + "a1x [0.14303672]\n", + "a1x [0.14030354]\n", + "a1x [0.14030354]\n", + "a1x [0.14030356]\n", + "a1x [0.14303606]\n", + "a1x [0.1405768]\n", + "a1x [0.1405768]\n", + "a1x [0.14057681]\n", + "a1x [0.14303553]\n", + "a1x [0.14082267]\n", + "a1x [0.14082267]\n", + "a1x [0.14082268]\n", + "a1x [0.1430351]\n", + "a1x [0.14104391]\n", + "a1x [0.14104391]\n", + "a1x [0.14104393]\n", + "a1x [0.14303475]\n", + "a1x [0.141243]\n", + "a1x [0.141243]\n", + "a1x [0.14124301]\n", + "a1x [0.14303454]\n", + "a1x [0.14142215]\n", + "a1x [0.14142215]\n", + "a1x [0.14142217]\n", + "a1x [0.14303425]\n", + "a1x [0.14158336]\n", + "a1x [0.14158336]\n", + "a1x [0.14158338]\n", + "a1x [0.14303406]\n", + "a1x [0.14172843]\n", + "a1x [0.14172843]\n", + "a1x [0.14172845]\n", + "a1x [0.14303391]\n", + "a1x [0.14185898]\n", + "a1x [0.14185898]\n", + "a1x [0.14185899]\n", + "a1x [0.14303379]\n", + "a1x [0.14197646]\n", + "a1x [0.14197646]\n", + "a1x [0.14197648]\n", + "a1x [0.1430337]\n", + "a1x [0.14208218]\n", + "a1x [0.14208218]\n", + "a1x [0.1420822]\n", + "a1x [0.14303362]\n", + "a1x [0.14217733]\n", + "a1x [0.14217733]\n", + "a1x [0.14217734]\n", + "a1x [0.14303347]\n", + "a1x [0.14226294]\n", + "a1x [0.14226294]\n", + "a1x [0.14226296]\n", + "No feasible solution found. Consider adjusting parameters.\n" + ] + } + ], + "source": [ + "import numpy as np\n", + "from scipy.optimize import minimize\n", + "\n", + "def distance(P1, P2):\n", + " \"\"\" Compute Euclidean distance between two points \"\"\"\n", + " return np.linalg.norm(P1 - P2)\n", + "\n", + "def detect_collision(P1, P2, V1, V2, r1, r2):\n", + " \"\"\"\n", + " Checks if a collision is possible based on initial relative motion.\n", + " \"\"\"\n", + " delta_p = P2 - P1 # Displacement vector\n", + " delta_v = V2 - V1 # Relative velocity\n", + "\n", + " # Check if objects are moving toward each other\n", + " return np.dot(delta_p, delta_v) < 0\n", + "\n", + "def constraint_no_collision(a1x, P1, P2, V1, V2, r1, r2, t_final):\n", + " \"\"\"\n", + " Ensures that Object 1 does not collide with Object 2 during the movement.\n", + " \"\"\"\n", + "\n", + " # Simulate motion for multiple time steps\n", + " time_steps = np.linspace(0, t_final, num=100)\n", + " print('a1x', a1x)\n", + " for t in time_steps:\n", + " # Update Object 1's position (only decelerating in x-direction)\n", + " new_x = P1[0] + V1[0] * t - 0.5 * a1x[0] * t**2 # Apply braking in x direction\n", + " new_y = P1[1] + V1[1] * t # Y-direction remains unchanged\n", + " P1_new = np.array([new_x, new_y])\n", + "\n", + " # Update Object 2's position (continues moving)\n", + " P2_new = P2 + V2 * t\n", + "\n", + " # Check if collision occurs\n", + " if distance(P1_new, P2_new) < (r1 + r2):\n", + " return distance(P1_new, P2_new) - (r1 + r2) # Violation of collision constraint\n", + "\n", + " return distance(P1_new, P2_new) - (r1 + r2) # No collision\n", + "\n", + "def objective(a1x):\n", + " \"\"\" Objective function: minimize deceleration a1x \"\"\"\n", + " return a1x # Minimize braking force\n", + "\n", + "if __name__ == \"__main__\":\n", + " # Define initial conditions\n", + " P1 = np.array([0, 0]) # Initial position of Object 1\n", + " V1 = np.array([5, 2]) # Initial velocity of Object 1\n", + " P2 = np.array([10, 10]) # Initial position of Object 2\n", + " V2 = np.array([2, -1]) # Velocity of Object 2\n", + " r1, r2 = 1, 1 # Radii of the objects\n", + " t_final = 5 # Maximum time to check for collisions\n", + "\n", + " # Check if collision is even possible before optimization\n", + " if detect_collision(P1, P2, V1, V2, r1, r2):\n", + " print(\"Collision detected. Computing optimal braking force...\")\n", + "\n", + " # Initial guess for deceleration\n", + " a1x0 = [0.1] # Small initial deceleration\n", + "\n", + " # Bounds: a1x in [0, max] to ensure non-negative braking\n", + " bounds = [(0.0, 10000000)] # Prevents infinite braking\n", + "\n", + " # Solve optimization problem\n", + " res = minimize(\n", + " objective,\n", + " a1x0,\n", + " bounds=bounds,\n", + " constraints={'type': 'ineq', 'fun': constraint_no_collision, 'args': (P1, P2, V1, V2, r1, r2, t_final)},\n", + " method=\"SLSQP\"\n", + " )\n", + "\n", + " # Optimal deceleration\n", + " if res.success:\n", + " optimal_a1x = res.x[0]\n", + " print(f\"Optimal Deceleration in x-direction: {optimal_a1x:.4f}\")\n", + " else:\n", + " print(\"No feasible solution found. Consider adjusting parameters.\")\n", + " else:\n", + " print(\"No collision detected. No braking required.\")\n" + ] + }, + { + "cell_type": "code", + "execution_count": 35, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Collision detected. Computing optimal braking force...\n", + "Estimated time to collision: 0.02 seconds\n", + "No feasible solution found. Consider adjusting parameters.\n" + ] + } + ], + "source": [ + "import numpy as np\n", + "from scipy.optimize import minimize\n", + "\n", + "def distance(P1, P2):\n", + " \"\"\" Compute Euclidean distance between two points \"\"\"\n", + " return np.linalg.norm(P1 - P2)\n", + "\n", + "def detect_collision(P1, P2, V1, V2, r1, r2):\n", + " \"\"\"\n", + " Checks if a collision is possible based on initial relative motion.\n", + " \"\"\"\n", + " delta_p = P2 - P1 # Displacement vector\n", + " delta_v = V2 - V1 # Relative velocity\n", + "\n", + " # Check if objects are moving toward each other\n", + " return np.dot(delta_p, delta_v) < 0\n", + "\n", + "def estimate_collision_time(P1, P2, V1, V2, r1, r2):\n", + " \"\"\"\n", + " Estimates the time of closest approach (if collision is possible).\n", + " \"\"\"\n", + " delta_p = P2 - P1\n", + " delta_v = V2 - V1\n", + "\n", + " if np.linalg.norm(delta_v) < 1e-6:\n", + " return np.inf # If objects have no relative velocity, they won't collide\n", + "\n", + " t_c = -np.dot(delta_p, delta_v) / np.linalg.norm(delta_v)**2\n", + "\n", + " if t_c < 0:\n", + " return np.inf # If t_c is negative, the objects were closer in the past\n", + "\n", + " return t_c\n", + "\n", + "def constraint_no_collision(a1x, P1, P2, V1, V2, r1, r2):\n", + " \"\"\"\n", + " Ensures Object 1 does not collide with Object 2 during movement.\n", + " \"\"\"\n", + "\n", + " # Estimate time of closest approach\n", + " # t_c = estimate_collision_time(P1, P2, V1, V2, r1, r2)\n", + " # if t_c == np.inf:\n", + " # return 1 # No collision risk\n", + "\n", + " # Simulate motion for multiple time steps up to t_c\n", + " time_steps = np.linspace(0, min(500, 5), num=10000) # Consider max 5 seconds\n", + "\n", + " for t in time_steps:\n", + " # Update Object 1's position (only decelerating in x-direction)\n", + " new_x = P1[0] + V1[0] * t - 0.5 * a1x[0] * t**2 # Apply braking in x direction\n", + " new_y = P1[1] + V1[1] * t # Y-direction remains unchanged\n", + " P1_new = np.array([new_x, new_y])\n", + "\n", + " # Update Object 2's position (continues moving)\n", + " P2_new = P2 + V2 * t\n", + "\n", + " # Check if collision occurs\n", + " d = distance(P1_new, P2_new) - (r1 + r2)\n", + "\n", + " if d < 0: # Collision detected\n", + " return d # Negative value signals violation\n", + "\n", + " return 1 # Constraint satisfied\n", + "\n", + "def objective(a1x):\n", + " \"\"\" Objective function: minimize deceleration a1x \"\"\"\n", + " return a1x # Minimize braking force\n", + "\n", + "if __name__ == \"__main__\":\n", + " # Define initial conditions\n", + " P1 = np.array([0, 0]) # Initial position of Object 1\n", + " V1 = np.array([500, 500]) # Initial velocity of Object 1\n", + " P2 = np.array([10, 10]) # Initial position of Object 2\n", + " V2 = np.array([1, 1]) # Velocity of Object 2\n", + " r1, r2 = 1, 1 # Radii of the objects\n", + "\n", + " # Check if a collision is even possible before optimization\n", + " if detect_collision(P1, P2, V1, V2, r1, r2):\n", + " print(\"Collision detected. Computing optimal braking force...\")\n", + "\n", + " # Estimate time to collision\n", + " t_final = estimate_collision_time(P1, P2, V1, V2, r1, r2)\n", + "\n", + " if t_final == np.inf:\n", + " print(\"No risk of collision. No braking required.\")\n", + " else:\n", + " print(f\"Estimated time to collision: {t_final:.2f} seconds\")\n", + "\n", + " # Initial guess for deceleration\n", + " a1x0 = [0.1] # Small initial deceleration\n", + "\n", + " # Bounds: a1x in [0, 50] to ensure non-negative braking\n", + " bounds = [(0.0, 50)] # Allow strong braking if needed\n", + "\n", + " # Solve optimization problem\n", + " res = minimize(\n", + " objective,\n", + " a1x0,\n", + " bounds=bounds,\n", + " constraints={'type': 'ineq', 'fun': constraint_no_collision, 'args': (P1, P2, V1, V2, r1, r2)},\n", + " method=\"SLSQP\"\n", + " )\n", + "\n", + " # Optimal deceleration\n", + " if res.success:\n", + " optimal_a1x = res.x[0]\n", + " print(f\"Optimal Deceleration in x-direction: {optimal_a1x:.4f}\")\n", + " else:\n", + " print(\"No feasible solution found. Consider adjusting parameters.\")\n", + " else:\n", + " print(\"No collision detected. No braking required.\")\n" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [] + } + ], + "metadata": { + "kernelspec": { + "display_name": "Python 3", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.8.10" + } + }, + "nbformat": 4, + "nbformat_minor": 2 +} diff --git a/tuning logs/2025-02-09_15-47-37 (before tuning)/.~lock.PurePursuitTrajectoryTracker_debug.csv# b/tuning logs/2025-02-09_15-47-37 (before tuning)/.~lock.PurePursuitTrajectoryTracker_debug.csv# new file mode 100644 index 000000000..15ee4e380 --- /dev/null +++ b/tuning logs/2025-02-09_15-47-37 (before tuning)/.~lock.PurePursuitTrajectoryTracker_debug.csv# @@ -0,0 +1 @@ +,acrl,acrl,09.02.2025 15:48,file:///home/acrl/.config/libreoffice/4; \ No newline at end of file diff --git a/tuning logs/2025-02-09_15-47-37 (before tuning)/PurePursuitTrajectoryTracker_debug.csv b/tuning logs/2025-02-09_15-47-37 (before tuning)/PurePursuitTrajectoryTracker_debug.csv new file mode 100644 index 000000000..18c4a8214 --- /dev/null +++ b/tuning logs/2025-02-09_15-47-37 (before tuning)/PurePursuitTrajectoryTracker_debug.csv @@ -0,0 +1,3331 @@ +curr pt[0] time,curr pt[0] vehicle time,curr pt[0],curr pt[1] time,curr pt[1] vehicle time,curr pt[1],curr param time,curr param vehicle time,curr param,desired pt[0] time,desired pt[0] vehicle time,desired pt[0],desired pt[1] time,desired pt[1] vehicle time,desired pt[1],desired yaw (rad) time,desired yaw (rad) vehicle time,desired yaw (rad),crosstrack error time,crosstrack error vehicle time,crosstrack error,front wheel angle (rad) time,front wheel angle (rad) vehicle time,front wheel angle (rad),desired speed (m/s) time,desired speed (m/s) vehicle time,desired speed (m/s),feedforward accel (m/s^2) time,feedforward accel (m/s^2) vehicle time,feedforward accel (m/s^2),output accel (m/s^2) time,output accel (m/s^2) vehicle time,output accel (m/s^2),current yaw (rad) time,current yaw (rad) vehicle time,current yaw (rad),current speed (m/s) time,current speed (m/s) vehicle time,current speed (m/s) +1739137658.1560988,0.019999980926513672,0.0,1739137658.1561017,0.019999980926513672,0.0,1739137658.1561046,0.019999980926513672,2e-06,1739137658.1561072,0.019999980926513672,1.9947503416207786,1739137658.156109,0.019999980926513672,-0.06638719928805828,1739137658.156111,0.019999980926513672,-0.03326867705567338,1739137658.1561127,0.019999980926513672,-0.06638719928805828,1739137658.156114,0.019999980926513672,-0.255368292345595,1739137658.1561158,0.019999980926513672,2.434486501996753,1739137658.1561172,0.019999980926513672,0.0,1739137658.156119,0.019999980926513672,2.434486501996753,1739137658.1561205,0.019999980926513672,0.0,1739137658.156122,0.019999980926513672,0.0 +1739137658.174843,0.039999961853027344,0.0,1739137658.1748457,0.039999961853027344,0.0,1739137658.1748486,0.039999961853027344,2e-06,1739137658.1748512,0.039999961853027344,1.9947503416207786,1739137658.1748526,0.039999961853027344,-0.06638719928805828,1739137658.1748545,0.039999961853027344,-0.03326867705567338,1739137658.1748562,0.039999961853027344,-0.06638719928805828,1739137658.1748574,0.039999961853027344,-0.255368292345595,1739137658.1748588,0.039999961853027344,2.434486501996753,1739137658.1748602,0.039999961853027344,0.0,1739137658.1748617,0.039999961853027344,2.434486501996753,1739137658.1748636,0.039999961853027344,0.0,1739137658.174865,0.039999961853027344,0.0 +1739137658.1948607,0.059999942779541016,0.00047983963607833857,1739137658.1948633,0.059999942779541016,-7.382692679414049e-09,1739137658.1948662,0.059999942779541016,1.5201603639216616e-06,1739137658.194869,0.059999942779541016,2.0906705661711618,1739137658.1948702,0.059999942779541016,-0.06755024778519472,1739137658.1948721,0.059999942779541016,-0.03230649574871559,1739137658.1948736,0.059999942779541016,-0.06744497884003313,1739137658.1948748,0.059999942779541016,-0.23638263434831996,1739137658.1948762,0.059999942779541016,2.4334566598647585,1739137658.1948779,0.059999942779541016,0.0,1739137658.1948793,0.059999942779541016,2.3714754758328263,1739137658.1948805,0.059999942779541016,6.2831349474322575,1739137658.1948817,0.059999942779541016,0.03197591848874033 +1739137658.21471,0.07999992370605469,0.00047983963607833857,1739137658.2147124,0.07999992370605469,-7.382692679414049e-09,1739137658.2147155,0.07999992370605469,1.5201603639216616e-06,1739137658.214718,0.07999992370605469,2.0906705661711618,1739137658.2147195,0.07999992370605469,-0.06755024778519472,1739137658.214721,0.07999992370605469,-0.03230649574871559,1739137658.2147226,0.07999992370605469,-0.06744497884003313,1739137658.2147238,0.07999992370605469,-0.23638263434831996,1739137658.214725,0.07999992370605469,2.4334566598647585,1739137658.2147267,0.07999992370605469,0.0,1739137658.2147279,0.07999992370605469,2.401480741376018,1739137658.2147293,0.07999992370605469,6.2831349474322575,1739137658.2147305,0.07999992370605469,0.03197591848874033 +1739137658.235332,0.09999990463256836,0.00047983963607833857,1739137658.2353344,0.09999990463256836,-7.382692679414049e-09,1739137658.2353375,0.09999990463256836,1.5201603639216616e-06,1739137658.2353404,0.09999990463256836,2.0906705661711618,1739137658.2353415,0.09999990463256836,-0.06755024778519472,1739137658.2353435,0.09999990463256836,-0.03230649574871559,1739137658.235345,0.09999990463256836,-0.06744497884003313,1739137658.235346,0.09999990463256836,-0.23638263434831996,1739137658.2353477,0.09999990463256836,2.4334566598647585,1739137658.2353492,0.09999990463256836,0.0,1739137658.2353506,0.09999990463256836,2.401480741376018,1739137658.235352,0.09999990463256836,6.2831349474322575,1739137658.2353532,0.09999990463256836,0.03197591848874033 +1739137658.2827468,0.14999985694885254,0.00047983963607833857,1739137658.2827501,0.14999985694885254,-7.382692679414049e-09,1739137658.2827535,0.14999985694885254,1.5201603639216616e-06,1739137658.2827563,0.14999985694885254,2.0906705661711618,1739137658.2827575,0.14999985694885254,-0.06755024778519472,1739137658.2827594,0.14999985694885254,-0.03230649574871559,1739137658.282761,0.14999985694885254,-0.06744497884003313,1739137658.2827625,0.14999985694885254,-0.23638263434831996,1739137658.282764,0.14999985694885254,2.4334566598647585,1739137658.2827656,0.14999985694885254,0.0,1739137658.2827668,0.14999985694885254,2.401480741376018,1739137658.2827687,0.14999985694885254,6.2831349474322575,1739137658.28277,0.14999985694885254,0.03197591848874033 +1739137658.3025825,0.1699998378753662,0.009488760325109702,1739137658.3025856,0.1699998378753662,-3.871437738389716e-06,1739137658.3025887,0.1699998378753662,0.0,1739137658.3025918,0.1699998378753662,2.419775955995444,1739137658.3025932,0.1699998378753662,-0.07243420639075222,1739137658.3025954,0.1699998378753662,-0.030041459197039617,1739137658.3025973,0.1699998378753662,-0.07031972567796632,1739137658.302602,0.1699998378753662,-0.18551742367070756,1739137658.3026085,0.1699998378753662,2.4306600393528326,1739137658.302611,0.1699998378753662,0.0,1739137658.302615,0.1699998378753662,2.1866798653339288,1739137658.3026175,0.1699998378753662,6.282309651457002,1739137658.30262,0.1699998378753662,0.1416939914738729 +1739137658.3847132,0.18999981880187988,0.009488760325109702,1739137658.3847165,0.18999981880187988,-3.871437738389716e-06,1739137658.3847198,0.18999981880187988,0.0,1739137658.384723,0.18999981880187988,2.419775955995444,1739137658.3847241,0.18999981880187988,-0.07243420639075222,1739137658.384726,0.18999981880187988,-0.030041459197039617,1739137658.3847275,0.18999981880187988,-0.07031972567796632,1739137658.384729,0.18999981880187988,-0.18551742367070756,1739137658.3847303,0.18999981880187988,2.4306600393528326,1739137658.3847315,0.18999981880187988,0.0,1739137658.384733,0.18999981880187988,2.2889660478789597,1739137658.3847344,0.18999981880187988,6.282309651457002,1739137658.384736,0.18999981880187988,0.1416939914738729 +1739137658.411551,0.20999979972839355,0.009488760325109702,1739137658.4115555,0.20999979972839355,-3.871437738389716e-06,1739137658.4115613,0.20999979972839355,0.0,1739137658.4115672,0.20999979972839355,2.419775955995444,1739137658.4115705,0.20999979972839355,-0.07243420639075222,1739137658.4115746,0.20999979972839355,-0.030041459197039617,1739137658.4115784,0.20999979972839355,-0.07031972567796632,1739137658.4115822,0.20999979972839355,-0.18551742367070756,1739137658.4115858,0.20999979972839355,2.4306600393528326,1739137658.4115896,0.20999979972839355,0.0,1739137658.4115932,0.20999979972839355,2.2889660478789597,1739137658.411597,0.20999979972839355,6.282309651457002,1739137658.4116008,0.20999979972839355,0.1416939914738729 +1739137658.470626,0.26999974250793457,0.009488760325109702,1739137658.4706285,0.26999974250793457,-3.871437738389716e-06,1739137658.4706316,0.26999974250793457,0.0,1739137658.4706345,0.26999974250793457,2.419775955995444,1739137658.470636,0.26999974250793457,-0.07243420639075222,1739137658.4706373,0.26999974250793457,-0.030041459197039617,1739137658.4706388,0.26999974250793457,-0.07031972567796632,1739137658.4706404,0.26999974250793457,-0.18551742367070756,1739137658.4706416,0.26999974250793457,2.4306600393528326,1739137658.4706433,0.26999974250793457,0.0,1739137658.4706445,0.26999974250793457,2.2889660478789597,1739137658.470646,0.26999974250793457,6.282309651457002,1739137658.4706473,0.26999974250793457,0.1416939914738729 +1739137658.4920034,0.28999972343444824,0.030566275467516668,1739137658.492008,0.28999972343444824,-3.978397365678177e-05,1739137658.4920146,0.28999972343444824,0.021552150593622765,1739137658.4920201,0.28999972343444824,2.7704242415779703,1739137658.4920232,0.28999972343444824,-0.07543663910884056,1739137658.492028,0.28999972343444824,-0.027511583739654052,1739137658.4920316,0.28999972343444824,-0.06802616304148179,1739137658.492035,0.28999972343444824,-0.1389861314898566,1739137658.4920385,0.28999972343444824,2.4328910109902946,1739137658.4920423,0.28999972343444824,0.0,1739137658.4920459,0.28999972343444824,2.083786274611481,1739137658.4920497,0.28999972343444824,6.28049523044231,1739137658.4920533,0.28999972343444824,0.25140003363415137 +1739137658.512025,0.3099997043609619,0.030566275467516668,1739137658.5120292,0.3099997043609619,-3.978397365678177e-05,1739137658.5120337,0.3099997043609619,0.021552150593622765,1739137658.5120394,0.3099997043609619,2.7704242415779703,1739137658.5120425,0.3099997043609619,-0.07543663910884056,1739137658.5120463,0.3099997043609619,-0.027511583739654052,1739137658.51205,0.3099997043609619,-0.06802616304148179,1739137658.5120535,0.3099997043609619,-0.1389861314898566,1739137658.5120568,0.3099997043609619,2.4328910109902946,1739137658.5120604,0.3099997043609619,0.0,1739137658.512064,0.3099997043609619,2.1814909773561433,1739137658.5120676,0.3099997043609619,6.28049523044231,1739137658.5120711,0.3099997043609619,0.25140003363415137 +1739137658.531495,0.3299996852874756,0.030566275467516668,1739137658.531499,0.3299996852874756,-3.978397365678177e-05,1739137658.5315037,0.3299996852874756,0.021552150593622765,1739137658.531509,0.3299996852874756,2.7704242415779703,1739137658.531512,0.3299996852874756,-0.07543663910884056,1739137658.5315158,0.3299996852874756,-0.027511583739654052,1739137658.5315192,0.3299996852874756,-0.06802616304148179,1739137658.5315228,0.3299996852874756,-0.1389861314898566,1739137658.531526,0.3299996852874756,2.4328910109902946,1739137658.5315297,0.3299996852874756,0.0,1739137658.531533,0.3299996852874756,2.1814909773561433,1739137658.5315366,0.3299996852874756,6.28049523044231,1739137658.53154,0.3299996852874756,0.25140003363415137 +1739137658.5505056,0.34999966621398926,0.030566275467516668,1739137658.5505083,0.34999966621398926,-3.978397365678177e-05,1739137658.5505114,0.34999966621398926,0.021552150593622765,1739137658.5505142,0.34999966621398926,2.7704242415779703,1739137658.5505157,0.34999966621398926,-0.07543663910884056,1739137658.5505178,0.34999966621398926,-0.027511583739654052,1739137658.5505192,0.34999966621398926,-0.06802616304148179,1739137658.5505207,0.34999966621398926,-0.1389861314898566,1739137658.5505219,0.34999966621398926,2.4328910109902946,1739137658.5505238,0.34999966621398926,0.0,1739137658.550525,0.34999966621398926,2.1814909773561433,1739137658.5505264,0.34999966621398926,6.28049523044231,1739137658.5505278,0.34999966621398926,0.25140003363415137 +1739137658.5711577,0.36999964714050293,0.030566275467516668,1739137658.571161,0.36999964714050293,-3.978397365678177e-05,1739137658.5711646,0.36999964714050293,0.021552150593622765,1739137658.5711677,0.36999964714050293,2.7704242415779703,1739137658.5711691,0.36999964714050293,-0.07543663910884056,1739137658.571171,0.36999964714050293,-0.027511583739654052,1739137658.5711727,0.36999964714050293,-0.06802616304148179,1739137658.5711741,0.36999964714050293,-0.1389861314898566,1739137658.5711753,0.36999964714050293,2.4328910109902946,1739137658.5711772,0.36999964714050293,0.0,1739137658.5711787,0.36999964714050293,2.1814909773561433,1739137658.5711806,0.36999964714050293,6.28049523044231,1739137658.5711818,0.36999964714050293,0.25140003363415137 +1739137658.5922012,0.3899996280670166,0.06370495600805981,1739137658.5922055,0.3899996280670166,-0.00017089492489841263,1739137658.5922105,0.3899996280670166,0.021883537399028197,1739137658.592216,0.3899996280670166,3.0996364246665196,1739137658.592219,0.3899996280670166,-0.07866398274683266,1739137658.592223,0.3899996280670166,-0.025848938183812595,1739137658.5922265,0.3899996280670166,-0.061893639756747894,1739137658.59223,0.3899996280670166,-0.103036781064373,1739137658.5922334,0.3899996280670166,2.438866240951109,1739137658.5922372,0.3899996280670166,0.0,1739137658.5922406,0.3899996280670166,1.9835946192849272,1739137658.5922446,0.3899996280670166,6.277718004048266,1739137658.5922482,0.3899996280670166,0.3610352136046854 +1739137658.610619,0.4099996089935303,0.06370495600805981,1739137658.6106222,0.4099996089935303,-0.00017089492489841263,1739137658.6106255,0.4099996089935303,0.021883537399028197,1739137658.6106284,0.4099996089935303,3.0996364246665196,1739137658.6106298,0.4099996089935303,-0.07866398274683266,1739137658.6106317,0.4099996089935303,-0.025848938183812595,1739137658.6106331,0.4099996089935303,-0.061893639756747894,1739137658.6106348,0.4099996089935303,-0.103036781064373,1739137658.610636,0.4099996089935303,2.438866240951109,1739137658.610638,0.4099996089935303,0.0,1739137658.6106393,0.4099996089935303,2.0778310273464236,1739137658.6106412,0.4099996089935303,6.277718004048266,1739137658.6106424,0.4099996089935303,0.3610352136046854 +1739137658.630747,0.42999958992004395,0.06370495600805981,1739137658.6307497,0.42999958992004395,-0.00017089492489841263,1739137658.6307528,0.42999958992004395,0.021883537399028197,1739137658.6307557,0.42999958992004395,3.0996364246665196,1739137658.6307569,0.42999958992004395,-0.07866398274683266,1739137658.630759,0.42999958992004395,-0.025848938183812595,1739137658.6307604,0.42999958992004395,-0.061893639756747894,1739137658.6307616,0.42999958992004395,-0.103036781064373,1739137658.630763,0.42999958992004395,2.438866240951109,1739137658.6307645,0.42999958992004395,0.0,1739137658.630766,0.42999958992004395,2.0778310273464236,1739137658.6307673,0.42999958992004395,6.277718004048266,1739137658.6307685,0.42999958992004395,0.3610352136046854 +1739137658.650796,0.4499995708465576,0.06370495600805981,1739137658.6507983,0.4499995708465576,-0.00017089492489841263,1739137658.6508012,0.4499995708465576,0.021883537399028197,1739137658.650804,0.4499995708465576,3.0996364246665196,1739137658.6508055,0.4499995708465576,-0.07866398274683266,1739137658.6508074,0.4499995708465576,-0.025848938183812595,1739137658.6508086,0.4499995708465576,-0.061893639756747894,1739137658.65081,0.4499995708465576,-0.103036781064373,1739137658.6508114,0.4499995708465576,2.438866240951109,1739137658.650813,0.4499995708465576,0.0,1739137658.6508145,0.4499995708465576,2.0778310273464236,1739137658.650816,0.4499995708465576,6.277718004048266,1739137658.6508174,0.4499995708465576,0.3610352136046854 +1739137658.6707785,0.4699995517730713,0.06370495600805981,1739137658.6707814,0.4699995517730713,-0.00017089492489841263,1739137658.6707845,0.4699995517730713,0.021883537399028197,1739137658.6707876,0.4699995517730713,3.0996364246665196,1739137658.670789,0.4699995517730713,-0.07866398274683266,1739137658.6707911,0.4699995517730713,-0.025848938183812595,1739137658.6707928,0.4699995517730713,-0.061893639756747894,1739137658.6707945,0.4699995517730713,-0.103036781064373,1739137658.6707957,0.4699995517730713,2.438866240951109,1739137658.6707976,0.4699995517730713,0.0,1739137658.6707988,0.4699995517730713,2.0778310273464236,1739137658.6708007,0.4699995517730713,6.277718004048266,1739137658.670802,0.4699995517730713,0.3610352136046854 +1739137658.690748,0.48999953269958496,0.06370495600805981,1739137658.6907508,0.48999953269958496,-0.00017089492489841263,1739137658.6907537,0.48999953269958496,0.021883537399028197,1739137658.6907568,0.48999953269958496,3.0996364246665196,1739137658.6907585,0.48999953269958496,-0.07866398274683266,1739137658.6907604,0.48999953269958496,-0.025848938183812595,1739137658.690762,0.48999953269958496,-0.061893639756747894,1739137658.6907635,0.48999953269958496,-0.103036781064373,1739137658.6907651,0.48999953269958496,2.438866240951109,1739137658.6907668,0.48999953269958496,0.0,1739137658.6907685,0.48999953269958496,2.0778310273464236,1739137658.69077,0.48999953269958496,6.277718004048266,1739137658.6907713,0.48999953269958496,0.3610352136046854 +1739137658.7108274,0.5099995136260986,0.10890817722579005,1739137658.71083,0.5099995136260986,-0.0004890063206310913,1739137658.7108328,0.5099995136260986,0.0223355696112055,1739137658.710836,0.5099995136260986,3.429071903590535,1739137658.7108374,0.5099995136260986,-0.08488799780887579,1739137658.7108393,0.5099995136260986,-0.02541465615061828,1739137658.7108405,0.5099995136260986,-0.055307237649998356,1739137658.7108421,0.5099995136260986,-0.07699779042225788,1739137658.7108436,0.5099995136260986,2.4453000538645098,1739137658.7108455,0.5099995136260986,0.0,1739137658.710847,0.5099995136260986,1.8807207707573985,1739137658.7108486,0.5099995136260986,6.274424026362159,1739137658.71085,0.5099995136260986,0.4707172092717497 +1739137658.731654,0.5299994945526123,0.10890817722579005,1739137658.7316573,0.5299994945526123,-0.0004890063206310913,1739137658.7316606,0.5299994945526123,0.0223355696112055,1739137658.731664,0.5299994945526123,3.429071903590535,1739137658.7316654,0.5299994945526123,-0.08488799780887579,1739137658.7316675,0.5299994945526123,-0.02541465615061828,1739137658.7316692,0.5299994945526123,-0.055307237649998356,1739137658.7316709,0.5299994945526123,-0.07699779042225788,1739137658.7316723,0.5299994945526123,2.4453000538645098,1739137658.7316744,0.5299994945526123,0.0,1739137658.7316759,0.5299994945526123,1.97458284459276,1739137658.7316778,0.5299994945526123,6.274424026362159,1739137658.7316794,0.5299994945526123,0.4707172092717497 +1739137658.7517931,0.549999475479126,0.10890817722579005,1739137658.751798,0.549999475479126,-0.0004890063206310913,1739137658.7518036,0.549999475479126,0.0223355696112055,1739137658.7518103,0.549999475479126,3.429071903590535,1739137658.7518141,0.549999475479126,-0.08488799780887579,1739137658.751819,0.549999475479126,-0.02541465615061828,1739137658.7518232,0.549999475479126,-0.055307237649998356,1739137658.7518275,0.549999475479126,-0.07699779042225788,1739137658.7518315,0.549999475479126,2.4453000538645098,1739137658.7518358,0.549999475479126,0.0,1739137658.7518404,0.549999475479126,1.97458284459276,1739137658.7518446,0.549999475479126,6.274424026362159,1739137658.751849,0.549999475479126,0.4707172092717497 +1739137658.771171,0.5699994564056396,0.10890817722579005,1739137658.7711744,0.5699994564056396,-0.0004890063206310913,1739137658.771178,0.5699994564056396,0.0223355696112055,1739137658.7711816,0.5699994564056396,3.429071903590535,1739137658.7711833,0.5699994564056396,-0.08488799780887579,1739137658.7711856,0.5699994564056396,-0.02541465615061828,1739137658.7711875,0.5699994564056396,-0.055307237649998356,1739137658.771189,0.5699994564056396,-0.07699779042225788,1739137658.771191,0.5699994564056396,2.4453000538645098,1739137658.7711928,0.5699994564056396,0.0,1739137658.7711945,0.5699994564056396,1.97458284459276,1739137658.7711964,0.5699994564056396,6.274424026362159,1739137658.771198,0.5699994564056396,0.4707172092717497 +1739137658.7909393,0.5899994373321533,0.10890817722579005,1739137658.7909427,0.5899994373321533,-0.0004890063206310913,1739137658.7909462,0.5899994373321533,0.0223355696112055,1739137658.7909498,0.5899994373321533,3.429071903590535,1739137658.7909515,0.5899994373321533,-0.08488799780887579,1739137658.7909536,0.5899994373321533,-0.02541465615061828,1739137658.7909553,0.5899994373321533,-0.055307237649998356,1739137658.790957,0.5899994373321533,-0.07699779042225788,1739137658.7909591,0.5899994373321533,2.4453000538645098,1739137658.7909608,0.5899994373321533,0.0,1739137658.7909625,0.5899994373321533,1.97458284459276,1739137658.7909644,0.5899994373321533,6.274424026362159,1739137658.7909663,0.5899994373321533,0.4707172092717497 +1739137658.8109107,0.609999418258667,0.16616774480877172,1739137658.8109138,0.609999418258667,-0.0010797110103126784,1739137658.8109174,0.609999418258667,0.022908165287035317,1739137658.8109207,0.609999418258667,3.758397996610445,1739137658.8109224,0.609999418258667,-0.09125328881356544,1739137658.8109245,0.609999418258667,-0.025097123034331422,1739137658.8109267,0.609999418258667,-0.046862810076064694,1739137658.810928,0.609999418258667,-0.05574008871618291,1739137658.81093,0.609999418258667,2.453573682890901,1739137658.8109317,0.609999418258667,0.0,1739137658.8109336,0.609999418258667,1.7811292930414357,1739137658.8109353,0.609999418258667,6.271130048676053,1739137658.8109372,0.609999418258667,0.5803236049971447 +1739137658.830875,0.6299993991851807,0.16616774480877172,1739137658.8308783,0.6299993991851807,-0.0010797110103126784,1739137658.8308814,0.6299993991851807,0.022908165287035317,1739137658.830885,0.6299993991851807,3.758397996610445,1739137658.8308864,0.6299993991851807,-0.09125328881356544,1739137658.8308885,0.6299993991851807,-0.025097123034331422,1739137658.8308902,0.6299993991851807,-0.046862810076064694,1739137658.8308918,0.6299993991851807,-0.05574008871618291,1739137658.8308938,0.6299993991851807,2.453573682890901,1739137658.830896,0.6299993991851807,0.0,1739137658.8308973,0.6299993991851807,1.8732500778937564,1739137658.8308995,0.6299993991851807,6.271130048676053,1739137658.830901,0.6299993991851807,0.5803236049971447 +1739137658.850967,0.6499993801116943,0.16616774480877172,1739137658.85097,0.6499993801116943,-0.0010797110103126784,1739137658.8509736,0.6499993801116943,0.022908165287035317,1739137658.850977,0.6499993801116943,3.758397996610445,1739137658.8509789,0.6499993801116943,-0.09125328881356544,1739137658.8509808,0.6499993801116943,-0.025097123034331422,1739137658.8509827,0.6499993801116943,-0.046862810076064694,1739137658.850984,0.6499993801116943,-0.05574008871618291,1739137658.850986,0.6499993801116943,2.453573682890901,1739137658.8509877,0.6499993801116943,0.0,1739137658.8509896,0.6499993801116943,1.8732500778937564,1739137658.8509912,0.6499993801116943,6.271130048676053,1739137658.8509932,0.6499993801116943,0.5803236049971447 +1739137658.8708668,0.669999361038208,0.16616774480877172,1739137658.8708699,0.669999361038208,-0.0010797110103126784,1739137658.8708735,0.669999361038208,0.022908165287035317,1739137658.8708768,0.669999361038208,3.758397996610445,1739137658.8708782,0.669999361038208,-0.09125328881356544,1739137658.8708806,0.669999361038208,-0.025097123034331422,1739137658.870882,0.669999361038208,-0.046862810076064694,1739137658.870884,0.669999361038208,-0.05574008871618291,1739137658.8708854,0.669999361038208,2.453573682890901,1739137658.8708873,0.669999361038208,0.0,1739137658.870889,0.669999361038208,1.8732500778937564,1739137658.8708909,0.669999361038208,6.271130048676053,1739137658.8708923,0.669999361038208,0.5803236049971447 +1739137658.8910694,0.6899993419647217,0.16616774480877172,1739137658.8910732,0.6899993419647217,-0.0010797110103126784,1739137658.891077,0.6899993419647217,0.022908165287035317,1739137658.8910809,0.6899993419647217,3.758397996610445,1739137658.891083,0.6899993419647217,-0.09125328881356544,1739137658.8910856,0.6899993419647217,-0.025097123034331422,1739137658.8910873,0.6899993419647217,-0.046862810076064694,1739137658.8910892,0.6899993419647217,-0.05574008871618291,1739137658.8910909,0.6899993419647217,2.453573682890901,1739137658.8910933,0.6899993419647217,0.0,1739137658.891095,0.6899993419647217,1.8732500778937564,1739137658.891097,0.6899993419647217,6.271130048676053,1739137658.891099,0.6899993419647217,0.5803236049971447 +1739137658.911272,0.7099993228912354,0.16616774480877172,1739137658.911276,0.7099993228912354,-0.0010797110103126784,1739137658.9112806,0.7099993228912354,0.022908165287035317,1739137658.9112847,0.7099993228912354,3.758397996610445,1739137658.9112868,0.7099993228912354,-0.09125328881356544,1739137658.9112897,0.7099993228912354,-0.025097123034331422,1739137658.9112918,0.7099993228912354,-0.046862810076064694,1739137658.911294,0.7099993228912354,-0.05574008871618291,1739137658.911296,0.7099993228912354,2.453573682890901,1739137658.911298,0.7099993228912354,0.0,1739137658.9113002,0.7099993228912354,1.8732500778937564,1739137658.9113023,0.7099993228912354,6.271130048676053,1739137658.9113045,0.7099993228912354,0.5803236049971447 +1739137658.9313402,0.729999303817749,0.23548666461475332,1739137658.9313447,0.729999303817749,-0.002022499727824645,1739137658.9313512,0.729999303817749,0.023601354485095132,1739137658.9313555,0.729999303817749,4.08801513935136,1739137658.9313574,0.729999303817749,-0.09660708178317665,1739137658.93136,0.729999303817749,-0.024546368809941765,1739137658.9313626,0.729999303817749,-0.03544239270275333,1739137658.931365,0.729999303817749,-0.03665550626198573,1739137658.9313672,0.729999303817749,2.4648076568951804,1739137658.9313695,0.729999303817749,0.0,1739137658.931372,0.729999303817749,1.6853496531955916,1739137658.9313743,0.729999303817749,6.267836070989946,1739137658.9313767,0.729999303817749,0.6899815662887875 +1739137658.9512632,0.7499992847442627,0.23548666461475332,1739137658.9512672,0.7499992847442627,-0.002022499727824645,1739137658.9512718,0.7499992847442627,0.023601354485095132,1739137658.9512758,0.7499992847442627,4.08801513935136,1739137658.9512784,0.7499992847442627,-0.09660708178317665,1739137658.9512808,0.7499992847442627,-0.024546368809941765,1739137658.951283,0.7499992847442627,-0.03544239270275333,1739137658.951285,0.7499992847442627,-0.03665550626198573,1739137658.951287,0.7499992847442627,2.4648076568951804,1739137658.9512894,0.7499992847442627,0.0,1739137658.9512913,0.7499992847442627,1.774826090606393,1739137658.951294,0.7499992847442627,6.267836070989946,1739137658.951296,0.7499992847442627,0.6899815662887875 +1739137658.9714048,0.7699992656707764,0.23548666461475332,1739137658.9714088,0.7699992656707764,-0.002022499727824645,1739137658.9714136,0.7699992656707764,0.023601354485095132,1739137658.971418,0.7699992656707764,4.08801513935136,1739137658.9714198,0.7699992656707764,-0.09660708178317665,1739137658.9714227,0.7699992656707764,-0.024546368809941765,1739137658.971425,0.7699992656707764,-0.03544239270275333,1739137658.971427,0.7699992656707764,-0.03665550626198573,1739137658.971429,0.7699992656707764,2.4648076568951804,1739137658.9714317,0.7699992656707764,0.0,1739137658.9714336,0.7699992656707764,1.774826090606393,1739137658.9714367,0.7699992656707764,6.267836070989946,1739137658.971439,0.7699992656707764,0.6899815662887875 +1739137658.991188,0.78999924659729,0.23548666461475332,1739137658.9911926,0.78999924659729,-0.002022499727824645,1739137658.991197,0.78999924659729,0.023601354485095132,1739137658.9912019,0.78999924659729,4.08801513935136,1739137658.991204,0.78999924659729,-0.09660708178317665,1739137658.991207,0.78999924659729,-0.024546368809941765,1739137658.9912093,0.78999924659729,-0.03544239270275333,1739137658.991211,0.78999924659729,-0.03665550626198573,1739137658.991213,0.78999924659729,2.4648076568951804,1739137658.9912157,0.78999924659729,0.0,1739137658.9912176,0.78999924659729,1.774826090606393,1739137658.99122,0.78999924659729,6.267836070989946,1739137658.9912224,0.78999924659729,0.6899815662887875 +1739137659.0110693,0.8099992275238037,0.23548666461475332,1739137659.0110729,0.8099992275238037,-0.002022499727824645,1739137659.0110774,0.8099992275238037,0.023601354485095132,1739137659.0110815,0.8099992275238037,4.08801513935136,1739137659.0110836,0.8099992275238037,-0.09660708178317665,1739137659.0110862,0.8099992275238037,-0.024546368809941765,1739137659.0110886,0.8099992275238037,-0.03544239270275333,1739137659.011091,0.8099992275238037,-0.03665550626198573,1739137659.0110927,0.8099992275238037,2.4648076568951804,1739137659.011095,0.8099992275238037,0.0,1739137659.0110974,0.8099992275238037,1.774826090606393,1739137659.0110996,0.8099992275238037,6.267836070989946,1739137659.0111015,0.8099992275238037,0.6899815662887875 +1739137659.0312595,0.8299992084503174,0.31685554567320917,1739137659.0312638,0.8299992084503174,-0.0033966940746790186,1739137659.0312681,0.8299992084503174,0.02441504329567969,1739137659.0312726,0.8299992084503174,4.4175289908862165,1739137659.0312748,0.8299992084503174,-0.1009836554542913,1739137659.0312774,0.8299992084503174,-0.02379329801419388,1739137659.0312796,0.8299992084503174,-0.021124699196407658,1739137659.0312817,0.8299992084503174,-0.019284994033337995,1739137659.0312836,0.8299992084503174,2.478964300531405,1739137659.0312865,0.8299992084503174,0.0,1739137659.0312886,0.8299992084503174,1.5926586683633346,1739137659.0312905,0.8299992084503174,6.264542093303839,1739137659.031293,0.8299992084503174,0.7995591972901228 +1739137659.05119,0.849999189376831,0.31685554567320917,1739137659.051194,0.849999189376831,-0.0033966940746790186,1739137659.0511985,0.849999189376831,0.02441504329567969,1739137659.0512028,0.849999189376831,4.4175289908862165,1739137659.051205,0.849999189376831,-0.1009836554542913,1739137659.0512078,0.849999189376831,-0.02379329801419388,1739137659.05121,0.849999189376831,-0.021124699196407658,1739137659.0512125,0.849999189376831,-0.019284994033337995,1739137659.0512147,0.849999189376831,2.478964300531405,1739137659.0512168,0.849999189376831,0.0,1739137659.0512192,0.849999189376831,1.6794051032412822,1739137659.0512211,0.849999189376831,6.264542093303839,1739137659.0512235,0.849999189376831,0.7995591972901228 +1739137659.0712526,0.8699991703033447,0.31685554567320917,1739137659.0712564,0.8699991703033447,-0.0033966940746790186,1739137659.071261,0.8699991703033447,0.02441504329567969,1739137659.071265,0.8699991703033447,4.4175289908862165,1739137659.0712674,0.8699991703033447,-0.1009836554542913,1739137659.07127,0.8699991703033447,-0.02379329801419388,1739137659.0712721,0.8699991703033447,-0.021124699196407658,1739137659.0712745,0.8699991703033447,-0.019284994033337995,1739137659.0712764,0.8699991703033447,2.478964300531405,1739137659.0712788,0.8699991703033447,0.0,1739137659.071281,0.8699991703033447,1.6794051032412822,1739137659.0712833,0.8699991703033447,6.264542093303839,1739137659.0712852,0.8699991703033447,0.7995591972901228 +1739137659.0912945,0.8899991512298584,0.31685554567320917,1739137659.0912983,0.8899991512298584,-0.0033966940746790186,1739137659.0913029,0.8899991512298584,0.02441504329567969,1739137659.0913072,0.8899991512298584,4.4175289908862165,1739137659.0913093,0.8899991512298584,-0.1009836554542913,1739137659.091312,0.8899991512298584,-0.02379329801419388,1739137659.0913138,0.8899991512298584,-0.021124699196407658,1739137659.091316,0.8899991512298584,-0.019284994033337995,1739137659.0913181,0.8899991512298584,2.478964300531405,1739137659.0913203,0.8899991512298584,0.0,1739137659.0913224,0.8899991512298584,1.6794051032412822,1739137659.0913246,0.8899991512298584,6.264542093303839,1739137659.0913267,0.8899991512298584,0.7995591972901228 +1739137659.1112316,0.9099991321563721,0.31685554567320917,1739137659.1112356,0.9099991321563721,-0.0033966940746790186,1739137659.11124,0.9099991321563721,0.02441504329567969,1739137659.111244,0.9099991321563721,4.4175289908862165,1739137659.1112463,0.9099991321563721,-0.1009836554542913,1739137659.111249,0.9099991321563721,-0.02379329801419388,1739137659.111251,0.9099991321563721,-0.021124699196407658,1739137659.1112533,0.9099991321563721,-0.019284994033337995,1739137659.1112554,0.9099991321563721,2.478964300531405,1739137659.1112576,0.9099991321563721,0.0,1739137659.1112597,0.9099991321563721,1.6794051032412822,1739137659.1112618,0.9099991321563721,6.264542093303839,1739137659.1112642,0.9099991321563721,0.7995591972901228 +1739137659.1312065,0.9299991130828857,0.31685554567320917,1739137659.1312106,0.9299991130828857,-0.0033966940746790186,1739137659.131215,0.9299991130828857,0.02441504329567969,1739137659.1312199,0.9299991130828857,4.4175289908862165,1739137659.131222,0.9299991130828857,-0.1009836554542913,1739137659.1312249,0.9299991130828857,-0.02379329801419388,1739137659.1312273,0.9299991130828857,-0.021124699196407658,1739137659.1312294,0.9299991130828857,-0.019284994033337995,1739137659.1312315,0.9299991130828857,2.478964300531405,1739137659.1312337,0.9299991130828857,0.0,1739137659.1312358,0.9299991130828857,1.6794051032412822,1739137659.1312385,0.9299991130828857,6.264542093303839,1739137659.1312404,0.9299991130828857,0.7995591972901228 +1739137659.1512506,0.9499990940093994,0.41027726356634187,1739137659.151255,0.9499990940093994,-0.0052712127789442675,1739137659.1512592,0.9499990940093994,0.025349260474611016,1739137659.1512632,0.9499990940093994,4.747328325223695,1739137659.1512654,0.9499990940093994,-0.10561899258487577,1739137659.151268,0.9499990940093994,-0.0231332021540313,1739137659.1512704,0.9499990940093994,-0.006927333435798948,1739137659.1512723,0.9499990940093994,-0.0056537329610017555,1739137659.1512744,0.9499990940093994,2.4930822552952843,1739137659.1512768,0.9499990940093994,0.0,1739137659.1512787,0.9499990940093994,1.4970563232066125,1739137659.151281,0.9499990940093994,6.261648923416454,1739137659.1512833,0.9499990940093994,0.9091931363144348 +1739137659.1711721,0.9699990749359131,0.41027726356634187,1739137659.1711767,0.9699990749359131,-0.0052712127789442675,1739137659.171181,0.9699990749359131,0.025349260474611016,1739137659.1711855,0.9699990749359131,4.747328325223695,1739137659.1711874,0.9699990749359131,-0.10561899258487577,1739137659.1711903,0.9699990749359131,-0.0231332021540313,1739137659.1711926,0.9699990749359131,-0.006927333435798948,1739137659.1711946,0.9699990749359131,-0.0056537329610017555,1739137659.1711967,0.9699990749359131,2.4930822552952843,1739137659.171199,0.9699990749359131,0.0,1739137659.171201,0.9699990749359131,1.5838891189808495,1739137659.1712036,0.9699990749359131,6.261648923416454,1739137659.1712055,0.9699990749359131,0.9091931363144348 +1739137659.1912944,0.9899990558624268,0.41027726356634187,1739137659.1912982,0.9899990558624268,-0.0052712127789442675,1739137659.1913025,0.9899990558624268,0.025349260474611016,1739137659.191307,0.9899990558624268,4.747328325223695,1739137659.191309,0.9899990558624268,-0.10561899258487577,1739137659.1913118,0.9899990558624268,-0.0231332021540313,1739137659.1913142,0.9899990558624268,-0.006927333435798948,1739137659.1913164,0.9899990558624268,-0.0056537329610017555,1739137659.1913185,0.9899990558624268,2.4930822552952843,1739137659.191321,0.9899990558624268,0.0,1739137659.1913228,0.9899990558624268,1.5838891189808495,1739137659.1913252,0.9899990558624268,6.261648923416454,1739137659.1913273,0.9899990558624268,0.9091931363144348 +1739137659.211309,1.0099990367889404,0.41027726356634187,1739137659.2113135,1.0099990367889404,-0.0052712127789442675,1739137659.211318,1.0099990367889404,0.025349260474611016,1739137659.2113225,1.0099990367889404,4.747328325223695,1739137659.2113247,1.0099990367889404,-0.10561899258487577,1739137659.2113278,1.0099990367889404,-0.0231332021540313,1739137659.21133,1.0099990367889404,-0.006927333435798948,1739137659.2113323,1.0099990367889404,-0.0056537329610017555,1739137659.2113345,1.0099990367889404,2.4930822552952843,1739137659.2113369,1.0099990367889404,0.0,1739137659.211339,1.0099990367889404,1.5838891189808495,1739137659.2113414,1.0099990367889404,6.261648923416454,1739137659.2113435,1.0099990367889404,0.9091931363144348 +1739137659.2313893,1.029999017715454,0.41027726356634187,1739137659.2313936,1.029999017715454,-0.0052712127789442675,1739137659.2313979,1.029999017715454,0.025349260474611016,1739137659.2314024,1.029999017715454,4.747328325223695,1739137659.2314045,1.029999017715454,-0.10561899258487577,1739137659.2314074,1.029999017715454,-0.0231332021540313,1739137659.2314095,1.029999017715454,-0.006927333435798948,1739137659.2314117,1.029999017715454,-0.0056537329610017555,1739137659.2314138,1.029999017715454,2.4930822552952843,1739137659.231416,1.029999017715454,0.0,1739137659.2314181,1.029999017715454,1.5838891189808495,1739137659.2314203,1.029999017715454,6.261648923416454,1739137659.2314224,1.029999017715454,0.9091931363144348 +1739137659.251233,1.0499989986419678,0.5157428689552095,1739137659.251237,1.0499989986419678,-0.0076564362307109946,1739137659.2512414,1.0499989986419678,0.026403916528499695,1739137659.2512457,1.0499989986419678,5.076996279093356,1739137659.2512481,1.0499989986419678,-0.10994727050245673,1739137659.2512507,1.0499989986419678,-0.022422277819419988,1739137659.251253,1.0499989986419678,0.0059481338217301435,1739137659.251255,1.0499989986419678,0.004389194950413677,1739137659.2512572,1.0499989986419678,2.4940589366288854,1739137659.2512593,1.0499989986419678,0.0,1739137659.2512617,1.0499989986419678,1.3766148163675787,1739137659.2512643,1.0499989986419678,6.259459299925138,1739137659.2512662,1.0499989986419678,1.0187420220918342 +1739137659.271107,1.0699989795684814,0.5157428689552095,1739137659.2711112,1.0699989795684814,-0.0076564362307109946,1739137659.271116,1.0699989795684814,0.026403916528499695,1739137659.27112,1.0699989795684814,5.076996279093356,1739137659.2711225,1.0699989795684814,-0.10994727050245673,1739137659.271125,1.0699989795684814,-0.022422277819419988,1739137659.2711272,1.0699989795684814,0.0059481338217301435,1739137659.2711294,1.0699989795684814,0.004389194950413677,1739137659.2711313,1.0699989795684814,2.4940589366288854,1739137659.2711337,1.0699989795684814,0.0,1739137659.271136,1.0699989795684814,1.4753169145370513,1739137659.271138,1.0699989795684814,6.259459299925138,1739137659.27114,1.0699989795684814,1.0187420220918342 +1739137659.2909245,1.0899989604949951,0.5157428689552095,1739137659.290928,1.0899989604949951,-0.0076564362307109946,1739137659.2909315,1.0899989604949951,0.026403916528499695,1739137659.290935,1.0899989604949951,5.076996279093356,1739137659.290937,1.0899989604949951,-0.10994727050245673,1739137659.290939,1.0899989604949951,-0.022422277819419988,1739137659.2909412,1.0899989604949951,0.0059481338217301435,1739137659.290943,1.0899989604949951,0.004389194950413677,1739137659.2909446,1.0899989604949951,2.4940589366288854,1739137659.2909465,1.0899989604949951,0.0,1739137659.2909484,1.0899989604949951,1.4753169145370513,1739137659.2909503,1.0899989604949951,6.259459299925138,1739137659.290952,1.0899989604949951,1.0187420220918342 +1739137659.310799,1.1099989414215088,0.5157428689552095,1739137659.310802,1.1099989414215088,-0.0076564362307109946,1739137659.3108053,1.1099989414215088,0.026403916528499695,1739137659.3108084,1.1099989414215088,5.076996279093356,1739137659.3108099,1.1099989414215088,-0.10994727050245673,1739137659.3108118,1.1099989414215088,-0.022422277819419988,1739137659.3108134,1.1099989414215088,0.0059481338217301435,1739137659.3108149,1.1099989414215088,0.004389194950413677,1739137659.3108165,1.1099989414215088,2.4940589366288854,1739137659.310818,1.1099989414215088,0.0,1739137659.3108196,1.1099989414215088,1.4753169145370513,1739137659.3108213,1.1099989414215088,6.259459299925138,1739137659.310823,1.1099989414215088,1.0187420220918342 +1739137659.3310413,1.1299989223480225,0.5157428689552095,1739137659.3310444,1.1299989223480225,-0.0076564362307109946,1739137659.3310478,1.1299989223480225,0.026403916528499695,1739137659.331051,1.1299989223480225,5.076996279093356,1739137659.3310525,1.1299989223480225,-0.10994727050245673,1739137659.3310544,1.1299989223480225,-0.022422277819419988,1739137659.331056,1.1299989223480225,0.0059481338217301435,1739137659.3310575,1.1299989223480225,0.004389194950413677,1739137659.3310592,1.1299989223480225,2.4940589366288854,1739137659.3310614,1.1299989223480225,0.0,1739137659.3310628,1.1299989223480225,1.4753169145370513,1739137659.3310645,1.1299989223480225,6.259459299925138,1739137659.3310661,1.1299989223480225,1.0187420220918342 +1739137659.3508434,1.1499989032745361,0.5157428689552095,1739137659.3508463,1.1499989032745361,-0.0076564362307109946,1739137659.3508494,1.1499989032745361,0.026403916528499695,1739137659.3508523,1.1499989032745361,5.076996279093356,1739137659.350854,1.1499989032745361,-0.10994727050245673,1739137659.3508558,1.1499989032745361,-0.022422277819419988,1739137659.3508577,1.1499989032745361,0.0059481338217301435,1739137659.350859,1.1499989032745361,0.004389194950413677,1739137659.3508606,1.1499989032745361,2.4940589366288854,1739137659.3508623,1.1499989032745361,0.0,1739137659.350864,1.1499989032745361,1.4753169145370513,1739137659.3508656,1.1499989032745361,6.259459299925138,1739137659.3508675,1.1499989032745361,1.0187420220918342 +1739137659.3708432,1.1699988842010498,0.6332574695647688,1739137659.370846,1.1699988842010498,-0.010538309758193698,1739137659.3708496,1.1699988842010498,0.027579062534595286,1739137659.3708527,1.1699988842010498,5.406979950018895,1739137659.370854,1.1699988842010498,-0.11366645781269684,1739137659.370856,1.1699988842010498,-0.021599937905993075,1739137659.3708577,1.1699988842010498,0.01785219514878431,1739137659.3708591,1.1699988842010498,0.01202717250318322,1739137659.3708608,1.1699988842010498,2.4822113935757386,1739137659.3708625,1.1699988842010498,0.0,1739137659.3708642,1.1699988842010498,1.2434434537744234,1739137659.370866,1.1699988842010498,6.257846552777684,1739137659.3708677,1.1699988842010498,1.1283519509472153 +1739137659.3909316,1.1899988651275635,0.6332574695647688,1739137659.3909347,1.1899988651275635,-0.010538309758193698,1739137659.3909378,1.1899988651275635,0.027579062534595286,1739137659.390941,1.1899988651275635,5.406979950018895,1739137659.3909428,1.1899988651275635,-0.11366645781269684,1739137659.3909445,1.1899988651275635,-0.021599937905993075,1739137659.3909464,1.1899988651275635,0.01785219514878431,1739137659.3909478,1.1899988651275635,0.01202717250318322,1739137659.390949,1.1899988651275635,2.4822113935757386,1739137659.390951,1.1899988651275635,0.0,1739137659.3909526,1.1899988651275635,1.3538594426285233,1739137659.3909543,1.1899988651275635,6.257846552777684,1739137659.3909557,1.1899988651275635,1.1283519509472153 +1739137659.4109979,1.2099988460540771,0.6332574695647688,1739137659.4110005,1.2099988460540771,-0.010538309758193698,1739137659.411004,1.2099988460540771,0.027579062534595286,1739137659.4110072,1.2099988460540771,5.406979950018895,1739137659.4110088,1.2099988460540771,-0.11366645781269684,1739137659.4110107,1.2099988460540771,-0.021599937905993075,1739137659.4110124,1.2099988460540771,0.01785219514878431,1739137659.4110138,1.2099988460540771,0.01202717250318322,1739137659.4110155,1.2099988460540771,2.4822113935757386,1739137659.4110174,1.2099988460540771,0.0,1739137659.411019,1.2099988460540771,1.3538594426285233,1739137659.4110208,1.2099988460540771,6.257846552777684,1739137659.4110224,1.2099988460540771,1.1283519509472153 +1739137659.4308891,1.2299988269805908,0.6332574695647688,1739137659.4308922,1.2299988269805908,-0.010538309758193698,1739137659.4308953,1.2299988269805908,0.027579062534595286,1739137659.4308987,1.2299988269805908,5.406979950018895,1739137659.4309003,1.2299988269805908,-0.11366645781269684,1739137659.4309022,1.2299988269805908,-0.021599937905993075,1739137659.4309042,1.2299988269805908,0.01785219514878431,1739137659.4309056,1.2299988269805908,0.01202717250318322,1739137659.4309072,1.2299988269805908,2.4822113935757386,1739137659.430909,1.2299988269805908,0.0,1739137659.4309103,1.2299988269805908,1.3538594426285233,1739137659.430912,1.2299988269805908,6.257846552777684,1739137659.4309134,1.2299988269805908,1.1283519509472153 +1739137659.4516973,1.2499988079071045,0.6332574695647688,1739137659.4517024,1.2499988079071045,-0.010538309758193698,1739137659.4517078,1.2499988079071045,0.027579062534595286,1739137659.4517148,1.2499988079071045,5.406979950018895,1739137659.4517186,1.2499988079071045,-0.11366645781269684,1739137659.4517233,1.2499988079071045,-0.021599937905993075,1739137659.4517279,1.2499988079071045,0.01785219514878431,1739137659.451732,1.2499988079071045,0.01202717250318322,1739137659.451736,1.2499988079071045,2.4822113935757386,1739137659.4517405,1.2499988079071045,0.0,1739137659.4517446,1.2499988079071045,1.3538594426285233,1739137659.4517488,1.2499988079071045,6.257846552777684,1739137659.4517531,1.2499988079071045,1.1283519509472153 +1739137659.4709787,1.2699987888336182,0.7628127066752786,1739137659.4709816,1.2699987888336182,-0.013900604925712656,1739137659.470985,1.2699987888336182,0.028874614905700386,1739137659.470988,1.2699987888336182,5.736787370478963,1739137659.4709895,1.2699987888336182,-0.119,1739137659.4709916,1.2699987888336182,-0.021126717582400003,1739137659.4709935,1.2699987888336182,0.027145626129554797,1739137659.470995,1.2699987888336182,0.01684556261872996,1739137659.4709964,1.2699987888336182,2.473001218900093,1739137659.4709983,1.2699987888336182,0.0,1739137659.4709997,1.2699987888336182,1.1271923370670478,1739137659.4710014,1.2699987888336182,6.256602248383197,1739137659.471003,1.2699987888336182,1.2378721109798767 +1739137659.4910402,1.2899987697601318,0.7628127066752786,1739137659.491043,1.2899987697601318,-0.013900604925712656,1739137659.4910464,1.2899987697601318,0.028874614905700386,1739137659.4910498,1.2899987697601318,5.736787370478963,1739137659.4910512,1.2899987697601318,-0.119,1739137659.491053,1.2899987697601318,-0.021126717582400003,1739137659.4910548,1.2899987697601318,0.027145626129554797,1739137659.4910564,1.2899987697601318,0.01684556261872996,1739137659.4910579,1.2899987697601318,2.473001218900093,1739137659.49106,1.2899987697601318,0.0,1739137659.4910614,1.2899987697601318,1.2351291079202165,1739137659.4910634,1.2899987697601318,6.256602248383197,1739137659.4910645,1.2899987697601318,1.2378721109798767 +1739137659.5108478,1.3099987506866455,0.7628127066752786,1739137659.5108511,1.3099987506866455,-0.013900604925712656,1739137659.5108542,1.3099987506866455,0.028874614905700386,1739137659.5108569,1.3099987506866455,5.736787370478963,1739137659.5108585,1.3099987506866455,-0.119,1739137659.5108607,1.3099987506866455,-0.021126717582400003,1739137659.5108624,1.3099987506866455,0.027145626129554797,1739137659.5108638,1.3099987506866455,0.01684556261872996,1739137659.5108654,1.3099987506866455,2.473001218900093,1739137659.510867,1.3099987506866455,0.0,1739137659.5108688,1.3099987506866455,1.2351291079202165,1739137659.5108705,1.3099987506866455,6.256602248383197,1739137659.5108721,1.3099987506866455,1.2378721109798767 +1739137659.5308146,1.3299987316131592,0.7628127066752786,1739137659.5308177,1.3299987316131592,-0.013900604925712656,1739137659.530821,1.3299987316131592,0.028874614905700386,1739137659.5308242,1.3299987316131592,5.736787370478963,1739137659.5308256,1.3299987316131592,-0.119,1739137659.5308278,1.3299987316131592,-0.021126717582400003,1739137659.5308294,1.3299987316131592,0.027145626129554797,1739137659.5308309,1.3299987316131592,0.01684556261872996,1739137659.5308325,1.3299987316131592,2.473001218900093,1739137659.5308344,1.3299987316131592,0.0,1739137659.5308359,1.3299987316131592,1.2351291079202165,1739137659.5308378,1.3299987316131592,6.256602248383197,1739137659.5308394,1.3299987316131592,1.2378721109798767 +1739137659.5508254,1.3499987125396729,0.7628127066752786,1739137659.5508282,1.3499987125396729,-0.013900604925712656,1739137659.5508313,1.3499987125396729,0.028874614905700386,1739137659.5508344,1.3499987125396729,5.736787370478963,1739137659.550836,1.3499987125396729,-0.119,1739137659.5508382,1.3499987125396729,-0.021126717582400003,1739137659.5508401,1.3499987125396729,0.027145626129554797,1739137659.5508413,1.3499987125396729,0.01684556261872996,1739137659.5508428,1.3499987125396729,2.473001218900093,1739137659.5508447,1.3499987125396729,0.0,1739137659.550846,1.3499987125396729,1.2351291079202165,1739137659.5508482,1.3499987125396729,6.256602248383197,1739137659.5508497,1.3499987125396729,1.2378721109798767 +1739137659.5708737,1.3699986934661865,0.7628127066752786,1739137659.5708768,1.3699986934661865,-0.013900604925712656,1739137659.57088,1.3699986934661865,0.028874614905700386,1739137659.5708833,1.3699986934661865,5.736787370478963,1739137659.570885,1.3699986934661865,-0.119,1739137659.5708866,1.3699986934661865,-0.021126717582400003,1739137659.5708885,1.3699986934661865,0.027145626129554797,1739137659.57089,1.3699986934661865,0.01684556261872996,1739137659.5708916,1.3699986934661865,2.473001218900093,1739137659.570893,1.3699986934661865,0.0,1739137659.570895,1.3699986934661865,1.2351291079202165,1739137659.5708966,1.3699986934661865,6.256602248383197,1739137659.5708983,1.3699986934661865,1.2378721109798767 +1739137659.5908713,1.3899986743927002,0.9044143896551242,1739137659.5908742,1.3899986743927002,-0.017732745040421882,1739137659.5908775,1.3899986743927002,0.06761107322249052,1739137659.5908804,1.3899986743927002,6.104266714226895,1739137659.590882,1.3899986743927002,-0.12192843172225658,1739137659.5908844,1.3899986743927002,-0.020035519791123464,1739137659.5908859,1.3899986743927002,0.039280581419231166,1739137659.5908873,1.3899986743927002,0.022305129738112408,1739137659.590889,1.3899986743927002,2.461026401497471,1739137659.5908906,1.3899986743927002,0.0,1739137659.5908923,1.3899986743927002,1.0030584832812734,1739137659.590894,1.3899986743927002,6.2555970592406425,1739137659.5908957,1.3899986743927002,1.3474580417550468 +1739137659.610931,1.4099986553192139,0.9044143896551242,1739137659.6109338,1.4099986553192139,-0.017732745040421882,1739137659.610937,1.4099986553192139,0.06761107322249052,1739137659.6109402,1.4099986553192139,6.104266714226895,1739137659.6109416,1.4099986553192139,-0.12192843172225658,1739137659.6109438,1.4099986553192139,-0.020035519791123464,1739137659.6109455,1.4099986553192139,0.039280581419231166,1739137659.6109471,1.4099986553192139,0.022305129738112408,1739137659.6109486,1.4099986553192139,2.461026401497471,1739137659.6109502,1.4099986553192139,0.0,1739137659.6109521,1.4099986553192139,1.1135683597424244,1739137659.610954,1.4099986553192139,6.2555970592406425,1739137659.6109555,1.4099986553192139,1.3474580417550468 +1739137659.6307805,1.4299986362457275,0.9044143896551242,1739137659.6307833,1.4299986362457275,-0.017732745040421882,1739137659.630787,1.4299986362457275,0.06761107322249052,1739137659.63079,1.4299986362457275,6.104266714226895,1739137659.6307914,1.4299986362457275,-0.12192843172225658,1739137659.6307936,1.4299986362457275,-0.020035519791123464,1739137659.630795,1.4299986362457275,0.039280581419231166,1739137659.630797,1.4299986362457275,0.022305129738112408,1739137659.6307983,1.4299986362457275,2.461026401497471,1739137659.6307998,1.4299986362457275,0.0,1739137659.6308014,1.4299986362457275,1.1135683597424244,1739137659.630803,1.4299986362457275,6.2555970592406425,1739137659.6308048,1.4299986362457275,1.3474580417550468 +1739137659.650842,1.4499986171722412,0.9044143896551242,1739137659.6508446,1.4499986171722412,-0.017732745040421882,1739137659.6508498,1.4499986171722412,0.06761107322249052,1739137659.6508536,1.4499986171722412,6.104266714226895,1739137659.650855,1.4499986171722412,-0.12192843172225658,1739137659.6508572,1.4499986171722412,-0.020035519791123464,1739137659.6508586,1.4499986171722412,0.039280581419231166,1739137659.65086,1.4499986171722412,0.022305129738112408,1739137659.6508613,1.4499986171722412,2.461026401497471,1739137659.6508632,1.4499986171722412,0.0,1739137659.6508644,1.4499986171722412,1.1135683597424244,1739137659.650866,1.4499986171722412,6.2555970592406425,1739137659.6508672,1.4499986171722412,1.3474580417550468 +1739137659.6708183,1.4699985980987549,0.9044143896551242,1739137659.6708212,1.4699985980987549,-0.017732745040421882,1739137659.6708243,1.4699985980987549,0.06761107322249052,1739137659.670827,1.4699985980987549,6.104266714226895,1739137659.6708286,1.4699985980987549,-0.12192843172225658,1739137659.6708302,1.4699985980987549,-0.020035519791123464,1739137659.670832,1.4699985980987549,0.039280581419231166,1739137659.6708333,1.4699985980987549,0.022305129738112408,1739137659.6708348,1.4699985980987549,2.461026401497471,1739137659.6708364,1.4699985980987549,0.0,1739137659.6708379,1.4699985980987549,1.1135683597424244,1739137659.6708393,1.4699985980987549,6.2555970592406425,1739137659.6708415,1.4699985980987549,1.3474580417550468 +1739137659.6908784,1.4899985790252686,1.0580535491217233,1739137659.690881,1.4899985790252686,-0.022033342740099826,1739137659.690884,1.4899985790252686,0.23717974222897317,1739137659.6908875,1.4899985790252686,6.602294159784939,1739137659.6908886,1.4899985790252686,-0.1249927975488259,1739137659.6908906,1.4899985790252686,-0.018568389939027288,1739137659.690892,1.4899985790252686,0.054501114686172934,1739137659.6908934,1.4899985790252686,0.02722392833297369,1739137659.6908948,1.4899985790252686,2.446088666012095,1739137659.6908963,1.4899985790252686,0.0,1739137659.690898,1.4899985790252686,0.8760216178775166,1739137659.6908994,1.4899985790252686,6.254788231844154,1739137659.690901,1.4899985790252686,1.456949495501272 +1739137659.7109604,1.5099985599517822,1.0580535491217233,1739137659.7109632,1.5099985599517822,-0.022033342740099826,1739137659.7109663,1.5099985599517822,0.23717974222897317,1739137659.7109694,1.5099985599517822,6.602294159784939,1739137659.7109709,1.5099985599517822,-0.1249927975488259,1739137659.7109723,1.5099985599517822,-0.018568389939027288,1739137659.710974,1.5099985599517822,0.054501114686172934,1739137659.7109752,1.5099985599517822,0.02722392833297369,1739137659.7109768,1.5099985599517822,2.446088666012095,1739137659.7109783,1.5099985599517822,0.0,1739137659.7109797,1.5099985599517822,0.9891391705108228,1739137659.7109814,1.5099985599517822,6.254788231844154,1739137659.7109826,1.5099985599517822,1.456949495501272 +1739137659.7311156,1.529998540878296,1.0580535491217233,1739137659.7311199,1.529998540878296,-0.022033342740099826,1739137659.7311234,1.529998540878296,0.23717974222897317,1739137659.731127,1.529998540878296,6.602294159784939,1739137659.7311292,1.529998540878296,-0.1249927975488259,1739137659.7311313,1.529998540878296,-0.018568389939027288,1739137659.731133,1.529998540878296,0.054501114686172934,1739137659.7311344,1.529998540878296,0.02722392833297369,1739137659.7311363,1.529998540878296,2.446088666012095,1739137659.7311385,1.529998540878296,0.0,1739137659.7311401,1.529998540878296,0.9891391705108228,1739137659.7311418,1.529998540878296,6.254788231844154,1739137659.7311437,1.529998540878296,1.456949495501272 +1739137659.750819,1.5499985218048096,1.0580535491217233,1739137659.7508218,1.5499985218048096,-0.022033342740099826,1739137659.7508247,1.5499985218048096,0.23717974222897317,1739137659.7508276,1.5499985218048096,6.602294159784939,1739137659.750829,1.5499985218048096,-0.1249927975488259,1739137659.7508311,1.5499985218048096,-0.018568389939027288,1739137659.7508326,1.5499985218048096,0.054501114686172934,1739137659.7508342,1.5499985218048096,0.02722392833297369,1739137659.7508354,1.5499985218048096,2.446088666012095,1739137659.7508373,1.5499985218048096,0.0,1739137659.7508385,1.5499985218048096,0.9891391705108228,1739137659.7508404,1.5499985218048096,6.254788231844154,1739137659.7508416,1.5499985218048096,1.456949495501272 +1739137659.7708063,1.5699985027313232,1.0580535491217233,1739137659.770809,1.5699985027313232,-0.022033342740099826,1739137659.7708118,1.5699985027313232,0.23717974222897317,1739137659.770815,1.5699985027313232,6.602294159784939,1739137659.7708166,1.5699985027313232,-0.1249927975488259,1739137659.770818,1.5699985027313232,-0.018568389939027288,1739137659.77082,1.5699985027313232,0.054501114686172934,1739137659.770821,1.5699985027313232,0.02722392833297369,1739137659.7708228,1.5699985027313232,2.446088666012095,1739137659.7708242,1.5699985027313232,0.0,1739137659.7708256,1.5699985027313232,0.9891391705108228,1739137659.7708273,1.5699985027313232,6.254788231844154,1739137659.7708287,1.5699985027313232,1.456949495501272 +1739137659.790824,1.589998483657837,1.0580535491217233,1739137659.7908266,1.589998483657837,-0.022033342740099826,1739137659.7908297,1.589998483657837,0.23717974222897317,1739137659.7908328,1.589998483657837,6.602294159784939,1739137659.7908342,1.589998483657837,-0.1249927975488259,1739137659.7908359,1.589998483657837,-0.018568389939027288,1739137659.7908375,1.589998483657837,0.054501114686172934,1739137659.7908387,1.589998483657837,0.02722392833297369,1739137659.7908404,1.589998483657837,2.446088666012095,1739137659.7908418,1.589998483657837,0.0,1739137659.7908435,1.589998483657837,0.9891391705108228,1739137659.790845,1.589998483657837,6.254788231844154,1739137659.790846,1.589998483657837,1.456949495501272 +1739137659.8109329,1.6099984645843506,1.2234631041479798,1739137659.810936,1.6099984645843506,-0.02677624285897373,1739137659.810939,1.6099984645843506,0.2385030186691832,1739137659.8109422,1.6099984645843506,6.921991849936961,1739137659.8109438,1.6099984645843506,-0.1263665308322827,1739137659.8109455,1.6099984645843506,-0.017474712344325495,1739137659.8109472,1.6099984645843506,0.06536365146134059,1739137659.8109484,1.6099984645843506,0.030906800148837274,1739137659.8109498,1.6099984645843506,2.4354834314111313,1739137659.8109515,1.6099984645843506,0.0,1739137659.810953,1.6099984645843506,0.7662868319445034,1739137659.8109548,1.6099984645843506,6.254241826765719,1739137659.810956,1.6099984645843506,1.5630763852328877 +1739137659.8316588,1.6299984455108643,1.2234631041479798,1739137659.8316648,1.6299984455108643,-0.02677624285897373,1739137659.8316698,1.6299984455108643,0.2385030186691832,1739137659.8316731,1.6299984455108643,6.921991849936961,1739137659.8316743,1.6299984455108643,-0.1263665308322827,1739137659.8316767,1.6299984455108643,-0.017474712344325495,1739137659.8316789,1.6299984455108643,0.06536365146134059,1739137659.8316803,1.6299984455108643,0.030906800148837274,1739137659.8316815,1.6299984455108643,2.4354834314111313,1739137659.8316846,1.6299984455108643,0.0,1739137659.8316867,1.6299984455108643,0.8724070461782436,1739137659.8316884,1.6299984455108643,6.254241826765719,1739137659.8316903,1.6299984455108643,1.5630763852328877 +1739137659.8513105,1.649998426437378,1.2234631041479798,1739137659.851314,1.649998426437378,-0.02677624285897373,1739137659.851317,1.649998426437378,0.2385030186691832,1739137659.8513198,1.649998426437378,6.921991849936961,1739137659.8513215,1.649998426437378,-0.1263665308322827,1739137659.8513231,1.649998426437378,-0.017474712344325495,1739137659.8513246,1.649998426437378,0.06536365146134059,1739137659.8513262,1.649998426437378,0.030906800148837274,1739137659.8513284,1.649998426437378,2.4354834314111313,1739137659.8513298,1.649998426437378,0.0,1739137659.851331,1.649998426437378,0.8724070461782436,1739137659.8513327,1.649998426437378,6.254241826765719,1739137659.851334,1.649998426437378,1.5630763852328877 +1739137659.8710191,1.6699984073638916,1.2234631041479798,1739137659.8710234,1.6699984073638916,-0.02677624285897373,1739137659.8710275,1.6699984073638916,0.2385030186691832,1739137659.8710303,1.6699984073638916,6.921991849936961,1739137659.8710318,1.6699984073638916,-0.1263665308322827,1739137659.8710337,1.6699984073638916,-0.017474712344325495,1739137659.8710353,1.6699984073638916,0.06536365146134059,1739137659.871037,1.6699984073638916,0.030906800148837274,1739137659.8710384,1.6699984073638916,2.4354834314111313,1739137659.8710406,1.6699984073638916,0.0,1739137659.871042,1.6699984073638916,0.8724070461782436,1739137659.871044,1.6699984073638916,6.254241826765719,1739137659.871045,1.6699984073638916,1.5630763852328877 +1739137659.8911905,1.6899983882904053,1.2234631041479798,1739137659.8911939,1.6899983882904053,-0.02677624285897373,1739137659.891197,1.6899983882904053,0.2385030186691832,1739137659.8912,1.6899983882904053,6.921991849936961,1739137659.8912015,1.6899983882904053,-0.1263665308322827,1739137659.8912034,1.6899983882904053,-0.017474712344325495,1739137659.8912048,1.6899983882904053,0.06536365146134059,1739137659.891206,1.6899983882904053,0.030906800148837274,1739137659.8912075,1.6899983882904053,2.4354834314111313,1739137659.891209,1.6899983882904053,0.0,1739137659.8912106,1.6899983882904053,0.8724070461782436,1739137659.891212,1.6899983882904053,6.254241826765719,1739137659.8912137,1.6899983882904053,1.5630763852328877 +1739137659.9112673,1.709998369216919,1.4000410271605768,1739137659.9112716,1.709998369216919,-0.031921628716252926,1739137659.911276,1.709998369216919,0.7312278179773868,1739137659.9112794,1.709998369216919,7.698309544822759,1739137659.911281,1.709998369216919,-0.13088650043517241,1739137659.911283,1.709998369216919,-0.015711735354446744,1739137659.9112844,1.709998369216919,0.08572818472986504,1739137659.9112859,1.709998369216919,0.03318543927784899,1739137659.911287,1.709998369216919,2.4157250214793033,1739137659.911289,1.709998369216919,0.0,1739137659.9112906,1.709998369216919,0.6542034693199381,1739137659.911292,1.709998369216919,6.253863442355595,1739137659.9112935,1.709998369216919,1.6576150350828986 +1739137659.930993,1.7299983501434326,1.4000410271605768,1739137659.9309971,1.7299983501434326,-0.031921628716252926,1739137659.9310012,1.7299983501434326,0.7312278179773868,1739137659.931004,1.7299983501434326,7.698309544822759,1739137659.931006,1.7299983501434326,-0.13088650043517241,1739137659.9310079,1.7299983501434326,-0.015711735354446744,1739137659.931009,1.7299983501434326,0.08572818472986504,1739137659.9310102,1.7299983501434326,0.03318543927784899,1739137659.931012,1.7299983501434326,2.4157250214793033,1739137659.9310138,1.7299983501434326,0.0,1739137659.9310155,1.7299983501434326,0.7581099863964047,1739137659.931017,1.7299983501434326,6.253863442355595,1739137659.9310186,1.7299983501434326,1.6576150350828986 +1739137659.951632,1.7499983310699463,1.4000410271605768,1739137659.9516366,1.7499983310699463,-0.031921628716252926,1739137659.9516408,1.7499983310699463,0.7312278179773868,1739137659.9516451,1.7499983310699463,7.698309544822759,1739137659.951647,1.7499983310699463,-0.13088650043517241,1739137659.9516494,1.7499983310699463,-0.015711735354446744,1739137659.9516523,1.7499983310699463,0.08572818472986504,1739137659.9516547,1.7499983310699463,0.03318543927784899,1739137659.9516563,1.7499983310699463,2.4157250214793033,1739137659.9516594,1.7499983310699463,0.0,1739137659.9516618,1.7499983310699463,0.7581099863964047,1739137659.9516644,1.7499983310699463,6.253863442355595,1739137659.9516666,1.7499983310699463,1.6576150350828986 +1739137659.9717054,1.76999831199646,1.4000410271605768,1739137659.9717112,1.76999831199646,-0.031921628716252926,1739137659.9717174,1.76999831199646,0.7312278179773868,1739137659.9717212,1.76999831199646,7.698309544822759,1739137659.971724,1.76999831199646,-0.13088650043517241,1739137659.971727,1.76999831199646,-0.015711735354446744,1739137659.9717295,1.76999831199646,0.08572818472986504,1739137659.9717321,1.76999831199646,0.03318543927784899,1739137659.9717345,1.76999831199646,2.4157250214793033,1739137659.9717383,1.76999831199646,0.0,1739137659.9717412,1.76999831199646,0.7581099863964047,1739137659.971744,1.76999831199646,6.253863442355595,1739137659.9717462,1.76999831199646,1.6576150350828986 +1739137659.9925044,1.7899982929229736,1.4000410271605768,1739137659.9925098,1.7899982929229736,-0.031921628716252926,1739137659.9925158,1.7899982929229736,0.7312278179773868,1739137659.992519,1.7899982929229736,7.698309544822759,1739137659.9925208,1.7899982929229736,-0.13088650043517241,1739137659.9925237,1.7899982929229736,-0.015711735354446744,1739137659.992526,1.7899982929229736,0.08572818472986504,1739137659.992528,1.7899982929229736,0.03318543927784899,1739137659.99253,1.7899982929229736,2.4157250214793033,1739137659.9925327,1.7899982929229736,0.0,1739137659.9925346,1.7899982929229736,0.7581099863964047,1739137659.9925368,1.7899982929229736,6.253863442355595,1739137659.9925385,1.7899982929229736,1.6576150350828986 +1739137660.0118287,1.8099982738494873,1.4000410271605768,1739137660.0118318,1.8099982738494873,-0.031921628716252926,1739137660.011835,1.8099982738494873,0.7312278179773868,1739137660.0118382,1.8099982738494873,7.698309544822759,1739137660.0118394,1.8099982738494873,-0.13088650043517241,1739137660.0118413,1.8099982738494873,-0.015711735354446744,1739137660.0118427,1.8099982738494873,0.08572818472986504,1739137660.0118444,1.8099982738494873,0.03318543927784899,1739137660.0118456,1.8099982738494873,2.4157250214793033,1739137660.0118473,1.8099982738494873,0.0,1739137660.0118487,1.8099982738494873,0.7581099863964047,1739137660.0118504,1.8099982738494873,6.253863442355595,1739137660.0118518,1.8099982738494873,1.6576150350828986 +1739137660.0314426,1.829998254776001,1.586260360563645,1739137660.0314457,1.829998254776001,-0.03740706885942213,1739137660.031449,1.829998254776001,0.7334624499782236,1739137660.031452,1.829998254776001,7.943486667179752,1739137660.0314534,1.829998254776001,-0.1322642948767284,1739137660.0314553,1.829998254776001,-0.014920058320178915,1739137660.031457,1.829998254776001,0.09327047441912953,1739137660.0314584,1.829998254776001,0.0354391400040962,1739137660.0314596,1.829998254776001,2.4084479649638415,1739137660.0314615,1.829998254776001,0.0,1739137660.031463,1.829998254776001,0.5896144933075644,1739137660.0314643,1.829998254776001,6.253594788175582,1739137660.031466,1.829998254776001,1.738597482484971 +1739137660.051423,1.8499982357025146,1.586260360563645,1739137660.0514312,1.8499982357025146,-0.03740706885942213,1739137660.051437,1.8499982357025146,0.7334624499782236,1739137660.0514421,1.8499982357025146,7.943486667179752,1739137660.0514445,1.8499982357025146,-0.1322642948767284,1739137660.0514479,1.8499982357025146,-0.014920058320178915,1739137660.0514495,1.8499982357025146,0.09327047441912953,1739137660.0514512,1.8499982357025146,0.0354391400040962,1739137660.0514529,1.8499982357025146,2.4084479649638415,1739137660.0514557,1.8499982357025146,0.0,1739137660.0514576,1.8499982357025146,0.6698504824788705,1739137660.0514596,1.8499982357025146,6.253594788175582,1739137660.0514612,1.8499982357025146,1.738597482484971 +1739137660.071256,1.8699982166290283,1.586260360563645,1739137660.0712595,1.8699982166290283,-0.03740706885942213,1739137660.071263,1.8699982166290283,0.7334624499782236,1739137660.071266,1.8699982166290283,7.943486667179752,1739137660.0712676,1.8699982166290283,-0.1322642948767284,1739137660.0712693,1.8699982166290283,-0.014920058320178915,1739137660.071271,1.8699982166290283,0.09327047441912953,1739137660.0712726,1.8699982166290283,0.0354391400040962,1739137660.071274,1.8699982166290283,2.4084479649638415,1739137660.0712757,1.8699982166290283,0.0,1739137660.0712774,1.8699982166290283,0.6698504824788705,1739137660.071279,1.8699982166290283,6.253594788175582,1739137660.0712807,1.8699982166290283,1.738597482484971 +1739137660.0916188,1.889998197555542,1.586260360563645,1739137660.0916247,1.889998197555542,-0.03740706885942213,1739137660.09163,1.889998197555542,0.7334624499782236,1739137660.091636,1.889998197555542,7.943486667179752,1739137660.0916393,1.889998197555542,-0.1322642948767284,1739137660.0916438,1.889998197555542,-0.014920058320178915,1739137660.0916476,1.889998197555542,0.09327047441912953,1739137660.0916514,1.889998197555542,0.0354391400040962,1739137660.0916553,1.889998197555542,2.4084479649638415,1739137660.091659,1.889998197555542,0.0,1739137660.091663,1.889998197555542,0.6698504824788705,1739137660.0916667,1.889998197555542,6.253594788175582,1739137660.0916705,1.889998197555542,1.738597482484971 +1739137660.1112146,1.9099981784820557,1.586260360563645,1739137660.1112192,1.9099981784820557,-0.03740706885942213,1739137660.111223,1.9099981784820557,0.7334624499782236,1739137660.111226,1.9099981784820557,7.943486667179752,1739137660.1112278,1.9099981784820557,-0.1322642948767284,1739137660.1112294,1.9099981784820557,-0.014920058320178915,1739137660.111231,1.9099981784820557,0.09327047441912953,1739137660.111233,1.9099981784820557,0.0354391400040962,1739137660.1112342,1.9099981784820557,2.4084479649638415,1739137660.111236,1.9099981784820557,0.0,1739137660.1112375,1.9099981784820557,0.6698504824788705,1739137660.1112394,1.9099981784820557,6.253594788175582,1739137660.1112409,1.9099981784820557,1.738597482484971 +1739137660.1325982,1.9299981594085693,1.781040198230289,1739137660.132603,1.9299981594085693,-0.04319099605485821,1739137660.1326072,1.9299981594085693,1.0379881627769498,1739137660.1326113,1.9299981594085693,8.465753918800816,1739137660.132614,1.9299981594085693,-0.135,1739137660.1326168,1.9299981594085693,-0.01373330794246994,1739137660.132619,1.9299981594085693,0.10731251651929191,1739137660.1326215,1.9299981594085693,0.0368784093332436,1739137660.1326241,1.9299981594085693,2.394958074463492,1739137660.1326268,1.9299981594085693,0.0,1739137660.132629,1.9299981594085693,0.5055258130032596,1739137660.1326318,1.9299981594085693,6.253399403731086,1739137660.1326346,1.9299981594085693,1.8111823797635642 +1739137660.1520386,1.949998140335083,1.781040198230289,1739137660.1520455,1.949998140335083,-0.04319099605485821,1739137660.1520524,1.949998140335083,1.0379881627769498,1739137660.152057,1.949998140335083,8.465753918800816,1739137660.1520603,1.949998140335083,-0.135,1739137660.1520653,1.949998140335083,-0.01373330794246994,1739137660.1520689,1.949998140335083,0.10731251651929191,1739137660.1520717,1.949998140335083,0.0368784093332436,1739137660.152074,1.949998140335083,2.394958074463492,1739137660.1520765,1.949998140335083,0.0,1739137660.152079,1.949998140335083,0.583775694699928,1739137660.1520817,1.949998140335083,6.253399403731086,1739137660.1520846,1.949998140335083,1.8111823797635642 +1739137660.1720273,1.9699981212615967,1.781040198230289,1739137660.1720312,1.9699981212615967,-0.04319099605485821,1739137660.1720364,1.9699981212615967,1.0379881627769498,1739137660.1720417,1.9699981212615967,8.465753918800816,1739137660.1720445,1.9699981212615967,-0.135,1739137660.1720483,1.9699981212615967,-0.01373330794246994,1739137660.1720517,1.9699981212615967,0.10731251651929191,1739137660.1720552,1.9699981212615967,0.0368784093332436,1739137660.1720586,1.9699981212615967,2.394958074463492,1739137660.1720622,1.9699981212615967,0.0,1739137660.1720653,1.9699981212615967,0.583775694699928,1739137660.1720688,1.9699981212615967,6.253399403731086,1739137660.1720722,1.9699981212615967,1.8111823797635642 +1739137660.1922996,1.9899981021881104,1.781040198230289,1739137660.1923037,1.9899981021881104,-0.04319099605485821,1739137660.1923082,1.9899981021881104,1.0379881627769498,1739137660.1923134,1.9899981021881104,8.465753918800816,1739137660.1923165,1.9899981021881104,-0.135,1739137660.19232,1.9899981021881104,-0.01373330794246994,1739137660.1923234,1.9899981021881104,0.10731251651929191,1739137660.192327,1.9899981021881104,0.0368784093332436,1739137660.1923301,1.9899981021881104,2.394958074463492,1739137660.192334,1.9899981021881104,0.0,1739137660.192337,1.9899981021881104,0.583775694699928,1739137660.192341,1.9899981021881104,6.253399403731086,1739137660.1923447,1.9899981021881104,1.8111823797635642 +1739137660.2123077,2.009998083114624,1.781040198230289,1739137660.2123117,2.009998083114624,-0.04319099605485821,1739137660.2123168,2.009998083114624,1.0379881627769498,1739137660.2123218,2.009998083114624,8.465753918800816,1739137660.2123249,2.009998083114624,-0.135,1739137660.2123287,2.009998083114624,-0.01373330794246994,1739137660.212332,2.009998083114624,0.10731251651929191,1739137660.2123356,2.009998083114624,0.0368784093332436,1739137660.212339,2.009998083114624,2.394958074463492,1739137660.2123427,2.009998083114624,0.0,1739137660.212346,2.009998083114624,0.583775694699928,1739137660.2123501,2.009998083114624,6.253399403731086,1739137660.212354,2.009998083114624,1.8111823797635642 +1739137660.231471,2.0299980640411377,1.781040198230289,1739137660.2314773,2.0299980640411377,-0.04319099605485821,1739137660.231484,2.0299980640411377,1.0379881627769498,1739137660.2314904,2.0299980640411377,8.465753918800816,1739137660.231494,2.0299980640411377,-0.135,1739137660.2314985,2.0299980640411377,-0.01373330794246994,1739137660.2315018,2.0299980640411377,0.10731251651929191,1739137660.2315063,2.0299980640411377,0.0368784093332436,1739137660.2315106,2.0299980640411377,2.394958074463492,1739137660.2315137,2.0299980640411377,0.0,1739137660.2315152,2.0299980640411377,0.583775694699928,1739137660.2315176,2.0299980640411377,6.253399403731086,1739137660.2315214,2.0299980640411377,1.8111823797635642 +1739137660.2513216,2.0499980449676514,1.9832345377138152,1739137660.2513247,2.0499980449676514,-0.04922593125751629,1739137660.2513285,2.0499980449676514,1.0406166891902355,1739137660.2513316,2.0499980449676514,8.655539408944307,1739137660.2513332,2.0499980449676514,-0.1350711264994746,1739137660.251335,2.0499980449676514,-0.012865188368790302,1739137660.2513363,2.0499980449676514,0.1136206143385092,1739137660.251338,2.0499980449676514,0.03919223167362171,1739137660.2513392,2.0499980449676514,2.3889226401649912,1739137660.2513413,2.0499980449676514,0.0,1739137660.2513425,2.0499980449676514,0.4531533431217241,1739137660.2513442,2.0499980449676514,6.253292014672891,1739137660.2513456,2.0499980449676514,1.87356814617193 +1739137660.2715678,2.069998025894165,1.9832345377138152,1739137660.2715716,2.069998025894165,-0.04922593125751629,1739137660.2715766,2.069998025894165,1.0406166891902355,1739137660.2715802,2.069998025894165,8.655539408944307,1739137660.2715821,2.069998025894165,-0.1350711264994746,1739137660.271584,2.069998025894165,-0.012865188368790302,1739137660.2715857,2.069998025894165,0.1136206143385092,1739137660.2715874,2.069998025894165,0.03919223167362171,1739137660.2715886,2.069998025894165,2.3889226401649912,1739137660.2715914,2.069998025894165,0.0,1739137660.2715929,2.069998025894165,0.5153544939930612,1739137660.2715945,2.069998025894165,6.253292014672891,1739137660.271596,2.069998025894165,1.87356814617193 +1739137660.2912047,2.0899980068206787,1.9832345377138152,1739137660.2912087,2.0899980068206787,-0.04922593125751629,1739137660.291212,2.0899980068206787,1.0406166891902355,1739137660.2912152,2.0899980068206787,8.655539408944307,1739137660.2912166,2.0899980068206787,-0.1350711264994746,1739137660.2912183,2.0899980068206787,-0.012865188368790302,1739137660.2912195,2.0899980068206787,0.1136206143385092,1739137660.291221,2.0899980068206787,0.03919223167362171,1739137660.291222,2.0899980068206787,2.3889226401649912,1739137660.2912238,2.0899980068206787,0.0,1739137660.2912252,2.0899980068206787,0.5153544939930612,1739137660.2912269,2.0899980068206787,6.253292014672891,1739137660.291228,2.0899980068206787,1.87356814617193 +1739137660.3113627,2.1099979877471924,1.9832345377138152,1739137660.3113663,2.1099979877471924,-0.04922593125751629,1739137660.3113716,2.1099979877471924,1.0406166891902355,1739137660.3113766,2.1099979877471924,8.655539408944307,1739137660.3113794,2.1099979877471924,-0.1350711264994746,1739137660.3113835,2.1099979877471924,-0.012865188368790302,1739137660.3113868,2.1099979877471924,0.1136206143385092,1739137660.3113902,2.1099979877471924,0.03919223167362171,1739137660.311394,2.1099979877471924,2.3889226401649912,1739137660.3113976,2.1099979877471924,0.0,1739137660.311401,2.1099979877471924,0.5153544939930612,1739137660.3114045,2.1099979877471924,6.253292014672891,1739137660.3114078,2.1099979877471924,1.87356814617193 +1739137660.3314354,2.129997968673706,1.9832345377138152,1739137660.3314404,2.129997968673706,-0.04922593125751629,1739137660.331444,2.129997968673706,1.0406166891902355,1739137660.3314471,2.129997968673706,8.655539408944307,1739137660.3314483,2.129997968673706,-0.1350711264994746,1739137660.3314502,2.129997968673706,-0.012865188368790302,1739137660.3314517,2.129997968673706,0.1136206143385092,1739137660.3314533,2.129997968673706,0.03919223167362171,1739137660.331455,2.129997968673706,2.3889226401649912,1739137660.3314567,2.129997968673706,0.0,1739137660.3314583,2.129997968673706,0.5153544939930612,1739137660.3314598,2.129997968673706,6.253292014672891,1739137660.3314617,2.129997968673706,1.87356814617193 +1739137660.352579,2.1499979496002197,2.192017944306566,1739137660.3525834,2.1499979496002197,-0.05547351075086926,1739137660.352588,2.1499979496002197,1.375834796663133,1739137660.3525932,2.1499979496002197,9.15823825001801,1739137660.3525965,2.1499979496002197,-0.13778727336465432,1739137660.3526003,2.1499979496002197,-0.011815579814409926,1739137660.3526034,2.1499979496002197,0.12617181748696385,1739137660.3526068,2.1499979496002197,0.039927570831782035,1739137660.35261,2.1499979496002197,2.37695915517455,1739137660.3526137,2.1499979496002197,0.0,1739137660.352617,2.1499979496002197,0.38592961975475865,1739137660.3526204,2.1499979496002197,6.253258053800059,1739137660.3526237,2.1499979496002197,1.9293986121380227 +1739137660.3727329,2.1699979305267334,2.192017944306566,1739137660.3727365,2.1699979305267334,-0.05547351075086926,1739137660.3727415,2.1699979305267334,1.375834796663133,1739137660.3727467,2.1699979305267334,9.15823825001801,1739137660.3727496,2.1699979305267334,-0.13778727336465432,1739137660.3727534,2.1699979305267334,-0.011815579814409926,1739137660.372757,2.1699979305267334,0.12617181748696385,1739137660.3727603,2.1699979305267334,0.039927570831782035,1739137660.3727636,2.1699979305267334,2.37695915517455,1739137660.3727672,2.1699979305267334,0.0,1739137660.3727708,2.1699979305267334,0.44756054303652726,1739137660.3727741,2.1699979305267334,6.253258053800059,1739137660.3727777,2.1699979305267334,1.9293986121380227 +1739137660.390943,2.189997911453247,2.192017944306566,1739137660.390947,2.189997911453247,-0.05547351075086926,1739137660.3909504,2.189997911453247,1.375834796663133,1739137660.3909535,2.189997911453247,9.15823825001801,1739137660.3909547,2.189997911453247,-0.13778727336465432,1739137660.3909566,2.189997911453247,-0.011815579814409926,1739137660.3909583,2.189997911453247,0.12617181748696385,1739137660.3909595,2.189997911453247,0.039927570831782035,1739137660.390961,2.189997911453247,2.37695915517455,1739137660.3909628,2.189997911453247,0.0,1739137660.3909643,2.189997911453247,0.44756054303652726,1739137660.390966,2.189997911453247,6.253258053800059,1739137660.3909683,2.189997911453247,1.9293986121380227 +1739137660.4119837,2.2099978923797607,2.192017944306566,1739137660.4119902,2.2099978923797607,-0.05547351075086926,1739137660.4119954,2.2099978923797607,1.375834796663133,1739137660.4120016,2.2099978923797607,9.15823825001801,1739137660.4120052,2.2099978923797607,-0.13778727336465432,1739137660.4120095,2.2099978923797607,-0.011815579814409926,1739137660.4120133,2.2099978923797607,0.12617181748696385,1739137660.412017,2.2099978923797607,0.039927570831782035,1739137660.4120207,2.2099978923797607,2.37695915517455,1739137660.4120245,2.2099978923797607,0.0,1739137660.4120283,2.2099978923797607,0.44756054303652726,1739137660.4120328,2.2099978923797607,6.253258053800059,1739137660.4120367,2.2099978923797607,1.9293986121380227 +1739137660.4328032,2.2299978733062744,2.192017944306566,1739137660.432807,2.2299978733062744,-0.05547351075086926,1739137660.4328115,2.2299978733062744,1.375834796663133,1739137660.432817,2.2299978733062744,9.15823825001801,1739137660.4328196,2.2299978733062744,-0.13778727336465432,1739137660.4328237,2.2299978733062744,-0.011815579814409926,1739137660.4328272,2.2299978733062744,0.12617181748696385,1739137660.4328306,2.2299978733062744,0.039927570831782035,1739137660.4328341,2.2299978733062744,2.37695915517455,1739137660.4328377,2.2299978733062744,0.0,1739137660.432841,2.2299978733062744,0.44756054303652726,1739137660.4328446,2.2299978733062744,6.253258053800059,1739137660.432848,2.2299978733062744,1.9293986121380227 +1739137660.4533617,2.249997854232788,2.192017944306566,1739137660.4533653,2.249997854232788,-0.05547351075086926,1739137660.45337,2.249997854232788,1.375834796663133,1739137660.4533756,2.249997854232788,9.15823825001801,1739137660.4533782,2.249997854232788,-0.13778727336465432,1739137660.4533823,2.249997854232788,-0.011815579814409926,1739137660.4533858,2.249997854232788,0.12617181748696385,1739137660.4533894,2.249997854232788,0.039927570831782035,1739137660.4533927,2.249997854232788,2.37695915517455,1739137660.4533963,2.249997854232788,0.0,1739137660.4533997,2.249997854232788,0.44756054303652726,1739137660.4534032,2.249997854232788,6.253258053800059,1739137660.4534068,2.249997854232788,1.9293986121380227 +1739137660.47278,2.2699978351593018,2.4064942267684657,1739137660.4727848,2.2699978351593018,-0.061889516970281555,1739137660.4727895,2.2699978351593018,1.6397968207595048,1739137660.4727948,2.2699978351593018,9.565565601669892,1739137660.4727976,2.2699978351593018,-0.13956482203366874,1739137660.4728017,2.2699978351593018,-0.010849487763995502,1739137660.4728053,2.2699978351593018,0.13619089240802001,1739137660.4728086,2.2699978351593018,0.04080825146210996,1739137660.4728122,2.2699978351593018,2.3674522452434106,1739137660.472816,2.2699978351593018,0.0,1739137660.472819,2.2699978351593018,0.33817322950064865,1739137660.4728231,2.2699978351593018,6.253312250002321,1739137660.4728265,2.2699978351593018,1.9771897928000723 +1739137660.4930017,2.2899978160858154,2.4064942267684657,1739137660.4930058,2.2899978160858154,-0.061889516970281555,1739137660.4930105,2.2899978160858154,1.6397968207595048,1739137660.4930155,2.2899978160858154,9.565565601669892,1739137660.4930186,2.2899978160858154,-0.13956482203366874,1739137660.4930222,2.2899978160858154,-0.010849487763995502,1739137660.4930258,2.2899978160858154,0.13619089240802001,1739137660.493029,2.2899978160858154,0.04080825146210996,1739137660.4930325,2.2899978160858154,2.3674522452434106,1739137660.493036,2.2899978160858154,0.0,1739137660.4930396,2.2899978160858154,0.39026245244333824,1739137660.4930432,2.2899978160858154,6.253312250002321,1739137660.4930465,2.2899978160858154,1.9771897928000723 +1739137660.511391,2.309997797012329,2.4064942267684657,1739137660.511394,2.309997797012329,-0.061889516970281555,1739137660.5113976,2.309997797012329,1.6397968207595048,1739137660.5114005,2.309997797012329,9.565565601669892,1739137660.511402,2.309997797012329,-0.13956482203366874,1739137660.5114038,2.309997797012329,-0.010849487763995502,1739137660.5114055,2.309997797012329,0.13619089240802001,1739137660.5114071,2.309997797012329,0.04080825146210996,1739137660.5114083,2.309997797012329,2.3674522452434106,1739137660.51141,2.309997797012329,0.0,1739137660.511411,2.309997797012329,0.39026245244333824,1739137660.5114124,2.309997797012329,6.253312250002321,1739137660.5114143,2.309997797012329,1.9771897928000723 +1739137660.5311298,2.3299977779388428,2.4064942267684657,1739137660.531133,2.3299977779388428,-0.061889516970281555,1739137660.5311372,2.3299977779388428,1.6397968207595048,1739137660.5311399,2.3299977779388428,9.565565601669892,1739137660.5311413,2.3299977779388428,-0.13956482203366874,1739137660.5311434,2.3299977779388428,-0.010849487763995502,1739137660.5311453,2.3299977779388428,0.13619089240802001,1739137660.5311468,2.3299977779388428,0.04080825146210996,1739137660.531148,2.3299977779388428,2.3674522452434106,1739137660.5311508,2.3299977779388428,0.0,1739137660.5311532,2.3299977779388428,0.39026245244333824,1739137660.5311546,2.3299977779388428,6.253312250002321,1739137660.531156,2.3299977779388428,1.9771897928000723 +1739137660.5510232,2.3499977588653564,2.4064942267684657,1739137660.5510263,2.3499977588653564,-0.061889516970281555,1739137660.5510292,2.3499977588653564,1.6397968207595048,1739137660.5510323,2.3499977588653564,9.565565601669892,1739137660.5510335,2.3499977588653564,-0.13956482203366874,1739137660.5510354,2.3499977588653564,-0.010849487763995502,1739137660.5510366,2.3499977588653564,0.13619089240802001,1739137660.5510385,2.3499977588653564,0.04080825146210996,1739137660.55104,2.3499977588653564,2.3674522452434106,1739137660.5510418,2.3499977588653564,0.0,1739137660.551043,2.3499977588653564,0.39026245244333824,1739137660.551045,2.3499977588653564,6.253312250002321,1739137660.5510464,2.3499977588653564,1.9771897928000723 +1739137660.5724316,2.36999773979187,2.625992561937591,1739137660.5724354,2.36999773979187,-0.06844238526834978,1739137660.5724401,2.36999773979187,2.2290500049930815,1739137660.5724454,2.36999773979187,10.281481572119345,1739137660.5724483,2.36999773979187,-0.143,1739137660.572452,2.36999773979187,-0.00973879754762044,1739137660.5724556,2.36999773979187,0.15366342855236223,1739137660.572459,2.36999773979187,0.04026693626139558,1739137660.5724623,2.36999773979187,2.3509637734739077,1739137660.572466,2.36999773979187,0.0,1739137660.5724692,2.36999773979187,0.27816650643647456,1739137660.5724728,2.36999773979187,6.253373793151418,1739137660.5724761,2.36999773979187,2.019418218464236 +1739137660.5912511,2.389997720718384,2.625992561937591,1739137660.591255,2.389997720718384,-0.06844238526834978,1739137660.5912583,2.389997720718384,2.2290500049930815,1739137660.5912614,2.389997720718384,10.281481572119345,1739137660.591263,2.389997720718384,-0.143,1739137660.5912647,2.389997720718384,-0.00973879754762044,1739137660.5912662,2.389997720718384,0.15366342855236223,1739137660.5912676,2.389997720718384,0.04026693626139558,1739137660.5912697,2.389997720718384,2.3509637734739077,1739137660.5912712,2.389997720718384,0.0,1739137660.5912726,2.389997720718384,0.33154555500967176,1739137660.591275,2.389997720718384,6.253373793151418,1739137660.5912766,2.389997720718384,2.019418218464236 +1739137660.6125505,2.4099977016448975,2.625992561937591,1739137660.6125546,2.4099977016448975,-0.06844238526834978,1739137660.6125593,2.4099977016448975,2.2290500049930815,1739137660.6125648,2.4099977016448975,10.281481572119345,1739137660.612568,2.4099977016448975,-0.143,1739137660.6125715,2.4099977016448975,-0.00973879754762044,1739137660.6125746,2.4099977016448975,0.15366342855236223,1739137660.6125777,2.4099977016448975,0.04026693626139558,1739137660.6125808,2.4099977016448975,2.3509637734739077,1739137660.612584,2.4099977016448975,0.0,1739137660.6125877,2.4099977016448975,0.33154555500967176,1739137660.612591,2.4099977016448975,6.253373793151418,1739137660.6125941,2.4099977016448975,2.019418218464236 +1739137660.631473,2.429997682571411,2.625992561937591,1739137660.6314764,2.429997682571411,-0.06844238526834978,1739137660.6314793,2.429997682571411,2.2290500049930815,1739137660.6314824,2.429997682571411,10.281481572119345,1739137660.6314836,2.429997682571411,-0.143,1739137660.6314855,2.429997682571411,-0.00973879754762044,1739137660.6314871,2.429997682571411,0.15366342855236223,1739137660.6314886,2.429997682571411,0.04026693626139558,1739137660.63149,2.429997682571411,2.3509637734739077,1739137660.6314917,2.429997682571411,0.0,1739137660.631493,2.429997682571411,0.33154555500967176,1739137660.6314948,2.429997682571411,6.253373793151418,1739137660.6314962,2.429997682571411,2.019418218464236 +1739137660.652348,2.449997663497925,2.625992561937591,1739137660.6523523,2.449997663497925,-0.06844238526834978,1739137660.652357,2.449997663497925,2.2290500049930815,1739137660.6523623,2.449997663497925,10.281481572119345,1739137660.6523652,2.449997663497925,-0.143,1739137660.6523693,2.449997663497925,-0.00973879754762044,1739137660.6523726,2.449997663497925,0.15366342855236223,1739137660.6523762,2.449997663497925,0.04026693626139558,1739137660.6523793,2.449997663497925,2.3509637734739077,1739137660.652383,2.449997663497925,0.0,1739137660.6523862,2.449997663497925,0.33154555500967176,1739137660.65239,2.449997663497925,6.253373793151418,1739137660.652393,2.449997663497925,2.019418218464236 +1739137660.6734216,2.4699976444244385,2.625992561937591,1739137660.6734254,2.4699976444244385,-0.06844238526834978,1739137660.67343,2.4699976444244385,2.2290500049930815,1739137660.6734354,2.4699976444244385,10.281481572119345,1739137660.6734383,2.4699976444244385,-0.143,1739137660.6734421,2.4699976444244385,-0.00973879754762044,1739137660.6734455,2.4699976444244385,0.15366342855236223,1739137660.6734488,2.4699976444244385,0.04026693626139558,1739137660.6734524,2.4699976444244385,2.3509637734739077,1739137660.6734557,2.4699976444244385,0.0,1739137660.6734593,2.4699976444244385,0.33154555500967176,1739137660.673463,2.4699976444244385,6.253373793151418,1739137660.6734664,2.4699976444244385,2.019418218464236 +1739137660.6938026,2.489997625350952,2.8497468147779053,1739137660.6938064,2.489997625350952,-0.07510853027225117,1739137660.693811,2.489997625350952,2.6681385019798434,1739137660.693816,2.489997625350952,10.826302786078172,1739137660.693819,2.489997625350952,-0.145,1739137660.6938226,2.489997625350952,-0.00876188688851796,1739137660.693826,2.489997625350952,0.16740676200676016,1739137660.6938295,2.489997625350952,0.04040859692252238,1739137660.6938326,2.489997625350952,2.3380752006918124,1739137660.6938362,2.489997625350952,0.0,1739137660.6938398,2.489997625350952,0.23965070627594326,1739137660.6938434,2.489997625350952,6.253435336300515,1739137660.693847,2.489997625350952,2.0546650207781343 +1739137660.7127457,2.509997606277466,2.8497468147779053,1739137660.7127483,2.509997606277466,-0.07510853027225117,1739137660.7127514,2.509997606277466,2.6681385019798434,1739137660.712754,2.509997606277466,10.826302786078172,1739137660.7127554,2.509997606277466,-0.145,1739137660.712757,2.509997606277466,-0.00876188688851796,1739137660.7127585,2.509997606277466,0.16740676200676016,1739137660.7127597,2.509997606277466,0.04040859692252238,1739137660.7127612,2.509997606277466,2.3380752006918124,1739137660.7127626,2.509997606277466,0.0,1739137660.7127638,2.509997606277466,0.2834101799136781,1739137660.7127655,2.509997606277466,6.253435336300515,1739137660.7127666,2.509997606277466,2.0546650207781343 +1739137660.7310946,2.5299975872039795,2.8497468147779053,1739137660.7310977,2.5299975872039795,-0.07510853027225117,1739137660.731102,2.5299975872039795,2.6681385019798434,1739137660.7311046,2.5299975872039795,10.826302786078172,1739137660.731106,2.5299975872039795,-0.145,1739137660.7311084,2.5299975872039795,-0.00876188688851796,1739137660.7311099,2.5299975872039795,0.16740676200676016,1739137660.7311115,2.5299975872039795,0.04040859692252238,1739137660.7311127,2.5299975872039795,2.3380752006918124,1739137660.7311144,2.5299975872039795,0.0,1739137660.7311158,2.5299975872039795,0.2834101799136781,1739137660.7311175,2.5299975872039795,6.253435336300515,1739137660.7311192,2.5299975872039795,2.0546650207781343 +1739137660.7510016,2.549997568130493,2.8497468147779053,1739137660.7510045,2.549997568130493,-0.07510853027225117,1739137660.7510087,2.549997568130493,2.6681385019798434,1739137660.7510116,2.549997568130493,10.826302786078172,1739137660.7510128,2.549997568130493,-0.145,1739137660.7510152,2.549997568130493,-0.00876188688851796,1739137660.7510166,2.549997568130493,0.16740676200676016,1739137660.751018,2.549997568130493,0.04040859692252238,1739137660.7510195,2.549997568130493,2.3380752006918124,1739137660.7510219,2.549997568130493,0.0,1739137660.751023,2.549997568130493,0.2834101799136781,1739137660.7510247,2.549997568130493,6.253435336300515,1739137660.751026,2.549997568130493,2.0546650207781343 +1739137660.7711442,2.569997549057007,2.8497468147779053,1739137660.771147,2.569997549057007,-0.07510853027225117,1739137660.7711504,2.569997549057007,2.6681385019798434,1739137660.7711535,2.569997549057007,10.826302786078172,1739137660.771155,2.569997549057007,-0.145,1739137660.7711573,2.569997549057007,-0.00876188688851796,1739137660.771159,2.569997549057007,0.16740676200676016,1739137660.7711608,2.569997549057007,0.04040859692252238,1739137660.7711625,2.569997549057007,2.3380752006918124,1739137660.7711642,2.569997549057007,0.0,1739137660.7711656,2.569997549057007,0.2834101799136781,1739137660.7711675,2.569997549057007,6.253435336300515,1739137660.771169,2.569997549057007,2.0546650207781343 +1739137660.790978,2.5899975299835205,3.077233552548215,1739137660.7909803,2.5899975299835205,-0.08187186494627863,1739137660.7909832,2.5899975299835205,2.5956207406995127,1739137660.790986,2.5899975299835205,10.846949937939732,1739137660.7909873,2.5899975299835205,-0.145,1739137660.7909887,2.5899975299835205,-0.008124716896402888,1739137660.79099,2.5899975299835205,0.16753646281611356,1739137660.7909913,2.5899975299835205,0.04262185379263679,1739137660.7909927,2.5899975299835205,2.337953903739959,1739137660.790994,2.5899975299835205,0.0,1739137660.7909951,2.5899975299835205,0.22389182306799627,1739137660.7909966,2.5899975299835205,6.253496879449612,1739137660.7909977,2.5899975299835205,2.085719991825431 +1739137660.8110166,2.609997510910034,3.077233552548215,1739137660.8110201,2.609997510910034,-0.08187186494627863,1739137660.811023,2.609997510910034,2.5956207406995127,1739137660.811026,2.609997510910034,10.846949937939732,1739137660.811028,2.609997510910034,-0.145,1739137660.81103,2.609997510910034,-0.008124716896402888,1739137660.8110318,2.609997510910034,0.16753646281611356,1739137660.8110332,2.609997510910034,0.04262185379263679,1739137660.811035,2.609997510910034,2.337953903739959,1739137660.8110366,2.609997510910034,0.0,1739137660.8110385,2.609997510910034,0.2522339119145278,1739137660.8110402,2.609997510910034,6.253496879449612,1739137660.8110416,2.609997510910034,2.085719991825431 +1739137660.831222,2.629997491836548,3.077233552548215,1739137660.831225,2.629997491836548,-0.08187186494627863,1739137660.831228,2.629997491836548,2.5956207406995127,1739137660.8312304,2.629997491836548,10.846949937939732,1739137660.8312318,2.629997491836548,-0.145,1739137660.8312333,2.629997491836548,-0.008124716896402888,1739137660.831235,2.629997491836548,0.16753646281611356,1739137660.831236,2.629997491836548,0.04262185379263679,1739137660.8312373,2.629997491836548,2.337953903739959,1739137660.831239,2.629997491836548,0.0,1739137660.8312404,2.629997491836548,0.2522339119145278,1739137660.8312418,2.629997491836548,6.253496879449612,1739137660.831243,2.629997491836548,2.085719991825431 +1739137660.8510273,2.6499974727630615,3.077233552548215,1739137660.8510299,2.6499974727630615,-0.08187186494627863,1739137660.8510325,2.6499974727630615,2.5956207406995127,1739137660.8510354,2.6499974727630615,10.846949937939732,1739137660.8510368,2.6499974727630615,-0.145,1739137660.8510382,2.6499974727630615,-0.008124716896402888,1739137660.8510396,2.6499974727630615,0.16753646281611356,1739137660.8510408,2.6499974727630615,0.04262185379263679,1739137660.851042,2.6499974727630615,2.337953903739959,1739137660.851044,2.6499974727630615,0.0,1739137660.8510451,2.6499974727630615,0.2522339119145278,1739137660.8510466,2.6499974727630615,6.253496879449612,1739137660.8510482,2.6499974727630615,2.085719991825431 +1739137660.8709073,2.669997453689575,3.077233552548215,1739137660.87091,2.669997453689575,-0.08187186494627863,1739137660.8709128,2.669997453689575,2.5956207406995127,1739137660.8709157,2.669997453689575,10.846949937939732,1739137660.8709168,2.669997453689575,-0.145,1739137660.8709185,2.669997453689575,-0.008124716896402888,1739137660.87092,2.669997453689575,0.16753646281611356,1739137660.8709214,2.669997453689575,0.04262185379263679,1739137660.8709228,2.669997453689575,2.337953903739959,1739137660.870924,2.669997453689575,0.0,1739137660.8709254,2.669997453689575,0.2522339119145278,1739137660.870927,2.669997453689575,6.253496879449612,1739137660.8709283,2.669997453689575,2.085719991825431 +1739137660.8907928,2.689997434616089,3.077233552548215,1739137660.8907955,2.689997434616089,-0.08187186494627863,1739137660.8907983,2.689997434616089,2.5956207406995127,1739137660.8908012,2.689997434616089,10.846949937939732,1739137660.8908024,2.689997434616089,-0.145,1739137660.890804,2.689997434616089,-0.008124716896402888,1739137660.8908052,2.689997434616089,0.16753646281611356,1739137660.8908067,2.689997434616089,0.04262185379263679,1739137660.8908079,2.689997434616089,2.337953903739959,1739137660.8908093,2.689997434616089,0.0,1739137660.890811,2.689997434616089,0.2522339119145278,1739137660.8908122,2.689997434616089,6.253496879449612,1739137660.8908134,2.689997434616089,2.085719991825431 +1739137660.9109135,2.7099974155426025,3.307891293370223,1739137660.9109159,2.7099974155426025,-0.08870830102808647,1739137660.9109187,2.7099974155426025,2.624005315692783,1739137660.910921,2.7099974155426025,10.956487575804779,1739137660.9109225,2.7099974155426025,-0.1457494352638536,1739137660.9109242,2.7099974155426025,-0.007457587597299514,1739137660.9109256,2.7099974155426025,0.16899212294555468,1739137660.9109268,2.7099974155426025,0.04436478558665745,1739137660.910928,2.7099974155426025,2.3365929934701137,1739137660.91093,2.7099974155426025,0.0,1739137660.9109309,2.7099974155426025,0.19798209431480562,1739137660.9109325,2.7099974155426025,6.253632008326356,1739137660.9109337,2.7099974155426025,2.11277668739298 +1739137660.9309065,2.729997396469116,3.307891293370223,1739137660.9309092,2.729997396469116,-0.08870830102808647,1739137660.930912,2.729997396469116,2.624005315692783,1739137660.9309149,2.729997396469116,10.956487575804779,1739137660.930916,2.729997396469116,-0.1457494352638536,1739137660.9309177,2.729997396469116,-0.007457587597299514,1739137660.930919,2.729997396469116,0.16899212294555468,1739137660.9309204,2.729997396469116,0.04436478558665745,1739137660.9309218,2.729997396469116,2.3365929934701137,1739137660.930923,2.729997396469116,0.0,1739137660.9309242,2.729997396469116,0.22381630607713365,1739137660.9309258,2.729997396469116,6.253632008326356,1739137660.930927,2.729997396469116,2.11277668739298 +1739137660.9510589,2.74999737739563,3.307891293370223,1739137660.9510617,2.74999737739563,-0.08870830102808647,1739137660.9510648,2.74999737739563,2.624005315692783,1739137660.9510677,2.74999737739563,10.956487575804779,1739137660.951069,2.74999737739563,-0.1457494352638536,1739137660.9510713,2.74999737739563,-0.007457587597299514,1739137660.951073,2.74999737739563,0.16899212294555468,1739137660.9510746,2.74999737739563,0.04436478558665745,1739137660.951076,2.74999737739563,2.3365929934701137,1739137660.951078,2.74999737739563,0.0,1739137660.9510794,2.74999737739563,0.22381630607713365,1739137660.9510813,2.74999737739563,6.253632008326356,1739137660.9510827,2.74999737739563,2.11277668739298 +1739137660.9711962,2.7699973583221436,3.307891293370223,1739137660.971199,2.7699973583221436,-0.08870830102808647,1739137660.9712014,2.7699973583221436,2.624005315692783,1739137660.9712043,2.7699973583221436,10.956487575804779,1739137660.9712057,2.7699973583221436,-0.1457494352638536,1739137660.9712074,2.7699973583221436,-0.007457587597299514,1739137660.9712088,2.7699973583221436,0.16899212294555468,1739137660.9712102,2.7699973583221436,0.04436478558665745,1739137660.9712114,2.7699973583221436,2.3365929934701137,1739137660.971213,2.7699973583221436,0.0,1739137660.9712143,2.7699973583221436,0.22381630607713365,1739137660.971216,2.7699973583221436,6.253632008326356,1739137660.9712172,2.7699973583221436,2.11277668739298 +1739137660.9909904,2.7899973392486572,3.307891293370223,1739137660.9909928,2.7899973392486572,-0.08870830102808647,1739137660.9909954,2.7899973392486572,2.624005315692783,1739137660.990998,2.7899973392486572,10.956487575804779,1739137660.9909992,2.7899973392486572,-0.1457494352638536,1739137660.991001,2.7899973392486572,-0.007457587597299514,1739137660.9910023,2.7899973392486572,0.16899212294555468,1739137660.9910038,2.7899973392486572,0.04436478558665745,1739137660.9910052,2.7899973392486572,2.3365929934701137,1739137660.9910066,2.7899973392486572,0.0,1739137660.991008,2.7899973392486572,0.22381630607713365,1739137660.9910095,2.7899973392486572,6.253632008326356,1739137660.991011,2.7899973392486572,2.11277668739298 +1739137661.0109332,2.809997320175171,3.5414049710406426,1739137661.0109358,2.809997320175171,-0.09559059211150878,1739137661.0109386,2.809997320175171,3.288339936382257,1739137661.0109413,2.809997320175171,11.693554750526726,1739137661.0109425,2.809997320175171,-0.14986277375263363,1739137661.010944,2.809997320175171,-0.006657308971258779,1739137661.0109453,2.809997320175171,0.1849377407661254,1739137661.0109468,2.809997320175171,0.04273894843270501,1739137661.010948,2.809997320175171,2.3217370537113493,1739137661.0109494,2.809997320175171,0.0,1739137661.0109506,2.809997320175171,0.14915830303573155,1739137661.0109522,2.809997320175171,6.253840791391597,1739137661.0109534,2.809997320175171,2.137027302896401 +1739137661.0310016,2.8299973011016846,3.5414049710406426,1739137661.0310042,2.8299973011016846,-0.09559059211150878,1739137661.0310073,2.8299973011016846,3.288339936382257,1739137661.0310094,2.8299973011016846,11.693554750526726,1739137661.0310109,2.8299973011016846,-0.14986277375263363,1739137661.0310123,2.8299973011016846,-0.006657308971258779,1739137661.0310142,2.8299973011016846,0.1849377407661254,1739137661.0310154,2.8299973011016846,0.04273894843270501,1739137661.0310166,2.8299973011016846,2.3217370537113493,1739137661.031018,2.8299973011016846,0.0,1739137661.0310192,2.8299973011016846,0.18470975081494823,1739137661.031021,2.8299973011016846,6.253840791391597,1739137661.0310223,2.8299973011016846,2.137027302896401 +1739137661.0510137,2.8499972820281982,3.5414049710406426,1739137661.0510163,2.8499972820281982,-0.09559059211150878,1739137661.0510192,2.8499972820281982,3.288339936382257,1739137661.051022,2.8499972820281982,11.693554750526726,1739137661.0510232,2.8499972820281982,-0.14986277375263363,1739137661.0510252,2.8499972820281982,-0.006657308971258779,1739137661.0510263,2.8499972820281982,0.1849377407661254,1739137661.0510278,2.8499972820281982,0.04273894843270501,1739137661.051029,2.8499972820281982,2.3217370537113493,1739137661.0510306,2.8499972820281982,0.0,1739137661.051032,2.8499972820281982,0.18470975081494823,1739137661.0510335,2.8499972820281982,6.253840791391597,1739137661.051035,2.8499972820281982,2.137027302896401 +1739137661.071013,2.869997262954712,3.5414049710406426,1739137661.0710156,2.869997262954712,-0.09559059211150878,1739137661.0710185,2.869997262954712,3.288339936382257,1739137661.0710213,2.869997262954712,11.693554750526726,1739137661.0710225,2.869997262954712,-0.14986277375263363,1739137661.0710244,2.869997262954712,-0.006657308971258779,1739137661.0710256,2.869997262954712,0.1849377407661254,1739137661.071027,2.869997262954712,0.04273894843270501,1739137661.0710282,2.869997262954712,2.3217370537113493,1739137661.0710297,2.869997262954712,0.0,1739137661.071031,2.869997262954712,0.18470975081494823,1739137661.0710325,2.869997262954712,6.253840791391597,1739137661.071034,2.869997262954712,2.137027302896401 +1739137661.0910213,2.8899972438812256,3.5414049710406426,1739137661.091024,2.8899972438812256,-0.09559059211150878,1739137661.0910268,2.8899972438812256,3.288339936382257,1739137661.0910292,2.8899972438812256,11.693554750526726,1739137661.0910308,2.8899972438812256,-0.14986277375263363,1739137661.0910323,2.8899972438812256,-0.006657308971258779,1739137661.0910337,2.8899972438812256,0.1849377407661254,1739137661.091035,2.8899972438812256,0.04273894843270501,1739137661.0910358,2.8899972438812256,2.3217370537113493,1739137661.0910375,2.8899972438812256,0.0,1739137661.0910387,2.8899972438812256,0.18470975081494823,1739137661.0910404,2.8899972438812256,6.253840791391597,1739137661.0910413,2.8899972438812256,2.137027302896401 +1739137661.1111073,2.9099972248077393,3.5414049710406426,1739137661.1111104,2.9099972248077393,-0.09559059211150878,1739137661.111113,2.9099972248077393,3.288339936382257,1739137661.1111155,2.9099972248077393,11.693554750526726,1739137661.111117,2.9099972248077393,-0.14986277375263363,1739137661.1111183,2.9099972248077393,-0.006657308971258779,1739137661.11112,2.9099972248077393,0.1849377407661254,1739137661.111121,2.9099972248077393,0.04273894843270501,1739137661.1111221,2.9099972248077393,2.3217370537113493,1739137661.111124,2.9099972248077393,0.0,1739137661.1111252,2.9099972248077393,0.18470975081494823,1739137661.111127,2.9099972248077393,6.253840791391597,1739137661.111128,2.9099972248077393,2.137027302896401 +1739137661.13097,2.929997205734253,3.7773228653955755,1739137661.1309726,2.929997205734253,-0.10249144679524669,1739137661.1309755,2.929997205734253,3.309114512794859,1739137661.1309783,2.929997205734253,11.772884554709076,1739137661.1309795,2.929997205734253,-0.1504632549527596,1739137661.1309812,2.929997205734253,-0.005999732652910324,1739137661.1309824,2.929997205734253,0.18485437834811275,1739137661.1309836,2.929997205734253,0.04440947536301021,1739137661.130985,2.929997205734253,2.3218144732480326,1739137661.1309865,2.929997205734253,0.0,1739137661.130988,2.929997205734253,0.14759358286926128,1739137661.1309896,2.929997205734253,6.2540643068158905,1739137661.1309907,2.929997205734253,2.1565465158612267 +1739137661.1509256,2.9499971866607666,3.7773228653955755,1739137661.150928,2.9499971866607666,-0.10249144679524669,1739137661.150931,2.9499971866607666,3.309114512794859,1739137661.1509335,2.9499971866607666,11.772884554709076,1739137661.1509347,2.9499971866607666,-0.1504632549527596,1739137661.1509366,2.9499971866607666,-0.005999732652910324,1739137661.150938,2.9499971866607666,0.18485437834811275,1739137661.1509395,2.9499971866607666,0.04440947536301021,1739137661.1509407,2.9499971866607666,2.3218144732480326,1739137661.1509423,2.9499971866607666,0.0,1739137661.1509435,2.9499971866607666,0.16526795738680589,1739137661.150945,2.9499971866607666,6.2540643068158905,1739137661.1509464,2.9499971866607666,2.1565465158612267 +1739137661.1709394,2.9699971675872803,3.7773228653955755,1739137661.170942,2.9699971675872803,-0.10249144679524669,1739137661.1709452,2.9699971675872803,3.309114512794859,1739137661.1709478,2.9699971675872803,11.772884554709076,1739137661.1709492,2.9699971675872803,-0.1504632549527596,1739137661.1709507,2.9699971675872803,-0.005999732652910324,1739137661.170952,2.9699971675872803,0.18485437834811275,1739137661.1709535,2.9699971675872803,0.04440947536301021,1739137661.1709545,2.9699971675872803,2.3218144732480326,1739137661.1709561,2.9699971675872803,0.0,1739137661.1709576,2.9699971675872803,0.16526795738680589,1739137661.1709588,2.9699971675872803,6.2540643068158905,1739137661.1709607,2.9699971675872803,2.1565465158612267 +1739137661.1909466,2.989997148513794,3.7773228653955755,1739137661.1909494,2.989997148513794,-0.10249144679524669,1739137661.1909523,2.989997148513794,3.309114512794859,1739137661.190955,2.989997148513794,11.772884554709076,1739137661.1909564,2.989997148513794,-0.1504632549527596,1739137661.190958,2.989997148513794,-0.005999732652910324,1739137661.1909597,2.989997148513794,0.18485437834811275,1739137661.190961,2.989997148513794,0.04440947536301021,1739137661.190962,2.989997148513794,2.3218144732480326,1739137661.1909637,2.989997148513794,0.0,1739137661.190965,2.989997148513794,0.16526795738680589,1739137661.1909666,2.989997148513794,6.2540643068158905,1739137661.1909678,2.989997148513794,2.1565465158612267 +1739137661.2110865,3.0099971294403076,3.7773228653955755,1739137661.2110894,3.0099971294403076,-0.10249144679524669,1739137661.211092,3.0099971294403076,3.309114512794859,1739137661.2110949,3.0099971294403076,11.772884554709076,1739137661.211096,3.0099971294403076,-0.1504632549527596,1739137661.2110977,3.0099971294403076,-0.005999732652910324,1739137661.2110994,3.0099971294403076,0.18485437834811275,1739137661.2111006,3.0099971294403076,0.04440947536301021,1739137661.211102,3.0099971294403076,2.3218144732480326,1739137661.2111032,3.0099971294403076,0.0,1739137661.2111044,3.0099971294403076,0.16526795738680589,1739137661.211106,3.0099971294403076,6.2540643068158905,1739137661.2111073,3.0099971294403076,2.1565465158612267 +1739137661.2309983,3.0299971103668213,4.015336778184979,1739137661.231001,3.0299971103668213,-0.10940037160313665,1739137661.2310038,3.0299971103668213,3.330073554969942,1739137661.2310061,3.0299971103668213,11.8475979014272,1739137661.2310076,3.0299971103668213,-0.151,1739137661.231009,3.0299971103668213,-0.005311267917704552,1739137661.2310102,3.0299971103668213,0.18471888835095346,1739137661.231012,3.0299971103668213,0.04624678539871167,1739137661.2310133,3.0299971103668213,2.3219403097124722,1739137661.2310147,3.0299971103668213,0.0,1739137661.231016,3.0299971103668213,0.13129936568821174,1739137661.2310176,3.0299971103668213,6.254287822240184,1739137661.2310188,3.0299971103668213,2.174465416087404 +1739137661.2509136,3.049997091293335,4.015336778184979,1739137661.2509177,3.049997091293335,-0.10940037160313665,1739137661.250921,3.049997091293335,3.330073554969942,1739137661.250924,3.049997091293335,11.8475979014272,1739137661.2509258,3.049997091293335,-0.151,1739137661.250928,3.049997091293335,-0.005311267917704552,1739137661.2509294,3.049997091293335,0.18471888835095346,1739137661.250931,3.049997091293335,0.04624678539871167,1739137661.2509327,3.049997091293335,2.3219403097124722,1739137661.2509348,3.049997091293335,0.0,1739137661.2509363,3.049997091293335,0.14747489362506805,1739137661.2509382,3.049997091293335,6.254287822240184,1739137661.2509398,3.049997091293335,2.174465416087404 +1739137661.2709095,3.0699970722198486,4.015336778184979,1739137661.2709124,3.0699970722198486,-0.10940037160313665,1739137661.2709153,3.0699970722198486,3.330073554969942,1739137661.270918,3.0699970722198486,11.8475979014272,1739137661.270919,3.0699970722198486,-0.151,1739137661.270921,3.0699970722198486,-0.005311267917704552,1739137661.2709222,3.0699970722198486,0.18471888835095346,1739137661.2709236,3.0699970722198486,0.04624678539871167,1739137661.2709248,3.0699970722198486,2.3219403097124722,1739137661.2709265,3.0699970722198486,0.0,1739137661.270928,3.0699970722198486,0.14747489362506805,1739137661.2709296,3.0699970722198486,6.254287822240184,1739137661.2709308,3.0699970722198486,2.174465416087404 +1739137661.2909102,3.0899970531463623,4.015336778184979,1739137661.2909133,3.0899970531463623,-0.10940037160313665,1739137661.2909157,3.0899970531463623,3.330073554969942,1739137661.2909188,3.0899970531463623,11.8475979014272,1739137661.2909203,3.0899970531463623,-0.151,1739137661.2909217,3.0899970531463623,-0.005311267917704552,1739137661.290923,3.0899970531463623,0.18471888835095346,1739137661.2909243,3.0899970531463623,0.04624678539871167,1739137661.2909255,3.0899970531463623,2.3219403097124722,1739137661.2909272,3.0899970531463623,0.0,1739137661.2909286,3.0899970531463623,0.14747489362506805,1739137661.2909303,3.0899970531463623,6.254287822240184,1739137661.2909315,3.0899970531463623,2.174465416087404 +1739137661.3110964,3.109997034072876,4.015336778184979,1739137661.311099,3.109997034072876,-0.10940037160313665,1739137661.311102,3.109997034072876,3.330073554969942,1739137661.3111048,3.109997034072876,11.8475979014272,1739137661.3111057,3.109997034072876,-0.151,1739137661.3111076,3.109997034072876,-0.005311267917704552,1739137661.3111088,3.109997034072876,0.18471888835095346,1739137661.3111103,3.109997034072876,0.04624678539871167,1739137661.3111115,3.109997034072876,2.3219403097124722,1739137661.311113,3.109997034072876,0.0,1739137661.3111145,3.109997034072876,0.14747489362506805,1739137661.3111157,3.109997034072876,6.254287822240184,1739137661.3111174,3.109997034072876,2.174465416087404 +1739137661.330931,3.1299970149993896,4.015336778184979,1739137661.3309338,3.1299970149993896,-0.10940037160313665,1739137661.3309364,3.1299970149993896,3.330073554969942,1739137661.3309388,3.1299970149993896,11.8475979014272,1739137661.3309402,3.1299970149993896,-0.151,1739137661.330942,3.1299970149993896,-0.005311267917704552,1739137661.3309433,3.1299970149993896,0.18471888835095346,1739137661.3309445,3.1299970149993896,0.04624678539871167,1739137661.3309457,3.1299970149993896,2.3219403097124722,1739137661.3309474,3.1299970149993896,0.0,1739137661.3309484,3.1299970149993896,0.14747489362506805,1739137661.3309498,3.1299970149993896,6.254287822240184,1739137661.3309512,3.1299970149993896,2.174465416087404 +1739137661.3510315,3.1499969959259033,4.255206926136404,1739137661.3510342,3.1499969959259033,-0.1163022690241311,1739137661.351037,3.1499969959259033,3.3511959317845093,1739137661.3510394,3.1499969959259033,11.916197958974704,1739137661.3510408,3.1499969959259033,-0.151,1739137661.3510423,3.1499969959259033,-0.004529112953776976,1739137661.351044,3.1499969959259033,0.18439265663430507,1739137661.3510451,3.1499969959259033,0.0482523609324903,1739137661.351046,3.1499969959259033,2.322243325712005,1739137661.3510478,3.1499969959259033,0.0,1739137661.351049,3.1499969959259033,0.1178402956997768,1739137661.3510504,3.1499969959259033,6.254585082223699,1739137661.3510516,3.1499969959259033,2.19029130966505 +1739137661.3710697,3.169996976852417,4.255206926136404,1739137661.3710725,3.169996976852417,-0.1163022690241311,1739137661.3710754,3.169996976852417,3.3511959317845093,1739137661.3710778,3.169996976852417,11.916197958974704,1739137661.3710794,3.169996976852417,-0.151,1739137661.3710809,3.169996976852417,-0.004529112953776976,1739137661.3710823,3.169996976852417,0.18439265663430507,1739137661.3710837,3.169996976852417,0.0482523609324903,1739137661.3710847,3.169996976852417,2.322243325712005,1739137661.3710864,3.169996976852417,0.0,1739137661.3710876,3.169996976852417,0.1319520160469554,1739137661.3710892,3.169996976852417,6.254585082223699,1739137661.3710904,3.169996976852417,2.19029130966505 +1739137661.390906,3.1899969577789307,4.255206926136404,1739137661.390909,3.1899969577789307,-0.1163022690241311,1739137661.3909118,3.1899969577789307,3.3511959317845093,1739137661.3909142,3.1899969577789307,11.916197958974704,1739137661.3909156,3.1899969577789307,-0.151,1739137661.390917,3.1899969577789307,-0.004529112953776976,1739137661.3909187,3.1899969577789307,0.18439265663430507,1739137661.3909197,3.1899969577789307,0.0482523609324903,1739137661.3909209,3.1899969577789307,2.322243325712005,1739137661.3909225,3.1899969577789307,0.0,1739137661.3909237,3.1899969577789307,0.1319520160469554,1739137661.3909254,3.1899969577789307,6.254585082223699,1739137661.3909266,3.1899969577789307,2.19029130966505 +1739137661.410916,3.2099969387054443,4.255206926136404,1739137661.4109187,3.2099969387054443,-0.1163022690241311,1739137661.4109218,3.2099969387054443,3.3511959317845093,1739137661.410925,3.2099969387054443,11.916197958974704,1739137661.4109266,3.2099969387054443,-0.151,1739137661.4109287,3.2099969387054443,-0.004529112953776976,1739137661.4109302,3.2099969387054443,0.18439265663430507,1739137661.4109318,3.2099969387054443,0.0482523609324903,1739137661.410933,3.2099969387054443,2.322243325712005,1739137661.4109342,3.2099969387054443,0.0,1739137661.4109359,3.2099969387054443,0.1319520160469554,1739137661.4109373,3.2099969387054443,6.254585082223699,1739137661.410939,3.2099969387054443,2.19029130966505 +1739137661.430918,3.229996919631958,4.255206926136404,1739137661.4309206,3.229996919631958,-0.1163022690241311,1739137661.4309232,3.229996919631958,3.3511959317845093,1739137661.430926,3.229996919631958,11.916197958974704,1739137661.4309273,3.229996919631958,-0.151,1739137661.4309292,3.229996919631958,-0.004529112953776976,1739137661.4309304,3.229996919631958,0.18439265663430507,1739137661.4309318,3.229996919631958,0.0482523609324903,1739137661.430933,3.229996919631958,2.322243325712005,1739137661.4309344,3.229996919631958,0.0,1739137661.430936,3.229996919631958,0.1319520160469554,1739137661.4309373,3.229996919631958,6.254585082223699,1739137661.430939,3.229996919631958,2.19029130966505 +1739137661.4509037,3.2499969005584717,4.496755040191557,1739137661.4509063,3.2499969005584717,-0.1231731191804073,1739137661.4509091,3.2499969005584717,3.6971691356971124,1739137661.4509118,3.2499969005584717,12.305078737367532,1739137661.450913,3.2499969005584717,-0.153,1739137661.4509149,3.2499969005584717,-0.0038198641481311476,1739137661.450916,3.2499969005584717,0.19057799510060883,1739137661.4509175,3.2499969005584717,0.04800704140025614,1739137661.4509187,3.2499969005584717,2.3165048830929704,1739137661.45092,3.2499969005584717,0.0,1739137661.4509215,3.2499969005584717,0.09368557445592214,1739137661.450923,3.2499969005584717,6.254956166716106,1739137661.4509244,3.2499969005584717,2.204597184490952 +1739137661.4711292,3.2699968814849854,4.496755040191557,1739137661.4711323,3.2699968814849854,-0.1231731191804073,1739137661.4711347,3.2699968814849854,3.6971691356971124,1739137661.4711375,3.2699968814849854,12.305078737367532,1739137661.4711387,3.2699968814849854,-0.153,1739137661.4711406,3.2699968814849854,-0.0038198641481311476,1739137661.471142,3.2699968814849854,0.19057799510060883,1739137661.4711432,3.2699968814849854,0.04800704140025614,1739137661.4711444,3.2699968814849854,2.3165048830929704,1739137661.4711459,3.2699968814849854,0.0,1739137661.4711473,3.2699968814849854,0.11190769860201843,1739137661.4711487,3.2699968814849854,6.254956166716106,1739137661.4711502,3.2699968814849854,2.204597184490952 +1739137661.4909675,3.289996862411499,4.496755040191557,1739137661.4909701,3.289996862411499,-0.1231731191804073,1739137661.4909732,3.289996862411499,3.6971691356971124,1739137661.4909759,3.289996862411499,12.305078737367532,1739137661.490977,3.289996862411499,-0.153,1739137661.4909785,3.289996862411499,-0.0038198641481311476,1739137661.49098,3.289996862411499,0.19057799510060883,1739137661.4909813,3.289996862411499,0.04800704140025614,1739137661.4909823,3.289996862411499,2.3165048830929704,1739137661.490984,3.289996862411499,0.0,1739137661.4909852,3.289996862411499,0.11190769860201843,1739137661.4909868,3.289996862411499,6.254956166716106,1739137661.490988,3.289996862411499,2.204597184490952 +1739137661.5109696,3.3099968433380127,4.496755040191557,1739137661.5109725,3.3099968433380127,-0.1231731191804073,1739137661.510975,3.3099968433380127,3.6971691356971124,1739137661.5109777,3.3099968433380127,12.305078737367532,1739137661.5109792,3.3099968433380127,-0.153,1739137661.5109808,3.3099968433380127,-0.0038198641481311476,1739137661.510982,3.3099968433380127,0.19057799510060883,1739137661.5109835,3.3099968433380127,0.04800704140025614,1739137661.5109847,3.3099968433380127,2.3165048830929704,1739137661.510986,3.3099968433380127,0.0,1739137661.5109873,3.3099968433380127,0.11190769860201843,1739137661.510989,3.3099968433380127,6.254956166716106,1739137661.5109906,3.3099968433380127,2.204597184490952 +1739137661.5310664,3.3299968242645264,4.496755040191557,1739137661.5310693,3.3299968242645264,-0.1231731191804073,1739137661.5310717,3.3299968242645264,3.6971691356971124,1739137661.5310743,3.3299968242645264,12.305078737367532,1739137661.5310755,3.3299968242645264,-0.153,1739137661.5310774,3.3299968242645264,-0.0038198641481311476,1739137661.5310786,3.3299968242645264,0.19057799510060883,1739137661.53108,3.3299968242645264,0.04800704140025614,1739137661.5310812,3.3299968242645264,2.3165048830929704,1739137661.5310829,3.3299968242645264,0.0,1739137661.531084,3.3299968242645264,0.11190769860201843,1739137661.5310855,3.3299968242645264,6.254956166716106,1739137661.5310872,3.3299968242645264,2.204597184490952 +1739137661.5510683,3.34999680519104,4.496755040191557,1739137661.5510714,3.34999680519104,-0.1231731191804073,1739137661.5510743,3.34999680519104,3.6971691356971124,1739137661.5510771,3.34999680519104,12.305078737367532,1739137661.5510788,3.34999680519104,-0.153,1739137661.5510807,3.34999680519104,-0.0038198641481311476,1739137661.5510821,3.34999680519104,0.19057799510060883,1739137661.5510836,3.34999680519104,0.04800704140025614,1739137661.551085,3.34999680519104,2.3165048830929704,1739137661.5510867,3.34999680519104,0.0,1739137661.551088,3.34999680519104,0.11190769860201843,1739137661.5510898,3.34999680519104,6.254956166716106,1739137661.5510912,3.34999680519104,2.204597184490952 +1739137661.5711415,3.3699967861175537,4.739744354754899,1739137661.571144,3.3699967861175537,-0.1299916282566551,1739137661.571147,3.3699967861175537,3.8819145102646417,1739137661.5711496,3.3699967861175537,12.525495251884937,1739137661.5711508,3.3699967861175537,-0.15337966354800703,1739137661.5711527,3.3699967861175537,-0.0030039446742622165,1739137661.5711539,3.3699967861175537,0.19337393571471506,1739137661.5711555,3.3699967861175537,0.04899430605484331,1739137661.5711567,3.3699967861175537,2.3139156072210003,1739137661.5711582,3.3699967861175537,0.0,1739137661.5711596,3.3699967861175537,0.0842637984148609,1739137661.571161,3.3699967861175537,6.255342017886951,1739137661.5711625,3.3699967861175537,2.2164880402363774 +1739137661.5909748,3.3899967670440674,4.739744354754899,1739137661.5909772,3.3899967670440674,-0.1299916282566551,1739137661.5909798,3.3899967670440674,3.8819145102646417,1739137661.5909824,3.3899967670440674,12.525495251884937,1739137661.5909836,3.3899967670440674,-0.15337966354800703,1739137661.5909853,3.3899967670440674,-0.0030039446742622165,1739137661.5909865,3.3899967670440674,0.19337393571471506,1739137661.590988,3.3899967670440674,0.04899430605484331,1739137661.5909894,3.3899967670440674,2.3139156072210003,1739137661.5909908,3.3899967670440674,0.0,1739137661.5909922,3.3899967670440674,0.09742756698462296,1739137661.5909936,3.3899967670440674,6.255342017886951,1739137661.5909948,3.3899967670440674,2.2164880402363774 +1739137661.6109397,3.409996747970581,4.739744354754899,1739137661.6109424,3.409996747970581,-0.1299916282566551,1739137661.6109452,3.409996747970581,3.8819145102646417,1739137661.6109483,3.409996747970581,12.525495251884937,1739137661.6109495,3.409996747970581,-0.15337966354800703,1739137661.6109512,3.409996747970581,-0.0030039446742622165,1739137661.6109524,3.409996747970581,0.19337393571471506,1739137661.6109538,3.409996747970581,0.04899430605484331,1739137661.6109548,3.409996747970581,2.3139156072210003,1739137661.610957,3.409996747970581,0.0,1739137661.610958,3.409996747970581,0.09742756698462296,1739137661.6109595,3.409996747970581,6.255342017886951,1739137661.610961,3.409996747970581,2.2164880402363774 +1739137661.6308649,3.4299967288970947,4.739744354754899,1739137661.6308675,3.4299967288970947,-0.1299916282566551,1739137661.6308706,3.4299967288970947,3.8819145102646417,1739137661.6308734,3.4299967288970947,12.525495251884937,1739137661.6308749,3.4299967288970947,-0.15337966354800703,1739137661.6308768,3.4299967288970947,-0.0030039446742622165,1739137661.630878,3.4299967288970947,0.19337393571471506,1739137661.6308792,3.4299967288970947,0.04899430605484331,1739137661.6308806,3.4299967288970947,2.3139156072210003,1739137661.630882,3.4299967288970947,0.0,1739137661.630883,3.4299967288970947,0.09742756698462296,1739137661.6308846,3.4299967288970947,6.255342017886951,1739137661.630886,3.4299967288970947,2.2164880402363774 +1739137661.6509366,3.4499967098236084,4.739744354754899,1739137661.6509392,3.4499967098236084,-0.1299916282566551,1739137661.6509416,3.4499967098236084,3.8819145102646417,1739137661.6509445,3.4499967098236084,12.525495251884937,1739137661.650946,3.4499967098236084,-0.15337966354800703,1739137661.6509476,3.4499967098236084,-0.0030039446742622165,1739137661.650949,3.4499967098236084,0.19337393571471506,1739137661.6509504,3.4499967098236084,0.04899430605484331,1739137661.6509516,3.4499967098236084,2.3139156072210003,1739137661.6509533,3.4499967098236084,0.0,1739137661.6509545,3.4499967098236084,0.09742756698462296,1739137661.6509557,3.4499967098236084,6.255342017886951,1739137661.6509573,3.4499967098236084,2.2164880402363774 +1739137661.6717262,3.469996690750122,4.98399002679426,1739137661.6717296,3.469996690750122,-0.13674516595526942,1739137661.6717343,3.469996690750122,4.1487516964339965,1739137661.671739,3.469996690750122,12.82393889793054,1739137661.671742,3.469996690750122,-0.155,1739137661.6717455,3.469996690750122,-0.0023284336868278476,1739137661.6717486,3.469996690750122,0.19646886328553678,1739137661.671752,3.469996690750122,0.049092750401051044,1739137661.6717553,3.469996690750122,2.311052819127242,1739137661.6717587,3.469996690750122,0.0,1739137661.6717618,3.469996690750122,0.0718446804205374,1739137661.671765,3.469996690750122,6.255794350333622,1739137661.6717684,3.469996690750122,2.2270258056858183 +1739137661.6909733,3.4899966716766357,4.98399002679426,1739137661.6909757,3.4899966716766357,-0.13674516595526942,1739137661.6909783,3.4899966716766357,4.1487516964339965,1739137661.690981,3.4899966716766357,12.82393889793054,1739137661.690982,3.4899966716766357,-0.155,1739137661.6909838,3.4899966716766357,-0.0023284336868278476,1739137661.690985,3.4899966716766357,0.19646886328553678,1739137661.6909862,3.4899966716766357,0.049092750401051044,1739137661.6909873,3.4899966716766357,2.311052819127242,1739137661.690989,3.4899966716766357,0.0,1739137661.6909904,3.4899966716766357,0.08402701344142383,1739137661.6909919,3.4899966716766357,6.255794350333622,1739137661.690993,3.4899966716766357,2.2270258056858183 +1739137661.7111237,3.5099966526031494,4.98399002679426,1739137661.7111263,3.5099966526031494,-0.13674516595526942,1739137661.7111292,3.5099966526031494,4.1487516964339965,1739137661.7111316,3.5099966526031494,12.82393889793054,1739137661.711133,3.5099966526031494,-0.155,1739137661.7111342,3.5099966526031494,-0.0023284336868278476,1739137661.7111354,3.5099966526031494,0.19646886328553678,1739137661.7111368,3.5099966526031494,0.049092750401051044,1739137661.7111378,3.5099966526031494,2.311052819127242,1739137661.7111394,3.5099966526031494,0.0,1739137661.7111406,3.5099966526031494,0.08402701344142383,1739137661.7111418,3.5099966526031494,6.255794350333622,1739137661.7111433,3.5099966526031494,2.2270258056858183 +1739137661.730914,3.529996633529663,4.98399002679426,1739137661.7309163,3.529996633529663,-0.13674516595526942,1739137661.730919,3.529996633529663,4.1487516964339965,1739137661.7309215,3.529996633529663,12.82393889793054,1739137661.7309225,3.529996633529663,-0.155,1739137661.7309244,3.529996633529663,-0.0023284336868278476,1739137661.7309256,3.529996633529663,0.19646886328553678,1739137661.730927,3.529996633529663,0.049092750401051044,1739137661.7309282,3.529996633529663,2.311052819127242,1739137661.7309296,3.529996633529663,0.0,1739137661.7309308,3.529996633529663,0.08402701344142383,1739137661.7309322,3.529996633529663,6.255794350333622,1739137661.7309334,3.529996633529663,2.2270258056858183 +1739137661.7509432,3.5499966144561768,4.98399002679426,1739137661.7509475,3.5499966144561768,-0.13674516595526942,1739137661.7509508,3.5499966144561768,4.1487516964339965,1739137661.7509542,3.5499966144561768,12.82393889793054,1739137661.7509558,3.5499966144561768,-0.155,1739137661.7509577,3.5499966144561768,-0.0023284336868278476,1739137661.7509594,3.5499966144561768,0.19646886328553678,1739137661.7509608,3.5499966144561768,0.049092750401051044,1739137661.7509625,3.5499966144561768,2.311052819127242,1739137661.7509642,3.5499966144561768,0.0,1739137661.7509658,3.5499966144561768,0.08402701344142383,1739137661.7509675,3.5499966144561768,6.255794350333622,1739137661.7509692,3.5499966144561768,2.2270258056858183 +1739137661.7709792,3.5699965953826904,4.98399002679426,1739137661.7709816,3.5699965953826904,-0.13674516595526942,1739137661.7709846,3.5699965953826904,4.1487516964339965,1739137661.7709875,3.5699965953826904,12.82393889793054,1739137661.770989,3.5699965953826904,-0.155,1739137661.770991,3.5699965953826904,-0.0023284336868278476,1739137661.7709928,3.5699965953826904,0.19646886328553678,1739137661.770994,3.5699965953826904,0.049092750401051044,1739137661.7709951,3.5699965953826904,2.311052819127242,1739137661.7709968,3.5699965953826904,0.0,1739137661.770998,3.5699965953826904,0.08402701344142383,1739137661.7709997,3.5699965953826904,6.255794350333622,1739137661.771001,3.5699965953826904,2.2270258056858183 +1739137661.791049,3.589996576309204,5.229310016499634,1739137661.791052,3.589996576309204,-0.1434142324422858,1739137661.791055,3.589996576309204,4.497576465029914,1739137661.7910576,3.589996576309204,13.199628198536209,1739137661.791059,3.589996576309204,-0.15707775223152343,1739137661.7910604,3.589996576309204,-0.001714298738431028,1739137661.791062,3.589996576309204,0.2009071645481186,1739137661.791063,3.589996576309204,0.048573130359955,1739137661.7910643,3.589996576309204,2.306953599460244,1739137661.791066,3.589996576309204,0.0,1739137661.7910671,3.589996576309204,0.05909975187164464,1739137661.791069,3.589996576309204,6.2562614563971435,1739137661.7910702,3.589996576309204,2.235983717101913 +1739137661.810988,3.6099965572357178,5.229310016499634,1739137661.8109908,3.6099965572357178,-0.1434142324422858,1739137661.810994,3.6099965572357178,4.497576465029914,1739137661.8109965,3.6099965572357178,13.199628198536209,1739137661.810998,3.6099965572357178,-0.15707775223152343,1739137661.8109996,3.6099965572357178,-0.001714298738431028,1739137661.811001,3.6099965572357178,0.2009071645481186,1739137661.8110023,3.6099965572357178,0.048573130359955,1739137661.8110037,3.6099965572357178,2.306953599460244,1739137661.811005,3.6099965572357178,0.0,1739137661.8110065,3.6099965572357178,0.07096988235833113,1739137661.8110082,3.6099965572357178,6.2562614563971435,1739137661.8110096,3.6099965572357178,2.235983717101913 +1739137661.8310034,3.6299965381622314,5.229310016499634,1739137661.831006,3.6299965381622314,-0.1434142324422858,1739137661.8310094,3.6299965381622314,4.497576465029914,1739137661.8310118,3.6299965381622314,13.199628198536209,1739137661.8310134,3.6299965381622314,-0.15707775223152343,1739137661.831015,3.6299965381622314,-0.001714298738431028,1739137661.8310168,3.6299965381622314,0.2009071645481186,1739137661.831018,3.6299965381622314,0.048573130359955,1739137661.8310192,3.6299965381622314,2.306953599460244,1739137661.8310208,3.6299965381622314,0.0,1739137661.8310223,3.6299965381622314,0.07096988235833113,1739137661.831024,3.6299965381622314,6.2562614563971435,1739137661.8310251,3.6299965381622314,2.235983717101913 +1739137661.8510149,3.649996519088745,5.229310016499634,1739137661.8510177,3.649996519088745,-0.1434142324422858,1739137661.8510206,3.649996519088745,4.497576465029914,1739137661.8510234,3.649996519088745,13.199628198536209,1739137661.8510246,3.649996519088745,-0.15707775223152343,1739137661.8510265,3.649996519088745,-0.001714298738431028,1739137661.8510277,3.649996519088745,0.2009071645481186,1739137661.8510292,3.649996519088745,0.048573130359955,1739137661.8510308,3.649996519088745,2.306953599460244,1739137661.8510323,3.649996519088745,0.0,1739137661.8510337,3.649996519088745,0.07096988235833113,1739137661.8510354,3.649996519088745,6.2562614563971435,1739137661.8510368,3.649996519088745,2.235983717101913 +1739137661.8709748,3.669996500015259,5.229310016499634,1739137661.8709776,3.669996500015259,-0.1434142324422858,1739137661.87098,3.669996500015259,4.497576465029914,1739137661.870983,3.669996500015259,13.199628198536209,1739137661.8709846,3.669996500015259,-0.15707775223152343,1739137661.8709865,3.669996500015259,-0.001714298738431028,1739137661.870988,3.669996500015259,0.2009071645481186,1739137661.8709893,3.669996500015259,0.048573130359955,1739137661.8709905,3.669996500015259,2.306953599460244,1739137661.8709922,3.669996500015259,0.0,1739137661.8709934,3.669996500015259,0.07096988235833113,1739137661.870995,3.669996500015259,6.2562614563971435,1739137661.8709965,3.669996500015259,2.235983717101913 +1739137661.8912194,3.6899964809417725,5.475561623925422,1739137661.891222,3.6899964809417725,-0.1499935222475255,1739137661.891225,3.6899964809417725,5.063175577013665,1739137661.891228,3.6899964809417725,13.788183698650503,1739137661.8912292,3.6899964809417725,-0.15958569644823453,1739137661.8912313,3.6899964809417725,-0.001153928310103962,1739137661.8912327,3.6899964809417725,0.21031044732618312,1739137661.8912342,3.6899964809417725,0.04674554872698729,1739137661.8912356,3.6899964809417725,2.298292722984519,1739137661.8912373,3.6899964809417725,0.0,1739137661.8912392,3.6899964809417725,0.0398209071300846,1739137661.8912404,3.6899964809417725,6.256728562460665,1739137661.891242,3.6899964809417725,2.2436389630979923 +1739137661.9109795,3.709996461868286,5.475561623925422,1739137661.9109824,3.709996461868286,-0.1499935222475255,1739137661.9109852,3.709996461868286,5.063175577013665,1739137661.910988,3.709996461868286,13.788183698650503,1739137661.9109893,3.709996461868286,-0.15958569644823453,1739137661.9109912,3.709996461868286,-0.001153928310103962,1739137661.9109924,3.709996461868286,0.21031044732618312,1739137661.9109938,3.709996461868286,0.04674554872698729,1739137661.9109952,3.709996461868286,2.298292722984519,1739137661.9109967,3.709996461868286,0.0,1739137661.910998,3.709996461868286,0.054653759886526654,1739137661.9109998,3.709996461868286,6.256728562460665,1739137661.9110012,3.709996461868286,2.2436389630979923 +1739137661.931059,3.7299964427948,5.475561623925422,1739137661.931062,3.7299964427948,-0.1499935222475255,1739137661.931065,3.7299964427948,5.063175577013665,1739137661.9310677,3.7299964427948,13.788183698650503,1739137661.931069,3.7299964427948,-0.15958569644823453,1739137661.9310708,3.7299964427948,-0.001153928310103962,1739137661.9310722,3.7299964427948,0.21031044732618312,1739137661.931074,3.7299964427948,0.04674554872698729,1739137661.931075,3.7299964427948,2.298292722984519,1739137661.9310765,3.7299964427948,0.0,1739137661.931078,3.7299964427948,0.054653759886526654,1739137661.9310794,3.7299964427948,6.256728562460665,1739137661.9310808,3.7299964427948,2.2436389630979923 +1739137661.951018,3.7499964237213135,5.475561623925422,1739137661.9510207,3.7499964237213135,-0.1499935222475255,1739137661.9510236,3.7499964237213135,5.063175577013665,1739137661.9510264,3.7499964237213135,13.788183698650503,1739137661.9510276,3.7499964237213135,-0.15958569644823453,1739137661.9510295,3.7499964237213135,-0.001153928310103962,1739137661.951031,3.7499964237213135,0.21031044732618312,1739137661.9510324,3.7499964237213135,0.04674554872698729,1739137661.9510336,3.7499964237213135,2.298292722984519,1739137661.9510357,3.7499964237213135,0.0,1739137661.951037,3.7499964237213135,0.054653759886526654,1739137661.9510384,3.7499964237213135,6.256728562460665,1739137661.9510398,3.7499964237213135,2.2436389630979923 +1739137661.9713695,3.769996404647827,5.475561623925422,1739137661.9713724,3.769996404647827,-0.1499935222475255,1739137661.971375,3.769996404647827,5.063175577013665,1739137661.9713778,3.769996404647827,13.788183698650503,1739137661.9713793,3.769996404647827,-0.15958569644823453,1739137661.971381,3.769996404647827,-0.001153928310103962,1739137661.9713826,3.769996404647827,0.21031044732618312,1739137661.9713838,3.769996404647827,0.04674554872698729,1739137661.971385,3.769996404647827,2.298292722984519,1739137661.9713867,3.769996404647827,0.0,1739137661.971388,3.769996404647827,0.054653759886526654,1739137661.9713895,3.769996404647827,6.256728562460665,1739137661.971391,3.769996404647827,2.2436389630979923 +1739137661.9910614,3.789996385574341,5.475561623925422,1739137661.9910643,3.789996385574341,-0.1499935222475255,1739137661.9910674,3.789996385574341,5.063175577013665,1739137661.99107,3.789996385574341,13.788183698650503,1739137661.9910712,3.789996385574341,-0.15958569644823453,1739137661.9910727,3.789996385574341,-0.001153928310103962,1739137661.9910743,3.789996385574341,0.21031044732618312,1739137661.9910755,3.789996385574341,0.04674554872698729,1739137661.991077,3.789996385574341,2.298292722984519,1739137661.9910784,3.789996385574341,0.0,1739137661.99108,3.789996385574341,0.054653759886526654,1739137661.9910815,3.789996385574341,6.256728562460665,1739137661.9910827,3.789996385574341,2.2436389630979923 +1739137662.0131204,3.8099963665008545,5.722548498165324,1739137662.0131252,3.8099963665008545,-0.15647701450296836,1739137662.0131304,3.8099963665008545,5.072567561727037,1739137662.0131364,3.8099963665008545,13.814643064568859,1739137662.0131397,3.8099963665008545,-0.15981985012892796,1739137662.0131443,3.8099963665008545,-0.00041309890886419493,1739137662.013148,3.8099963665008545,0.20694523172028598,1739137662.013152,3.8099963665008545,0.0485385466584592,1739137662.013156,3.8099963665008545,2.301388506328076,1739137662.01316,3.8099963665008545,0.0,1739137662.0131638,3.8099963665008545,0.04970216939914388,1739137662.0131679,3.8099963665008545,6.2571956685241865,1739137662.0131717,3.8099963665008545,2.2493284355189704 +1739137662.0337913,3.829996347427368,5.722548498165324,1739137662.0337954,3.829996347427368,-0.15647701450296836,1739137662.0338006,3.829996347427368,5.072567561727037,1739137662.0338068,3.829996347427368,13.814643064568859,1739137662.0338101,3.829996347427368,-0.15981985012892796,1739137662.0338142,3.829996347427368,-0.00041309890886419493,1739137662.033818,3.829996347427368,0.20694523172028598,1739137662.033822,3.829996347427368,0.0485385466584592,1739137662.0338259,3.829996347427368,2.301388506328076,1739137662.03383,3.829996347427368,0.0,1739137662.0338337,3.829996347427368,0.052060070809105685,1739137662.0338378,3.829996347427368,6.2571956685241865,1739137662.0338416,3.829996347427368,2.2493284355189704 +1739137662.0517604,3.849996328353882,5.722548498165324,1739137662.0517642,3.849996328353882,-0.15647701450296836,1739137662.0517683,3.849996328353882,5.072567561727037,1739137662.0517735,3.849996328353882,13.814643064568859,1739137662.0517762,3.849996328353882,-0.15981985012892796,1739137662.0517795,3.849996328353882,-0.00041309890886419493,1739137662.0517828,3.849996328353882,0.20694523172028598,1739137662.0517862,3.849996328353882,0.0485385466584592,1739137662.0517898,3.849996328353882,2.301388506328076,1739137662.051793,3.849996328353882,0.0,1739137662.0517964,3.849996328353882,0.052060070809105685,1739137662.0518,3.849996328353882,6.2571956685241865,1739137662.051803,3.849996328353882,2.2493284355189704 +1739137662.0730884,3.8699963092803955,5.722548498165324,1739137662.073092,3.8699963092803955,-0.15647701450296836,1739137662.0730968,3.8699963092803955,5.072567561727037,1739137662.0731015,3.8699963092803955,13.814643064568859,1739137662.0731046,3.8699963092803955,-0.15981985012892796,1739137662.0731082,3.8699963092803955,-0.00041309890886419493,1739137662.0731113,3.8699963092803955,0.20694523172028598,1739137662.0731146,3.8699963092803955,0.0485385466584592,1739137662.073118,3.8699963092803955,2.301388506328076,1739137662.0731213,3.8699963092803955,0.0,1739137662.0731246,3.8699963092803955,0.052060070809105685,1739137662.073128,3.8699963092803955,6.2571956685241865,1739137662.0731313,3.8699963092803955,2.2493284355189704 +1739137662.0910192,3.889996290206909,5.722548498165324,1739137662.0910218,3.889996290206909,-0.15647701450296836,1739137662.0910246,3.889996290206909,5.072567561727037,1739137662.091027,3.889996290206909,13.814643064568859,1739137662.0910287,3.889996290206909,-0.15981985012892796,1739137662.0910304,3.889996290206909,-0.00041309890886419493,1739137662.0910316,3.889996290206909,0.20694523172028598,1739137662.0910327,3.889996290206909,0.0485385466584592,1739137662.0910342,3.889996290206909,2.301388506328076,1739137662.0910354,3.889996290206909,0.0,1739137662.0910366,3.889996290206909,0.052060070809105685,1739137662.0910382,3.889996290206909,6.2571956685241865,1739137662.0910392,3.889996290206909,2.2493284355189704 +1739137662.1131217,3.909996271133423,5.9701758976709645,1739137662.1131258,3.909996271133423,-0.16286157478402608,1739137662.1131308,3.909996271133423,5.081983787468531,1739137662.1131363,3.909996271133423,13.841077614461593,1739137662.1131394,3.909996271133423,-0.16,1739137662.1131434,3.909996271133423,0.0003635637644721121,1739137662.113147,3.909996271133423,0.20372417968346948,1739137662.1131508,3.909996271133423,0.050506087156153755,1739137662.1131544,3.909996271133423,2.3043555741879453,1739137662.1131585,3.909996271133423,0.0,1739137662.113162,3.909996271133423,0.046894120848957874,1739137662.1131656,3.909996271133423,6.257662774587708,1739137662.1131694,3.909996271133423,2.2550014759386223 +1739137662.1328568,3.9299962520599365,5.9701758976709645,1739137662.132861,3.9299962520599365,-0.16286157478402608,1739137662.1328654,3.9299962520599365,5.081983787468531,1739137662.1328712,3.9299962520599365,13.841077614461593,1739137662.1328743,3.9299962520599365,-0.16,1739137662.132878,3.9299962520599365,0.0003635637644721121,1739137662.1328816,3.9299962520599365,0.20372417968346948,1739137662.1328852,3.9299962520599365,0.050506087156153755,1739137662.1328888,3.9299962520599365,2.3043555741879453,1739137662.1328926,3.9299962520599365,0.0,1739137662.1328962,3.9299962520599365,0.04935409824932302,1739137662.1329002,3.9299962520599365,6.257662774587708,1739137662.132904,3.9299962520599365,2.2550014759386223 +1739137662.1528459,3.94999623298645,5.9701758976709645,1739137662.1528494,3.94999623298645,-0.16286157478402608,1739137662.152854,3.94999623298645,5.081983787468531,1739137662.1528592,3.94999623298645,13.841077614461593,1739137662.1528618,3.94999623298645,-0.16,1739137662.152866,3.94999623298645,0.0003635637644721121,1739137662.1528692,3.94999623298645,0.20372417968346948,1739137662.1528726,3.94999623298645,0.050506087156153755,1739137662.1528754,3.94999623298645,2.3043555741879453,1739137662.152879,3.94999623298645,0.0,1739137662.152882,3.94999623298645,0.04935409824932302,1739137662.1528857,3.94999623298645,6.257662774587708,1739137662.1528888,3.94999623298645,2.2550014759386223 +1739137662.1730626,3.969996213912964,5.9701758976709645,1739137662.1730664,3.969996213912964,-0.16286157478402608,1739137662.1730711,3.969996213912964,5.081983787468531,1739137662.1730762,3.969996213912964,13.841077614461593,1739137662.1730788,3.969996213912964,-0.16,1739137662.1730824,3.969996213912964,0.0003635637644721121,1739137662.1730857,3.969996213912964,0.20372417968346948,1739137662.1730888,3.969996213912964,0.050506087156153755,1739137662.1730921,3.969996213912964,2.3043555741879453,1739137662.1730955,3.969996213912964,0.0,1739137662.1730988,3.969996213912964,0.04935409824932302,1739137662.1731024,3.969996213912964,6.257662774587708,1739137662.1731057,3.969996213912964,2.2550014759386223 +1739137662.1909494,3.9899961948394775,5.9701758976709645,1739137662.1909518,3.9899961948394775,-0.16286157478402608,1739137662.1909544,3.9899961948394775,5.081983787468531,1739137662.190957,3.9899961948394775,13.841077614461593,1739137662.1909583,3.9899961948394775,-0.16,1739137662.19096,3.9899961948394775,0.0003635637644721121,1739137662.1909611,3.9899961948394775,0.20372417968346948,1739137662.1909623,3.9899961948394775,0.050506087156153755,1739137662.190964,3.9899961948394775,2.3043555741879453,1739137662.1909654,3.9899961948394775,0.0,1739137662.1909668,3.9899961948394775,0.04935409824932302,1739137662.190968,3.9899961948394775,6.257662774587708,1739137662.1909697,3.9899961948394775,2.2550014759386223 +1739137662.212939,4.009996175765991,5.9701758976709645,1739137662.212942,4.009996175765991,-0.16286157478402608,1739137662.212945,4.009996175765991,5.081983787468531,1739137662.2129474,4.009996175765991,13.841077614461593,1739137662.212949,4.009996175765991,-0.16,1739137662.2129505,4.009996175765991,0.0003635637644721121,1739137662.2129521,4.009996175765991,0.20372417968346948,1739137662.2129533,4.009996175765991,0.050506087156153755,1739137662.2129545,4.009996175765991,2.3043555741879453,1739137662.2129564,4.009996175765991,0.0,1739137662.2129576,4.009996175765991,0.04935409824932302,1739137662.2129593,4.009996175765991,6.257662774587708,1739137662.2129605,4.009996175765991,2.2550014759386223 +1739137662.2311308,4.029996156692505,6.218412545416591,1739137662.2311337,4.029996156692505,-0.16914581603197565,1739137662.2311368,4.029996156692505,5.518811185955755,1739137662.2311394,4.029996156692505,14.293960281918187,1739137662.2311409,4.029996156692505,-0.162,1739137662.2311423,4.029996156692505,0.0008848705252063918,1739137662.231144,4.029996156692505,0.20945869656434746,1739137662.2311451,4.029996156692505,0.049329436146256095,1739137662.2311466,4.029996156692505,2.299075885419873,1739137662.231148,4.029996156692505,0.0,1739137662.2311492,4.029996156692505,0.029052563300206564,1739137662.2311509,4.029996156692505,6.2581298806512295,1739137662.231152,4.029996156692505,2.2603559196955594 +1739137662.2511716,4.0499961376190186,6.218412545416591,1739137662.2511747,4.0499961376190186,-0.16914581603197565,1739137662.2511775,4.0499961376190186,5.518811185955755,1739137662.2511802,4.0499961376190186,14.293960281918187,1739137662.2511818,4.0499961376190186,-0.162,1739137662.2511833,4.0499961376190186,0.0008848705252063918,1739137662.251185,4.0499961376190186,0.20945869656434746,1739137662.2511861,4.0499961376190186,0.049329436146256095,1739137662.2511876,4.0499961376190186,2.299075885419873,1739137662.2511892,4.0499961376190186,0.0,1739137662.2511904,4.0499961376190186,0.0387199657243138,1739137662.251192,4.0499961376190186,6.2581298806512295,1739137662.2511933,4.0499961376190186,2.2603559196955594 +1739137662.271058,4.069996118545532,6.218412545416591,1739137662.2710607,4.069996118545532,-0.16914581603197565,1739137662.2710636,4.069996118545532,5.518811185955755,1739137662.2710662,4.069996118545532,14.293960281918187,1739137662.2710676,4.069996118545532,-0.162,1739137662.2710698,4.069996118545532,0.0008848705252063918,1739137662.2710712,4.069996118545532,0.20945869656434746,1739137662.2710726,4.069996118545532,0.049329436146256095,1739137662.2710738,4.069996118545532,2.299075885419873,1739137662.2710752,4.069996118545532,0.0,1739137662.2710767,4.069996118545532,0.0387199657243138,1739137662.2710783,4.069996118545532,6.2581298806512295,1739137662.2710798,4.069996118545532,2.2603559196955594 +1739137662.2910504,4.089996099472046,6.218412545416591,1739137662.2910533,4.089996099472046,-0.16914581603197565,1739137662.2910562,4.089996099472046,5.518811185955755,1739137662.2910588,4.089996099472046,14.293960281918187,1739137662.2910602,4.089996099472046,-0.162,1739137662.2910619,4.089996099472046,0.0008848705252063918,1739137662.2910633,4.089996099472046,0.20945869656434746,1739137662.2910645,4.089996099472046,0.049329436146256095,1739137662.291066,4.089996099472046,2.299075885419873,1739137662.2910674,4.089996099472046,0.0,1739137662.2910686,4.089996099472046,0.0387199657243138,1739137662.2910702,4.089996099472046,6.2581298806512295,1739137662.2910717,4.089996099472046,2.2603559196955594 +1739137662.3112054,4.10999608039856,6.218412545416591,1739137662.31121,4.10999608039856,-0.16914581603197565,1739137662.3112135,4.10999608039856,5.518811185955755,1739137662.311217,4.10999608039856,14.293960281918187,1739137662.311219,4.10999608039856,-0.162,1739137662.311221,4.10999608039856,0.0008848705252063918,1739137662.3112228,4.10999608039856,0.20945869656434746,1739137662.3112242,4.10999608039856,0.049329436146256095,1739137662.311226,4.10999608039856,2.299075885419873,1739137662.3112283,4.10999608039856,0.0,1739137662.3112297,4.10999608039856,0.0387199657243138,1739137662.3112314,4.10999608039856,6.2581298806512295,1739137662.3112333,4.10999608039856,2.2603559196955594 +1739137662.3311317,4.129996061325073,6.467180965756313,1739137662.3311343,4.129996061325073,-0.17532725053765752,1739137662.3311372,4.129996061325073,5.717006169180005,1739137662.3311403,4.129996061325073,14.504597678068983,1739137662.3311417,4.129996061325073,-0.162,1739137662.3311434,4.129996061325073,0.0016581494776789392,1739137662.331145,4.129996061325073,0.21092988674912744,1739137662.3311465,4.129996061325073,0.05014812690616255,1739137662.3311474,4.129996061325073,2.2977233322808086,1739137662.3311493,4.129996061325073,0.0,1739137662.3311505,4.129996061325073,0.02821991491899098,1739137662.3311522,4.129996061325073,6.258596986714751,1739137662.3311534,4.129996061325073,2.264503390671075 +1739137662.3511145,4.149996042251587,6.467180965756313,1739137662.3511174,4.149996042251587,-0.17532725053765752,1739137662.3511202,4.149996042251587,5.717006169180005,1739137662.3511229,4.149996042251587,14.504597678068983,1739137662.3511243,4.149996042251587,-0.162,1739137662.351126,4.149996042251587,0.0016581494776789392,1739137662.3511274,4.149996042251587,0.21092988674912744,1739137662.3511286,4.149996042251587,0.05014812690616255,1739137662.35113,4.149996042251587,2.2977233322808086,1739137662.3511317,4.149996042251587,0.0,1739137662.3511329,4.149996042251587,0.03321994160973363,1739137662.3511345,4.149996042251587,6.258596986714751,1739137662.3511357,4.149996042251587,2.264503390671075 +1739137662.3714507,4.169996023178101,6.467180965756313,1739137662.3714535,4.169996023178101,-0.17532725053765752,1739137662.3714561,4.169996023178101,5.717006169180005,1739137662.3714588,4.169996023178101,14.504597678068983,1739137662.3714602,4.169996023178101,-0.162,1739137662.371462,4.169996023178101,0.0016581494776789392,1739137662.3714635,4.169996023178101,0.21092988674912744,1739137662.3714647,4.169996023178101,0.05014812690616255,1739137662.371466,4.169996023178101,2.2977233322808086,1739137662.3714676,4.169996023178101,0.0,1739137662.3714688,4.169996023178101,0.03321994160973363,1739137662.37147,4.169996023178101,6.258596986714751,1739137662.3714714,4.169996023178101,2.264503390671075 +1739137662.3909647,4.189996004104614,6.467180965756313,1739137662.3909676,4.189996004104614,-0.17532725053765752,1739137662.3909707,4.189996004104614,5.717006169180005,1739137662.390973,4.189996004104614,14.504597678068983,1739137662.3909745,4.189996004104614,-0.162,1739137662.3909762,4.189996004104614,0.0016581494776789392,1739137662.3909776,4.189996004104614,0.21092988674912744,1739137662.390979,4.189996004104614,0.05014812690616255,1739137662.3909802,4.189996004104614,2.2977233322808086,1739137662.390982,4.189996004104614,0.0,1739137662.390983,4.189996004104614,0.03321994160973363,1739137662.3909848,4.189996004104614,6.258596986714751,1739137662.3909864,4.189996004104614,2.264503390671075 +1739137662.4108086,4.209995985031128,6.467180965756313,1739137662.4108112,4.209995985031128,-0.17532725053765752,1739137662.410814,4.209995985031128,5.717006169180005,1739137662.4108167,4.209995985031128,14.504597678068983,1739137662.410818,4.209995985031128,-0.162,1739137662.4108198,4.209995985031128,0.0016581494776789392,1739137662.4108214,4.209995985031128,0.21092988674912744,1739137662.4108226,4.209995985031128,0.05014812690616255,1739137662.4108238,4.209995985031128,2.2977233322808086,1739137662.4108255,4.209995985031128,0.0,1739137662.4108267,4.209995985031128,0.03321994160973363,1739137662.4108284,4.209995985031128,6.258596986714751,1739137662.4108298,4.209995985031128,2.264503390671075 +1739137662.4308915,4.229995965957642,6.467180965756313,1739137662.4308946,4.229995965957642,-0.17532725053765752,1739137662.4308972,4.229995965957642,5.717006169180005,1739137662.4308996,4.229995965957642,14.504597678068983,1739137662.4309013,4.229995965957642,-0.162,1739137662.430903,4.229995965957642,0.0016581494776789392,1739137662.4309046,4.229995965957642,0.21092988674912744,1739137662.4309058,4.229995965957642,0.05014812690616255,1739137662.4309072,4.229995965957642,2.2977233322808086,1739137662.4309087,4.229995965957642,0.0,1739137662.43091,4.229995965957642,0.03321994160973363,1739137662.4309118,4.229995965957642,6.258596986714751,1739137662.4309132,4.229995965957642,2.264503390671075 +1739137662.4510891,4.249995946884155,6.716375011023906,1739137662.451092,4.249995946884155,-0.18140279269654958,1739137662.451095,4.249995946884155,5.97195760433794,1739137662.451098,4.249995946884155,14.770158653731661,1739137662.4510992,4.249995946884155,-0.163,1739137662.4511008,4.249995946884155,0.002284983243285541,1739137662.4511025,4.249995946884155,0.21264564332034638,1739137662.451104,4.249995946884155,0.05035061034582385,1739137662.4511054,4.249995946884155,2.296146939721381,1739137662.4511068,4.249995946884155,0.0,1739137662.451108,4.249995946884155,0.023456612231707953,1739137662.45111,4.249995946884155,6.259064092778273,1739137662.451111,4.249995946884155,2.2680411207014646 +1739137662.4709833,4.269995927810669,6.716375011023906,1739137662.470986,4.269995927810669,-0.18140279269654958,1739137662.4709892,4.269995927810669,5.97195760433794,1739137662.4709923,4.269995927810669,14.770158653731661,1739137662.4709938,4.269995927810669,-0.163,1739137662.4709954,4.269995927810669,0.002284983243285541,1739137662.4709966,4.269995927810669,0.21264564332034638,1739137662.470998,4.269995927810669,0.05035061034582385,1739137662.4709995,4.269995927810669,2.296146939721381,1739137662.4710011,4.269995927810669,0.0,1739137662.4710023,4.269995927810669,0.028105819019916378,1739137662.471004,4.269995927810669,6.259064092778273,1739137662.4710052,4.269995927810669,2.2680411207014646 +1739137662.490973,4.289995908737183,6.716375011023906,1739137662.4909754,4.289995908737183,-0.18140279269654958,1739137662.4909782,4.289995908737183,5.97195760433794,1739137662.4909809,4.289995908737183,14.770158653731661,1739137662.4909823,4.289995908737183,-0.163,1739137662.4909844,4.289995908737183,0.002284983243285541,1739137662.4909859,4.289995908737183,0.21264564332034638,1739137662.4909873,4.289995908737183,0.05035061034582385,1739137662.4909885,4.289995908737183,2.296146939721381,1739137662.4909906,4.289995908737183,0.0,1739137662.4909918,4.289995908737183,0.028105819019916378,1739137662.4909935,4.289995908737183,6.259064092778273,1739137662.4909947,4.289995908737183,2.2680411207014646 +1739137662.5108588,4.309995889663696,6.716375011023906,1739137662.5108616,4.309995889663696,-0.18140279269654958,1739137662.510864,4.309995889663696,5.97195760433794,1739137662.5108669,4.309995889663696,14.770158653731661,1739137662.5108683,4.309995889663696,-0.163,1739137662.5108697,4.309995889663696,0.002284983243285541,1739137662.5108714,4.309995889663696,0.21264564332034638,1739137662.5108726,4.309995889663696,0.05035061034582385,1739137662.510874,4.309995889663696,2.296146939721381,1739137662.5108757,4.309995889663696,0.0,1739137662.510877,4.309995889663696,0.028105819019916378,1739137662.5108788,4.309995889663696,6.259064092778273,1739137662.51088,4.309995889663696,2.2680411207014646 +1739137662.5309765,4.32999587059021,6.716375011023906,1739137662.5309794,4.32999587059021,-0.18140279269654958,1739137662.5309827,4.32999587059021,5.97195760433794,1739137662.5309854,4.32999587059021,14.770158653731661,1739137662.530987,4.32999587059021,-0.163,1739137662.5309887,4.32999587059021,0.002284983243285541,1739137662.5309906,4.32999587059021,0.21264564332034638,1739137662.5309918,4.32999587059021,0.05035061034582385,1739137662.5309932,4.32999587059021,2.296146939721381,1739137662.5309947,4.32999587059021,0.0,1739137662.530996,4.32999587059021,0.028105819019916378,1739137662.5309973,4.32999587059021,6.259064092778273,1739137662.530999,4.32999587059021,2.2680411207014646 +1739137662.551036,4.349995851516724,6.96593920718159,1739137662.5510385,4.349995851516724,-0.18737072091575957,1739137662.5510416,4.349995851516724,6.202422221193378,1739137662.5510445,4.349995851516724,15.009714983986836,1739137662.551046,4.349995851516724,-0.164,1739137662.5510476,4.349995851516724,0.0029054334435155435,1739137662.5510492,4.349995851516724,0.21361478417336158,1739137662.5510504,4.349995851516724,0.05070579378177105,1739137662.5510519,4.349995851516724,2.2952569963071054,1739137662.5510533,4.349995851516724,0.0,1739137662.5510545,4.349995851516724,0.02061843019191242,1739137662.5510561,4.349995851516724,6.259531198841794,1739137662.5510573,4.349995851516724,2.271073141082677 +1739137662.57083,4.369995832443237,6.96593920718159,1739137662.570833,4.369995832443237,-0.18737072091575957,1739137662.5708358,4.369995832443237,6.202422221193378,1739137662.5708385,4.369995832443237,15.009714983986836,1739137662.57084,4.369995832443237,-0.164,1739137662.5708416,4.369995832443237,0.0029054334435155435,1739137662.570843,4.369995832443237,0.21361478417336158,1739137662.5708444,4.369995832443237,0.05070579378177105,1739137662.5708456,4.369995832443237,2.2952569963071054,1739137662.5708473,4.369995832443237,0.0,1739137662.5708485,4.369995832443237,0.024183855224428452,1739137662.5708504,4.369995832443237,6.259531198841794,1739137662.5708518,4.369995832443237,2.271073141082677 +1739137662.5908673,4.389995813369751,6.96593920718159,1739137662.5908697,4.389995813369751,-0.18737072091575957,1739137662.590873,4.389995813369751,6.202422221193378,1739137662.5908759,4.389995813369751,15.009714983986836,1739137662.5908773,4.389995813369751,-0.164,1739137662.5908792,4.389995813369751,0.0029054334435155435,1739137662.5908804,4.389995813369751,0.21361478417336158,1739137662.590882,4.389995813369751,0.05070579378177105,1739137662.5908833,4.389995813369751,2.2952569963071054,1739137662.590885,4.389995813369751,0.0,1739137662.590886,4.389995813369751,0.024183855224428452,1739137662.5908878,4.389995813369751,6.259531198841794,1739137662.5908892,4.389995813369751,2.271073141082677 +1739137662.6109202,4.409995794296265,6.96593920718159,1739137662.610923,4.409995794296265,-0.18737072091575957,1739137662.610926,4.409995794296265,6.202422221193378,1739137662.610929,4.409995794296265,15.009714983986836,1739137662.6109302,4.409995794296265,-0.164,1739137662.6109316,4.409995794296265,0.0029054334435155435,1739137662.6109333,4.409995794296265,0.21361478417336158,1739137662.6109347,4.409995794296265,0.05070579378177105,1739137662.6109362,4.409995794296265,2.2952569963071054,1739137662.6109376,4.409995794296265,0.0,1739137662.6109388,4.409995794296265,0.024183855224428452,1739137662.6109402,4.409995794296265,6.259531198841794,1739137662.6109416,4.409995794296265,2.271073141082677 +1739137662.6309211,4.429995775222778,6.96593920718159,1739137662.6309237,4.429995775222778,-0.18737072091575957,1739137662.6309266,4.429995775222778,6.202422221193378,1739137662.6309292,4.429995775222778,15.009714983986836,1739137662.6309307,4.429995775222778,-0.164,1739137662.6309326,4.429995775222778,0.0029054334435155435,1739137662.630934,4.429995775222778,0.21361478417336158,1739137662.6309352,4.429995775222778,0.05070579378177105,1739137662.6309366,4.429995775222778,2.2952569963071054,1739137662.6309383,4.429995775222778,0.0,1739137662.6309397,4.429995775222778,0.024183855224428452,1739137662.6309412,4.429995775222778,6.259531198841794,1739137662.6309426,4.429995775222778,2.271073141082677 +1739137662.6508641,4.449995756149292,6.96593920718159,1739137662.650867,4.449995756149292,-0.18737072091575957,1739137662.6508698,4.449995756149292,6.202422221193378,1739137662.6508722,4.449995756149292,15.009714983986836,1739137662.6508737,4.449995756149292,-0.164,1739137662.6508753,4.449995756149292,0.0029054334435155435,1739137662.6508768,4.449995756149292,0.21361478417336158,1739137662.650878,4.449995756149292,0.05070579378177105,1739137662.6508799,4.449995756149292,2.2952569963071054,1739137662.6508813,4.449995756149292,0.0,1739137662.6508825,4.449995756149292,0.024183855224428452,1739137662.6508842,4.449995756149292,6.259531198841794,1739137662.6508853,4.449995756149292,2.271073141082677 +1739137662.6710458,4.469995737075806,7.21581446388954,1739137662.6710486,4.469995737075806,-0.19322930569075325,1739137662.6710517,4.469995737075806,6.403661948644935,1739137662.6710548,4.469995737075806,15.21868541580057,1739137662.671056,4.469995737075806,-0.164,1739137662.671058,4.469995737075806,0.0036523362550241337,1739137662.6710594,4.469995737075806,0.21476740851882306,1739137662.6710608,4.469995737075806,0.05150145570837081,1739137662.671062,4.469995737075806,2.294199012580193,1739137662.6710637,4.469995737075806,0.0,1739137662.6710649,4.469995737075806,0.017244525818483666,1739137662.6710663,4.469995737075806,6.259998304905315,1739137662.6710677,4.469995737075806,2.273650042536736 +1739137662.6908715,4.489995718002319,7.21581446388954,1739137662.6908739,4.489995718002319,-0.19322930569075325,1739137662.690877,4.489995718002319,6.403661948644935,1739137662.6908798,4.489995718002319,15.21868541580057,1739137662.690881,4.489995718002319,-0.164,1739137662.690883,4.489995718002319,0.0036523362550241337,1739137662.6908844,4.489995718002319,0.21476740851882306,1739137662.6908855,4.489995718002319,0.05150145570837081,1739137662.690887,4.489995718002319,2.294199012580193,1739137662.6908884,4.489995718002319,0.0,1739137662.6908898,4.489995718002319,0.02054897004345735,1739137662.6908913,4.489995718002319,6.259998304905315,1739137662.6908925,4.489995718002319,2.273650042536736 +1739137662.71106,4.509995698928833,7.21581446388954,1739137662.7110627,4.509995698928833,-0.19322930569075325,1739137662.7110655,4.509995698928833,6.403661948644935,1739137662.7110684,4.509995698928833,15.21868541580057,1739137662.7110696,4.509995698928833,-0.164,1739137662.7110717,4.509995698928833,0.0036523362550241337,1739137662.7110734,4.509995698928833,0.21476740851882306,1739137662.7110746,4.509995698928833,0.05150145570837081,1739137662.7110758,4.509995698928833,2.294199012580193,1739137662.7110775,4.509995698928833,0.0,1739137662.7110786,4.509995698928833,0.02054897004345735,1739137662.71108,4.509995698928833,6.259998304905315,1739137662.7110815,4.509995698928833,2.273650042536736 +1739137662.7309813,4.529995679855347,7.21581446388954,1739137662.730984,4.529995679855347,-0.19322930569075325,1739137662.7309868,4.529995679855347,6.403661948644935,1739137662.7309895,4.529995679855347,15.21868541580057,1739137662.730991,4.529995679855347,-0.164,1739137662.7309928,4.529995679855347,0.0036523362550241337,1739137662.7309942,4.529995679855347,0.21476740851882306,1739137662.7309957,4.529995679855347,0.05150145570837081,1739137662.730997,4.529995679855347,2.294199012580193,1739137662.7309988,4.529995679855347,0.0,1739137662.731,4.529995679855347,0.02054897004345735,1739137662.7310016,4.529995679855347,6.259998304905315,1739137662.731003,4.529995679855347,2.273650042536736 +1739137662.7508593,4.54999566078186,7.21581446388954,1739137662.750862,4.54999566078186,-0.19322930569075325,1739137662.7508647,4.54999566078186,6.403661948644935,1739137662.7508671,4.54999566078186,15.21868541580057,1739137662.7508688,4.54999566078186,-0.164,1739137662.7508705,4.54999566078186,0.0036523362550241337,1739137662.750872,4.54999566078186,0.21476740851882306,1739137662.750873,4.54999566078186,0.05150145570837081,1739137662.7508745,4.54999566078186,2.294199012580193,1739137662.7508762,4.54999566078186,0.0,1739137662.7508774,4.54999566078186,0.02054897004345735,1739137662.750879,4.54999566078186,6.259998304905315,1739137662.7508802,4.54999566078186,2.273650042536736 +1739137662.770944,4.569995641708374,7.465960545587583,1739137662.7709467,4.569995641708374,-0.19897127317325936,1739137662.7709498,4.569995641708374,6.939767874227795,1739137662.7709527,4.569995641708374,15.761441553699855,1739137662.770954,4.569995641708374,-0.165,1739137662.7709558,4.569995641708374,0.004095131221357746,1739137662.7709572,4.569995641708374,0.22186662191304898,1739137662.7709591,4.569995641708374,0.04951688485768703,1739137662.7709603,4.569995641708374,2.2876934504828927,1739137662.7709618,4.569995641708374,0.0,1739137662.770963,4.569995641708374,0.0038955798407283634,1739137662.7709644,4.569995641708374,6.260531993054258,1739137662.770966,4.569995641708374,2.275867680869865 +1739137662.7909374,4.589995622634888,7.465960545587583,1739137662.7909398,4.589995622634888,-0.19897127317325936,1739137662.7909427,4.589995622634888,6.939767874227795,1739137662.7909455,4.589995622634888,15.761441553699855,1739137662.7909467,4.589995622634888,-0.165,1739137662.7909486,4.589995622634888,0.004095131221357746,1739137662.7909498,4.589995622634888,0.22186662191304898,1739137662.7909515,4.589995622634888,0.04951688485768703,1739137662.790953,4.589995622634888,2.2876934504828927,1739137662.7909546,4.589995622634888,0.0,1739137662.7909558,4.589995622634888,0.011825769613027948,1739137662.7909572,4.589995622634888,6.260531993054258,1739137662.7909586,4.589995622634888,2.275867680869865 +1739137662.810868,4.609995603561401,7.465960545587583,1739137662.8108702,4.609995603561401,-0.19897127317325936,1739137662.8108733,4.609995603561401,6.939767874227795,1739137662.810876,4.609995603561401,15.761441553699855,1739137662.810877,4.609995603561401,-0.165,1739137662.810879,4.609995603561401,0.004095131221357746,1739137662.8108804,4.609995603561401,0.22186662191304898,1739137662.8108819,4.609995603561401,0.04951688485768703,1739137662.810883,4.609995603561401,2.2876934504828927,1739137662.8108847,4.609995603561401,0.0,1739137662.8108857,4.609995603561401,0.011825769613027948,1739137662.810887,4.609995603561401,6.260531993054258,1739137662.8108888,4.609995603561401,2.275867680869865 +1739137662.8309371,4.629995584487915,7.465960545587583,1739137662.8309395,4.629995584487915,-0.19897127317325936,1739137662.8309426,4.629995584487915,6.939767874227795,1739137662.8309455,4.629995584487915,15.761441553699855,1739137662.830947,4.629995584487915,-0.165,1739137662.8309488,4.629995584487915,0.004095131221357746,1739137662.8309503,4.629995584487915,0.22186662191304898,1739137662.8309517,4.629995584487915,0.04951688485768703,1739137662.830953,4.629995584487915,2.2876934504828927,1739137662.8309546,4.629995584487915,0.0,1739137662.8309557,4.629995584487915,0.011825769613027948,1739137662.8309574,4.629995584487915,6.260531993054258,1739137662.8309586,4.629995584487915,2.275867680869865 +1739137662.8508887,4.649995565414429,7.465960545587583,1739137662.8508916,4.649995565414429,-0.19897127317325936,1739137662.8508945,4.649995565414429,6.939767874227795,1739137662.850897,4.649995565414429,15.761441553699855,1739137662.8508985,4.649995565414429,-0.165,1739137662.8509004,4.649995565414429,0.004095131221357746,1739137662.8509018,4.649995565414429,0.22186662191304898,1739137662.8509033,4.649995565414429,0.04951688485768703,1739137662.8509045,4.649995565414429,2.2876934504828927,1739137662.850906,4.649995565414429,0.0,1739137662.8509073,4.649995565414429,0.011825769613027948,1739137662.8509095,4.649995565414429,6.260531993054258,1739137662.8509107,4.649995565414429,2.275867680869865 +1739137662.870886,4.669995546340942,7.465960545587583,1739137662.8708892,4.669995546340942,-0.19897127317325936,1739137662.870892,4.669995546340942,6.939767874227795,1739137662.870895,4.669995546340942,15.761441553699855,1739137662.870896,4.669995546340942,-0.165,1739137662.870898,4.669995546340942,0.004095131221357746,1739137662.8708994,4.669995546340942,0.22186662191304898,1739137662.8709006,4.669995546340942,0.04951688485768703,1739137662.870902,4.669995546340942,2.2876934504828927,1739137662.8709035,4.669995546340942,0.0,1739137662.870905,4.669995546340942,0.011825769613027948,1739137662.8709066,4.669995546340942,6.260531993054258,1739137662.870908,4.669995546340942,2.275867680869865 +1739137662.8909707,4.689995527267456,7.716292998056529,1739137662.8909733,4.689995527267456,-0.2045806548660387,1739137662.8909764,4.689995527267456,6.954793430757624,1739137662.8909793,4.689995527267456,15.77987951725852,1739137662.890981,4.689995527267456,-0.165,1739137662.8909824,4.689995527267456,0.004908527600038678,1739137662.8909838,4.689995527267456,0.21780067873055822,1739137662.8909853,4.689995527267456,0.05144473183010714,1739137662.8909864,4.689995527267456,2.291417130351703,1739137662.890988,4.689995527267456,0.0,1739137662.8909893,4.689995527267456,0.016763083495502606,1739137662.8909912,4.689995527267456,6.261080477222183,1739137662.8909922,4.689995527267456,2.2770051498794763 +1739137662.9110348,4.70999550819397,7.716292998056529,1739137662.9110374,4.70999550819397,-0.2045806548660387,1739137662.9110403,4.70999550819397,6.954793430757624,1739137662.9110432,4.70999550819397,15.77987951725852,1739137662.9110444,4.70999550819397,-0.165,1739137662.9110458,4.70999550819397,0.004908527600038678,1739137662.9110475,4.70999550819397,0.21780067873055822,1739137662.9110487,4.70999550819397,0.05144473183010714,1739137662.91105,4.70999550819397,2.291417130351703,1739137662.9110515,4.70999550819397,0.0,1739137662.9110527,4.70999550819397,0.014411980472226471,1739137662.9110544,4.70999550819397,6.261080477222183,1739137662.9110556,4.70999550819397,2.2770051498794763 +1739137662.9309337,4.729995489120483,7.716292998056529,1739137662.9309366,4.729995489120483,-0.2045806548660387,1739137662.9309394,4.729995489120483,6.954793430757624,1739137662.9309423,4.729995489120483,15.77987951725852,1739137662.9309435,4.729995489120483,-0.165,1739137662.9309454,4.729995489120483,0.004908527600038678,1739137662.9309468,4.729995489120483,0.21780067873055822,1739137662.9309478,4.729995489120483,0.05144473183010714,1739137662.9309492,4.729995489120483,2.291417130351703,1739137662.9309506,4.729995489120483,0.0,1739137662.9309518,4.729995489120483,0.014411980472226471,1739137662.9309535,4.729995489120483,6.261080477222183,1739137662.9309547,4.729995489120483,2.2770051498794763 +1739137662.9510171,4.749995470046997,7.716292998056529,1739137662.9510226,4.749995470046997,-0.2045806548660387,1739137662.9510262,4.749995470046997,6.954793430757624,1739137662.9510295,4.749995470046997,15.77987951725852,1739137662.951031,4.749995470046997,-0.165,1739137662.951033,4.749995470046997,0.004908527600038678,1739137662.9510348,4.749995470046997,0.21780067873055822,1739137662.9510367,4.749995470046997,0.05144473183010714,1739137662.9510384,4.749995470046997,2.291417130351703,1739137662.9510405,4.749995470046997,0.0,1739137662.9510424,4.749995470046997,0.014411980472226471,1739137662.9510446,4.749995470046997,6.261080477222183,1739137662.9510462,4.749995470046997,2.2770051498794763 +1739137662.9711616,4.769995450973511,7.716292998056529,1739137662.9711645,4.769995450973511,-0.2045806548660387,1739137662.9711673,4.769995450973511,6.954793430757624,1739137662.97117,4.769995450973511,15.77987951725852,1739137662.9711716,4.769995450973511,-0.165,1739137662.971173,4.769995450973511,0.004908527600038678,1739137662.9711747,4.769995450973511,0.21780067873055822,1739137662.9711761,4.769995450973511,0.05144473183010714,1739137662.9711776,4.769995450973511,2.291417130351703,1739137662.9711792,4.769995450973511,0.0,1739137662.971181,4.769995450973511,0.014411980472226471,1739137662.971182,4.769995450973511,6.261080477222183,1739137662.9711833,4.769995450973511,2.2770051498794763 +1739137662.991022,4.789995431900024,7.966784062780031,1739137662.991025,4.789995431900024,-0.21005613087343278,1739137662.9910276,4.789995431900024,7.284175420828751,1739137662.9910307,4.789995431900024,16.114054651843695,1739137662.9910321,4.789995431900024,-0.165,1739137662.9910338,4.789995431900024,0.005530155291700144,1739137662.9910352,4.789995431900024,0.2206574439161495,1739137662.9910367,4.789995431900024,0.05105406268781056,1739137662.9910378,4.789995431900024,2.288800209548649,1739137662.9910395,4.789995431900024,0.0,1739137662.9910407,4.789995431900024,0.006365854230734706,1739137662.9910426,4.789995431900024,6.261628961390109,1739137662.9910438,4.789995431900024,2.2786028647174925 +1739137663.0109265,4.809995412826538,7.966784062780031,1739137663.010929,4.809995412826538,-0.21005613087343278,1739137663.0109317,4.809995412826538,7.284175420828751,1739137663.0109346,4.809995412826538,16.114054651843695,1739137663.0109363,4.809995412826538,-0.165,1739137663.010938,4.809995412826538,0.005530155291700144,1739137663.0109394,4.809995412826538,0.2206574439161495,1739137663.0109408,4.809995412826538,0.05105406268781056,1739137663.010942,4.809995412826538,2.288800209548649,1739137663.0109434,4.809995412826538,0.0,1739137663.0109448,4.809995412826538,0.010197344831156308,1739137663.0109463,4.809995412826538,6.261628961390109,1739137663.0109475,4.809995412826538,2.2786028647174925 +1739137663.0311925,4.829995393753052,7.966784062780031,1739137663.0311954,4.829995393753052,-0.21005613087343278,1739137663.0311987,4.829995393753052,7.284175420828751,1739137663.0312018,4.829995393753052,16.114054651843695,1739137663.0312033,4.829995393753052,-0.165,1739137663.0312052,4.829995393753052,0.005530155291700144,1739137663.0312066,4.829995393753052,0.2206574439161495,1739137663.0312083,4.829995393753052,0.05105406268781056,1739137663.0312095,4.829995393753052,2.288800209548649,1739137663.0312114,4.829995393753052,0.0,1739137663.0312126,4.829995393753052,0.010197344831156308,1739137663.0312145,4.829995393753052,6.261628961390109,1739137663.0312161,4.829995393753052,2.2786028647174925 +1739137663.0528867,4.849995374679565,7.966784062780031,1739137663.052892,4.849995374679565,-0.21005613087343278,1739137663.0528984,4.849995374679565,7.284175420828751,1739137663.0529056,4.849995374679565,16.114054651843695,1739137663.0529099,4.849995374679565,-0.165,1739137663.052915,4.849995374679565,0.005530155291700144,1739137663.05292,4.849995374679565,0.2206574439161495,1739137663.0529249,4.849995374679565,0.05105406268781056,1739137663.0529284,4.849995374679565,2.288800209548649,1739137663.0529315,4.849995374679565,0.0,1739137663.0529344,4.849995374679565,0.010197344831156308,1739137663.0529375,4.849995374679565,6.261628961390109,1739137663.0529404,4.849995374679565,2.2786028647174925 +1739137663.0712745,4.869995355606079,7.966784062780031,1739137663.0712774,4.869995355606079,-0.21005613087343278,1739137663.0712805,4.869995355606079,7.284175420828751,1739137663.0712833,4.869995355606079,16.114054651843695,1739137663.071285,4.869995355606079,-0.165,1739137663.0712867,4.869995355606079,0.005530155291700144,1739137663.0712883,4.869995355606079,0.2206574439161495,1739137663.0712898,4.869995355606079,0.05105406268781056,1739137663.0712912,4.869995355606079,2.288800209548649,1739137663.0712929,4.869995355606079,0.0,1739137663.0712945,4.869995355606079,0.010197344831156308,1739137663.0712962,4.869995355606079,6.261628961390109,1739137663.071298,4.869995355606079,2.2786028647174925 +1739137663.0910838,4.889995336532593,7.966784062780031,1739137663.0910869,4.889995336532593,-0.21005613087343278,1739137663.0910902,4.889995336532593,7.284175420828751,1739137663.0910933,4.889995336532593,16.114054651843695,1739137663.091095,4.889995336532593,-0.165,1739137663.0910969,4.889995336532593,0.005530155291700144,1739137663.0910983,4.889995336532593,0.2206574439161495,1739137663.0911,4.889995336532593,0.05105406268781056,1739137663.0911014,4.889995336532593,2.288800209548649,1739137663.0911036,4.889995336532593,0.0,1739137663.0911055,4.889995336532593,0.010197344831156308,1739137663.0911076,4.889995336532593,6.261628961390109,1739137663.091109,4.889995336532593,2.2786028647174925 +1739137663.1111803,4.9099953174591064,8.2174221452223,1739137663.1111834,4.9099953174591064,-0.21539728821490556,1739137663.1111865,4.9099953174591064,7.491996158686494,1739137663.1111898,4.9099953174591064,16.3249966672948,1739137663.1111913,4.9099953174591064,-0.165,1739137663.1111934,4.9099953174591064,0.006215994559491621,1739137663.1111946,4.9099953174591064,0.22069644352165002,1739137663.111196,4.9099953174591064,0.05156382206339035,1739137663.1111977,4.9099953174591064,2.2887645049050462,1739137663.1111991,4.9099953174591064,0.0,1739137663.1112008,4.9099953174591064,0.008142912928248194,1739137663.1112022,4.9099953174591064,6.262177445558034,1739137663.1112037,4.9099953174591064,2.279643290581947 +1739137663.1313038,4.92999529838562,8.2174221452223,1739137663.1313066,4.92999529838562,-0.21539728821490556,1739137663.13131,4.92999529838562,7.491996158686494,1739137663.1313133,4.92999529838562,16.3249966672948,1739137663.1313148,4.92999529838562,-0.165,1739137663.1313167,4.92999529838562,0.006215994559491621,1739137663.1313183,4.92999529838562,0.22069644352165002,1739137663.1313198,4.92999529838562,0.05156382206339035,1739137663.1313214,4.92999529838562,2.2887645049050462,1739137663.1313229,4.92999529838562,0.0,1739137663.1313245,4.92999529838562,0.009121214323099203,1739137663.1313262,4.92999529838562,6.262177445558034,1739137663.1313276,4.92999529838562,2.279643290581947 +1739137663.1511497,4.949995279312134,8.2174221452223,1739137663.1511526,4.949995279312134,-0.21539728821490556,1739137663.151156,4.949995279312134,7.491996158686494,1739137663.151159,4.949995279312134,16.3249966672948,1739137663.1511602,4.949995279312134,-0.165,1739137663.1511624,4.949995279312134,0.006215994559491621,1739137663.1511638,4.949995279312134,0.22069644352165002,1739137663.1511657,4.949995279312134,0.05156382206339035,1739137663.1511672,4.949995279312134,2.2887645049050462,1739137663.151169,4.949995279312134,0.0,1739137663.1511705,4.949995279312134,0.009121214323099203,1739137663.1511726,4.949995279312134,6.262177445558034,1739137663.1511738,4.949995279312134,2.279643290581947 +1739137663.1710956,4.9699952602386475,8.2174221452223,1739137663.1710985,4.9699952602386475,-0.21539728821490556,1739137663.171102,4.9699952602386475,7.491996158686494,1739137663.1711054,4.9699952602386475,16.3249966672948,1739137663.1711068,4.9699952602386475,-0.165,1739137663.171109,4.9699952602386475,0.006215994559491621,1739137663.1711104,4.9699952602386475,0.22069644352165002,1739137663.1711118,4.9699952602386475,0.05156382206339035,1739137663.1711135,4.9699952602386475,2.2887645049050462,1739137663.1711152,4.9699952602386475,0.0,1739137663.1711168,4.9699952602386475,0.009121214323099203,1739137663.1711185,4.9699952602386475,6.262177445558034,1739137663.1711202,4.9699952602386475,2.279643290581947 +1739137663.190997,4.989995241165161,8.2174221452223,1739137663.191,4.989995241165161,-0.21539728821490556,1739137663.191003,4.989995241165161,7.491996158686494,1739137663.1910062,4.989995241165161,16.3249966672948,1739137663.1910079,4.989995241165161,-0.165,1739137663.1910098,4.989995241165161,0.006215994559491621,1739137663.1910114,4.989995241165161,0.22069644352165002,1739137663.1910126,4.989995241165161,0.05156382206339035,1739137663.191014,4.989995241165161,2.2887645049050462,1739137663.1910162,4.989995241165161,0.0,1739137663.1910174,4.989995241165161,0.009121214323099203,1739137663.1910193,4.989995241165161,6.262177445558034,1739137663.1910207,4.989995241165161,2.279643290581947 +1739137663.2111797,5.009995222091675,8.468178205323406,1739137663.2111826,5.009995222091675,-0.22060336349951637,1739137663.2111857,5.009995222091675,7.701551033616368,1739137663.2111886,5.009995222091675,16.53751799525449,1739137663.21119,5.009995222091675,-0.165,1739137663.211192,5.009995222091675,0.0068905864574997375,1739137663.2111933,5.009995222091675,0.22067387765883564,1739137663.211195,5.009995222091675,0.05204774736728601,1739137663.2111962,5.009995222091675,2.288785164176618,1739137663.211198,5.009995222091675,0.0,1739137663.2111995,5.009995222091675,0.00727291107412101,1739137663.2112012,5.009995222091675,6.262725929725959,1739137663.2112026,5.009995222091675,2.280632108258551 +1739137663.2310874,5.0299952030181885,8.468178205323406,1739137663.2310908,5.0299952030181885,-0.22060336349951637,1739137663.2310934,5.0299952030181885,7.701551033616368,1739137663.2310967,5.0299952030181885,16.53751799525449,1739137663.2310987,5.0299952030181885,-0.165,1739137663.2311006,5.0299952030181885,0.0068905864574997375,1739137663.2311022,5.0299952030181885,0.22067387765883564,1739137663.2311037,5.0299952030181885,0.05204774736728601,1739137663.2311053,5.0299952030181885,2.288785164176618,1739137663.2311068,5.0299952030181885,0.0,1739137663.2311084,5.0299952030181885,0.008153055918067142,1739137663.23111,5.0299952030181885,6.262725929725959,1739137663.2311115,5.0299952030181885,2.280632108258551 +1739137663.2510393,5.049995183944702,8.468178205323406,1739137663.2510424,5.049995183944702,-0.22060336349951637,1739137663.2510455,5.049995183944702,7.701551033616368,1739137663.2510486,5.049995183944702,16.53751799525449,1739137663.25105,5.049995183944702,-0.165,1739137663.2510521,5.049995183944702,0.0068905864574997375,1739137663.2510536,5.049995183944702,0.22067387765883564,1739137663.2510548,5.049995183944702,0.05204774736728601,1739137663.2510564,5.049995183944702,2.288785164176618,1739137663.251058,5.049995183944702,0.0,1739137663.2510598,5.049995183944702,0.008153055918067142,1739137663.2510617,5.049995183944702,6.262725929725959,1739137663.251063,5.049995183944702,2.280632108258551 +1739137663.2710783,5.069995164871216,8.468178205323406,1739137663.2710812,5.069995164871216,-0.22060336349951637,1739137663.2710845,5.069995164871216,7.701551033616368,1739137663.2710876,5.069995164871216,16.53751799525449,1739137663.2710888,5.069995164871216,-0.165,1739137663.2710907,5.069995164871216,0.0068905864574997375,1739137663.2710922,5.069995164871216,0.22067387765883564,1739137663.2710938,5.069995164871216,0.05204774736728601,1739137663.2710953,5.069995164871216,2.288785164176618,1739137663.271097,5.069995164871216,0.0,1739137663.2710984,5.069995164871216,0.008153055918067142,1739137663.2711,5.069995164871216,6.262725929725959,1739137663.2711017,5.069995164871216,2.280632108258551 +1739137663.2917597,5.0899951457977295,8.468178205323406,1739137663.2917638,5.0899951457977295,-0.22060336349951637,1739137663.2917688,5.0899951457977295,7.701551033616368,1739137663.2917747,5.0899951457977295,16.53751799525449,1739137663.2917778,5.0899951457977295,-0.165,1739137663.2917821,5.0899951457977295,0.0068905864574997375,1739137663.291786,5.0899951457977295,0.22067387765883564,1739137663.2917898,5.0899951457977295,0.05204774736728601,1739137663.2917936,5.0899951457977295,2.288785164176618,1739137663.2917974,5.0899951457977295,0.0,1739137663.2918015,5.0899951457977295,0.008153055918067142,1739137663.2918055,5.0899951457977295,6.262725929725959,1739137663.2918093,5.0899951457977295,2.280632108258551 +1739137663.313147,5.109995126724243,8.468178205323406,1739137663.3131518,5.109995126724243,-0.22060336349951637,1739137663.3131576,5.109995126724243,7.701551033616368,1739137663.3131642,5.109995126724243,16.53751799525449,1739137663.3131678,5.109995126724243,-0.165,1739137663.3131726,5.109995126724243,0.0068905864574997375,1739137663.3131769,5.109995126724243,0.22067387765883564,1739137663.313181,5.109995126724243,0.05204774736728601,1739137663.3131852,5.109995126724243,2.288785164176618,1739137663.3131893,5.109995126724243,0.0,1739137663.3131938,5.109995126724243,0.008153055918067142,1739137663.313198,5.109995126724243,6.262725929725959,1739137663.3132024,5.109995126724243,2.280632108258551 +1739137663.3321526,5.129995107650757,8.719039541677391,1739137663.3321579,5.129995107650757,-0.22567397376616505,1739137663.332164,5.129995107650757,8.097865513982033,1739137663.3321707,5.129995107650757,16.93645782688081,1739137663.3321745,5.129995107650757,-0.165,1739137663.3321795,5.129995107650757,0.007383446856826888,1739137663.3321838,5.129995107650757,0.224267275268204,1739137663.3321884,5.129995107650757,0.0510059462133773,1739137663.3321927,5.129995107650757,2.2854977213055525,1739137663.3321974,5.129995107650757,0.0,1739137663.3322017,5.129995107650757,0.00020634693495024444,1739137663.3322062,5.129995107650757,6.2632744138938845,1739137663.3322113,5.129995107650757,2.281507225345437 +1739137663.3531363,5.1499950885772705,8.719039541677391,1739137663.353141,5.1499950885772705,-0.22567397376616505,1739137663.3531466,5.1499950885772705,8.097865513982033,1739137663.353153,5.1499950885772705,16.93645782688081,1739137663.353157,5.1499950885772705,-0.165,1739137663.3531618,5.1499950885772705,0.007383446856826888,1739137663.353166,5.1499950885772705,0.224267275268204,1739137663.3531702,5.1499950885772705,0.0510059462133773,1739137663.3531742,5.1499950885772705,2.2854977213055525,1739137663.3531787,5.1499950885772705,0.0,1739137663.353183,5.1499950885772705,0.003990495960115581,1739137663.3531873,5.1499950885772705,6.2632744138938845,1739137663.3531914,5.1499950885772705,2.281507225345437 +1739137663.3730066,5.169995069503784,8.719039541677391,1739137663.3730102,5.169995069503784,-0.22567397376616505,1739137663.3730145,5.169995069503784,8.097865513982033,1739137663.3730195,5.169995069503784,16.93645782688081,1739137663.3730223,5.169995069503784,-0.165,1739137663.3730261,5.169995069503784,0.007383446856826888,1739137663.3730295,5.169995069503784,0.224267275268204,1739137663.3730323,5.169995069503784,0.0510059462133773,1739137663.3730354,5.169995069503784,2.2854977213055525,1739137663.3730388,5.169995069503784,0.0,1739137663.373042,5.169995069503784,0.003990495960115581,1739137663.3730454,5.169995069503784,6.2632744138938845,1739137663.3730485,5.169995069503784,2.281507225345437 +1739137663.3989084,5.189995050430298,8.719039541677391,1739137663.3989153,5.189995050430298,-0.22567397376616505,1739137663.3989246,5.189995050430298,8.097865513982033,1739137663.398935,5.189995050430298,16.93645782688081,1739137663.398941,5.189995050430298,-0.165,1739137663.3989484,5.189995050430298,0.007383446856826888,1739137663.398955,5.189995050430298,0.224267275268204,1739137663.3989618,5.189995050430298,0.0510059462133773,1739137663.3989682,5.189995050430298,2.2854977213055525,1739137663.3989758,5.189995050430298,0.0,1739137663.3989823,5.189995050430298,0.003990495960115581,1739137663.3989892,5.189995050430298,6.2632744138938845,1739137663.3989956,5.189995050430298,2.281507225345437 +1739137663.413103,5.2099950313568115,8.719039541677391,1739137663.4131072,5.2099950313568115,-0.22567397376616505,1739137663.4131124,5.2099950313568115,8.097865513982033,1739137663.4131181,5.2099950313568115,16.93645782688081,1739137663.4131217,5.2099950313568115,-0.165,1739137663.4131262,5.2099950313568115,0.007383446856826888,1739137663.4131305,5.2099950313568115,0.224267275268204,1739137663.4131343,5.2099950313568115,0.0510059462133773,1739137663.4131382,5.2099950313568115,2.2854977213055525,1739137663.4131424,5.2099950313568115,0.0,1739137663.4131463,5.2099950313568115,0.003990495960115581,1739137663.4131508,5.2099950313568115,6.2632744138938845,1739137663.4131546,5.2099950313568115,2.281507225345437 +1739137663.4327753,5.229995012283325,8.969976358576414,1739137663.4327786,5.229995012283325,-0.23060842262357273,1739137663.432783,5.229995012283325,8.123716940571489,1739137663.4327877,5.229995012283325,16.963515829671948,1739137663.4327905,5.229995012283325,-0.165,1739137663.4327943,5.229995012283325,0.008207496774204577,1739137663.4327974,5.229995012283325,0.22036063545275122,1739137663.432801,5.229995012283325,0.05296300347943337,1739137663.432804,5.229995012283325,2.2890719597891724,1739137663.4328074,5.229995012283325,0.0,1739137663.4328108,5.229995012283325,0.010046223686959744,1739137663.4328141,5.229995012283325,6.26382289806181,1739137663.4328175,5.229995012283325,2.2819094174126633 +1739137663.4525793,5.249994993209839,8.969976358576414,1739137663.452583,5.249994993209839,-0.23060842262357273,1739137663.4525878,5.249994993209839,8.123716940571489,1739137663.452593,5.249994993209839,16.963515829671948,1739137663.4525962,5.249994993209839,-0.165,1739137663.4526,5.249994993209839,0.008207496774204577,1739137663.4526033,5.249994993209839,0.22036063545275122,1739137663.4526067,5.249994993209839,0.05296300347943337,1739137663.45261,5.249994993209839,2.2890719597891724,1739137663.4526138,5.249994993209839,0.0,1739137663.4526172,5.249994993209839,0.007162542376509151,1739137663.452621,5.249994993209839,6.26382289806181,1739137663.4526246,5.249994993209839,2.2819094174126633 +1739137663.4730117,5.2699949741363525,8.969976358576414,1739137663.473015,5.2699949741363525,-0.23060842262357273,1739137663.4730198,5.2699949741363525,8.123716940571489,1739137663.4730248,5.2699949741363525,16.963515829671948,1739137663.4730272,5.2699949741363525,-0.165,1739137663.4730308,5.2699949741363525,0.008207496774204577,1739137663.4730341,5.2699949741363525,0.22036063545275122,1739137663.4730372,5.2699949741363525,0.05296300347943337,1739137663.4730403,5.2699949741363525,2.2890719597891724,1739137663.4730437,5.2699949741363525,0.0,1739137663.473047,5.2699949741363525,0.007162542376509151,1739137663.47305,5.2699949741363525,6.26382289806181,1739137663.4730535,5.2699949741363525,2.2819094174126633 +1739137663.4928703,5.289994955062866,8.969976358576414,1739137663.4928741,5.289994955062866,-0.23060842262357273,1739137663.4928787,5.289994955062866,8.123716940571489,1739137663.492884,5.289994955062866,16.963515829671948,1739137663.492887,5.289994955062866,-0.165,1739137663.4928906,5.289994955062866,0.008207496774204577,1739137663.4928937,5.289994955062866,0.22036063545275122,1739137663.492897,5.289994955062866,0.05296300347943337,1739137663.4929004,5.289994955062866,2.2890719597891724,1739137663.4929037,5.289994955062866,0.0,1739137663.492907,5.289994955062866,0.007162542376509151,1739137663.4929104,5.289994955062866,6.26382289806181,1739137663.4929137,5.289994955062866,2.2819094174126633 +1739137663.5125296,5.30999493598938,8.969976358576414,1739137663.5125332,5.30999493598938,-0.23060842262357273,1739137663.512538,5.30999493598938,8.123716940571489,1739137663.5125432,5.30999493598938,16.963515829671948,1739137663.5125463,5.30999493598938,-0.165,1739137663.5125499,5.30999493598938,0.008207496774204577,1739137663.5125535,5.30999493598938,0.22036063545275122,1739137663.5125568,5.30999493598938,0.05296300347943337,1739137663.5125601,5.30999493598938,2.2890719597891724,1739137663.5125637,5.30999493598938,0.0,1739137663.512567,5.30999493598938,0.007162542376509151,1739137663.5125704,5.30999493598938,6.26382289806181,1739137663.5125737,5.30999493598938,2.2819094174126633 +1739137663.5328112,5.3299949169158936,8.969976358576414,1739137663.5328152,5.3299949169158936,-0.23060842262357273,1739137663.5328195,5.3299949169158936,8.123716940571489,1739137663.5328248,5.3299949169158936,16.963515829671948,1739137663.5328276,5.3299949169158936,-0.165,1739137663.5328312,5.3299949169158936,0.008207496774204577,1739137663.5328345,5.3299949169158936,0.22036063545275122,1739137663.5328379,5.3299949169158936,0.05296300347943337,1739137663.5328412,5.3299949169158936,2.2890719597891724,1739137663.5328445,5.3299949169158936,0.0,1739137663.532848,5.3299949169158936,0.007162542376509151,1739137663.5328512,5.3299949169158936,6.26382289806181,1739137663.5328546,5.3299949169158936,2.2819094174126633 +1739137663.558866,5.349994897842407,9.220985418540275,1739137663.5588746,5.349994897842407,-0.23539895664772015,1739137663.558886,5.349994897842407,8.431221489373417,1739137663.5588999,5.349994897842407,17.273541181401548,1739137663.5589075,5.349994897842407,-0.16428116654284414,1739137663.5589173,5.349994897842407,0.008831474533911724,1739137663.558926,5.349994897842407,0.22200037982725093,1739137663.5589345,5.349994897842407,0.05257740046416137,1739137663.5589433,5.349994897842407,2.287571054915489,1739137663.558952,5.349994897842407,0.0,1739137663.5589607,5.349994897842407,0.0026911071978618284,1739137663.55897,5.349994897842407,6.264445429579573,1739137663.5589783,5.349994897842407,2.2827506918069957 +1739137663.5743763,5.369994878768921,9.220985418540275,1739137663.574381,5.369994878768921,-0.23539895664772015,1739137663.5743868,5.369994878768921,8.431221489373417,1739137663.5743942,5.369994878768921,17.273541181401548,1739137663.574398,5.369994878768921,-0.16428116654284414,1739137663.574403,5.369994878768921,0.008831474533911724,1739137663.5744073,5.369994878768921,0.22200037982725093,1739137663.574412,5.369994878768921,0.05257740046416137,1739137663.5744166,5.369994878768921,2.287571054915489,1739137663.5744212,5.369994878768921,0.0,1739137663.574426,5.369994878768921,0.004820363108493098,1739137663.5744305,5.369994878768921,6.264445429579573,1739137663.574435,5.369994878768921,2.2827506918069957 +1739137663.59344,5.389994859695435,9.220985418540275,1739137663.5934439,5.389994859695435,-0.23539895664772015,1739137663.5934484,5.389994859695435,8.431221489373417,1739137663.593454,5.389994859695435,17.273541181401548,1739137663.5934567,5.389994859695435,-0.16428116654284414,1739137663.5934603,5.389994859695435,0.008831474533911724,1739137663.5934637,5.389994859695435,0.22200037982725093,1739137663.593467,5.389994859695435,0.05257740046416137,1739137663.59347,5.389994859695435,2.287571054915489,1739137663.5934734,5.389994859695435,0.0,1739137663.593477,5.389994859695435,0.004820363108493098,1739137663.5934806,5.389994859695435,6.264445429579573,1739137663.5934844,5.389994859695435,2.2827506918069957 +1739137663.6132455,5.409994840621948,9.220985418540275,1739137663.613249,5.409994840621948,-0.23539895664772015,1739137663.6132536,5.409994840621948,8.431221489373417,1739137663.613259,5.409994840621948,17.273541181401548,1739137663.613262,5.409994840621948,-0.16428116654284414,1739137663.6132655,5.409994840621948,0.008831474533911724,1739137663.6132689,5.409994840621948,0.22200037982725093,1739137663.6132717,5.409994840621948,0.05257740046416137,1739137663.613275,5.409994840621948,2.287571054915489,1739137663.6132784,5.409994840621948,0.0,1739137663.6132817,5.409994840621948,0.004820363108493098,1739137663.613285,5.409994840621948,6.264445429579573,1739137663.6132884,5.409994840621948,2.2827506918069957 +1739137663.6333752,5.429994821548462,9.220985418540275,1739137663.6333787,5.429994821548462,-0.23539895664772015,1739137663.6333833,5.429994821548462,8.431221489373417,1739137663.6333883,5.429994821548462,17.273541181401548,1739137663.6333911,5.429994821548462,-0.16428116654284414,1739137663.6333947,5.429994821548462,0.008831474533911724,1739137663.633398,5.429994821548462,0.22200037982725093,1739137663.6334014,5.429994821548462,0.05257740046416137,1739137663.633405,5.429994821548462,2.287571054915489,1739137663.6334083,5.429994821548462,0.0,1739137663.6334116,5.429994821548462,0.004820363108493098,1739137663.633415,5.429994821548462,6.264445429579573,1739137663.6334183,5.429994821548462,2.2827506918069957 +1739137663.6529548,5.449994802474976,9.472068828507563,1739137663.6529582,5.449994802474976,-0.2400328584829161,1739137663.6529622,5.449994802474976,8.741237711947111,1739137663.6529675,5.449994802474976,17.58501638965651,1739137663.6529703,5.449994802474976,-0.164,1739137663.652974,5.449994802474976,0.009371517814717768,1739137663.6529772,5.449994802474976,0.22293736402883732,1739137663.6529803,5.449994802474976,0.05201577503757443,1739137663.6529837,5.449994802474976,2.2867138483879335,1739137663.6529868,5.449994802474976,0.0,1739137663.65299,5.449994802474976,0.002254679551905764,1739137663.6529934,5.449994802474976,6.26507536583232,1739137663.6529968,5.449994802474976,2.2832374141511425 +1739137663.673166,5.469994783401489,9.472068828507563,1739137663.673171,5.469994783401489,-0.2400328584829161,1739137663.673176,5.469994783401489,8.741237711947111,1739137663.673182,5.469994783401489,17.58501638965651,1739137663.6731853,5.469994783401489,-0.164,1739137663.6731896,5.469994783401489,0.009371517814717768,1739137663.6731932,5.469994783401489,0.22293736402883732,1739137663.673197,5.469994783401489,0.05201577503757443,1739137663.6732008,5.469994783401489,2.2867138483879335,1739137663.6732044,5.469994783401489,0.0,1739137663.6732082,5.469994783401489,0.003476434236791004,1739137663.673212,5.469994783401489,6.26507536583232,1739137663.673216,5.469994783401489,2.2832374141511425 +1739137663.6922896,5.489994764328003,9.472068828507563,1739137663.6922932,5.489994764328003,-0.2400328584829161,1739137663.6922977,5.489994764328003,8.741237711947111,1739137663.6923027,5.489994764328003,17.58501638965651,1739137663.6923053,5.489994764328003,-0.164,1739137663.692309,5.489994764328003,0.009371517814717768,1739137663.692312,5.489994764328003,0.22293736402883732,1739137663.6923153,5.489994764328003,0.05201577503757443,1739137663.6923187,5.489994764328003,2.2867138483879335,1739137663.692322,5.489994764328003,0.0,1739137663.692325,5.489994764328003,0.003476434236791004,1739137663.6923287,5.489994764328003,6.26507536583232,1739137663.6923318,5.489994764328003,2.2832374141511425 +1739137663.7132823,5.509994745254517,9.472068828507563,1739137663.713286,5.509994745254517,-0.2400328584829161,1739137663.7132905,5.509994745254517,8.741237711947111,1739137663.7132957,5.509994745254517,17.58501638965651,1739137663.7132983,5.509994745254517,-0.164,1739137663.713302,5.509994745254517,0.009371517814717768,1739137663.7133052,5.509994745254517,0.22293736402883732,1739137663.7133086,5.509994745254517,0.05201577503757443,1739137663.7133117,5.509994745254517,2.2867138483879335,1739137663.7133152,5.509994745254517,0.0,1739137663.7133183,5.509994745254517,0.003476434236791004,1739137663.713322,5.509994745254517,6.26507536583232,1739137663.713325,5.509994745254517,2.2832374141511425 +1739137663.7324657,5.52999472618103,9.472068828507563,1739137663.732469,5.52999472618103,-0.2400328584829161,1739137663.7324736,5.52999472618103,8.741237711947111,1739137663.7324786,5.52999472618103,17.58501638965651,1739137663.7324815,5.52999472618103,-0.164,1739137663.732485,5.52999472618103,0.009371517814717768,1739137663.7324882,5.52999472618103,0.22293736402883732,1739137663.7324915,5.52999472618103,0.05201577503757443,1739137663.7324946,5.52999472618103,2.2867138483879335,1739137663.732498,5.52999472618103,0.0,1739137663.7325013,5.52999472618103,0.003476434236791004,1739137663.7325046,5.52999472618103,6.26507536583232,1739137663.7325077,5.52999472618103,2.2832374141511425 +1739137663.7521937,5.549994707107544,9.472068828507563,1739137663.7521973,5.549994707107544,-0.2400328584829161,1739137663.7522018,5.549994707107544,8.741237711947111,1739137663.7522066,5.549994707107544,17.58501638965651,1739137663.7522094,5.549994707107544,-0.164,1739137663.752213,5.549994707107544,0.009371517814717768,1739137663.752216,5.549994707107544,0.22293736402883732,1739137663.7522194,5.549994707107544,0.05201577503757443,1739137663.7522225,5.549994707107544,2.2867138483879335,1739137663.7522259,5.549994707107544,0.0,1739137663.7522292,5.549994707107544,0.003476434236791004,1739137663.7522328,5.549994707107544,6.26507536583232,1739137663.752236,5.549994707107544,2.2832374141511425 +1739137663.772555,5.569994688034058,9.723201798349523,1739137663.7725585,5.569994688034058,-0.24450942572956702,1739137663.7725627,5.569994688034058,9.149360806141146,1739137663.7725677,5.569994688034058,17.99418597558166,1739137663.7725704,5.569994688034058,-0.1603601956895582,1739137663.772574,5.569994688034058,0.01017367763789466,1739137663.7725773,5.569994688034058,0.2287058575217949,1739137663.7725804,5.569994688034058,0.051341289202560786,1739137663.7725837,5.569994688034058,2.281443573453675,1739137663.7725868,5.569994688034058,0.0,1739137663.7725904,5.569994688034058,-0.007265347130816223,1739137663.7725937,5.569994688034058,6.265705302085068,1739137663.7725968,5.569994688034058,2.2835937840446823 +1739137663.7923262,5.589994668960571,9.723201798349523,1739137663.79233,5.589994668960571,-0.24450942572956702,1739137663.7923346,5.589994668960571,9.149360806141146,1739137663.7923398,5.589994668960571,17.99418597558166,1739137663.7923424,5.589994668960571,-0.1603601956895582,1739137663.792346,5.589994668960571,0.01017367763789466,1739137663.792349,5.589994668960571,0.2287058575217949,1739137663.7923524,5.589994668960571,0.051341289202560786,1739137663.7923555,5.589994668960571,2.281443573453675,1739137663.792359,5.589994668960571,0.0,1739137663.7923622,5.589994668960571,-0.0021502105910071734,1739137663.792366,5.589994668960571,6.265705302085068,1739137663.7923691,5.589994668960571,2.2835937840446823 +1739137663.8127213,5.609994649887085,9.723201798349523,1739137663.812725,5.609994649887085,-0.24450942572956702,1739137663.8127477,5.609994649887085,9.149360806141146,1739137663.8127534,5.609994649887085,17.99418597558166,1739137663.8127563,5.609994649887085,-0.1603601956895582,1739137663.8127756,5.609994649887085,0.01017367763789466,1739137663.812779,5.609994649887085,0.2287058575217949,1739137663.8127823,5.609994649887085,0.051341289202560786,1739137663.8127856,5.609994649887085,2.281443573453675,1739137663.812789,5.609994649887085,0.0,1739137663.8127923,5.609994649887085,-0.0021502105910071734,1739137663.8127956,5.609994649887085,6.265705302085068,1739137663.812799,5.609994649887085,2.2835937840446823 +1739137663.8324552,5.629994630813599,9.723201798349523,1739137663.8324587,5.629994630813599,-0.24450942572956702,1739137663.832463,5.629994630813599,9.149360806141146,1739137663.8324683,5.629994630813599,17.99418597558166,1739137663.8324711,5.629994630813599,-0.1603601956895582,1739137663.8324752,5.629994630813599,0.01017367763789466,1739137663.8324785,5.629994630813599,0.2287058575217949,1739137663.8324816,5.629994630813599,0.051341289202560786,1739137663.832485,5.629994630813599,2.281443573453675,1739137663.8324885,5.629994630813599,0.0,1739137663.8324919,5.629994630813599,-0.0021502105910071734,1739137663.8324952,5.629994630813599,6.265705302085068,1739137663.8324988,5.629994630813599,2.2835937840446823 +1739137663.852888,5.649994611740112,9.723201798349523,1739137663.8528917,5.649994611740112,-0.24450942572956702,1739137663.8528962,5.649994611740112,9.149360806141146,1739137663.8529015,5.649994611740112,17.99418597558166,1739137663.852904,5.649994611740112,-0.1603601956895582,1739137663.8529081,5.649994611740112,0.01017367763789466,1739137663.8529115,5.649994611740112,0.2287058575217949,1739137663.8529146,5.649994611740112,0.051341289202560786,1739137663.852918,5.649994611740112,2.281443573453675,1739137663.8529212,5.649994611740112,0.0,1739137663.8529246,5.649994611740112,-0.0021502105910071734,1739137663.8529282,5.649994611740112,6.265705302085068,1739137663.8529317,5.649994611740112,2.2835937840446823 +1739137663.8724551,5.669994592666626,9.974345095868738,1739137663.8724587,5.669994592666626,-0.24882792817775634,1739137663.8724635,5.669994592666626,9.17623745747815,1739137663.8724685,5.669994592666626,18.020215656019285,1739137663.8724713,5.669994592666626,-0.15999640573301194,1739137663.872475,5.669994592666626,0.011040186721031164,1739137663.8724782,5.669994592666626,0.22438596948205367,1739137663.8724816,5.669994592666626,0.0532282660486858,1739137663.872485,5.669994592666626,2.285389213739303,1739137663.8724883,5.669994592666626,0.0,1739137663.8724916,5.669994592666626,0.00591974239623545,1739137663.8724952,5.669994592666626,6.266335238337815,1739137663.8724985,5.669994592666626,2.283312308018562 +1739137663.8931317,5.68999457359314,9.974345095868738,1739137663.8931355,5.68999457359314,-0.24882792817775634,1739137663.8931403,5.68999457359314,9.17623745747815,1739137663.8931456,5.68999457359314,18.020215656019285,1739137663.8931484,5.68999457359314,-0.15999640573301194,1739137663.8931522,5.68999457359314,0.011040186721031164,1739137663.8931556,5.68999457359314,0.22438596948205367,1739137663.8931587,5.68999457359314,0.0532282660486858,1739137663.893162,5.68999457359314,2.285389213739303,1739137663.8931653,5.68999457359314,0.0,1739137663.8931687,5.68999457359314,0.002076905720740818,1739137663.8931723,5.68999457359314,6.266335238337815,1739137663.8931754,5.68999457359314,2.283312308018562 +1739137663.91235,5.709994554519653,9.974345095868738,1739137663.9123538,5.709994554519653,-0.24882792817775634,1739137663.9123583,5.709994554519653,9.17623745747815,1739137663.9123635,5.709994554519653,18.020215656019285,1739137663.9123664,5.709994554519653,-0.15999640573301194,1739137663.91237,5.709994554519653,0.011040186721031164,1739137663.9123733,5.709994554519653,0.22438596948205367,1739137663.9123764,5.709994554519653,0.0532282660486858,1739137663.9123797,5.709994554519653,2.285389213739303,1739137663.912383,5.709994554519653,0.0,1739137663.9123864,5.709994554519653,0.002076905720740818,1739137663.9123895,5.709994554519653,6.266335238337815,1739137663.9123929,5.709994554519653,2.283312308018562 +1739137663.9323454,5.729994535446167,9.974345095868738,1739137663.9323492,5.729994535446167,-0.24882792817775634,1739137663.9323533,5.729994535446167,9.17623745747815,1739137663.9323585,5.729994535446167,18.020215656019285,1739137663.9323611,5.729994535446167,-0.15999640573301194,1739137663.9323647,5.729994535446167,0.011040186721031164,1739137663.932368,5.729994535446167,0.22438596948205367,1739137663.9323716,5.729994535446167,0.0532282660486858,1739137663.932375,5.729994535446167,2.285389213739303,1739137663.9323783,5.729994535446167,0.0,1739137663.9323816,5.729994535446167,0.002076905720740818,1739137663.932385,5.729994535446167,6.266335238337815,1739137663.9323883,5.729994535446167,2.283312308018562 +1739137663.9528847,5.749994516372681,9.974345095868738,1739137663.9528883,5.749994516372681,-0.24882792817775634,1739137663.9528928,5.749994516372681,9.17623745747815,1739137663.9528978,5.749994516372681,18.020215656019285,1739137663.9529006,5.749994516372681,-0.15999640573301194,1739137663.9529042,5.749994516372681,0.011040186721031164,1739137663.9529076,5.749994516372681,0.22438596948205367,1739137663.952911,5.749994516372681,0.0532282660486858,1739137663.9529142,5.749994516372681,2.285389213739303,1739137663.9529176,5.749994516372681,0.0,1739137663.952921,5.749994516372681,0.002076905720740818,1739137663.9529245,5.749994516372681,6.266335238337815,1739137663.9529278,5.749994516372681,2.283312308018562 +1739137663.9725463,5.769994497299194,9.974345095868738,1739137663.97255,5.769994497299194,-0.24882792817775634,1739137663.9725542,5.769994497299194,9.17623745747815,1739137663.9725595,5.769994497299194,18.020215656019285,1739137663.972562,5.769994497299194,-0.15999640573301194,1739137663.9725664,5.769994497299194,0.011040186721031164,1739137663.9725697,5.769994497299194,0.22438596948205367,1739137663.972573,5.769994497299194,0.0532282660486858,1739137663.9725766,5.769994497299194,2.285389213739303,1739137663.97258,5.769994497299194,0.0,1739137663.9725828,5.769994497299194,0.002076905720740818,1739137663.9725864,5.769994497299194,6.266335238337815,1739137663.97259,5.769994497299194,2.283312308018562 +1739137663.9926124,5.789994478225708,10.22549365144374,1739137663.992616,5.789994478225708,-0.2529882649655706,1739137663.9926202,5.789994478225708,9.853320889664968,1739137663.9926255,5.789994478225708,18.698061354498208,1739137663.9926283,5.789994478225708,-0.14608938790500312,1739137663.992632,5.789994478225708,0.012616388435313925,1739137663.9926353,5.789994478225708,0.2443049608335607,1739137663.9926383,5.789994478225708,0.0522613158899862,1739137663.9926414,5.789994478225708,2.2672525034879283,1739137663.992645,5.789994478225708,0.0,1739137663.9926481,5.789994478225708,-0.0331272072117262,1739137663.992652,5.789994478225708,6.2669651745905615,1739137663.9926553,5.789994478225708,2.2836158390241934 +1739137664.012363,5.809994459152222,10.22549365144374,1739137664.0123663,5.809994459152222,-0.2529882649655706,1739137664.0123708,5.809994459152222,9.853320889664968,1739137664.012376,5.809994459152222,18.698061354498208,1739137664.012379,5.809994459152222,-0.14608938790500312,1739137664.0123825,5.809994459152222,0.012616388435313925,1739137664.0123858,5.809994459152222,0.2443049608335607,1739137664.0123894,5.809994459152222,0.0522613158899862,1739137664.0123928,5.809994459152222,2.2672525034879283,1739137664.012396,5.809994459152222,0.0,1739137664.0123994,5.809994459152222,-0.016363335536265122,1739137664.0124028,5.809994459152222,6.2669651745905615,1739137664.012406,5.809994459152222,2.2836158390241934 +1739137664.032146,5.829994440078735,10.22549365144374,1739137664.0321498,5.829994440078735,-0.2529882649655706,1739137664.032154,5.829994440078735,9.853320889664968,1739137664.0321593,5.829994440078735,18.698061354498208,1739137664.032162,5.829994440078735,-0.14608938790500312,1739137664.0321655,5.829994440078735,0.012616388435313925,1739137664.0321689,5.829994440078735,0.2443049608335607,1739137664.0321722,5.829994440078735,0.0522613158899862,1739137664.0321755,5.829994440078735,2.2672525034879283,1739137664.0321789,5.829994440078735,0.0,1739137664.0321822,5.829994440078735,-0.016363335536265122,1739137664.0321856,5.829994440078735,6.2669651745905615,1739137664.032189,5.829994440078735,2.2836158390241934 +1739137664.052316,5.849994421005249,10.22549365144374,1739137664.0523195,5.849994421005249,-0.2529882649655706,1739137664.052324,5.849994421005249,9.853320889664968,1739137664.0523293,5.849994421005249,18.698061354498208,1739137664.052332,5.849994421005249,-0.14608938790500312,1739137664.052336,5.849994421005249,0.012616388435313925,1739137664.0523393,5.849994421005249,0.2443049608335607,1739137664.052343,5.849994421005249,0.0522613158899862,1739137664.0523458,5.849994421005249,2.2672525034879283,1739137664.0523493,5.849994421005249,0.0,1739137664.0523524,5.849994421005249,-0.016363335536265122,1739137664.052356,5.849994421005249,6.2669651745905615,1739137664.052359,5.849994421005249,2.2836158390241934 +1739137664.0720935,5.869994401931763,10.22549365144374,1739137664.0720973,5.869994401931763,-0.2529882649655706,1739137664.0721016,5.869994401931763,9.853320889664968,1739137664.0721068,5.869994401931763,18.698061354498208,1739137664.0721095,5.869994401931763,-0.14608938790500312,1739137664.072113,5.869994401931763,0.012616388435313925,1739137664.0721164,5.869994401931763,0.2443049608335607,1739137664.0721195,5.869994401931763,0.0522613158899862,1739137664.0721228,5.869994401931763,2.2672525034879283,1739137664.0721264,5.869994401931763,0.0,1739137664.0721297,5.869994401931763,-0.016363335536265122,1739137664.072133,5.869994401931763,6.2669651745905615,1739137664.0721364,5.869994401931763,2.2836158390241934 +1739137664.091482,5.889994382858276,10.476559710422896,1739137664.0914848,5.889994382858276,-0.25698905114992243,1739137664.0914874,5.889994382858276,9.864371797046235,1739137664.09149,5.889994382858276,18.70328590110229,1739137664.0914917,5.889994382858276,-0.14595985369167877,1739137664.0914931,5.889994382858276,0.013495338781959224,1739137664.0914943,5.889994382858276,0.23926678571632776,1739137664.0914958,5.889994382858276,0.054286649761639105,1739137664.0914967,5.889994382858276,2.271826236652729,1739137664.0914981,5.889994382858276,0.0,1739137664.0914996,5.889994382858276,-0.003924995064379205,1739137664.091501,5.889994382858276,6.267595110843309,1739137664.0915022,5.889994382858276,2.281674253948243 +1739137664.11167,5.90999436378479,10.476559710422896,1739137664.1116729,5.90999436378479,-0.25698905114992243,1739137664.111676,5.90999436378479,9.864371797046235,1739137664.111679,5.90999436378479,18.70328590110229,1739137664.1116803,5.90999436378479,-0.14595985369167877,1739137664.111682,5.90999436378479,0.013495338781959224,1739137664.111684,5.90999436378479,0.23926678571632776,1739137664.1116853,5.90999436378479,0.054286649761639105,1739137664.1116867,5.90999436378479,2.271826236652729,1739137664.1116881,5.90999436378479,0.0,1739137664.1116896,5.90999436378479,-0.009848017295514211,1739137664.111691,5.90999436378479,6.267595110843309,1739137664.1116922,5.90999436378479,2.281674253948243 +1739137664.1317954,5.929994344711304,10.476559710422896,1739137664.1317985,5.929994344711304,-0.25698905114992243,1739137664.1318016,5.929994344711304,9.864371797046235,1739137664.1318047,5.929994344711304,18.70328590110229,1739137664.1318066,5.929994344711304,-0.14595985369167877,1739137664.1318088,5.929994344711304,0.013495338781959224,1739137664.1318102,5.929994344711304,0.23926678571632776,1739137664.1318119,5.929994344711304,0.054286649761639105,1739137664.1318133,5.929994344711304,2.271826236652729,1739137664.1318152,5.929994344711304,0.0,1739137664.1318166,5.929994344711304,-0.009848017295514211,1739137664.1318185,5.929994344711304,6.267595110843309,1739137664.13182,5.929994344711304,2.281674253948243 +1739137664.151786,5.949994325637817,10.476559710422896,1739137664.1517887,5.949994325637817,-0.25698905114992243,1739137664.1517923,5.949994325637817,9.864371797046235,1739137664.1517954,5.949994325637817,18.70328590110229,1739137664.1517973,5.949994325637817,-0.14595985369167877,1739137664.1517992,5.949994325637817,0.013495338781959224,1739137664.151801,5.949994325637817,0.23926678571632776,1739137664.1518025,5.949994325637817,0.054286649761639105,1739137664.151804,5.949994325637817,2.271826236652729,1739137664.1518059,5.949994325637817,0.0,1739137664.1518075,5.949994325637817,-0.009848017295514211,1739137664.1518092,5.949994325637817,6.267595110843309,1739137664.1518106,5.949994325637817,2.281674253948243 +1739137664.1717505,5.969994306564331,10.476559710422896,1739137664.1717536,5.969994306564331,-0.25698905114992243,1739137664.1717572,5.969994306564331,9.864371797046235,1739137664.1717603,5.969994306564331,18.70328590110229,1739137664.171762,5.969994306564331,-0.14595985369167877,1739137664.171764,5.969994306564331,0.013495338781959224,1739137664.1717656,5.969994306564331,0.23926678571632776,1739137664.171767,5.969994306564331,0.054286649761639105,1739137664.1717687,5.969994306564331,2.271826236652729,1739137664.1717703,5.969994306564331,0.0,1739137664.171772,5.969994306564331,-0.009848017295514211,1739137664.1717737,5.969994306564331,6.267595110843309,1739137664.1717753,5.969994306564331,2.281674253948243 +1739137664.1916127,5.989994287490845,10.476559710422896,1739137664.1916156,5.989994287490845,-0.25698905114992243,1739137664.191619,5.989994287490845,9.864371797046235,1739137664.1916218,5.989994287490845,18.70328590110229,1739137664.1916234,5.989994287490845,-0.14595985369167877,1739137664.191625,5.989994287490845,0.013495338781959224,1739137664.191627,5.989994287490845,0.23926678571632776,1739137664.1916282,5.989994287490845,0.054286649761639105,1739137664.19163,5.989994287490845,2.271826236652729,1739137664.1916313,5.989994287490845,0.0,1739137664.191633,5.989994287490845,-0.009848017295514211,1739137664.1916347,5.989994287490845,6.267595110843309,1739137664.191636,5.989994287490845,2.281674253948243 +1739137664.2123172,6.009994268417358,10.727471687439705,1739137664.2123206,6.009994268417358,-0.26082927885679386,1739137664.2123237,6.009994268417358,9.875415764262682,1739137664.212327,6.009994268417358,18.711445175389525,1739137664.2123284,6.009994268417358,-0.1457575576349705,1739137664.2123303,6.009994268417358,0.014411840725937895,1739137664.212332,6.009994268417358,0.23449670894089591,1739137664.2123337,6.009994268417358,0.05648696758666297,1739137664.2123349,6.009994268417358,2.276165088895773,1739137664.2123365,6.009994268417358,0.0,1739137664.2123382,6.009994268417358,0.0002693687253638114,1739137664.2123399,6.009994268417358,6.268225047096056,1739137664.2123413,6.009994268417358,2.2807135254441984 +1739137664.2319162,6.029994249343872,10.727471687439705,1739137664.2319195,6.029994249343872,-0.26082927885679386,1739137664.2319233,6.029994249343872,9.875415764262682,1739137664.2319272,6.029994249343872,18.711445175389525,1739137664.2319288,6.029994249343872,-0.1457575576349705,1739137664.2319312,6.029994249343872,0.014411840725937895,1739137664.2319329,6.029994249343872,0.23449670894089591,1739137664.2319345,6.029994249343872,0.05648696758666297,1739137664.2319362,6.029994249343872,2.276165088895773,1739137664.2319386,6.029994249343872,0.0,1739137664.23194,6.029994249343872,-0.004548436548425183,1739137664.231942,6.029994249343872,6.268225047096056,1739137664.2319436,6.029994249343872,2.2807135254441984 +1739137664.2518494,6.049994230270386,10.727471687439705,1739137664.2518528,6.049994230270386,-0.26082927885679386,1739137664.2518563,6.049994230270386,9.875415764262682,1739137664.2518597,6.049994230270386,18.711445175389525,1739137664.2518618,6.049994230270386,-0.1457575576349705,1739137664.2518637,6.049994230270386,0.014411840725937895,1739137664.2518656,6.049994230270386,0.23449670894089591,1739137664.2518673,6.049994230270386,0.05648696758666297,1739137664.2518692,6.049994230270386,2.276165088895773,1739137664.2518713,6.049994230270386,0.0,1739137664.251873,6.049994230270386,-0.004548436548425183,1739137664.251875,6.049994230270386,6.268225047096056,1739137664.2518764,6.049994230270386,2.2807135254441984 +1739137664.2725909,6.069994211196899,10.727471687439705,1739137664.2725942,6.069994211196899,-0.26082927885679386,1739137664.2725978,6.069994211196899,9.875415764262682,1739137664.272601,6.069994211196899,18.711445175389525,1739137664.2726026,6.069994211196899,-0.1457575576349705,1739137664.2726047,6.069994211196899,0.014411840725937895,1739137664.2726061,6.069994211196899,0.23449670894089591,1739137664.2726078,6.069994211196899,0.05648696758666297,1739137664.2726092,6.069994211196899,2.276165088895773,1739137664.2726114,6.069994211196899,0.0,1739137664.2726128,6.069994211196899,-0.004548436548425183,1739137664.2726147,6.069994211196899,6.268225047096056,1739137664.2726161,6.069994211196899,2.2807135254441984 +1739137664.2917497,6.089994192123413,10.727471687439705,1739137664.291753,6.089994192123413,-0.26082927885679386,1739137664.2917566,6.089994192123413,9.875415764262682,1739137664.2917604,6.089994192123413,18.711445175389525,1739137664.291762,6.089994192123413,-0.1457575576349705,1739137664.2917643,6.089994192123413,0.014411840725937895,1739137664.2917662,6.089994192123413,0.23449670894089591,1739137664.2917678,6.089994192123413,0.05648696758666297,1739137664.2917695,6.089994192123413,2.276165088895773,1739137664.2917714,6.089994192123413,0.0,1739137664.291773,6.089994192123413,-0.004548436548425183,1739137664.2917752,6.089994192123413,6.268225047096056,1739137664.2917767,6.089994192123413,2.2807135254441984 +1739137664.3119595,6.109994173049927,10.978301282884582,1739137664.3119628,6.109994173049927,-0.2645041077238206,1739137664.3119664,6.109994173049927,10.158054188130837,1739137664.3119698,6.109994173049927,18.99264996891713,1739137664.3119717,6.109994173049927,-0.13959791796178625,1739137664.3119736,6.109994173049927,0.015584058393144848,1739137664.3119755,6.109994173049927,0.23920258225259317,1739137664.311977,6.109994173049927,0.05718242040598982,1739137664.3119788,6.109994173049927,2.2718845810472668,1739137664.3119805,6.109994173049927,0.0,1739137664.3119824,6.109994173049927,-0.011853689494935392,1739137664.311984,6.109994173049927,6.268921768264599,1739137664.3119857,6.109994173049927,2.280259576925152 +1739137664.3319175,6.12999415397644,10.978301282884582,1739137664.3319209,6.12999415397644,-0.2645041077238206,1739137664.3319247,6.12999415397644,10.158054188130837,1739137664.331928,6.12999415397644,18.99264996891713,1739137664.33193,6.12999415397644,-0.13959791796178625,1739137664.3319318,6.12999415397644,0.015584058393144848,1739137664.3319337,6.12999415397644,0.23920258225259317,1739137664.3319354,6.12999415397644,0.05718242040598982,1739137664.331937,6.12999415397644,2.2718845810472668,1739137664.331939,6.12999415397644,0.0,1739137664.331941,6.12999415397644,-0.008374995877885372,1739137664.3319428,6.12999415397644,6.268921768264599,1739137664.3319445,6.12999415397644,2.280259576925152 +1739137664.351904,6.149994134902954,10.978301282884582,1739137664.3519075,6.149994134902954,-0.2645041077238206,1739137664.3519113,6.149994134902954,10.158054188130837,1739137664.3519144,6.149994134902954,18.99264996891713,1739137664.3519163,6.149994134902954,-0.13959791796178625,1739137664.3519182,6.149994134902954,0.015584058393144848,1739137664.3519201,6.149994134902954,0.23920258225259317,1739137664.351922,6.149994134902954,0.05718242040598982,1739137664.3519235,6.149994134902954,2.2718845810472668,1739137664.3519256,6.149994134902954,0.0,1739137664.351927,6.149994134902954,-0.008374995877885372,1739137664.351929,6.149994134902954,6.268921768264599,1739137664.3519306,6.149994134902954,2.280259576925152 +1739137664.3718772,6.169994115829468,10.978301282884582,1739137664.3718805,6.169994115829468,-0.2645041077238206,1739137664.3718839,6.169994115829468,10.158054188130837,1739137664.3718872,6.169994115829468,18.99264996891713,1739137664.3718889,6.169994115829468,-0.13959791796178625,1739137664.3718913,6.169994115829468,0.015584058393144848,1739137664.3718932,6.169994115829468,0.23920258225259317,1739137664.3718948,6.169994115829468,0.05718242040598982,1739137664.3718965,6.169994115829468,2.2718845810472668,1739137664.3718987,6.169994115829468,0.0,1739137664.3719,6.169994115829468,-0.008374995877885372,1739137664.371902,6.169994115829468,6.268921768264599,1739137664.3719037,6.169994115829468,2.280259576925152 +1739137664.392733,6.1899940967559814,10.978301282884582,1739137664.392737,6.1899940967559814,-0.2645041077238206,1739137664.3927407,6.1899940967559814,10.158054188130837,1739137664.3927438,6.1899940967559814,18.99264996891713,1739137664.3927457,6.1899940967559814,-0.13959791796178625,1739137664.3927479,6.1899940967559814,0.015584058393144848,1739137664.3927495,6.1899940967559814,0.23920258225259317,1739137664.3927512,6.1899940967559814,0.05718242040598982,1739137664.3927526,6.1899940967559814,2.2718845810472668,1739137664.3927548,6.1899940967559814,0.0,1739137664.3927562,6.1899940967559814,-0.008374995877885372,1739137664.3927581,6.1899940967559814,6.268921768264599,1739137664.3927596,6.1899940967559814,2.280259576925152 +1739137664.4118931,6.209994077682495,10.978301282884582,1739137664.4118962,6.209994077682495,-0.2645041077238206,1739137664.4118998,6.209994077682495,10.158054188130837,1739137664.4119039,6.209994077682495,18.99264996891713,1739137664.4119055,6.209994077682495,-0.13959791796178625,1739137664.4119077,6.209994077682495,0.015584058393144848,1739137664.4119093,6.209994077682495,0.23920258225259317,1739137664.411911,6.209994077682495,0.05718242040598982,1739137664.4119127,6.209994077682495,2.2718845810472668,1739137664.4119148,6.209994077682495,0.0,1739137664.4119163,6.209994077682495,-0.008374995877885372,1739137664.4119182,6.209994077682495,6.268921768264599,1739137664.4119196,6.209994077682495,2.280259576925152 +1739137664.4319701,6.229994058609009,11.229053056766126,1739137664.4319737,6.229994058609009,-0.2679922291783212,1739137664.4319773,6.229994058609009,10.952312937714106,1739137664.4319808,6.229994058609009,19.783900708315382,1739137664.4319828,6.229994058609009,-0.1322841607640385,1739137664.431985,6.229994058609009,0.01586196414955547,1739137664.4319866,6.229994058609009,0.25099223093545325,1739137664.4319885,6.229994058609009,0.052659054185622264,1739137664.4319906,6.229994058609009,2.26119591555511,1739137664.4319925,6.229994058609009,0.0,1739137664.4319942,6.229994058609009,-0.026898650457996463,1739137664.431996,6.229994058609009,6.269707571124375,1739137664.4319978,6.229994058609009,2.279273773711444 +1739137664.4529977,6.2499940395355225,11.229053056766126,1739137664.453002,6.2499940395355225,-0.2679922291783212,1739137664.4530063,6.2499940395355225,10.952312937714106,1739137664.4530108,6.2499940395355225,19.783900708315382,1739137664.4530127,6.2499940395355225,-0.1322841607640385,1739137664.4530156,6.2499940395355225,0.01586196414955547,1739137664.4530177,6.2499940395355225,0.25099223093545325,1739137664.4530196,6.2499940395355225,0.052659054185622264,1739137664.453022,6.2499940395355225,2.26119591555511,1739137664.4530241,6.2499940395355225,0.0,1739137664.4530265,6.2499940395355225,-0.018077858156334337,1739137664.453029,6.2499940395355225,6.269707571124375,1739137664.4530308,6.2499940395355225,2.279273773711444 +1739137664.4716856,6.269994020462036,11.229053056766126,1739137664.4716914,6.269994020462036,-0.2679922291783212,1739137664.4716947,6.269994020462036,10.952312937714106,1739137664.4716983,6.269994020462036,19.783900708315382,1739137664.4717,6.269994020462036,-0.1322841607640385,1739137664.471702,6.269994020462036,0.01586196414955547,1739137664.4717042,6.269994020462036,0.25099223093545325,1739137664.4717062,6.269994020462036,0.052659054185622264,1739137664.4717076,6.269994020462036,2.26119591555511,1739137664.47171,6.269994020462036,0.0,1739137664.4717116,6.269994020462036,-0.018077858156334337,1739137664.4717135,6.269994020462036,6.269707571124375,1739137664.471715,6.269994020462036,2.279273773711444 +1739137664.4915562,6.28999400138855,11.229053056766126,1739137664.491559,6.28999400138855,-0.2679922291783212,1739137664.4915617,6.28999400138855,10.952312937714106,1739137664.4915652,6.28999400138855,19.783900708315382,1739137664.4915671,6.28999400138855,-0.1322841607640385,1739137664.491569,6.28999400138855,0.01586196414955547,1739137664.491571,6.28999400138855,0.25099223093545325,1739137664.4915724,6.28999400138855,0.052659054185622264,1739137664.491574,6.28999400138855,2.26119591555511,1739137664.4915755,6.28999400138855,0.0,1739137664.4915774,6.28999400138855,-0.018077858156334337,1739137664.491579,6.28999400138855,6.269707571124375,1739137664.4915807,6.28999400138855,2.279273773711444 +1739137664.511685,6.3099939823150635,11.229053056766126,1739137664.5116875,6.3099939823150635,-0.2679922291783212,1739137664.5116901,6.3099939823150635,10.952312937714106,1739137664.5116928,6.3099939823150635,19.783900708315382,1739137664.5116942,6.3099939823150635,-0.1322841607640385,1739137664.5116956,6.3099939823150635,0.01586196414955547,1739137664.511697,6.3099939823150635,0.25099223093545325,1739137664.5116982,6.3099939823150635,0.052659054185622264,1739137664.5116994,6.3099939823150635,2.26119591555511,1739137664.511701,6.3099939823150635,0.0,1739137664.511702,6.3099939823150635,-0.018077858156334337,1739137664.5117035,6.3099939823150635,6.269707571124375,1739137664.511705,6.3099939823150635,2.279273773711444 +1739137664.5315878,6.329993963241577,11.479647274835985,1739137664.5315907,6.329993963241577,-0.2712795220310422,1739137664.5315936,6.329993963241577,10.957829297804498,1739137664.5315962,6.329993963241577,19.783245976558035,1739137664.5315979,6.329993963241577,-0.1322896168620164,1739137664.5315995,6.329993963241577,0.016736951255910137,1739137664.531601,6.329993963241577,0.24430297295372744,1739137664.5316029,6.329993963241577,0.05440239147764163,1739137664.5316043,6.329993963241577,2.2672543062988564,1739137664.5316057,6.329993963241577,0.0,1739137664.5316072,6.329993963241577,-0.0025847595125987497,1739137664.5316086,6.329993963241577,6.270500798044034,1739137664.5316098,6.329993963241577,2.27721673551775 +1739137664.551942,6.349993944168091,11.479647274835985,1739137664.551945,6.349993944168091,-0.2712795220310422,1739137664.5519478,6.349993944168091,10.957829297804498,1739137664.5519507,6.349993944168091,19.783245976558035,1739137664.5519521,6.349993944168091,-0.1322896168620164,1739137664.5519536,6.349993944168091,0.016736951255910137,1739137664.5519552,6.349993944168091,0.24430297295372744,1739137664.5519564,6.349993944168091,0.05440239147764163,1739137664.551958,6.349993944168091,2.2672543062988564,1739137664.5519595,6.349993944168091,0.0,1739137664.5519612,6.349993944168091,-0.009962429218893565,1739137664.5519629,6.349993944168091,6.270500798044034,1739137664.551964,6.349993944168091,2.27721673551775 +1739137664.5716987,6.3699939250946045,11.479647274835985,1739137664.5717013,6.3699939250946045,-0.2712795220310422,1739137664.5717044,6.3699939250946045,10.957829297804498,1739137664.5717072,6.3699939250946045,19.783245976558035,1739137664.5717084,6.3699939250946045,-0.1322896168620164,1739137664.5717103,6.3699939250946045,0.016736951255910137,1739137664.5717118,6.3699939250946045,0.24430297295372744,1739137664.5717132,6.3699939250946045,0.05440239147764163,1739137664.5717146,6.3699939250946045,2.2672543062988564,1739137664.571716,6.3699939250946045,0.0,1739137664.5717177,6.3699939250946045,-0.009962429218893565,1739137664.5717192,6.3699939250946045,6.270500798044034,1739137664.5717206,6.3699939250946045,2.27721673551775 +1739137664.5916107,6.389993906021118,11.479647274835985,1739137664.5916133,6.389993906021118,-0.2712795220310422,1739137664.591616,6.389993906021118,10.957829297804498,1739137664.5916188,6.389993906021118,19.783245976558035,1739137664.5916204,6.389993906021118,-0.1322896168620164,1739137664.591622,6.389993906021118,0.016736951255910137,1739137664.5916238,6.389993906021118,0.24430297295372744,1739137664.591625,6.389993906021118,0.05440239147764163,1739137664.5916262,6.389993906021118,2.2672543062988564,1739137664.591628,6.389993906021118,0.0,1739137664.5916293,6.389993906021118,-0.009962429218893565,1739137664.591631,6.389993906021118,6.270500798044034,1739137664.5916324,6.389993906021118,2.27721673551775 +1739137664.6114924,6.409993886947632,11.479647274835985,1739137664.6114953,6.409993886947632,-0.2712795220310422,1739137664.6114984,6.409993886947632,10.957829297804498,1739137664.6115012,6.409993886947632,19.783245976558035,1739137664.611503,6.409993886947632,-0.1322896168620164,1739137664.6115046,6.409993886947632,0.016736951255910137,1739137664.611506,6.409993886947632,0.24430297295372744,1739137664.6115072,6.409993886947632,0.05440239147764163,1739137664.6115088,6.409993886947632,2.2672543062988564,1739137664.6115103,6.409993886947632,0.0,1739137664.6115115,6.409993886947632,-0.009962429218893565,1739137664.6115134,6.409993886947632,6.270500798044034,1739137664.6115146,6.409993886947632,2.27721673551775 +1739137664.6315994,6.4299938678741455,11.479647274835985,1739137664.6316018,6.4299938678741455,-0.2712795220310422,1739137664.6316047,6.4299938678741455,10.957829297804498,1739137664.6316075,6.4299938678741455,19.783245976558035,1739137664.6316092,6.4299938678741455,-0.1322896168620164,1739137664.6316109,6.4299938678741455,0.016736951255910137,1739137664.6316123,6.4299938678741455,0.24430297295372744,1739137664.6316137,6.4299938678741455,0.05440239147764163,1739137664.6316152,6.4299938678741455,2.2672543062988564,1739137664.6316168,6.4299938678741455,0.0,1739137664.6316183,6.4299938678741455,-0.009962429218893565,1739137664.63162,6.4299938678741455,6.270500798044034,1739137664.6316211,6.4299938678741455,2.27721673551775 +1739137664.6516118,6.449993848800659,11.73008141400305,1739137664.651615,6.449993848800659,-0.2743660235970111,1739137664.651618,6.449993848800659,10.963341935367739,1739137664.6516209,6.449993848800659,19.785925237993954,1739137664.6516223,6.449993848800659,-0.13226728968338375,1739137664.6516242,6.449993848800659,0.017637382520153663,1739137664.6516256,6.449993848800659,0.23788074228749015,1739137664.6516275,6.449993848800659,0.05627848122846936,1739137664.6516287,6.449993848800659,2.273086125803382,1739137664.6516306,6.449993848800659,0.0,1739137664.6516318,6.449993848800659,0.0029740485912546667,1739137664.6516335,6.449993848800659,6.271294024963693,1739137664.6516347,6.449993848800659,2.2762723078180738 +1739137664.6715467,6.469993829727173,11.73008141400305,1739137664.671549,6.469993829727173,-0.2743660235970111,1739137664.671552,6.469993829727173,10.963341935367739,1739137664.6715546,6.469993829727173,19.785925237993954,1739137664.6715562,6.469993829727173,-0.13226728968338375,1739137664.6715581,6.469993829727173,0.017637382520153663,1739137664.6715593,6.469993829727173,0.23788074228749015,1739137664.6715608,6.469993829727173,0.05627848122846936,1739137664.671562,6.469993829727173,2.273086125803382,1739137664.6715636,6.469993829727173,0.0,1739137664.6715648,6.469993829727173,-0.003186182014691674,1739137664.6715662,6.469993829727173,6.271294024963693,1739137664.6715677,6.469993829727173,2.2762723078180738 +1739137664.6913416,6.4899938106536865,11.73008141400305,1739137664.691345,6.4899938106536865,-0.2743660235970111,1739137664.6913476,6.4899938106536865,10.963341935367739,1739137664.6913502,6.4899938106536865,19.785925237993954,1739137664.6913517,6.4899938106536865,-0.13226728968338375,1739137664.6913536,6.4899938106536865,0.017637382520153663,1739137664.691355,6.4899938106536865,0.23788074228749015,1739137664.6913562,6.4899938106536865,0.05627848122846936,1739137664.6913574,6.4899938106536865,2.273086125803382,1739137664.691359,6.4899938106536865,0.0,1739137664.6913602,6.4899938106536865,-0.003186182014691674,1739137664.6913614,6.4899938106536865,6.271294024963693,1739137664.6913629,6.4899938106536865,2.2762723078180738 +1739137664.7114584,6.5099937915802,11.73008141400305,1739137664.7114608,6.5099937915802,-0.2743660235970111,1739137664.7114637,6.5099937915802,10.963341935367739,1739137664.7114663,6.5099937915802,19.785925237993954,1739137664.7114677,6.5099937915802,-0.13226728968338375,1739137664.7114694,6.5099937915802,0.017637382520153663,1739137664.7114706,6.5099937915802,0.23788074228749015,1739137664.7114718,6.5099937915802,0.05627848122846936,1739137664.7114732,6.5099937915802,2.273086125803382,1739137664.7114744,6.5099937915802,0.0,1739137664.7114756,6.5099937915802,-0.003186182014691674,1739137664.711477,6.5099937915802,6.271294024963693,1739137664.7114782,6.5099937915802,2.2762723078180738 +1739137664.7318,6.529993772506714,11.73008141400305,1739137664.731803,6.529993772506714,-0.2743660235970111,1739137664.7318053,6.529993772506714,10.963341935367739,1739137664.7318082,6.529993772506714,19.785925237993954,1739137664.7318096,6.529993772506714,-0.13226728968338375,1739137664.7318113,6.529993772506714,0.017637382520153663,1739137664.731813,6.529993772506714,0.23788074228749015,1739137664.7318141,6.529993772506714,0.05627848122846936,1739137664.7318153,6.529993772506714,2.273086125803382,1739137664.731817,6.529993772506714,0.0,1739137664.7318182,6.529993772506714,-0.003186182014691674,1739137664.7318199,6.529993772506714,6.271294024963693,1739137664.7318213,6.529993772506714,2.2762723078180738 +1739137664.7515974,6.5499937534332275,11.980441020380663,1739137664.7516,6.5499937534332275,-0.27725298102672546,1739137664.751603,6.5499937534332275,11.36017917525726,1739137664.7516055,6.5499937534332275,20.181874514123546,1739137664.7516072,6.5499937534332275,-0.13,1739137664.7516088,6.5499937534332275,0.017952612930606984,1739137664.7516103,6.5499937534332275,0.23826200677165693,1739137664.7516117,6.5499937534332275,0.054384973139852924,1739137664.751613,6.5499937534332275,2.272739493432088,1739137664.7516146,6.5499937534332275,0.0,1739137664.7516158,6.5499937534332275,-0.0032889008519977,1739137664.7516174,6.5499937534332275,6.2720872518833515,1739137664.7516189,6.5499937534332275,2.275979480527601 +1739137664.7727566,6.569993734359741,11.980441020380663,1739137664.7727609,6.569993734359741,-0.27725298102672546,1739137664.7727656,6.569993734359741,11.36017917525726,1739137664.7727702,6.569993734359741,20.181874514123546,1739137664.7727726,6.569993734359741,-0.13,1739137664.7727752,6.569993734359741,0.017952612930606984,1739137664.7727773,6.569993734359741,0.23826200677165693,1739137664.7727792,6.569993734359741,0.054384973139852924,1739137664.7727811,6.569993734359741,2.272739493432088,1739137664.7727835,6.569993734359741,0.0,1739137664.7727854,6.569993734359741,-0.003239987095512653,1739137664.772788,6.569993734359741,6.2720872518833515,1739137664.7727897,6.569993734359741,2.275979480527601 +1739137664.793119,6.589993715286255,11.980441020380663,1739137664.7931228,6.589993715286255,-0.27725298102672546,1739137664.7931275,6.589993715286255,11.36017917525726,1739137664.793132,6.589993715286255,20.181874514123546,1739137664.7931345,6.589993715286255,-0.13,1739137664.7931368,6.589993715286255,0.017952612930606984,1739137664.7931392,6.589993715286255,0.23826200677165693,1739137664.793141,6.589993715286255,0.054384973139852924,1739137664.793143,6.589993715286255,2.272739493432088,1739137664.7931457,6.589993715286255,0.0,1739137664.7931476,6.589993715286255,-0.003239987095512653,1739137664.79315,6.589993715286255,6.2720872518833515,1739137664.793152,6.589993715286255,2.275979480527601 +1739137664.8129861,6.6099936962127686,11.980441020380663,1739137664.8129902,6.6099936962127686,-0.27725298102672546,1739137664.8129947,6.6099936962127686,11.36017917525726,1739137664.812999,6.6099936962127686,20.181874514123546,1739137664.8130012,6.6099936962127686,-0.13,1739137664.8130038,6.6099936962127686,0.017952612930606984,1739137664.8130062,6.6099936962127686,0.23826200677165693,1739137664.813008,6.6099936962127686,0.054384973139852924,1739137664.81301,6.6099936962127686,2.272739493432088,1739137664.8130121,6.6099936962127686,0.0,1739137664.8130143,6.6099936962127686,-0.003239987095512653,1739137664.8130164,6.6099936962127686,6.2720872518833515,1739137664.8130183,6.6099936962127686,2.275979480527601 +1739137664.8336043,6.629993677139282,11.980441020380663,1739137664.8336084,6.629993677139282,-0.27725298102672546,1739137664.8336134,6.629993677139282,11.36017917525726,1739137664.833618,6.629993677139282,20.181874514123546,1739137664.8336208,6.629993677139282,-0.13,1739137664.8336234,6.629993677139282,0.017952612930606984,1739137664.8336256,6.629993677139282,0.23826200677165693,1739137664.8336277,6.629993677139282,0.054384973139852924,1739137664.8336296,6.629993677139282,2.272739493432088,1739137664.8336322,6.629993677139282,0.0,1739137664.8336344,6.629993677139282,-0.003239987095512653,1739137664.8336365,6.629993677139282,6.2720872518833515,1739137664.833639,6.629993677139282,2.275979480527601 +1739137664.8523934,6.649993658065796,11.980441020380663,1739137664.8523977,6.649993658065796,-0.27725298102672546,1739137664.852402,6.649993658065796,11.36017917525726,1739137664.8524063,6.649993658065796,20.181874514123546,1739137664.8524084,6.649993658065796,-0.13,1739137664.852411,6.649993658065796,0.017952612930606984,1739137664.8524132,6.649993658065796,0.23826200677165693,1739137664.8524153,6.649993658065796,0.054384973139852924,1739137664.8524172,6.649993658065796,2.272739493432088,1739137664.8524196,6.649993658065796,0.0,1739137664.8524215,6.649993658065796,-0.003239987095512653,1739137664.852424,6.649993658065796,6.2720872518833515,1739137664.852426,6.649993658065796,2.275979480527601 +1739137664.873431,6.66999363899231,12.230766463994954,1739137664.873435,6.66999363899231,-0.2799409557451842,1739137664.8734398,6.66999363899231,11.387967987473164,1739137664.873444,6.66999363899231,20.208596222750774,1739137664.8734465,6.66999363899231,-0.12996038607027294,1739137664.8734493,6.66999363899231,0.018797456058147755,1739137664.8734512,6.66999363899231,0.2321813180787748,1739137664.8734536,6.66999363899231,0.056007351308622146,1739137664.8734553,6.66999363899231,2.2782741501442487,1739137664.8734581,6.66999363899231,0.0,1739137664.8734605,6.66999363899231,0.00800518866082852,1739137664.8734632,6.66999363899231,6.2728804788030095,1739137664.8734653,6.66999363899231,2.2756238097566586 +1739137664.8919773,6.689993619918823,12.230766463994954,1739137664.8919806,6.689993619918823,-0.2799409557451842,1739137664.8919842,6.689993619918823,11.387967987473164,1739137664.8919878,6.689993619918823,20.208596222750774,1739137664.8919895,6.689993619918823,-0.12996038607027294,1739137664.8919919,6.689993619918823,0.018797456058147755,1739137664.8919935,6.689993619918823,0.2321813180787748,1739137664.8919952,6.689993619918823,0.056007351308622146,1739137664.8919969,6.689993619918823,2.2782741501442487,1739137664.8919988,6.689993619918823,0.0,1739137664.8920004,6.689993619918823,0.0026503403875901554,1739137664.8920026,6.689993619918823,6.2728804788030095,1739137664.892004,6.689993619918823,2.2756238097566586 +1739137664.9127765,6.709993600845337,12.230766463994954,1739137664.9127798,6.709993600845337,-0.2799409557451842,1739137664.9127836,6.709993600845337,11.387967987473164,1739137664.9127872,6.709993600845337,20.208596222750774,1739137664.912789,6.709993600845337,-0.12996038607027294,1739137664.912791,6.709993600845337,0.018797456058147755,1739137664.912793,6.709993600845337,0.2321813180787748,1739137664.9127948,6.709993600845337,0.056007351308622146,1739137664.9127967,6.709993600845337,2.2782741501442487,1739137664.9127986,6.709993600845337,0.0,1739137664.9128003,6.709993600845337,0.0026503403875901554,1739137664.9128025,6.709993600845337,6.2728804788030095,1739137664.9128044,6.709993600845337,2.2756238097566586 +1739137664.9319465,6.729993581771851,12.230766463994954,1739137664.9319499,6.729993581771851,-0.2799409557451842,1739137664.9319537,6.729993581771851,11.387967987473164,1739137664.9319572,6.729993581771851,20.208596222750774,1739137664.9319592,6.729993581771851,-0.12996038607027294,1739137664.9319613,6.729993581771851,0.018797456058147755,1739137664.931963,6.729993581771851,0.2321813180787748,1739137664.9319646,6.729993581771851,0.056007351308622146,1739137664.9319668,6.729993581771851,2.2782741501442487,1739137664.9319685,6.729993581771851,0.0,1739137664.9319704,6.729993581771851,0.0026503403875901554,1739137664.9319723,6.729993581771851,6.2728804788030095,1739137664.9319742,6.729993581771851,2.2756238097566586 +1739137664.9519088,6.749993562698364,12.230766463994954,1739137664.9519126,6.749993562698364,-0.2799409557451842,1739137664.9519162,6.749993562698364,11.387967987473164,1739137664.9519198,6.749993562698364,20.208596222750774,1739137664.9519217,6.749993562698364,-0.12996038607027294,1739137664.951924,6.749993562698364,0.018797456058147755,1739137664.9519258,6.749993562698364,0.2321813180787748,1739137664.9519272,6.749993562698364,0.056007351308622146,1739137664.9519293,6.749993562698364,2.2782741501442487,1739137664.9519315,6.749993562698364,0.0,1739137664.9519331,6.749993562698364,0.0026503403875901554,1739137664.9519353,6.749993562698364,6.2728804788030095,1739137664.9519367,6.749993562698364,2.2756238097566586 +1739137664.9726393,6.769993543624878,12.48108042237343,1739137664.972643,6.769993543624878,-0.28243022558721176,1739137664.9726467,6.769993543624878,11.812128875139623,1739137664.9726508,6.769993543624878,20.63343656108423,1739137664.9726524,6.769993543624878,-0.129,1739137664.9726548,6.769993543624878,0.018818132026923423,1739137664.9726567,6.769993543624878,0.23096407850088474,1739137664.9726584,6.769993543624878,0.05335434265308342,1739137664.97266,6.769993543624878,2.2793837024264545,1739137664.972662,6.769993543624878,0.0,1739137664.9726639,6.769993543624878,0.004334791447248821,1739137664.9726655,6.769993543624878,6.273673705722668,1739137664.9726675,6.769993543624878,2.275851030932118 +1739137664.9920042,6.789993524551392,12.48108042237343,1739137664.992008,6.789993524551392,-0.28243022558721176,1739137664.9920115,6.789993524551392,11.812128875139623,1739137664.9920154,6.789993524551392,20.63343656108423,1739137664.9920173,6.789993524551392,-0.129,1739137664.9920194,6.789993524551392,0.018818132026923423,1739137664.9920213,6.789993524551392,0.23096407850088474,1739137664.992023,6.789993524551392,0.05335434265308342,1739137664.992025,6.789993524551392,2.2793837024264545,1739137664.9920268,6.789993524551392,0.0,1739137664.9920285,6.789993524551392,0.003532671494336448,1739137664.9920304,6.789993524551392,6.273673705722668,1739137664.9920323,6.789993524551392,2.275851030932118 +1739137665.0119634,6.809993505477905,12.48108042237343,1739137665.0119665,6.809993505477905,-0.28243022558721176,1739137665.0119703,6.809993505477905,11.812128875139623,1739137665.0119739,6.809993505477905,20.63343656108423,1739137665.0119758,6.809993505477905,-0.129,1739137665.0119777,6.809993505477905,0.018818132026923423,1739137665.0119796,6.809993505477905,0.23096407850088474,1739137665.0119812,6.809993505477905,0.05335434265308342,1739137665.0119832,6.809993505477905,2.2793837024264545,1739137665.011985,6.809993505477905,0.0,1739137665.011987,6.809993505477905,0.003532671494336448,1739137665.0119886,6.809993505477905,6.273673705722668,1739137665.0119905,6.809993505477905,2.275851030932118 +1739137665.0319972,6.829993486404419,12.48108042237343,1739137665.0320005,6.829993486404419,-0.28243022558721176,1739137665.0320044,6.829993486404419,11.812128875139623,1739137665.0320077,6.829993486404419,20.63343656108423,1739137665.03201,6.829993486404419,-0.129,1739137665.032012,6.829993486404419,0.018818132026923423,1739137665.032014,6.829993486404419,0.23096407850088474,1739137665.0320153,6.829993486404419,0.05335434265308342,1739137665.0320175,6.829993486404419,2.2793837024264545,1739137665.0320194,6.829993486404419,0.0,1739137665.032021,6.829993486404419,0.003532671494336448,1739137665.0320227,6.829993486404419,6.273673705722668,1739137665.0320246,6.829993486404419,2.275851030932118 +1739137665.051889,6.849993467330933,12.48108042237343,1739137665.0518925,6.849993467330933,-0.28243022558721176,1739137665.051896,6.849993467330933,11.812128875139623,1739137665.0518997,6.849993467330933,20.63343656108423,1739137665.0519013,6.849993467330933,-0.129,1739137665.0519037,6.849993467330933,0.018818132026923423,1739137665.0519059,6.849993467330933,0.23096407850088474,1739137665.0519075,6.849993467330933,0.05335434265308342,1739137665.0519094,6.849993467330933,2.2793837024264545,1739137665.051911,6.849993467330933,0.0,1739137665.051913,6.849993467330933,0.003532671494336448,1739137665.0519147,6.849993467330933,6.273673705722668,1739137665.0519166,6.849993467330933,2.275851030932118 +1739137665.0720222,6.869993448257446,12.48108042237343,1739137665.0720255,6.869993448257446,-0.28243022558721176,1739137665.0720294,6.869993448257446,11.812128875139623,1739137665.072033,6.869993448257446,20.63343656108423,1739137665.0720348,6.869993448257446,-0.129,1739137665.072037,6.869993448257446,0.018818132026923423,1739137665.072039,6.869993448257446,0.23096407850088474,1739137665.0720406,6.869993448257446,0.05335434265308342,1739137665.0720422,6.869993448257446,2.2793837024264545,1739137665.0720444,6.869993448257446,0.0,1739137665.072046,6.869993448257446,0.003532671494336448,1739137665.0720482,6.869993448257446,6.273673705722668,1739137665.0720499,6.869993448257446,2.275851030932118 +1739137665.092087,6.88999342918396,12.73143443836285,1739137665.0920904,6.88999342918396,-0.28472128722720846,1739137665.0920942,6.88999342918396,12.213371797613616,1739137665.0920978,6.88999342918396,21.035879208989524,1739137665.0920997,6.88999342918396,-0.127,1739137665.0921018,6.88999342918396,0.01899011092857485,1739137665.0921037,6.88999342918396,0.23011563569719468,1739137665.0921054,6.88999342918396,0.05122916755122581,1739137665.092107,6.88999342918396,2.2801574043870696,1739137665.092109,6.88999342918396,0.0,1739137665.0921109,6.88999342918396,0.004241061549523482,1739137665.0921125,6.88999342918396,6.274466932642327,1739137665.0921144,6.88999342918396,2.2762536716037647 +1739137665.112232,6.909993410110474,12.73143443836285,1739137665.1122355,6.909993410110474,-0.28472128722720846,1739137665.1122391,6.909993410110474,12.213371797613616,1739137665.1122427,6.909993410110474,21.035879208989524,1739137665.1122444,6.909993410110474,-0.127,1739137665.1122465,6.909993410110474,0.01899011092857485,1739137665.1122487,6.909993410110474,0.23011563569719468,1739137665.1122503,6.909993410110474,0.05122916755122581,1739137665.112252,6.909993410110474,2.2801574043870696,1739137665.112254,6.909993410110474,0.0,1739137665.1122558,6.909993410110474,0.003903732783304914,1739137665.1122575,6.909993410110474,6.274466932642327,1739137665.1122596,6.909993410110474,2.2762536716037647 +1739137665.1322072,6.929993391036987,12.73143443836285,1739137665.1322117,6.929993391036987,-0.28472128722720846,1739137665.1322157,6.929993391036987,12.213371797613616,1739137665.1322196,6.929993391036987,21.035879208989524,1739137665.1322215,6.929993391036987,-0.127,1739137665.132224,6.929993391036987,0.01899011092857485,1739137665.132226,6.929993391036987,0.23011563569719468,1739137665.1322281,6.929993391036987,0.05122916755122581,1739137665.1322296,6.929993391036987,2.2801574043870696,1739137665.132232,6.929993391036987,0.0,1739137665.1322336,6.929993391036987,0.003903732783304914,1739137665.132236,6.929993391036987,6.274466932642327,1739137665.132238,6.929993391036987,2.2762536716037647 +1739137665.152666,6.949993371963501,12.73143443836285,1739137665.1526692,6.949993371963501,-0.28472128722720846,1739137665.152673,6.949993371963501,12.213371797613616,1739137665.1526766,6.949993371963501,21.035879208989524,1739137665.1526785,6.949993371963501,-0.127,1739137665.1526806,6.949993371963501,0.01899011092857485,1739137665.1526828,6.949993371963501,0.23011563569719468,1739137665.1526845,6.949993371963501,0.05122916755122581,1739137665.1526864,6.949993371963501,2.2801574043870696,1739137665.1526883,6.949993371963501,0.0,1739137665.15269,6.949993371963501,0.003903732783304914,1739137665.152692,6.949993371963501,6.274466932642327,1739137665.152694,6.949993371963501,2.2762536716037647 +1739137665.1728117,6.969993352890015,12.73143443836285,1739137665.172817,6.969993352890015,-0.28472128722720846,1739137665.172823,6.969993352890015,12.213371797613616,1739137665.1728284,6.969993352890015,21.035879208989524,1739137665.172831,6.969993352890015,-0.127,1739137665.1728349,6.969993352890015,0.01899011092857485,1739137665.1728382,6.969993352890015,0.23011563569719468,1739137665.1728413,6.969993352890015,0.05122916755122581,1739137665.1728442,6.969993352890015,2.2801574043870696,1739137665.1728475,6.969993352890015,0.0,1739137665.1728506,6.969993352890015,0.003903732783304914,1739137665.1728542,6.969993352890015,6.274466932642327,1739137665.1728573,6.969993352890015,2.2762536716037647 +1739137665.1923451,6.989993333816528,12.98183516261841,1739137665.1923485,6.989993333816528,-0.2868141362301637,1739137665.1923523,6.989993333816528,12.263205727438477,1739137665.1923556,6.989993333816528,21.087003142306276,1739137665.1923575,6.989993333816528,-0.127,1739137665.1923597,6.989993333816528,0.01971500535190427,1739137665.1923614,6.989993333816528,0.2240430977547311,1739137665.192363,6.989993333816528,0.05235833565378842,1739137665.1923647,6.989993333816528,2.2857026733730286,1739137665.192367,6.989993333816528,0.0,1739137665.1923687,6.989993333816528,0.013669248514664105,1739137665.1923707,6.989993333816528,6.275260159561986,1739137665.1923726,6.989993333816528,2.276683672767728 +1739137665.2133603,7.009993314743042,12.98183516261841,1739137665.2133653,7.009993314743042,-0.2868141362301637,1739137665.2133708,7.009993314743042,12.263205727438477,1739137665.2133765,7.009993314743042,21.087003142306276,1739137665.2133796,7.009993314743042,-0.127,1739137665.2133834,7.009993314743042,0.01971500535190427,1739137665.2133865,7.009993314743042,0.2240430977547311,1739137665.2133896,7.009993314743042,0.05235833565378842,1739137665.2133927,7.009993314743042,2.2857026733730286,1739137665.213396,7.009993314743042,0.0,1739137665.2133987,7.009993314743042,0.009019000605300587,1739137665.2134023,7.009993314743042,6.275260159561986,1739137665.2134056,7.009993314743042,2.276683672767728 +1739137665.2319946,7.029993295669556,12.98183516261841,1739137665.2319987,7.029993295669556,-0.2868141362301637,1739137665.2320023,7.029993295669556,12.263205727438477,1739137665.2320058,7.029993295669556,21.087003142306276,1739137665.232008,7.029993295669556,-0.127,1739137665.2320101,7.029993295669556,0.01971500535190427,1739137665.232012,7.029993295669556,0.2240430977547311,1739137665.232014,7.029993295669556,0.05235833565378842,1739137665.2320156,7.029993295669556,2.2857026733730286,1739137665.2320175,7.029993295669556,0.0,1739137665.2320192,7.029993295669556,0.009019000605300587,1739137665.2320213,7.029993295669556,6.275260159561986,1739137665.232023,7.029993295669556,2.276683672767728 +1739137665.2530208,7.049993276596069,12.98183516261841,1739137665.2530255,7.049993276596069,-0.2868141362301637,1739137665.253031,7.049993276596069,12.263205727438477,1739137665.2530367,7.049993276596069,21.087003142306276,1739137665.2530398,7.049993276596069,-0.127,1739137665.2530437,7.049993276596069,0.01971500535190427,1739137665.253047,7.049993276596069,0.2240430977547311,1739137665.2530503,7.049993276596069,0.05235833565378842,1739137665.2530532,7.049993276596069,2.2857026733730286,1739137665.2530568,7.049993276596069,0.0,1739137665.2530599,7.049993276596069,0.009019000605300587,1739137665.2530634,7.049993276596069,6.275260159561986,1739137665.2530665,7.049993276596069,2.276683672767728 +1739137665.2724776,7.069993257522583,12.98183516261841,1739137665.272481,7.069993257522583,-0.2868141362301637,1739137665.2724855,7.069993257522583,12.263205727438477,1739137665.2724893,7.069993257522583,21.087003142306276,1739137665.272491,7.069993257522583,-0.127,1739137665.2724936,7.069993257522583,0.01971500535190427,1739137665.2724953,7.069993257522583,0.2240430977547311,1739137665.2724972,7.069993257522583,0.05235833565378842,1739137665.272499,7.069993257522583,2.2857026733730286,1739137665.2725012,7.069993257522583,0.0,1739137665.272503,7.069993257522583,0.009019000605300587,1739137665.2725048,7.069993257522583,6.275260159561986,1739137665.2725065,7.069993257522583,2.276683672767728 +1739137665.2927833,7.089993238449097,12.98183516261841,1739137665.292788,7.089993238449097,-0.2868141362301637,1739137665.2927935,7.089993238449097,12.263205727438477,1739137665.2927995,7.089993238449097,21.087003142306276,1739137665.292802,7.089993238449097,-0.127,1739137665.292806,7.089993238449097,0.01971500535190427,1739137665.2928085,7.089993238449097,0.2240430977547311,1739137665.2928112,7.089993238449097,0.05235833565378842,1739137665.2928138,7.089993238449097,2.2857026733730286,1739137665.2928166,7.089993238449097,0.0,1739137665.2928195,7.089993238449097,0.009019000605300587,1739137665.2928221,7.089993238449097,6.275260159561986,1739137665.292825,7.089993238449097,2.276683672767728 +1739137665.3128788,7.10999321937561,13.232325163054352,1739137665.3128822,7.10999321937561,-0.2887090185217307,1739137665.312886,7.10999321937561,12.683320513265357,1739137665.3128893,7.10999321937561,21.5104908603165,1739137665.3128912,7.10999321937561,-0.126,1739137665.3128934,7.10999321937561,0.01965267142099583,1739137665.3128953,7.10999321937561,0.22174360128021936,1739137665.312897,7.10999321937561,0.04967828968522869,1739137665.3128989,7.10999321937561,2.2878060266511078,1739137665.3129008,7.10999321937561,0.0,1739137665.3129027,7.10999321937561,0.010885474681422808,1739137665.3129046,7.10999321937561,6.276053386481644,1739137665.3129063,7.10999321937561,2.277809349592784 +1739137665.3333745,7.129993200302124,13.232325163054352,1739137665.3333795,7.129993200302124,-0.2887090185217307,1739137665.3333857,7.129993200302124,12.683320513265357,1739137665.3333921,7.129993200302124,21.5104908603165,1739137665.333395,7.129993200302124,-0.126,1739137665.3333988,7.129993200302124,0.01965267142099583,1739137665.333402,7.129993200302124,0.22174360128021936,1739137665.3334053,7.129993200302124,0.04967828968522869,1739137665.3334086,7.129993200302124,2.2878060266511078,1739137665.333412,7.129993200302124,0.0,1739137665.3334153,7.129993200302124,0.009996677058323744,1739137665.3334186,7.129993200302124,6.276053386481644,1739137665.3334217,7.129993200302124,2.277809349592784 +1739137665.3519435,7.149993181228638,13.232325163054352,1739137665.3519473,7.149993181228638,-0.2887090185217307,1739137665.3519511,7.149993181228638,12.683320513265357,1739137665.3519552,7.149993181228638,21.5104908603165,1739137665.351957,7.149993181228638,-0.126,1739137665.351959,7.149993181228638,0.01965267142099583,1739137665.351961,7.149993181228638,0.22174360128021936,1739137665.3519626,7.149993181228638,0.04967828968522869,1739137665.3519645,7.149993181228638,2.2878060266511078,1739137665.3519664,7.149993181228638,0.0,1739137665.3519683,7.149993181228638,0.009996677058323744,1739137665.3519702,7.149993181228638,6.276053386481644,1739137665.351972,7.149993181228638,2.277809349592784 +1739137665.3723857,7.169993162155151,13.232325163054352,1739137665.3723927,7.169993162155151,-0.2887090185217307,1739137665.3723977,7.169993162155151,12.683320513265357,1739137665.3724017,7.169993162155151,21.5104908603165,1739137665.3724046,7.169993162155151,-0.126,1739137665.372408,7.169993162155151,0.01965267142099583,1739137665.3724103,7.169993162155151,0.22174360128021936,1739137665.3724132,7.169993162155151,0.04967828968522869,1739137665.3724153,7.169993162155151,2.2878060266511078,1739137665.3724182,7.169993162155151,0.0,1739137665.3724203,7.169993162155151,0.009996677058323744,1739137665.3724225,7.169993162155151,6.276053386481644,1739137665.3724248,7.169993162155151,2.277809349592784 +1739137665.3921444,7.189993143081665,13.232325163054352,1739137665.3921478,7.189993143081665,-0.2887090185217307,1739137665.3921516,7.189993143081665,12.683320513265357,1739137665.3921552,7.189993143081665,21.5104908603165,1739137665.3921568,7.189993143081665,-0.126,1739137665.392159,7.189993143081665,0.01965267142099583,1739137665.3921611,7.189993143081665,0.22174360128021936,1739137665.392163,7.189993143081665,0.04967828968522869,1739137665.3921647,7.189993143081665,2.2878060266511078,1739137665.3921666,7.189993143081665,0.0,1739137665.3921685,7.189993143081665,0.009996677058323744,1739137665.3921702,7.189993143081665,6.276053386481644,1739137665.3921723,7.189993143081665,2.277809349592784 +1739137665.412452,7.209993124008179,13.482932539481194,1739137665.4124553,7.209993124008179,-0.2904059900227143,1739137665.4124596,7.209993124008179,12.71113962902024,1739137665.412463,7.209993124008179,21.541581583740992,1739137665.4124646,7.209993124008179,-0.126,1739137665.412467,7.209993124008179,0.020398355327995877,1739137665.4124687,7.209993124008179,0.2154836536890352,1739137665.4124703,7.209993124008179,0.05093996010477347,1739137665.4124718,7.209993124008179,2.2935418231415343,1739137665.412474,7.209993124008179,0.0,1739137665.4124756,7.209993124008179,0.018864905868541886,1739137665.4124777,7.209993124008179,6.276846613401303,1739137665.4124794,7.209993124008179,2.2788998854826534 +1739137665.468438,7.239993095397949,13.482932539481194,1739137665.4684424,7.239993095397949,-0.2904059900227143,1739137665.4684472,7.239993095397949,12.71113962902024,1739137665.4684522,7.239993095397949,21.541581583740992,1739137665.4684548,7.239993095397949,-0.126,1739137665.4684584,7.239993095397949,0.020398355327995877,1739137665.4684613,7.239993095397949,0.2154836536890352,1739137665.4684644,7.239993095397949,0.05093996010477347,1739137665.4684675,7.239993095397949,2.2935418231415343,1739137665.4684708,7.239993095397949,0.0,1739137665.468474,7.239993095397949,0.014641937658880888,1739137665.468477,7.239993095397949,6.276846613401303,1739137665.4684796,7.239993095397949,2.2788998854826534 +1739137665.472599,7.249993085861206,13.482932539481194,1739137665.4726033,7.249993085861206,-0.2904059900227143,1739137665.472609,7.249993085861206,12.71113962902024,1739137665.4726152,7.249993085861206,21.541581583740992,1739137665.4726183,7.249993085861206,-0.126,1739137665.4726224,7.249993085861206,0.020398355327995877,1739137665.4726255,7.249993085861206,0.2154836536890352,1739137665.4726288,7.249993085861206,0.05093996010477347,1739137665.4726322,7.249993085861206,2.2935418231415343,1739137665.4726357,7.249993085861206,0.0,1739137665.4726386,7.249993085861206,0.014641937658880888,1739137665.4726424,7.249993085861206,6.276846613401303,1739137665.472646,7.249993085861206,2.2788998854826534 +1739137665.4932146,7.26999306678772,13.482932539481194,1739137665.493218,7.26999306678772,-0.2904059900227143,1739137665.4932215,7.26999306678772,12.71113962902024,1739137665.4932258,7.26999306678772,21.541581583740992,1739137665.493228,7.26999306678772,-0.126,1739137665.4932306,7.26999306678772,0.020398355327995877,1739137665.493233,7.26999306678772,0.2154836536890352,1739137665.493235,7.26999306678772,0.05093996010477347,1739137665.493238,7.26999306678772,2.2935418231415343,1739137665.4932404,7.26999306678772,0.0,1739137665.4932435,7.26999306678772,0.014641937658880888,1739137665.4932456,7.26999306678772,6.276846613401303,1739137665.49325,7.26999306678772,2.2788998854826534 +1739137665.513082,7.289993047714233,13.482932539481194,1739137665.5130863,7.289993047714233,-0.2904059900227143,1739137665.5130918,7.289993047714233,12.71113962902024,1739137665.5130975,7.289993047714233,21.541581583740992,1739137665.5131004,7.289993047714233,-0.126,1739137665.5131042,7.289993047714233,0.020398355327995877,1739137665.5131078,7.289993047714233,0.2154836536890352,1739137665.5131123,7.289993047714233,0.05093996010477347,1739137665.5131156,7.289993047714233,2.2935418231415343,1739137665.5131185,7.289993047714233,0.0,1739137665.5131228,7.289993047714233,0.014641937658880888,1739137665.5131273,7.289993047714233,6.276846613401303,1739137665.513131,7.289993047714233,2.2788998854826534 +1739137665.5317714,7.309993028640747,13.482932539481194,1739137665.531774,7.309993028640747,-0.2904059900227143,1739137665.5317767,7.309993028640747,12.71113962902024,1739137665.5317793,7.309993028640747,21.541581583740992,1739137665.5317807,7.309993028640747,-0.126,1739137665.5317822,7.309993028640747,0.020398355327995877,1739137665.5317833,7.309993028640747,0.2154836536890352,1739137665.5317848,7.309993028640747,0.05093996010477347,1739137665.5317857,7.309993028640747,2.2935418231415343,1739137665.5317872,7.309993028640747,0.0,1739137665.5317886,7.309993028640747,0.014641937658880888,1739137665.5317898,7.309993028640747,6.276846613401303,1739137665.5317912,7.309993028640747,2.2788998854826534 +1739137665.5532944,7.329993009567261,13.733698697701737,1739137665.5532982,7.329993009567261,-0.2919051097532135,1739137665.5533028,7.329993009567261,12.935448676115557,1739137665.5533082,7.329993009567261,21.771072154471298,1739137665.5533109,7.329993009567261,-0.125,1739137665.553315,7.329993009567261,0.020763141746371453,1739137665.5533185,7.329993009567261,0.21147330310248683,1739137665.5533218,7.329993009567261,0.05025631002123414,1739137665.5533254,7.329993009567261,2.2972239383848345,1739137665.553329,7.329993009567261,0.0,1739137665.5533323,7.329993009567261,0.018371490863646235,1739137665.553336,7.329993009567261,6.277639840320962,1739137665.5533392,7.329993009567261,2.280628426124922 +1739137665.5727477,7.349992990493774,13.733698697701737,1739137665.5727513,7.349992990493774,-0.2919051097532135,1739137665.5727558,7.349992990493774,12.935448676115557,1739137665.572761,7.349992990493774,21.771072154471298,1739137665.572764,7.349992990493774,-0.125,1739137665.5727677,7.349992990493774,0.020763141746371453,1739137665.572771,7.349992990493774,0.21147330310248683,1739137665.5727744,7.349992990493774,0.05025631002123414,1739137665.5727777,7.349992990493774,2.2972239383848345,1739137665.5727813,7.349992990493774,0.0,1739137665.572785,7.349992990493774,0.016595512259912404,1739137665.5727885,7.349992990493774,6.277639840320962,1739137665.5727918,7.349992990493774,2.280628426124922 +1739137665.5929923,7.369992971420288,13.733698697701737,1739137665.5929964,7.369992971420288,-0.2919051097532135,1739137665.5930018,7.369992971420288,12.935448676115557,1739137665.5930064,7.369992971420288,21.771072154471298,1739137665.5930092,7.369992971420288,-0.125,1739137665.5930126,7.369992971420288,0.020763141746371453,1739137665.5930152,7.369992971420288,0.21147330310248683,1739137665.5930185,7.369992971420288,0.05025631002123414,1739137665.5930216,7.369992971420288,2.2972239383848345,1739137665.5930252,7.369992971420288,0.0,1739137665.5930276,7.369992971420288,0.016595512259912404,1739137665.593031,7.369992971420288,6.277639840320962,1739137665.5930333,7.369992971420288,2.280628426124922 +1739137665.6123962,7.389992952346802,13.733698697701737,1739137665.6124,7.389992952346802,-0.2919051097532135,1739137665.6124046,7.389992952346802,12.935448676115557,1739137665.6124094,7.389992952346802,21.771072154471298,1739137665.612412,7.389992952346802,-0.125,1739137665.6124153,7.389992952346802,0.020763141746371453,1739137665.612418,7.389992952346802,0.21147330310248683,1739137665.6124206,7.389992952346802,0.05025631002123414,1739137665.6124232,7.389992952346802,2.2972239383848345,1739137665.612426,7.389992952346802,0.0,1739137665.6124284,7.389992952346802,0.016595512259912404,1739137665.6124313,7.389992952346802,6.277639840320962,1739137665.612434,7.389992952346802,2.280628426124922 +1739137665.6316183,7.409992933273315,13.733698697701737,1739137665.6316202,7.409992933273315,-0.2919051097532135,1739137665.6316226,7.409992933273315,12.935448676115557,1739137665.6316252,7.409992933273315,21.771072154471298,1739137665.6316261,7.409992933273315,-0.125,1739137665.6316278,7.409992933273315,0.020763141746371453,1739137665.631629,7.409992933273315,0.21147330310248683,1739137665.6316304,7.409992933273315,0.05025631002123414,1739137665.6316314,7.409992933273315,2.2972239383848345,1739137665.6316326,7.409992933273315,0.0,1739137665.6316338,7.409992933273315,0.016595512259912404,1739137665.631635,7.409992933273315,6.277639840320962,1739137665.6316361,7.409992933273315,2.280628426124922 +1739137665.6515784,7.429992914199829,13.98465635737784,1739137665.6515803,7.429992914199829,-0.2932063007843011,1739137665.651583,7.429992914199829,13.160667781943747,1739137665.6515856,7.429992914199829,22.001780981770942,1739137665.6515868,7.429992914199829,-0.124,1739137665.6515887,7.429992914199829,0.02110247642280037,1739137665.6515899,7.429992914199829,0.207303546560059,1739137665.651591,7.429992914199829,0.04951397915350306,1739137665.6515923,7.429992914199829,2.301058681303321,1739137665.6515937,7.429992914199829,0.0,1739137665.651595,7.429992914199829,0.02042074842129546,1739137665.6515965,7.429992914199829,6.278433067240621,1739137665.6515977,7.429992914199829,2.2824594748211955 +1739137665.6714513,7.449992895126343,13.98465635737784,1739137665.6714537,7.449992895126343,-0.2932063007843011,1739137665.6714563,7.449992895126343,13.160667781943747,1739137665.6714587,7.449992895126343,22.001780981770942,1739137665.6714602,7.449992895126343,-0.124,1739137665.671462,7.449992895126343,0.02110247642280037,1739137665.6714635,7.449992895126343,0.207303546560059,1739137665.6714644,7.449992895126343,0.04951397915350306,1739137665.6714656,7.449992895126343,2.301058681303321,1739137665.6714673,7.449992895126343,0.0,1739137665.6714685,7.449992895126343,0.018599206482125652,1739137665.67147,7.449992895126343,6.278433067240621,1739137665.671471,7.449992895126343,2.2824594748211955 +1739137665.6915848,7.4699928760528564,13.98465635737784,1739137665.6915877,7.4699928760528564,-0.2932063007843011,1739137665.6915905,7.4699928760528564,13.160667781943747,1739137665.6915932,7.4699928760528564,22.001780981770942,1739137665.691595,7.4699928760528564,-0.124,1739137665.6915967,7.4699928760528564,0.02110247642280037,1739137665.6915982,7.4699928760528564,0.207303546560059,1739137665.6915994,7.4699928760528564,0.04951397915350306,1739137665.6916006,7.4699928760528564,2.301058681303321,1739137665.6916025,7.4699928760528564,0.0,1739137665.6916037,7.4699928760528564,0.018599206482125652,1739137665.6916053,7.4699928760528564,6.278433067240621,1739137665.6916065,7.4699928760528564,2.2824594748211955 +1739137665.713222,7.48999285697937,13.98465635737784,1739137665.7132263,7.48999285697937,-0.2932063007843011,1739137665.7132306,7.48999285697937,13.160667781943747,1739137665.7132356,7.48999285697937,22.001780981770942,1739137665.7132387,7.48999285697937,-0.124,1739137665.7132423,7.48999285697937,0.02110247642280037,1739137665.7132456,7.48999285697937,0.207303546560059,1739137665.713249,7.48999285697937,0.04951397915350306,1739137665.7132523,7.48999285697937,2.301058681303321,1739137665.713256,7.48999285697937,0.0,1739137665.7132592,7.48999285697937,0.018599206482125652,1739137665.7132626,7.48999285697937,6.278433067240621,1739137665.713266,7.48999285697937,2.2824594748211955 +1739137665.7316582,7.509992837905884,13.98465635737784,1739137665.7316618,7.509992837905884,-0.2932063007843011,1739137665.7316647,7.509992837905884,13.160667781943747,1739137665.7316675,7.509992837905884,22.001780981770942,1739137665.7316692,7.509992837905884,-0.124,1739137665.731671,7.509992837905884,0.02110247642280037,1739137665.7316725,7.509992837905884,0.207303546560059,1739137665.7316744,7.509992837905884,0.04951397915350306,1739137665.7316756,7.509992837905884,2.301058681303321,1739137665.7316773,7.509992837905884,0.0,1739137665.7316785,7.509992837905884,0.018599206482125652,1739137665.73168,7.509992837905884,6.278433067240621,1739137665.7316816,7.509992837905884,2.2824594748211955 +1739137665.7515671,7.5299928188323975,13.98465635737784,1739137665.75157,7.5299928188323975,-0.2932063007843011,1739137665.7515733,7.5299928188323975,13.160667781943747,1739137665.7515767,7.5299928188323975,22.001780981770942,1739137665.7515783,7.5299928188323975,-0.124,1739137665.7515805,7.5299928188323975,0.02110247642280037,1739137665.7515821,7.5299928188323975,0.207303546560059,1739137665.751584,7.5299928188323975,0.04951397915350306,1739137665.7515855,7.5299928188323975,2.301058681303321,1739137665.7515874,7.5299928188323975,0.0,1739137665.7515888,7.5299928188323975,0.018599206482125652,1739137665.751591,7.5299928188323975,6.278433067240621,1739137665.7515926,7.5299928188323975,2.2824594748211955 +1739137665.7715752,7.549992799758911,14.235829920429161,1739137665.7715778,7.549992799758911,-0.2943093674824979,1739137665.771581,7.549992799758911,13.486330972389474,1739137665.7715838,7.549992799758911,22.333660940206833,1739137665.7715855,7.549992799758911,-0.124,1739137665.7715874,7.549992799758911,0.021028379468249276,1739137665.7715888,7.549992799758911,0.2023673674748891,1739137665.7715902,7.549992799758911,0.047376842812146006,1739137665.7715914,7.549992799758911,2.3056065447340486,1739137665.7715938,7.549992799758911,0.0,1739137665.7715955,7.549992799758911,0.023325368275159825,1739137665.7715971,7.549992799758911,6.27922629416028,1739137665.7715983,7.549992799758911,2.284531730817917 +1739137665.7916636,7.569992780685425,14.235829920429161,1739137665.7916663,7.569992780685425,-0.2943093674824979,1739137665.791669,7.569992780685425,13.486330972389474,1739137665.7916718,7.569992780685425,22.333660940206833,1739137665.7916734,7.569992780685425,-0.124,1739137665.7916749,7.569992780685425,0.021028379468249276,1739137665.7916765,7.569992780685425,0.2023673674748891,1739137665.791678,7.569992780685425,0.047376842812146006,1739137665.7916791,7.569992780685425,2.3056065447340486,1739137665.7916808,7.569992780685425,0.0,1739137665.7916822,7.569992780685425,0.02107481391613142,1739137665.791684,7.569992780685425,6.27922629416028,1739137665.791685,7.569992780685425,2.284531730817917 +1739137665.811646,7.5899927616119385,14.235829920429161,1739137665.8116488,7.5899927616119385,-0.2943093674824979,1739137665.8116522,7.5899927616119385,13.486330972389474,1739137665.8116548,7.5899927616119385,22.333660940206833,1739137665.8116562,7.5899927616119385,-0.124,1739137665.8116584,7.5899927616119385,0.021028379468249276,1739137665.81166,7.5899927616119385,0.2023673674748891,1739137665.8116612,7.5899927616119385,0.047376842812146006,1739137665.8116627,7.5899927616119385,2.3056065447340486,1739137665.8116643,7.5899927616119385,0.0,1739137665.8116658,7.5899927616119385,0.02107481391613142,1739137665.8116672,7.5899927616119385,6.27922629416028,1739137665.8116686,7.5899927616119385,2.284531730817917 +1739137665.8314908,7.609992742538452,14.235829920429161,1739137665.831494,7.609992742538452,-0.2943093674824979,1739137665.8314972,7.609992742538452,13.486330972389474,1739137665.8315003,7.609992742538452,22.333660940206833,1739137665.8315017,7.609992742538452,-0.124,1739137665.8315036,7.609992742538452,0.021028379468249276,1739137665.8315058,7.609992742538452,0.2023673674748891,1739137665.831507,7.609992742538452,0.047376842812146006,1739137665.8315082,7.609992742538452,2.3056065447340486,1739137665.8315098,7.609992742538452,0.0,1739137665.8315113,7.609992742538452,0.02107481391613142,1739137665.8315127,7.609992742538452,6.27922629416028,1739137665.8315141,7.609992742538452,2.284531730817917 +1739137665.8515913,7.629992723464966,14.235829920429161,1739137665.8515942,7.629992723464966,-0.2943093674824979,1739137665.8515973,7.629992723464966,13.486330972389474,1739137665.8516002,7.629992723464966,22.333660940206833,1739137665.8516016,7.629992723464966,-0.124,1739137665.8516035,7.629992723464966,0.021028379468249276,1739137665.8516047,7.629992723464966,0.2023673674748891,1739137665.8516061,7.629992723464966,0.047376842812146006,1739137665.8516073,7.629992723464966,2.3056065447340486,1739137665.8516088,7.629992723464966,0.0,1739137665.8516102,7.629992723464966,0.02107481391613142,1739137665.8516116,7.629992723464966,6.27922629416028,1739137665.851613,7.629992723464966,2.284531730817917 +1739137665.8719141,7.6499927043914795,14.487243505710737,1739137665.8719175,7.6499927043914795,-0.29521405505416265,1739137665.8719208,7.6499927043914795,13.814514906331038,1739137665.8719237,7.6499927043914795,22.668812392352816,1739137665.8719249,7.6499927043914795,-0.12184769192633867,1739137665.8719268,7.6499927043914795,0.02118669716596372,1739137665.8719282,7.6499927043914795,0.19926654816255718,1739137665.8719296,7.6499927043914795,0.04570080765676415,1739137665.8719308,7.6499927043914795,2.3084680266751163,1739137665.8719327,7.6499927043914795,0.0,1739137665.8719342,7.6499927043914795,0.022098376422917,1739137665.8719358,7.6499927043914795,6.280019521079938,1739137665.871937,7.6499927043914795,2.2868570612131993 +1739137665.8918118,7.669992685317993,14.487243505710737,1739137665.891815,7.669992685317993,-0.29521405505416265,1739137665.891818,7.669992685317993,13.814514906331038,1739137665.8918214,7.669992685317993,22.668812392352816,1739137665.8918228,7.669992685317993,-0.12184769192633867,1739137665.891825,7.669992685317993,0.02118669716596372,1739137665.8918266,7.669992685317993,0.19926654816255718,1739137665.891828,7.669992685317993,0.04570080765676415,1739137665.8918295,7.669992685317993,2.3084680266751163,1739137665.891831,7.669992685317993,0.0,1739137665.8918324,7.669992685317993,0.021610965461916987,1739137665.8918338,7.669992685317993,6.280019521079938,1739137665.8918355,7.669992685317993,2.2868570612131993 +1739137665.9118414,7.689992666244507,14.487243505710737,1739137665.911844,7.689992666244507,-0.29521405505416265,1739137665.9118474,7.689992666244507,13.814514906331038,1739137665.9118502,7.689992666244507,22.668812392352816,1739137665.9118514,7.689992666244507,-0.12184769192633867,1739137665.9118533,7.689992666244507,0.02118669716596372,1739137665.9118545,7.689992666244507,0.19926654816255718,1739137665.9118562,7.689992666244507,0.04570080765676415,1739137665.9118574,7.689992666244507,2.3084680266751163,1739137665.911859,7.689992666244507,0.0,1739137665.9118602,7.689992666244507,0.021610965461916987,1739137665.9118617,7.689992666244507,6.280019521079938,1739137665.9118633,7.689992666244507,2.2868570612131993 +1739137665.9317858,7.7099926471710205,14.487243505710737,1739137665.9317884,7.7099926471710205,-0.29521405505416265,1739137665.9317913,7.7099926471710205,13.814514906331038,1739137665.9317942,7.7099926471710205,22.668812392352816,1739137665.9317954,7.7099926471710205,-0.12184769192633867,1739137665.9317973,7.7099926471710205,0.02118669716596372,1739137665.9317987,7.7099926471710205,0.19926654816255718,1739137665.9318004,7.7099926471710205,0.04570080765676415,1739137665.9318016,7.7099926471710205,2.3084680266751163,1739137665.9318032,7.7099926471710205,0.0,1739137665.9318044,7.7099926471710205,0.021610965461916987,1739137665.9318058,7.7099926471710205,6.280019521079938,1739137665.9318073,7.7099926471710205,2.2868570612131993 +1739137665.9517202,7.729992628097534,14.487243505710737,1739137665.9517229,7.729992628097534,-0.29521405505416265,1739137665.9517257,7.729992628097534,13.814514906331038,1739137665.9517286,7.729992628097534,22.668812392352816,1739137665.95173,7.729992628097534,-0.12184769192633867,1739137665.951732,7.729992628097534,0.02118669716596372,1739137665.9517336,7.729992628097534,0.19926654816255718,1739137665.951735,7.729992628097534,0.04570080765676415,1739137665.9517362,7.729992628097534,2.3084680266751163,1739137665.951738,7.729992628097534,0.0,1739137665.9517393,7.729992628097534,0.021610965461916987,1739137665.951741,7.729992628097534,6.280019521079938,1739137665.9517424,7.729992628097534,2.2868570612131993 +1739137665.9716902,7.749992609024048,14.487243505710737,1739137665.971693,7.749992609024048,-0.29521405505416265,1739137665.971696,7.749992609024048,13.814514906331038,1739137665.9716988,7.749992609024048,22.668812392352816,1739137665.9717002,7.749992609024048,-0.12184769192633867,1739137665.971702,7.749992609024048,0.02118669716596372,1739137665.9717035,7.749992609024048,0.19926654816255718,1739137665.9717052,7.749992609024048,0.04570080765676415,1739137665.9717064,7.749992609024048,2.3084680266751163,1739137665.971708,7.749992609024048,0.0,1739137665.9717095,7.749992609024048,0.021610965461916987,1739137665.971711,7.749992609024048,6.280019521079938,1739137665.9717126,7.749992609024048,2.2868570612131993 +1739137665.9919493,7.7699925899505615,14.738916227554128,1739137665.9919524,7.7699925899505615,-0.2959200392578296,1739137665.9919555,7.7699925899505615,14.041739127809427,1739137665.9919589,7.7699925899505615,22.903161257392558,1739137665.9919603,7.7699925899505615,-0.121,1739137665.9919624,7.7699925899505615,0.02142185604459359,1739137665.991964,7.7699925899505615,0.19428968326304896,1739137665.991966,7.7699925899505615,0.044748385745490435,1739137665.9919677,7.7699925899505615,2.3130681774190824,1739137665.9919696,7.7699925899505615,0.0,1739137665.991971,7.7699925899505615,0.025857994322377675,1739137665.9919732,7.7699925899505615,6.2808127479995965,1739137665.9919746,7.7699925899505615,2.2892325788024372 +1739137666.011599,7.789992570877075,14.738916227554128,1739137666.011602,7.789992570877075,-0.2959200392578296,1739137666.011605,7.789992570877075,14.041739127809427,1739137666.0116076,7.789992570877075,22.903161257392558,1739137666.011609,7.789992570877075,-0.121,1739137666.011611,7.789992570877075,0.02142185604459359,1739137666.0116124,7.789992570877075,0.19428968326304896,1739137666.0116136,7.789992570877075,0.044748385745490435,1739137666.011615,7.789992570877075,2.3130681774190824,1739137666.0116165,7.789992570877075,0.0,1739137666.011618,7.789992570877075,0.023835598616645193,1739137666.0116196,7.789992570877075,6.2808127479995965,1739137666.0116208,7.789992570877075,2.2892325788024372 +1739137666.0316815,7.809992551803589,14.738916227554128,1739137666.0316844,7.809992551803589,-0.2959200392578296,1739137666.0316877,7.809992551803589,14.041739127809427,1739137666.0316908,7.809992551803589,22.903161257392558,1739137666.031692,7.809992551803589,-0.121,1739137666.0316942,7.809992551803589,0.02142185604459359,1739137666.0316956,7.809992551803589,0.19428968326304896,1739137666.0316968,7.809992551803589,0.044748385745490435,1739137666.0316982,7.809992551803589,2.3130681774190824,1739137666.0316997,7.809992551803589,0.0,1739137666.031701,7.809992551803589,0.023835598616645193,1739137666.0317025,7.809992551803589,6.2808127479995965,1739137666.0317037,7.809992551803589,2.2892325788024372 +1739137666.0533407,7.8299925327301025,14.738916227554128,1739137666.0533447,7.8299925327301025,-0.2959200392578296,1739137666.05335,7.8299925327301025,14.041739127809427,1739137666.0533555,7.8299925327301025,22.903161257392558,1739137666.0533586,7.8299925327301025,-0.121,1739137666.0533626,7.8299925327301025,0.02142185604459359,1739137666.0533662,7.8299925327301025,0.19428968326304896,1739137666.0533698,7.8299925327301025,0.044748385745490435,1739137666.0533733,7.8299925327301025,2.3130681774190824,1739137666.0533776,7.8299925327301025,0.0,1739137666.0533812,7.8299925327301025,0.023835598616645193,1739137666.053385,7.8299925327301025,6.2808127479995965,1739137666.0533886,7.8299925327301025,2.2892325788024372 +1739137666.0730016,7.849992513656616,14.738916227554128,1739137666.073006,7.849992513656616,-0.2959200392578296,1739137666.0730107,7.849992513656616,14.041739127809427,1739137666.0730162,7.849992513656616,22.903161257392558,1739137666.073019,7.849992513656616,-0.121,1739137666.0730233,7.849992513656616,0.02142185604459359,1739137666.073027,7.849992513656616,0.19428968326304896,1739137666.0730305,7.849992513656616,0.044748385745490435,1739137666.073034,7.849992513656616,2.3130681774190824,1739137666.0730376,7.849992513656616,0.0,1739137666.0730412,7.849992513656616,0.023835598616645193,1739137666.0730453,7.849992513656616,6.2808127479995965,1739137666.0730488,7.849992513656616,2.2892325788024372 +1739137666.0931103,7.86999249458313,14.990862998635102,1739137666.093114,7.86999249458313,-0.29642693817761145,1739137666.0931182,7.86999249458313,14.274058086026281,1739137666.093123,7.86999249458313,23.143353001035386,1739137666.0931258,7.86999249458313,-0.12,1739137666.0931294,7.86999249458313,0.02163748793636021,1739137666.0931325,7.86999249458313,0.18930220325792696,1739137666.0931358,7.86999249458313,0.04372524343062828,1739137666.093139,7.86999249458313,2.317687335993415,1739137666.0931423,7.86999249458313,0.0,1739137666.0931454,7.86999249458313,0.027642200439364148,1739137666.0931487,7.86999249458313,6.281605974919255,1739137666.093152,7.86999249458313,2.291857803994186 +1739137666.1129446,7.8899924755096436,14.990862998635102,1739137666.1129482,7.8899924755096436,-0.29642693817761145,1739137666.112953,7.8899924755096436,14.274058086026281,1739137666.1129577,7.8899924755096436,23.143353001035386,1739137666.1129606,7.8899924755096436,-0.12,1739137666.1129644,7.8899924755096436,0.02163748793636021,1739137666.1129675,7.8899924755096436,0.18930220325792696,1739137666.1129708,7.8899924755096436,0.04372524343062828,1739137666.1129742,7.8899924755096436,2.317687335993415,1739137666.1129775,7.8899924755096436,0.0,1739137666.1129808,7.8899924755096436,0.025829531999228994,1739137666.1129844,7.8899924755096436,6.281605974919255,1739137666.1129873,7.8899924755096436,2.291857803994186 +1739137666.1318822,7.909992456436157,14.990862998635102,1739137666.131885,7.909992456436157,-0.29642693817761145,1739137666.131888,7.909992456436157,14.274058086026281,1739137666.131891,7.909992456436157,23.143353001035386,1739137666.1318924,7.909992456436157,-0.12,1739137666.1318944,7.909992456436157,0.02163748793636021,1739137666.1318958,7.909992456436157,0.18930220325792696,1739137666.1318974,7.909992456436157,0.04372524343062828,1739137666.1318986,7.909992456436157,2.317687335993415,1739137666.1319,7.909992456436157,0.0,1739137666.1319015,7.909992456436157,0.025829531999228994,1739137666.1319032,7.909992456436157,6.281605974919255,1739137666.1319046,7.909992456436157,2.291857803994186 +1739137666.1515973,7.929992437362671,14.990862998635102,1739137666.1516,7.929992437362671,-0.29642693817761145,1739137666.1516027,7.929992437362671,14.274058086026281,1739137666.1516056,7.929992437362671,23.143353001035386,1739137666.1516068,7.929992437362671,-0.12,1739137666.1516092,7.929992437362671,0.02163748793636021,1739137666.1516104,7.929992437362671,0.18930220325792696,1739137666.1516118,7.929992437362671,0.04372524343062828,1739137666.1516132,7.929992437362671,2.317687335993415,1739137666.1516147,7.929992437362671,0.0,1739137666.151616,7.929992437362671,0.025829531999228994,1739137666.1516173,7.929992437362671,6.281605974919255,1739137666.1516187,7.929992437362671,2.291857803994186 +1739137666.1717339,7.949992418289185,14.990862998635102,1739137666.1717362,7.949992418289185,-0.29642693817761145,1739137666.1717393,7.949992418289185,14.274058086026281,1739137666.1717422,7.949992418289185,23.143353001035386,1739137666.1717434,7.949992418289185,-0.12,1739137666.1717453,7.949992418289185,0.02163748793636021,1739137666.1717467,7.949992418289185,0.18930220325792696,1739137666.1717482,7.949992418289185,0.04372524343062828,1739137666.1717494,7.949992418289185,2.317687335993415,1739137666.171751,7.949992418289185,0.0,1739137666.1717522,7.949992418289185,0.025829531999228994,1739137666.1717536,7.949992418289185,6.281605974919255,1739137666.1717548,7.949992418289185,2.291857803994186 +1739137666.1919053,7.969992399215698,14.990862998635102,1739137666.1919076,7.969992399215698,-0.29642693817761145,1739137666.191911,7.969992399215698,14.274058086026281,1739137666.1919134,7.969992399215698,23.143353001035386,1739137666.1919148,7.969992399215698,-0.12,1739137666.1919162,7.969992399215698,0.02163748793636021,1739137666.191918,7.969992399215698,0.18930220325792696,1739137666.1919188,7.969992399215698,0.04372524343062828,1739137666.19192,7.969992399215698,2.317687335993415,1739137666.191922,7.969992399215698,0.0,1739137666.191923,7.969992399215698,0.025829531999228994,1739137666.1919246,7.969992399215698,6.281605974919255,1739137666.1919258,7.969992399215698,2.291857803994186 +1739137666.2114995,7.989992380142212,15.243112247930789,1739137666.211502,7.989992380142212,-0.29673435271905735,1739137666.211505,7.989992380142212,14.701926775443482,1739137666.2115076,7.989992380142212,23.57980840965693,1739137666.2115088,7.989992380142212,-0.119,1739137666.211511,7.989992380142212,0.021316289878079462,1739137666.2115123,7.989992380142212,0.1842878185038781,1739137666.2115133,7.989992380142212,0.04070763675094063,1739137666.211515,7.989992380142212,2.322340711613408,1739137666.2115164,7.989992380142212,0.0,1739137666.211518,7.989992380142212,0.02924638798502739,1739137666.2115195,7.989992380142212,6.282399201838914,1739137666.211521,7.989992380142212,2.294721398720127 +1739137666.2315984,8.009992361068726,15.243112247930789,1739137666.231601,8.009992361068726,-0.29673435271905735,1739137666.2316039,8.009992361068726,14.701926775443482,1739137666.231607,8.009992361068726,23.57980840965693,1739137666.2316086,8.009992361068726,-0.119,1739137666.2316103,8.009992361068726,0.021316289878079462,1739137666.2316122,8.009992361068726,0.1842878185038781,1739137666.2316134,8.009992361068726,0.04070763675094063,1739137666.2316153,8.009992361068726,2.322340711613408,1739137666.2316167,8.009992361068726,0.0,1739137666.2316182,8.009992361068726,0.02761931289328068,1739137666.2316198,8.009992361068726,6.282399201838914,1739137666.2316213,8.009992361068726,2.294721398720127 +1739137666.251953,8.02999234199524,15.243112247930789,1739137666.2519562,8.02999234199524,-0.29673435271905735,1739137666.2519593,8.02999234199524,14.701926775443482,1739137666.251962,8.02999234199524,23.57980840965693,1739137666.2519634,8.02999234199524,-0.119,1739137666.2519653,8.02999234199524,0.021316289878079462,1739137666.251967,8.02999234199524,0.1842878185038781,1739137666.2519681,8.02999234199524,0.04070763675094063,1739137666.2519696,8.02999234199524,2.322340711613408,1739137666.2519712,8.02999234199524,0.0,1739137666.251973,8.02999234199524,0.02761931289328068,1739137666.2519743,8.02999234199524,6.282399201838914,1739137666.2519758,8.02999234199524,2.294721398720127 +1739137666.2719295,8.049992322921753,15.243112247930789,1739137666.2719324,8.049992322921753,-0.29673435271905735,1739137666.2719355,8.049992322921753,14.701926775443482,1739137666.2719383,8.049992322921753,23.57980840965693,1739137666.2719395,8.049992322921753,-0.119,1739137666.2719417,8.049992322921753,0.021316289878079462,1739137666.2719429,8.049992322921753,0.1842878185038781,1739137666.2719443,8.049992322921753,0.04070763675094063,1739137666.271946,8.049992322921753,2.322340711613408,1739137666.2719476,8.049992322921753,0.0,1739137666.271949,8.049992322921753,0.02761931289328068,1739137666.2719505,8.049992322921753,6.282399201838914,1739137666.271952,8.049992322921753,2.294721398720127 +1739137666.2918363,8.069992303848267,15.243112247930789,1739137666.2918391,8.069992303848267,-0.29673435271905735,1739137666.2918422,8.069992303848267,14.701926775443482,1739137666.291845,8.069992303848267,23.57980840965693,1739137666.2918465,8.069992303848267,-0.119,1739137666.2918482,8.069992303848267,0.021316289878079462,1739137666.2918496,8.069992303848267,0.1842878185038781,1739137666.291851,8.069992303848267,0.04070763675094063,1739137666.2918527,8.069992303848267,2.322340711613408,1739137666.2918546,8.069992303848267,0.0,1739137666.2918558,8.069992303848267,0.02761931289328068,1739137666.2918575,8.069992303848267,6.282399201838914,1739137666.2918591,8.069992303848267,2.294721398720127 +1739137666.3126779,8.08999228477478,15.4956837429954,1739137666.312682,8.08999228477478,-0.29684181194622195,1739137666.3126872,8.08999228477478,14.940044784967089,1739137666.3126917,8.08999228477478,23.827025165920904,1739137666.312694,8.08999228477478,-0.11713800678113086,1739137666.312697,8.08999228477478,0.02156626824723159,1739137666.312699,8.08999228477478,0.17964447285452673,1739137666.3127015,8.08999228477478,0.0397326753423512,1739137666.3127034,8.08999228477478,2.3266580920460296,1739137666.3127055,8.08999228477478,0.0,1739137666.312708,8.08999228477478,0.03006667843178649,1739137666.31271,8.08999228477478,7.121578986622875e-06,1739137666.3127124,8.08999228477478,2.297756826357611 +1739137666.3330064,8.109992265701294,15.4956837429954,1739137666.333013,8.109992265701294,-0.29684181194622195,1739137666.3330207,8.109992265701294,14.940044784967089,1739137666.3330283,8.109992265701294,23.827025165920904,1739137666.3330317,8.109992265701294,-0.11713800678113086,1739137666.3330367,8.109992265701294,0.02156626824723159,1739137666.3330407,8.109992265701294,0.17964447285452673,1739137666.3330443,8.109992265701294,0.0397326753423512,1739137666.333048,8.109992265701294,2.3266580920460296,1739137666.3330522,8.109992265701294,0.0,1739137666.333056,8.109992265701294,0.028901265688418665,1739137666.3330605,8.109992265701294,7.121578986622875e-06,1739137666.3330648,8.109992265701294,2.297756826357611 +1739137666.3527179,8.129992246627808,15.4956837429954,1739137666.3527217,8.129992246627808,-0.29684181194622195,1739137666.3527262,8.129992246627808,14.940044784967089,1739137666.3527305,8.129992246627808,23.827025165920904,1739137666.3527327,8.129992246627808,-0.11713800678113086,1739137666.3527355,8.129992246627808,0.02156626824723159,1739137666.3527374,8.129992246627808,0.17964447285452673,1739137666.3527396,8.129992246627808,0.0397326753423512,1739137666.3527417,8.129992246627808,2.3266580920460296,1739137666.3527439,8.129992246627808,0.0,1739137666.3527462,8.129992246627808,0.028901265688418665,1739137666.3527486,8.129992246627808,7.121578986622875e-06,1739137666.3527508,8.129992246627808,2.297756826357611 +1739137666.3726614,8.149992227554321,15.4956837429954,1739137666.3726652,8.149992227554321,-0.29684181194622195,1739137666.3726695,8.149992227554321,14.940044784967089,1739137666.372674,8.149992227554321,23.827025165920904,1739137666.3726761,8.149992227554321,-0.11713800678113086,1739137666.372679,8.149992227554321,0.02156626824723159,1739137666.3726811,8.149992227554321,0.17964447285452673,1739137666.3726833,8.149992227554321,0.0397326753423512,1739137666.3726852,8.149992227554321,2.3266580920460296,1739137666.3726876,8.149992227554321,0.0,1739137666.3726897,8.149992227554321,0.028901265688418665,1739137666.372692,8.149992227554321,7.121578986622875e-06,1739137666.3726943,8.149992227554321,2.297756826357611 +1739137666.3925228,8.169992208480835,15.4956837429954,1739137666.3925269,8.169992208480835,-0.29684181194622195,1739137666.3925314,8.169992208480835,14.940044784967089,1739137666.3925364,8.169992208480835,23.827025165920904,1739137666.3925385,8.169992208480835,-0.11713800678113086,1739137666.3925421,8.169992208480835,0.02156626824723159,1739137666.392545,8.169992208480835,0.17964447285452673,1739137666.3925478,8.169992208480835,0.0397326753423512,1739137666.3925505,8.169992208480835,2.3266580920460296,1739137666.3925529,8.169992208480835,0.0,1739137666.3925555,8.169992208480835,0.028901265688418665,1739137666.3925586,8.169992208480835,7.121578986622875e-06,1739137666.392561,8.169992208480835,2.297756826357611 +1739137666.411938,8.189992189407349,15.4956837429954,1739137666.4119422,8.189992189407349,-0.29684181194622195,1739137666.4119468,8.189992189407349,14.940044784967089,1739137666.4119506,8.189992189407349,23.827025165920904,1739137666.4119527,8.189992189407349,-0.11713800678113086,1739137666.4119549,8.189992189407349,0.02156626824723159,1739137666.411957,8.189992189407349,0.17964447285452673,1739137666.411959,8.189992189407349,0.0397326753423512,1739137666.411961,8.189992189407349,2.3266580920460296,1739137666.4119635,8.189992189407349,0.0,1739137666.4119651,8.189992189407349,0.028901265688418665,1739137666.4119675,8.189992189407349,7.121578986622875e-06,1739137666.4119692,8.189992189407349,2.297756826357611 +1739137666.4320152,8.209992170333862,15.74859767564854,1739137666.4320178,8.209992170333862,-0.2967487977894452,1739137666.4320204,8.209992170333862,14.969129794208044,1739137666.432023,8.209992170333862,23.86567068527004,1739137666.4320242,8.209992170333862,-0.117,1739137666.432026,8.209992170333862,0.02214091513741331,1739137666.432027,8.209992170333862,0.17325225371662573,1739137666.4320285,8.209992170333862,0.04036752049318877,1739137666.4320295,8.209992170333862,2.332614707352232,1739137666.432031,8.209992170333862,0.0,1739137666.432032,8.209992170333862,0.034188670245560215,1739137666.4320333,8.209992170333862,0.000800348498645325,1739137666.4320345,8.209992170333862,2.300943850058306 +1739137666.451686,8.229992151260376,15.74859767564854,1739137666.4516885,8.229992151260376,-0.2967487977894452,1739137666.4516912,8.229992151260376,14.969129794208044,1739137666.4516938,8.229992151260376,23.86567068527004,1739137666.4516952,8.229992151260376,-0.117,1739137666.4516969,8.229992151260376,0.02214091513741331,1739137666.451698,8.229992151260376,0.17325225371662573,1739137666.4516995,8.229992151260376,0.04036752049318877,1739137666.4517007,8.229992151260376,2.332614707352232,1739137666.4517024,8.229992151260376,0.0,1739137666.4517038,8.229992151260376,0.031670857293925714,1739137666.4517055,8.229992151260376,0.000800348498645325,1739137666.4517066,8.229992151260376,2.300943850058306 +1739137666.478326,8.24999213218689,15.74859767564854,1739137666.4783385,8.24999213218689,-0.2967487977894452,1739137666.4783547,8.24999213218689,14.969129794208044,1739137666.478374,8.24999213218689,23.86567068527004,1739137666.4783866,8.24999213218689,-0.117,1739137666.4783998,8.24999213218689,0.02214091513741331,1739137666.4784102,8.24999213218689,0.17325225371662573,1739137666.478417,8.24999213218689,0.04036752049318877,1739137666.4784238,8.24999213218689,2.332614707352232,1739137666.4784317,8.24999213218689,0.0,1739137666.47844,8.24999213218689,0.031670857293925714,1739137666.478453,8.24999213218689,0.000800348498645325,1739137666.4784613,8.24999213218689,2.300943850058306 +1739137666.4968796,8.269992113113403,15.74859767564854,1739137666.4968882,8.269992113113403,-0.2967487977894452,1739137666.496898,8.269992113113403,14.969129794208044,1739137666.4969072,8.269992113113403,23.86567068527004,1739137666.4969122,8.269992113113403,-0.117,1739137666.496918,8.269992113113403,0.02214091513741331,1739137666.4969232,8.269992113113403,0.17325225371662573,1739137666.4969282,8.269992113113403,0.04036752049318877,1739137666.4969327,8.269992113113403,2.332614707352232,1739137666.4969382,8.269992113113403,0.0,1739137666.496943,8.269992113113403,0.031670857293925714,1739137666.4969482,8.269992113113403,0.000800348498645325,1739137666.4969528,8.269992113113403,2.300943850058306 +1739137666.533731,8.299992084503174,15.74859767564854,1739137666.5337348,8.299992084503174,-0.2967487977894452,1739137666.5337393,8.299992084503174,14.969129794208044,1739137666.5337436,8.299992084503174,23.86567068527004,1739137666.5337458,8.299992084503174,-0.117,1739137666.5337481,8.299992084503174,0.02214091513741331,1739137666.5337505,8.299992084503174,0.17325225371662573,1739137666.5337522,8.299992084503174,0.04036752049318877,1739137666.5337546,8.299992084503174,2.332614707352232,1739137666.533757,8.299992084503174,0.0,1739137666.5337586,8.299992084503174,0.031670857293925714,1739137666.533761,8.299992084503174,0.000800348498645325,1739137666.5337634,8.299992084503174,2.300943850058306 +1739137666.5519443,8.319992065429688,16.001876213289002,1739137666.551947,8.319992065429688,-0.29645473975200165,1739137666.55195,8.319992065429688,15.585051214652788,1739137666.551953,8.319992065429688,24.492042778850898,1739137666.551955,8.319992065429688,-0.11474761968413902,1739137666.5519567,8.319992065429688,0.021398800922100114,1739137666.5519586,8.319992065429688,0.16817717433710355,1739137666.55196,8.319992065429688,0.03581841189856409,1739137666.5519617,8.319992065429688,2.337354798913243,1739137666.5519633,8.319992065429688,0.0,1739137666.5519652,8.319992065429688,0.03406389012899146,1739137666.5519667,8.319992065429688,0.0015935754183040263,1739137666.5519683,8.319992065429688,2.304430448798771 +1739137666.5731494,8.339992046356201,16.001876213289002,1739137666.5731535,8.339992046356201,-0.29645473975200165,1739137666.573158,8.339992046356201,15.585051214652788,1739137666.573163,8.339992046356201,24.492042778850898,1739137666.573166,8.339992046356201,-0.11474761968413902,1739137666.573169,8.339992046356201,0.021398800922100114,1739137666.5731716,8.339992046356201,0.16817717433710355,1739137666.5731745,8.339992046356201,0.03581841189856409,1739137666.573177,8.339992046356201,2.337354798913243,1739137666.5731802,8.339992046356201,0.0,1739137666.573183,8.339992046356201,0.032924350114472034,1739137666.5731864,8.339992046356201,0.0015935754183040263,1739137666.573189,8.339992046356201,2.304430448798771 +1739137666.5927775,8.359992027282715,16.001876213289002,1739137666.5927804,8.359992027282715,-0.29645473975200165,1739137666.5927835,8.359992027282715,15.585051214652788,1739137666.5927866,8.359992027282715,24.492042778850898,1739137666.5927877,8.359992027282715,-0.11474761968413902,1739137666.5927896,8.359992027282715,0.021398800922100114,1739137666.5927913,8.359992027282715,0.16817717433710355,1739137666.5927927,8.359992027282715,0.03581841189856409,1739137666.5927944,8.359992027282715,2.337354798913243,1739137666.5927958,8.359992027282715,0.0,1739137666.5927975,8.359992027282715,0.032924350114472034,1739137666.5927992,8.359992027282715,0.0015935754183040263,1739137666.5928009,8.359992027282715,2.304430448798771 +1739137666.612037,8.379992008209229,16.001876213289002,1739137666.61204,8.379992008209229,-0.29645473975200165,1739137666.6120434,8.379992008209229,15.585051214652788,1739137666.6120462,8.379992008209229,24.492042778850898,1739137666.612048,8.379992008209229,-0.11474761968413902,1739137666.6120498,8.379992008209229,0.021398800922100114,1739137666.6120515,8.379992008209229,0.16817717433710355,1739137666.612053,8.379992008209229,0.03581841189856409,1739137666.6120546,8.379992008209229,2.337354798913243,1739137666.6120563,8.379992008209229,0.0,1739137666.6120577,8.379992008209229,0.032924350114472034,1739137666.6120596,8.379992008209229,0.0015935754183040263,1739137666.6120613,8.379992008209229,2.304430448798771 +1739137666.63264,8.399991989135742,16.001876213289002,1739137666.6326427,8.399991989135742,-0.29645473975200165,1739137666.632646,8.399991989135742,15.585051214652788,1739137666.6326492,8.399991989135742,24.492042778850898,1739137666.6326509,8.399991989135742,-0.11474761968413902,1739137666.6326525,8.399991989135742,0.021398800922100114,1739137666.6326542,8.399991989135742,0.16817717433710355,1739137666.6326559,8.399991989135742,0.03581841189856409,1739137666.632657,8.399991989135742,2.337354798913243,1739137666.632659,8.399991989135742,0.0,1739137666.6326604,8.399991989135742,0.032924350114472034,1739137666.632662,8.399991989135742,0.0015935754183040263,1739137666.6326635,8.399991989135742,2.304430448798771 +1739137666.6522574,8.419991970062256,16.255544778573626,1739137666.6522605,8.419991970062256,-0.2959590107455199,1739137666.6522636,8.419991970062256,15.631979403501436,1739137666.6522667,8.419991970062256,24.549836607521588,1739137666.6522686,8.419991970062256,-0.11427775115836107,1739137666.6522706,8.419991970062256,0.021900870467604514,1739137666.6522725,8.419991970062256,0.16188392575163263,1739137666.652274,8.419991970062256,0.03612492907426948,1739137666.6522756,8.419991970062256,2.3432460327148403,1739137666.6522775,8.419991970062256,0.0,1739137666.652279,8.419991970062256,0.03725553945027048,1739137666.6522806,8.419991970062256,0.002386802337962727,1739137666.6522818,8.419991970062256,2.3080529654071498 +1739137666.6724772,8.43999195098877,16.255544778573626,1739137666.6724803,8.43999195098877,-0.2959590107455199,1739137666.6724834,8.43999195098877,15.631979403501436,1739137666.6724865,8.43999195098877,24.549836607521588,1739137666.672488,8.43999195098877,-0.11427775115836107,1739137666.67249,8.43999195098877,0.021900870467604514,1739137666.6724916,8.43999195098877,0.16188392575163263,1739137666.672493,8.43999195098877,0.03612492907426948,1739137666.6724944,8.43999195098877,2.3432460327148403,1739137666.672496,8.43999195098877,0.0,1739137666.6724977,8.43999195098877,0.03519306730769056,1739137666.6724992,8.43999195098877,0.002386802337962727,1739137666.6725008,8.43999195098877,2.3080529654071498 +1739137666.6920989,8.459991931915283,16.255544778573626,1739137666.692102,8.459991931915283,-0.2959590107455199,1739137666.692105,8.459991931915283,15.631979403501436,1739137666.692108,8.459991931915283,24.549836607521588,1739137666.6921096,8.459991931915283,-0.11427775115836107,1739137666.6921113,8.459991931915283,0.021900870467604514,1739137666.6921132,8.459991931915283,0.16188392575163263,1739137666.6921146,8.459991931915283,0.03612492907426948,1739137666.6921163,8.459991931915283,2.3432460327148403,1739137666.6921177,8.459991931915283,0.0,1739137666.6921194,8.459991931915283,0.03519306730769056,1739137666.6921208,8.459991931915283,0.002386802337962727,1739137666.6921227,8.459991931915283,2.3080529654071498 +1739137666.7123668,8.479991912841797,16.255544778573626,1739137666.71237,8.479991912841797,-0.2959590107455199,1739137666.7123735,8.479991912841797,15.631979403501436,1739137666.7123764,8.479991912841797,24.549836607521588,1739137666.7123778,8.479991912841797,-0.11427775115836107,1739137666.7123797,8.479991912841797,0.021900870467604514,1739137666.7123811,8.479991912841797,0.16188392575163263,1739137666.7123828,8.479991912841797,0.03612492907426948,1739137666.7123842,8.479991912841797,2.3432460327148403,1739137666.712386,8.479991912841797,0.0,1739137666.7123876,8.479991912841797,0.03519306730769056,1739137666.7123895,8.479991912841797,0.002386802337962727,1739137666.712391,8.479991912841797,2.3080529654071498 +1739137666.7322562,8.49999189376831,16.255544778573626,1739137666.7322593,8.49999189376831,-0.2959590107455199,1739137666.7322626,8.49999189376831,15.631979403501436,1739137666.7322657,8.49999189376831,24.549836607521588,1739137666.7322679,8.49999189376831,-0.11427775115836107,1739137666.7322698,8.49999189376831,0.021900870467604514,1739137666.7322717,8.49999189376831,0.16188392575163263,1739137666.732273,8.49999189376831,0.03612492907426948,1739137666.7322748,8.49999189376831,2.3432460327148403,1739137666.7322767,8.49999189376831,0.0,1739137666.732278,8.49999189376831,0.03519306730769056,1739137666.7322798,8.49999189376831,0.002386802337962727,1739137666.7322814,8.49999189376831,2.3080529654071498 +1739137666.7528117,8.519991874694824,16.255544778573626,1739137666.7528145,8.519991874694824,-0.2959590107455199,1739137666.7528179,8.519991874694824,15.631979403501436,1739137666.752821,8.519991874694824,24.549836607521588,1739137666.7528226,8.519991874694824,-0.11427775115836107,1739137666.7528243,8.519991874694824,0.021900870467604514,1739137666.7528257,8.519991874694824,0.16188392575163263,1739137666.7528274,8.519991874694824,0.03612492907426948,1739137666.7528288,8.519991874694824,2.3432460327148403,1739137666.7528305,8.519991874694824,0.0,1739137666.752832,8.519991874694824,0.03519306730769056,1739137666.7528336,8.519991874694824,0.002386802337962727,1739137666.752835,8.519991874694824,2.3080529654071498 +1739137666.772418,8.539991855621338,16.509628190719855,1739137666.7724214,8.539991855621338,-0.29526092220043587,1739137666.7724245,8.539991855621338,15.771558233261036,1739137666.7724278,8.539991855621338,24.701156349236435,1739137666.7724292,8.539991855621338,-0.114,1739137666.7724311,8.539991855621338,0.0221242414201369,1739137666.7724328,8.539991855621338,0.155210750388431,1739137666.7724342,8.539991855621338,0.035509967714885654,1739137666.7724357,8.539991855621338,2.349509144643133,1739137666.7724373,8.539991855621338,0.0,1739137666.7724388,8.539991855621338,0.03967771147610194,1739137666.7724404,8.539991855621338,0.003180029257621428,1739137666.7724419,8.539991855621338,2.31196697907593 +1739137666.7920647,8.559991836547852,16.509628190719855,1739137666.792068,8.559991836547852,-0.29526092220043587,1739137666.7920713,8.559991836547852,15.771558233261036,1739137666.7920742,8.559991836547852,24.701156349236435,1739137666.7920759,8.559991836547852,-0.114,1739137666.7920778,8.559991836547852,0.0221242414201369,1739137666.7920797,8.559991836547852,0.155210750388431,1739137666.792081,8.559991836547852,0.035509967714885654,1739137666.7920828,8.559991836547852,2.349509144643133,1739137666.7920845,8.559991836547852,0.0,1739137666.7920861,8.559991836547852,0.0375421655672028,1739137666.7920876,8.559991836547852,0.003180029257621428,1739137666.792089,8.559991836547852,2.31196697907593 +1739137666.8129435,8.579991817474365,16.509628190719855,1739137666.8129473,8.579991817474365,-0.29526092220043587,1739137666.8129513,8.579991817474365,15.771558233261036,1739137666.8129554,8.579991817474365,24.701156349236435,1739137666.8129575,8.579991817474365,-0.114,1739137666.8129597,8.579991817474365,0.0221242414201369,1739137666.8129618,8.579991817474365,0.155210750388431,1739137666.8129642,8.579991817474365,0.035509967714885654,1739137666.8129659,8.579991817474365,2.349509144643133,1739137666.812968,8.579991817474365,0.0,1739137666.8129697,8.579991817474365,0.0375421655672028,1739137666.812972,8.579991817474365,0.003180029257621428,1739137666.812974,8.579991817474365,2.31196697907593 +1739137666.8337464,8.599991798400879,16.509628190719855,1739137666.8337514,8.599991798400879,-0.29526092220043587,1739137666.8337579,8.599991798400879,15.771558233261036,1739137666.8337643,8.599991798400879,24.701156349236435,1739137666.8337677,8.599991798400879,-0.114,1739137666.8337717,8.599991798400879,0.0221242414201369,1739137666.8337748,8.599991798400879,0.155210750388431,1739137666.8337781,8.599991798400879,0.035509967714885654,1739137666.833781,8.599991798400879,2.349509144643133,1739137666.8337843,8.599991798400879,0.0,1739137666.8337872,8.599991798400879,0.0375421655672028,1739137666.83379,8.599991798400879,0.003180029257621428,1739137666.8337927,8.599991798400879,2.31196697907593 +1739137666.8538399,8.619991779327393,16.509628190719855,1739137666.8538456,8.619991779327393,-0.29526092220043587,1739137666.8538518,8.619991779327393,15.771558233261036,1739137666.853858,8.619991779327393,24.701156349236435,1739137666.8538616,8.619991779327393,-0.114,1739137666.853866,8.619991779327393,0.0221242414201369,1739137666.8538702,8.619991779327393,0.155210750388431,1739137666.8538737,8.619991779327393,0.035509967714885654,1739137666.8538768,8.619991779327393,2.349509144643133,1739137666.8538806,8.619991779327393,0.0,1739137666.8538842,8.619991779327393,0.0375421655672028,1739137666.853888,8.619991779327393,0.003180029257621428,1739137666.8538916,8.619991779327393,2.31196697907593 +1739137666.8727324,8.639991760253906,16.764145388397047,1739137666.872736,8.639991760253906,-0.2943597486035756,1739137666.8727398,8.639991760253906,15.904606373579986,1739137666.8727436,8.639991760253906,24.846435471416754,1739137666.8727458,8.639991760253906,-0.114,1739137666.8727481,8.639991760253906,0.022311723197583594,1739137666.87275,8.639991760253906,0.1482454004514213,1739137666.8727522,8.639991760253906,0.03483917292358558,1739137666.8727539,8.639991760253906,2.3560643335887437,1739137666.8727562,8.639991760253906,0.0,1739137666.872758,8.639991760253906,0.04227326724558447,1739137666.8727598,8.639991760253906,0.0039732561772801295,1739137666.872762,8.639991760253906,2.3160439730297187 +1739137666.8927808,8.65999174118042,16.764145388397047,1739137666.8927846,8.65999174118042,-0.2943597486035756,1739137666.8927886,8.65999174118042,15.904606373579986,1739137666.8927925,8.65999174118042,24.846435471416754,1739137666.8927944,8.65999174118042,-0.114,1739137666.8927968,8.65999174118042,0.022311723197583594,1739137666.8927984,8.65999174118042,0.1482454004514213,1739137666.8928003,8.65999174118042,0.03483917292358558,1739137666.8928022,8.65999174118042,2.3560643335887437,1739137666.8928044,8.65999174118042,0.0,1739137666.892806,8.65999174118042,0.040020360559025026,1739137666.8928082,8.65999174118042,0.0039732561772801295,1739137666.8928099,8.65999174118042,2.3160439730297187 +1739137666.913257,8.679991722106934,16.764145388397047,1739137666.9132614,8.679991722106934,-0.2943597486035756,1739137666.9132655,8.679991722106934,15.904606373579986,1739137666.9132695,8.679991722106934,24.846435471416754,1739137666.9132712,8.679991722106934,-0.114,1739137666.913274,8.679991722106934,0.022311723197583594,1739137666.9132762,8.679991722106934,0.1482454004514213,1739137666.9132779,8.679991722106934,0.03483917292358558,1739137666.9132798,8.679991722106934,2.3560643335887437,1739137666.9132822,8.679991722106934,0.0,1739137666.9132838,8.679991722106934,0.040020360559025026,1739137666.9132862,8.679991722106934,0.0039732561772801295,1739137666.9132879,8.679991722106934,2.3160439730297187 +1739137666.9328845,8.699991703033447,16.764145388397047,1739137666.9328883,8.699991703033447,-0.2943597486035756,1739137666.9328923,8.699991703033447,15.904606373579986,1739137666.9328961,8.699991703033447,24.846435471416754,1739137666.9328983,8.699991703033447,-0.114,1739137666.9329007,8.699991703033447,0.022311723197583594,1739137666.9329026,8.699991703033447,0.1482454004514213,1739137666.9329045,8.699991703033447,0.03483917292358558,1739137666.9329064,8.699991703033447,2.3560643335887437,1739137666.9329083,8.699991703033447,0.0,1739137666.9329104,8.699991703033447,0.040020360559025026,1739137666.9329123,8.699991703033447,0.0039732561772801295,1739137666.9329143,8.699991703033447,2.3160439730297187 +1739137666.9529908,8.719991683959961,16.764145388397047,1739137666.9529948,8.719991683959961,-0.2943597486035756,1739137666.9529989,8.719991683959961,15.904606373579986,1739137666.9530027,8.719991683959961,24.846435471416754,1739137666.9530046,8.719991683959961,-0.114,1739137666.9530067,8.719991683959961,0.022311723197583594,1739137666.9530094,8.719991683959961,0.1482454004514213,1739137666.9530113,8.719991683959961,0.03483917292358558,1739137666.953013,8.719991683959961,2.3560643335887437,1739137666.9530153,8.719991683959961,0.0,1739137666.9530172,8.719991683959961,0.040020360559025026,1739137666.9530194,8.719991683959961,0.0039732561772801295,1739137666.9530213,8.719991683959961,2.3160439730297187 +1739137666.9751256,8.739991664886475,16.764145388397047,1739137666.9751346,8.739991664886475,-0.2943597486035756,1739137666.9751444,8.739991664886475,15.904606373579986,1739137666.975154,8.739991664886475,24.846435471416754,1739137666.9751585,8.739991664886475,-0.114,1739137666.9751642,8.739991664886475,0.022311723197583594,1739137666.9751687,8.739991664886475,0.1482454004514213,1739137666.9751735,8.739991664886475,0.03483917292358558,1739137666.975178,8.739991664886475,2.3560643335887437,1739137666.9751832,8.739991664886475,0.0,1739137666.9751883,8.739991664886475,0.040020360559025026,1739137666.9751935,8.739991664886475,0.0039732561772801295,1739137666.9751983,8.739991664886475,2.3160439730297187 +1739137666.9971817,8.759991645812988,17.019131564092273,1739137666.9971907,8.759991645812988,-0.2932546472282107,1739137666.9972022,8.759991645812988,16.244067782110452,1739137666.9972167,8.759991645812988,25.19917003688652,1739137666.9972265,8.759991645812988,-0.113,1739137666.9972446,8.759991645812988,0.02203235109590292,1739137666.997255,8.759991645812988,0.14126273212186413,1739137666.997267,8.759991645812988,0.032410101722435386,1739137666.9972749,8.759991645812988,2.362654178566857,1739137666.9972837,8.759991645812988,0.0,1739137666.9972951,8.759991645812988,0.04415183435806365,1739137666.9973075,8.759991645812988,0.00476648309693883,1739137666.9973176,8.759991645812988,2.320469713667313 +1739137667.0155756,8.779991626739502,17.019131564092273,1739137667.0155847,8.779991626739502,-0.2932546472282107,1739137667.0155964,8.779991626739502,16.244067782110452,1739137667.0156095,8.779991626739502,25.19917003688652,1739137667.0156171,8.779991626739502,-0.113,1739137667.015627,8.779991626739502,0.02203235109590292,1739137667.0156355,8.779991626739502,0.14126273212186413,1739137667.0156438,8.779991626739502,0.032410101722435386,1739137667.015651,8.779991626739502,2.362654178566857,1739137667.0156598,8.779991626739502,0.0,1739137667.015666,8.779991626739502,0.04218446489954397,1739137667.0156727,8.779991626739502,0.00476648309693883,1739137667.0156786,8.779991626739502,2.320469713667313 +1739137667.035438,8.809991598129272,17.019131564092273,1739137667.0354426,8.809991598129272,-0.2932546472282107,1739137667.0354483,8.809991598129272,16.244067782110452,1739137667.0354545,8.809991598129272,25.19917003688652,1739137667.0354576,8.809991598129272,-0.113,1739137667.0354614,8.809991598129272,0.02203235109590292,1739137667.0354645,8.809991598129272,0.14126273212186413,1739137667.0354676,8.809991598129272,0.032410101722435386,1739137667.035471,8.809991598129272,2.362654178566857,1739137667.035474,8.809991598129272,0.0,1739137667.035477,8.809991598129272,0.04218446489954397,1739137667.0354803,8.809991598129272,0.00476648309693883,1739137667.0354834,8.809991598129272,2.320469713667313 +1739137667.0537505,8.829991579055786,17.019131564092273,1739137667.0537548,8.829991579055786,-0.2932546472282107,1739137667.0537598,8.829991579055786,16.244067782110452,1739137667.0537639,8.829991579055786,25.19917003688652,1739137667.0537665,8.829991579055786,-0.113,1739137667.0537696,8.829991579055786,0.02203235109590292,1739137667.0537715,8.829991579055786,0.14126273212186413,1739137667.053774,8.829991579055786,0.032410101722435386,1739137667.0537765,8.829991579055786,2.362654178566857,1739137667.0537786,8.829991579055786,0.0,1739137667.053781,8.829991579055786,0.04218446489954397,1739137667.053784,8.829991579055786,0.00476648309693883,1739137667.053786,8.829991579055786,2.320469713667313 +1739137667.0734034,8.8499915599823,17.019131564092273,1739137667.0734062,8.8499915599823,-0.2932546472282107,1739137667.0734088,8.8499915599823,16.244067782110452,1739137667.073412,8.8499915599823,25.19917003688652,1739137667.0734153,8.8499915599823,-0.113,1739137667.0734198,8.8499915599823,0.02203235109590292,1739137667.0734258,8.8499915599823,0.14126273212186413,1739137667.07343,8.8499915599823,0.032410101722435386,1739137667.0734334,8.8499915599823,2.362654178566857,1739137667.0734353,8.8499915599823,0.0,1739137667.0734377,8.8499915599823,0.04218446489954397,1739137667.07344,8.8499915599823,0.00476648309693883,1739137667.0734417,8.8499915599823,2.320469713667313 +1739137667.0935888,8.869991540908813,17.27460787925969,1739137667.0935922,8.869991540908813,-0.2919447650343141,1739137667.0935955,8.869991540908813,16.47909587713166,1739137667.0936003,8.869991540908813,25.447956592041354,1739137667.0936036,8.869991540908813,-0.11299222282893208,1739137667.0936081,8.869991540908813,0.021891144201674876,1739137667.0936112,8.869991540908813,0.13350856186145257,1739137667.093634,8.869991540908813,0.03068152870920659,1739137667.0936356,8.869991540908813,2.3699937242069153,1739137667.0936372,8.869991540908813,0.0,1739137667.0936384,8.869991540908813,0.04744092330556158,1739137667.0936399,8.869991540908813,0.005559710016597531,1739137667.0936413,8.869991540908813,2.325055877583187 +1739137667.119858,8.889991521835327,17.27460787925969,1739137667.1198664,8.889991521835327,-0.2919447650343141,1739137667.1198766,8.889991521835327,16.47909587713166,1739137667.1198864,8.889991521835327,25.447956592041354,1739137667.1198912,8.889991521835327,-0.11299222282893208,1739137667.1198971,8.889991521835327,0.021891144201674876,1739137667.1199017,8.889991521835327,0.13350856186145257,1739137667.1199062,8.889991521835327,0.03068152870920659,1739137667.119911,8.889991521835327,2.3699937242069153,1739137667.119916,8.889991521835327,0.0,1739137667.119921,8.889991521835327,0.04493784662372846,1739137667.119926,8.889991521835327,0.005559710016597531,1739137667.1199303,8.889991521835327,2.325055877583187 +1739137667.1415749,8.90999150276184,17.27460787925969,1739137667.1415832,8.90999150276184,-0.2919447650343141,1739137667.1415923,8.90999150276184,16.47909587713166,1739137667.1416018,8.90999150276184,25.447956592041354,1739137667.1416063,8.90999150276184,-0.11299222282893208,1739137667.1416123,8.90999150276184,0.021891144201674876,1739137667.141617,8.90999150276184,0.13350856186145257,1739137667.1416218,8.90999150276184,0.03068152870920659,1739137667.1416264,8.90999150276184,2.3699937242069153,1739137667.141632,8.90999150276184,0.0,1739137667.1416368,8.90999150276184,0.04493784662372846,1739137667.1416423,8.90999150276184,0.005559710016597531,1739137667.1416469,8.90999150276184,2.325055877583187 +1739137667.164367,8.939991474151611,17.27460787925969,1739137667.1643715,8.939991474151611,-0.2919447650343141,1739137667.1643765,8.939991474151611,16.47909587713166,1739137667.164382,8.939991474151611,25.447956592041354,1739137667.1643846,8.939991474151611,-0.11299222282893208,1739137667.1643877,8.939991474151611,0.021891144201674876,1739137667.1643903,8.939991474151611,0.13350856186145257,1739137667.164393,8.939991474151611,0.03068152870920659,1739137667.1643956,8.939991474151611,2.3699937242069153,1739137667.1643984,8.939991474151611,0.0,1739137667.1644006,8.939991474151611,0.04493784662372846,1739137667.1644037,8.939991474151611,0.005559710016597531,1739137667.1644063,8.939991474151611,2.325055877583187 +1739137667.1834915,8.959991455078125,17.27460787925969,1739137667.1834948,8.959991455078125,-0.2919447650343141,1739137667.1834989,8.959991455078125,16.47909587713166,1739137667.1835022,8.959991455078125,25.447956592041354,1739137667.1835039,8.959991455078125,-0.11299222282893208,1739137667.183506,8.959991455078125,0.021891144201674876,1739137667.1835077,8.959991455078125,0.13350856186145257,1739137667.1835096,8.959991455078125,0.03068152870920659,1739137667.1835115,8.959991455078125,2.3699937242069153,1739137667.1835134,8.959991455078125,0.0,1739137667.1835148,8.959991455078125,0.04493784662372846,1739137667.183517,8.959991455078125,0.005559710016597531,1739137667.1835186,8.959991455078125,2.325055877583187 +1739137667.2033741,8.979991436004639,17.530607034271718,1739137667.2033765,8.979991436004639,-0.2904291280416045,1739137667.2033794,8.979991436004639,16.650620893748304,1739137667.203382,8.979991436004639,25.634289701049482,1739137667.203383,8.979991436004639,-0.112,1739137667.2033849,8.979991436004639,0.02201471964616707,1739137667.2033865,8.979991436004639,0.1269436887387421,1739137667.2033877,8.979991436004639,0.02967650919982158,1739137667.203389,8.979991436004639,2.3762253858800513,1739137667.2033904,8.979991436004639,0.0,1739137667.2033918,8.979991436004639,0.04740875818939633,1739137667.2033932,8.979991436004639,0.006352936936256232,1739137667.2033944,8.979991436004639,2.3299932528335106 +1739137667.2233803,8.999991416931152,17.530607034271718,1739137667.2233825,8.999991416931152,-0.2904291280416045,1739137667.223385,8.999991416931152,16.650620893748304,1739137667.2233877,8.999991416931152,25.634289701049482,1739137667.223389,8.999991416931152,-0.112,1739137667.22339,8.999991416931152,0.02201471964616707,1739137667.2233915,8.999991416931152,0.1269436887387421,1739137667.2233927,8.999991416931152,0.02967650919982158,1739137667.2233942,8.999991416931152,2.3762253858800513,1739137667.2233956,8.999991416931152,0.0,1739137667.2233965,8.999991416931152,0.046232133046540724,1739137667.2233982,8.999991416931152,0.006352936936256232,1739137667.2233994,8.999991416931152,2.3299932528335106 +1739137667.2434042,9.019991397857666,17.530607034271718,1739137667.2434068,9.019991397857666,-0.2904291280416045,1739137667.2434096,9.019991397857666,16.650620893748304,1739137667.243412,9.019991397857666,25.634289701049482,1739137667.2434134,9.019991397857666,-0.112,1739137667.243415,9.019991397857666,0.02201471964616707,1739137667.2434165,9.019991397857666,0.1269436887387421,1739137667.2434182,9.019991397857666,0.02967650919982158,1739137667.2434194,9.019991397857666,2.3762253858800513,1739137667.2434208,9.019991397857666,0.0,1739137667.2434223,9.019991397857666,0.046232133046540724,1739137667.243424,9.019991397857666,0.006352936936256232,1739137667.2434254,9.019991397857666,2.3299932528335106 +1739137667.2634122,9.03999137878418,17.530607034271718,1739137667.2634146,9.03999137878418,-0.2904291280416045,1739137667.2634172,9.03999137878418,16.650620893748304,1739137667.2634199,9.03999137878418,25.634289701049482,1739137667.2634213,9.03999137878418,-0.112,1739137667.263423,9.03999137878418,0.02201471964616707,1739137667.2634242,9.03999137878418,0.1269436887387421,1739137667.2634254,9.03999137878418,0.02967650919982158,1739137667.2634265,9.03999137878418,2.3762253858800513,1739137667.2634282,9.03999137878418,0.0,1739137667.2634294,9.03999137878418,0.046232133046540724,1739137667.2634308,9.03999137878418,0.006352936936256232,1739137667.2634323,9.03999137878418,2.3299932528335106 +1739137667.2840374,9.059991359710693,17.530607034271718,1739137667.2840397,9.059991359710693,-0.2904291280416045,1739137667.2840424,9.059991359710693,16.650620893748304,1739137667.2840447,9.059991359710693,25.634289701049482,1739137667.2840462,9.059991359710693,-0.112,1739137667.2840476,9.059991359710693,0.02201471964616707,1739137667.2840488,9.059991359710693,0.1269436887387421,1739137667.2840502,9.059991359710693,0.02967650919982158,1739137667.2840512,9.059991359710693,2.3762253858800513,1739137667.2840528,9.059991359710693,0.0,1739137667.2840538,9.059991359710693,0.046232133046540724,1739137667.2840552,9.059991359710693,0.006352936936256232,1739137667.2840564,9.059991359710693,2.3299932528335106 +1739137667.3035738,9.079991340637207,17.78715427441165,1739137667.303577,9.079991340637207,-0.2887067370187353,1739137667.3035796,9.079991340637207,16.90851016234635,1739137667.3035822,9.079991340637207,25.9073744236447,1739137667.3035834,9.079991340637207,-0.113,1739137667.3035853,9.079991340637207,0.021634797937375036,1739137667.3035867,9.079991340637207,0.11767432073422925,1739137667.3035882,9.079991340637207,0.027398194230839633,1739137667.3035893,9.079991340637207,2.385052182558634,1739137667.3035913,9.079991340637207,0.0,1739137667.3035922,9.079991340637207,0.05341024536419908,1739137667.3035936,9.079991340637207,0.007146163855914933,1739137667.303595,9.079991340637207,2.335060087624645 +1739137667.3231783,9.09999132156372,17.78715427441165,1739137667.323181,9.09999132156372,-0.2887067370187353,1739137667.3231838,9.09999132156372,16.90851016234635,1739137667.3231866,9.09999132156372,25.9073744236447,1739137667.323188,9.09999132156372,-0.113,1739137667.3231895,9.09999132156372,0.021634797937375036,1739137667.323191,9.09999132156372,0.11767432073422925,1739137667.3231924,9.09999132156372,0.027398194230839633,1739137667.3231936,9.09999132156372,2.385052182558634,1739137667.323195,9.09999132156372,0.0,1739137667.3231964,9.09999132156372,0.04999209493398915,1739137667.3231976,9.09999132156372,0.007146163855914933,1739137667.323199,9.09999132156372,2.335060087624645 +1739137667.3431497,9.119991302490234,17.78715427441165,1739137667.3431518,9.119991302490234,-0.2887067370187353,1739137667.3431544,9.119991302490234,16.90851016234635,1739137667.3431568,9.119991302490234,25.9073744236447,1739137667.343158,9.119991302490234,-0.113,1739137667.3431594,9.119991302490234,0.021634797937375036,1739137667.343161,9.119991302490234,0.11767432073422925,1739137667.3431623,9.119991302490234,0.027398194230839633,1739137667.3431635,9.119991302490234,2.385052182558634,1739137667.343165,9.119991302490234,0.0,1739137667.3431659,9.119991302490234,0.04999209493398915,1739137667.3431675,9.119991302490234,0.007146163855914933,1739137667.3431687,9.119991302490234,2.335060087624645 +1739137667.363273,9.139991283416748,17.78715427441165,1739137667.3632755,9.139991283416748,-0.2887067370187353,1739137667.3632786,9.139991283416748,16.90851016234635,1739137667.3632812,9.139991283416748,25.9073744236447,1739137667.3632824,9.139991283416748,-0.113,1739137667.363284,9.139991283416748,0.021634797937375036,1739137667.363286,9.139991283416748,0.11767432073422925,1739137667.3632874,9.139991283416748,0.027398194230839633,1739137667.3632889,9.139991283416748,2.385052182558634,1739137667.3632903,9.139991283416748,0.0,1739137667.3632917,9.139991283416748,0.04999209493398915,1739137667.363293,9.139991283416748,0.007146163855914933,1739137667.3632946,9.139991283416748,2.335060087624645 +1739137667.3832288,9.159991264343262,17.78715427441165,1739137667.3832316,9.159991264343262,-0.2887067370187353,1739137667.3832343,9.159991264343262,16.90851016234635,1739137667.3832371,9.159991264343262,25.9073744236447,1739137667.3832383,9.159991264343262,-0.113,1739137667.3832402,9.159991264343262,0.021634797937375036,1739137667.3832414,9.159991264343262,0.11767432073422925,1739137667.3832428,9.159991264343262,0.027398194230839633,1739137667.3832443,9.159991264343262,2.385052182558634,1739137667.3832455,9.159991264343262,0.0,1739137667.383247,9.159991264343262,0.04999209493398915,1739137667.3832486,9.159991264343262,0.007146163855914933,1739137667.38325,9.159991264343262,2.335060087624645 +1739137667.4031312,9.179991245269775,17.78715427441165,1739137667.4031332,9.179991245269775,-0.2887067370187353,1739137667.4031363,9.179991245269775,16.90851016234635,1739137667.4031389,9.179991245269775,25.9073744236447,1739137667.40314,9.179991245269775,-0.113,1739137667.403142,9.179991245269775,0.021634797937375036,1739137667.4031434,9.179991245269775,0.11767432073422925,1739137667.4031446,9.179991245269775,0.027398194230839633,1739137667.4031458,9.179991245269775,2.385052182558634,1739137667.4031472,9.179991245269775,0.0,1739137667.4031487,9.179991245269775,0.04999209493398915,1739137667.40315,9.179991245269775,0.007146163855914933,1739137667.4031513,9.179991245269775,2.335060087624645 +1739137667.4231644,9.199991226196289,18.044284260111926,1739137667.4231672,9.199991226196289,-0.2867764577334686,1739137667.42317,9.199991226196289,17.190803621570627,1739137667.4231732,9.199991226196289,26.206284857268745,1739137667.4231744,9.199991226196289,-0.112,1739137667.4231763,9.199991226196289,0.021410161551043964,1739137667.4231777,9.199991226196289,0.10997031786600825,1739137667.4231791,9.199991226196289,0.025343350309939554,1739137667.4231806,9.199991226196289,2.392413298286828,1739137667.423182,9.199991226196289,0.0,1739137667.4231834,9.199991226196289,0.053468110574312146,1739137667.4231853,9.199991226196289,0.007939390775573634,1739137667.423187,9.199991226196289,2.3406004340823947 +1739137667.4442906,9.219991207122803,18.044284260111926,1739137667.4442942,9.219991207122803,-0.2867764577334686,1739137667.4442985,9.219991207122803,17.190803621570627,1739137667.4443026,9.219991207122803,26.206284857268745,1739137667.4443047,9.219991207122803,-0.112,1739137667.444307,9.219991207122803,0.021410161551043964,1739137667.4443092,9.219991207122803,0.10997031786600825,1739137667.4443114,9.219991207122803,0.025343350309939554,1739137667.444313,9.219991207122803,2.392413298286828,1739137667.4443154,9.219991207122803,0.0,1739137667.4443173,9.219991207122803,0.05181286420443332,1739137667.4443195,9.219991207122803,0.007939390775573634,1739137667.4443216,9.219991207122803,2.3406004340823947 +1739137667.4639452,9.239991188049316,18.044284260111926,1739137667.463949,9.239991188049316,-0.2867764577334686,1739137667.4639535,9.239991188049316,17.190803621570627,1739137667.4639575,9.239991188049316,26.206284857268745,1739137667.4639595,9.239991188049316,-0.112,1739137667.463962,9.239991188049316,0.021410161551043964,1739137667.4639642,9.239991188049316,0.10997031786600825,1739137667.4639661,9.239991188049316,0.025343350309939554,1739137667.463968,9.239991188049316,2.392413298286828,1739137667.4639707,9.239991188049316,0.0,1739137667.4639726,9.239991188049316,0.05181286420443332,1739137667.4639747,9.239991188049316,0.007939390775573634,1739137667.4639766,9.239991188049316,2.3406004340823947 +1739137667.4840078,9.25999116897583,18.044284260111926,1739137667.484012,9.25999116897583,-0.2867764577334686,1739137667.4840167,9.25999116897583,17.190803621570627,1739137667.4840205,9.25999116897583,26.206284857268745,1739137667.4840226,9.25999116897583,-0.112,1739137667.484025,9.25999116897583,0.021410161551043964,1739137667.4840271,9.25999116897583,0.10997031786600825,1739137667.4840293,9.25999116897583,0.025343350309939554,1739137667.484031,9.25999116897583,2.392413298286828,1739137667.4840333,9.25999116897583,0.0,1739137667.4840353,9.25999116897583,0.05181286420443332,1739137667.4840379,9.25999116897583,0.007939390775573634,1739137667.48404,9.25999116897583,2.3406004340823947 +1739137667.5039597,9.279991149902344,18.044284260111926,1739137667.503963,9.279991149902344,-0.2867764577334686,1739137667.5039673,9.279991149902344,17.190803621570627,1739137667.5039713,9.279991149902344,26.206284857268745,1739137667.503973,9.279991149902344,-0.112,1739137667.5039756,9.279991149902344,0.021410161551043964,1739137667.5039778,9.279991149902344,0.10997031786600825,1739137667.5039797,9.279991149902344,0.025343350309939554,1739137667.5039816,9.279991149902344,2.392413298286828,1739137667.5039835,9.279991149902344,0.0,1739137667.5039856,9.279991149902344,0.05181286420443332,1739137667.5039878,9.279991149902344,0.007939390775573634,1739137667.5039897,9.279991149902344,2.3406004340823947 +1739137667.523745,9.299991130828857,18.302026024324803,1739137667.5237484,9.299991130828857,-0.2846371241605663,1739137667.523752,9.299991130828857,17.430346635614356,1739137667.5237558,9.299991130828857,26.46286667798235,1739137667.5237575,9.299991130828857,-0.11081568617210542,1739137667.5237596,9.299991130828857,0.02129623244125734,1739137667.5237615,9.299991130828857,0.10255021460427781,1739137667.5237634,9.299991130828857,0.023640247743908882,1739137667.523765,9.299991130828857,2.3995246279136024,1739137667.5237668,9.299991130828857,0.0,1739137667.5237687,9.299991130828857,0.05454275308401788,1739137667.5237706,9.299991130828857,0.008732617695232335,1739137667.5237722,9.299991130828857,2.3462818225644817 +1739137667.5431414,9.319991111755371,18.302026024324803,1739137667.543144,9.319991111755371,-0.2846371241605663,1739137667.5431466,9.319991111755371,17.430346635614356,1739137667.543149,9.319991111755371,26.46286667798235,1739137667.5431504,9.319991111755371,-0.11081568617210542,1739137667.5431519,9.319991111755371,0.02129623244125734,1739137667.543153,9.319991111755371,0.10255021460427781,1739137667.5431545,9.319991111755371,0.023640247743908882,1739137667.5431554,9.319991111755371,2.3995246279136024,1739137667.543157,9.319991111755371,0.0,1739137667.5431583,9.319991111755371,0.053242805349120736,1739137667.5431595,9.319991111755371,0.008732617695232335,1739137667.543161,9.319991111755371,2.3462818225644817 +1739137667.563069,9.339991092681885,18.302026024324803,1739137667.5630715,9.339991092681885,-0.2846371241605663,1739137667.563074,9.339991092681885,17.430346635614356,1739137667.563077,9.339991092681885,26.46286667798235,1739137667.5630782,9.339991092681885,-0.11081568617210542,1739137667.5630798,9.339991092681885,0.02129623244125734,1739137667.5630813,9.339991092681885,0.10255021460427781,1739137667.5630825,9.339991092681885,0.023640247743908882,1739137667.563084,9.339991092681885,2.3995246279136024,1739137667.5630853,9.339991092681885,0.0,1739137667.5630865,9.339991092681885,0.053242805349120736,1739137667.5630882,9.339991092681885,0.008732617695232335,1739137667.5630894,9.339991092681885,2.3462818225644817 +1739137667.5834017,9.359991073608398,18.302026024324803,1739137667.5834067,9.359991073608398,-0.2846371241605663,1739137667.5834107,9.359991073608398,17.430346635614356,1739137667.5834146,9.359991073608398,26.46286667798235,1739137667.5834177,9.359991073608398,-0.11081568617210542,1739137667.5834205,9.359991073608398,0.02129623244125734,1739137667.583423,9.359991073608398,0.10255021460427781,1739137667.583425,9.359991073608398,0.023640247743908882,1739137667.5834274,9.359991073608398,2.3995246279136024,1739137667.5834293,9.359991073608398,0.0,1739137667.583432,9.359991073608398,0.053242805349120736,1739137667.5834346,9.359991073608398,0.008732617695232335,1739137667.5834363,9.359991073608398,2.3462818225644817 +1739137667.603604,9.379991054534912,18.302026024324803,1739137667.6036077,9.379991054534912,-0.2846371241605663,1739137667.6036115,9.379991054534912,17.430346635614356,1739137667.603615,9.379991054534912,26.46286667798235,1739137667.6036165,9.379991054534912,-0.11081568617210542,1739137667.6036186,9.379991054534912,0.02129623244125734,1739137667.6036203,9.379991054534912,0.10255021460427781,1739137667.603622,9.379991054534912,0.023640247743908882,1739137667.6036234,9.379991054534912,2.3995246279136024,1739137667.6036253,9.379991054534912,0.0,1739137667.6036267,9.379991054534912,0.053242805349120736,1739137667.6036286,9.379991054534912,0.008732617695232335,1739137667.60363,9.379991054534912,2.3462818225644817 +1739137667.6232917,9.399991035461426,18.302026024324803,1739137667.6232948,9.399991035461426,-0.2846371241605663,1739137667.623298,9.399991035461426,17.430346635614356,1739137667.623301,9.399991035461426,26.46286667798235,1739137667.623303,9.399991035461426,-0.11081568617210542,1739137667.6233048,9.399991035461426,0.02129623244125734,1739137667.6233068,9.399991035461426,0.10255021460427781,1739137667.6233082,9.399991035461426,0.023640247743908882,1739137667.6233099,9.399991035461426,2.3995246279136024,1739137667.6233115,9.399991035461426,0.0,1739137667.6233134,9.399991035461426,0.053242805349120736,1739137667.6233156,9.399991035461426,0.008732617695232335,1739137667.623317,9.399991035461426,2.3462818225644817 +1739137667.6435292,9.41999101638794,18.5604007804334,1739137667.6435359,9.41999101638794,-0.28228757024953843,1739137667.643543,9.41999101638794,17.805643385080927,1739137667.6435513,9.41999101638794,26.855700010549516,1739137667.6435544,9.41999101638794,-0.10653902430447547,1739137667.6435592,9.41999101638794,0.021183353624792324,1739137667.6435633,9.41999101638794,0.09672203570187127,1739137667.6435688,9.41999101638794,0.021579935521295935,1739137667.6435757,9.41999101638794,2.4051250970091873,1739137667.6435797,9.41999101638794,0.0,1739137667.6435833,9.41999101638794,0.0527584913301281,1739137667.6435874,9.41999101638794,0.009525844614891036,1739137667.6435912,9.41999101638794,2.3521359798405217 +1739137667.6634316,9.439990997314453,18.5604007804334,1739137667.6634345,9.439990997314453,-0.28228757024953843,1739137667.6634378,9.439990997314453,17.805643385080927,1739137667.6634412,9.439990997314453,26.855700010549516,1739137667.6634426,9.439990997314453,-0.10653902430447547,1739137667.6634448,9.439990997314453,0.021183353624792324,1739137667.6634464,9.439990997314453,0.09672203570187127,1739137667.6634483,9.439990997314453,0.021579935521295935,1739137667.6634495,9.439990997314453,2.4051250970091873,1739137667.6634517,9.439990997314453,0.0,1739137667.663453,9.439990997314453,0.05298911716866561,1739137667.663455,9.439990997314453,0.009525844614891036,1739137667.6634564,9.439990997314453,2.3521359798405217 +1739137667.683507,9.459990978240967,18.5604007804334,1739137667.6835105,9.459990978240967,-0.28228757024953843,1739137667.6835139,9.459990978240967,17.805643385080927,1739137667.6835172,9.459990978240967,26.855700010549516,1739137667.6835186,9.459990978240967,-0.10653902430447547,1739137667.6835208,9.459990978240967,0.021183353624792324,1739137667.6835225,9.459990978240967,0.09672203570187127,1739137667.6835241,9.459990978240967,0.021579935521295935,1739137667.6835256,9.459990978240967,2.4051250970091873,1739137667.6835275,9.459990978240967,0.0,1739137667.683529,9.459990978240967,0.05298911716866561,1739137667.683531,9.459990978240967,0.009525844614891036,1739137667.6835327,9.459990978240967,2.3521359798405217 +1739137667.70352,9.47999095916748,18.5604007804334,1739137667.703523,9.47999095916748,-0.28228757024953843,1739137667.7035265,9.47999095916748,17.805643385080927,1739137667.7035294,9.47999095916748,26.855700010549516,1739137667.7035313,9.47999095916748,-0.10653902430447547,1739137667.7035332,9.47999095916748,0.021183353624792324,1739137667.7035348,9.47999095916748,0.09672203570187127,1739137667.7035363,9.47999095916748,0.021579935521295935,1739137667.703538,9.47999095916748,2.4051250970091873,1739137667.7035396,9.47999095916748,0.0,1739137667.7035413,9.47999095916748,0.05298911716866561,1739137667.703543,9.47999095916748,0.009525844614891036,1739137667.7035446,9.47999095916748,2.3521359798405217 +1739137667.7235136,9.499990940093994,18.5604007804334,1739137667.7235172,9.499990940093994,-0.28228757024953843,1739137667.723521,9.499990940093994,17.805643385080927,1739137667.7235243,9.499990940093994,26.855700010549516,1739137667.7235265,9.499990940093994,-0.10653902430447547,1739137667.7235284,9.499990940093994,0.021183353624792324,1739137667.7235303,9.499990940093994,0.09672203570187127,1739137667.7235317,9.499990940093994,0.021579935521295935,1739137667.7235336,9.499990940093994,2.4051250970091873,1739137667.7235353,9.499990940093994,0.0,1739137667.7235372,9.499990940093994,0.05298911716866561,1739137667.7235389,9.499990940093994,0.009525844614891036,1739137667.7235405,9.499990940093994,2.3521359798405217 +1739137667.7440853,9.519990921020508,18.81941296226048,1739137667.7440882,9.519990921020508,-0.27972674638077333,1739137667.7440915,9.519990921020508,18.1216487975429,1739137667.7440946,9.519990921020508,27.18905221633813,1739137667.7440963,9.519990921020508,-0.10282884376960869,1739137667.7440982,9.519990921020508,0.02113251996120381,1739137667.7441,9.519990921020508,0.09052311094599627,1739137667.7441013,9.519990921020508,0.01983978277174046,1739137667.744103,9.519990921020508,2.411096172601466,1739137667.7441046,9.519990921020508,0.0,1739137667.7441063,9.519990921020508,0.05332925686240791,1739137667.744108,9.519990921020508,0.010319071534549737,1739137667.7441096,9.519990921020508,2.3579288871027044 +1739137667.7634442,9.539990901947021,18.81941296226048,1739137667.7634475,9.539990901947021,-0.27972674638077333,1739137667.763451,9.539990901947021,18.1216487975429,1739137667.7634547,9.539990901947021,27.18905221633813,1739137667.7634563,9.539990901947021,-0.10282884376960869,1739137667.7634583,9.539990901947021,0.02113251996120381,1739137667.76346,9.539990901947021,0.09052311094599627,1739137667.7634614,9.539990901947021,0.01983978277174046,1739137667.7634633,9.539990901947021,2.411096172601466,1739137667.763465,9.539990901947021,0.0,1739137667.7634666,9.539990901947021,0.05316728549876171,1739137667.7634683,9.539990901947021,0.010319071534549737,1739137667.7634702,9.539990901947021,2.3579288871027044 +1739137667.7835352,9.559990882873535,18.81941296226048,1739137667.7835386,9.559990882873535,-0.27972674638077333,1739137667.7835422,9.559990882873535,18.1216487975429,1739137667.783546,9.559990882873535,27.18905221633813,1739137667.7835476,9.559990882873535,-0.10282884376960869,1739137667.78355,9.559990882873535,0.02113251996120381,1739137667.7835515,9.559990882873535,0.09052311094599627,1739137667.7835531,9.559990882873535,0.01983978277174046,1739137667.7835548,9.559990882873535,2.411096172601466,1739137667.7835572,9.559990882873535,0.0,1739137667.7835588,9.559990882873535,0.05316728549876171,1739137667.7835608,9.559990882873535,0.010319071534549737,1739137667.7835624,9.559990882873535,2.3579288871027044 +1739137667.803806,9.579990863800049,18.81941296226048,1739137667.803809,9.579990863800049,-0.27972674638077333,1739137667.803812,9.579990863800049,18.1216487975429,1739137667.8038154,9.579990863800049,27.18905221633813,1739137667.8038173,9.579990863800049,-0.10282884376960869,1739137667.803819,9.579990863800049,0.02113251996120381,1739137667.8038208,9.579990863800049,0.09052311094599627,1739137667.8038223,9.579990863800049,0.01983978277174046,1739137667.8038242,9.579990863800049,2.411096172601466,1739137667.8038259,9.579990863800049,0.0,1739137667.8038275,9.579990863800049,0.05316728549876171,1739137667.8038292,9.579990863800049,0.010319071534549737,1739137667.8038309,9.579990863800049,2.3579288871027044 +1739137667.8235369,9.599990844726562,18.81941296226048,1739137667.8235402,9.599990844726562,-0.27972674638077333,1739137667.8235438,9.599990844726562,18.1216487975429,1739137667.8235471,9.599990844726562,27.18905221633813,1739137667.823549,9.599990844726562,-0.10282884376960869,1739137667.8235507,9.599990844726562,0.02113251996120381,1739137667.8235526,9.599990844726562,0.09052311094599627,1739137667.823554,9.599990844726562,0.01983978277174046,1739137667.8235555,9.599990844726562,2.411096172601466,1739137667.8235576,9.599990844726562,0.0,1739137667.8235593,9.599990844726562,0.05316728549876171,1739137667.8235612,9.599990844726562,0.010319071534549737,1739137667.823563,9.599990844726562,2.3579288871027044 +1739137667.8437476,9.619990825653076,18.81941296226048,1739137667.8437505,9.619990825653076,-0.27972674638077333,1739137667.8437536,9.619990825653076,18.1216487975429,1739137667.8437564,9.619990825653076,27.18905221633813,1739137667.843758,9.619990825653076,-0.10282884376960869,1739137667.84376,9.619990825653076,0.02113251996120381,1739137667.8437617,9.619990825653076,0.09052311094599627,1739137667.8437634,9.619990825653076,0.01983978277174046,1739137667.843765,9.619990825653076,2.411096172601466,1739137667.8437667,9.619990825653076,0.0,1739137667.8437684,9.619990825653076,0.05316728549876171,1739137667.84377,9.619990825653076,0.010319071534549737,1739137667.843772,9.619990825653076,2.3579288871027044 +1739137667.8636668,9.63999080657959,19.079062200491016,1739137667.8636703,9.63999080657959,-0.27695364135206013,1739137667.8636742,9.63999080657959,18.4705675963616,1739137667.8636775,9.63999080657959,27.555417169992623,1739137667.8636792,9.63999080657959,-0.099,1739137667.8636816,9.63999080657959,0.02099103970487921,1739137667.863683,9.63999080657959,0.0837528066045802,1739137667.863685,9.63999080657959,0.017896816587300135,1739137667.8636863,9.63999080657959,2.4176345639392878,1739137667.8636887,9.63999080657959,0.0,1739137667.8636901,9.63999080657959,0.05453251436282097,1739137667.8636923,9.63999080657959,0.011112298454208438,1739137667.8636942,9.63999080657959,2.36375215888411 +1739137667.8835154,9.659990787506104,19.079062200491016,1739137667.8835192,9.659990787506104,-0.27695364135206013,1739137667.8835232,9.659990787506104,18.4705675963616,1739137667.8835268,9.659990787506104,27.555417169992623,1739137667.8835285,9.659990787506104,-0.099,1739137667.8835309,9.659990787506104,0.02099103970487921,1739137667.8835323,9.659990787506104,0.0837528066045802,1739137667.8835344,9.659990787506104,0.017896816587300135,1739137667.8835356,9.659990787506104,2.4176345639392878,1739137667.8835378,9.659990787506104,0.0,1739137667.8835392,9.659990787506104,0.05388240505517761,1739137667.8835413,9.659990787506104,0.011112298454208438,1739137667.8835428,9.659990787506104,2.36375215888411 +1739137667.9034064,9.679990768432617,19.079062200491016,1739137667.9034092,9.679990768432617,-0.27695364135206013,1739137667.9034126,9.679990768432617,18.4705675963616,1739137667.903416,9.679990768432617,27.555417169992623,1739137667.9034173,9.679990768432617,-0.099,1739137667.9034195,9.679990768432617,0.02099103970487921,1739137667.9034212,9.679990768432617,0.0837528066045802,1739137667.9034228,9.679990768432617,0.017896816587300135,1739137667.9034243,9.679990768432617,2.4176345639392878,1739137667.903426,9.679990768432617,0.0,1739137667.9034276,9.679990768432617,0.05388240505517761,1739137667.9034293,9.679990768432617,0.011112298454208438,1739137667.903431,9.679990768432617,2.36375215888411 +1739137667.9234443,9.69999074935913,19.079062200491016,1739137667.9234476,9.69999074935913,-0.27695364135206013,1739137667.923451,9.69999074935913,18.4705675963616,1739137667.9234543,9.69999074935913,27.555417169992623,1739137667.9234557,9.69999074935913,-0.099,1739137667.9234579,9.69999074935913,0.02099103970487921,1739137667.9234598,9.69999074935913,0.0837528066045802,1739137667.9234614,9.69999074935913,0.017896816587300135,1739137667.9234629,9.69999074935913,2.4176345639392878,1739137667.923465,9.69999074935913,0.0,1739137667.9234667,9.69999074935913,0.05388240505517761,1739137667.9234688,9.69999074935913,0.011112298454208438,1739137667.9234705,9.69999074935913,2.36375215888411 +1739137667.9443765,9.719990730285645,19.079062200491016,1739137667.944381,9.719990730285645,-0.27695364135206013,1739137667.9443862,9.719990730285645,18.4705675963616,1739137667.9443917,9.719990730285645,27.555417169992623,1739137667.9443946,9.719990730285645,-0.099,1739137667.9443982,9.719990730285645,0.02099103970487921,1739137667.9444013,9.719990730285645,0.0837528066045802,1739137667.944404,9.719990730285645,0.017896816587300135,1739137667.944407,9.719990730285645,2.4176345639392878,1739137667.94441,9.719990730285645,0.0,1739137667.9444127,9.719990730285645,0.05388240505517761,1739137667.9444158,9.719990730285645,0.011112298454208438,1739137667.944419,9.719990730285645,2.36375215888411 +1739137667.9634163,9.739990711212158,19.339353114528738,1739137667.9634197,9.739990711212158,-0.27396718749866533,1739137667.9634228,9.739990711212158,18.501808478953834,1739137667.9634259,9.739990711212158,27.604351883232834,1739137667.9634273,9.739990711212158,-0.09861845150240692,1739137667.9634292,9.739990711212158,0.021212638888786804,1739137667.9634306,9.739990711212158,0.07693948101247755,1739137667.963432,9.739990711212158,0.0172923746065312,1739137667.9634335,9.739990711212158,2.424232403079531,1739137667.9634352,9.739990711212158,0.0,1739137667.9634368,9.739990711212158,0.055217476283737195,1739137667.9634385,9.739990711212158,0.011905525373867139,1739137667.96344,9.739990711212158,2.369650675317454 +1739137667.9836648,9.759990692138672,19.339353114528738,1739137667.9836674,9.759990692138672,-0.27396718749866533,1739137667.9836707,9.759990692138672,18.501808478953834,1739137667.9836738,9.759990692138672,27.604351883232834,1739137667.9836752,9.759990692138672,-0.09861845150240692,1739137667.9836771,9.759990692138672,0.021212638888786804,1739137667.9836788,9.759990692138672,0.07693948101247755,1739137667.98368,9.759990692138672,0.0172923746065312,1739137667.9836814,9.759990692138672,2.424232403079531,1739137667.983683,9.759990692138672,0.0,1739137667.9836843,9.759990692138672,0.05458172776207704,1739137667.9836862,9.759990692138672,0.011905525373867139,1739137667.9836876,9.759990692138672,2.369650675317454 +1739137668.0032976,9.779990673065186,19.339353114528738,1739137668.0033007,9.779990673065186,-0.27396718749866533,1739137668.0033035,9.779990673065186,18.501808478953834,1739137668.0033064,9.779990673065186,27.604351883232834,1739137668.0033078,9.779990673065186,-0.09861845150240692,1739137668.0033097,9.779990673065186,0.021212638888786804,1739137668.0033114,9.779990673065186,0.07693948101247755,1739137668.0033126,9.779990673065186,0.0172923746065312,1739137668.003314,9.779990673065186,2.424232403079531,1739137668.0033157,9.779990673065186,0.0,1739137668.0033169,9.779990673065186,0.05458172776207704,1739137668.0033188,9.779990673065186,0.011905525373867139,1739137668.00332,9.779990673065186,2.369650675317454 +1739137668.0236635,9.7999906539917,19.339353114528738,1739137668.0236669,9.7999906539917,-0.27396718749866533,1739137668.02367,9.7999906539917,18.501808478953834,1739137668.023673,9.7999906539917,27.604351883232834,1739137668.0236742,9.7999906539917,-0.09861845150240692,1739137668.0236764,9.7999906539917,0.021212638888786804,1739137668.0236776,9.7999906539917,0.07693948101247755,1739137668.0236793,9.7999906539917,0.0172923746065312,1739137668.0236807,9.7999906539917,2.424232403079531,1739137668.0236828,9.7999906539917,0.0,1739137668.023684,9.7999906539917,0.05458172776207704,1739137668.023686,9.7999906539917,0.011905525373867139,1739137668.0236874,9.7999906539917,2.369650675317454 +1739137668.043424,9.819990634918213,19.339353114528738,1739137668.0434265,9.819990634918213,-0.27396718749866533,1739137668.04343,9.819990634918213,18.501808478953834,1739137668.043433,9.819990634918213,27.604351883232834,1739137668.0434344,9.819990634918213,-0.09861845150240692,1739137668.0434365,9.819990634918213,0.021212638888786804,1739137668.0434382,9.819990634918213,0.07693948101247755,1739137668.0434396,9.819990634918213,0.0172923746065312,1739137668.043441,9.819990634918213,2.424232403079531,1739137668.043443,9.819990634918213,0.0,1739137668.0434442,9.819990634918213,0.05458172776207704,1739137668.043446,9.819990634918213,0.011905525373867139,1739137668.0434473,9.819990634918213,2.369650675317454 +1739137668.063347,9.839990615844727,19.339353114528738,1739137668.0633512,9.839990615844727,-0.27396718749866533,1739137668.0633543,9.839990615844727,18.501808478953834,1739137668.0633574,9.839990615844727,27.604351883232834,1739137668.063359,9.839990615844727,-0.09861845150240692,1739137668.063361,9.839990615844727,0.021212638888786804,1739137668.063363,9.839990615844727,0.07693948101247755,1739137668.0633643,9.839990615844727,0.0172923746065312,1739137668.0633662,9.839990615844727,2.424232403079531,1739137668.0633678,9.839990615844727,0.0,1739137668.0633695,9.839990615844727,0.05458172776207704,1739137668.0633712,9.839990615844727,0.011905525373867139,1739137668.0633729,9.839990615844727,2.369650675317454 +1739137668.0834672,9.85999059677124,19.600295576746745,1739137668.0834703,9.85999059677124,-0.27076624187503473,1739137668.0834737,9.85999059677124,19.378076705664775,1739137668.0834768,9.85999059677124,28.49852662949062,1739137668.0834782,9.85999059677124,-0.08917601123368343,1739137668.0834801,9.85999059677124,0.020404620565192627,1739137668.0834816,9.85999059677124,0.06858219429303491,1739137668.083483,9.85999059677124,0.013298772595066559,1739137668.0834844,9.85999059677124,2.43234996578664,1739137668.0834858,9.85999059677124,0.0,1739137668.0834873,9.85999059677124,0.05864835738402536,1739137668.083489,9.85999059677124,0.01269875229352584,1739137668.0834904,9.85999059677124,2.3756380996661424 +1739137668.103424,9.879990577697754,19.600295576746745,1739137668.1034274,9.879990577697754,-0.27076624187503473,1739137668.1034307,9.879990577697754,19.378076705664775,1739137668.1034336,9.879990577697754,28.49852662949062,1739137668.1034353,9.879990577697754,-0.08917601123368343,1739137668.103437,9.879990577697754,0.020404620565192627,1739137668.1034386,9.879990577697754,0.06858219429303491,1739137668.10344,9.879990577697754,0.013298772595066559,1739137668.1034417,9.879990577697754,2.43234996578664,1739137668.1034434,9.879990577697754,0.0,1739137668.103445,9.879990577697754,0.0567118661204975,1739137668.1034467,9.879990577697754,0.01269875229352584,1739137668.1034484,9.879990577697754,2.3756380996661424 +1739137668.1233406,9.899990558624268,19.600295576746745,1739137668.1233435,9.899990558624268,-0.27076624187503473,1739137668.1233468,9.899990558624268,19.378076705664775,1739137668.1233497,9.899990558624268,28.49852662949062,1739137668.1233513,9.899990558624268,-0.08917601123368343,1739137668.1233532,9.899990558624268,0.020404620565192627,1739137668.123355,9.899990558624268,0.06858219429303491,1739137668.1233563,9.899990558624268,0.013298772595066559,1739137668.123358,9.899990558624268,2.43234996578664,1739137668.1233594,9.899990558624268,0.0,1739137668.123361,9.899990558624268,0.0567118661204975,1739137668.1233625,9.899990558624268,0.01269875229352584,1739137668.1233642,9.899990558624268,2.3756380996661424 +1739137668.1434746,9.919990539550781,19.600295576746745,1739137668.1434774,9.919990539550781,-0.27076624187503473,1739137668.1434805,9.919990539550781,19.378076705664775,1739137668.1434836,9.919990539550781,28.49852662949062,1739137668.143485,9.919990539550781,-0.08917601123368343,1739137668.143487,9.919990539550781,0.020404620565192627,1739137668.1434882,9.919990539550781,0.06858219429303491,1739137668.1434898,9.919990539550781,0.013298772595066559,1739137668.143491,9.919990539550781,2.43234996578664,1739137668.143493,9.919990539550781,0.0,1739137668.1434944,9.919990539550781,0.0567118661204975,1739137668.143496,9.919990539550781,0.01269875229352584,1739137668.1434975,9.919990539550781,2.3756380996661424 +1739137668.1893225,9.959990501403809,19.86190503309309,1739137668.1893325,9.959990501403809,-0.26734956366984886,1739137668.189344,9.959990501403809,19.40920823096999,1739137668.1893568,9.959990501403809,28.548315007162607,1739137668.1893616,9.959990501403809,-0.08876979668973489,1739137668.189372,9.959990501403809,0.020555628252132276,1739137668.1893814,9.959990501403809,0.06137020626259882,1739137668.1893876,9.959990501403809,0.012487690523384885,1739137668.1893923,9.959990501403809,2.4393769281227025,1739137668.1894011,9.959990501403809,0.0,1739137668.1894097,9.959990501403809,0.05825337979142449,1739137668.1894193,9.959990501403809,0.01349197921318454,1739137668.1894238,9.959990501403809,2.381857602826983 +1739137668.2054446,9.979990482330322,19.86190503309309,1739137668.2054486,9.979990482330322,-0.26734956366984886,1739137668.2054539,9.979990482330322,19.40920823096999,1739137668.20546,9.979990482330322,28.548315007162607,1739137668.2054634,9.979990482330322,-0.08876979668973489,1739137668.2054677,9.979990482330322,0.020555628252132276,1739137668.205472,9.979990482330322,0.06137020626259882,1739137668.2054758,9.979990482330322,0.012487690523384885,1739137668.2054799,9.979990482330322,2.4393769281227025,1739137668.2054844,9.979990482330322,0.0,1739137668.2054884,9.979990482330322,0.05751932529571935,1739137668.2054927,9.979990482330322,0.01349197921318454,1739137668.2054968,9.979990482330322,2.381857602826983 +1739137668.2234952,9.999990463256836,19.86190503309309,1739137668.2234976,9.999990463256836,-0.26734956366984886,1739137668.2235005,9.999990463256836,19.40920823096999,1739137668.2235034,9.999990463256836,28.548315007162607,1739137668.2235048,9.999990463256836,-0.08876979668973489,1739137668.2235065,9.999990463256836,0.020555628252132276,1739137668.2235076,9.999990463256836,0.06137020626259882,1739137668.2235093,9.999990463256836,0.012487690523384885,1739137668.2235105,9.999990463256836,2.4393769281227025,1739137668.2235122,9.999990463256836,0.0,1739137668.2235134,9.999990463256836,0.05751932529571935,1739137668.223515,9.999990463256836,0.01349197921318454,1739137668.2235165,9.999990463256836,2.381857602826983 +1739137668.2435887,10.01999044418335,19.86190503309309,1739137668.2435913,10.01999044418335,-0.26734956366984886,1739137668.2435942,10.01999044418335,19.40920823096999,1739137668.243597,10.01999044418335,28.548315007162607,1739137668.2435987,10.01999044418335,-0.08876979668973489,1739137668.2436004,10.01999044418335,0.020555628252132276,1739137668.2436016,10.01999044418335,0.06137020626259882,1739137668.243603,10.01999044418335,0.012487690523384885,1739137668.2436042,10.01999044418335,2.4393769281227025,1739137668.2436059,10.01999044418335,0.0,1739137668.243607,10.01999044418335,0.05751932529571935,1739137668.2436082,10.01999044418335,0.01349197921318454,1739137668.24361,10.01999044418335,2.381857602826983 +1739137668.2633562,10.039990425109863,19.86190503309309,1739137668.2633588,10.039990425109863,-0.26734956366984886,1739137668.2633612,10.039990425109863,19.40920823096999,1739137668.2633638,10.039990425109863,28.548315007162607,1739137668.263365,10.039990425109863,-0.08876979668973489,1739137668.2633667,10.039990425109863,0.020555628252132276,1739137668.263368,10.039990425109863,0.06137020626259882,1739137668.2633696,10.039990425109863,0.012487690523384885,1739137668.2633705,10.039990425109863,2.4393769281227025,1739137668.2633722,10.039990425109863,0.0,1739137668.2633739,10.039990425109863,0.05751932529571935,1739137668.263375,10.039990425109863,0.01349197921318454,1739137668.2633765,10.039990425109863,2.381857602826983 +1739137668.2832594,10.059990406036377,19.86190503309309,1739137668.2832618,10.059990406036377,-0.26734956366984886,1739137668.2832642,10.059990406036377,19.40920823096999,1739137668.283267,10.059990406036377,28.548315007162607,1739137668.2832685,10.059990406036377,-0.08876979668973489,1739137668.28327,10.059990406036377,0.020555628252132276,1739137668.2832713,10.059990406036377,0.06137020626259882,1739137668.2832727,10.059990406036377,0.012487690523384885,1739137668.283274,10.059990406036377,2.4393769281227025,1739137668.2832756,10.059990406036377,0.0,1739137668.2832768,10.059990406036377,0.05751932529571935,1739137668.283278,10.059990406036377,0.01349197921318454,1739137668.2832794,10.059990406036377,2.381857602826983 +1739137668.303449,10.07999038696289,20.124201013679556,1739137668.3034515,10.07999038696289,-0.2637158209860475,1739137668.3034546,10.07999038696289,19.44042145265978,1739137668.3034575,10.07999038696289,28.598459153811124,1739137668.3034592,10.07999038696289,-0.08836212070072258,1739137668.3034608,10.07999038696289,0.02068956080381923,1739137668.3034625,10.07999038696289,0.05428340150700759,1739137668.303464,10.07999038696289,0.011605578886378592,1739137668.3034651,10.07999038696289,2.446301693583741,1739137668.303467,10.07999038696289,0.0,1739137668.3034682,10.07999038696289,0.05869132579397353,1739137668.3034697,10.07999038696289,0.014285206132843242,1739137668.303471,10.07999038696289,2.38816846354392 +1739137668.323264,10.099990367889404,20.124201013679556,1739137668.323267,10.099990367889404,-0.2637158209860475,1739137668.3232703,10.099990367889404,19.44042145265978,1739137668.3232732,10.099990367889404,28.598459153811124,1739137668.3232749,10.099990367889404,-0.08836212070072258,1739137668.3232768,10.099990367889404,0.02068956080381923,1739137668.3232784,10.099990367889404,0.05428340150700759,1739137668.32328,10.099990367889404,0.011605578886378592,1739137668.323282,10.099990367889404,2.446301693583741,1739137668.3232834,10.099990367889404,0.0,1739137668.323285,10.099990367889404,0.05813323003982118,1739137668.3232875,10.099990367889404,0.014285206132843242,1739137668.3232894,10.099990367889404,2.38816846354392 +1739137668.3432388,10.119990348815918,20.124201013679556,1739137668.3432434,10.119990348815918,-0.2637158209860475,1739137668.343246,10.119990348815918,19.44042145265978,1739137668.3432488,10.119990348815918,28.598459153811124,1739137668.3432503,10.119990348815918,-0.08836212070072258,1739137668.343252,10.119990348815918,0.02068956080381923,1739137668.3432531,10.119990348815918,0.05428340150700759,1739137668.3432546,10.119990348815918,0.011605578886378592,1739137668.3432558,10.119990348815918,2.446301693583741,1739137668.3432574,10.119990348815918,0.0,1739137668.3432586,10.119990348815918,0.05813323003982118,1739137668.34326,10.119990348815918,0.014285206132843242,1739137668.3432617,10.119990348815918,2.38816846354392 +1739137668.3631601,10.139990329742432,20.124201013679556,1739137668.3631635,10.139990329742432,-0.2637158209860475,1739137668.3631666,10.139990329742432,19.44042145265978,1739137668.3631692,10.139990329742432,28.598459153811124,1739137668.3631709,10.139990329742432,-0.08836212070072258,1739137668.3631723,10.139990329742432,0.02068956080381923,1739137668.363174,10.139990329742432,0.05428340150700759,1739137668.3631752,10.139990329742432,0.011605578886378592,1739137668.3631768,10.139990329742432,2.446301693583741,1739137668.363178,10.139990329742432,0.0,1739137668.3631794,10.139990329742432,0.05813323003982118,1739137668.363181,10.139990329742432,0.014285206132843242,1739137668.3631823,10.139990329742432,2.38816846354392 +1739137668.383179,10.159990310668945,20.124201013679556,1739137668.3831823,10.159990310668945,-0.2637158209860475,1739137668.3831854,10.159990310668945,19.44042145265978,1739137668.3831882,10.159990310668945,28.598459153811124,1739137668.3831897,10.159990310668945,-0.08836212070072258,1739137668.3831916,10.159990310668945,0.02068956080381923,1739137668.3831928,10.159990310668945,0.05428340150700759,1739137668.3831944,10.159990310668945,0.011605578886378592,1739137668.3831956,10.159990310668945,2.446301693583741,1739137668.383197,10.159990310668945,0.0,1739137668.3831985,10.159990310668945,0.05813323003982118,1739137668.3832002,10.159990310668945,0.014285206132843242,1739137668.3832014,10.159990310668945,2.38816846354392 +1739137668.403236,10.179990291595459,20.387189846070264,1739137668.4032388,10.179990291595459,-0.25986382728680457,1739137668.4032416,10.179990291595459,19.996811527804546,1739137668.4032447,10.179990291595459,29.173908847417838,1739137668.4032462,10.179990291595459,-0.08339737707516579,1739137668.4032478,10.179990291595459,0.020080616055235406,1739137668.4032493,10.179990291595459,0.04396145615828733,1739137668.4032507,10.179990291595459,0.008742455834486296,1739137668.403252,10.179990291595459,2.4564228100833536,1739137668.4032536,10.179990291595459,0.0,1739137668.4032547,10.179990291595459,0.06530904067044666,1739137668.4032564,10.179990291595459,0.015078433052501942,1739137668.4032576,10.179990291595459,2.394530823801125 +1739137668.4231565,10.199990272521973,20.387189846070264,1739137668.4231598,10.199990272521973,-0.25986382728680457,1739137668.4231634,10.199990272521973,19.996811527804546,1739137668.4231665,10.199990272521973,29.173908847417838,1739137668.4231677,10.199990272521973,-0.08339737707516579,1739137668.4231694,10.199990272521973,0.020080616055235406,1739137668.4231708,10.199990272521973,0.04396145615828733,1739137668.4231722,10.199990272521973,0.008742455834486296,1739137668.423174,10.199990272521973,2.4564228100833536,1739137668.4231753,10.199990272521973,0.0,1739137668.4231768,10.199990272521973,0.06189198628222847,1739137668.4231784,10.199990272521973,0.015078433052501942,1739137668.4231799,10.199990272521973,2.394530823801125 +1739137668.4432065,10.219990253448486,20.387189846070264,1739137668.443209,10.219990253448486,-0.25986382728680457,1739137668.4432116,10.219990253448486,19.996811527804546,1739137668.4432142,10.219990253448486,29.173908847417838,1739137668.4432154,10.219990253448486,-0.08339737707516579,1739137668.443217,10.219990253448486,0.020080616055235406,1739137668.4432185,10.219990253448486,0.04396145615828733,1739137668.4432197,10.219990253448486,0.008742455834486296,1739137668.443221,10.219990253448486,2.4564228100833536,1739137668.4432228,10.219990253448486,0.0,1739137668.443224,10.219990253448486,0.06189198628222847,1739137668.4432254,10.219990253448486,0.015078433052501942,1739137668.4432268,10.219990253448486,2.394530823801125 +1739137668.4633427,10.239990234375,20.387189846070264,1739137668.4633458,10.239990234375,-0.25986382728680457,1739137668.4633484,10.239990234375,19.996811527804546,1739137668.4633512,10.239990234375,29.173908847417838,1739137668.463353,10.239990234375,-0.08339737707516579,1739137668.4633546,10.239990234375,0.020080616055235406,1739137668.4633563,10.239990234375,0.04396145615828733,1739137668.4633574,10.239990234375,0.008742455834486296,1739137668.4633586,10.239990234375,2.4564228100833536,1739137668.4633603,10.239990234375,0.0,1739137668.4633615,10.239990234375,0.06189198628222847,1739137668.4633632,10.239990234375,0.015078433052501942,1739137668.4633641,10.239990234375,2.394530823801125 +1739137668.4834237,10.259990215301514,20.387189846070264,1739137668.4834278,10.259990215301514,-0.25986382728680457,1739137668.483431,10.259990215301514,19.996811527804546,1739137668.483434,10.259990215301514,29.173908847417838,1739137668.4834356,10.259990215301514,-0.08339737707516579,1739137668.4834375,10.259990215301514,0.020080616055235406,1739137668.4834392,10.259990215301514,0.04396145615828733,1739137668.4834404,10.259990215301514,0.008742455834486296,1739137668.4834418,10.259990215301514,2.4564228100833536,1739137668.4834437,10.259990215301514,0.0,1739137668.4834452,10.259990215301514,0.06189198628222847,1739137668.483447,10.259990215301514,0.015078433052501942,1739137668.4834485,10.259990215301514,2.394530823801125 +1739137668.503301,10.279990196228027,20.387189846070264,1739137668.5033038,10.279990196228027,-0.25986382728680457,1739137668.5033076,10.279990196228027,19.996811527804546,1739137668.5033107,10.279990196228027,29.173908847417838,1739137668.503312,10.279990196228027,-0.08339737707516579,1739137668.5033145,10.279990196228027,0.020080616055235406,1739137668.5033162,10.279990196228027,0.04396145615828733,1739137668.5033178,10.279990196228027,0.008742455834486296,1739137668.5033195,10.279990196228027,2.4564228100833536,1739137668.5033214,10.279990196228027,0.0,1739137668.5033226,10.279990196228027,0.06189198628222847,1739137668.5033245,10.279990196228027,0.015078433052501942,1739137668.5033257,10.279990196228027,2.394530823801125 +1739137668.5231774,10.299990177154541,20.650902669584536,1739137668.52318,10.299990177154541,-0.25579199469592595,1739137668.523183,10.299990177154541,20.028193353802745,1739137668.523186,10.299990177154541,29.225817743970108,1739137668.5231874,10.299990177154541,-0.08312980544345305,1739137668.5231893,10.299990177154541,0.020133011029025413,1739137668.5231905,10.299990177154541,0.03654801972651784,1739137668.5231922,10.299990177154541,0.007631649680417062,1739137668.5231934,10.299990177154541,2.4637178347187754,1739137668.5231948,10.299990177154541,0.0,1739137668.5231965,10.299990177154541,0.06275573178122383,1739137668.523198,10.299990177154541,0.015871659972160643,1739137668.5231993,10.299990177154541,2.4013734105234916 +1739137668.543455,10.319990158081055,20.650902669584536,1739137668.543458,10.319990158081055,-0.25579199469592595,1739137668.5434613,10.319990158081055,20.028193353802745,1739137668.5434642,10.319990158081055,29.225817743970108,1739137668.5434656,10.319990158081055,-0.08312980544345305,1739137668.5434675,10.319990158081055,0.020133011029025413,1739137668.543469,10.319990158081055,0.03654801972651784,1739137668.5434704,10.319990158081055,0.007631649680417062,1739137668.5434718,10.319990158081055,2.4637178347187754,1739137668.5434735,10.319990158081055,0.0,1739137668.543475,10.319990158081055,0.06234442419528374,1739137668.5434766,10.319990158081055,0.015871659972160643,1739137668.543478,10.319990158081055,2.4013734105234916 +1739137668.563139,10.339990139007568,20.650902669584536,1739137668.5631416,10.339990139007568,-0.25579199469592595,1739137668.5631447,10.339990139007568,20.028193353802745,1739137668.5631475,10.339990139007568,29.225817743970108,1739137668.563149,10.339990139007568,-0.08312980544345305,1739137668.563151,10.339990139007568,0.020133011029025413,1739137668.5631523,10.339990139007568,0.03654801972651784,1739137668.5631537,10.339990139007568,0.007631649680417062,1739137668.5631552,10.339990139007568,2.4637178347187754,1739137668.5631568,10.339990139007568,0.0,1739137668.563158,10.339990139007568,0.06234442419528374,1739137668.5631595,10.339990139007568,0.015871659972160643,1739137668.5631611,10.339990139007568,2.4013734105234916 +1739137668.5831344,10.359990119934082,20.650902669584536,1739137668.5831368,10.359990119934082,-0.25579199469592595,1739137668.58314,10.359990119934082,20.028193353802745,1739137668.583143,10.359990119934082,29.225817743970108,1739137668.5831444,10.359990119934082,-0.08312980544345305,1739137668.5831466,10.359990119934082,0.020133011029025413,1739137668.583148,10.359990119934082,0.03654801972651784,1739137668.5831492,10.359990119934082,0.007631649680417062,1739137668.5831509,10.359990119934082,2.4637178347187754,1739137668.5831523,10.359990119934082,0.0,1739137668.583154,10.359990119934082,0.06234442419528374,1739137668.5831554,10.359990119934082,0.015871659972160643,1739137668.5831568,10.359990119934082,2.4013734105234916 +1739137668.6035347,10.379990100860596,20.650902669584536,1739137668.6035376,10.379990100860596,-0.25579199469592595,1739137668.6035407,10.379990100860596,20.028193353802745,1739137668.6035438,10.379990100860596,29.225817743970108,1739137668.6035454,10.379990100860596,-0.08312980544345305,1739137668.603547,10.379990100860596,0.020133011029025413,1739137668.6035488,10.379990100860596,0.03654801972651784,1739137668.60355,10.379990100860596,0.007631649680417062,1739137668.6035514,10.379990100860596,2.4637178347187754,1739137668.603553,10.379990100860596,0.0,1739137668.6035545,10.379990100860596,0.06234442419528374,1739137668.6035562,10.379990100860596,0.015871659972160643,1739137668.6035573,10.379990100860596,2.4013734105234916 +1739137668.6231918,10.39999008178711,20.91536035939168,1739137668.6231942,10.39999008178711,-0.2514988335848587,1739137668.623197,10.39999008178711,20.059663818889796,1739137668.6232002,10.39999008178711,29.27775115365884,1739137668.6232018,10.39999008178711,-0.08277891608546414,1739137668.6232035,10.39999008178711,0.020173301331182072,1739137668.623205,10.39999008178711,0.029344643298101533,1739137668.6232064,10.39999008178711,0.006442904748212569,1739137668.623208,10.39999008178711,2.470826906455083,1739137668.6232095,10.39999008178711,0.0,1739137668.623211,10.39999008178711,0.06289362058427263,1739137668.6232128,10.39999008178711,0.016664886891819344,1739137668.623214,10.39999008178711,2.408194808091447 +1739137668.6436903,10.419990062713623,20.91536035939168,1739137668.643694,10.419990062713623,-0.2514988335848587,1739137668.643698,10.419990062713623,20.059663818889796,1739137668.643702,10.419990062713623,29.27775115365884,1739137668.6437042,10.419990062713623,-0.08277891608546414,1739137668.6437066,10.419990062713623,0.020173301331182072,1739137668.6437094,10.419990062713623,0.029344643298101533,1739137668.6437116,10.419990062713623,0.006442904748212569,1739137668.6437135,10.419990062713623,2.470826906455083,1739137668.6437156,10.419990062713623,0.0,1739137668.6437182,10.419990062713623,0.06263209836363615,1739137668.6437201,10.419990062713623,0.016664886891819344,1739137668.6437223,10.419990062713623,2.408194808091447 +1739137668.6633162,10.439990043640137,20.91536035939168,1739137668.6633189,10.439990043640137,-0.2514988335848587,1739137668.663322,10.439990043640137,20.059663818889796,1739137668.663325,10.439990043640137,29.27775115365884,1739137668.663327,10.439990043640137,-0.08277891608546414,1739137668.663329,10.439990043640137,0.020173301331182072,1739137668.6633306,10.439990043640137,0.029344643298101533,1739137668.6633325,10.439990043640137,0.006442904748212569,1739137668.663334,10.439990043640137,2.470826906455083,1739137668.6633353,10.439990043640137,0.0,1739137668.6633372,10.439990043640137,0.06263209836363615,1739137668.663339,10.439990043640137,0.016664886891819344,1739137668.6633406,10.439990043640137,2.408194808091447 +1739137668.6833882,10.45999002456665,20.91536035939168,1739137668.6833906,10.45999002456665,-0.2514988335848587,1739137668.6833937,10.45999002456665,20.059663818889796,1739137668.683397,10.45999002456665,29.27775115365884,1739137668.683399,10.45999002456665,-0.08277891608546414,1739137668.6834009,10.45999002456665,0.020173301331182072,1739137668.6834025,10.45999002456665,0.029344643298101533,1739137668.683404,10.45999002456665,0.006442904748212569,1739137668.6834054,10.45999002456665,2.470826906455083,1739137668.6834073,10.45999002456665,0.0,1739137668.683409,10.45999002456665,0.06263209836363615,1739137668.6834106,10.45999002456665,0.016664886891819344,1739137668.6834123,10.45999002456665,2.408194808091447 +1739137668.7035134,10.479990005493164,20.91536035939168,1739137668.7035165,10.479990005493164,-0.2514988335848587,1739137668.7035205,10.479990005493164,20.059663818889796,1739137668.7035239,10.479990005493164,29.27775115365884,1739137668.7035253,10.479990005493164,-0.08277891608546414,1739137668.7035275,10.479990005493164,0.020173301331182072,1739137668.703529,10.479990005493164,0.029344643298101533,1739137668.7035306,10.479990005493164,0.006442904748212569,1739137668.7035317,10.479990005493164,2.470826906455083,1739137668.7035336,10.479990005493164,0.0,1739137668.7035356,10.479990005493164,0.06263209836363615,1739137668.7035375,10.479990005493164,0.016664886891819344,1739137668.703539,10.479990005493164,2.408194808091447 +1739137668.7234294,10.499989986419678,20.91536035939168,1739137668.7234325,10.499989986419678,-0.2514988335848587,1739137668.7234354,10.499989986419678,20.059663818889796,1739137668.7234387,10.499989986419678,29.27775115365884,1739137668.7234404,10.499989986419678,-0.08277891608546414,1739137668.7234428,10.499989986419678,0.020173301331182072,1739137668.7234445,10.499989986419678,0.029344643298101533,1739137668.7234461,10.499989986419678,0.006442904748212569,1739137668.7234476,10.499989986419678,2.470826906455083,1739137668.723449,10.499989986419678,0.0,1739137668.7234507,10.499989986419678,0.06263209836363615,1739137668.7234523,10.499989986419678,0.016664886891819344,1739137668.723454,10.499989986419678,2.408194808091447 +1739137668.744095,10.519989967346191,21.180567297264435,1739137668.744098,10.519989967346191,-0.24698308174128059,1739137668.7441015,10.519989967346191,20.51487348252348,1739137668.7441049,10.519989967346191,29.75352722745154,1739137668.7441065,10.519989967346191,-0.07881227310457052,1739137668.744109,10.519989967346191,0.01961390745422396,1739137668.7441103,10.519989967346191,0.01848507374123235,1739137668.744112,10.519989967346191,0.003861744079564476,1739137668.7441134,10.519989967346191,2.481583097724923,1739137668.7441154,10.519989967346191,0.0,1739137668.744117,10.519989967346191,0.07006841051059196,1739137668.7441194,10.519989967346191,0.017458113811478045,1739137668.7441208,10.519989967346191,2.4150557900056264 +1739137668.7639868,10.539989948272705,21.180567297264435,1739137668.7639909,10.539989948272705,-0.24698308174128059,1739137668.7639945,10.539989948272705,20.51487348252348,1739137668.7639978,10.539989948272705,29.75352722745154,1739137668.7639995,10.539989948272705,-0.07881227310457052,1739137668.7640016,10.539989948272705,0.01961390745422396,1739137668.764003,10.539989948272705,0.01848507374123235,1739137668.7640047,10.539989948272705,0.003861744079564476,1739137668.7640064,10.539989948272705,2.481583097724923,1739137668.7640083,10.539989948272705,0.0,1739137668.7640097,10.539989948272705,0.06652730771929649,1739137668.7640116,10.539989948272705,0.017458113811478045,1739137668.7640133,10.539989948272705,2.4150557900056264 +1739137668.783415,10.559989929199219,21.180567297264435,1739137668.7834182,10.559989929199219,-0.24698308174128059,1739137668.7834213,10.559989929199219,20.51487348252348,1739137668.7834241,10.559989929199219,29.75352722745154,1739137668.7834258,10.559989929199219,-0.07881227310457052,1739137668.7834275,10.559989929199219,0.01961390745422396,1739137668.7834291,10.559989929199219,0.01848507374123235,1739137668.7834306,10.559989929199219,0.003861744079564476,1739137668.783432,10.559989929199219,2.481583097724923,1739137668.7834337,10.559989929199219,0.0,1739137668.7834353,10.559989929199219,0.06652730771929649,1739137668.783437,10.559989929199219,0.017458113811478045,1739137668.7834387,10.559989929199219,2.4150557900056264 +1739137668.8036757,10.579989910125732,21.180567297264435,1739137668.8036792,10.579989910125732,-0.24698308174128059,1739137668.8036828,10.579989910125732,20.51487348252348,1739137668.8036864,10.579989910125732,29.75352722745154,1739137668.803688,10.579989910125732,-0.07881227310457052,1739137668.80369,10.579989910125732,0.01961390745422396,1739137668.8036916,10.579989910125732,0.01848507374123235,1739137668.803693,10.579989910125732,0.003861744079564476,1739137668.803695,10.579989910125732,2.481583097724923,1739137668.8036969,10.579989910125732,0.0,1739137668.8036988,10.579989910125732,0.06652730771929649,1739137668.8037004,10.579989910125732,0.017458113811478045,1739137668.8037024,10.579989910125732,2.4150557900056264 +1739137668.823329,10.599989891052246,21.180567297264435,1739137668.8233316,10.599989891052246,-0.24698308174128059,1739137668.823335,10.599989891052246,20.51487348252348,1739137668.823338,10.599989891052246,29.75352722745154,1739137668.8233395,10.599989891052246,-0.07881227310457052,1739137668.8233416,10.599989891052246,0.01961390745422396,1739137668.823343,10.599989891052246,0.01848507374123235,1739137668.8233447,10.599989891052246,0.003861744079564476,1739137668.8233461,10.599989891052246,2.481583097724923,1739137668.823348,10.599989891052246,0.0,1739137668.8233492,10.599989891052246,0.06652730771929649,1739137668.8233511,10.599989891052246,0.017458113811478045,1739137668.8233523,10.599989891052246,2.4150557900056264 +1739137668.8435261,10.61998987197876,21.446547467209747,1739137668.8435295,10.61998987197876,-0.24224311389026276,1739137668.843533,10.61998987197876,20.653300650384125,1739137668.8435364,10.61998987197876,29.91387012742984,1739137668.8435378,10.61998987197876,-0.07747167960142994,1739137668.8435402,10.61998987197876,0.01945722952945036,1739137668.843542,10.61998987197876,0.010212580170619755,1739137668.8435435,10.61998987197876,0.0021871067014604104,1739137668.8435452,10.61998987197876,2.489808250813396,1739137668.843547,10.61998987197876,0.0,1739137668.8435488,10.61998987197876,0.06827993220483862,1739137668.8435504,10.61998987197876,0.018251340731136746,1739137668.8435526,10.61998987197876,2.4223629021138215 +1739137668.8634086,10.639989852905273,21.446547467209747,1739137668.8634114,10.639989852905273,-0.24224311389026276,1739137668.8634145,10.639989852905273,20.653300650384125,1739137668.8634179,10.639989852905273,29.91387012742984,1739137668.8634195,10.639989852905273,-0.07747167960142994,1739137668.8634214,10.639989852905273,0.01945722952945036,1739137668.8634229,10.639989852905273,0.010212580170619755,1739137668.8634245,10.639989852905273,0.0021871067014604104,1739137668.863426,10.639989852905273,2.489808250813396,1739137668.8634279,10.639989852905273,0.0,1739137668.8634293,10.639989852905273,0.0674453486995743,1739137668.8634312,10.639989852905273,0.018251340731136746,1739137668.8634326,10.639989852905273,2.4223629021138215 +1739137668.8833897,10.659989833831787,21.446547467209747,1739137668.8833935,10.659989833831787,-0.24224311389026276,1739137668.8833983,10.659989833831787,20.653300650384125,1739137668.8834033,10.659989833831787,29.91387012742984,1739137668.883406,10.659989833831787,-0.07747167960142994,1739137668.8834088,10.659989833831787,0.01945722952945036,1739137668.8834114,10.659989833831787,0.010212580170619755,1739137668.883414,10.659989833831787,0.0021871067014604104,1739137668.8834167,10.659989833831787,2.489808250813396,1739137668.8834186,10.659989833831787,0.0,1739137668.883421,10.659989833831787,0.0674453486995743,1739137668.8834236,10.659989833831787,0.018251340731136746,1739137668.8834255,10.659989833831787,2.4223629021138215 +1739137668.9051833,10.6799898147583,21.446547467209747,1739137668.9051874,10.6799898147583,-0.24224311389026276,1739137668.9051926,10.6799898147583,20.653300650384125,1739137668.905199,10.6799898147583,29.91387012742984,1739137668.9052024,10.6799898147583,-0.07747167960142994,1739137668.9052072,10.6799898147583,0.01945722952945036,1739137668.9052112,10.6799898147583,0.010212580170619755,1739137668.905215,10.6799898147583,0.0021871067014604104,1739137668.905219,10.6799898147583,2.489808250813396,1739137668.9052234,10.6799898147583,0.0,1739137668.9052272,10.6799898147583,0.0674453486995743,1739137668.9052317,10.6799898147583,0.018251340731136746,1739137668.9052358,10.6799898147583,2.4223629021138215 +1739137668.923196,10.699989795684814,21.446547467209747,1739137668.9231985,10.699989795684814,-0.24224311389026276,1739137668.9232016,10.699989795684814,20.653300650384125,1739137668.9232044,10.699989795684814,29.91387012742984,1739137668.9232059,10.699989795684814,-0.07747167960142994,1739137668.9232078,10.699989795684814,0.01945722952945036,1739137668.923209,10.699989795684814,0.010212580170619755,1739137668.9232104,10.699989795684814,0.0021871067014604104,1739137668.9232118,10.699989795684814,2.489808250813396,1739137668.9232132,10.699989795684814,0.0,1739137668.9232147,10.699989795684814,0.0674453486995743,1739137668.923216,10.699989795684814,0.018251340731136746,1739137668.9232173,10.699989795684814,2.4223629021138215 +1739137668.9433796,10.719989776611328,21.446547467209747,1739137668.9433827,10.719989776611328,-0.24224311389026276,1739137668.9433858,10.719989776611328,20.653300650384125,1739137668.9433887,10.719989776611328,29.91387012742984,1739137668.9433901,10.719989776611328,-0.07747167960142994,1739137668.943392,10.719989776611328,0.01945722952945036,1739137668.9433935,10.719989776611328,0.010212580170619755,1739137668.9433951,10.719989776611328,0.0021871067014604104,1739137668.9433963,10.719989776611328,2.489808250813396,1739137668.943398,10.719989776611328,0.0,1739137668.9433992,10.719989776611328,0.0674453486995743,1739137668.9434009,10.719989776611328,0.018251340731136746,1739137668.9434025,10.719989776611328,2.4223629021138215 +1739137668.9632082,10.739989757537842,21.71333259898481,1739137668.9632108,10.739989757537842,-0.23727710934231716,1739137668.9632132,10.739989757537842,20.899182749620724,1739137668.963216,10.739989757537842,30.181945469308914,1739137668.9632177,10.739989757537842,-0.07611707724622002,1739137668.9632194,10.739989757537842,0.0190279782550528,1739137668.963221,10.739989757537842,-0.0001405146071587791,1739137668.9632223,10.739989757537842,-3.008367421604825e-05,1739137668.9632235,10.739989757537842,2.499859489341638,1739137668.9632251,10.739989757537842,0.0,1739137668.9632266,10.739989757537842,0.07250853260479391,1739137668.9632282,10.739989757537842,0.019044567650795447,1739137668.9632294,10.739989757537842,2.429761997896131 +1739137668.9832566,10.759989738464355,21.71333259898481,1739137668.9832592,10.759989738464355,-0.23727710934231716,1739137668.983262,10.759989738464355,20.899182749620724,1739137668.9832647,10.759989738464355,30.181945469308914,1739137668.9832666,10.759989738464355,-0.07611707724622002,1739137668.983268,10.759989738464355,0.0190279782550528,1739137668.9832697,10.759989738464355,-0.0001405146071587791,1739137668.983271,10.759989738464355,-3.008367421604825e-05,1739137668.9832726,10.759989738464355,2.499859489341638,1739137668.983274,10.759989738464355,0.0,1739137668.9832752,10.759989738464355,0.07009749144550703,1739137668.9832768,10.759989738464355,0.019044567650795447,1739137668.983278,10.759989738464355,2.429761997896131 +1739137669.0033607,10.77998971939087,21.71333259898481,1739137669.0033636,10.77998971939087,-0.23727710934231716,1739137669.0033667,10.77998971939087,20.899182749620724,1739137669.0033696,10.77998971939087,30.181945469308914,1739137669.0033708,10.77998971939087,-0.07611707724622002,1739137669.0033724,10.77998971939087,0.0190279782550528,1739137669.003374,10.77998971939087,-0.0001405146071587791,1739137669.0033753,10.77998971939087,-3.008367421604825e-05,1739137669.003377,10.77998971939087,2.499859489341638,1739137669.0033784,10.77998971939087,0.0,1739137669.00338,10.77998971939087,0.07009749144550703,1739137669.0033817,10.77998971939087,0.019044567650795447,1739137669.003383,10.77998971939087,2.429761997896131 +1739137669.0232158,10.799989700317383,21.71333259898481,1739137669.0232184,10.799989700317383,-0.23727710934231716,1739137669.0232215,10.799989700317383,20.899182749620724,1739137669.0232246,10.799989700317383,30.181945469308914,1739137669.023226,10.799989700317383,-0.07611707724622002,1739137669.0232282,10.799989700317383,0.0190279782550528,1739137669.0232298,10.799989700317383,-0.0001405146071587791,1739137669.0232315,10.799989700317383,-3.008367421604825e-05,1739137669.023233,10.799989700317383,2.499859489341638,1739137669.0232346,10.799989700317383,0.0,1739137669.023236,10.799989700317383,0.07009749144550703,1739137669.023238,10.799989700317383,0.019044567650795447,1739137669.0232394,10.799989700317383,2.429761997896131 +1739137669.043376,10.819989681243896,21.71333259898481,1739137669.0433786,10.819989681243896,-0.23727710934231716,1739137669.0433815,10.819989681243896,20.899182749620724,1739137669.0433843,10.819989681243896,30.181945469308914,1739137669.0433857,10.819989681243896,-0.07611707724622002,1739137669.0433874,10.819989681243896,0.0190279782550528,1739137669.0433886,10.819989681243896,-0.0001405146071587791,1739137669.0433903,10.819989681243896,-3.008367421604825e-05,1739137669.0433915,10.819989681243896,2.499859489341638,1739137669.0433931,10.819989681243896,0.0,1739137669.0433943,10.819989681243896,0.07009749144550703,1739137669.0433958,10.819989681243896,0.019044567650795447,1739137669.0433974,10.819989681243896,2.429761997896131 +1739137669.0632339,10.83998966217041,21.980941132744682,1739137669.0632367,10.83998966217041,-0.2320834246733643,1739137669.06324,10.83998966217041,21.145164480497492,1739137669.063243,10.83998966217041,30.45098415813876,1739137669.0632446,10.83998966217041,-0.075,1739137669.0632463,10.83998966217041,0.018543638862871765,1739137669.0632482,10.83998966217041,-0.010963436390443981,1739137669.0632498,10.83998966217041,-0.0023464821107279494,1739137669.0632513,10.83998966217041,2.489060567894973,1739137669.063253,10.83998966217041,0.0,1739137669.0632544,10.83998966217041,0.03480589522747721,1739137669.0632563,10.83998966217041,0.019837794570454148,1739137669.063258,10.83998966217041,2.4374491422638136 +1739137669.08619,10.859989643096924,21.980941132744682,1739137669.0861983,10.859989643096924,-0.2320834246733643,1739137669.086208,10.859989643096924,21.145164480497492,1739137669.0862172,10.859989643096924,30.45098415813876,1739137669.086222,10.859989643096924,-0.075,1739137669.0862274,10.859989643096924,0.018543638862871765,1739137669.086232,10.859989643096924,-0.010963436390443981,1739137669.0862365,10.859989643096924,-0.0023464821107279494,1739137669.086241,10.859989643096924,2.489060567894973,1739137669.0862463,10.859989643096924,0.0,1739137669.0862508,10.859989643096924,0.0516114256311595,1739137669.086256,10.859989643096924,0.019837794570454148,1739137669.086261,10.859989643096924,2.4374491422638136 +1739137669.1068401,10.879989624023438,21.980941132744682,1739137669.1068487,10.879989624023438,-0.2320834246733643,1739137669.1068583,10.879989624023438,21.145164480497492,1739137669.106868,10.879989624023438,30.45098415813876,1739137669.1068726,10.879989624023438,-0.075,1739137669.1068788,10.879989624023438,0.018543638862871765,1739137669.1068838,10.879989624023438,-0.010963436390443981,1739137669.1068888,10.879989624023438,-0.0023464821107279494,1739137669.1068933,10.879989624023438,2.489060567894973,1739137669.1068985,10.879989624023438,0.0,1739137669.1069028,10.879989624023438,0.0516114256311595,1739137669.1069078,10.879989624023438,0.019837794570454148,1739137669.1069126,10.879989624023438,2.4374491422638136 +1739137669.1272283,10.899989604949951,21.980941132744682,1739137669.1272364,10.899989604949951,-0.2320834246733643,1739137669.1272461,10.899989604949951,21.145164480497492,1739137669.127256,10.899989604949951,30.45098415813876,1739137669.1272604,10.899989604949951,-0.075,1739137669.1272666,10.899989604949951,0.018543638862871765,1739137669.1272714,10.899989604949951,-0.010963436390443981,1739137669.1272762,10.899989604949951,-0.0023464821107279494,1739137669.127281,10.899989604949951,2.489060567894973,1739137669.1272862,10.899989604949951,0.0,1739137669.1272912,10.899989604949951,0.0516114256311595,1739137669.1272962,10.899989604949951,0.019837794570454148,1739137669.127301,10.899989604949951,2.4374491422638136 +1739137669.1546698,10.909989595413208,21.980941132744682,1739137669.154678,10.909989595413208,-0.2320834246733643,1739137669.1546876,10.909989595413208,21.145164480497492,1739137669.1546977,10.909989595413208,30.45098415813876,1739137669.1547027,10.909989595413208,-0.075,1739137669.1547084,10.909989595413208,0.018543638862871765,1739137669.1547132,10.909989595413208,-0.010963436390443981,1739137669.1547177,10.909989595413208,-0.0023464821107279494,1739137669.1547222,10.909989595413208,2.489060567894973,1739137669.1547275,10.909989595413208,0.0,1739137669.154732,10.909989595413208,0.0516114256311595,1739137669.1547372,10.909989595413208,0.019837794570454148,1739137669.1547418,10.909989595413208,2.4374491422638136 +1739137669.1736445,10.939989566802979,21.980941132744682,1739137669.173653,10.939989566802979,-0.2320834246733643,1739137669.1736634,10.939989566802979,21.145164480497492,1739137669.173673,10.939989566802979,30.45098415813876,1739137669.1736777,10.939989566802979,-0.075,1739137669.1736836,10.939989566802979,0.018543638862871765,1739137669.1736887,10.939989566802979,-0.010963436390443981,1739137669.1736937,10.939989566802979,-0.0023464821107279494,1739137669.1736982,10.939989566802979,2.489060567894973,1739137669.1737037,10.939989566802979,0.0,1739137669.1737082,10.939989566802979,0.0516114256311595,1739137669.1737137,10.939989566802979,0.019837794570454148,1739137669.173718,10.939989566802979,2.4374491422638136 +1739137669.1921268,10.959989547729492,22.249257015422124,1739137669.1921313,10.959989547729492,-0.22666310973484105,1739137669.192137,10.959989547729492,21.41395187009734,1739137669.1921422,10.959989547729492,30.73571584132507,1739137669.1921449,10.959989547729492,-0.07352379622799085,1739137669.1921482,10.959989547729492,0.018043178880352808,1739137669.1921508,10.959989547729492,-0.021965170595962456,1739137669.192153,10.959989547729492,-0.004683074121312101,1739137669.1921556,10.959989547729492,2.4781310411673405,1739137669.1921582,10.959989547729492,0.0,1739137669.1921608,10.959989547729492,0.020596595325736086,1739137669.192164,10.959989547729492,0.02063102149011285,1739137669.192166,10.959989547729492,2.44276547165175 +1739137669.211105,10.979989528656006,22.249257015422124,1739137669.2111087,10.979989528656006,-0.22666310973484105,1739137669.211112,10.979989528656006,21.41395187009734,1739137669.2111158,10.979989528656006,30.73571584132507,1739137669.2111177,10.979989528656006,-0.07352379622799085,1739137669.2111201,10.979989528656006,0.018043178880352808,1739137669.2111223,10.979989528656006,-0.021965170595962456,1739137669.2111237,10.979989528656006,-0.004683074121312101,1739137669.2111256,10.979989528656006,2.4781310411673405,1739137669.211128,10.979989528656006,0.0,1739137669.21113,10.979989528656006,0.035365569515590334,1739137669.2111316,10.979989528656006,0.02063102149011285,1739137669.2111335,10.979989528656006,2.44276547165175 +1739137669.230742,10.99998950958252,22.249257015422124,1739137669.2307446,10.99998950958252,-0.22666310973484105,1739137669.2307472,10.99998950958252,21.41395187009734,1739137669.2307498,10.99998950958252,30.73571584132507,1739137669.2307513,10.99998950958252,-0.07352379622799085,1739137669.2307527,10.99998950958252,0.018043178880352808,1739137669.2307544,10.99998950958252,-0.021965170595962456,1739137669.2307556,10.99998950958252,-0.004683074121312101,1739137669.2307568,10.99998950958252,2.4781310411673405,1739137669.2307584,10.99998950958252,0.0,1739137669.2307596,10.99998950958252,0.035365569515590334,1739137669.2307613,10.99998950958252,0.02063102149011285,1739137669.2307625,10.99998950958252,2.44276547165175 +1739137669.2502067,11.019989490509033,22.249257015422124,1739137669.2502096,11.019989490509033,-0.22666310973484105,1739137669.2502122,11.019989490509033,21.41395187009734,1739137669.2502146,11.019989490509033,30.73571584132507,1739137669.2502162,11.019989490509033,-0.07352379622799085,1739137669.2502182,11.019989490509033,0.018043178880352808,1739137669.2502198,11.019989490509033,-0.021965170595962456,1739137669.250221,11.019989490509033,-0.004683074121312101,1739137669.250222,11.019989490509033,2.4781310411673405,1739137669.2502239,11.019989490509033,0.0,1739137669.2502248,11.019989490509033,0.035365569515590334,1739137669.2502265,11.019989490509033,0.02063102149011285,1739137669.2502275,11.019989490509033,2.44276547165175 +1739137669.2700875,11.039989471435547,22.249257015422124,1739137669.2700896,11.039989471435547,-0.22666310973484105,1739137669.2700922,11.039989471435547,21.41395187009734,1739137669.2700946,11.039989471435547,30.73571584132507,1739137669.2700958,11.039989471435547,-0.07352379622799085,1739137669.2700975,11.039989471435547,0.018043178880352808,1739137669.2700987,11.039989471435547,-0.021965170595962456,1739137669.2700999,11.039989471435547,-0.004683074121312101,1739137669.270101,11.039989471435547,2.4781310411673405,1739137669.2701023,11.039989471435547,0.0,1739137669.2701035,11.039989471435547,0.035365569515590334,1739137669.270105,11.039989471435547,0.02063102149011285,1739137669.270106,11.039989471435547,2.44276547165175 +1739137669.290277,11.05998945236206,22.51808654115586,1739137669.2902796,11.05998945236206,-0.2210190981626443,1739137669.2902825,11.05998945236206,21.8342402810523,1739137669.2902853,11.05998945236206,31.1671990702535,1739137669.2902865,11.05998945236206,-0.072,1739137669.2902884,11.05998945236206,0.017227704544404733,1739137669.2902899,11.05998945236206,-0.036301660509854526,1739137669.2902913,11.05998945236206,-0.007451519052457117,1739137669.290293,11.05998945236206,2.4639606305199115,1739137669.2902944,11.05998945236206,0.0,1739137669.290296,11.05998945236206,0.0011848094389332736,1739137669.2902975,11.05998945236206,0.02142424840977155,1739137669.290299,11.05998945236206,2.4464992605326694 +1739137669.3110597,11.079989433288574,22.51808654115586,1739137669.3110635,11.079989433288574,-0.2210190981626443,1739137669.3110678,11.079989433288574,21.8342402810523,1739137669.3110714,11.079989433288574,31.1671990702535,1739137669.3110735,11.079989433288574,-0.072,1739137669.311076,11.079989433288574,0.017227704544404733,1739137669.3110778,11.079989433288574,-0.036301660509854526,1739137669.3110797,11.079989433288574,-0.007451519052457117,1739137669.3110816,11.079989433288574,2.4639606305199115,1739137669.3110843,11.079989433288574,0.0,1739137669.3110862,11.079989433288574,0.017461369987242126,1739137669.311088,11.079989433288574,0.02142424840977155,1739137669.31109,11.079989433288574,2.4464992605326694 +1739137669.3304472,11.099989414215088,22.51808654115586,1739137669.3304508,11.099989414215088,-0.2210190981626443,1739137669.3304546,11.099989414215088,21.8342402810523,1739137669.3304584,11.099989414215088,31.1671990702535,1739137669.3304603,11.099989414215088,-0.072,1739137669.3304627,11.099989414215088,0.017227704544404733,1739137669.330465,11.099989414215088,-0.036301660509854526,1739137669.3304667,11.099989414215088,-0.007451519052457117,1739137669.3304834,11.099989414215088,2.4639606305199115,1739137669.3304856,11.099989414215088,0.0,1739137669.3304873,11.099989414215088,0.017461369987242126,1739137669.3304894,11.099989414215088,0.02142424840977155,1739137669.3304913,11.099989414215088,2.4464992605326694 +1739137669.3510878,11.119989395141602,22.51808654115586,1739137669.3510911,11.119989395141602,-0.2210190981626443,1739137669.351095,11.119989395141602,21.8342402810523,1739137669.3510988,11.119989395141602,31.1671990702535,1739137669.351101,11.119989395141602,-0.072,1739137669.3511033,11.119989395141602,0.017227704544404733,1739137669.351105,11.119989395141602,-0.036301660509854526,1739137669.3511071,11.119989395141602,-0.007451519052457117,1739137669.3511086,11.119989395141602,2.4639606305199115,1739137669.351111,11.119989395141602,0.0,1739137669.3511126,11.119989395141602,0.017461369987242126,1739137669.3511147,11.119989395141602,0.02142424840977155,1739137669.3511167,11.119989395141602,2.4464992605326694 +1739137669.3716354,11.139989376068115,22.51808654115586,1739137669.3716388,11.139989376068115,-0.2210190981626443,1739137669.3716426,11.139989376068115,21.8342402810523,1739137669.3716462,11.139989376068115,31.1671990702535,1739137669.371648,11.139989376068115,-0.072,1739137669.3716502,11.139989376068115,0.017227704544404733,1739137669.3716524,11.139989376068115,-0.036301660509854526,1739137669.3716538,11.139989376068115,-0.007451519052457117,1739137669.3716557,11.139989376068115,2.4639606305199115,1739137669.3716583,11.139989376068115,0.0,1739137669.3716598,11.139989376068115,0.017461369987242126,1739137669.371662,11.139989376068115,0.02142424840977155,1739137669.3716636,11.139989376068115,2.4464992605326694 +1739137669.3910928,11.159989356994629,22.51808654115586,1739137669.3910959,11.159989356994629,-0.2210190981626443,1739137669.3911,11.159989356994629,21.8342402810523,1739137669.3911035,11.159989356994629,31.1671990702535,1739137669.3911057,11.159989356994629,-0.072,1739137669.3911078,11.159989356994629,0.017227704544404733,1739137669.3911097,11.159989356994629,-0.036301660509854526,1739137669.3911116,11.159989356994629,-0.007451519052457117,1739137669.3911135,11.159989356994629,2.4639606305199115,1739137669.3911154,11.159989356994629,0.0,1739137669.391117,11.159989356994629,0.017461369987242126,1739137669.391119,11.159989356994629,0.02142424840977155,1739137669.391121,11.159989356994629,2.4464992605326694 +1739137669.410704,11.179989337921143,22.787202539381877,1739137669.410707,11.179989337921143,-0.2151555185482188,1739137669.4107106,11.179989337921143,22.100460136980367,1739137669.4107144,11.179989337921143,31.438180312658833,1739137669.410716,11.179989337921143,-0.07357681692618435,1739137669.4107184,11.179989337921143,0.016364169173351546,1739137669.4107206,11.179989337921143,-0.050643312945209844,1739137669.4107223,11.179989337921143,-0.010391180566659577,1739137669.4107242,11.179989337921143,2.449866189895861,1739137669.4107258,11.179989337921143,0.0,1739137669.4107277,11.179989337921143,-0.012479361534885195,1739137669.41073,11.179989337921143,0.02221747532943025,1739137669.410732,11.179989337921143,2.44808805310749 +1739137669.4306889,11.199989318847656,22.787202539381877,1739137669.4306927,11.199989318847656,-0.2151555185482188,1739137669.4306972,11.199989318847656,22.100460136980367,1739137669.4307017,11.199989318847656,31.438180312658833,1739137669.4307036,11.199989318847656,-0.07357681692618435,1739137669.430706,11.199989318847656,0.016364169173351546,1739137669.430708,11.199989318847656,-0.050643312945209844,1739137669.4307103,11.199989318847656,-0.010391180566659577,1739137669.4307122,11.199989318847656,2.449866189895861,1739137669.4307148,11.199989318847656,0.0,1739137669.4307168,11.199989318847656,0.0017781367883711319,1739137669.430719,11.199989318847656,0.02221747532943025,1739137669.4307208,11.199989318847656,2.44808805310749 +1739137669.4503775,11.21998929977417,22.787202539381877,1739137669.4503806,11.21998929977417,-0.2151555185482188,1739137669.4503846,11.21998929977417,22.100460136980367,1739137669.4503884,11.21998929977417,31.438180312658833,1739137669.4503906,11.21998929977417,-0.07357681692618435,1739137669.4503927,11.21998929977417,0.016364169173351546,1739137669.4503949,11.21998929977417,-0.050643312945209844,1739137669.4503968,11.21998929977417,-0.010391180566659577,1739137669.4503984,11.21998929977417,2.449866189895861,1739137669.4504006,11.21998929977417,0.0,1739137669.450402,11.21998929977417,0.0017781367883711319,1739137669.4504042,11.21998929977417,0.02221747532943025,1739137669.4504058,11.21998929977417,2.44808805310749 +1739137669.4703932,11.239989280700684,22.787202539381877,1739137669.4703958,11.239989280700684,-0.2151555185482188,1739137669.4703994,11.239989280700684,22.100460136980367,1739137669.4704034,11.239989280700684,31.438180312658833,1739137669.470405,11.239989280700684,-0.07357681692618435,1739137669.4704075,11.239989280700684,0.016364169173351546,1739137669.4704094,11.239989280700684,-0.050643312945209844,1739137669.4704113,11.239989280700684,-0.010391180566659577,1739137669.4704127,11.239989280700684,2.449866189895861,1739137669.4704149,11.239989280700684,0.0,1739137669.4704165,11.239989280700684,0.0017781367883711319,1739137669.4704185,11.239989280700684,0.02221747532943025,1739137669.4704206,11.239989280700684,2.44808805310749 +1739137669.4905722,11.259989261627197,22.787202539381877,1739137669.4905753,11.259989261627197,-0.2151555185482188,1739137669.4905791,11.259989261627197,22.100460136980367,1739137669.490583,11.259989261627197,31.438180312658833,1739137669.4905849,11.259989261627197,-0.07357681692618435,1739137669.4905872,11.259989261627197,0.016364169173351546,1739137669.4905891,11.259989261627197,-0.050643312945209844,1739137669.490591,11.259989261627197,-0.010391180566659577,1739137669.4905925,11.259989261627197,2.449866189895861,1739137669.4905949,11.259989261627197,0.0,1739137669.4905965,11.259989261627197,0.0017781367883711319,1739137669.4905987,11.259989261627197,0.02221747532943025,1739137669.4906,11.259989261627197,2.44808805310749 +1739137669.5107079,11.279989242553711,23.056424643500538,1739137669.5107126,11.279989242553711,-0.20907598009444417,1739137669.5107176,11.279989242553711,22.24050903114346,1739137669.5107217,11.279989242553711,31.578424068197926,1739137669.5107238,11.279989242553711,-0.07401809006117856,1739137669.5107267,11.279989242553711,0.015846819248918353,1739137669.5107284,11.279989242553711,-0.06105775091086561,1739137669.5107303,11.279989242553711,-0.0129103278515751,1739137669.5107322,11.279989242553711,2.439681825726118,1739137669.5107346,11.279989242553711,0.0,1739137669.5107365,11.279989242553711,-0.01778998635951299,1739137669.5107384,11.279989242553711,0.023010702249088952,1739137669.5107405,11.279989242553711,2.448153653550859 +1739137669.5301964,11.299989223480225,23.056424643500538,1739137669.5301993,11.299989223480225,-0.20907598009444417,1739137669.5302026,11.299989223480225,22.24050903114346,1739137669.5302057,11.299989223480225,31.578424068197926,1739137669.5302072,11.299989223480225,-0.07401809006117856,1739137669.5302093,11.299989223480225,0.015846819248918353,1739137669.530211,11.299989223480225,-0.06105775091086561,1739137669.5302126,11.299989223480225,-0.0129103278515751,1739137669.5302138,11.299989223480225,2.439681825726118,1739137669.5302157,11.299989223480225,0.0,1739137669.5302172,11.299989223480225,-0.008471827824740874,1739137669.530219,11.299989223480225,0.023010702249088952,1739137669.5302205,11.299989223480225,2.448153653550859 +1739137669.5499709,11.319989204406738,23.056424643500538,1739137669.5499732,11.319989204406738,-0.20907598009444417,1739137669.5499759,11.319989204406738,22.24050903114346,1739137669.5499783,11.319989204406738,31.578424068197926,1739137669.5499797,11.319989204406738,-0.07401809006117856,1739137669.5499809,11.319989204406738,0.015846819248918353,1739137669.5499825,11.319989204406738,-0.06105775091086561,1739137669.5499837,11.319989204406738,-0.0129103278515751,1739137669.549985,11.319989204406738,2.439681825726118,1739137669.5499864,11.319989204406738,0.0,1739137669.5499876,11.319989204406738,-0.008471827824740874,1739137669.5499892,11.319989204406738,0.023010702249088952,1739137669.5499904,11.319989204406738,2.448153653550859 +1739137669.569835,11.339989185333252,23.056424643500538,1739137669.5698373,11.339989185333252,-0.20907598009444417,1739137669.56984,11.339989185333252,22.24050903114346,1739137669.5698423,11.339989185333252,31.578424068197926,1739137669.5698438,11.339989185333252,-0.07401809006117856,1739137669.5698452,11.339989185333252,0.015846819248918353,1739137669.5698466,11.339989185333252,-0.06105775091086561,1739137669.5698478,11.339989185333252,-0.0129103278515751,1739137669.5698488,11.339989185333252,2.439681825726118,1739137669.5698504,11.339989185333252,0.0,1739137669.5698514,11.339989185333252,-0.008471827824740874,1739137669.5698528,11.339989185333252,0.023010702249088952,1739137669.569854,11.339989185333252,2.448153653550859 +1739137669.589949,11.359989166259766,23.056424643500538,1739137669.589952,11.359989166259766,-0.20907598009444417,1739137669.5899546,11.359989166259766,22.24050903114346,1739137669.5899568,11.359989166259766,31.578424068197926,1739137669.5899582,11.359989166259766,-0.07401809006117856,1739137669.5899596,11.359989166259766,0.015846819248918353,1739137669.589961,11.359989166259766,-0.06105775091086561,1739137669.589962,11.359989166259766,-0.0129103278515751,1739137669.5899632,11.359989166259766,2.439681825726118,1739137669.5899646,11.359989166259766,0.0,1739137669.5899658,11.359989166259766,-0.008471827824740874,1739137669.589967,11.359989166259766,0.023010702249088952,1739137669.5899682,11.359989166259766,2.448153653550859 +1739137669.609865,11.37998914718628,23.056424643500538,1739137669.609867,11.37998914718628,-0.20907598009444417,1739137669.6098695,11.37998914718628,22.24050903114346,1739137669.609872,11.37998914718628,31.578424068197926,1739137669.6098733,11.37998914718628,-0.07401809006117856,1739137669.6098752,11.37998914718628,0.015846819248918353,1739137669.6098764,11.37998914718628,-0.06105775091086561,1739137669.6098778,11.37998914718628,-0.0129103278515751,1739137669.609879,11.37998914718628,2.439681825726118,1739137669.6098807,11.37998914718628,0.0,1739137669.6098816,11.37998914718628,-0.008471827824740874,1739137669.609883,11.37998914718628,0.023010702249088952,1739137669.6098845,11.37998914718628,2.448153653550859 +1739137669.6299095,11.399989128112793,23.325583925314536,1739137669.629912,11.399989128112793,-0.20278425058322025,1739137669.6299143,11.399989128112793,22.634423368790905,1739137669.6299167,11.399989128112793,31.968988626423965,1739137669.6299179,11.399989128112793,-0.07731521285066632,1739137669.6299195,11.399989128112793,0.014515139610709125,1739137669.6299207,11.399989128112793,-0.08029407119469856,1739137669.6299222,11.399989128112793,-0.016504756155448278,1739137669.629923,11.399989128112793,2.4209816620605484,1739137669.6299245,11.399989128112793,0.0,1739137669.629926,11.399989128112793,-0.04204939446136112,1739137669.6299272,11.399989128112793,0.023803929168747653,1739137669.6299284,11.399989128112793,2.4470417310885333 +1739137669.6500225,11.419989109039307,23.325583925314536,1739137669.6500244,11.419989109039307,-0.20278425058322025,1739137669.650027,11.419989109039307,22.634423368790905,1739137669.6500297,11.419989109039307,31.968988626423965,1739137669.6500309,11.419989109039307,-0.07731521285066632,1739137669.6500323,11.419989109039307,0.014515139610709125,1739137669.650034,11.419989109039307,-0.08029407119469856,1739137669.6500351,11.419989109039307,-0.016504756155448278,1739137669.6500366,11.419989109039307,2.4209816620605484,1739137669.650038,11.419989109039307,0.0,1739137669.6500392,11.419989109039307,-0.026060069027984856,1739137669.6500409,11.419989109039307,0.023803929168747653,1739137669.6500418,11.419989109039307,2.4470417310885333 +1739137669.6700137,11.43998908996582,23.325583925314536,1739137669.670016,11.43998908996582,-0.20278425058322025,1739137669.670019,11.43998908996582,22.634423368790905,1739137669.6700213,11.43998908996582,31.968988626423965,1739137669.670023,11.43998908996582,-0.07731521285066632,1739137669.6700244,11.43998908996582,0.014515139610709125,1739137669.6700258,11.43998908996582,-0.08029407119469856,1739137669.670027,11.43998908996582,-0.016504756155448278,1739137669.6700284,11.43998908996582,2.4209816620605484,1739137669.6700299,11.43998908996582,0.0,1739137669.670031,11.43998908996582,-0.026060069027984856,1739137669.6700327,11.43998908996582,0.023803929168747653,1739137669.6700337,11.43998908996582,2.4470417310885333 +1739137669.6900177,11.459989070892334,23.325583925314536,1739137669.69002,11.459989070892334,-0.20278425058322025,1739137669.6900232,11.459989070892334,22.634423368790905,1739137669.6900258,11.459989070892334,31.968988626423965,1739137669.690027,11.459989070892334,-0.07731521285066632,1739137669.690029,11.459989070892334,0.014515139610709125,1739137669.69003,11.459989070892334,-0.08029407119469856,1739137669.6900313,11.459989070892334,-0.016504756155448278,1739137669.6900325,11.459989070892334,2.4209816620605484,1739137669.690034,11.459989070892334,0.0,1739137669.690035,11.459989070892334,-0.026060069027984856,1739137669.6900368,11.459989070892334,0.023803929168747653,1739137669.690038,11.459989070892334,2.4470417310885333 +1739137669.709911,11.479989051818848,23.325583925314536,1739137669.709913,11.479989051818848,-0.20278425058322025,1739137669.7099159,11.479989051818848,22.634423368790905,1739137669.7099183,11.479989051818848,31.968988626423965,1739137669.7099195,11.479989051818848,-0.07731521285066632,1739137669.7099211,11.479989051818848,0.014515139610709125,1739137669.7099223,11.479989051818848,-0.08029407119469856,1739137669.7099235,11.479989051818848,-0.016504756155448278,1739137669.709925,11.479989051818848,2.4209816620605484,1739137669.7099264,11.479989051818848,0.0,1739137669.7099273,11.479989051818848,-0.026060069027984856,1739137669.709929,11.479989051818848,0.023803929168747653,1739137669.7099302,11.479989051818848,2.4470417310885333 +1739137669.7300305,11.499989032745361,23.594527602052317,1739137669.730033,11.499989032745361,-0.196284121759021,1739137669.7300358,11.499989032745361,22.640878017032612,1739137669.730038,11.499989032745361,31.96646035998452,1739137669.7300394,11.499989032745361,-0.07729243567553619,1739137669.7300408,11.499989032745361,0.01421221094663165,1739137669.7300422,11.499989032745361,-0.08694928085061736,1739137669.7300436,11.499989032745361,-0.019050754676280923,1739137669.730045,11.499989032745361,2.4145453766136966,1739137669.7300467,11.499989032745361,0.0,1739137669.7300477,11.499989032745361,-0.03263106050581894,1739137669.7300494,11.499989032745361,0.024597156088406354,1739137669.7300506,11.499989032745361,2.4440473919955474 +1739137669.7499828,11.519989013671875,23.594527602052317,1739137669.7499847,11.519989013671875,-0.196284121759021,1739137669.7499876,11.519989013671875,22.640878017032612,1739137669.7499902,11.519989013671875,31.96646035998452,1739137669.7499912,11.519989013671875,-0.07729243567553619,1739137669.7499926,11.519989013671875,0.01421221094663165,1739137669.7499943,11.519989013671875,-0.08694928085061736,1739137669.7499955,11.519989013671875,-0.019050754676280923,1739137669.749997,11.519989013671875,2.4145453766136966,1739137669.749998,11.519989013671875,0.0,1739137669.7499993,11.519989013671875,-0.02950201538185082,1739137669.7500007,11.519989013671875,0.024597156088406354,1739137669.750002,11.519989013671875,2.4440473919955474 +1739137669.7700152,11.539988994598389,23.594527602052317,1739137669.7700179,11.539988994598389,-0.196284121759021,1739137669.7700202,11.539988994598389,22.640878017032612,1739137669.7700229,11.539988994598389,31.96646035998452,1739137669.7700243,11.539988994598389,-0.07729243567553619,1739137669.7700257,11.539988994598389,0.01421221094663165,1739137669.770027,11.539988994598389,-0.08694928085061736,1739137669.7700284,11.539988994598389,-0.019050754676280923,1739137669.7700295,11.539988994598389,2.4145453766136966,1739137669.7700312,11.539988994598389,0.0,1739137669.7700322,11.539988994598389,-0.02950201538185082,1739137669.7700336,11.539988994598389,0.024597156088406354,1739137669.770035,11.539988994598389,2.4440473919955474 +1739137669.7898786,11.559988975524902,23.594527602052317,1739137669.7898808,11.559988975524902,-0.196284121759021,1739137669.7898834,11.559988975524902,22.640878017032612,1739137669.7898858,11.559988975524902,31.96646035998452,1739137669.789887,11.559988975524902,-0.07729243567553619,1739137669.7898881,11.559988975524902,0.01421221094663165,1739137669.78989,11.559988975524902,-0.08694928085061736,1739137669.789891,11.559988975524902,-0.019050754676280923,1739137669.7898924,11.559988975524902,2.4145453766136966,1739137669.7898936,11.559988975524902,0.0,1739137669.7898948,11.559988975524902,-0.02950201538185082,1739137669.7898962,11.559988975524902,0.024597156088406354,1739137669.7898974,11.559988975524902,2.4440473919955474 +1739137669.8099833,11.579988956451416,23.594527602052317,1739137669.8099856,11.579988956451416,-0.196284121759021,1739137669.8099883,11.579988956451416,22.640878017032612,1739137669.8099911,11.579988956451416,31.96646035998452,1739137669.8099926,11.579988956451416,-0.07729243567553619,1739137669.8099942,11.579988956451416,0.01421221094663165,1739137669.809996,11.579988956451416,-0.08694928085061736,1739137669.809997,11.579988956451416,-0.019050754676280923,1739137669.8099983,11.579988956451416,2.4145453766136966,1739137669.8100002,11.579988956451416,0.0,1739137669.8100014,11.579988956451416,-0.02950201538185082,1739137669.8100028,11.579988956451416,0.024597156088406354,1739137669.8100042,11.579988956451416,2.4440473919955474 +1739137669.8301997,11.59998893737793,23.594527602052317,1739137669.8302028,11.59998893737793,-0.196284121759021,1739137669.8302064,11.59998893737793,22.640878017032612,1739137669.8302097,11.59998893737793,31.96646035998452,1739137669.8302116,11.59998893737793,-0.07729243567553619,1739137669.8302135,11.59998893737793,0.01421221094663165,1739137669.8302155,11.59998893737793,-0.08694928085061736,1739137669.8302171,11.59998893737793,-0.019050754676280923,1739137669.8302188,11.59998893737793,2.4145453766136966,1739137669.8302205,11.59998893737793,0.0,1739137669.8302221,11.59998893737793,-0.02950201538185082,1739137669.830224,11.59998893737793,0.024597156088406354,1739137669.8302257,11.59998893737793,2.4440473919955474 +1739137669.85046,11.619988918304443,23.863121434228916,1739137669.850463,11.619988918304443,-0.1895792652029753,1739137669.8504665,11.619988918304443,23.203650433383608,1739137669.8504853,11.619988918304443,32.51934694947646,1739137669.8504872,11.619988918304443,-0.08,1739137669.8504896,11.619988918304443,0.012658336152632862,1739137669.8504918,11.619988918304443,-0.11021732137102894,1739137669.8504932,11.619988918304443,-0.02258947537064897,1739137669.8504949,11.619988918304443,2.3921769361754204,1739137669.8504968,11.619988918304443,0.0,1739137669.8504987,11.619988918304443,-0.06592217297532448,1739137669.8505003,11.619988918304443,0.025390383008065055,1739137669.8505023,11.619988918304443,2.44075616829982 +1739137669.8703673,11.639988899230957,23.863121434228916,1739137669.8703701,11.639988899230957,-0.1895792652029753,1739137669.8703735,11.639988899230957,23.203650433383608,1739137669.870377,11.639988899230957,32.51934694947646,1739137669.8703785,11.639988899230957,-0.08,1739137669.8703809,11.639988899230957,0.012658336152632862,1739137669.8703825,11.639988899230957,-0.11021732137102894,1739137669.8703842,11.639988899230957,-0.02258947537064897,1739137669.870386,11.639988899230957,2.3921769361754204,1739137669.8703878,11.639988899230957,0.0,1739137669.8703895,11.639988899230957,-0.04857923212439941,1739137669.8703914,11.639988899230957,0.025390383008065055,1739137669.8703928,11.639988899230957,2.44075616829982 +1739137669.8901596,11.65998888015747,23.863121434228916,1739137669.8901627,11.65998888015747,-0.1895792652029753,1739137669.8901663,11.65998888015747,23.203650433383608,1739137669.8901696,11.65998888015747,32.51934694947646,1739137669.8901713,11.65998888015747,-0.08,1739137669.8901734,11.65998888015747,0.012658336152632862,1739137669.8901753,11.65998888015747,-0.11021732137102894,1739137669.8901768,11.65998888015747,-0.02258947537064897,1739137669.8901782,11.65998888015747,2.3921769361754204,1739137669.89018,11.65998888015747,0.0,1739137669.8901818,11.65998888015747,-0.04857923212439941,1739137669.8901837,11.65998888015747,0.025390383008065055,1739137669.890185,11.65998888015747,2.44075616829982 +1739137669.9103248,11.679988861083984,23.863121434228916,1739137669.9103274,11.679988861083984,-0.1895792652029753,1739137669.9103315,11.679988861083984,23.203650433383608,1739137669.9103348,11.679988861083984,32.51934694947646,1739137669.9103363,11.679988861083984,-0.08,1739137669.9103384,11.679988861083984,0.012658336152632862,1739137669.9103405,11.679988861083984,-0.11021732137102894,1739137669.9103422,11.679988861083984,-0.02258947537064897,1739137669.9103436,11.679988861083984,2.3921769361754204,1739137669.9103458,11.679988861083984,0.0,1739137669.9103475,11.679988861083984,-0.04857923212439941,1739137669.9103494,11.679988861083984,0.025390383008065055,1739137669.9103508,11.679988861083984,2.44075616829982 +1739137669.9301965,11.699988842010498,23.863121434228916,1739137669.9301996,11.699988842010498,-0.1895792652029753,1739137669.9302032,11.699988842010498,23.203650433383608,1739137669.9302065,11.699988842010498,32.51934694947646,1739137669.930208,11.699988842010498,-0.08,1739137669.9302104,11.699988842010498,0.012658336152632862,1739137669.930212,11.699988842010498,-0.11021732137102894,1739137669.9302137,11.699988842010498,-0.02258947537064897,1739137669.9302154,11.699988842010498,2.3921769361754204,1739137669.9302173,11.699988842010498,0.0,1739137669.930219,11.699988842010498,-0.04857923212439941,1739137669.930221,11.699988842010498,0.025390383008065055,1739137669.9302225,11.699988842010498,2.44075616829982 +1739137669.9510508,11.719988822937012,24.131239399020192,1739137669.9510548,11.719988822937012,-0.18267986708051698,1739137669.9510593,11.719988822937012,23.453156247425436,1739137669.951064,11.719988822937012,32.75244349121138,1739137669.951066,11.719988822937012,-0.07937404212271594,1739137669.951069,11.719988822937012,0.01198218715583894,1739137669.9510717,11.719988822937012,-0.12187414991329754,1739137669.9510744,11.719988822937012,-0.025182242838462612,1739137669.9510772,11.719988822937012,2.3810488214867127,1739137669.9510798,11.719988822937012,0.0,1739137669.9510822,11.719988822937012,-0.05938254139895897,1739137669.9510853,11.719988822937012,0.026118200938401514,1739137669.9510877,11.719988822937012,2.435286927327916 +1739137669.9706337,11.739988803863525,24.131239399020192,1739137669.9706373,11.739988803863525,-0.18267986708051698,1739137669.9706414,11.739988803863525,23.453156247425436,1739137669.970646,11.739988803863525,32.75244349121138,1739137669.970648,11.739988803863525,-0.07937404212271594,1739137669.9706511,11.739988803863525,0.01198218715583894,1739137669.9706538,11.739988803863525,-0.12187414991329754,1739137669.970656,11.739988803863525,-0.025182242838462612,1739137669.9706583,11.739988803863525,2.3810488214867127,1739137669.970661,11.739988803863525,0.0,1739137669.970663,11.739988803863525,-0.054238105841203144,1739137669.9706657,11.739988803863525,0.026118200938401514,1739137669.9706678,11.739988803863525,2.435286927327916 +1739137669.9907753,11.759988784790039,24.131239399020192,1739137669.9907787,11.759988784790039,-0.18267986708051698,1739137669.9907827,11.759988784790039,23.453156247425436,1739137669.990787,11.759988784790039,32.75244349121138,1739137669.9907892,11.759988784790039,-0.07937404212271594,1739137669.9907925,11.759988784790039,0.01198218715583894,1739137669.9907947,11.759988784790039,-0.12187414991329754,1739137669.9907973,11.759988784790039,-0.025182242838462612,1739137669.9907997,11.759988784790039,2.3810488214867127,1739137669.9908028,11.759988784790039,0.0,1739137669.990805,11.759988784790039,-0.054238105841203144,1739137669.9908085,11.759988784790039,0.026118200938401514,1739137669.990811,11.759988784790039,2.435286927327916 +1739137670.011094,11.779988765716553,24.131239399020192,1739137670.011098,11.779988765716553,-0.18267986708051698,1739137670.0111024,11.779988765716553,23.453156247425436,1739137670.0111067,11.779988765716553,32.75244349121138,1739137670.0111089,11.779988765716553,-0.07937404212271594,1739137670.0111115,11.779988765716553,0.01198218715583894,1739137670.011114,11.779988765716553,-0.12187414991329754,1739137670.011116,11.779988765716553,-0.025182242838462612,1739137670.0111182,11.779988765716553,2.3810488214867127,1739137670.0111206,11.779988765716553,0.0,1739137670.011123,11.779988765716553,-0.054238105841203144,1739137670.0111256,11.779988765716553,0.026118200938401514,1739137670.0111277,11.779988765716553,2.435286927327916 +1739137670.0309408,11.799988746643066,24.131239399020192,1739137670.0309436,11.799988746643066,-0.18267986708051698,1739137670.0309463,11.799988746643066,23.453156247425436,1739137670.030949,11.799988746643066,32.75244349121138,1739137670.0309505,11.799988746643066,-0.07937404212271594,1739137670.0309525,11.799988746643066,0.01198218715583894,1739137670.030954,11.799988746643066,-0.12187414991329754,1739137670.0309553,11.799988746643066,-0.025182242838462612,1739137670.0309567,11.799988746643066,2.3810488214867127,1739137670.0309584,11.799988746643066,0.0,1739137670.0309596,11.799988746643066,-0.054238105841203144,1739137670.030961,11.799988746643066,0.026118200938401514,1739137670.0309625,11.799988746643066,2.435286927327916 +1739137670.050797,11.81998872756958,24.131239399020192,1739137670.0508003,11.81998872756958,-0.18267986708051698,1739137670.0508044,11.81998872756958,23.453156247425436,1739137670.0508091,11.81998872756958,32.75244349121138,1739137670.0508113,11.81998872756958,-0.07937404212271594,1739137670.0508142,11.81998872756958,0.01198218715583894,1739137670.050817,11.81998872756958,-0.12187414991329754,1739137670.0508194,11.81998872756958,-0.025182242838462612,1739137670.0508218,11.81998872756958,2.3810488214867127,1739137670.0508277,11.81998872756958,0.0,1739137670.0508306,11.81998872756958,-0.054238105841203144,1739137670.0508347,11.81998872756958,0.026118200938401514,1739137670.050838,11.81998872756958,2.435286927327916 +1739137670.0699525,11.839988708496094,24.39872046757109,1739137670.0699549,11.839988708496094,-0.17561337571940694,1739137670.0699577,11.839988708496094,23.594023179458176,1739137670.0699606,11.839988708496094,32.87519317660323,1739137670.0699623,11.839988708496094,-0.079,1739137670.0699642,11.839988708496094,0.011397334205531306,1739137670.0699658,11.839988708496094,-0.13021355489563313,1739137670.0699673,11.839988708496094,-0.02783224245782121,1739137670.0699687,11.839988708496094,2.3731194419388575,1739137670.0699701,11.839988708496094,0.0,1739137670.0699718,11.839988708496094,-0.0578474461082162,1739137670.0699732,11.839988708496094,0.026758702437660885,1739137670.0699744,11.839988708496094,2.4292481537280084 +1739137670.0899873,11.859988689422607,24.39872046757109,1739137670.0899897,11.859988689422607,-0.17561337571940694,1739137670.0899925,11.859988689422607,23.594023179458176,1739137670.089995,11.859988689422607,32.87519317660323,1739137670.0899966,11.859988689422607,-0.079,1739137670.089998,11.859988689422607,0.011397334205531306,1739137670.0899994,11.859988689422607,-0.13021355489563313,1739137670.0900006,11.859988689422607,-0.02783224245782121,1739137670.0900016,11.859988689422607,2.3731194419388575,1739137670.0900033,11.859988689422607,0.0,1739137670.0900042,11.859988689422607,-0.05612871178915091,1739137670.0900059,11.859988689422607,0.026758702437660885,1739137670.0900073,11.859988689422607,2.4292481537280084 +1739137670.1100008,11.879988670349121,24.39872046757109,1739137670.1100032,11.879988670349121,-0.17561337571940694,1739137670.1100063,11.879988670349121,23.594023179458176,1739137670.1100092,11.879988670349121,32.87519317660323,1739137670.1100106,11.879988670349121,-0.079,1739137670.1100125,11.879988670349121,0.011397334205531306,1739137670.1100142,11.879988670349121,-0.13021355489563313,1739137670.1100154,11.879988670349121,-0.02783224245782121,1739137670.110017,11.879988670349121,2.3731194419388575,1739137670.1100185,11.879988670349121,0.0,1739137670.11002,11.879988670349121,-0.05612871178915091,1739137670.1100218,11.879988670349121,0.026758702437660885,1739137670.1100233,11.879988670349121,2.4292481537280084 +1739137670.1299117,11.899988651275635,24.39872046757109,1739137670.1299138,11.899988651275635,-0.17561337571940694,1739137670.1299164,11.899988651275635,23.594023179458176,1739137670.129919,11.899988651275635,32.87519317660323,1739137670.1299202,11.899988651275635,-0.079,1739137670.1299217,11.899988651275635,0.011397334205531306,1739137670.129923,11.899988651275635,-0.13021355489563313,1739137670.1299243,11.899988651275635,-0.02783224245782121,1739137670.1299255,11.899988651275635,2.3731194419388575,1739137670.129927,11.899988651275635,0.0,1739137670.129928,11.899988651275635,-0.05612871178915091,1739137670.1299295,11.899988651275635,0.026758702437660885,1739137670.1299307,11.899988651275635,2.4292481537280084 +1739137670.1500514,11.919988632202148,24.39872046757109,1739137670.150054,11.919988632202148,-0.17561337571940694,1739137670.150057,11.919988632202148,23.594023179458176,1739137670.1500597,11.919988632202148,32.87519317660323,1739137670.1500614,11.919988632202148,-0.079,1739137670.1500633,11.919988632202148,0.011397334205531306,1739137670.150065,11.919988632202148,-0.13021355489563313,1739137670.1500666,11.919988632202148,-0.02783224245782121,1739137670.1500683,11.919988632202148,2.3731194419388575,1739137670.1500697,11.919988632202148,0.0,1739137670.1500714,11.919988632202148,-0.05612871178915091,1739137670.1500728,11.919988632202148,0.026758702437660885,1739137670.150074,11.919988632202148,2.4292481537280084 +1739137670.169882,11.939988613128662,24.66553221761235,1739137670.1698842,11.939988613128662,-0.16840663441295156,1739137670.169887,11.939988613128662,23.87082896455323,1739137670.1698895,11.939988613128662,33.133539076861794,1739137670.1698906,11.939988613128662,-0.079,1739137670.169892,11.939988613128662,0.010557775155666398,1739137670.1698933,11.939988613128662,-0.14150374973148577,1739137670.1698945,11.939988613128662,-0.030306346034276725,1739137670.169896,11.939988613128662,2.3624264130411414,1739137670.1698973,11.939988613128662,0.0,1739137670.1698985,11.939988613128662,-0.06479548054287035,1739137670.1698997,11.939988613128662,0.02726801771130469,1739137670.169901,11.939988613128662,2.423094858782511 +1739137670.1953306,11.959988594055176,24.66553221761235,1739137670.1953392,11.959988594055176,-0.16840663441295156,1739137670.195349,11.959988594055176,23.87082896455323,1739137670.1953585,11.959988594055176,33.133539076861794,1739137670.1953633,11.959988594055176,-0.079,1739137670.1953695,11.959988594055176,0.010557775155666398,1739137670.1953745,11.959988594055176,-0.14150374973148577,1739137670.1953793,11.959988594055176,-0.030306346034276725,1739137670.1953835,11.959988594055176,2.3624264130411414,1739137670.195389,11.959988594055176,0.0,1739137670.1953933,11.959988594055176,-0.06066844574136976,1739137670.1953986,11.959988594055176,0.02726801771130469,1739137670.1954033,11.959988594055176,2.423094858782511 +1739137670.2242212,11.97998857498169,24.66553221761235,1739137670.224228,11.97998857498169,-0.16840663441295156,1739137670.2242367,11.97998857498169,23.87082896455323,1739137670.2242472,11.97998857498169,33.133539076861794,1739137670.224253,11.97998857498169,-0.079,1739137670.2242606,11.97998857498169,0.010557775155666398,1739137670.2242672,11.97998857498169,-0.14150374973148577,1739137670.224274,11.97998857498169,-0.030306346034276725,1739137670.2242806,11.97998857498169,2.3624264130411414,1739137670.2242873,11.97998857498169,0.0,1739137670.224294,11.97998857498169,-0.06066844574136976,1739137670.2243009,11.97998857498169,0.02726801771130469,1739137670.2243075,11.97998857498169,2.423094858782511 +1739137670.2418683,12.00998854637146,24.66553221761235,1739137670.2418718,12.00998854637146,-0.16840663441295156,1739137670.2418761,12.00998854637146,23.87082896455323,1739137670.2418804,12.00998854637146,33.133539076861794,1739137670.2418823,12.00998854637146,-0.079,1739137670.241885,12.00998854637146,0.010557775155666398,1739137670.2418873,12.00998854637146,-0.14150374973148577,1739137670.2418892,12.00998854637146,-0.030306346034276725,1739137670.2418914,12.00998854637146,2.3624264130411414,1739137670.241894,12.00998854637146,0.0,1739137670.241896,12.00998854637146,-0.06066844574136976,1739137670.2418983,12.00998854637146,0.02726801771130469,1739137670.2419002,12.00998854637146,2.423094858782511 +1739137670.2614377,12.029988527297974,24.66553221761235,1739137670.2614415,12.029988527297974,-0.16840663441295156,1739137670.261446,12.029988527297974,23.87082896455323,1739137670.26145,12.029988527297974,33.133539076861794,1739137670.2614522,12.029988527297974,-0.079,1739137670.261455,12.029988527297974,0.010557775155666398,1739137670.2614572,12.029988527297974,-0.14150374973148577,1739137670.2614594,12.029988527297974,-0.030306346034276725,1739137670.2614613,12.029988527297974,2.3624264130411414,1739137670.2614636,12.029988527297974,0.0,1739137670.2614655,12.029988527297974,-0.06066844574136976,1739137670.261468,12.029988527297974,0.02726801771130469,1739137670.2614698,12.029988527297974,2.423094858782511 +1739137670.2807708,12.049988508224487,24.931631841886173,1739137670.2807739,12.049988508224487,-0.16109956282441118,1739137670.2807772,12.049988508224487,24.200688375664917,1739137670.2807806,12.049988508224487,33.44321527112101,1739137670.2807822,12.049988508224487,-0.07698252570042928,1739137670.2807841,12.049988508224487,0.009882332647215521,1739137670.2807856,12.049988508224487,-0.1513827752946191,1739137670.2807872,12.049988508224487,-0.03209134932946457,1739137670.2807887,12.049988508224487,2.3531094453073167,1739137670.2807906,12.049988508224487,0.0,1739137670.280792,12.049988508224487,-0.06562141218829536,1739137670.280794,12.049988508224487,0.027667902808585144,1739137670.280795,12.049988508224487,2.416372300866493 +1739137670.299874,12.069988489151001,24.931631841886173,1739137670.2998767,12.069988489151001,-0.16109956282441118,1739137670.2998798,12.069988489151001,24.200688375664917,1739137670.2998822,12.069988489151001,33.44321527112101,1739137670.2998836,12.069988489151001,-0.07698252570042928,1739137670.299885,12.069988489151001,0.009882332647215521,1739137670.2998867,12.069988489151001,-0.1513827752946191,1739137670.299888,12.069988489151001,-0.03209134932946457,1739137670.2998893,12.069988489151001,2.3531094453073167,1739137670.2998912,12.069988489151001,0.0,1739137670.2998924,12.069988489151001,-0.06326285555917632,1739137670.299894,12.069988489151001,0.027667902808585144,1739137670.2998953,12.069988489151001,2.416372300866493 +1739137670.3201725,12.089988470077515,24.931631841886173,1739137670.3201747,12.089988470077515,-0.16109956282441118,1739137670.3201773,12.089988470077515,24.200688375664917,1739137670.32018,12.089988470077515,33.44321527112101,1739137670.3201816,12.089988470077515,-0.07698252570042928,1739137670.320183,12.089988470077515,0.009882332647215521,1739137670.3201842,12.089988470077515,-0.1513827752946191,1739137670.3201857,12.089988470077515,-0.03209134932946457,1739137670.3201869,12.089988470077515,2.3531094453073167,1739137670.3201885,12.089988470077515,0.0,1739137670.3201897,12.089988470077515,-0.06326285555917632,1739137670.320191,12.089988470077515,0.027667902808585144,1739137670.3201923,12.089988470077515,2.416372300866493 +1739137670.3400464,12.109988451004028,24.931631841886173,1739137670.3400521,12.109988451004028,-0.16109956282441118,1739137670.3400562,12.109988451004028,24.200688375664917,1739137670.3400607,12.109988451004028,33.44321527112101,1739137670.3400626,12.109988451004028,-0.07698252570042928,1739137670.3400652,12.109988451004028,0.009882332647215521,1739137670.3400676,12.109988451004028,-0.1513827752946191,1739137670.3400698,12.109988451004028,-0.03209134932946457,1739137670.3400722,12.109988451004028,2.3531094453073167,1739137670.3400743,12.109988451004028,0.0,1739137670.3400757,12.109988451004028,-0.06326285555917632,1739137670.3400786,12.109988451004028,0.027667902808585144,1739137670.34008,12.109988451004028,2.416372300866493 +1739137670.3599746,12.129988431930542,24.931631841886173,1739137670.3599772,12.129988431930542,-0.16109956282441118,1739137670.35998,12.129988431930542,24.200688375664917,1739137670.3599825,12.129988431930542,33.44321527112101,1739137670.359984,12.129988431930542,-0.07698252570042928,1739137670.3599854,12.129988431930542,0.009882332647215521,1739137670.359987,12.129988431930542,-0.1513827752946191,1739137670.3599882,12.129988431930542,-0.03209134932946457,1739137670.3599894,12.129988431930542,2.3531094453073167,1739137670.3599916,12.129988431930542,0.0,1739137670.3599927,12.129988431930542,-0.06326285555917632,1739137670.3599942,12.129988431930542,0.027667902808585144,1739137670.3599954,12.129988431930542,2.416372300866493 +1739137670.4002185,12.16998839378357,25.196978720317748,1739137670.4002213,12.16998839378357,-0.1537166669050407,1739137670.4002244,12.16998839378357,24.665699203851474,1739137670.4002275,12.16998839378357,33.88730229595196,1739137670.4002292,12.16998839378357,-0.07474100601750458,1739137670.4002314,12.16998839378357,0.009087519719166525,1739137670.4002333,12.16998839378357,-0.1642433330771283,1739137670.4002347,12.16998839378357,-0.033400522464858,1739137670.4002364,12.16998839378357,2.341035607195729,1739137670.400238,12.16998839378357,0.0,1739137670.4002397,12.16998839378357,-0.07300359152149014,1739137670.4002414,12.16998839378357,0.02798742925377705,1739137670.4002433,12.16998839378357,2.409400750703772 +1739137670.4201374,12.189988374710083,25.196978720317748,1739137670.4201398,12.189988374710083,-0.1537166669050407,1739137670.4201427,12.189988374710083,24.665699203851474,1739137670.420145,12.189988374710083,33.88730229595196,1739137670.4201465,12.189988374710083,-0.07474100601750458,1739137670.420148,12.189988374710083,0.009087519719166525,1739137670.4201493,12.189988374710083,-0.1642433330771283,1739137670.4201505,12.189988374710083,-0.033400522464858,1739137670.4201517,12.189988374710083,2.341035607195729,1739137670.4201534,12.189988374710083,0.0,1739137670.4201546,12.189988374710083,-0.06836514350804279,1739137670.420156,12.189988374710083,0.02798742925377705,1739137670.4201572,12.189988374710083,2.409400750703772 +1739137670.4398396,12.209988355636597,25.196978720317748,1739137670.4398417,12.209988355636597,-0.1537166669050407,1739137670.4398446,12.209988355636597,24.665699203851474,1739137670.4398475,12.209988355636597,33.88730229595196,1739137670.4398484,12.209988355636597,-0.07474100601750458,1739137670.4398503,12.209988355636597,0.009087519719166525,1739137670.4398515,12.209988355636597,-0.1642433330771283,1739137670.4398527,12.209988355636597,-0.033400522464858,1739137670.4398541,12.209988355636597,2.341035607195729,1739137670.4398553,12.209988355636597,0.0,1739137670.4398565,12.209988355636597,-0.06836514350804279,1739137670.4398582,12.209988355636597,0.02798742925377705,1739137670.4398594,12.209988355636597,2.409400750703772 +1739137670.4599333,12.22998833656311,25.196978720317748,1739137670.4599354,12.22998833656311,-0.1537166669050407,1739137670.4599383,12.22998833656311,24.665699203851474,1739137670.459941,12.22998833656311,33.88730229595196,1739137670.459942,12.22998833656311,-0.07474100601750458,1739137670.4599438,12.22998833656311,0.009087519719166525,1739137670.459945,12.22998833656311,-0.1642433330771283,1739137670.4599462,12.22998833656311,-0.033400522464858,1739137670.4599476,12.22998833656311,2.341035607195729,1739137670.459949,12.22998833656311,0.0,1739137670.4599504,12.22998833656311,-0.06836514350804279,1739137670.4599519,12.22998833656311,0.02798742925377705,1739137670.459953,12.22998833656311,2.409400750703772 +1739137670.4798877,12.249988317489624,25.196978720317748,1739137670.4798903,12.249988317489624,-0.1537166669050407,1739137670.4798934,12.249988317489624,24.665699203851474,1739137670.4798963,12.249988317489624,33.88730229595196,1739137670.4798982,12.249988317489624,-0.07474100601750458,1739137670.4799,12.249988317489624,0.009087519719166525,1739137670.479901,12.249988317489624,-0.1642433330771283,1739137670.4799025,12.249988317489624,-0.033400522464858,1739137670.4799037,12.249988317489624,2.341035607195729,1739137670.4799058,12.249988317489624,0.0,1739137670.479907,12.249988317489624,-0.06836514350804279,1739137670.4799092,12.249988317489624,0.02798742925377705,1739137670.4799104,12.249988317489624,2.409400750703772 +1739137670.4999168,12.269988298416138,25.461531283603623,1739137670.4999192,12.269988298416138,-0.14627936436314837,1739137670.499922,12.269988298416138,24.698239169135636,1739137670.4999244,12.269988298416138,33.897287706829964,1739137670.4999259,12.269988298416138,-0.0746556606253849,1739137670.4999273,12.269988298416138,0.00849028577155228,1739137670.4999285,12.269988298416138,-0.1665470601762432,1739137670.4999301,12.269988298416138,-0.035944134903735284,1739137670.499931,12.269988298416138,2.338879357962952,1739137670.4999328,12.269988298416138,0.0,1739137670.499934,12.269988298416138,-0.058128948501821626,1739137670.4999354,12.269988298416138,0.028233847513468108,1739137670.4999368,12.269988298416138,2.401882687474131 +1739137670.5259311,12.289988279342651,25.461531283603623,1739137670.5259392,12.289988279342651,-0.14627936436314837,1739137670.5259485,12.289988279342651,24.698239169135636,1739137670.5259585,12.289988279342651,33.897287706829964,1739137670.5259633,12.289988279342651,-0.0746556606253849,1739137670.5259693,12.289988279342651,0.00849028577155228,1739137670.525974,12.289988279342651,-0.1665470601762432,1739137670.5259786,12.289988279342651,-0.035944134903735284,1739137670.5259836,12.289988279342651,2.338879357962952,1739137670.525989,12.289988279342651,0.0,1739137670.5259943,12.289988279342651,-0.06300332951117893,1739137670.5259995,12.289988279342651,0.028233847513468108,1739137670.5260043,12.289988279342651,2.401882687474131 +1739137670.5430884,12.309988260269165,25.461531283603623,1739137670.543097,12.309988260269165,-0.14627936436314837,1739137670.5431066,12.309988260269165,24.698239169135636,1739137670.5431163,12.309988260269165,33.897287706829964,1739137670.5431209,12.309988260269165,-0.0746556606253849,1739137670.543127,12.309988260269165,0.00849028577155228,1739137670.543132,12.309988260269165,-0.1665470601762432,1739137670.5431368,12.309988260269165,-0.035944134903735284,1739137670.5431414,12.309988260269165,2.338879357962952,1739137670.543147,12.309988260269165,0.0,1739137670.5431519,12.309988260269165,-0.06300332951117893,1739137670.543157,12.309988260269165,0.028233847513468108,1739137670.5431616,12.309988260269165,2.401882687474131 +1739137670.5676637,12.319988250732422,25.461531283603623,1739137670.5676723,12.319988250732422,-0.14627936436314837,1739137670.5676818,12.319988250732422,24.698239169135636,1739137670.5676918,12.319988250732422,33.897287706829964,1739137670.5676963,12.319988250732422,-0.0746556606253849,1739137670.5677023,12.319988250732422,0.00849028577155228,1739137670.567707,12.319988250732422,-0.1665470601762432,1739137670.5677118,12.319988250732422,-0.035944134903735284,1739137670.5677164,12.319988250732422,2.338879357962952,1739137670.5677218,12.319988250732422,0.0,1739137670.5677264,12.319988250732422,-0.06300332951117893,1739137670.5677314,12.319988250732422,0.028233847513468108,1739137670.5677361,12.319988250732422,2.401882687474131 +1739137670.5840633,12.349988222122192,25.461531283603623,1739137670.5840695,12.349988222122192,-0.14627936436314837,1739137670.5840766,12.349988222122192,24.698239169135636,1739137670.5840836,12.349988222122192,33.897287706829964,1739137670.5840864,12.349988222122192,-0.0746556606253849,1739137670.5840907,12.349988222122192,0.00849028577155228,1739137670.584094,12.349988222122192,-0.1665470601762432,1739137670.5840974,12.349988222122192,-0.035944134903735284,1739137670.5841007,12.349988222122192,2.338879357962952,1739137670.5841043,12.349988222122192,0.0,1739137670.5841076,12.349988222122192,-0.06300332951117893,1739137670.5841115,12.349988222122192,0.028233847513468108,1739137670.5841143,12.349988222122192,2.401882687474131 +1739137670.6101396,12.35998821258545,25.461531283603623,1739137670.610149,12.35998821258545,-0.14627936436314837,1739137670.6101606,12.35998821258545,24.698239169135636,1739137670.6101747,12.35998821258545,33.897287706829964,1739137670.610182,12.35998821258545,-0.0746556606253849,1739137670.6101916,12.35998821258545,0.00849028577155228,1739137670.6102004,12.35998821258545,-0.1665470601762432,1739137670.6102087,12.35998821258545,-0.035944134903735284,1739137670.6102173,12.35998821258545,2.338879357962952,1739137670.6102262,12.35998821258545,0.0,1739137670.610235,12.35998821258545,-0.06300332951117893,1739137670.6102445,12.35998821258545,0.028233847513468108,1739137670.610253,12.35998821258545,2.401882687474131 +1739137670.6266985,12.38998818397522,25.725296372674535,1739137670.626703,12.38998818397522,-0.13881038536015478,1739137670.6267085,12.38998818397522,24.94730127509136,1739137670.6267138,12.38998818397522,34.12594187064849,1739137670.6267164,12.38998818397522,-0.07272317755757576,1739137670.6267195,12.38998818397522,0.007866757920513568,1739137670.626722,12.38998818397522,-0.17242206234628174,1739137670.6267247,12.38998818397522,-0.037524007020487554,1739137670.626727,12.38998818397522,2.333389442620972,1739137670.62673,12.38998818397522,0.0,1739137670.6267326,12.38998818397522,-0.06050240051913118,1739137670.6267354,12.38998818397522,0.028392422808606925,1739137670.6267378,12.38998818397522,2.395082762302661 +1739137670.6475406,12.409988164901733,25.725296372674535,1739137670.6475453,12.409988164901733,-0.13881038536015478,1739137670.6475508,12.409988164901733,24.94730127509136,1739137670.6475558,12.409988164901733,34.12594187064849,1739137670.6475585,12.409988164901733,-0.07272317755757576,1739137670.6475618,12.409988164901733,0.007866757920513568,1739137670.6475642,12.409988164901733,-0.17242206234628174,1739137670.6475666,12.409988164901733,-0.037524007020487554,1739137670.647569,12.409988164901733,2.333389442620972,1739137670.6475718,12.409988164901733,0.0,1739137670.6475742,12.409988164901733,-0.06169331968168912,1739137670.647577,12.409988164901733,0.028392422808606925,1739137670.6475794,12.409988164901733,2.395082762302661 +1739137670.668151,12.429988145828247,25.725296372674535,1739137670.6681561,12.429988145828247,-0.13881038536015478,1739137670.668163,12.429988145828247,24.94730127509136,1739137670.6681714,12.429988145828247,34.12594187064849,1739137670.6681762,12.429988145828247,-0.07272317755757576,1739137670.6681821,12.429988145828247,0.007866757920513568,1739137670.6681874,12.429988145828247,-0.17242206234628174,1739137670.6681929,12.429988145828247,-0.037524007020487554,1739137670.668198,12.429988145828247,2.333389442620972,1739137670.6682036,12.429988145828247,0.0,1739137670.6682088,12.429988145828247,-0.06169331968168912,1739137670.6682146,12.429988145828247,0.028392422808606925,1739137670.6682198,12.429988145828247,2.395082762302661 +1739137670.6856956,12.44998812675476,25.725296372674535,1739137670.6856983,12.44998812675476,-0.13881038536015478,1739137670.6857014,12.44998812675476,24.94730127509136,1739137670.6857045,12.44998812675476,34.12594187064849,1739137670.685706,12.44998812675476,-0.07272317755757576,1739137670.685708,12.44998812675476,0.007866757920513568,1739137670.6857095,12.44998812675476,-0.17242206234628174,1739137670.6857111,12.44998812675476,-0.037524007020487554,1739137670.6857126,12.44998812675476,2.333389442620972,1739137670.6857142,12.44998812675476,0.0,1739137670.6857157,12.44998812675476,-0.06169331968168912,1739137670.6857176,12.44998812675476,0.028392422808606925,1739137670.6857188,12.44998812675476,2.395082762302661 +1739137670.7068098,12.469988107681274,25.725296372674535,1739137670.7068138,12.469988107681274,-0.13881038536015478,1739137670.7068183,12.469988107681274,24.94730127509136,1739137670.7068233,12.469988107681274,34.12594187064849,1739137670.7068262,12.469988107681274,-0.07272317755757576,1739137670.7068298,12.469988107681274,0.007866757920513568,1739137670.7068331,12.469988107681274,-0.17242206234628174,1739137670.7068367,12.469988107681274,-0.037524007020487554,1739137670.7068398,12.469988107681274,2.333389442620972,1739137670.7068431,12.469988107681274,0.0,1739137670.7068465,12.469988107681274,-0.06169331968168912,1739137670.7068498,12.469988107681274,0.028392422808606925,1739137670.706853,12.469988107681274,2.395082762302661 +1739137670.7251472,12.489988088607788,25.98831215095895,1739137670.7251492,12.489988088607788,-0.13132894397504646,1739137670.7251518,12.489988088607788,25.728566183088265,1739137670.7251544,12.489988088607788,34.8869853210231,1739137670.7251556,12.489988088607788,-0.06892007339488454,1739137670.725157,12.489988088607788,0.007013163221297567,1739137670.7251585,12.489988088607788,-0.19099608895294226,1739137670.7251596,12.489988088607788,-0.03704432985611043,1739137670.7251606,12.489988088607788,2.316117508905418,1739137670.7251623,12.489988088607788,0.0,1739137670.7251632,12.489988088607788,-0.08180755170568223,1739137670.725165,12.489988088607788,0.028477718094755897,1739137670.725166,12.489988088607788,2.3883468501006546 +1739137670.7454584,12.509988069534302,25.98831215095895,1739137670.7454607,12.509988069534302,-0.13132894397504646,1739137670.7454634,12.509988069534302,25.728566183088265,1739137670.7454655,12.509988069534302,34.8869853210231,1739137670.745467,12.509988069534302,-0.06892007339488454,1739137670.7454684,12.509988069534302,0.007013163221297567,1739137670.7454698,12.509988069534302,-0.19099608895294226,1739137670.745471,12.509988069534302,-0.03704432985611043,1739137670.745472,12.509988069534302,2.316117508905418,1739137670.7454736,12.509988069534302,0.0,1739137670.7454748,12.509988069534302,-0.07222934119523661,1739137670.745476,12.509988069534302,0.028477718094755897,1739137670.7454774,12.509988069534302,2.3883468501006546 +1739137670.7650905,12.529988050460815,25.98831215095895,1739137670.765093,12.529988050460815,-0.13132894397504646,1739137670.7650957,12.529988050460815,25.728566183088265,1739137670.7650983,12.529988050460815,34.8869853210231,1739137670.7650995,12.529988050460815,-0.06892007339488454,1739137670.765101,12.529988050460815,0.007013163221297567,1739137670.7651026,12.529988050460815,-0.19099608895294226,1739137670.7651038,12.529988050460815,-0.03704432985611043,1739137670.765105,12.529988050460815,2.316117508905418,1739137670.7651067,12.529988050460815,0.0,1739137670.7651076,12.529988050460815,-0.07222934119523661,1739137670.7651093,12.529988050460815,0.028477718094755897,1739137670.7651105,12.529988050460815,2.3883468501006546 +1739137670.7852309,12.549988031387329,25.98831215095895,1739137670.785234,12.549988031387329,-0.13132894397504646,1739137670.7852368,12.549988031387329,25.728566183088265,1739137670.7852392,12.549988031387329,34.8869853210231,1739137670.7852407,12.549988031387329,-0.06892007339488454,1739137670.785242,12.549988031387329,0.007013163221297567,1739137670.7852437,12.549988031387329,-0.19099608895294226,1739137670.785245,12.549988031387329,-0.03704432985611043,1739137670.785246,12.549988031387329,2.316117508905418,1739137670.7852478,12.549988031387329,0.0,1739137670.785249,12.549988031387329,-0.07222934119523661,1739137670.7852507,12.549988031387329,0.028477718094755897,1739137670.7852519,12.549988031387329,2.3883468501006546 +1739137670.8051958,12.569988012313843,25.98831215095895,1739137670.8051984,12.569988012313843,-0.13132894397504646,1739137670.8052008,12.569988012313843,25.728566183088265,1739137670.8052034,12.569988012313843,34.8869853210231,1739137670.8052046,12.569988012313843,-0.06892007339488454,1739137670.8052063,12.569988012313843,0.007013163221297567,1739137670.8052075,12.569988012313843,-0.19099608895294226,1739137670.805209,12.569988012313843,-0.03704432985611043,1739137670.80521,12.569988012313843,2.316117508905418,1739137670.8052115,12.569988012313843,0.0,1739137670.805213,12.569988012313843,-0.07222934119523661,1739137670.8052142,12.569988012313843,0.028477718094755897,1739137670.8052156,12.569988012313843,2.3883468501006546 +1739137670.8252375,12.589987993240356,25.98831215095895,1739137670.8252401,12.589987993240356,-0.13132894397504646,1739137670.8252437,12.589987993240356,25.728566183088265,1739137670.8252466,12.589987993240356,34.8869853210231,1739137670.8252478,12.589987993240356,-0.06892007339488454,1739137670.8252494,12.589987993240356,0.007013163221297567,1739137670.8252509,12.589987993240356,-0.19099608895294226,1739137670.8252523,12.589987993240356,-0.03704432985611043,1739137670.8252537,12.589987993240356,2.316117508905418,1739137670.8252552,12.589987993240356,0.0,1739137670.825256,12.589987993240356,-0.07222934119523661,1739137670.825258,12.589987993240356,0.028477718094755897,1739137670.8252592,12.589987993240356,2.3883468501006546 +1739137670.8452644,12.60998797416687,26.250509488239377,1739137670.8452673,12.60998797416687,-0.12385172264585265,1739137670.8452706,12.60998797416687,25.754516242257697,1739137670.8452733,12.60998797416687,34.88864641137735,1739137670.8452752,12.60998797416687,-0.06891176794311327,1739137670.8452766,12.60998797416687,0.00636007676253702,1739137670.8452785,12.60998797416687,-0.19165354443092636,1739137670.8452797,12.60998797416687,-0.039448028606211744,1739137670.8452811,12.60998797416687,2.3155084913317623,1739137670.8452826,12.60998797416687,0.0,1739137670.8452837,12.60998797416687,-0.05793540131164729,1739137670.8452857,12.60998797416687,0.028548356051261686,1739137670.8452868,12.60998797416687,2.380250534083429 +1739137670.8652704,12.629987955093384,26.250509488239377,1739137670.865273,12.629987955093384,-0.12385172264585265,1739137670.8652763,12.629987955093384,25.754516242257697,1739137670.8652792,12.629987955093384,34.88864641137735,1739137670.8652806,12.629987955093384,-0.06891176794311327,1739137670.8652823,12.629987955093384,0.00636007676253702,1739137670.8652835,12.629987955093384,-0.19165354443092636,1739137670.865285,12.629987955093384,-0.039448028606211744,1739137670.865286,12.629987955093384,2.3155084913317623,1739137670.8652875,12.629987955093384,0.0,1739137670.8652887,12.629987955093384,-0.0647420427516665,1739137670.8652902,12.629987955093384,0.028548356051261686,1739137670.8652916,12.629987955093384,2.380250534083429 +1739137670.885105,12.649987936019897,26.250509488239377,1739137670.8851078,12.649987936019897,-0.12385172264585265,1739137670.88511,12.649987936019897,25.754516242257697,1739137670.8851125,12.649987936019897,34.88864641137735,1739137670.8851142,12.649987936019897,-0.06891176794311327,1739137670.8851156,12.649987936019897,0.00636007676253702,1739137670.8851168,12.649987936019897,-0.19165354443092636,1739137670.8851182,12.649987936019897,-0.039448028606211744,1739137670.8851192,12.649987936019897,2.3155084913317623,1739137670.8851209,12.649987936019897,0.0,1739137670.8851218,12.649987936019897,-0.0647420427516665,1739137670.8851233,12.649987936019897,0.028548356051261686,1739137670.8851247,12.649987936019897,2.380250534083429 +1739137670.9052618,12.669987916946411,26.250509488239377,1739137670.9052646,12.669987916946411,-0.12385172264585265,1739137670.905268,12.669987916946411,25.754516242257697,1739137670.905271,12.669987916946411,34.88864641137735,1739137670.9052722,12.669987916946411,-0.06891176794311327,1739137670.9052742,12.669987916946411,0.00636007676253702,1739137670.9052753,12.669987916946411,-0.19165354443092636,1739137670.905277,12.669987916946411,-0.039448028606211744,1739137670.9052782,12.669987916946411,2.3155084913317623,1739137670.9052796,12.669987916946411,0.0,1739137670.905281,12.669987916946411,-0.0647420427516665,1739137670.9052825,12.669987916946411,0.028548356051261686,1739137670.9052842,12.669987916946411,2.380250534083429 +1739137670.9252264,12.689987897872925,26.250509488239377,1739137670.9252293,12.689987897872925,-0.12385172264585265,1739137670.9252324,12.689987897872925,25.754516242257697,1739137670.9252353,12.689987897872925,34.88864641137735,1739137670.9252365,12.689987897872925,-0.06891176794311327,1739137670.9252386,12.689987897872925,0.00636007676253702,1739137670.9252398,12.689987897872925,-0.19165354443092636,1739137670.925241,12.689987897872925,-0.039448028606211744,1739137670.9252427,12.689987897872925,2.3155084913317623,1739137670.925244,12.689987897872925,0.0,1739137670.9252458,12.689987897872925,-0.0647420427516665,1739137670.9252474,12.689987897872925,0.028548356051261686,1739137670.9252489,12.689987897872925,2.380250534083429 +1739137670.9451983,12.709987878799438,26.51188026147817,1739137670.9452007,12.709987878799438,-0.11638587101644404,1739137670.9452033,12.709987878799438,25.904138400012876,1739137670.945206,12.709987878799438,35.01721208537053,1739137670.9452074,12.709987878799438,-0.06826893957314735,1739137670.945209,12.709987878799438,0.005657206459112468,1739137670.9452105,12.709987878799438,-0.19472210451821656,1739137670.945212,12.709987878799438,-0.041341150238142284,1739137670.9452128,12.709987878799438,2.312668124080566,1739137670.9452145,12.709987878799438,0.0,1739137670.9452157,12.709987878799438,-0.056766000526525126,1739137670.9452174,12.709987878799438,0.02855296245242706,1739137670.9452186,12.709987878799438,2.3732322418497223 +1739137670.9652178,12.729987859725952,26.51188026147817,1739137670.965221,12.729987859725952,-0.11638587101644404,1739137670.965224,12.729987859725952,25.904138400012876,1739137670.9652267,12.729987859725952,35.01721208537053,1739137670.9652283,12.729987859725952,-0.06826893957314735,1739137670.96523,12.729987859725952,0.005657206459112468,1739137670.9652317,12.729987859725952,-0.19472210451821656,1739137670.965233,12.729987859725952,-0.041341150238142284,1739137670.9652345,12.729987859725952,2.312668124080566,1739137670.965236,12.729987859725952,0.0,1739137670.9652371,12.729987859725952,-0.060564117769156045,1739137670.965239,12.729987859725952,0.02855296245242706,1739137670.9652402,12.729987859725952,2.3732322418497223 +1739137670.9852872,12.749987840652466,26.51188026147817,1739137670.9852898,12.749987840652466,-0.11638587101644404,1739137670.9852924,12.749987840652466,25.904138400012876,1739137670.985295,12.749987840652466,35.01721208537053,1739137670.9852965,12.749987840652466,-0.06826893957314735,1739137670.9852982,12.749987840652466,0.005657206459112468,1739137670.9852993,12.749987840652466,-0.19472210451821656,1739137670.985301,12.749987840652466,-0.041341150238142284,1739137670.9853024,12.749987840652466,2.312668124080566,1739137670.9853044,12.749987840652466,0.0,1739137670.9853055,12.749987840652466,-0.060564117769156045,1739137670.985307,12.749987840652466,0.02855296245242706,1739137670.9853082,12.749987840652466,2.3732322418497223 +1739137671.0053887,12.76998782157898,26.51188026147817,1739137671.0053914,12.76998782157898,-0.11638587101644404,1739137671.0053942,12.76998782157898,25.904138400012876,1739137671.0053968,12.76998782157898,35.01721208537053,1739137671.005398,12.76998782157898,-0.06826893957314735,1739137671.0053997,12.76998782157898,0.005657206459112468,1739137671.0054014,12.76998782157898,-0.19472210451821656,1739137671.0054026,12.76998782157898,-0.041341150238142284,1739137671.005404,12.76998782157898,2.312668124080566,1739137671.0054057,12.76998782157898,0.0,1739137671.005407,12.76998782157898,-0.060564117769156045,1739137671.0054083,12.76998782157898,0.02855296245242706,1739137671.0054095,12.76998782157898,2.3732322418497223 +1739137671.0251791,12.789987802505493,26.51188026147817,1739137671.025183,12.789987802505493,-0.11638587101644404,1739137671.0251858,12.789987802505493,25.904138400012876,1739137671.0251887,12.789987802505493,35.01721208537053,1739137671.0251899,12.789987802505493,-0.06826893957314735,1739137671.0251913,12.789987802505493,0.005657206459112468,1739137671.025193,12.789987802505493,-0.19472210451821656,1739137671.0251942,12.789987802505493,-0.041341150238142284,1739137671.0251958,12.789987802505493,2.312668124080566,1739137671.0251973,12.789987802505493,0.0,1739137671.0251987,12.789987802505493,-0.060564117769156045,1739137671.0252001,12.789987802505493,0.02855296245242706,1739137671.0252016,12.789987802505493,2.3732322418497223 +1739137671.045246,12.809987783432007,26.51188026147817,1739137671.0452485,12.809987783432007,-0.11638587101644404,1739137671.0452518,12.809987783432007,25.904138400012876,1739137671.0452545,12.809987783432007,35.01721208537053,1739137671.045256,12.809987783432007,-0.06826893957314735,1739137671.0452576,12.809987783432007,0.005657206459112468,1739137671.0452588,12.809987783432007,-0.19472210451821656,1739137671.0452604,12.809987783432007,-0.041341150238142284,1739137671.0452619,12.809987783432007,2.312668124080566,1739137671.0452633,12.809987783432007,0.0,1739137671.0452647,12.809987783432007,-0.060564117769156045,1739137671.0452662,12.809987783432007,0.02855296245242706,1739137671.0452673,12.809987783432007,2.3732322418497223 +1739137671.0653417,12.82998776435852,26.772504845156956,1739137671.0653448,12.82998776435852,-0.10895126997868498,1739137671.065348,12.82998776435852,26.586329260821863,1739137671.0653503,12.82998776435852,35.67972878132622,1739137671.065352,12.82998776435852,-0.06521915673390526,1739137671.0653534,12.82998776435852,0.004909696013976854,1739137671.065355,12.82998776435852,-0.20983508205844165,1739137671.0653563,12.82998776435852,-0.04062071484767149,1739137671.0653577,12.82998776435852,2.2987297759494063,1739137671.065359,12.82998776435852,0.0,1739137671.0653603,12.82998776435852,-0.07466068835158375,1739137671.065362,12.82998776435852,0.028469445656248725,1739137671.0653632,12.82998776435852,2.366677808289426 +1739137671.0853658,12.849987745285034,26.772504845156956,1739137671.0853686,12.849987745285034,-0.10895126997868498,1739137671.085372,12.849987745285034,26.586329260821863,1739137671.0853748,12.849987745285034,35.67972878132622,1739137671.0853763,12.849987745285034,-0.06521915673390526,1739137671.085378,12.849987745285034,0.004909696013976854,1739137671.0853796,12.849987745285034,-0.20983508205844165,1739137671.085381,12.849987745285034,-0.04062071484767149,1739137671.0853827,12.849987745285034,2.2987297759494063,1739137671.0853841,12.849987745285034,0.0,1739137671.0853856,12.849987745285034,-0.06794803234001989,1739137671.0853872,12.849987745285034,0.028469445656248725,1739137671.0853887,12.849987745285034,2.366677808289426 +1739137671.1054242,12.869987726211548,26.772504845156956,1739137671.105427,12.869987726211548,-0.10895126997868498,1739137671.1054301,12.869987726211548,26.586329260821863,1739137671.1054327,12.869987726211548,35.67972878132622,1739137671.1054342,12.869987726211548,-0.06521915673390526,1739137671.1054358,12.869987726211548,0.004909696013976854,1739137671.1054378,12.869987726211548,-0.20983508205844165,1739137671.105439,12.869987726211548,-0.04062071484767149,1739137671.1054401,12.869987726211548,2.2987297759494063,1739137671.1054418,12.869987726211548,0.0,1739137671.1054432,12.869987726211548,-0.06794803234001989,1739137671.105445,12.869987726211548,0.028469445656248725,1739137671.105446,12.869987726211548,2.366677808289426 +1739137671.1255484,12.889987707138062,26.772504845156956,1739137671.1255517,12.889987707138062,-0.10895126997868498,1739137671.1255553,12.889987707138062,26.586329260821863,1739137671.1255589,12.889987707138062,35.67972878132622,1739137671.125561,12.889987707138062,-0.06521915673390526,1739137671.1255634,12.889987707138062,0.004909696013976854,1739137671.1255655,12.889987707138062,-0.20983508205844165,1739137671.1255674,12.889987707138062,-0.04062071484767149,1739137671.1255696,12.889987707138062,2.2987297759494063,1739137671.1255715,12.889987707138062,0.0,1739137671.1255734,12.889987707138062,-0.06794803234001989,1739137671.1255758,12.889987707138062,0.028469445656248725,1739137671.1255774,12.889987707138062,2.366677808289426 +1739137671.1455293,12.909987688064575,26.772504845156956,1739137671.1455328,12.909987688064575,-0.10895126997868498,1739137671.145536,12.909987688064575,26.586329260821863,1739137671.145539,12.909987688064575,35.67972878132622,1739137671.1455407,12.909987688064575,-0.06521915673390526,1739137671.1455426,12.909987688064575,0.004909696013976854,1739137671.1455445,12.909987688064575,-0.20983508205844165,1739137671.1455464,12.909987688064575,-0.04062071484767149,1739137671.145548,12.909987688064575,2.2987297759494063,1739137671.1455498,12.909987688064575,0.0,1739137671.1455514,12.909987688064575,-0.06794803234001989,1739137671.1455529,12.909987688064575,0.028469445656248725,1739137671.1455545,12.909987688064575,2.366677808289426 +1739137671.165555,12.929987668991089,27.032358358937405,1739137671.1655583,12.929987668991089,-0.10156211977098284,1739137671.165562,12.929987668991089,26.93111690202614,1739137671.1655653,12.929987668991089,36.00203911331249,1739137671.1655667,12.929987668991089,-0.06447349706549048,1739137671.1655688,12.929987668991089,0.00413486414417208,1739137671.1655703,12.929987668991089,-0.21743898384061186,1739137671.1655722,12.929987668991089,-0.04150873640210004,1739137671.1655738,12.929987668991089,2.2917486718812135,1739137671.165576,12.929987668991089,0.0,1739137671.1655774,12.929987668991089,-0.06697319407131226,1739137671.165579,12.929987668991089,0.028378583908232474,1739137671.165581,12.929987668991089,2.359186074883803 +1739137671.1854765,12.949987649917603,27.032358358937405,1739137671.1854799,12.949987649917603,-0.10156211977098284,1739137671.1854835,12.949987649917603,26.93111690202614,1739137671.1854868,12.949987649917603,36.00203911331249,1739137671.1854885,12.949987649917603,-0.06447349706549048,1739137671.1854904,12.949987649917603,0.00413486414417208,1739137671.1854923,12.949987649917603,-0.21743898384061186,1739137671.1854937,12.949987649917603,-0.04150873640210004,1739137671.1854954,12.949987649917603,2.2917486718812135,1739137671.1854973,12.949987649917603,0.0,1739137671.1854987,12.949987649917603,-0.06743740300258949,1739137671.1855004,12.949987649917603,0.028378583908232474,1739137671.185502,12.949987649917603,2.359186074883803 +1739137671.2055135,12.969987630844116,27.032358358937405,1739137671.2055166,12.969987630844116,-0.10156211977098284,1739137671.2055197,12.969987630844116,26.93111690202614,1739137671.2055228,12.969987630844116,36.00203911331249,1739137671.2055244,12.969987630844116,-0.06447349706549048,1739137671.2055264,12.969987630844116,0.00413486414417208,1739137671.205528,12.969987630844116,-0.21743898384061186,1739137671.2055295,12.969987630844116,-0.04150873640210004,1739137671.205531,12.969987630844116,2.2917486718812135,1739137671.2055328,12.969987630844116,0.0,1739137671.2055342,12.969987630844116,-0.06743740300258949,1739137671.205536,12.969987630844116,0.028378583908232474,1739137671.2055376,12.969987630844116,2.359186074883803 +1739137671.2254732,12.98998761177063,27.032358358937405,1739137671.2254765,12.98998761177063,-0.10156211977098284,1739137671.2254798,12.98998761177063,26.93111690202614,1739137671.225483,12.98998761177063,36.00203911331249,1739137671.2254846,12.98998761177063,-0.06447349706549048,1739137671.2254865,12.98998761177063,0.00413486414417208,1739137671.2254882,12.98998761177063,-0.21743898384061186,1739137671.2254899,12.98998761177063,-0.04150873640210004,1739137671.2254913,12.98998761177063,2.2917486718812135,1739137671.225493,12.98998761177063,0.0,1739137671.2254946,12.98998761177063,-0.06743740300258949,1739137671.2254963,12.98998761177063,0.028378583908232474,1739137671.225498,12.98998761177063,2.359186074883803 +1739137671.2456052,13.009987592697144,27.032358358937405,1739137671.245608,13.009987592697144,-0.10156211977098284,1739137671.2456121,13.009987592697144,26.93111690202614,1739137671.2456152,13.009987592697144,36.00203911331249,1739137671.245617,13.009987592697144,-0.06447349706549048,1739137671.2456193,13.009987592697144,0.00413486414417208,1739137671.245621,13.009987592697144,-0.21743898384061186,1739137671.2456226,13.009987592697144,-0.04150873640210004,1739137671.245624,13.009987592697144,2.2917486718812135,1739137671.245626,13.009987592697144,0.0,1739137671.2456274,13.009987592697144,-0.06743740300258949,1739137671.245629,13.009987592697144,0.028378583908232474,1739137671.2456307,13.009987592697144,2.359186074883803 +1739137671.2670915,13.029987573623657,27.032358358937405,1739137671.2670958,13.029987573623657,-0.10156211977098284,1739137671.2671013,13.029987573623657,26.93111690202614,1739137671.2671072,13.029987573623657,36.00203911331249,1739137671.2671108,13.029987573623657,-0.06447349706549048,1739137671.2671156,13.029987573623657,0.00413486414417208,1739137671.2671196,13.029987573623657,-0.21743898384061186,1739137671.2671237,13.029987573623657,-0.04150873640210004,1739137671.2671278,13.029987573623657,2.2917486718812135,1739137671.2671318,13.029987573623657,0.0,1739137671.267136,13.029987573623657,-0.06743740300258949,1739137671.2671404,13.029987573623657,0.028378583908232474,1739137671.2671442,13.029987573623657,2.359186074883803 +1739137671.2855213,13.049987554550171,27.29139583989168,1739137671.2855244,13.049987554550171,-0.09421972981763549,1739137671.2855284,13.049987554550171,26.93760018143995,1739137671.2855318,13.049987554550171,35.98640359662003,1739137671.2855334,13.049987554550171,-0.06454830815014341,1739137671.2855356,13.049987554550171,0.003412453136857989,1739137671.285537,13.049987554550171,-0.2162696109900724,1739137671.2855387,13.049987554550171,-0.04393500293851723,1739137671.28554,13.049987554550171,2.292820886096166,1739137671.2855418,13.049987554550171,0.0,1739137671.2855434,13.049987554550171,-0.0513147298564225,1739137671.285545,13.049987554550171,0.028287722160216223,1739137671.285547,13.049987554550171,2.3518130831907555 +1739137671.3068757,13.069987535476685,27.29139583989168,1739137671.3068793,13.069987535476685,-0.09421972981763549,1739137671.3068838,13.069987535476685,26.93760018143995,1739137671.3068895,13.069987535476685,35.98640359662003,1739137671.3068926,13.069987535476685,-0.06454830815014341,1739137671.3068964,13.069987535476685,0.003412453136857989,1739137671.3069,13.069987535476685,-0.2162696109900724,1739137671.3069036,13.069987535476685,-0.04393500293851723,1739137671.3069074,13.069987535476685,2.292820886096166,1739137671.306911,13.069987535476685,0.0,1739137671.3069146,13.069987535476685,-0.05899219709458947,1739137671.3069184,13.069987535476685,0.028287722160216223,1739137671.3069217,13.069987535476685,2.3518130831907555 +1739137671.3551288,13.099987506866455,27.29139583989168,1739137671.3551333,13.099987506866455,-0.09421972981763549,1739137671.3551378,13.099987506866455,26.93760018143995,1739137671.3551428,13.099987506866455,35.98640359662003,1739137671.355146,13.099987506866455,-0.06454830815014341,1739137671.3551495,13.099987506866455,0.003412453136857989,1739137671.355153,13.099987506866455,-0.2162696109900724,1739137671.3551567,13.099987506866455,-0.04393500293851723,1739137671.3551598,13.099987506866455,2.292820886096166,1739137671.3551633,13.099987506866455,0.0,1739137671.3551667,13.099987506866455,-0.05899219709458947,1739137671.35517,13.099987506866455,0.028287722160216223,1739137671.3551733,13.099987506866455,2.3518130831907555 +1739137671.3857026,13.129987478256226,27.29139583989168,1739137671.38571,13.129987478256226,-0.09421972981763549,1739137671.3857188,13.129987478256226,26.93760018143995,1739137671.385728,13.129987478256226,35.98640359662003,1739137671.385732,13.129987478256226,-0.06454830815014341,1739137671.385737,13.129987478256226,0.003412453136857989,1739137671.3857415,13.129987478256226,-0.2162696109900724,1739137671.3857465,13.129987478256226,-0.04393500293851723,1739137671.3857508,13.129987478256226,2.292820886096166,1739137671.3857553,13.129987478256226,0.0,1739137671.385759,13.129987478256226,-0.05899219709458947,1739137671.385764,13.129987478256226,0.028287722160216223,1739137671.3857675,13.129987478256226,2.3518130831907555 +1739137671.4030604,13.14998745918274,27.549674178792863,1739137671.4030628,13.14998745918274,-0.08692856376996616,1739137671.4030654,13.14998745918274,26.944064431078527,1739137671.403068,13.14998745918274,35.973721931984954,1739137671.4030695,13.14998745918274,-0.06460898597136387,1739137671.4030712,13.14998745918274,0.002649501311690779,1739137671.4030726,13.14998745918274,-0.21463198161634517,1739137671.4030738,13.14998745918274,-0.04645219622539803,1739137671.403075,13.14998745918274,2.294323294452761,1739137671.4030766,13.14998745918274,0.0,1739137671.403078,13.14998745918274,-0.043940100119515386,1739137671.4030797,13.14998745918274,0.028130655100465533,1739137671.403081,13.14998745918274,2.345431063379066 +1739137671.423557,13.169987440109253,27.549674178792863,1739137671.4235606,13.169987440109253,-0.08692856376996616,1739137671.4235635,13.169987440109253,26.944064431078527,1739137671.4235663,13.169987440109253,35.973721931984954,1739137671.4235675,13.169987440109253,-0.06460898597136387,1739137671.4235692,13.169987440109253,0.002649501311690779,1739137671.4235706,13.169987440109253,-0.21463198161634517,1739137671.423572,13.169987440109253,-0.04645219622539803,1739137671.4235733,13.169987440109253,2.294323294452761,1739137671.4235744,13.169987440109253,0.0,1739137671.4235759,13.169987440109253,-0.051107768926304864,1739137671.4235773,13.169987440109253,0.028130655100465533,1739137671.4235787,13.169987440109253,2.345431063379066 +1739137671.4444175,13.189987421035767,27.549674178792863,1739137671.4444208,13.189987421035767,-0.08692856376996616,1739137671.4444263,13.189987421035767,26.944064431078527,1739137671.444431,13.189987421035767,35.973721931984954,1739137671.444435,13.189987421035767,-0.06460898597136387,1739137671.4444382,13.189987421035767,0.002649501311690779,1739137671.4444404,13.189987421035767,-0.21463198161634517,1739137671.4444423,13.189987421035767,-0.04645219622539803,1739137671.4444442,13.189987421035767,2.294323294452761,1739137671.4444482,13.189987421035767,0.0,1739137671.4444509,13.189987421035767,-0.051107768926304864,1739137671.4444735,13.189987421035767,0.028130655100465533,1739137671.4444778,13.189987421035767,2.345431063379066 +1739137671.4645827,13.20998740196228,27.549674178792863,1739137671.464585,13.20998740196228,-0.08692856376996616,1739137671.4645875,13.20998740196228,26.944064431078527,1739137671.46459,13.20998740196228,35.973721931984954,1739137671.4645913,13.20998740196228,-0.06460898597136387,1739137671.4645932,13.20998740196228,0.002649501311690779,1739137671.4645944,13.20998740196228,-0.21463198161634517,1739137671.4645958,13.20998740196228,-0.04645219622539803,1739137671.464597,13.20998740196228,2.294323294452761,1739137671.4645982,13.20998740196228,0.0,1739137671.4645996,13.20998740196228,-0.051107768926304864,1739137671.464601,13.20998740196228,0.028130655100465533,1739137671.4646025,13.20998740196228,2.345431063379066 +1739137671.4834337,13.229987382888794,27.549674178792863,1739137671.4834366,13.229987382888794,-0.08692856376996616,1739137671.4834397,13.229987382888794,26.944064431078527,1739137671.4834425,13.229987382888794,35.973721931984954,1739137671.4834437,13.229987382888794,-0.06460898597136387,1739137671.4834456,13.229987382888794,0.002649501311690779,1739137671.4834473,13.229987382888794,-0.21463198161634517,1739137671.4834485,13.229987382888794,-0.04645219622539803,1739137671.4834497,13.229987382888794,2.294323294452761,1739137671.4834514,13.229987382888794,0.0,1739137671.483453,13.229987382888794,-0.051107768926304864,1739137671.4834547,13.229987382888794,0.028130655100465533,1739137671.4834564,13.229987382888794,2.345431063379066 +1739137671.502891,13.249987363815308,27.549674178792863,1739137671.502893,13.249987363815308,-0.08692856376996616,1739137671.5028956,13.249987363815308,26.944064431078527,1739137671.5028982,13.249987363815308,35.973721931984954,1739137671.5028992,13.249987363815308,-0.06460898597136387,1739137671.502901,13.249987363815308,0.002649501311690779,1739137671.5029023,13.249987363815308,-0.21463198161634517,1739137671.5029035,13.249987363815308,-0.04645219622539803,1739137671.502905,13.249987363815308,2.294323294452761,1739137671.502906,13.249987363815308,0.0,1739137671.5029073,13.249987363815308,-0.051107768926304864,1739137671.502909,13.249987363815308,0.028130655100465533,1739137671.5029101,13.249987363815308,2.345431063379066 +1739137671.5231655,13.269987344741821,27.807303867630367,1739137671.523168,13.269987344741821,-0.07971346273164404,1739137671.5231705,13.269987344741821,26.950512388400504,1739137671.5231733,13.269987344741821,35.963812012379265,1739137671.5231748,13.269987344741821,-0.06465640185464466,1739137671.5231762,13.269987344741821,0.0018460159060833656,1739137671.5231774,13.269987344741821,-0.21182457956510903,1739137671.5231788,13.269987344741821,-0.04890115013301327,1739137671.52318,13.269987344741821,2.2969011767815055,1739137671.5231812,13.269987344741821,0.0,1739137671.5231826,13.269987344741821,-0.035776720015036734,1739137671.5231838,13.269987344741821,0.027818899464696095,1739137671.5231853,13.269987344741821,2.3399783999250188 +1739137671.5430176,13.289987325668335,27.807303867630367,1739137671.5430205,13.289987325668335,-0.07971346273164404,1739137671.5430233,13.289987325668335,26.950512388400504,1739137671.543026,13.289987325668335,35.963812012379265,1739137671.5430272,13.289987325668335,-0.06465640185464466,1739137671.5430288,13.289987325668335,0.0018460159060833656,1739137671.54303,13.289987325668335,-0.21182457956510903,1739137671.5430312,13.289987325668335,-0.04890115013301327,1739137671.5430326,13.289987325668335,2.2969011767815055,1739137671.543034,13.289987325668335,0.0,1739137671.543035,13.289987325668335,-0.043077223143513255,1739137671.5430367,13.289987325668335,0.027818899464696095,1739137671.543038,13.289987325668335,2.3399783999250188 +1739137671.563009,13.309987306594849,27.807303867630367,1739137671.563012,13.309987306594849,-0.07971346273164404,1739137671.5630145,13.309987306594849,26.950512388400504,1739137671.563017,13.309987306594849,35.963812012379265,1739137671.5630183,13.309987306594849,-0.06465640185464466,1739137671.5630198,13.309987306594849,0.0018460159060833656,1739137671.5630214,13.309987306594849,-0.21182457956510903,1739137671.5630226,13.309987306594849,-0.04890115013301327,1739137671.5630236,13.309987306594849,2.2969011767815055,1739137671.5630252,13.309987306594849,0.0,1739137671.5630264,13.309987306594849,-0.043077223143513255,1739137671.5630279,13.309987306594849,0.027818899464696095,1739137671.563029,13.309987306594849,2.3399783999250188 +1739137671.5830495,13.329987287521362,27.807303867630367,1739137671.5830526,13.329987287521362,-0.07971346273164404,1739137671.5830567,13.329987287521362,26.950512388400504,1739137671.5830593,13.329987287521362,35.963812012379265,1739137671.5830607,13.329987287521362,-0.06465640185464466,1739137671.583063,13.329987287521362,0.0018460159060833656,1739137671.5830648,13.329987287521362,-0.21182457956510903,1739137671.5830662,13.329987287521362,-0.04890115013301327,1739137671.5830672,13.329987287521362,2.2969011767815055,1739137671.583069,13.329987287521362,0.0,1739137671.5830705,13.329987287521362,-0.043077223143513255,1739137671.5830724,13.329987287521362,0.027818899464696095,1739137671.583074,13.329987287521362,2.3399783999250188 +1739137671.602752,13.349987268447876,27.807303867630367,1739137671.6027544,13.349987268447876,-0.07971346273164404,1739137671.602757,13.349987268447876,26.950512388400504,1739137671.6027594,13.349987268447876,35.963812012379265,1739137671.602761,13.349987268447876,-0.06465640185464466,1739137671.6027625,13.349987268447876,0.0018460159060833656,1739137671.602764,13.349987268447876,-0.21182457956510903,1739137671.6027653,13.349987268447876,-0.04890115013301327,1739137671.6027663,13.349987268447876,2.2969011767815055,1739137671.602768,13.349987268447876,0.0,1739137671.6027691,13.349987268447876,-0.043077223143513255,1739137671.6027708,13.349987268447876,0.027818899464696095,1739137671.6027718,13.349987268447876,2.3399783999250188 +1739137671.6232011,13.36998724937439,28.064371898445295,1739137671.6232045,13.36998724937439,-0.07260550368960583,1739137671.623208,13.36998724937439,27.392570144242214,1739137671.6232107,13.36998724937439,36.39192907322956,1739137671.6232126,13.36998724937439,-0.063,1739137671.6232142,13.36998724937439,0.0011534594393119485,1739137671.623216,13.36998724937439,-0.2186997889005855,1739137671.6232173,13.36998724937439,-0.04843574872096762,1739137671.6232188,13.36998724937439,2.290593183946033,1739137671.623221,13.36998724937439,0.0,1739137671.6232226,13.36998724937439,-0.04625179661566183,1739137671.623224,13.36998724937439,0.027418639754756606,1739137671.6232257,13.36998724937439,2.3353332781531293 +1739137671.643065,13.389987230300903,28.064371898445295,1739137671.6430676,13.389987230300903,-0.07260550368960583,1739137671.6430705,13.389987230300903,27.392570144242214,1739137671.6430733,13.389987230300903,36.39192907322956,1739137671.6430748,13.389987230300903,-0.063,1739137671.6430767,13.389987230300903,0.0011534594393119485,1739137671.6430779,13.389987230300903,-0.2186997889005855,1739137671.6430793,13.389987230300903,-0.04843574872096762,1739137671.6430805,13.389987230300903,2.290593183946033,1739137671.6430821,13.389987230300903,0.0,1739137671.6430836,13.389987230300903,-0.04474009420709635,1739137671.6430852,13.389987230300903,0.027418639754756606,1739137671.6430867,13.389987230300903,2.3353332781531293 +1739137671.6629477,13.409987211227417,28.064371898445295,1739137671.66295,13.409987211227417,-0.07260550368960583,1739137671.6629531,13.409987211227417,27.392570144242214,1739137671.662956,13.409987211227417,36.39192907322956,1739137671.6629574,13.409987211227417,-0.063,1739137671.662959,13.409987211227417,0.0011534594393119485,1739137671.6629605,13.409987211227417,-0.2186997889005855,1739137671.662962,13.409987211227417,-0.04843574872096762,1739137671.6629634,13.409987211227417,2.290593183946033,1739137671.662965,13.409987211227417,0.0,1739137671.6629663,13.409987211227417,-0.04474009420709635,1739137671.662968,13.409987211227417,0.027418639754756606,1739137671.6629694,13.409987211227417,2.3353332781531293 +1739137671.6830616,13.42998719215393,28.064371898445295,1739137671.683064,13.42998719215393,-0.07260550368960583,1739137671.6830673,13.42998719215393,27.392570144242214,1739137671.6830704,13.42998719215393,36.39192907322956,1739137671.683072,13.42998719215393,-0.063,1739137671.6830738,13.42998719215393,0.0011534594393119485,1739137671.6830754,13.42998719215393,-0.2186997889005855,1739137671.6830769,13.42998719215393,-0.04843574872096762,1739137671.6830783,13.42998719215393,2.290593183946033,1739137671.6830802,13.42998719215393,0.0,1739137671.6830816,13.42998719215393,-0.04474009420709635,1739137671.6830833,13.42998719215393,0.027418639754756606,1739137671.683085,13.42998719215393,2.3353332781531293 +1739137671.7032163,13.449987173080444,28.064371898445295,1739137671.7032194,13.449987173080444,-0.07260550368960583,1739137671.7032228,13.449987173080444,27.392570144242214,1739137671.7032259,13.449987173080444,36.39192907322956,1739137671.7032273,13.449987173080444,-0.063,1739137671.7032292,13.449987173080444,0.0011534594393119485,1739137671.7032306,13.449987173080444,-0.2186997889005855,1739137671.7032323,13.449987173080444,-0.04843574872096762,1739137671.7032337,13.449987173080444,2.290593183946033,1739137671.7032354,13.449987173080444,0.0,1739137671.7032368,13.449987173080444,-0.04474009420709635,1739137671.7032387,13.449987173080444,0.027418639754756606,1739137671.7032402,13.449987173080444,2.3353332781531293 +1739137671.7234342,13.469987154006958,28.064371898445295,1739137671.7234375,13.469987154006958,-0.07260550368960583,1739137671.723441,13.469987154006958,27.392570144242214,1739137671.7234442,13.469987154006958,36.39192907322956,1739137671.7234457,13.469987154006958,-0.063,1739137671.7234478,13.469987154006958,0.0011534594393119485,1739137671.7234497,13.469987154006958,-0.2186997889005855,1739137671.723451,13.469987154006958,-0.04843574872096762,1739137671.7234523,13.469987154006958,2.290593183946033,1739137671.7234545,13.469987154006958,0.0,1739137671.723456,13.469987154006958,-0.04474009420709635,1739137671.723458,13.469987154006958,0.027418639754756606,1739137671.7234602,13.469987154006958,2.3353332781531293 +1739137671.7432487,13.489987134933472,28.320915198803625,1739137671.7432518,13.489987134933472,-0.06561808494770727,1739137671.7432551,13.489987134933472,27.85651924513047,1739137671.7432585,13.489987134933472,36.841093195339425,1739137671.74326,13.489987134933472,-0.06245452839298939,1739137671.7432618,13.489987134933472,0.0003713016806248601,1739137671.7432632,13.489987134933472,-0.22688531866132855,1739137671.743265,13.489987134933472,-0.04800242181089846,1739137671.7432663,13.489987134933472,2.283105561196257,1739137671.743268,13.489987134933472,0.0,1739137671.7432697,13.489987134933472,-0.049627321289343274,1739137671.7432716,13.489987134933472,0.027003623942393834,1739137671.7432733,13.489987134933472,2.33040563033149 +1739137671.7633457,13.509987115859985,28.320915198803625,1739137671.763349,13.509987115859985,-0.06561808494770727,1739137671.7633524,13.509987115859985,27.85651924513047,1739137671.7633557,13.509987115859985,36.841093195339425,1739137671.7633572,13.509987115859985,-0.06245452839298939,1739137671.763359,13.509987115859985,0.0003713016806248601,1739137671.7633605,13.509987115859985,-0.22688531866132855,1739137671.763362,13.509987115859985,-0.04800242181089846,1739137671.7633638,13.509987115859985,2.283105561196257,1739137671.7633653,13.509987115859985,0.0,1739137671.763367,13.509987115859985,-0.04730006913523299,1739137671.7633686,13.509987115859985,0.027003623942393834,1739137671.7633703,13.509987115859985,2.33040563033149 +1739137671.7833834,13.529987096786499,28.320915198803625,1739137671.7833865,13.529987096786499,-0.06561808494770727,1739137671.7833893,13.529987096786499,27.85651924513047,1739137671.7833922,13.529987096786499,36.841093195339425,1739137671.7833939,13.529987096786499,-0.06245452839298939,1739137671.7833958,13.529987096786499,0.0003713016806248601,1739137671.7833974,13.529987096786499,-0.22688531866132855,1739137671.7833986,13.529987096786499,-0.04800242181089846,1739137671.7834005,13.529987096786499,2.283105561196257,1739137671.7834022,13.529987096786499,0.0,1739137671.7834039,13.529987096786499,-0.04730006913523299,1739137671.7834053,13.529987096786499,0.027003623942393834,1739137671.7834072,13.529987096786499,2.33040563033149 +1739137671.8031716,13.549987077713013,28.320915198803625,1739137671.8031747,13.549987077713013,-0.06561808494770727,1739137671.803178,13.549987077713013,27.85651924513047,1739137671.8031812,13.549987077713013,36.841093195339425,1739137671.8031826,13.549987077713013,-0.06245452839298939,1739137671.8031847,13.549987077713013,0.0003713016806248601,1739137671.8031864,13.549987077713013,-0.22688531866132855,1739137671.803188,13.549987077713013,-0.04800242181089846,1739137671.8031895,13.549987077713013,2.283105561196257,1739137671.8031917,13.549987077713013,0.0,1739137671.803193,13.549987077713013,-0.04730006913523299,1739137671.8031948,13.549987077713013,0.027003623942393834,1739137671.8031967,13.549987077713013,2.33040563033149 +1739137671.8232265,13.569987058639526,28.320915198803625,1739137671.8232296,13.569987058639526,-0.06561808494770727,1739137671.8232324,13.569987058639526,27.85651924513047,1739137671.8232355,13.569987058639526,36.841093195339425,1739137671.8232372,13.569987058639526,-0.06245452839298939,1739137671.8232388,13.569987058639526,0.0003713016806248601,1739137671.8232408,13.569987058639526,-0.22688531866132855,1739137671.823242,13.569987058639526,-0.04800242181089846,1739137671.8232436,13.569987058639526,2.283105561196257,1739137671.8232453,13.569987058639526,0.0,1739137671.823247,13.569987058639526,-0.04730006913523299,1739137671.8232486,13.569987058639526,0.027003623942393834,1739137671.8232503,13.569987058639526,2.33040563033149 +1739137671.8433588,13.58998703956604,28.57690743656422,1739137671.8433623,13.58998703956604,-0.05875199268641573,1739137671.8433657,13.58998703956604,27.888020022559555,1739137671.843369,13.58998703956604,36.85701137990988,1739137671.8433704,13.58998703956604,-0.062335735970821836,1739137671.8433726,13.58998703956604,-0.0004328137768738983,1739137671.843374,13.58998703956604,-0.22371297644829533,1739137671.843376,13.58998703956604,-0.05011529974309467,1739137671.8433802,13.58998703956604,2.2860045169626533,1739137671.843385,13.58998703956604,0.0,1739137671.84339,13.58998703956604,-0.031849778631437446,1739137671.8433945,13.58998703956604,0.026588608130031062,1739137671.8433979,13.58998703956604,2.3252115804616595 +1739137671.863816,13.609987020492554,28.57690743656422,1739137671.8638194,13.609987020492554,-0.05875199268641573,1739137671.8638232,13.609987020492554,27.888020022559555,1739137671.8638263,13.609987020492554,36.85701137990988,1739137671.863828,13.609987020492554,-0.062335735970821836,1739137671.86383,13.609987020492554,-0.0004328137768738983,1739137671.8638318,13.609987020492554,-0.22371297644829533,1739137671.8638358,13.609987020492554,-0.05011529974309467,1739137671.8638406,13.609987020492554,2.2860045169626533,1739137671.863844,13.609987020492554,0.0,1739137671.8638487,13.609987020492554,-0.03920706349900627,1739137671.8638542,13.609987020492554,0.026588608130031062,1739137671.8638566,13.609987020492554,2.3252115804616595 +1739137671.8836331,13.629987001419067,28.57690743656422,1739137671.8836358,13.629987001419067,-0.05875199268641573,1739137671.8836389,13.629987001419067,27.888020022559555,1739137671.883642,13.629987001419067,36.85701137990988,1739137671.8836434,13.629987001419067,-0.062335735970821836,1739137671.8836455,13.629987001419067,-0.0004328137768738983,1739137671.8836472,13.629987001419067,-0.22371297644829533,1739137671.8836484,13.629987001419067,-0.05011529974309467,1739137671.88365,13.629987001419067,2.2860045169626533,1739137671.8836517,13.629987001419067,0.0,1739137671.8836532,13.629987001419067,-0.03920706349900627,1739137671.8836548,13.629987001419067,0.026588608130031062,1739137671.8836567,13.629987001419067,2.3252115804616595 +1739137671.903609,13.649986982345581,28.57690743656422,1739137671.9036129,13.649986982345581,-0.05875199268641573,1739137671.9036164,13.649986982345581,27.888020022559555,1739137671.9036198,13.649986982345581,36.85701137990988,1739137671.9036214,13.649986982345581,-0.062335735970821836,1739137671.9036236,13.649986982345581,-0.0004328137768738983,1739137671.9036255,13.649986982345581,-0.22371297644829533,1739137671.903627,13.649986982345581,-0.05011529974309467,1739137671.9036286,13.649986982345581,2.2860045169626533,1739137671.9036303,13.649986982345581,0.0,1739137671.903632,13.649986982345581,-0.03920706349900627,1739137671.9036338,13.649986982345581,0.026588608130031062,1739137671.9036355,13.649986982345581,2.3252115804616595 +1739137671.9241736,13.669986963272095,28.57690743656422,1739137671.9241765,13.669986963272095,-0.05875199268641573,1739137671.9241796,13.669986963272095,27.888020022559555,1739137671.9241824,13.669986963272095,36.85701137990988,1739137671.924184,13.669986963272095,-0.062335735970821836,1739137671.9241858,13.669986963272095,-0.0004328137768738983,1739137671.9241874,13.669986963272095,-0.22371297644829533,1739137671.9241889,13.669986963272095,-0.05011529974309467,1739137671.9241905,13.669986963272095,2.2860045169626533,1739137671.9241924,13.669986963272095,0.0,1739137671.924194,13.669986963272095,-0.03920706349900627,1739137671.9241958,13.669986963272095,0.026588608130031062,1739137671.9241972,13.669986963272095,2.3252115804616595 +1739137671.943335,13.689986944198608,28.57690743656422,1739137671.9433377,13.689986944198608,-0.05875199268641573,1739137671.9433403,13.689986944198608,27.888020022559555,1739137671.9433432,13.689986944198608,36.85701137990988,1739137671.9433444,13.689986944198608,-0.062335735970821836,1739137671.9433463,13.689986944198608,-0.0004328137768738983,1739137671.9433475,13.689986944198608,-0.22371297644829533,1739137671.9433494,13.689986944198608,-0.05011529974309467,1739137671.9433503,13.689986944198608,2.2860045169626533,1739137671.943352,13.689986944198608,0.0,1739137671.9433534,13.689986944198608,-0.03920706349900627,1739137671.943355,13.689986944198608,0.026588608130031062,1739137671.9433565,13.689986944198608,2.3252115804616595 +1739137671.9633813,13.709986925125122,28.832390760247094,1739137671.9633846,13.709986925125122,-0.05201337821798013,1739137671.963388,13.709986925125122,28.35008377589214,1739137671.9633908,13.709986925125122,37.30663055910283,1739137671.9633923,13.709986925125122,-0.06055111339213707,1739137671.9633942,13.709986925125122,-0.0010074924108936139,1739137671.9633956,13.709986925125122,-0.22968531335861597,1739137671.9633968,13.709986925125122,-0.04912286476750101,1739137671.9633982,13.709986925125122,2.280549919234315,1739137671.9633996,13.709986925125122,0.0,1739137671.9634013,13.709986925125122,-0.04170485737178154,1739137671.963403,13.709986925125122,0.02609975656316524,1739137671.9634042,13.709986925125122,2.3210653503582237 +1739137671.9830513,13.729986906051636,28.832390760247094,1739137671.983054,13.729986906051636,-0.05201337821798013,1739137671.9830563,13.729986906051636,28.35008377589214,1739137671.9830592,13.729986906051636,37.30663055910283,1739137671.9830606,13.729986906051636,-0.06055111339213707,1739137671.983062,13.729986906051636,-0.0010074924108936139,1739137671.9830635,13.729986906051636,-0.22968531335861597,1739137671.983065,13.729986906051636,-0.04912286476750101,1739137671.983066,13.729986906051636,2.280549919234315,1739137671.9830678,13.729986906051636,0.0,1739137671.983069,13.729986906051636,-0.04051543112390865,1739137671.9830704,13.729986906051636,0.02609975656316524,1739137671.9830718,13.729986906051636,2.3210653503582237 +1739137672.0029678,13.74998688697815,28.832390760247094,1739137672.0029705,13.74998688697815,-0.05201337821798013,1739137672.0029736,13.74998688697815,28.35008377589214,1739137672.0029762,13.74998688697815,37.30663055910283,1739137672.0029778,13.74998688697815,-0.06055111339213707,1739137672.0029795,13.74998688697815,-0.0010074924108936139,1739137672.0029814,13.74998688697815,-0.22968531335861597,1739137672.0029829,13.74998688697815,-0.04912286476750101,1739137672.0029845,13.74998688697815,2.280549919234315,1739137672.0029864,13.74998688697815,0.0,1739137672.0029879,13.74998688697815,-0.04051543112390865,1739137672.0029893,13.74998688697815,0.02609975656316524,1739137672.002991,13.74998688697815,2.3210653503582237 +1739137672.0233219,13.769986867904663,28.832390760247094,1739137672.023326,13.769986867904663,-0.05201337821798013,1739137672.02333,13.769986867904663,28.35008377589214,1739137672.0233338,13.769986867904663,37.30663055910283,1739137672.023336,13.769986867904663,-0.06055111339213707,1739137672.0233386,13.769986867904663,-0.0010074924108936139,1739137672.0233402,13.769986867904663,-0.22968531335861597,1739137672.0233424,13.769986867904663,-0.04912286476750101,1739137672.0233448,13.769986867904663,2.280549919234315,1739137672.0233464,13.769986867904663,0.0,1739137672.0233488,13.769986867904663,-0.04051543112390865,1739137672.023351,13.769986867904663,0.02609975656316524,1739137672.0233533,13.769986867904663,2.3210653503582237 +1739137672.0476341,13.789986848831177,28.832390760247094,1739137672.0476434,13.789986848831177,-0.05201337821798013,1739137672.0476534,13.789986848831177,28.35008377589214,1739137672.0476632,13.789986848831177,37.30663055910283,1739137672.0476677,13.789986848831177,-0.06055111339213707,1739137672.047674,13.789986848831177,-0.0010074924108936139,1739137672.0476785,13.789986848831177,-0.22968531335861597,1739137672.0476832,13.789986848831177,-0.04912286476750101,1739137672.047688,13.789986848831177,2.280549919234315,1739137672.0476933,13.789986848831177,0.0,1739137672.047698,13.789986848831177,-0.04051543112390865,1739137672.047703,13.789986848831177,0.02609975656316524,1739137672.0477078,13.789986848831177,2.3210653503582237 +1739137672.0732894,13.80998682975769,29.087400055374104,1739137672.0732992,13.80998682975769,-0.045413725029172625,1739137672.0733118,13.80998682975769,28.381463118499145,1739137672.0733256,13.80998682975769,37.324683883347696,1739137672.0733333,13.80998682975769,-0.060476512878728524,1739137672.073343,13.80998682975769,-0.0018286089656595402,1739137672.073352,13.80998682975769,-0.225938282060041,1739137672.0733612,13.80998682975769,-0.051141027938323536,1739137672.0733702,13.80998682975769,2.2839705988427976,1739137672.0733807,13.80998682975769,0.0,1739137672.0733895,13.80998682975769,-0.025504940544941436,1739137672.073399,13.80998682975769,0.02560352142084911,1739137672.073408,13.80998682975769,2.3166233956150566 +1739137672.0894442,13.829986810684204,29.087400055374104,1739137672.0894477,13.829986810684204,-0.045413725029172625,1739137672.089452,13.829986810684204,28.381463118499145,1739137672.089456,13.829986810684204,37.324683883347696,1739137672.0894582,13.829986810684204,-0.060476512878728524,1739137672.0894604,13.829986810684204,-0.0018286089656595402,1739137672.0894628,13.829986810684204,-0.225938282060041,1739137672.089465,13.829986810684204,-0.051141027938323536,1739137672.089467,13.829986810684204,2.2839705988427976,1739137672.0894694,13.829986810684204,0.0,1739137672.0894716,13.829986810684204,-0.03265279677225896,1739137672.089474,13.829986810684204,0.02560352142084911,1739137672.089476,13.829986810684204,2.3166233956150566 +1739137672.1096318,13.849986791610718,29.087400055374104,1739137672.1096358,13.849986791610718,-0.045413725029172625,1739137672.10964,13.849986791610718,28.381463118499145,1739137672.109644,13.849986791610718,37.324683883347696,1739137672.109646,13.849986791610718,-0.060476512878728524,1739137672.109649,13.849986791610718,-0.0018286089656595402,1739137672.1096509,13.849986791610718,-0.225938282060041,1739137672.1096525,13.849986791610718,-0.051141027938323536,1739137672.1096542,13.849986791610718,2.2839705988427976,1739137672.109656,13.849986791610718,0.0,1739137672.1096578,13.849986791610718,-0.03265279677225896,1739137672.1096604,13.849986791610718,0.02560352142084911,1739137672.1096623,13.849986791610718,2.3166233956150566 +1739137672.129753,13.869986772537231,29.087400055374104,1739137672.1297567,13.869986772537231,-0.045413725029172625,1739137672.1297607,13.869986772537231,28.381463118499145,1739137672.1297643,13.869986772537231,37.324683883347696,1739137672.1297662,13.869986772537231,-0.060476512878728524,1739137672.1297684,13.869986772537231,-0.0018286089656595402,1739137672.1297703,13.869986772537231,-0.225938282060041,1739137672.129772,13.869986772537231,-0.051141027938323536,1739137672.1297736,13.869986772537231,2.2839705988427976,1739137672.1297758,13.869986772537231,0.0,1739137672.1297777,13.869986772537231,-0.03265279677225896,1739137672.1297793,13.869986772537231,0.02560352142084911,1739137672.1297812,13.869986772537231,2.3166233956150566 +1739137672.1505265,13.889986753463745,29.087400055374104,1739137672.1505296,13.889986753463745,-0.045413725029172625,1739137672.1505332,13.889986753463745,28.381463118499145,1739137672.1505368,13.889986753463745,37.324683883347696,1739137672.1505384,13.889986753463745,-0.060476512878728524,1739137672.1505408,13.889986753463745,-0.0018286089656595402,1739137672.1505425,13.889986753463745,-0.225938282060041,1739137672.1505444,13.889986753463745,-0.051141027938323536,1739137672.1505458,13.889986753463745,2.2839705988427976,1739137672.1505482,13.889986753463745,0.0,1739137672.1505497,13.889986753463745,-0.03265279677225896,1739137672.1505518,13.889986753463745,0.02560352142084911,1739137672.1505537,13.889986753463745,2.3166233956150566 +1739137672.1713703,13.909986734390259,29.087400055374104,1739137672.1713746,13.909986734390259,-0.045413725029172625,1739137672.1713798,13.909986734390259,28.381463118499145,1739137672.1713867,13.909986734390259,37.324683883347696,1739137672.17139,13.909986734390259,-0.060476512878728524,1739137672.1713955,13.909986734390259,-0.0018286089656595402,1739137672.1713996,13.909986734390259,-0.225938282060041,1739137672.1714046,13.909986734390259,-0.051141027938323536,1739137672.1714084,13.909986734390259,2.2839705988427976,1739137672.1714125,13.909986734390259,0.0,1739137672.1714165,13.909986734390259,-0.03265279677225896,1739137672.1714206,13.909986734390259,0.02560352142084911,1739137672.1714249,13.909986734390259,2.3166233956150566 +1739137672.1903982,13.929986715316772,29.34198107645306,1739137672.1904023,13.929986715316772,-0.038951575015738094,1739137672.1904066,13.929986715316772,28.776970384570657,1739137672.190412,13.929986715316772,37.70988771396206,1739137672.190415,13.929986715316772,-0.059,1739137672.1904185,13.929986715316772,-0.002395866432577646,1739137672.1904218,13.929986715316772,-0.2301154613109596,1739137672.1904252,13.929986715316772,-0.05047308967609248,1739137672.1904283,13.929986715316772,2.2801575634383013,1739137672.1904318,13.929986715316772,0.0,1739137672.1904352,13.929986715316772,-0.0333784976490514,1739137672.1904385,13.929986715316772,0.02510728627853298,1739137672.1904418,13.929986715316772,2.313190489068633 +1739137672.210232,13.949986696243286,29.34198107645306,1739137672.2102354,13.949986696243286,-0.038951575015738094,1739137672.2102394,13.949986696243286,28.776970384570657,1739137672.2102444,13.949986696243286,37.70988771396206,1739137672.2102468,13.949986696243286,-0.059,1739137672.2102504,13.949986696243286,-0.002395866432577646,1739137672.2102537,13.949986696243286,-0.2301154613109596,1739137672.2102568,13.949986696243286,-0.05047308967609248,1739137672.2102602,13.949986696243286,2.2801575634383013,1739137672.2102635,13.949986696243286,0.0,1739137672.2102666,13.949986696243286,-0.033032925630331444,1739137672.21027,13.949986696243286,0.02510728627853298,1739137672.2102733,13.949986696243286,2.313190489068633 +1739137672.2300255,13.9699866771698,29.34198107645306,1739137672.2300286,13.9699866771698,-0.038951575015738094,1739137672.2300327,13.9699866771698,28.776970384570657,1739137672.2300372,13.9699866771698,37.70988771396206,1739137672.2300398,13.9699866771698,-0.059,1739137672.2300432,13.9699866771698,-0.002395866432577646,1739137672.2300463,13.9699866771698,-0.2301154613109596,1739137672.2300494,13.9699866771698,-0.05047308967609248,1739137672.230052,13.9699866771698,2.2801575634383013,1739137672.230055,13.9699866771698,0.0,1739137672.2300582,13.9699866771698,-0.033032925630331444,1739137672.2300618,13.9699866771698,0.02510728627853298,1739137672.2300646,13.9699866771698,2.313190489068633 +1739137672.250515,13.989986658096313,29.34198107645306,1739137672.2505188,13.989986658096313,-0.038951575015738094,1739137672.250524,13.989986658096313,28.776970384570657,1739137672.2505293,13.989986658096313,37.70988771396206,1739137672.2505488,13.989986658096313,-0.059,1739137672.2505524,13.989986658096313,-0.002395866432577646,1739137672.2505558,13.989986658096313,-0.2301154613109596,1739137672.2505586,13.989986658096313,-0.05047308967609248,1739137672.250562,13.989986658096313,2.2801575634383013,1739137672.2505653,13.989986658096313,0.0,1739137672.2505684,13.989986658096313,-0.033032925630331444,1739137672.2505717,13.989986658096313,0.02510728627853298,1739137672.250575,13.989986658096313,2.313190489068633 +1739137672.2701476,14.009986639022827,29.34198107645306,1739137672.2701507,14.009986639022827,-0.038951575015738094,1739137672.2701545,14.009986639022827,28.776970384570657,1739137672.270159,14.009986639022827,37.70988771396206,1739137672.2701619,14.009986639022827,-0.059,1739137672.2701652,14.009986639022827,-0.002395866432577646,1739137672.2701683,14.009986639022827,-0.2301154613109596,1739137672.2701712,14.009986639022827,-0.05047308967609248,1739137672.2701743,14.009986639022827,2.2801575634383013,1739137672.2701774,14.009986639022827,0.0,1739137672.2701805,14.009986639022827,-0.033032925630331444,1739137672.2701833,14.009986639022827,0.02510728627853298,1739137672.2701864,14.009986639022827,2.313190489068633 +1739137672.2909684,14.02998661994934,29.596172286818486,1739137672.2909722,14.02998661994934,-0.03262553738269869,1739137672.2909765,14.02998661994934,28.7894320799162,1739137672.2909815,14.02998661994934,37.71150139977317,1739137672.2909844,14.02998661994934,-0.059,1739137672.2909882,14.02998661994934,-0.0032499445670311094,1739137672.2909915,14.02998661994934,-0.22607309331444955,1739137672.290995,14.02998661994934,-0.05272037863523604,1739137672.2909982,14.02998661994934,2.283847440186877,1739137672.2910018,14.02998661994934,0.0,1739137672.291005,14.02998661994934,-0.019085330345284545,1739137672.2910085,14.02998661994934,0.024611051136216852,1739137672.2910116,14.02998661994934,2.309574485890487 +1739137672.3106089,14.049986600875854,29.596172286818486,1739137672.3106122,14.049986600875854,-0.03262553738269869,1739137672.310616,14.049986600875854,28.7894320799162,1739137672.3106213,14.049986600875854,37.71150139977317,1739137672.310624,14.049986600875854,-0.059,1739137672.3106277,14.049986600875854,-0.0032499445670311094,1739137672.3106306,14.049986600875854,-0.22607309331444955,1739137672.3106337,14.049986600875854,-0.05272037863523604,1739137672.310637,14.049986600875854,2.283847440186877,1739137672.31064,14.049986600875854,0.0,1739137672.3106434,14.049986600875854,-0.025727045703610063,1739137672.3106468,14.049986600875854,0.024611051136216852,1739137672.3106499,14.049986600875854,2.309574485890487 +1739137672.3301284,14.069986581802368,29.596172286818486,1739137672.3301315,14.069986581802368,-0.03262553738269869,1739137672.3301356,14.069986581802368,28.7894320799162,1739137672.33014,14.069986581802368,37.71150139977317,1739137672.3301427,14.069986581802368,-0.059,1739137672.330146,14.069986581802368,-0.0032499445670311094,1739137672.3301492,14.069986581802368,-0.22607309331444955,1739137672.3301523,14.069986581802368,-0.05272037863523604,1739137672.330155,14.069986581802368,2.283847440186877,1739137672.330158,14.069986581802368,0.0,1739137672.330161,14.069986581802368,-0.025727045703610063,1739137672.3301644,14.069986581802368,0.024611051136216852,1739137672.3301678,14.069986581802368,2.309574485890487 +1739137672.3488677,14.089986562728882,29.596172286818486,1739137672.3488696,14.089986562728882,-0.03262553738269869,1739137672.3488722,14.089986562728882,28.7894320799162,1739137672.3488748,14.089986562728882,37.71150139977317,1739137672.348876,14.089986562728882,-0.059,1739137672.3488777,14.089986562728882,-0.0032499445670311094,1739137672.3488789,14.089986562728882,-0.22607309331444955,1739137672.34888,14.089986562728882,-0.05272037863523604,1739137672.3488812,14.089986562728882,2.283847440186877,1739137672.3488824,14.089986562728882,0.0,1739137672.3488836,14.089986562728882,-0.025727045703610063,1739137672.348885,14.089986562728882,0.024611051136216852,1739137672.3488863,14.089986562728882,2.309574485890487 +1739137672.3688235,14.109986543655396,29.596172286818486,1739137672.368826,14.109986543655396,-0.03262553738269869,1739137672.3688285,14.109986543655396,28.7894320799162,1739137672.368831,14.109986543655396,37.71150139977317,1739137672.3688323,14.109986543655396,-0.059,1739137672.3688338,14.109986543655396,-0.0032499445670311094,1739137672.368835,14.109986543655396,-0.22607309331444955,1739137672.3688364,14.109986543655396,-0.05272037863523604,1739137672.3688374,14.109986543655396,2.283847440186877,1739137672.368839,14.109986543655396,0.0,1739137672.36884,14.109986543655396,-0.025727045703610063,1739137672.3688412,14.109986543655396,0.024611051136216852,1739137672.3688426,14.109986543655396,2.309574485890487 +1739137672.3888488,14.12998652458191,29.596172286818486,1739137672.3888512,14.12998652458191,-0.03262553738269869,1739137672.3888538,14.12998652458191,28.7894320799162,1739137672.3888564,14.12998652458191,37.71150139977317,1739137672.3888576,14.12998652458191,-0.059,1739137672.388859,14.12998652458191,-0.0032499445670311094,1739137672.3888605,14.12998652458191,-0.22607309331444955,1739137672.3888617,14.12998652458191,-0.05272037863523604,1739137672.3888626,14.12998652458191,2.283847440186877,1739137672.3888643,14.12998652458191,0.0,1739137672.3888655,14.12998652458191,-0.025727045703610063,1739137672.3888671,14.12998652458191,0.024611051136216852,1739137672.388868,14.12998652458191,2.309574485890487 +1739137672.4120893,14.149986505508423,29.850021645365374,1739137672.4121013,14.149986505508423,-0.026441739215111504,1739137672.412116,14.149986505508423,29.64688677535977,1739137672.4121306,14.149986505508423,38.560893880223006,1739137672.4121377,14.149986505508423,-0.05713806874555412,1739137672.412147,14.149986505508423,-0.003523895385219097,1739137672.4121552,14.149986505508423,-0.24008418209235338,1739137672.412163,14.149986505508423,-0.048594609504668235,1739137672.4121704,14.149986505508423,2.2710835650576393,1739137672.4121797,14.149986505508423,0.0,1739137672.412188,14.149986505508423,-0.04496896328599163,1739137672.4121962,14.149986505508423,0.024040864005368916,1739137672.412204,14.149986505508423,2.3068897058700286 +1739137672.4328344,14.169986486434937,29.850021645365374,1739137672.43284,14.169986486434937,-0.026441739215111504,1739137672.4328492,14.169986486434937,29.64688677535977,1739137672.4328578,14.169986486434937,38.560893880223006,1739137672.4328625,14.169986486434937,-0.05713806874555412,1739137672.4328687,14.169986486434937,-0.003523895385219097,1739137672.4328744,14.169986486434937,-0.24008418209235338,1739137672.4328802,14.169986486434937,-0.048594609504668235,1739137672.4328854,14.169986486434937,2.2710835650576393,1739137672.4328911,14.169986486434937,0.0,1739137672.4328966,14.169986486434937,-0.03580614081238931,1739137672.432902,14.169986486434937,0.024040864005368916,1739137672.4329076,14.169986486434937,2.3068897058700286 +1739137672.4508781,14.18998646736145,29.850021645365374,1739137672.4508812,14.18998646736145,-0.026441739215111504,1739137672.4508853,14.18998646736145,29.64688677535977,1739137672.4508903,14.18998646736145,38.560893880223006,1739137672.4508932,14.18998646736145,-0.05713806874555412,1739137672.4508965,14.18998646736145,-0.003523895385219097,1739137672.4508994,14.18998646736145,-0.24008418209235338,1739137672.4509025,14.18998646736145,-0.048594609504668235,1739137672.4509056,14.18998646736145,2.2710835650576393,1739137672.4509087,14.18998646736145,0.0,1739137672.4509118,14.18998646736145,-0.03580614081238931,1739137672.450915,14.18998646736145,0.024040864005368916,1739137672.4509184,14.18998646736145,2.3068897058700286 +1739137672.4703639,14.209986448287964,29.850021645365374,1739137672.4703672,14.209986448287964,-0.026441739215111504,1739137672.4703712,14.209986448287964,29.64688677535977,1739137672.4703765,14.209986448287964,38.560893880223006,1739137672.4703794,14.209986448287964,-0.05713806874555412,1739137672.470383,14.209986448287964,-0.003523895385219097,1739137672.470386,14.209986448287964,-0.24008418209235338,1739137672.4703894,14.209986448287964,-0.048594609504668235,1739137672.4703922,14.209986448287964,2.2710835650576393,1739137672.4703956,14.209986448287964,0.0,1739137672.4703987,14.209986448287964,-0.03580614081238931,1739137672.470402,14.209986448287964,0.024040864005368916,1739137672.4704053,14.209986448287964,2.3068897058700286 +1739137672.490281,14.229986429214478,29.850021645365374,1739137672.4902842,14.229986429214478,-0.026441739215111504,1739137672.4902885,14.229986429214478,29.64688677535977,1739137672.4902933,14.229986429214478,38.560893880223006,1739137672.4902961,14.229986429214478,-0.05713806874555412,1739137672.4902997,14.229986429214478,-0.003523895385219097,1739137672.490303,14.229986429214478,-0.24008418209235338,1739137672.4903061,14.229986429214478,-0.048594609504668235,1739137672.4903095,14.229986429214478,2.2710835650576393,1739137672.490325,14.229986429214478,0.0,1739137672.490328,14.229986429214478,-0.03580614081238931,1739137672.4903314,14.229986429214478,0.024040864005368916,1739137672.4903343,14.229986429214478,2.3068897058700286 +1739137672.509154,14.249986410140991,30.103499842324034,1739137672.509157,14.249986410140991,-0.02041329364436173,1739137672.5091593,14.249986410140991,29.677056709243423,1739137672.509162,14.249986410140991,38.57879305479256,1739137672.5091634,14.249986410140991,-0.057215554349751355,1739137672.5091648,14.249986410140991,-0.00434227211687915,1739137672.509166,14.249986410140991,-0.2356320772201648,1739137672.5091674,14.249986410140991,-0.05038104185231909,1739137672.5091684,14.249986410140991,2.275131609333394,1739137672.5091696,14.249986410140991,0.0,1739137672.509171,14.249986410140991,-0.02026949094119946,1739137672.5091724,14.249986410140991,0.0234632816756678,1739137672.5091734,14.249986410140991,2.3027995086709883 +1739137672.5290916,14.269986391067505,30.103499842324034,1739137672.5290945,14.269986391067505,-0.02041329364436173,1739137672.5290968,14.269986391067505,29.677056709243423,1739137672.5290995,14.269986391067505,38.57879305479256,1739137672.529101,14.269986391067505,-0.057215554349751355,1739137672.5291023,14.269986391067505,-0.00434227211687915,1739137672.5291035,14.269986391067505,-0.2356320772201648,1739137672.529105,14.269986391067505,-0.05038104185231909,1739137672.5291061,14.269986391067505,2.275131609333394,1739137672.529108,14.269986391067505,0.0,1739137672.5291092,14.269986391067505,-0.02766789933759428,1739137672.5291104,14.269986391067505,0.0234632816756678,1739137672.5291119,14.269986391067505,2.3027995086709883 +1739137672.5488183,14.289986371994019,30.103499842324034,1739137672.5488205,14.289986371994019,-0.02041329364436173,1739137672.548823,14.289986371994019,29.677056709243423,1739137672.5488262,14.289986371994019,38.57879305479256,1739137672.5488272,14.289986371994019,-0.057215554349751355,1739137672.5488288,14.289986371994019,-0.00434227211687915,1739137672.5488303,14.289986371994019,-0.2356320772201648,1739137672.5488315,14.289986371994019,-0.05038104185231909,1739137672.5488324,14.289986371994019,2.275131609333394,1739137672.548834,14.289986371994019,0.0,1739137672.548835,14.289986371994019,-0.02766789933759428,1739137672.5488365,14.289986371994019,0.0234632816756678,1739137672.5488377,14.289986371994019,2.3027995086709883 +1739137672.5689454,14.309986352920532,30.103499842324034,1739137672.5689478,14.309986352920532,-0.02041329364436173,1739137672.568951,14.309986352920532,29.677056709243423,1739137672.5689535,14.309986352920532,38.57879305479256,1739137672.5689552,14.309986352920532,-0.057215554349751355,1739137672.568957,14.309986352920532,-0.00434227211687915,1739137672.568959,14.309986352920532,-0.2356320772201648,1739137672.5689604,14.309986352920532,-0.05038104185231909,1739137672.568962,14.309986352920532,2.275131609333394,1739137672.5689635,14.309986352920532,0.0,1739137672.5689652,14.309986352920532,-0.02766789933759428,1739137672.5689666,14.309986352920532,0.0234632816756678,1739137672.5689683,14.309986352920532,2.3027995086709883 +1739137672.5889575,14.329986333847046,30.103499842324034,1739137672.58896,14.329986333847046,-0.02041329364436173,1739137672.5889628,14.329986333847046,29.677056709243423,1739137672.5889654,14.329986333847046,38.57879305479256,1739137672.588967,14.329986333847046,-0.057215554349751355,1739137672.5889695,14.329986333847046,-0.00434227211687915,1739137672.5889714,14.329986333847046,-0.2356320772201648,1739137672.5889728,14.329986333847046,-0.05038104185231909,1739137672.5889742,14.329986333847046,2.275131609333394,1739137672.588976,14.329986333847046,0.0,1739137672.5889773,14.329986333847046,-0.02766789933759428,1739137672.588979,14.329986333847046,0.0234632816756678,1739137672.5889804,14.329986333847046,2.3027995086709883 +1739137672.6088624,14.34998631477356,30.103499842324034,1739137672.6088645,14.34998631477356,-0.02041329364436173,1739137672.6088674,14.34998631477356,29.677056709243423,1739137672.6088698,14.34998631477356,38.57879305479256,1739137672.6088715,14.34998631477356,-0.057215554349751355,1739137672.608873,14.34998631477356,-0.00434227211687915,1739137672.6088743,14.34998631477356,-0.2356320772201648,1739137672.6088755,14.34998631477356,-0.05038104185231909,1739137672.6088767,14.34998631477356,2.275131609333394,1739137672.6088784,14.34998631477356,0.0,1739137672.6088793,14.34998631477356,-0.02766789933759428,1739137672.608881,14.34998631477356,0.0234632816756678,1739137672.6088822,14.34998631477356,2.3027995086709883 +1739137672.6327214,14.369986295700073,30.356601913678503,1739137672.632732,14.369986295700073,-0.014540067999949002,1739137672.6327436,14.369986295700073,29.70718172896025,1739137672.6327538,14.369986295700073,38.600271054646555,1739137672.6327586,14.369986295700073,-0.057308532704097644,1739137672.632764,14.369986295700073,-0.00518799096180873,1739137672.6327693,14.369986295700073,-0.23140293019178432,1739137672.6327739,14.369986295700073,-0.052295375039389524,1739137672.6327786,14.369986295700073,2.27898361298666,1739137672.6327841,14.369986295700073,0.0,1739137672.6327891,14.369986295700073,-0.014811547408030243,1739137672.6327949,14.369986295700073,0.02288569934596668,1739137672.6327994,14.369986295700073,2.2999172358003457 +1739137672.654922,14.389986276626587,30.356601913678503,1739137672.6549292,14.389986276626587,-0.014540067999949002,1739137672.6549385,14.389986276626587,29.70718172896025,1739137672.6549487,14.389986276626587,38.600271054646555,1739137672.6549542,14.389986276626587,-0.057308532704097644,1739137672.6549616,14.389986276626587,-0.00518799096180873,1739137672.6549685,14.389986276626587,-0.23140293019178432,1739137672.6549752,14.389986276626587,-0.052295375039389524,1739137672.6549816,14.389986276626587,2.27898361298666,1739137672.6549885,14.389986276626587,0.0,1739137672.6549952,14.389986276626587,-0.020933622813685826,1739137672.655002,14.389986276626587,0.02288569934596668,1739137672.6550088,14.389986276626587,2.2999172358003457 +1739137672.670846,14.4099862575531,30.356601913678503,1739137672.6708493,14.4099862575531,-0.014540067999949002,1739137672.6708539,14.4099862575531,29.70718172896025,1739137672.6708593,14.4099862575531,38.600271054646555,1739137672.6708622,14.4099862575531,-0.057308532704097644,1739137672.670866,14.4099862575531,-0.00518799096180873,1739137672.6708696,14.4099862575531,-0.23140293019178432,1739137672.670873,14.4099862575531,-0.052295375039389524,1739137672.6708765,14.4099862575531,2.27898361298666,1739137672.67088,14.4099862575531,0.0,1739137672.6708834,14.4099862575531,-0.020933622813685826,1739137672.6708872,14.4099862575531,0.02288569934596668,1739137672.6708908,14.4099862575531,2.2999172358003457 +1739137672.6905148,14.429986238479614,30.356601913678503,1739137672.6905363,14.429986238479614,-0.014540067999949002,1739137672.690541,14.429986238479614,29.70718172896025,1739137672.6905622,14.429986238479614,38.600271054646555,1739137672.690565,14.429986238479614,-0.057308532704097644,1739137672.6905684,14.429986238479614,-0.00518799096180873,1739137672.6905715,14.429986238479614,-0.23140293019178432,1739137672.6905746,14.429986238479614,-0.052295375039389524,1739137672.6905777,14.429986238479614,2.27898361298666,1739137672.6905816,14.429986238479614,0.0,1739137672.6905847,14.429986238479614,-0.020933622813685826,1739137672.690588,14.429986238479614,0.02288569934596668,1739137672.6905909,14.429986238479614,2.2999172358003457 +1739137672.7088764,14.449986219406128,30.356601913678503,1739137672.708878,14.449986219406128,-0.014540067999949002,1739137672.7088807,14.449986219406128,29.70718172896025,1739137672.708883,14.449986219406128,38.600271054646555,1739137672.7088842,14.449986219406128,-0.057308532704097644,1739137672.7088857,14.449986219406128,-0.00518799096180873,1739137672.708887,14.449986219406128,-0.23140293019178432,1739137672.7088883,14.449986219406128,-0.052295375039389524,1739137672.7088892,14.449986219406128,2.27898361298666,1739137672.708891,14.449986219406128,0.0,1739137672.7088919,14.449986219406128,-0.020933622813685826,1739137672.7088935,14.449986219406128,0.02288569934596668,1739137672.7088947,14.449986219406128,2.2999172358003457 +1739137672.732389,14.469986200332642,30.609421504044604,1739137672.732402,14.469986200332642,-0.008819502405225776,1739137672.7324178,14.469986200332642,29.73727298077941,1739137672.7324405,14.469986200332642,38.6238419450943,1739137672.7324545,14.469986200332642,-0.0574105711908844,1739137672.7324736,14.469986200332642,-0.006062880499347123,1739137672.73249,14.469986200332642,-0.22735077902607917,1739137672.7325063,14.469986200332642,-0.05436005896796228,1739137672.7325225,14.469986200332642,2.282680522706287,1739137672.7325392,14.469986200332642,0.0,1739137672.7325563,14.469986200332642,-0.009726700662306006,1739137672.7325733,14.469986200332642,0.022308117016265564,1739137672.7325895,14.469986200332642,2.2977438556303693 +1739137672.7534325,14.489986181259155,30.609421504044604,1739137672.7534385,14.489986181259155,-0.008819502405225776,1739137672.753446,14.489986181259155,29.73727298077941,1739137672.753455,14.489986181259155,38.6238419450943,1739137672.7534597,14.489986181259155,-0.0574105711908844,1739137672.753466,14.489986181259155,-0.006062880499347123,1739137672.7534711,14.489986181259155,-0.22735077902607917,1739137672.7534766,14.489986181259155,-0.05436005896796228,1739137672.7534819,14.489986181259155,2.282680522706287,1739137672.7534876,14.489986181259155,0.0,1739137672.753493,14.489986181259155,-0.015063332924082129,1739137672.7534986,14.489986181259155,0.022308117016265564,1739137672.753504,14.489986181259155,2.2977438556303693 +1739137672.7691784,14.509986162185669,30.609421504044604,1739137672.7691813,14.509986162185669,-0.008819502405225776,1739137672.769184,14.509986162185669,29.73727298077941,1739137672.7691865,14.509986162185669,38.6238419450943,1739137672.7691882,14.509986162185669,-0.0574105711908844,1739137672.7691896,14.509986162185669,-0.006062880499347123,1739137672.7691915,14.509986162185669,-0.22735077902607917,1739137672.7691927,14.509986162185669,-0.05436005896796228,1739137672.769194,14.509986162185669,2.282680522706287,1739137672.7691956,14.509986162185669,0.0,1739137672.7691967,14.509986162185669,-0.015063332924082129,1739137672.7691984,14.509986162185669,0.022308117016265564,1739137672.7691996,14.509986162185669,2.2977438556303693 +1739137672.788871,14.529986143112183,30.609421504044604,1739137672.7888732,14.529986143112183,-0.008819502405225776,1739137672.788876,14.529986143112183,29.73727298077941,1739137672.7888784,14.529986143112183,38.6238419450943,1739137672.7888796,14.529986143112183,-0.0574105711908844,1739137672.7888813,14.529986143112183,-0.006062880499347123,1739137672.7888827,14.529986143112183,-0.22735077902607917,1739137672.788884,14.529986143112183,-0.05436005896796228,1739137672.7888854,14.529986143112183,2.282680522706287,1739137672.7888865,14.529986143112183,0.0,1739137672.7888877,14.529986143112183,-0.015063332924082129,1739137672.7888892,14.529986143112183,0.022308117016265564,1739137672.7888904,14.529986143112183,2.2977438556303693 +1739137672.8088799,14.549986124038696,30.609421504044604,1739137672.8088822,14.549986124038696,-0.008819502405225776,1739137672.8088846,14.549986124038696,29.73727298077941,1739137672.8088875,14.549986124038696,38.6238419450943,1739137672.8088887,14.549986124038696,-0.0574105711908844,1739137672.80889,14.549986124038696,-0.006062880499347123,1739137672.8088913,14.549986124038696,-0.22735077902607917,1739137672.8088927,14.549986124038696,-0.05436005896796228,1739137672.808894,14.549986124038696,2.282680522706287,1739137672.8088958,14.549986124038696,0.0,1739137672.8088968,14.549986124038696,-0.015063332924082129,1739137672.8088982,14.549986124038696,0.022308117016265564,1739137672.8088996,14.549986124038696,2.2977438556303693 +1739137672.8288891,14.56998610496521,30.609421504044604,1739137672.8288913,14.56998610496521,-0.008819502405225776,1739137672.8288944,14.56998610496521,29.73727298077941,1739137672.8288968,14.56998610496521,38.6238419450943,1739137672.828898,14.56998610496521,-0.0574105711908844,1739137672.8288999,14.56998610496521,-0.006062880499347123,1739137672.828901,14.56998610496521,-0.22735077902607917,1739137672.8289025,14.56998610496521,-0.05436005896796228,1739137672.8289034,14.56998610496521,2.282680522706287,1739137672.8289046,14.56998610496521,0.0,1739137672.828906,14.56998610496521,-0.015063332924082129,1739137672.8289073,14.56998610496521,0.022308117016265564,1739137672.8289082,14.56998610496521,2.2977438556303693 +1739137672.8488696,14.589986085891724,30.862039580407824,1739137672.8488717,14.589986085891724,-0.0032571326633563658,1739137672.8488743,14.589986085891724,30.291546000479542,1739137672.8488765,14.589986085891724,39.17343967207796,1739137672.848878,14.589986085891724,-0.06399930256737531,1739137672.8488796,14.589986085891724,-0.007308165631735764,1739137672.848881,14.589986085891724,-0.24070975625016894,1739137672.8488822,14.589986085891724,-0.05351398209572021,1739137672.8488832,14.589986085891724,2.2705153436781105,1739137672.8488848,14.589986085891724,0.0,1739137672.8488858,14.589986085891724,-0.035341519128535566,1739137672.8488872,14.589986085891724,0.021656507622484257,1739137672.8488884,14.589986085891724,2.2962005788379325 +1739137672.8689313,14.609986066818237,30.862039580407824,1739137672.8689337,14.609986066818237,-0.0032571326633563658,1739137672.8689365,14.609986066818237,30.291546000479542,1739137672.868939,14.609986066818237,39.17343967207796,1739137672.8689404,14.609986066818237,-0.06399930256737531,1739137672.8689418,14.609986066818237,-0.007308165631735764,1739137672.8689432,14.609986066818237,-0.24070975625016894,1739137672.8689444,14.609986066818237,-0.05351398209572021,1739137672.8689456,14.609986066818237,2.2705153436781105,1739137672.8689473,14.609986066818237,0.0,1739137672.8689482,14.609986066818237,-0.025685235159822017,1739137672.8689497,14.609986066818237,0.021656507622484257,1739137672.868951,14.609986066818237,2.2962005788379325 +1739137672.8888974,14.629986047744751,30.862039580407824,1739137672.8888998,14.629986047744751,-0.0032571326633563658,1739137672.8889024,14.629986047744751,30.291546000479542,1739137672.888905,14.629986047744751,39.17343967207796,1739137672.8889065,14.629986047744751,-0.06399930256737531,1739137672.8889081,14.629986047744751,-0.007308165631735764,1739137672.8889093,14.629986047744751,-0.24070975625016894,1739137672.8889108,14.629986047744751,-0.05351398209572021,1739137672.888912,14.629986047744751,2.2705153436781105,1739137672.8889134,14.629986047744751,0.0,1739137672.8889146,14.629986047744751,-0.025685235159822017,1739137672.8889163,14.629986047744751,0.021656507622484257,1739137672.888918,14.629986047744751,2.2962005788379325 +1739137672.908813,14.649986028671265,30.862039580407824,1739137672.9088154,14.649986028671265,-0.0032571326633563658,1739137672.9088182,14.649986028671265,30.291546000479542,1739137672.9088204,14.649986028671265,39.17343967207796,1739137672.9088218,14.649986028671265,-0.06399930256737531,1739137672.9088235,14.649986028671265,-0.007308165631735764,1739137672.908825,14.649986028671265,-0.24070975625016894,1739137672.908826,14.649986028671265,-0.05351398209572021,1739137672.9088273,14.649986028671265,2.2705153436781105,1739137672.908829,14.649986028671265,0.0,1739137672.9088302,14.649986028671265,-0.025685235159822017,1739137672.9088318,14.649986028671265,0.021656507622484257,1739137672.908833,14.649986028671265,2.2962005788379325 +1739137672.9288971,14.669986009597778,30.862039580407824,1739137672.9288993,14.669986009597778,-0.0032571326633563658,1739137672.9289021,14.669986009597778,30.291546000479542,1739137672.9289052,14.669986009597778,39.17343967207796,1739137672.9289067,14.669986009597778,-0.06399930256737531,1739137672.9289083,14.669986009597778,-0.007308165631735764,1739137672.9289098,14.669986009597778,-0.24070975625016894,1739137672.9289112,14.669986009597778,-0.05351398209572021,1739137672.9289124,14.669986009597778,2.2705153436781105,1739137672.9289138,14.669986009597778,0.0,1739137672.9289153,14.669986009597778,-0.025685235159822017,1739137672.9289165,14.669986009597778,0.021656507622484257,1739137672.9289176,14.669986009597778,2.2962005788379325 +1739137672.9489534,14.689985990524292,31.114417574922058,1739137672.9489555,14.689985990524292,0.0021337306245712284,1739137672.9489584,14.689985990524292,30.321584372690026,1739137672.9489613,14.689985990524292,39.194786361317206,1739137672.9489625,14.689985990524292,-0.064246085101933,1739137672.9489644,14.689985990524292,-0.008214763993975617,1739137672.9489655,14.689985990524292,-0.23602022310394272,1739137672.9489672,14.689985990524292,-0.05551357370318455,1739137672.9489684,14.689985990524292,2.2747784035654903,1739137672.94897,14.689985990524292,0.0,1739137672.9489713,14.689985990524292,-0.012016496829988855,1739137672.9489725,14.689985990524292,0.02099749552229493,1739137672.9489741,14.689985990524292,2.2933038266611785 +1739137672.9689896,14.709985971450806,31.114417574922058,1739137672.968992,14.709985971450806,0.0021337306245712284,1739137672.9689949,14.709985971450806,30.321584372690026,1739137672.9689975,14.709985971450806,39.194786361317206,1739137672.9689987,14.709985971450806,-0.064246085101933,1739137672.9690003,14.709985971450806,-0.008214763993975617,1739137672.9690018,14.709985971450806,-0.23602022310394272,1739137672.9690032,14.709985971450806,-0.05551357370318455,1739137672.9690046,14.709985971450806,2.2747784035654903,1739137672.9690058,14.709985971450806,0.0,1739137672.969007,14.709985971450806,-0.018525423095688165,1739137672.9690084,14.709985971450806,0.02099749552229493,1739137672.9690096,14.709985971450806,2.2933038266611785 +1739137672.9889178,14.72998595237732,31.114417574922058,1739137672.9889197,14.72998595237732,0.0021337306245712284,1739137672.9889228,14.72998595237732,30.321584372690026,1739137672.9889255,14.72998595237732,39.194786361317206,1739137672.988927,14.72998595237732,-0.064246085101933,1739137672.9889286,14.72998595237732,-0.008214763993975617,1739137672.9889297,14.72998595237732,-0.23602022310394272,1739137672.9889312,14.72998595237732,-0.05551357370318455,1739137672.9889324,14.72998595237732,2.2747784035654903,1739137672.9889338,14.72998595237732,0.0,1739137672.9889352,14.72998595237732,-0.018525423095688165,1739137672.9889364,14.72998595237732,0.02099749552229493,1739137672.9889376,14.72998595237732,2.2933038266611785 +1739137673.00887,14.749985933303833,31.114417574922058,1739137673.0088723,14.749985933303833,0.0021337306245712284,1739137673.008875,14.749985933303833,30.321584372690026,1739137673.0088778,14.749985933303833,39.194786361317206,1739137673.0088792,14.749985933303833,-0.064246085101933,1739137673.0088809,14.749985933303833,-0.008214763993975617,1739137673.0088828,14.749985933303833,-0.23602022310394272,1739137673.008884,14.749985933303833,-0.05551357370318455,1739137673.008885,14.749985933303833,2.2747784035654903,1739137673.0088866,14.749985933303833,0.0,1739137673.0088878,14.749985933303833,-0.018525423095688165,1739137673.0088894,14.749985933303833,0.02099749552229493,1739137673.0088906,14.749985933303833,2.2933038266611785 +1739137673.0289881,14.769985914230347,31.114417574922058,1739137673.0289907,14.769985914230347,0.0021337306245712284,1739137673.0289934,14.769985914230347,30.321584372690026,1739137673.0289958,14.769985914230347,39.194786361317206,1739137673.0289972,14.769985914230347,-0.064246085101933,1739137673.0289989,14.769985914230347,-0.008214763993975617,1739137673.0290003,14.769985914230347,-0.23602022310394272,1739137673.0290015,14.769985914230347,-0.05551357370318455,1739137673.0290027,14.769985914230347,2.2747784035654903,1739137673.0290043,14.769985914230347,0.0,1739137673.0290055,14.769985914230347,-0.018525423095688165,1739137673.029007,14.769985914230347,0.02099749552229493,1739137673.0290082,14.769985914230347,2.2933038266611785 +1739137673.0489082,14.78998589515686,31.114417574922058,1739137673.0489106,14.78998589515686,0.0021337306245712284,1739137673.0489135,14.78998589515686,30.321584372690026,1739137673.0489159,14.78998589515686,39.194786361317206,1739137673.0489173,14.78998589515686,-0.064246085101933,1739137673.048919,14.78998589515686,-0.008214763993975617,1739137673.0489206,14.78998589515686,-0.23602022310394272,1739137673.0489218,14.78998589515686,-0.05551357370318455,1739137673.0489233,14.78998589515686,2.2747784035654903,1739137673.0489247,14.78998589515686,0.0,1739137673.0489259,14.78998589515686,-0.018525423095688165,1739137673.0489275,14.78998589515686,0.02099749552229493,1739137673.0489287,14.78998589515686,2.2933038266611785 +1739137673.0689678,14.809985876083374,31.36653785275707,1739137673.0689702,14.809985876083374,0.007345216419786915,1739137673.068973,14.809985876083374,30.766936682694826,1739137673.0689757,14.809985876083374,39.63439770072651,1739137673.0689769,14.809985876083374,-0.07024823621942268,1739137673.0689788,14.809985876083374,-0.00938467464527474,1739137673.0689802,14.809985876083374,-0.24510928887566802,1739137673.0689814,14.809985876083374,-0.05506526672565509,1739137673.0689826,14.809985876083374,2.2665231749112675,1739137673.068984,14.809985876083374,0.0,1739137673.0689855,14.809985876083374,-0.030659932249696216,1739137673.068987,14.809985876083374,0.02026440180195232,1739137673.0689878,14.809985876083374,2.2914047665820454 +1739137673.0889268,14.829985857009888,31.36653785275707,1739137673.088929,14.829985857009888,0.007345216419786915,1739137673.0889318,14.829985857009888,30.766936682694826,1739137673.088935,14.829985857009888,39.63439770072651,1739137673.0889363,14.829985857009888,-0.07024823621942268,1739137673.0889385,14.829985857009888,-0.00938467464527474,1739137673.0889404,14.829985857009888,-0.24510928887566802,1739137673.0889418,14.829985857009888,-0.05506526672565509,1739137673.0889437,14.829985857009888,2.2665231749112675,1739137673.0889452,14.829985857009888,0.0,1739137673.0889466,14.829985857009888,-0.02488159167077786,1739137673.0889485,14.829985857009888,0.02026440180195232,1739137673.08895,14.829985857009888,2.2914047665820454 +1739137673.1088924,14.849985837936401,31.36653785275707,1739137673.108895,14.849985837936401,0.007345216419786915,1739137673.1088974,14.849985837936401,30.766936682694826,1739137673.1089003,14.849985837936401,39.63439770072651,1739137673.1089013,14.849985837936401,-0.07024823621942268,1739137673.108903,14.849985837936401,-0.00938467464527474,1739137673.1089044,14.849985837936401,-0.24510928887566802,1739137673.1089058,14.849985837936401,-0.05506526672565509,1739137673.1089067,14.849985837936401,2.2665231749112675,1739137673.1089082,14.849985837936401,0.0,1739137673.1089096,14.849985837936401,-0.02488159167077786,1739137673.108911,14.849985837936401,0.02026440180195232,1739137673.1089125,14.849985837936401,2.2914047665820454 +1739137673.1289284,14.869985818862915,31.36653785275707,1739137673.1289308,14.869985818862915,0.007345216419786915,1739137673.1289337,14.869985818862915,30.766936682694826,1739137673.1289363,14.869985818862915,39.63439770072651,1739137673.1289377,14.869985818862915,-0.07024823621942268,1739137673.1289396,14.869985818862915,-0.00938467464527474,1739137673.1289408,14.869985818862915,-0.24510928887566802,1739137673.128942,14.869985818862915,-0.05506526672565509,1739137673.1289432,14.869985818862915,2.2665231749112675,1739137673.1289446,14.869985818862915,0.0,1739137673.1289458,14.869985818862915,-0.02488159167077786,1739137673.1289475,14.869985818862915,0.02026440180195232,1739137673.1289487,14.869985818862915,2.2914047665820454 +1739137673.1488926,14.889985799789429,31.36653785275707,1739137673.1488948,14.889985799789429,0.007345216419786915,1739137673.1488981,14.889985799789429,30.766936682694826,1739137673.1489005,14.889985799789429,39.63439770072651,1739137673.1489022,14.889985799789429,-0.07024823621942268,1739137673.148904,14.889985799789429,-0.00938467464527474,1739137673.1489058,14.889985799789429,-0.24510928887566802,1739137673.148907,14.889985799789429,-0.05506526672565509,1739137673.1489084,14.889985799789429,2.2665231749112675,1739137673.1489098,14.889985799789429,0.0,1739137673.148911,14.889985799789429,-0.02488159167077786,1739137673.1489124,14.889985799789429,0.02026440180195232,1739137673.1489136,14.889985799789429,2.2914047665820454 +1739137673.1689403,14.909985780715942,31.618402618860216,1739137673.168943,14.909985780715942,0.012365013075967823,1739137673.1689456,14.909985780715942,30.796409880125555,1739137673.168948,14.909985780715942,39.65554643876338,1739137673.1689496,14.909985780715942,-0.07061286963385148,1739137673.168951,14.909985780715942,-0.01032393304402733,1739137673.1689525,14.909985780715942,-0.23986849114785505,1739137673.168954,14.909985780715942,-0.05702461215452004,1739137673.1689548,14.909985780715942,2.271279514374089,1739137673.1689565,14.909985780715942,0.0,1739137673.1689577,14.909985780715942,-0.010505917654095333,1739137673.1689591,14.909985780715942,0.019523899919594377,1739137673.1689606,14.909985780715942,2.288630994503405 +1739137673.18885,14.929985761642456,31.618402618860216,1739137673.1888523,14.929985761642456,0.012365013075967823,1739137673.188855,14.929985761642456,30.796409880125555,1739137673.1888573,14.929985761642456,39.65554643876338,1739137673.1888585,14.929985761642456,-0.07061286963385148,1739137673.1888602,14.929985761642456,-0.01032393304402733,1739137673.1888616,14.929985761642456,-0.23986849114785505,1739137673.188863,14.929985761642456,-0.05702461215452004,1739137673.1888642,14.929985761642456,2.271279514374089,1739137673.188866,14.929985761642456,0.0,1739137673.1888669,14.929985761642456,-0.017351480129315977,1739137673.1888683,14.929985761642456,0.019523899919594377,1739137673.1888695,14.929985761642456,2.288630994503405 +1739137673.208943,14.94998574256897,31.618402618860216,1739137673.208945,14.94998574256897,0.012365013075967823,1739137673.208948,14.94998574256897,30.796409880125555,1739137673.208951,14.94998574256897,39.65554643876338,1739137673.2089527,14.94998574256897,-0.07061286963385148,1739137673.2089546,14.94998574256897,-0.01032393304402733,1739137673.2089562,14.94998574256897,-0.23986849114785505,1739137673.208958,14.94998574256897,-0.05702461215452004,1739137673.2089593,14.94998574256897,2.271279514374089,1739137673.208961,14.94998574256897,0.0,1739137673.2089627,14.94998574256897,-0.017351480129315977,1739137673.208964,14.94998574256897,0.019523899919594377,1739137673.2089655,14.94998574256897,2.288630994503405 +1739137673.228925,14.969985723495483,31.618402618860216,1739137673.228927,14.969985723495483,0.012365013075967823,1739137673.22893,14.969985723495483,30.796409880125555,1739137673.2289329,14.969985723495483,39.65554643876338,1739137673.228934,14.969985723495483,-0.07061286963385148,1739137673.2289357,14.969985723495483,-0.01032393304402733,1739137673.228937,14.969985723495483,-0.23986849114785505,1739137673.2289386,14.969985723495483,-0.05702461215452004,1739137673.2289398,14.969985723495483,2.271279514374089,1739137673.2289417,14.969985723495483,0.0,1739137673.2289429,14.969985723495483,-0.017351480129315977,1739137673.2289443,14.969985723495483,0.019523899919594377,1739137673.2289457,14.969985723495483,2.288630994503405 +1739137673.2489061,14.989985704421997,31.618402618860216,1739137673.2489085,14.989985704421997,0.012365013075967823,1739137673.2489116,14.989985704421997,30.796409880125555,1739137673.2489142,14.989985704421997,39.65554643876338,1739137673.2489157,14.989985704421997,-0.07061286963385148,1739137673.2489173,14.989985704421997,-0.01032393304402733,1739137673.248919,14.989985704421997,-0.23986849114785505,1739137673.2489202,14.989985704421997,-0.05702461215452004,1739137673.2489216,14.989985704421997,2.271279514374089,1739137673.248923,14.989985704421997,0.0,1739137673.2489245,14.989985704421997,-0.017351480129315977,1739137673.248926,14.989985704421997,0.019523899919594377,1739137673.248927,14.989985704421997,2.288630994503405 +1739137673.2689912,15.00998568534851,31.618402618860216,1739137673.2689936,15.00998568534851,0.012365013075967823,1739137673.2689962,15.00998568534851,30.796409880125555,1739137673.2689989,15.00998568534851,39.65554643876338,1739137673.2690005,15.00998568534851,-0.07061286963385148,1739137673.269002,15.00998568534851,-0.01032393304402733,1739137673.2690036,15.00998568534851,-0.23986849114785505,1739137673.2690048,15.00998568534851,-0.05702461215452004,1739137673.269006,15.00998568534851,2.271279514374089,1739137673.2690074,15.00998568534851,0.0,1739137673.2690086,15.00998568534851,-0.017351480129315977,1739137673.26901,15.00998568534851,0.019523899919594377,1739137673.2690115,15.00998568534851,2.288630994503405 +1739137673.2889616,15.029985666275024,31.870023491855115,1739137673.2889638,15.029985666275024,0.017193545022692547,1739137673.2889664,15.029985666275024,31.031523600732278,1739137673.2889693,15.029985666275024,39.885343651839875,1739137673.2889705,15.029985666275024,-0.07379919117473506,1739137673.2889724,15.029985666275024,-0.011351864399679269,1739137673.2889736,15.029985666275024,-0.2415227809043793,1739137673.2889748,15.029985666275024,-0.05772952580217564,1739137673.2889762,15.029985666275024,2.2697770697507287,1739137673.2889776,15.029985666275024,0.0,1739137673.288979,15.029985666275024,-0.01685237714208333,1739137673.2889802,15.029985666275024,0.018783398037236436,1739137673.2889814,15.029985666275024,2.286867115100696 +1739137673.3089101,15.049985647201538,31.870023491855115,1739137673.3089123,15.049985647201538,0.017193545022692547,1739137673.3089151,15.049985647201538,31.031523600732278,1739137673.3089178,15.049985647201538,39.885343651839875,1739137673.308919,15.049985647201538,-0.07379919117473506,1739137673.3089206,15.049985647201538,-0.011351864399679269,1739137673.308922,15.049985647201538,-0.2415227809043793,1739137673.3089235,15.049985647201538,-0.05772952580217564,1739137673.3089247,15.049985647201538,2.2697770697507287,1739137673.308926,15.049985647201538,0.0,1739137673.3089275,15.049985647201538,-0.017090045349967387,1739137673.308929,15.049985647201538,0.018783398037236436,1739137673.3089306,15.049985647201538,2.286867115100696 +1739137673.3289208,15.069985628128052,31.870023491855115,1739137673.3289232,15.069985628128052,0.017193545022692547,1739137673.3289258,15.069985628128052,31.031523600732278,1739137673.3289287,15.069985628128052,39.885343651839875,1739137673.3289304,15.069985628128052,-0.07379919117473506,1739137673.3289318,15.069985628128052,-0.011351864399679269,1739137673.3289335,15.069985628128052,-0.2415227809043793,1739137673.3289347,15.069985628128052,-0.05772952580217564,1739137673.3289359,15.069985628128052,2.2697770697507287,1739137673.3289375,15.069985628128052,0.0,1739137673.328939,15.069985628128052,-0.017090045349967387,1739137673.3289404,15.069985628128052,0.018783398037236436,1739137673.3289416,15.069985628128052,2.286867115100696 +1739137673.348898,15.089985609054565,31.870023491855115,1739137673.3489003,15.089985609054565,0.017193545022692547,1739137673.3489032,15.089985609054565,31.031523600732278,1739137673.348906,15.089985609054565,39.885343651839875,1739137673.3489072,15.089985609054565,-0.07379919117473506,1739137673.348909,15.089985609054565,-0.011351864399679269,1739137673.3489106,15.089985609054565,-0.2415227809043793,1739137673.3489118,15.089985609054565,-0.05772952580217564,1739137673.3489132,15.089985609054565,2.2697770697507287,1739137673.3489146,15.089985609054565,0.0,1739137673.3489158,15.089985609054565,-0.017090045349967387,1739137673.3489172,15.089985609054565,0.018783398037236436,1739137673.3489184,15.089985609054565,2.286867115100696 +1739137673.3689096,15.109985589981079,31.870023491855115,1739137673.368912,15.109985589981079,0.017193545022692547,1739137673.3689146,15.109985589981079,31.031523600732278,1739137673.3689172,15.109985589981079,39.885343651839875,1739137673.368919,15.109985589981079,-0.07379919117473506,1739137673.3689203,15.109985589981079,-0.011351864399679269,1739137673.3689218,15.109985589981079,-0.2415227809043793,1739137673.368923,15.109985589981079,-0.05772952580217564,1739137673.3689241,15.109985589981079,2.2697770697507287,1739137673.3689258,15.109985589981079,0.0,1739137673.368927,15.109985589981079,-0.017090045349967387,1739137673.3689284,15.109985589981079,0.018783398037236436,1739137673.3689299,15.109985589981079,2.286867115100696 +1739137673.3890355,15.129985570907593,32.12144278146346,1739137673.3890378,15.129985570907593,0.02182586180457946,1739137673.389041,15.129985570907593,31.173997176370467,1739137673.3890438,15.129985570907593,40.02220519395617,1739137673.389045,15.129985570907593,-0.07546265386048838,1739137673.3890464,15.129985570907593,-0.012313191277908324,1739137673.389048,15.129985570907593,-0.23929029051679565,1739137673.3890493,15.129985570907593,-0.058864939305918615,1739137673.3890507,15.129985570907593,2.2718048772241826,1739137673.3890524,15.129985570907593,0.0,1739137673.3890536,15.129985570907593,-0.009654243201926592,1739137673.3890553,15.129985570907593,0.017976131275661486,1739137673.3890564,15.129985570907593,2.284999980360657 +1739137673.408864,15.149985551834106,32.12144278146346,1739137673.4088664,15.149985551834106,0.02182586180457946,1739137673.408869,15.149985551834106,31.173997176370467,1739137673.4088717,15.149985551834106,40.02220519395617,1739137673.4088733,15.149985551834106,-0.07546265386048838,1739137673.4088748,15.149985551834106,-0.012313191277908324,1739137673.4088762,15.149985551834106,-0.23929029051679565,1739137673.4088776,15.149985551834106,-0.058864939305918615,1739137673.408879,15.149985551834106,2.2718048772241826,1739137673.4088807,15.149985551834106,0.0,1739137673.408882,15.149985551834106,-0.01319510313647454,1739137673.4088836,15.149985551834106,0.017976131275661486,1739137673.4088848,15.149985551834106,2.284999980360657 +1739137673.4295795,15.16998553276062,32.12144278146346,1739137673.4295833,15.16998553276062,0.02182586180457946,1739137673.429588,15.16998553276062,31.173997176370467,1739137673.4295933,15.16998553276062,40.02220519395617,1739137673.4295962,15.16998553276062,-0.07546265386048838,1739137673.4296,15.16998553276062,-0.012313191277908324,1739137673.4296033,15.16998553276062,-0.23929029051679565,1739137673.4296072,15.16998553276062,-0.058864939305918615,1739137673.4296107,15.16998553276062,2.2718048772241826,1739137673.4296134,15.16998553276062,0.0,1739137673.4296172,15.16998553276062,-0.01319510313647454,1739137673.4296217,15.16998553276062,0.017976131275661486,1739137673.4296253,15.16998553276062,2.284999980360657 +1739137673.4503238,15.189985513687134,32.12144278146346,1739137673.4503276,15.189985513687134,0.02182586180457946,1739137673.4503326,15.189985513687134,31.173997176370467,1739137673.4503381,15.189985513687134,40.02220519395617,1739137673.4503407,15.189985513687134,-0.07546265386048838,1739137673.4503448,15.189985513687134,-0.012313191277908324,1739137673.4503484,15.189985513687134,-0.23929029051679565,1739137673.4503517,15.189985513687134,-0.058864939305918615,1739137673.450355,15.189985513687134,2.2718048772241826,1739137673.4503586,15.189985513687134,0.0,1739137673.450362,15.189985513687134,-0.01319510313647454,1739137673.4503655,15.189985513687134,0.017976131275661486,1739137673.450369,15.189985513687134,2.284999980360657 +1739137673.469697,15.209985494613647,32.12144278146346,1739137673.4697003,15.209985494613647,0.02182586180457946,1739137673.4697049,15.209985494613647,31.173997176370467,1739137673.4697104,15.209985494613647,40.02220519395617,1739137673.4697132,15.209985494613647,-0.07546265386048838,1739137673.4697168,15.209985494613647,-0.012313191277908324,1739137673.4697204,15.209985494613647,-0.23929029051679565,1739137673.4697237,15.209985494613647,-0.058864939305918615,1739137673.469727,15.209985494613647,2.2718048772241826,1739137673.4697304,15.209985494613647,0.0,1739137673.4697337,15.209985494613647,-0.01319510313647454,1739137673.4697373,15.209985494613647,0.017976131275661486,1739137673.4697409,15.209985494613647,2.284999980360657 +1739137673.490738,15.229985475540161,32.12144278146346,1739137673.4907422,15.229985475540161,0.02182586180457946,1739137673.4907475,15.229985475540161,31.173997176370467,1739137673.4907537,15.229985475540161,40.02220519395617,1739137673.4907548,15.229985475540161,-0.07546265386048838,1739137673.4907565,15.229985475540161,-0.012313191277908324,1739137673.490758,15.229985475540161,-0.23929029051679565,1739137673.4907591,15.229985475540161,-0.058864939305918615,1739137673.4907608,15.229985475540161,2.2718048772241826,1739137673.4907622,15.229985475540161,0.0,1739137673.4907632,15.229985475540161,-0.01319510313647454,1739137673.4907668,15.229985475540161,0.017976131275661486,1739137673.49077,15.229985475540161,2.284999980360657 +1739137673.5094142,15.249985456466675,32.37268817849604,1739137673.509417,15.249985456466675,0.02624886308119212,1739137673.5094204,15.249985456466675,31.572347792163466,1739137673.5094237,15.249985456466675,40.41641502085909,1739137673.5094252,15.249985456466675,-0.07894848338043926,1739137673.5094273,15.249985456466675,-0.013077439292143314,1739137673.509429,15.249985456466675,-0.24315741655851497,1739137673.5094306,15.249985456466675,-0.057708031791462694,1739137673.509432,15.249985456466675,2.2682934514286055,1739137673.5094335,15.249985456466675,0.0,1739137673.5094352,15.249985456466675,-0.017274956749079837,1739137673.5094368,15.249985456466675,0.017154027874260534,1739137673.5094385,15.249985456466675,2.2836256197726037 +1739137673.5290992,15.269985437393188,32.37268817849604,1739137673.5291018,15.269985437393188,0.02624886308119212,1739137673.5291047,15.269985437393188,31.572347792163466,1739137673.5291076,15.269985437393188,40.41641502085909,1739137673.5291092,15.269985437393188,-0.07894848338043926,1739137673.5291111,15.269985437393188,-0.013077439292143314,1739137673.5291126,15.269985437393188,-0.24315741655851497,1739137673.5291138,15.269985437393188,-0.057708031791462694,1739137673.5291152,15.269985437393188,2.2682934514286055,1739137673.529117,15.269985437393188,0.0,1739137673.5291185,15.269985437393188,-0.015332168343998198,1739137673.5291197,15.269985437393188,0.017154027874260534,1739137673.5291214,15.269985437393188,2.2836256197726037 +1739137673.5490131,15.289985418319702,32.37268817849604,1739137673.5490153,15.289985418319702,0.02624886308119212,1739137673.5490181,15.289985418319702,31.572347792163466,1739137673.549021,15.289985418319702,40.41641502085909,1739137673.5490224,15.289985418319702,-0.07894848338043926,1739137673.5490243,15.289985418319702,-0.013077439292143314,1739137673.5490255,15.289985418319702,-0.24315741655851497,1739137673.5490267,15.289985418319702,-0.057708031791462694,1739137673.549028,15.289985418319702,2.2682934514286055,1739137673.549029,15.289985418319702,0.0,1739137673.5490303,15.289985418319702,-0.015332168343998198,1739137673.5490317,15.289985418319702,0.017154027874260534,1739137673.5490332,15.289985418319702,2.2836256197726037 +1739137673.569009,15.309985399246216,32.37268817849604,1739137673.5690117,15.309985399246216,0.02624886308119212,1739137673.5690143,15.309985399246216,31.572347792163466,1739137673.569017,15.309985399246216,40.41641502085909,1739137673.5690181,15.309985399246216,-0.07894848338043926,1739137673.5690196,15.309985399246216,-0.013077439292143314,1739137673.569021,15.309985399246216,-0.24315741655851497,1739137673.5690222,15.309985399246216,-0.057708031791462694,1739137673.5690234,15.309985399246216,2.2682934514286055,1739137673.569025,15.309985399246216,0.0,1739137673.569026,15.309985399246216,-0.015332168343998198,1739137673.5690274,15.309985399246216,0.017154027874260534,1739137673.5690286,15.309985399246216,2.2836256197726037 +1739137673.5889766,15.32998538017273,32.37268817849604,1739137673.588979,15.32998538017273,0.02624886308119212,1739137673.5889819,15.32998538017273,31.572347792163466,1739137673.5889845,15.32998538017273,40.41641502085909,1739137673.5889862,15.32998538017273,-0.07894848338043926,1739137673.5889878,15.32998538017273,-0.013077439292143314,1739137673.5889895,15.32998538017273,-0.24315741655851497,1739137673.588991,15.32998538017273,-0.057708031791462694,1739137673.5889926,15.32998538017273,2.2682934514286055,1739137673.588994,15.32998538017273,0.0,1739137673.5889952,15.32998538017273,-0.015332168343998198,1739137673.588997,15.32998538017273,0.017154027874260534,1739137673.5889983,15.32998538017273,2.2836256197726037 +1739137673.6091235,15.349985361099243,32.623766518567194,1739137673.6091256,15.349985361099243,0.03046245239188128,1739137673.6091282,15.349985361099243,32.28239885221509,1739137673.6091309,15.349985361099243,41.12132307558827,1739137673.609132,15.349985361099243,-0.08634712111835226,1739137673.6091335,15.349985361099243,-0.013745388587177196,1739137673.6091352,15.349985361099243,-0.2555692778504334,1739137673.609136,15.349985361099243,-0.05434782445831508,1739137673.6091373,15.349985361099243,2.2570598629759684,1739137673.609139,15.349985361099243,0.0,1739137673.60914,15.349985361099243,-0.033543037494022626,1739137673.6091413,15.349985361099243,0.016331924472859582,1739137673.6091425,15.349985361099243,2.281931053685632 +1739137673.628953,15.369985342025757,32.623766518567194,1739137673.6289558,15.369985342025757,0.03046245239188128,1739137673.6289587,15.369985342025757,32.28239885221509,1739137673.6289616,15.369985342025757,41.12132307558827,1739137673.628963,15.369985342025757,-0.08634712111835226,1739137673.6289654,15.369985342025757,-0.013745388587177196,1739137673.6289668,15.369985342025757,-0.2555692778504334,1739137673.6289685,15.369985342025757,-0.05434782445831508,1739137673.62897,15.369985342025757,2.2570598629759684,1739137673.6289716,15.369985342025757,0.0,1739137673.628973,15.369985342025757,-0.024871190709663704,1739137673.6289747,15.369985342025757,0.016331924472859582,1739137673.628976,15.369985342025757,2.281931053685632 +1739137673.6489062,15.38998532295227,32.623766518567194,1739137673.6489086,15.38998532295227,0.03046245239188128,1739137673.648911,15.38998532295227,32.28239885221509,1739137673.6489134,15.38998532295227,41.12132307558827,1739137673.6489146,15.38998532295227,-0.08634712111835226,1739137673.6489162,15.38998532295227,-0.013745388587177196,1739137673.6489174,15.38998532295227,-0.2555692778504334,1739137673.6489189,15.38998532295227,-0.05434782445831508,1739137673.6489198,15.38998532295227,2.2570598629759684,1739137673.6489213,15.38998532295227,0.0,1739137673.6489227,15.38998532295227,-0.024871190709663704,1739137673.648924,15.38998532295227,0.016331924472859582,1739137673.6489255,15.38998532295227,2.281931053685632 +1739137673.6690872,15.409985303878784,32.623766518567194,1739137673.6690898,15.409985303878784,0.03046245239188128,1739137673.669093,15.409985303878784,32.28239885221509,1739137673.669096,15.409985303878784,41.12132307558827,1739137673.6690977,15.409985303878784,-0.08634712111835226,1739137673.6691,15.409985303878784,-0.013745388587177196,1739137673.6691017,15.409985303878784,-0.2555692778504334,1739137673.6691036,15.409985303878784,-0.05434782445831508,1739137673.669105,15.409985303878784,2.2570598629759684,1739137673.6691067,15.409985303878784,0.0,1739137673.6691082,15.409985303878784,-0.024871190709663704,1739137673.66911,15.409985303878784,0.016331924472859582,1739137673.6691113,15.409985303878784,2.281931053685632 +1739137673.6892061,15.429985284805298,32.623766518567194,1739137673.6892085,15.429985284805298,0.03046245239188128,1739137673.689212,15.429985284805298,32.28239885221509,1739137673.6892154,15.429985284805298,41.12132307558827,1739137673.6892173,15.429985284805298,-0.08634712111835226,1739137673.6892195,15.429985284805298,-0.013745388587177196,1739137673.6892216,15.429985284805298,-0.2555692778504334,1739137673.6892235,15.429985284805298,-0.05434782445831508,1739137673.6892252,15.429985284805298,2.2570598629759684,1739137673.689227,15.429985284805298,0.0,1739137673.689229,15.429985284805298,-0.024871190709663704,1739137673.6892307,15.429985284805298,0.016331924472859582,1739137673.6892323,15.429985284805298,2.281931053685632 +1739137673.7091608,15.449985265731812,32.623766518567194,1739137673.7091634,15.449985265731812,0.03046245239188128,1739137673.709167,15.449985265731812,32.28239885221509,1739137673.7091703,15.449985265731812,41.12132307558827,1739137673.7091722,15.449985265731812,-0.08634712111835226,1739137673.7091746,15.449985265731812,-0.013745388587177196,1739137673.7091765,15.449985265731812,-0.2555692778504334,1739137673.7091787,15.449985265731812,-0.05434782445831508,1739137673.70918,15.449985265731812,2.2570598629759684,1739137673.7091823,15.449985265731812,0.0,1739137673.7091837,15.449985265731812,-0.024871190709663704,1739137673.709186,15.449985265731812,0.016331924472859582,1739137673.7091877,15.449985265731812,2.281931053685632 +1739137673.7294936,15.469985246658325,32.87459417578815,1739137673.7294967,15.469985246658325,0.03446558170261671,1739137673.7295008,15.469985246658325,32.68290247789752,1739137673.7295046,15.469985246658325,41.513093581240476,1739137673.7295065,15.469985246658325,-0.09232163755887238,1739137673.729509,15.469985246658325,-0.014675942031700678,1739137673.7295113,15.469985246658325,-0.26074817846860177,1739137673.7295132,15.469985246658325,-0.05365324993261067,1739137673.7295156,15.469985246658325,2.252389067076019,1739137673.729518,15.469985246658325,0.0,1739137673.7295196,15.469985246658325,-0.028262004222063212,1739137673.729522,15.469985246658325,0.01550982107145863,1739137673.7295237,15.469985246658325,2.2790363973903394 +1739137673.7494442,15.489985227584839,32.87459417578815,1739137673.7494473,15.489985227584839,0.03446558170261671,1739137673.749451,15.489985227584839,32.68290247789752,1739137673.7494552,15.489985227584839,41.513093581240476,1739137673.7494571,15.489985227584839,-0.09232163755887238,1739137673.7494597,15.489985227584839,-0.014675942031700678,1739137673.7494621,15.489985227584839,-0.26074817846860177,1739137673.7494638,15.489985227584839,-0.05365324993261067,1739137673.749466,15.489985227584839,2.252389067076019,1739137673.749468,15.489985227584839,0.0,1739137673.74947,15.489985227584839,-0.026647330314320428,1739137673.749472,15.489985227584839,0.01550982107145863,1739137673.749474,15.489985227584839,2.2790363973903394 +1739137673.7694397,15.509985208511353,32.87459417578815,1739137673.7694426,15.509985208511353,0.03446558170261671,1739137673.7694464,15.509985208511353,32.68290247789752,1739137673.7694502,15.509985208511353,41.513093581240476,1739137673.7694526,15.509985208511353,-0.09232163755887238,1739137673.7694554,15.509985208511353,-0.014675942031700678,1739137673.7694573,15.509985208511353,-0.26074817846860177,1739137673.7694595,15.509985208511353,-0.05365324993261067,1739137673.7694619,15.509985208511353,2.252389067076019,1739137673.7694638,15.509985208511353,0.0,1739137673.7694657,15.509985208511353,-0.026647330314320428,1739137673.7694678,15.509985208511353,0.01550982107145863,1739137673.7694697,15.509985208511353,2.2790363973903394 +1739137673.7893324,15.529985189437866,32.87459417578815,1739137673.7893355,15.529985189437866,0.03446558170261671,1739137673.789339,15.529985189437866,32.68290247789752,1739137673.7893429,15.529985189437866,41.513093581240476,1739137673.7893448,15.529985189437866,-0.09232163755887238,1739137673.7893474,15.529985189437866,-0.014675942031700678,1739137673.789349,15.529985189437866,-0.26074817846860177,1739137673.7893512,15.529985189437866,-0.05365324993261067,1739137673.7893531,15.529985189437866,2.252389067076019,1739137673.7893553,15.529985189437866,0.0,1739137673.7893574,15.529985189437866,-0.026647330314320428,1739137673.789359,15.529985189437866,0.01550982107145863,1739137673.7893615,15.529985189437866,2.2790363973903394 +1739137673.8094294,15.54998517036438,32.87459417578815,1739137673.8094323,15.54998517036438,0.03446558170261671,1739137673.809436,15.54998517036438,32.68290247789752,1739137673.80944,15.54998517036438,41.513093581240476,1739137673.809442,15.54998517036438,-0.09232163755887238,1739137673.8094444,15.54998517036438,-0.014675942031700678,1739137673.8094466,15.54998517036438,-0.26074817846860177,1739137673.8094487,15.54998517036438,-0.05365324993261067,1739137673.8094504,15.54998517036438,2.252389067076019,1739137673.8094525,15.54998517036438,0.0,1739137673.809454,15.54998517036438,-0.026647330314320428,1739137673.8094563,15.54998517036438,0.01550982107145863,1739137673.8094583,15.54998517036438,2.2790363973903394 +1739137673.8294418,15.569985151290894,33.125112640280086,1739137673.829445,15.569985151290894,0.038257775274209926,1739137673.8294482,15.569985151290894,32.73351099991846,1739137673.829452,15.569985151290894,41.554913424458086,1739137673.8294537,15.569985151290894,-0.09271616438168004,1739137673.8294563,15.569985151290894,-0.015535764788494028,1739137673.8294585,15.569985151290894,-0.2547698947169357,1739137673.8294604,15.569985151290894,-0.05504921458469898,1739137673.8294625,15.569985151290894,2.257781680605889,1739137673.8294647,15.569985151290894,0.0,1739137673.8294663,15.569985151290894,-0.010760722262328997,1739137673.8294685,15.569985151290894,0.014687717670057679,1739137673.8294702,15.569985151290894,2.276107458100623 +1739137673.8494132,15.589985132217407,33.125112640280086,1739137673.8494163,15.589985132217407,0.038257775274209926,1739137673.8494198,15.589985132217407,32.73351099991846,1739137673.8494236,15.589985132217407,41.554913424458086,1739137673.8494256,15.589985132217407,-0.09271616438168004,1739137673.8494282,15.589985132217407,-0.015535764788494028,1739137673.8494303,15.589985132217407,-0.2547698947169357,1739137673.8494325,15.589985132217407,-0.05504921458469898,1739137673.8494344,15.589985132217407,2.257781680605889,1739137673.8494365,15.589985132217407,0.0,1739137673.8494384,15.589985132217407,-0.018325777494733853,1739137673.8494406,15.589985132217407,0.014687717670057679,1739137673.8494422,15.589985132217407,2.276107458100623 +1739137673.8693335,15.609985113143921,33.125112640280086,1739137673.8693383,15.609985113143921,0.038257775274209926,1739137673.8693435,15.609985113143921,32.73351099991846,1739137673.8693485,15.609985113143921,41.554913424458086,1739137673.869351,15.609985113143921,-0.09271616438168004,1739137673.8693542,15.609985113143921,-0.015535764788494028,1739137673.8693573,15.609985113143921,-0.2547698947169357,1739137673.8693604,15.609985113143921,-0.05504921458469898,1739137673.8693635,15.609985113143921,2.257781680605889,1739137673.8693662,15.609985113143921,0.0,1739137673.869378,15.609985113143921,-0.018325777494733853,1739137673.8693802,15.609985113143921,0.014687717670057679,1739137673.8693829,15.609985113143921,2.276107458100623 +1739137673.8894656,15.629985094070435,33.125112640280086,1739137673.8894687,15.629985094070435,0.038257775274209926,1739137673.8894725,15.629985094070435,32.73351099991846,1739137673.8894765,15.629985094070435,41.554913424458086,1739137673.8894787,15.629985094070435,-0.09271616438168004,1739137673.889481,15.629985094070435,-0.015535764788494028,1739137673.889483,15.629985094070435,-0.2547698947169357,1739137673.889485,15.629985094070435,-0.05504921458469898,1739137673.8894868,15.629985094070435,2.257781680605889,1739137673.889489,15.629985094070435,0.0,1739137673.8894906,15.629985094070435,-0.018325777494733853,1739137673.8894928,15.629985094070435,0.014687717670057679,1739137673.8894944,15.629985094070435,2.276107458100623 +1739137673.9093263,15.649985074996948,33.125112640280086,1739137673.9093294,15.649985074996948,0.038257775274209926,1739137673.909333,15.649985074996948,32.73351099991846,1739137673.9093368,15.649985074996948,41.554913424458086,1739137673.9093387,15.649985074996948,-0.09271616438168004,1739137673.909341,15.649985074996948,-0.015535764788494028,1739137673.9093432,15.649985074996948,-0.2547698947169357,1739137673.9093456,15.649985074996948,-0.05504921458469898,1739137673.9093473,15.649985074996948,2.257781680605889,1739137673.9093494,15.649985074996948,0.0,1739137673.9093513,15.649985074996948,-0.018325777494733853,1739137673.9093535,15.649985074996948,0.014687717670057679,1739137673.9093554,15.649985074996948,2.276107458100623 +1739137673.9294713,15.669985055923462,33.125112640280086,1739137673.9294744,15.669985055923462,0.038257775274209926,1739137673.9294782,15.669985055923462,32.73351099991846,1739137673.9294817,15.669985055923462,41.554913424458086,1739137673.929484,15.669985055923462,-0.09271616438168004,1739137673.9294865,15.669985055923462,-0.015535764788494028,1739137673.9294887,15.669985055923462,-0.2547698947169357,1739137673.9294908,15.669985055923462,-0.05504921458469898,1739137673.9294927,15.669985055923462,2.257781680605889,1739137673.9294953,15.669985055923462,0.0,1739137673.9294972,15.669985055923462,-0.018325777494733853,1739137673.9294994,15.669985055923462,0.014687717670057679,1739137673.9295015,15.669985055923462,2.276107458100623 +1739137673.949403,15.689985036849976,33.37537262490823,1739137673.949406,15.689985036849976,0.041840264177660735,1739137673.9494092,15.689985036849976,32.784067099302256,1739137673.9494126,15.689985036849976,41.59989662606956,1739137673.9494145,15.689985036849976,-0.09328106841640675,1739137673.9494164,15.689985036849976,-0.016427598420558708,1739137673.949418,15.689985036849976,-0.24914276721728207,1739137673.9494197,15.689985036849976,-0.056552173608124506,1739137673.9494214,15.689985036849976,2.2628693343864716,1739137673.949423,15.689985036849976,0.0,1739137673.949425,15.689985036849976,-0.005069127601206072,1739137673.9494267,15.689985036849976,0.013865614268656727,1739137673.9494283,15.689985036849976,2.2742511555666334 +1739137673.9692905,15.70998501777649,33.37537262490823,1739137673.9692936,15.70998501777649,0.041840264177660735,1739137673.9692974,15.70998501777649,32.784067099302256,1739137673.9693012,15.70998501777649,41.59989662606956,1739137673.9693034,15.70998501777649,-0.09328106841640675,1739137673.9693055,15.70998501777649,-0.016427598420558708,1739137673.9693077,15.70998501777649,-0.24914276721728207,1739137673.9693098,15.70998501777649,-0.056552173608124506,1739137673.9693117,15.70998501777649,2.2628693343864716,1739137673.9693136,15.70998501777649,0.0,1739137673.9693153,15.70998501777649,-0.011381821180161733,1739137673.9693174,15.70998501777649,0.013865614268656727,1739137673.9693193,15.70998501777649,2.2742511555666334 +1739137673.9893165,15.729984998703003,33.37537262490823,1739137673.989319,15.729984998703003,0.041840264177660735,1739137673.9893227,15.729984998703003,32.784067099302256,1739137673.9893262,15.729984998703003,41.59989662606956,1739137673.9893281,15.729984998703003,-0.09328106841640675,1739137673.9893308,15.729984998703003,-0.016427598420558708,1739137673.9893327,15.729984998703003,-0.24914276721728207,1739137673.9893348,15.729984998703003,-0.056552173608124506,1739137673.9893367,15.729984998703003,2.2628693343864716,1739137673.9893389,15.729984998703003,0.0,1739137673.9893408,15.729984998703003,-0.011381821180161733,1739137673.9893427,15.729984998703003,0.013865614268656727,1739137673.9893446,15.729984998703003,2.2742511555666334 +1739137674.0094104,15.749984979629517,33.37537262490823,1739137674.0094135,15.749984979629517,0.041840264177660735,1739137674.009417,15.749984979629517,32.784067099302256,1739137674.0094209,15.749984979629517,41.59989662606956,1739137674.0094225,15.749984979629517,-0.09328106841640675,1739137674.009425,15.749984979629517,-0.016427598420558708,1739137674.0094266,15.749984979629517,-0.24914276721728207,1739137674.0094287,15.749984979629517,-0.056552173608124506,1739137674.0094306,15.749984979629517,2.2628693343864716,1739137674.0094326,15.749984979629517,0.0,1739137674.0094345,15.749984979629517,-0.011381821180161733,1739137674.0094366,15.749984979629517,0.013865614268656727,1739137674.0094385,15.749984979629517,2.2742511555666334 +1739137674.0296159,15.76998496055603,33.37537262490823,1739137674.0296195,15.76998496055603,0.041840264177660735,1739137674.0296233,15.76998496055603,32.784067099302256,1739137674.0296268,15.76998496055603,41.59989662606956,1739137674.0296288,15.76998496055603,-0.09328106841640675,1739137674.029631,15.76998496055603,-0.016427598420558708,1739137674.0296328,15.76998496055603,-0.24914276721728207,1739137674.0296347,15.76998496055603,-0.056552173608124506,1739137674.0296366,15.76998496055603,2.2628693343864716,1739137674.0296388,15.76998496055603,0.0,1739137674.0296402,15.76998496055603,-0.011381821180161733,1739137674.0296423,15.76998496055603,0.013865614268656727,1739137674.029644,15.76998496055603,2.2742511555666334 +1739137674.0495715,15.789984941482544,33.62545901566971,1739137674.0495749,15.789984941482544,0.045214625814234743,1739137674.0495794,15.789984941482544,33.412072720250464,1739137674.0495834,15.789984941482544,42.22423552384599,1739137674.0495856,15.789984941482544,-0.10417647619136569,1739137674.0495884,15.789984941482544,-0.017371782354262955,1739137674.0495908,15.789984941482544,-0.26153344854490856,1739137674.049593,15.789984941482544,-0.054308351647267286,1739137674.049595,15.789984941482544,2.2516816846852494,1739137674.0495975,15.789984941482544,0.0,1739137674.0495996,15.789984941482544,-0.030472392777455615,1739137674.049602,15.789984941482544,0.013043510867255775,1739137674.0496047,15.789984941482544,2.273063324541813 +1739137674.06958,15.809984922409058,33.62545901566971,1739137674.0695834,15.809984922409058,0.045214625814234743,1739137674.0695875,15.809984922409058,33.412072720250464,1739137674.0695915,15.809984922409058,42.22423552384599,1739137674.069594,15.809984922409058,-0.10417647619136569,1739137674.0695972,15.809984922409058,-0.017371782354262955,1739137674.0695994,15.809984922409058,-0.26153344854490856,1739137674.0696015,15.809984922409058,-0.054308351647267286,1739137674.0696042,15.809984922409058,2.2516816846852494,1739137674.069606,15.809984922409058,0.0,1739137674.0696082,15.809984922409058,-0.021381639856563606,1739137674.0696106,15.809984922409058,0.013043510867255775,1739137674.0696127,15.809984922409058,2.273063324541813 +1739137674.089747,15.829984903335571,33.62545901566971,1739137674.0897505,15.829984903335571,0.045214625814234743,1739137674.0897543,15.829984903335571,33.412072720250464,1739137674.089758,15.829984903335571,42.22423552384599,1739137674.08976,15.829984903335571,-0.10417647619136569,1739137674.089762,15.829984903335571,-0.017371782354262955,1739137674.089764,15.829984903335571,-0.26153344854490856,1739137674.0897658,15.829984903335571,-0.054308351647267286,1739137674.089768,15.829984903335571,2.2516816846852494,1739137674.08977,15.829984903335571,0.0,1739137674.0897717,15.829984903335571,-0.021381639856563606,1739137674.089774,15.829984903335571,0.013043510867255775,1739137674.0897758,15.829984903335571,2.273063324541813 +1739137674.1095037,15.849984884262085,33.62545901566971,1739137674.109507,15.849984884262085,0.045214625814234743,1739137674.1095114,15.849984884262085,33.412072720250464,1739137674.1095161,15.849984884262085,42.22423552384599,1739137674.1095185,15.849984884262085,-0.10417647619136569,1739137674.1095214,15.849984884262085,-0.017371782354262955,1739137674.109524,15.849984884262085,-0.26153344854490856,1739137674.109526,15.849984884262085,-0.054308351647267286,1739137674.109528,15.849984884262085,2.2516816846852494,1739137674.1095302,15.849984884262085,0.0,1739137674.109532,15.849984884262085,-0.021381639856563606,1739137674.1095345,15.849984884262085,0.013043510867255775,1739137674.1095364,15.849984884262085,2.273063324541813 +1739137674.1296852,15.869984865188599,33.62545901566971,1739137674.1296887,15.869984865188599,0.045214625814234743,1739137674.129693,15.869984865188599,33.412072720250464,1739137674.1296966,15.869984865188599,42.22423552384599,1739137674.1296983,15.869984865188599,-0.10417647619136569,1739137674.1297007,15.869984865188599,-0.017371782354262955,1739137674.1297026,15.869984865188599,-0.26153344854490856,1739137674.129705,15.869984865188599,-0.054308351647267286,1739137674.1297069,15.869984865188599,2.2516816846852494,1739137674.1297088,15.869984865188599,0.0,1739137674.1297104,15.869984865188599,-0.021381639856563606,1739137674.1297123,15.869984865188599,0.013043510867255775,1739137674.1297143,15.869984865188599,2.273063324541813 +1739137674.1496606,15.889984846115112,33.62545901566971,1739137674.1496642,15.889984846115112,0.045214625814234743,1739137674.1496685,15.889984846115112,33.412072720250464,1739137674.1496725,15.889984846115112,42.22423552384599,1739137674.1496747,15.889984846115112,-0.10417647619136569,1739137674.1496775,15.889984846115112,-0.017371782354262955,1739137674.14968,15.889984846115112,-0.26153344854490856,1739137674.1496823,15.889984846115112,-0.054308351647267286,1739137674.1496844,15.889984846115112,2.2516816846852494,1739137674.1496868,15.889984846115112,0.0,1739137674.1496887,15.889984846115112,-0.021381639856563606,1739137674.149691,15.889984846115112,0.013043510867255775,1739137674.1496933,15.889984846115112,2.273063324541813 +1739137674.1695554,15.909984827041626,33.87534145145042,1739137674.1695585,15.909984827041626,0.04838078102987531,1739137674.1695623,15.909984827041626,33.42332059601581,1739137674.169566,15.909984827041626,42.227919419767886,1739137674.169568,15.909984827041626,-0.10426632731141193,1739137674.1695704,15.909984827041626,-0.01827341427039535,1739137674.1695724,15.909984827041626,-0.25471342617794,1739137674.1695743,15.909984827041626,-0.056053973791184826,1739137674.169576,15.909984827041626,2.2578326786349936,1739137674.169578,15.909984827041626,0.0,1739137674.1695795,15.909984827041626,-0.00482608117711936,1739137674.1695817,15.909984827041626,0.012221407465854824,1739137674.1695833,15.909984827041626,2.270542363121481 +1739137674.1917338,15.92998480796814,33.87534145145042,1739137674.1917384,15.92998480796814,0.04838078102987531,1739137674.1917448,15.92998480796814,33.42332059601581,1739137674.191752,15.92998480796814,42.227919419767886,1739137674.191756,15.92998480796814,-0.10426632731141193,1739137674.1917615,15.92998480796814,-0.01827341427039535,1739137674.1917663,15.92998480796814,-0.25471342617794,1739137674.1917708,15.92998480796814,-0.056053973791184826,1739137674.1917756,15.92998480796814,2.2578326786349936,1739137674.1917803,15.92998480796814,0.0,1739137674.191785,15.92998480796814,-0.012709684486487571,1739137674.19179,15.92998480796814,0.012221407465854824,1739137674.1917949,15.92998480796814,2.270542363121481 +1739137674.2097657,15.949984788894653,33.87534145145042,1739137674.2097697,15.949984788894653,0.04838078102987531,1739137674.209774,15.949984788894653,33.42332059601581,1739137674.209778,15.949984788894653,42.227919419767886,1739137674.2097802,15.949984788894653,-0.10426632731141193,1739137674.209783,15.949984788894653,-0.01827341427039535,1739137674.2097857,15.949984788894653,-0.25471342617794,1739137674.2097876,15.949984788894653,-0.056053973791184826,1739137674.2097898,15.949984788894653,2.2578326786349936,1739137674.2097921,15.949984788894653,0.0,1739137674.2097943,15.949984788894653,-0.012709684486487571,1739137674.209797,15.949984788894653,0.012221407465854824,1739137674.209799,15.949984788894653,2.270542363121481 +1739137674.2296422,15.969984769821167,33.87534145145042,1739137674.2296457,15.969984769821167,0.04838078102987531,1739137674.2296503,15.969984769821167,33.42332059601581,1739137674.229654,15.969984769821167,42.227919419767886,1739137674.2296557,15.969984769821167,-0.10426632731141193,1739137674.2296581,15.969984769821167,-0.01827341427039535,1739137674.2296603,15.969984769821167,-0.25471342617794,1739137674.2296622,15.969984769821167,-0.056053973791184826,1739137674.229664,15.969984769821167,2.2578326786349936,1739137674.229666,15.969984769821167,0.0,1739137674.229668,15.969984769821167,-0.012709684486487571,1739137674.2296698,15.969984769821167,0.012221407465854824,1739137674.2296717,15.969984769821167,2.270542363121481 +1739137674.2495966,15.98998475074768,33.87534145145042,1739137674.2496,15.98998475074768,0.04838078102987531,1739137674.2496045,15.98998475074768,33.42332059601581,1739137674.2496085,15.98998475074768,42.227919419767886,1739137674.2496107,15.98998475074768,-0.10426632731141193,1739137674.2496133,15.98998475074768,-0.01827341427039535,1739137674.2496157,15.98998475074768,-0.25471342617794,1739137674.2496176,15.98998475074768,-0.056053973791184826,1739137674.2496197,15.98998475074768,2.2578326786349936,1739137674.249622,15.98998475074768,0.0,1739137674.249624,15.98998475074768,-0.012709684486487571,1739137674.2496264,15.98998475074768,0.012221407465854824,1739137674.2496288,15.98998475074768,2.270542363121481 +1739137674.269777,16.009984731674194,34.12501883511332,1739137674.2697804,16.009984731674194,0.05133903768832848,1739137674.2697847,16.009984731674194,33.4345590365373,1739137674.269789,16.009984731674194,42.235200104870536,1739137674.269791,16.009984731674194,-0.10444390499684225,1739137674.2697937,16.009984731674194,-0.01920595638323971,1739137674.2697964,16.009984731674194,-0.24822124134819162,1739137674.2697985,16.009984731674194,-0.057936843739183175,1739137674.2698007,16.009984731674194,2.263703605189454,1739137674.269803,16.009984731674194,0.0,1739137674.2698052,16.009984731674194,0.0010156479973974569,1739137674.2698076,16.009984731674194,0.011399304064453872,1739137674.26981,16.009984731674194,2.269223833068386 +1739137674.2896447,16.029984712600708,34.12501883511332,1739137674.2896485,16.029984712600708,0.05133903768832848,1739137674.289653,16.029984712600708,33.4345590365373,1739137674.2896569,16.029984712600708,42.235200104870536,1739137674.2896585,16.029984712600708,-0.10444390499684225,1739137674.289661,16.029984712600708,-0.01920595638323971,1739137674.2896628,16.029984712600708,-0.24822124134819162,1739137674.2896645,16.029984712600708,-0.057936843739183175,1739137674.2896664,16.029984712600708,2.263703605189454,1739137674.2896686,16.029984712600708,0.0,1739137674.2896702,16.029984712600708,-0.005520227878931916,1739137674.2896724,16.029984712600708,0.011399304064453872,1739137674.2896743,16.029984712600708,2.269223833068386 +1739137674.309522,16.04998469352722,34.12501883511332,1739137674.3095253,16.04998469352722,0.05133903768832848,1739137674.3095293,16.04998469352722,33.4345590365373,1739137674.3095338,16.04998469352722,42.235200104870536,1739137674.309536,16.04998469352722,-0.10444390499684225,1739137674.3095388,16.04998469352722,-0.01920595638323971,1739137674.3095412,16.04998469352722,-0.24822124134819162,1739137674.3095434,16.04998469352722,-0.057936843739183175,1739137674.3095458,16.04998469352722,2.263703605189454,1739137674.3095477,16.04998469352722,0.0,1739137674.30955,16.04998469352722,-0.005520227878931916,1739137674.3095524,16.04998469352722,0.011399304064453872,1739137674.3095543,16.04998469352722,2.269223833068386 +1739137674.3297784,16.069984674453735,34.12501883511332,1739137674.3297827,16.069984674453735,0.05133903768832848,1739137674.3297875,16.069984674453735,33.4345590365373,1739137674.3297913,16.069984674453735,42.235200104870536,1739137674.3297935,16.069984674453735,-0.10444390499684225,1739137674.329796,16.069984674453735,-0.01920595638323971,1739137674.3297982,16.069984674453735,-0.24822124134819162,1739137674.3298001,16.069984674453735,-0.057936843739183175,1739137674.3298023,16.069984674453735,2.263703605189454,1739137674.3298042,16.069984674453735,0.0,1739137674.3298063,16.069984674453735,-0.005520227878931916,1739137674.3298085,16.069984674453735,0.011399304064453872,1739137674.3298104,16.069984674453735,2.269223833068386 +1739137674.349653,16.08998465538025,34.12501883511332,1739137674.3496566,16.08998465538025,0.05133903768832848,1739137674.3496606,16.08998465538025,33.4345590365373,1739137674.349665,16.08998465538025,42.235200104870536,1739137674.3496675,16.08998465538025,-0.10444390499684225,1739137674.3496704,16.08998465538025,-0.01920595638323971,1739137674.3496728,16.08998465538025,-0.24822124134819162,1739137674.3496747,16.08998465538025,-0.057936843739183175,1739137674.3496768,16.08998465538025,2.263703605189454,1739137674.349679,16.08998465538025,0.0,1739137674.3496811,16.08998465538025,-0.005520227878931916,1739137674.3496835,16.08998465538025,0.011399304064453872,1739137674.3496857,16.08998465538025,2.269223833068386 +1739137674.3695323,16.109984636306763,34.12501883511332,1739137674.3695354,16.109984636306763,0.05133903768832848,1739137674.3695393,16.109984636306763,33.4345590365373,1739137674.369543,16.109984636306763,42.235200104870536,1739137674.3695447,16.109984636306763,-0.10444390499684225,1739137674.3695474,16.109984636306763,-0.01920595638323971,1739137674.3695493,16.109984636306763,-0.24822124134819162,1739137674.3695512,16.109984636306763,-0.057936843739183175,1739137674.3695529,16.109984636306763,2.263703605189454,1739137674.369555,16.109984636306763,0.0,1739137674.3695567,16.109984636306763,-0.005520227878931916,1739137674.3695588,16.109984636306763,0.011399304064453872,1739137674.3695605,16.109984636306763,2.269223833068386 +1739137674.3921595,16.129984617233276,34.37460037211374,1739137674.3921654,16.129984617233276,0.0540909444055,1739137674.3921733,16.129984617233276,33.44579295760904,1739137674.3921802,16.129984617233276,42.2450067107478,1739137674.3921843,16.129984617233276,-0.10468309050604395,1739137674.3921905,16.129984617233276,-0.020170813865339688,1739137674.3921952,16.129984617233276,-0.24201046831400133,1739137674.392198,16.129984617233276,-0.05997862120519272,1739137674.392201,16.129984617233276,2.2693343362554166,1739137674.3922052,16.129984617233276,0.0,1739137674.3922107,16.129984617233276,0.006135790460518344,1739137674.392214,16.129984617233276,0.01057720066305292,1739137674.3922188,16.129984617233276,2.268749033491157 +1739137674.4094973,16.14998459815979,34.37460037211374,1739137674.4095008,16.14998459815979,0.0540909444055,1739137674.4095051,16.14998459815979,33.44579295760904,1739137674.4095094,16.14998459815979,42.2450067107478,1739137674.4095113,16.14998459815979,-0.10468309050604395,1739137674.4095142,16.14998459815979,-0.020170813865339688,1739137674.4095166,16.14998459815979,-0.24201046831400133,1739137674.409519,16.14998459815979,-0.05997862120519272,1739137674.4095209,16.14998459815979,2.2693343362554166,1739137674.4095232,16.14998459815979,0.0,1739137674.4095252,16.14998459815979,0.0005853027642594988,1739137674.4095275,16.14998459815979,0.01057720066305292,1739137674.4095297,16.14998459815979,2.268749033491157 +1739137674.4295647,16.169984579086304,34.37460037211374,1739137674.4295688,16.169984579086304,0.0540909444055,1739137674.429573,16.169984579086304,33.44579295760904,1739137674.4295769,16.169984579086304,42.2450067107478,1739137674.4295788,16.169984579086304,-0.10468309050604395,1739137674.4295814,16.169984579086304,-0.020170813865339688,1739137674.4295835,16.169984579086304,-0.24201046831400133,1739137674.4295855,16.169984579086304,-0.05997862120519272,1739137674.4295871,16.169984579086304,2.2693343362554166,1739137674.429589,16.169984579086304,0.0,1739137674.4295907,16.169984579086304,0.0005853027642594988,1739137674.4295928,16.169984579086304,0.01057720066305292,1739137674.429595,16.169984579086304,2.268749033491157 +1739137674.4495282,16.189984560012817,34.37460037211374,1739137674.4495316,16.189984560012817,0.0540909444055,1739137674.4495354,16.189984560012817,33.44579295760904,1739137674.4495392,16.189984560012817,42.2450067107478,1739137674.449541,16.189984560012817,-0.10468309050604395,1739137674.4495435,16.189984560012817,-0.020170813865339688,1739137674.4495451,16.189984560012817,-0.24201046831400133,1739137674.449547,16.189984560012817,-0.05997862120519272,1739137674.4495485,16.189984560012817,2.2693343362554166,1739137674.4495509,16.189984560012817,0.0,1739137674.4495523,16.189984560012817,0.0005853027642594988,1739137674.4495544,16.189984560012817,0.01057720066305292,1739137674.449556,16.189984560012817,2.268749033491157 +1739137674.46952,16.20998454093933,34.37460037211374,1739137674.4695237,16.20998454093933,0.0540909444055,1739137674.4695277,16.20998454093933,33.44579295760904,1739137674.4695323,16.20998454093933,42.2450067107478,1739137674.4695342,16.20998454093933,-0.10468309050604395,1739137674.469537,16.20998454093933,-0.020170813865339688,1739137674.4695394,16.20998454093933,-0.24201046831400133,1739137674.4695415,16.20998454093933,-0.05997862120519272,1739137674.4695437,16.20998454093933,2.2693343362554166,1739137674.469546,16.20998454093933,0.0,1739137674.4695482,16.20998454093933,0.0005853027642594988,1739137674.4695508,16.20998454093933,0.01057720066305292,1739137674.469553,16.20998454093933,2.268749033491157 +1739137674.492051,16.229984521865845,34.62415640568322,1739137674.4920573,16.229984521865845,0.056631313000822026,1739137674.4920642,16.229984521865845,33.95348698399708,1739137674.4920719,16.229984521865845,42.75296664030313,1739137674.492076,16.229984521865845,-0.11326699643864487,1739137674.4920814,16.229984521865845,-0.02089771706561598,1739137674.4920862,16.229984521865845,-0.2486429597556944,1739137674.492091,16.229984521865845,-0.0577657022595236,1739137674.4920955,16.229984521865845,2.2633217792031934,1739137674.4921007,16.229984521865845,0.0,1739137674.4921052,16.229984521865845,-0.011111168598698543,1739137674.4921103,16.229984521865845,0.00968823892661494,1739137674.492115,16.229984521865845,2.2688631967514827 +1739137674.5095859,16.24998450279236,34.62415640568322,1739137674.5095894,16.24998450279236,0.056631313000822026,1739137674.5095935,16.24998450279236,33.95348698399708,1739137674.509598,16.24998450279236,42.75296664030313,1739137674.5096002,16.24998450279236,-0.11326699643864487,1739137674.509603,16.24998450279236,-0.02089771706561598,1739137674.5096054,16.24998450279236,-0.2486429597556944,1739137674.5096078,16.24998450279236,-0.0577657022595236,1739137674.5096097,16.24998450279236,2.2633217792031934,1739137674.5096123,16.24998450279236,0.0,1739137674.5096142,16.24998450279236,-0.005541417548289296,1739137674.5096166,16.24998450279236,0.00968823892661494,1739137674.5096188,16.24998450279236,2.2688631967514827 +1739137674.5299156,16.269984483718872,34.62415640568322,1739137674.52992,16.269984483718872,0.056631313000822026,1739137674.5299244,16.269984483718872,33.95348698399708,1739137674.529929,16.269984483718872,42.75296664030313,1739137674.5299315,16.269984483718872,-0.11326699643864487,1739137674.5299346,16.269984483718872,-0.02089771706561598,1739137674.5299373,16.269984483718872,-0.2486429597556944,1739137674.5299394,16.269984483718872,-0.0577657022595236,1739137674.5299418,16.269984483718872,2.2633217792031934,1739137674.5299444,16.269984483718872,0.0,1739137674.5299466,16.269984483718872,-0.005541417548289296,1739137674.5299492,16.269984483718872,0.00968823892661494,1739137674.5299516,16.269984483718872,2.2688631967514827 +1739137674.5495622,16.289984464645386,34.62415640568322,1739137674.549565,16.289984464645386,0.056631313000822026,1739137674.5495694,16.289984464645386,33.95348698399708,1739137674.5495737,16.289984464645386,42.75296664030313,1739137674.549576,16.289984464645386,-0.11326699643864487,1739137674.5495784,16.289984464645386,-0.02089771706561598,1739137674.549581,16.289984464645386,-0.2486429597556944,1739137674.5495834,16.289984464645386,-0.0577657022595236,1739137674.5495856,16.289984464645386,2.2633217792031934,1739137674.5495882,16.289984464645386,0.0,1739137674.5495906,16.289984464645386,-0.005541417548289296,1739137674.5495925,16.289984464645386,0.00968823892661494,1739137674.5495946,16.289984464645386,2.2688631967514827 +1739137674.569508,16.3099844455719,34.62415640568322,1739137674.5695114,16.3099844455719,0.056631313000822026,1739137674.5695152,16.3099844455719,33.95348698399708,1739137674.5695195,16.3099844455719,42.75296664030313,1739137674.5695217,16.3099844455719,-0.11326699643864487,1739137674.5695243,16.3099844455719,-0.02089771706561598,1739137674.5695264,16.3099844455719,-0.2486429597556944,1739137674.5695288,16.3099844455719,-0.0577657022595236,1739137674.5695312,16.3099844455719,2.2633217792031934,1739137674.5695333,16.3099844455719,0.0,1739137674.5695357,16.3099844455719,-0.005541417548289296,1739137674.569538,16.3099844455719,0.00968823892661494,1739137674.56954,16.3099844455719,2.2688631967514827 +1739137674.5920422,16.329984426498413,34.62415640568322,1739137674.5920472,16.329984426498413,0.056631313000822026,1739137674.5920537,16.329984426498413,33.95348698399708,1739137674.592061,16.329984426498413,42.75296664030313,1739137674.592065,16.329984426498413,-0.11326699643864487,1739137674.59207,16.329984426498413,-0.02089771706561598,1739137674.5920749,16.329984426498413,-0.2486429597556944,1739137674.5920796,16.329984426498413,-0.0577657022595236,1739137674.5920842,16.329984426498413,2.2633217792031934,1739137674.5920892,16.329984426498413,0.0,1739137674.5920937,16.329984426498413,-0.005541417548289296,1739137674.5920987,16.329984426498413,0.00968823892661494,1739137674.5921035,16.329984426498413,2.2688631967514827 +1739137674.6113284,16.349984407424927,34.87367967982288,1739137674.6113312,16.349984407424927,0.05894631526641536,1739137674.6113355,16.349984407424927,34.192639356466074,1739137674.611339,16.349984407424927,42.98991394069671,1739137674.6113408,16.349984407424927,-0.11769470619939297,1739137674.6113431,16.349984407424927,-0.021760478318304737,1739137674.6113448,16.349984407424927,-0.24792969802617112,1739137674.6113465,16.349984407424927,-0.05777650389431927,1739137674.6113482,16.349984407424927,2.2639676076504363,1739137674.6113503,16.349984407424927,0.0,1739137674.611352,16.349984407424927,-0.002939562627369923,1739137674.6113544,16.349984407424927,0.008784419782390952,1739137674.6113563,16.349984407424927,2.2681461494305015 +1739137674.6317968,16.36998438835144,34.87367967982288,1739137674.6318002,16.36998438835144,0.05894631526641536,1739137674.6318169,16.36998438835144,34.192639356466074,1739137674.63182,16.36998438835144,42.98991394069671,1739137674.6318216,16.36998438835144,-0.11769470619939297,1739137674.6318238,16.36998438835144,-0.021760478318304737,1739137674.6318257,16.36998438835144,-0.24792969802617112,1739137674.6318269,16.36998438835144,-0.05777650389431927,1739137674.6318285,16.36998438835144,2.2639676076504363,1739137674.6318305,16.36998438835144,0.0,1739137674.6318321,16.36998438835144,-0.00417854178006527,1739137674.6318338,16.36998438835144,0.008784419782390952,1739137674.6318355,16.36998438835144,2.2681461494305015 +1739137674.6492457,16.389984369277954,34.87367967982288,1739137674.6492486,16.389984369277954,0.05894631526641536,1739137674.649252,16.389984369277954,34.192639356466074,1739137674.6492553,16.389984369277954,42.98991394069671,1739137674.6492572,16.389984369277954,-0.11769470619939297,1739137674.649259,16.389984369277954,-0.021760478318304737,1739137674.6492608,16.389984369277954,-0.24792969802617112,1739137674.6492624,16.389984369277954,-0.05777650389431927,1739137674.6492639,16.389984369277954,2.2639676076504363,1739137674.6492658,16.389984369277954,0.0,1739137674.6492672,16.389984369277954,-0.00417854178006527,1739137674.649269,16.389984369277954,0.008784419782390952,1739137674.6492705,16.389984369277954,2.2681461494305015 +1739137674.669308,16.409984350204468,34.87367967982288,1739137674.6693106,16.409984350204468,0.05894631526641536,1739137674.669314,16.409984350204468,34.192639356466074,1739137674.6693168,16.409984350204468,42.98991394069671,1739137674.6693187,16.409984350204468,-0.11769470619939297,1739137674.6693208,16.409984350204468,-0.021760478318304737,1739137674.6693225,16.409984350204468,-0.24792969802617112,1739137674.669324,16.409984350204468,-0.05777650389431927,1739137674.6693256,16.409984350204468,2.2639676076504363,1739137674.6693273,16.409984350204468,0.0,1739137674.669329,16.409984350204468,-0.00417854178006527,1739137674.6693306,16.409984350204468,0.008784419782390952,1739137674.6693323,16.409984350204468,2.2681461494305015 +1739137674.6892984,16.42998433113098,34.87367967982288,1739137674.6893015,16.42998433113098,0.05894631526641536,1739137674.6893048,16.42998433113098,34.192639356466074,1739137674.6893086,16.42998433113098,42.98991394069671,1739137674.6893108,16.42998433113098,-0.11769470619939297,1739137674.689313,16.42998433113098,-0.021760478318304737,1739137674.689315,16.42998433113098,-0.24792969802617112,1739137674.6893167,16.42998433113098,-0.05777650389431927,1739137674.6893187,16.42998433113098,2.2639676076504363,1739137674.6893208,16.42998433113098,0.0,1739137674.6893225,16.42998433113098,-0.00417854178006527,1739137674.6893244,16.42998433113098,0.008784419782390952,1739137674.6893263,16.42998433113098,2.2681461494305015 +1739137674.709394,16.449984312057495,35.12314348849318,1739137674.709397,16.449984312057495,0.06103527611153048,1739137674.7094007,16.449984312057495,34.32899212724217,1739137674.7094045,16.449984312057495,43.12487265220016,1739137674.7094061,16.449984312057495,-0.11993159092044464,1739137674.7094085,16.449984312057495,-0.022612115334615383,1739137674.709411,16.449984312057495,-0.24401902695055672,1739137674.7094128,16.449984312057495,-0.05850191453640309,1739137674.7094147,16.449984312057495,2.2675118320426386,1739137674.7094169,16.449984312057495,0.0,1739137674.7094185,16.449984312057495,0.003463040965198225,1739137674.7094204,16.449984312057495,0.007880600638166965,1739137674.7094223,16.449984312057495,2.2676876418215213 +1739137674.729407,16.46998429298401,35.12314348849318,1739137674.7294097,16.46998429298401,0.06103527611153048,1739137674.7294133,16.46998429298401,34.32899212724217,1739137674.7294173,16.46998429298401,43.12487265220016,1739137674.729419,16.46998429298401,-0.11993159092044464,1739137674.7294214,16.46998429298401,-0.022612115334615383,1739137674.7294233,16.46998429298401,-0.24401902695055672,1739137674.7294252,16.46998429298401,-0.05850191453640309,1739137674.7294269,16.46998429298401,2.2675118320426386,1739137674.729429,16.46998429298401,0.0,1739137674.7294307,16.46998429298401,-0.0001758097788826518,1739137674.7294328,16.46998429298401,0.007880600638166965,1739137674.7294347,16.46998429298401,2.2676876418215213 +1739137674.749301,16.489984273910522,35.12314348849318,1739137674.7493036,16.489984273910522,0.06103527611153048,1739137674.7493067,16.489984273910522,34.32899212724217,1739137674.74931,16.489984273910522,43.12487265220016,1739137674.7493112,16.489984273910522,-0.11993159092044464,1739137674.7493134,16.489984273910522,-0.022612115334615383,1739137674.7493148,16.489984273910522,-0.24401902695055672,1739137674.7493165,16.489984273910522,-0.05850191453640309,1739137674.749318,16.489984273910522,2.2675118320426386,1739137674.7493198,16.489984273910522,0.0,1739137674.7493212,16.489984273910522,-0.0001758097788826518,1739137674.749323,16.489984273910522,0.007880600638166965,1739137674.7493248,16.489984273910522,2.2676876418215213 +1739137674.769304,16.509984254837036,35.12314348849318,1739137674.769307,16.509984254837036,0.06103527611153048,1739137674.7693102,16.509984254837036,34.32899212724217,1739137674.7693133,16.509984254837036,43.12487265220016,1739137674.7693148,16.509984254837036,-0.11993159092044464,1739137674.769317,16.509984254837036,-0.022612115334615383,1739137674.7693188,16.509984254837036,-0.24401902695055672,1739137674.7693205,16.509984254837036,-0.05850191453640309,1739137674.769322,16.509984254837036,2.2675118320426386,1739137674.7693238,16.509984254837036,0.0,1739137674.7693253,16.509984254837036,-0.0001758097788826518,1739137674.769327,16.509984254837036,0.007880600638166965,1739137674.7693284,16.509984254837036,2.2676876418215213 +1739137674.7914045,16.52998423576355,35.12314348849318,1739137674.7914095,16.52998423576355,0.06103527611153048,1739137674.791415,16.52998423576355,34.32899212724217,1739137674.7914214,16.52998423576355,43.12487265220016,1739137674.791425,16.52998423576355,-0.11993159092044464,1739137674.7914295,16.52998423576355,-0.022612115334615383,1739137674.7914336,16.52998423576355,-0.24401902695055672,1739137674.7914376,16.52998423576355,-0.05850191453640309,1739137674.7914417,16.52998423576355,2.2675118320426386,1739137674.791446,16.52998423576355,0.0,1739137674.79145,16.52998423576355,-0.0001758097788826518,1739137674.7914546,16.52998423576355,0.007880600638166965,1739137674.7914586,16.52998423576355,2.2676876418215213 +1739137674.8092325,16.549984216690063,35.12314348849318,1739137674.809235,16.549984216690063,0.06103527611153048,1739137674.8092384,16.549984216690063,34.32899212724217,1739137674.8092418,16.549984216690063,43.12487265220016,1739137674.8092432,16.549984216690063,-0.11993159092044464,1739137674.809245,16.549984216690063,-0.022612115334615383,1739137674.8092468,16.549984216690063,-0.24401902695055672,1739137674.8092484,16.549984216690063,-0.05850191453640309,1739137674.80925,16.549984216690063,2.2675118320426386,1739137674.8092515,16.549984216690063,0.0,1739137674.8092535,16.549984216690063,-0.0001758097788826518,1739137674.8092551,16.549984216690063,0.007880600638166965,1739137674.8092568,16.549984216690063,2.2676876418215213 +1739137674.8293283,16.569984197616577,35.372588082903846,1739137674.8293312,16.569984197616577,0.06289860519790036,1739137674.8293347,16.569984197616577,34.5728165067387,1739137674.8293383,16.569984197616577,43.36883263917479,1739137674.8293402,16.569984197616577,-0.12299581597936972,1739137674.8293426,16.569984197616577,-0.023243529066052416,1739137674.8293447,16.569984197616577,-0.24167749540283812,1739137674.8293467,16.569984197616577,-0.05801849889801659,1739137674.8293483,16.569984197616577,2.2696366071287106,1739137674.8293505,16.569984197616577,0.0,1739137674.8293521,16.569984197616577,0.0037796409004067907,1739137674.829354,16.569984197616577,0.006976781493942978,1739137674.8293557,16.569984197616577,2.2677405151117376 +1739137674.849379,16.58998417854309,35.372588082903846,1739137674.849382,16.58998417854309,0.06289860519790036,1739137674.8493855,16.58998417854309,34.5728165067387,1739137674.8493888,16.58998417854309,43.36883263917479,1739137674.8493905,16.58998417854309,-0.12299581597936972,1739137674.849393,16.58998417854309,-0.023243529066052416,1739137674.849395,16.58998417854309,-0.24167749540283812,1739137674.849397,16.58998417854309,-0.05801849889801659,1739137674.8493989,16.58998417854309,2.2696366071287106,1739137674.8494005,16.58998417854309,0.0,1739137674.8494024,16.58998417854309,0.00189609201697305,1739137674.8494043,16.58998417854309,0.006976781493942978,1739137674.8494062,16.58998417854309,2.2677405151117376 +1739137674.8691819,16.609984159469604,35.372588082903846,1739137674.8691847,16.609984159469604,0.06289860519790036,1739137674.869188,16.609984159469604,34.5728165067387,1739137674.8691912,16.609984159469604,43.36883263917479,1739137674.869193,16.609984159469604,-0.12299581597936972,1739137674.869195,16.609984159469604,-0.023243529066052416,1739137674.8691967,16.609984159469604,-0.24167749540283812,1739137674.869198,16.609984159469604,-0.05801849889801659,1739137674.8691995,16.609984159469604,2.2696366071287106,1739137674.8692014,16.609984159469604,0.0,1739137674.8692029,16.609984159469604,0.00189609201697305,1739137674.8692045,16.609984159469604,0.006976781493942978,1739137674.869206,16.609984159469604,2.2677405151117376 +1739137674.8893,16.629984140396118,35.372588082903846,1739137674.889303,16.629984140396118,0.06289860519790036,1739137674.8893065,16.629984140396118,34.5728165067387,1739137674.88931,16.629984140396118,43.36883263917479,1739137674.8893123,16.629984140396118,-0.12299581597936972,1739137674.8893147,16.629984140396118,-0.023243529066052416,1739137674.8893166,16.629984140396118,-0.24167749540283812,1739137674.8893187,16.629984140396118,-0.05801849889801659,1739137674.8893204,16.629984140396118,2.2696366071287106,1739137674.8893225,16.629984140396118,0.0,1739137674.8893244,16.629984140396118,0.00189609201697305,1739137674.8893266,16.629984140396118,0.006976781493942978,1739137674.8893285,16.629984140396118,2.2677405151117376 +1739137674.9091866,16.649984121322632,35.372588082903846,1739137674.9091895,16.649984121322632,0.06289860519790036,1739137674.9091926,16.649984121322632,34.5728165067387,1739137674.9091954,16.649984121322632,43.36883263917479,1739137674.9091973,16.649984121322632,-0.12299581597936972,1739137674.9091995,16.649984121322632,-0.023243529066052416,1739137674.909201,16.649984121322632,-0.24167749540283812,1739137674.9092023,16.649984121322632,-0.05801849889801659,1739137674.909204,16.649984121322632,2.2696366071287106,1739137674.9092057,16.649984121322632,0.0,1739137674.909207,16.649984121322632,0.00189609201697305,1739137674.9092088,16.649984121322632,0.006976781493942978,1739137674.9092104,16.649984121322632,2.2677405151117376 +1739137674.9301965,16.669984102249146,35.62204567502217,1739137674.9302003,16.669984102249146,0.06453655401814284,1739137674.930205,16.669984102249146,35.24631519169364,1739137674.9302104,16.669984102249146,44.04292023718529,1739137674.9302125,16.669984102249146,-0.1329881344745637,1739137674.9302154,16.669984102249146,-0.023452252175464722,1739137674.930218,16.669984102249146,-0.24866038588502076,1739137674.9302201,16.669984102249146,-0.05382672151424647,1739137674.930222,16.669984102249146,2.263306002882965,1739137674.930225,16.669984102249146,0.0,1739137674.9302273,16.669984102249146,-0.010617961215131633,1739137674.9302294,16.669984102249146,0.006072962349718991,1739137674.9302316,16.669984102249146,2.267964888153609 +1739137674.9540615,16.68998408317566,35.62204567502217,1739137674.954069,16.68998408317566,0.06453655401814284,1739137674.9540784,16.68998408317566,35.24631519169364,1739137674.9540896,16.68998408317566,44.04292023718529,1739137674.9540958,16.68998408317566,-0.1329881344745637,1739137674.9541037,16.68998408317566,-0.023452252175464722,1739137674.9541113,16.68998408317566,-0.24866038588502076,1739137674.9541185,16.68998408317566,-0.05382672151424647,1739137674.9541254,16.68998408317566,2.263306002882965,1739137674.9541328,16.68998408317566,0.0,1739137674.9541397,16.68998408317566,-0.004658885270643953,1739137674.954147,16.68998408317566,0.006072962349718991,1739137674.9541543,16.68998408317566,2.267964888153609 +1739137674.9748285,16.709984064102173,35.62204567502217,1739137674.9748359,16.709984064102173,0.06453655401814284,1739137674.9748452,16.709984064102173,35.24631519169364,1739137674.9748564,16.709984064102173,44.04292023718529,1739137674.9748626,16.709984064102173,-0.1329881344745637,1739137674.9748704,16.709984064102173,-0.023452252175464722,1739137674.9748776,16.709984064102173,-0.24866038588502076,1739137674.9748845,16.709984064102173,-0.05382672151424647,1739137674.9748917,16.709984064102173,2.263306002882965,1739137674.974899,16.709984064102173,0.0,1739137674.974906,16.709984064102173,-0.004658885270643953,1739137674.9749134,16.709984064102173,0.006072962349718991,1739137674.9749205,16.709984064102173,2.267964888153609 +1739137674.9917555,16.729984045028687,35.62204567502217,1739137674.9917607,16.729984045028687,0.06453655401814284,1739137674.991767,16.729984045028687,35.24631519169364,1739137674.9917877,16.729984045028687,44.04292023718529,1739137674.9917912,16.729984045028687,-0.1329881344745637,1739137674.991796,16.729984045028687,-0.023452252175464722,1739137674.9918,16.729984045028687,-0.24866038588502076,1739137674.9918041,16.729984045028687,-0.05382672151424647,1739137674.9918082,16.729984045028687,2.263306002882965,1739137674.9918125,16.729984045028687,0.0,1739137674.9918165,16.729984045028687,-0.004658885270643953,1739137674.9918208,16.729984045028687,0.006072962349718991,1739137674.9918246,16.729984045028687,2.267964888153609 +1739137675.0097537,16.7499840259552,35.62204567502217,1739137675.0097566,16.7499840259552,0.06453655401814284,1739137675.009761,16.7499840259552,35.24631519169364,1739137675.0097656,16.7499840259552,44.04292023718529,1739137675.0097685,16.7499840259552,-0.1329881344745637,1739137675.009772,16.7499840259552,-0.023452252175464722,1739137675.0097752,16.7499840259552,-0.24866038588502076,1739137675.009778,16.7499840259552,-0.05382672151424647,1739137675.009781,16.7499840259552,2.263306002882965,1739137675.009784,16.7499840259552,0.0,1739137675.0097873,16.7499840259552,-0.004658885270643953,1739137675.0097904,16.7499840259552,0.006072962349718991,1739137675.0097935,16.7499840259552,2.267964888153609 +1739137675.0295434,16.769984006881714,35.62204567502217,1739137675.0295458,16.769984006881714,0.06453655401814284,1739137675.0295484,16.769984006881714,35.24631519169364,1739137675.0295508,16.769984006881714,44.04292023718529,1739137675.0295522,16.769984006881714,-0.1329881344745637,1739137675.0295537,16.769984006881714,-0.023452252175464722,1739137675.0295548,16.769984006881714,-0.24866038588502076,1739137675.0295563,16.769984006881714,-0.05382672151424647,1739137675.0295575,16.769984006881714,2.263306002882965,1739137675.029559,16.769984006881714,0.0,1739137675.0295599,16.769984006881714,-0.004658885270643953,1739137675.0295613,16.769984006881714,0.006072962349718991,1739137675.0295625,16.769984006881714,2.267964888153609 +1739137675.0506766,16.789983987808228,35.87148097876314,1739137675.05068,16.789983987808228,0.06594891046014872,1739137675.050684,16.789983987808228,35.284230770218706,1739137675.0506887,16.789983987808228,44.078949198613095,1739137675.0506916,16.789983987808228,-0.13338405712761647,1739137675.0506952,16.789983987808228,-0.02428200561819594,1739137675.0506985,16.789983987808228,-0.2417556941487842,1739137675.0507016,16.789983987808228,-0.05508642673345883,1739137675.050705,16.789983987808228,2.2695656151444408,1739137675.0507083,16.789983987808228,0.0,1739137675.0507116,16.789983987808228,0.008490479776997285,1739137675.050715,16.789983987808228,0.005169143205495004,1739137675.0507183,16.789983987808228,2.2673367408990277 +1739137675.069787,16.80998396873474,35.87148097876314,1739137675.0697904,16.80998396873474,0.06594891046014872,1739137675.0697947,16.80998396873474,35.284230770218706,1739137675.0697994,16.80998396873474,44.078949198613095,1739137675.0698023,16.80998396873474,-0.13338405712761647,1739137675.0698059,16.80998396873474,-0.02428200561819594,1739137675.0698092,16.80998396873474,-0.2417556941487842,1739137675.0698125,16.80998396873474,-0.05508642673345883,1739137675.0698156,16.80998396873474,2.2695656151444408,1739137675.069819,16.80998396873474,0.0,1739137675.0698223,16.80998396873474,0.0022288742454130706,1739137675.069826,16.80998396873474,0.005169143205495004,1739137675.0698287,16.80998396873474,2.2673367408990277 +1739137675.0904334,16.829983949661255,35.87148097876314,1739137675.0904367,16.829983949661255,0.06594891046014872,1739137675.090441,16.829983949661255,35.284230770218706,1739137675.090446,16.829983949661255,44.078949198613095,1739137675.0904489,16.829983949661255,-0.13338405712761647,1739137675.0904522,16.829983949661255,-0.02428200561819594,1739137675.0904555,16.829983949661255,-0.2417556941487842,1739137675.0904589,16.829983949661255,-0.05508642673345883,1739137675.090462,16.829983949661255,2.2695656151444408,1739137675.0904653,16.829983949661255,0.0,1739137675.0904756,16.829983949661255,0.0022288742454130706,1739137675.0904799,16.829983949661255,0.005169143205495004,1739137675.0905044,16.829983949661255,2.2673367408990277 +1739137675.1104503,16.84998393058777,35.87148097876314,1739137675.1104538,16.84998393058777,0.06594891046014872,1739137675.110458,16.84998393058777,35.284230770218706,1739137675.1104627,16.84998393058777,44.078949198613095,1739137675.1104655,16.84998393058777,-0.13338405712761647,1739137675.1106374,16.84998393058777,-0.02428200561819594,1739137675.1106405,16.84998393058777,-0.2417556941487842,1739137675.1106439,16.84998393058777,-0.05508642673345883,1739137675.110647,16.84998393058777,2.2695656151444408,1739137675.1106544,16.84998393058777,0.0,1739137675.1106746,16.84998393058777,0.0022288742454130706,1739137675.1106882,16.84998393058777,0.005169143205495004,1739137675.1106918,16.84998393058777,2.2673367408990277 +1739137675.129115,16.869983911514282,35.87148097876314,1739137675.1291182,16.869983911514282,0.06594891046014872,1739137675.1291208,16.869983911514282,35.284230770218706,1739137675.1291237,16.869983911514282,44.078949198613095,1739137675.1291249,16.869983911514282,-0.13338405712761647,1739137675.129126,16.869983911514282,-0.02428200561819594,1739137675.1291277,16.869983911514282,-0.2417556941487842,1739137675.129129,16.869983911514282,-0.05508642673345883,1739137675.12913,16.869983911514282,2.2695656151444408,1739137675.1291316,16.869983911514282,0.0,1739137675.1291325,16.869983911514282,0.0022288742454130706,1739137675.129134,16.869983911514282,0.005169143205495004,1739137675.1291351,16.869983911514282,2.2673367408990277 +1739137675.1489718,16.889983892440796,36.12090121996201,1739137675.148974,16.889983892440796,0.0671357370194503,1739137675.1489763,16.889983892440796,35.322143833707486,1739137675.1489787,16.889983892440796,44.11776172178957,1739137675.1489801,16.889983892440796,-0.13381056837131397,1739137675.1489818,16.889983892440796,-0.02512286256106557,1739137675.148983,16.889983892440796,-0.2350535755749796,1739137675.1489844,16.889983892440796,-0.056414884451469534,1739137675.1489856,16.889983892440796,2.275658137202097,1739137675.1489868,16.889983892440796,0.0,1739137675.1489882,16.889983892440796,0.013286183049926667,1739137675.1489894,16.889983892440796,0.004265324061271017,1739137675.1489906,16.889983892440796,2.2676373419274682 +1739137675.1689348,16.90998387336731,36.12090121996201,1739137675.1689372,16.90998387336731,0.0671357370194503,1739137675.16894,16.90998387336731,35.322143833707486,1739137675.1689427,16.90998387336731,44.11776172178957,1739137675.1689441,16.90998387336731,-0.13381056837131397,1739137675.1689456,16.90998387336731,-0.02512286256106557,1739137675.1689472,16.90998387336731,-0.2350535755749796,1739137675.1689484,16.90998387336731,-0.056414884451469534,1739137675.1689498,16.90998387336731,2.275658137202097,1739137675.1689513,16.90998387336731,0.0,1739137675.1689525,16.90998387336731,0.008020795274628956,1739137675.1689541,16.90998387336731,0.004265324061271017,1739137675.1689556,16.90998387336731,2.2676373419274682 +1739137675.188979,16.929983854293823,36.12090121996201,1739137675.188981,16.929983854293823,0.0671357370194503,1739137675.188984,16.929983854293823,35.322143833707486,1739137675.1889863,16.929983854293823,44.11776172178957,1739137675.1889877,16.929983854293823,-0.13381056837131397,1739137675.1889894,16.929983854293823,-0.02512286256106557,1739137675.1889908,16.929983854293823,-0.2350535755749796,1739137675.1889925,16.929983854293823,-0.056414884451469534,1739137675.1889937,16.929983854293823,2.275658137202097,1739137675.1889954,16.929983854293823,0.0,1739137675.1889966,16.929983854293823,0.008020795274628956,1739137675.1889982,16.929983854293823,0.004265324061271017,1739137675.1889994,16.929983854293823,2.2676373419274682 +1739137675.20895,16.949983835220337,36.12090121996201,1739137675.2089524,16.949983835220337,0.0671357370194503,1739137675.208955,16.949983835220337,35.322143833707486,1739137675.2089577,16.949983835220337,44.11776172178957,1739137675.2089589,16.949983835220337,-0.13381056837131397,1739137675.2089608,16.949983835220337,-0.02512286256106557,1739137675.208962,16.949983835220337,-0.2350535755749796,1739137675.2089636,16.949983835220337,-0.056414884451469534,1739137675.2089646,16.949983835220337,2.275658137202097,1739137675.2089665,16.949983835220337,0.0,1739137675.2089677,16.949983835220337,0.008020795274628956,1739137675.208969,16.949983835220337,0.004265324061271017,1739137675.2089705,16.949983835220337,2.2676373419274682 +1739137675.2289665,16.96998381614685,36.12090121996201,1739137675.2289686,16.96998381614685,0.0671357370194503,1739137675.2289712,16.96998381614685,35.322143833707486,1739137675.228974,16.96998381614685,44.11776172178957,1739137675.2289753,16.96998381614685,-0.13381056837131397,1739137675.228977,16.96998381614685,-0.02512286256106557,1739137675.2289784,16.96998381614685,-0.2350535755749796,1739137675.2289798,16.96998381614685,-0.056414884451469534,1739137675.228981,16.96998381614685,2.275658137202097,1739137675.2289824,16.96998381614685,0.0,1739137675.2289839,16.96998381614685,0.008020795274628956,1739137675.2289853,16.96998381614685,0.004265324061271017,1739137675.2289867,16.96998381614685,2.2676373419274682 +1739137675.2489657,16.989983797073364,36.12090121996201,1739137675.2489681,16.989983797073364,0.0671357370194503,1739137675.2489707,16.989983797073364,35.322143833707486,1739137675.2489736,16.989983797073364,44.11776172178957,1739137675.248975,16.989983797073364,-0.13381056837131397,1739137675.2489767,16.989983797073364,-0.02512286256106557,1739137675.2489781,16.989983797073364,-0.2350535755749796,1739137675.2489796,16.989983797073364,-0.056414884451469534,1739137675.2489805,16.989983797073364,2.275658137202097,1739137675.248982,16.989983797073364,0.0,1739137675.2489834,16.989983797073364,0.008020795274628956,1739137675.2489848,16.989983797073364,0.004265324061271017,1739137675.248986,16.989983797073364,2.2676373419274682 +1739137675.2691047,17.009983777999878,36.370393417879406,1739137675.269107,17.009983777999878,0.06809740093892191,1739137675.26911,17.009983777999878,35.57549285028172,1739137675.2691126,17.009983777999878,44.37403051879024,1739137675.2691138,17.009983777999878,-0.13736304430186513,1739137675.2691157,17.009983777999878,-0.025665247944835146,1739137675.269117,17.009983777999878,-0.232363499220188,1739137675.2691185,17.009983777999878,-0.05567348181650032,1739137675.2691197,17.009983777999878,2.278108132759319,1739137675.269121,17.009983777999878,0.0,1739137675.2691224,17.009983777999878,0.01082247364782972,1739137675.2691238,17.009983777999878,0.003361504917047033,1739137675.2691247,17.009983777999878,2.2686197923366143 +1739137675.288989,17.02998375892639,36.370393417879406,1739137675.2889915,17.02998375892639,0.06809740093892191,1739137675.2889943,17.02998375892639,35.57549285028172,1739137675.288997,17.02998375892639,44.37403051879024,1739137675.2889984,17.02998375892639,-0.13736304430186513,1739137675.289,17.02998375892639,-0.025665247944835146,1739137675.2890015,17.02998375892639,-0.232363499220188,1739137675.2890027,17.02998375892639,-0.05567348181650032,1739137675.289004,17.02998375892639,2.278108132759319,1739137675.2890055,17.02998375892639,0.0,1739137675.289007,17.02998375892639,0.009488340422704855,1739137675.2890084,17.02998375892639,0.003361504917047033,1739137675.2890096,17.02998375892639,2.2686197923366143 +1739137675.308955,17.049983739852905,36.370393417879406,1739137675.3089569,17.049983739852905,0.06809740093892191,1739137675.30896,17.049983739852905,35.57549285028172,1739137675.3089626,17.049983739852905,44.37403051879024,1739137675.308964,17.049983739852905,-0.13736304430186513,1739137675.308966,17.049983739852905,-0.025665247944835146,1739137675.308967,17.049983739852905,-0.232363499220188,1739137675.3089688,17.049983739852905,-0.05567348181650032,1739137675.30897,17.049983739852905,2.278108132759319,1739137675.3089714,17.049983739852905,0.0,1739137675.3089728,17.049983739852905,0.009488340422704855,1739137675.308974,17.049983739852905,0.003361504917047033,1739137675.3089755,17.049983739852905,2.2686197923366143 +1739137675.3289173,17.06998372077942,36.370393417879406,1739137675.3289196,17.06998372077942,0.06809740093892191,1739137675.328922,17.06998372077942,35.57549285028172,1739137675.3289247,17.06998372077942,44.37403051879024,1739137675.3289258,17.06998372077942,-0.13736304430186513,1739137675.328928,17.06998372077942,-0.025665247944835146,1739137675.3289292,17.06998372077942,-0.232363499220188,1739137675.3289306,17.06998372077942,-0.05567348181650032,1739137675.3289318,17.06998372077942,2.278108132759319,1739137675.3289335,17.06998372077942,0.0,1739137675.3289347,17.06998372077942,0.009488340422704855,1739137675.328936,17.06998372077942,0.003361504917047033,1739137675.3289375,17.06998372077942,2.2686197923366143 +1739137675.348952,17.089983701705933,36.370393417879406,1739137675.3489542,17.089983701705933,0.06809740093892191,1739137675.3489568,17.089983701705933,35.57549285028172,1739137675.3489594,17.089983701705933,44.37403051879024,1739137675.3489609,17.089983701705933,-0.13736304430186513,1739137675.3489625,17.089983701705933,-0.025665247944835146,1739137675.3489642,17.089983701705933,-0.232363499220188,1739137675.3489654,17.089983701705933,-0.05567348181650032,1739137675.3489664,17.089983701705933,2.278108132759319,1739137675.348968,17.089983701705933,0.0,1739137675.3489692,17.089983701705933,0.009488340422704855,1739137675.348971,17.089983701705933,0.003361504917047033,1739137675.3489723,17.089983701705933,2.2686197923366143 +1739137675.369011,17.109983682632446,36.61999324224795,1739137675.369013,17.109983682632446,0.06883388309070071,1739137675.3690157,17.109983682632446,36.29210708122874,1739137675.3690183,17.109983682632446,45.09374808423425,1739137675.3690197,17.109983682632446,-0.14087086526276246,1739137675.3690212,17.109983682632446,-0.02474250876322502,1739137675.3690226,17.109983682632446,-0.23052992077456297,1739137675.369024,17.109983682632446,-0.049278986172588746,1739137675.3690255,17.109983682632446,2.279779581618526,1739137675.369027,17.109983682632446,0.0,1739137675.369028,17.109983682632446,0.010675206730597884,1739137675.3690295,17.109983682632446,0.0024576857728230506,1739137675.369031,17.109983682632446,2.2696695496025874 +1739137675.3889813,17.12998366355896,36.61999324224795,1739137675.3889835,17.12998366355896,0.06883388309070071,1739137675.388986,17.12998366355896,36.29210708122874,1739137675.3889887,17.12998366355896,45.09374808423425,1739137675.38899,17.12998366355896,-0.14087086526276246,1739137675.3889916,17.12998366355896,-0.02474250876322502,1739137675.388993,17.12998366355896,-0.23052992077456297,1739137675.3889942,17.12998366355896,-0.049278986172588746,1739137675.388996,17.12998366355896,2.279779581618526,1739137675.3889973,17.12998366355896,0.0,1739137675.3889987,17.12998366355896,0.010110032015938408,1739137675.3890002,17.12998366355896,0.0024576857728230506,1739137675.3890014,17.12998366355896,2.2696695496025874 +1739137675.4089618,17.149983644485474,36.61999324224795,1739137675.4089642,17.149983644485474,0.06883388309070071,1739137675.4089665,17.149983644485474,36.29210708122874,1739137675.4089692,17.149983644485474,45.09374808423425,1739137675.4089706,17.149983644485474,-0.14087086526276246,1739137675.4089723,17.149983644485474,-0.02474250876322502,1739137675.4089735,17.149983644485474,-0.23052992077456297,1739137675.408975,17.149983644485474,-0.049278986172588746,1739137675.408976,17.149983644485474,2.279779581618526,1739137675.4089775,17.149983644485474,0.0,1739137675.408979,17.149983644485474,0.010110032015938408,1739137675.4089804,17.149983644485474,0.0024576857728230506,1739137675.4089818,17.149983644485474,2.2696695496025874 +1739137675.4289644,17.169983625411987,36.61999324224795,1739137675.4289668,17.169983625411987,0.06883388309070071,1739137675.4289694,17.169983625411987,36.29210708122874,1739137675.428972,17.169983625411987,45.09374808423425,1739137675.4289732,17.169983625411987,-0.14087086526276246,1739137675.428975,17.169983625411987,-0.02474250876322502,1739137675.4289763,17.169983625411987,-0.23052992077456297,1739137675.4289777,17.169983625411987,-0.049278986172588746,1739137675.428979,17.169983625411987,2.279779581618526,1739137675.4289806,17.169983625411987,0.0,1739137675.4289818,17.169983625411987,0.010110032015938408,1739137675.428983,17.169983625411987,0.0024576857728230506,1739137675.4289846,17.169983625411987,2.2696695496025874 +1739137675.4489686,17.1899836063385,36.61999324224795,1739137675.4489708,17.1899836063385,0.06883388309070071,1739137675.448974,17.1899836063385,36.29210708122874,1739137675.4489763,17.1899836063385,45.09374808423425,1739137675.4489777,17.1899836063385,-0.14087086526276246,1739137675.4489794,17.1899836063385,-0.02474250876322502,1739137675.4489808,17.1899836063385,-0.23052992077456297,1739137675.448982,17.1899836063385,-0.049278986172588746,1739137675.4489832,17.1899836063385,2.279779581618526,1739137675.4489849,17.1899836063385,0.0,1739137675.448986,17.1899836063385,0.010110032015938408,1739137675.4489877,17.1899836063385,0.0024576857728230506,1739137675.448989,17.1899836063385,2.2696695496025874 +1739137675.4691064,17.209983587265015,36.61999324224795,1739137675.4691088,17.209983587265015,0.06883388309070071,1739137675.4691114,17.209983587265015,36.29210708122874,1739137675.469114,17.209983587265015,45.09374808423425,1739137675.4691155,17.209983587265015,-0.14087086526276246,1739137675.4691172,17.209983587265015,-0.02474250876322502,1739137675.4691184,17.209983587265015,-0.23052992077456297,1739137675.4691198,17.209983587265015,-0.049278986172588746,1739137675.469121,17.209983587265015,2.279779581618526,1739137675.4691226,17.209983587265015,0.0,1739137675.4691238,17.209983587265015,0.010110032015938408,1739137675.4691253,17.209983587265015,0.0024576857728230506,1739137675.4691267,17.209983587265015,2.2696695496025874 +1739137675.489024,17.22998356819153,36.869712876990945,1739137675.4890263,17.22998356819153,0.06934501549603755,1739137675.4890292,17.22998356819153,36.325320303781965,1739137675.4890318,17.22998356819153,45.13031027519016,1739137675.4890332,17.22998356819153,-0.14026149541349736,1739137675.4890347,17.22998356819153,-0.025368812075923442,1739137675.4890363,17.22998356819153,-0.22244211932595473,1739137675.4890373,17.22998356819153,-0.05003403475375642,1739137675.4890387,17.22998356819153,2.287166886427559,1739137675.4890401,17.22998356819153,0.0,1739137675.4890413,17.22998356819153,0.022078680911684242,1739137675.489043,17.22998356819153,0.0015538666285990672,1739137675.4890442,17.22998356819153,2.2707875649799756 +1739137675.5089557,17.249983549118042,36.869712876990945,1739137675.5089579,17.249983549118042,0.06934501549603755,1739137675.5089605,17.249983549118042,36.325320303781965,1739137675.508963,17.249983549118042,45.13031027519016,1739137675.5089645,17.249983549118042,-0.14026149541349736,1739137675.5089662,17.249983549118042,-0.025368812075923442,1739137675.5089676,17.249983549118042,-0.22244211932595473,1739137675.5089693,17.249983549118042,-0.05003403475375642,1739137675.5089705,17.249983549118042,2.287166886427559,1739137675.508972,17.249983549118042,0.0,1739137675.5089736,17.249983549118042,0.01637932144758336,1739137675.5089748,17.249983549118042,0.0015538666285990672,1739137675.5089762,17.249983549118042,2.2707875649799756 +1739137675.5290446,17.269983530044556,36.869712876990945,1739137675.529047,17.269983530044556,0.06934501549603755,1739137675.5290496,17.269983530044556,36.325320303781965,1739137675.5290525,17.269983530044556,45.13031027519016,1739137675.529054,17.269983530044556,-0.14026149541349736,1739137675.5290558,17.269983530044556,-0.025368812075923442,1739137675.529057,17.269983530044556,-0.22244211932595473,1739137675.5290585,17.269983530044556,-0.05003403475375642,1739137675.52906,17.269983530044556,2.287166886427559,1739137675.529061,17.269983530044556,0.0,1739137675.5290625,17.269983530044556,0.01637932144758336,1739137675.529064,17.269983530044556,0.0015538666285990672,1739137675.5290651,17.269983530044556,2.2707875649799756 +1739137675.5489433,17.28998351097107,36.869712876990945,1739137675.5489454,17.28998351097107,0.06934501549603755,1739137675.5489485,17.28998351097107,36.325320303781965,1739137675.5489511,17.28998351097107,45.13031027519016,1739137675.5489526,17.28998351097107,-0.14026149541349736,1739137675.548954,17.28998351097107,-0.025368812075923442,1739137675.5489554,17.28998351097107,-0.22244211932595473,1739137675.5489566,17.28998351097107,-0.05003403475375642,1739137675.548958,17.28998351097107,2.287166886427559,1739137675.5489595,17.28998351097107,0.0,1739137675.5489607,17.28998351097107,0.01637932144758336,1739137675.5489626,17.28998351097107,0.0015538666285990672,1739137675.5489638,17.28998351097107,2.2707875649799756 +1739137675.568973,17.309983491897583,36.869712876990945,1739137675.5689754,17.309983491897583,0.06934501549603755,1739137675.568978,17.309983491897583,36.325320303781965,1739137675.5689807,17.309983491897583,45.13031027519016,1739137675.5689821,17.309983491897583,-0.14026149541349736,1739137675.5689836,17.309983491897583,-0.025368812075923442,1739137675.568985,17.309983491897583,-0.22244211932595473,1739137675.5689864,17.309983491897583,-0.05003403475375642,1739137675.5689876,17.309983491897583,2.287166886427559,1739137675.5689893,17.309983491897583,0.0,1739137675.5689905,17.309983491897583,0.01637932144758336,1739137675.5689917,17.309983491897583,0.0015538666285990672,1739137675.568993,17.309983491897583,2.2707875649799756 +1739137675.5890229,17.329983472824097,37.119592471882044,1739137675.5890253,17.329983472824097,0.06963062246961638,1739137675.5890281,17.329983472824097,36.35855457550945,1739137675.589031,17.329983472824097,45.16907041069867,1739137675.5890322,17.329983472824097,-0.13976929589301332,1739137675.589034,17.329983472824097,-0.02600823347229134,1739137675.5890355,17.329983472824097,-0.21463241663658197,1739137675.5890367,17.329983472824097,-0.05084119155310976,1739137675.5890381,17.329983472824097,2.2943228952219705,1739137675.5890396,17.329983472824097,0.0,1739137675.589041,17.329983472824097,0.02652221795684027,1739137675.5890422,17.329983472824097,0.000650047484375083,1739137675.5890434,17.329983472824097,2.2726306303965966 +1739137675.608982,17.34998345375061,37.119592471882044,1739137675.608984,17.34998345375061,0.06963062246961638,1739137675.6089869,17.34998345375061,36.35855457550945,1739137675.6089897,17.34998345375061,45.16907041069867,1739137675.608991,17.34998345375061,-0.13976929589301332,1739137675.6089926,17.34998345375061,-0.02600823347229134,1739137675.608994,17.34998345375061,-0.21463241663658197,1739137675.6089954,17.34998345375061,-0.05084119155310976,1739137675.6089966,17.34998345375061,2.2943228952219705,1739137675.608998,17.34998345375061,0.0,1739137675.6089995,17.34998345375061,0.021692264825373897,1739137675.609001,17.34998345375061,0.000650047484375083,1739137675.6090024,17.34998345375061,2.2726306303965966 +1739137675.628977,17.369983434677124,37.119592471882044,1739137675.6289797,17.369983434677124,0.06963062246961638,1739137675.6289823,17.369983434677124,36.35855457550945,1739137675.628985,17.369983434677124,45.16907041069867,1739137675.6289864,17.369983434677124,-0.13976929589301332,1739137675.6289878,17.369983434677124,-0.02600823347229134,1739137675.6289895,17.369983434677124,-0.21463241663658197,1739137675.6289907,17.369983434677124,-0.05084119155310976,1739137675.628992,17.369983434677124,2.2943228952219705,1739137675.6289935,17.369983434677124,0.0,1739137675.6289947,17.369983434677124,0.021692264825373897,1739137675.6289961,17.369983434677124,0.000650047484375083,1739137675.6289976,17.369983434677124,2.2726306303965966 +1739137675.6489642,17.389983415603638,37.119592471882044,1739137675.648966,17.389983415603638,0.06963062246961638,1739137675.648969,17.389983415603638,36.35855457550945,1739137675.6489716,17.389983415603638,45.16907041069867,1739137675.648973,17.389983415603638,-0.13976929589301332,1739137675.6489747,17.389983415603638,-0.02600823347229134,1739137675.6489758,17.389983415603638,-0.21463241663658197,1739137675.6489775,17.389983415603638,-0.05084119155310976,1739137675.6489785,17.389983415603638,2.2943228952219705,1739137675.64898,17.389983415603638,0.0,1739137675.6489813,17.389983415603638,0.021692264825373897,1739137675.6489825,17.389983415603638,0.000650047484375083,1739137675.6489837,17.389983415603638,2.2726306303965966 +1739137675.6689544,17.40998339653015,37.119592471882044,1739137675.6689568,17.40998339653015,0.06963062246961638,1739137675.6689594,17.40998339653015,36.35855457550945,1739137675.6689618,17.40998339653015,45.16907041069867,1739137675.668963,17.40998339653015,-0.13976929589301332,1739137675.6689649,17.40998339653015,-0.02600823347229134,1739137675.668966,17.40998339653015,-0.21463241663658197,1739137675.6689675,17.40998339653015,-0.05084119155310976,1739137675.668969,17.40998339653015,2.2943228952219705,1739137675.6689706,17.40998339653015,0.0,1739137675.6689715,17.40998339653015,0.021692264825373897,1739137675.668973,17.40998339653015,0.000650047484375083,1739137675.6689744,17.40998339653015,2.2726306303965966 +1739137675.6889617,17.429983377456665,37.119592471882044,1739137675.6889641,17.429983377456665,0.06963062246961638,1739137675.688967,17.429983377456665,36.35855457550945,1739137675.6889691,17.429983377456665,45.16907041069867,1739137675.6889708,17.429983377456665,-0.13976929589301332,1739137675.6889722,17.429983377456665,-0.02600823347229134,1739137675.6889737,17.429983377456665,-0.21463241663658197,1739137675.6889749,17.429983377456665,-0.05084119155310976,1739137675.688976,17.429983377456665,2.2943228952219705,1739137675.6889777,17.429983377456665,0.0,1739137675.688979,17.429983377456665,0.021692264825373897,1739137675.6889803,17.429983377456665,0.000650047484375083,1739137675.6889815,17.429983377456665,2.2726306303965966 +1739137675.7090175,17.44998335838318,37.36970993170401,1739137675.70902,17.44998335838318,0.06969043564986777,1739137675.7090228,17.44998335838318,36.85540272675603,1739137675.7090254,17.44998335838318,45.67309048640794,1739137675.7090266,17.44998335838318,-0.1253287633127301,1739137675.709028,17.44998335838318,-0.02348240578779573,1739137675.7090297,17.44998335838318,-0.1929120300398689,1739137675.7090309,17.44998335838318,-0.042950820518910866,1739137675.7090323,17.44998335838318,2.314343171018649,1739137675.7090337,17.44998335838318,0.0,1739137675.709035,17.44998335838318,0.055196362917743935,1739137675.7090364,17.44998335838318,6.2829315355197375,1739137675.7090378,17.44998335838318,2.2751011484957333 +1739137675.728963,17.469983339309692,37.36970993170401,1739137675.728965,17.469983339309692,0.06969043564986777,1739137675.728968,17.469983339309692,36.85540272675603,1739137675.7289705,17.469983339309692,45.67309048640794,1739137675.7289717,17.469983339309692,-0.1253287633127301,1739137675.7289736,17.469983339309692,-0.02348240578779573,1739137675.7289748,17.469983339309692,-0.1929120300398689,1739137675.728976,17.469983339309692,-0.042950820518910866,1739137675.7289774,17.469983339309692,2.314343171018649,1739137675.7289789,17.469983339309692,0.0,1739137675.7289803,17.469983339309692,0.039242022522915754,1739137675.7289817,17.469983339309692,6.2829315355197375,1739137675.728983,17.469983339309692,2.2751011484957333 +1739137675.7489665,17.489983320236206,37.36970993170401,1739137675.7489684,17.489983320236206,0.06969043564986777,1739137675.748971,17.489983320236206,36.85540272675603,1739137675.7489738,17.489983320236206,45.67309048640794,1739137675.748975,17.489983320236206,-0.1253287633127301,1739137675.7489767,17.489983320236206,-0.02348240578779573,1739137675.7489781,17.489983320236206,-0.1929120300398689,1739137675.7489796,17.489983320236206,-0.042950820518910866,1739137675.7489805,17.489983320236206,2.314343171018649,1739137675.748982,17.489983320236206,0.0,1739137675.7489834,17.489983320236206,0.039242022522915754,1739137675.7489846,17.489983320236206,6.2829315355197375,1739137675.748986,17.489983320236206,2.2751011484957333 +1739137675.7690654,17.50998330116272,37.36970993170401,1739137675.7690678,17.50998330116272,0.06969043564986777,1739137675.7690704,17.50998330116272,36.85540272675603,1739137675.769073,17.50998330116272,45.67309048640794,1739137675.7690742,17.50998330116272,-0.1253287633127301,1739137675.7690759,17.50998330116272,-0.02348240578779573,1739137675.7690773,17.50998330116272,-0.1929120300398689,1739137675.7690785,17.50998330116272,-0.042950820518910866,1739137675.76908,17.50998330116272,2.314343171018649,1739137675.7690814,17.50998330116272,0.0,1739137675.7690823,17.50998330116272,0.039242022522915754,1739137675.769084,17.50998330116272,6.2829315355197375,1739137675.7690852,17.50998330116272,2.2751011484957333 +1739137675.7889903,17.529983282089233,37.36970993170401,1739137675.7889924,17.529983282089233,0.06969043564986777,1739137675.7889953,17.529983282089233,36.85540272675603,1739137675.788998,17.529983282089233,45.67309048640794,1739137675.788999,17.529983282089233,-0.1253287633127301,1739137675.7890007,17.529983282089233,-0.02348240578779573,1739137675.7890022,17.529983282089233,-0.1929120300398689,1739137675.7890036,17.529983282089233,-0.042950820518910866,1739137675.7890048,17.529983282089233,2.314343171018649,1739137675.7890062,17.529983282089233,0.0,1739137675.7890077,17.529983282089233,0.039242022522915754,1739137675.789009,17.529983282089233,6.2829315355197375,1739137675.7890105,17.529983282089233,2.2751011484957333 +1739137675.8088796,17.549983263015747,37.62019552370499,1739137675.8088818,17.549983263015747,0.06952392593581891,1739137675.808884,17.549983263015747,36.888967629574445,1739137675.8088863,17.549983263015747,45.719904931363615,1739137675.8088875,17.549983263015747,-0.12296439740587806,1739137675.8088892,17.549983263015747,-0.023760370756901752,1739137675.8088903,17.549983263015747,-0.18311204734101105,1739137675.8088913,17.549983263015747,-0.04284444525769635,1739137675.8088927,17.549983263015747,2.3234331849886356,1739137675.808894,17.549983263015747,0.0,1739137675.8088953,17.549983263015747,0.04812619211381131,1739137675.8088965,17.549983263015747,6.282027716375513,1739137675.8088975,17.549983263015747,2.279537551936219 +1739137675.8289135,17.56998324394226,37.62019552370499,1739137675.8289156,17.56998324394226,0.06952392593581891,1739137675.828918,17.56998324394226,36.888967629574445,1739137675.8289206,17.56998324394226,45.719904931363615,1739137675.8289218,17.56998324394226,-0.12296439740587806,1739137675.8289235,17.56998324394226,-0.023760370756901752,1739137675.8289247,17.56998324394226,-0.18311204734101105,1739137675.8289258,17.56998324394226,-0.04284444525769635,1739137675.8289273,17.56998324394226,2.3234331849886356,1739137675.8289285,17.56998324394226,0.0,1739137675.82893,17.56998324394226,0.04389563305241673,1739137675.828931,17.56998324394226,6.282027716375513,1739137675.8289323,17.56998324394226,2.279537551936219 +1739137675.8489163,17.589983224868774,37.62019552370499,1739137675.8489182,17.589983224868774,0.06952392593581891,1739137675.8489208,17.589983224868774,36.888967629574445,1739137675.8489234,17.589983224868774,45.719904931363615,1739137675.8489246,17.589983224868774,-0.12296439740587806,1739137675.8489263,17.589983224868774,-0.023760370756901752,1739137675.8489277,17.589983224868774,-0.18311204734101105,1739137675.8489287,17.589983224868774,-0.04284444525769635,1739137675.8489301,17.589983224868774,2.3234331849886356,1739137675.8489316,17.589983224868774,0.0,1739137675.8489325,17.589983224868774,0.04389563305241673,1739137675.8489342,17.589983224868774,6.282027716375513,1739137675.8489354,17.589983224868774,2.279537551936219 +1739137675.8689184,17.609983205795288,37.62019552370499,1739137675.8689206,17.609983205795288,0.06952392593581891,1739137675.8689232,17.609983205795288,36.888967629574445,1739137675.8689258,17.609983205795288,45.719904931363615,1739137675.868927,17.609983205795288,-0.12296439740587806,1739137675.8689284,17.609983205795288,-0.023760370756901752,1739137675.8689299,17.609983205795288,-0.18311204734101105,1739137675.868931,17.609983205795288,-0.04284444525769635,1739137675.8689322,17.609983205795288,2.3234331849886356,1739137675.868934,17.609983205795288,0.0,1739137675.8689349,17.609983205795288,0.04389563305241673,1739137675.8689365,17.609983205795288,6.282027716375513,1739137675.8689375,17.609983205795288,2.279537551936219 +1739137675.889068,17.6299831867218,37.62019552370499,1739137675.8890698,17.6299831867218,0.06952392593581891,1739137675.8890724,17.6299831867218,36.888967629574445,1739137675.889075,17.6299831867218,45.719904931363615,1739137675.8890762,17.6299831867218,-0.12296439740587806,1739137675.8890777,17.6299831867218,-0.023760370756901752,1739137675.889079,17.6299831867218,-0.18311204734101105,1739137675.8890803,17.6299831867218,-0.04284444525769635,1739137675.8890812,17.6299831867218,2.3234331849886356,1739137675.889083,17.6299831867218,0.0,1739137675.8890839,17.6299831867218,0.04389563305241673,1739137675.8890853,17.6299831867218,6.282027716375513,1739137675.8890865,17.6299831867218,2.279537551936219 +1739137675.9089441,17.649983167648315,37.62019552370499,1739137675.9089463,17.649983167648315,0.06952392593581891,1739137675.9089491,17.649983167648315,36.888967629574445,1739137675.9089518,17.649983167648315,45.719904931363615,1739137675.9089532,17.649983167648315,-0.12296439740587806,1739137675.9089546,17.649983167648315,-0.023760370756901752,1739137675.9089558,17.649983167648315,-0.18311204734101105,1739137675.9089572,17.649983167648315,-0.04284444525769635,1739137675.9089584,17.649983167648315,2.3234331849886356,1739137675.90896,17.649983167648315,0.0,1739137675.9089613,17.649983167648315,0.04389563305241673,1739137675.9089625,17.649983167648315,6.282027716375513,1739137675.9089642,17.649983167648315,2.279537551936219 +1739137675.928907,17.66998314857483,37.87119307733888,1739137675.9289105,17.66998314857483,0.06913021662686614,1739137675.9289145,17.66998314857483,37.039616832420755,1739137675.9289184,17.66998314857483,45.8850537316508,1739137675.92892,17.66998314857483,-0.11554827899740851,1739137675.9289227,17.66998314857483,-0.023040806647581093,1739137675.9289246,17.66998314857483,-0.16815826285987068,1739137675.928927,17.66998314857483,-0.040194745977543966,1739137675.928929,17.66998314857483,2.3373724801129443,1739137675.928937,17.66998314857483,0.0,1739137675.9289389,17.66998314857483,0.06117281692155056,1739137675.9289405,17.66998314857483,6.281123897231289,1739137675.9289417,17.66998314857483,2.28442689771513 +1739137675.9489613,17.689983129501343,37.87119307733888,1739137675.9489636,17.689983129501343,0.06913021662686614,1739137675.9489665,17.689983129501343,37.039616832420755,1739137675.9489691,17.689983129501343,45.8850537316508,1739137675.9489706,17.689983129501343,-0.11554827899740851,1739137675.948972,17.689983129501343,-0.023040806647581093,1739137675.9489737,17.689983129501343,-0.16815826285987068,1739137675.9489748,17.689983129501343,-0.040194745977543966,1739137675.948976,17.689983129501343,2.3373724801129443,1739137675.9489777,17.689983129501343,0.0,1739137675.948979,17.689983129501343,0.05294558239781422,1739137675.9489806,17.689983129501343,6.281123897231289,1739137675.9489818,17.689983129501343,2.28442689771513 +1739137675.9704087,17.709983110427856,37.87119307733888,1739137675.9704123,17.709983110427856,0.06913021662686614,1739137675.9704168,17.709983110427856,37.039616832420755,1739137675.9704223,17.709983110427856,45.8850537316508,1739137675.9704251,17.709983110427856,-0.11554827899740851,1739137675.970429,17.709983110427856,-0.023040806647581093,1739137675.9704323,17.709983110427856,-0.16815826285987068,1739137675.9704359,17.709983110427856,-0.040194745977543966,1739137675.9704392,17.709983110427856,2.3373724801129443,1739137675.9704428,17.709983110427856,0.0,1739137675.970446,17.709983110427856,0.05294558239781422,1739137675.9704497,17.709983110427856,6.281123897231289,1739137675.9704533,17.709983110427856,2.28442689771513 +1739137675.9895055,17.72998309135437,37.87119307733888,1739137675.9895082,17.72998309135437,0.06913021662686614,1739137675.9895113,17.72998309135437,37.039616832420755,1739137675.9895306,17.72998309135437,45.8850537316508,1739137675.989532,17.72998309135437,-0.11554827899740851,1739137675.9895337,17.72998309135437,-0.023040806647581093,1739137675.989535,17.72998309135437,-0.16815826285987068,1739137675.9895363,17.72998309135437,-0.040194745977543966,1739137675.9895542,17.72998309135437,2.3373724801129443,1739137675.989556,17.72998309135437,0.0,1739137675.9895573,17.72998309135437,0.05294558239781422,1739137675.9895587,17.72998309135437,6.281123897231289,1739137675.9895604,17.72998309135437,2.28442689771513 +1739137676.0090559,17.749983072280884,37.87119307733888,1739137676.0090582,17.749983072280884,0.06913021662686614,1739137676.0090609,17.749983072280884,37.039616832420755,1739137676.0090637,17.749983072280884,45.8850537316508,1739137676.009065,17.749983072280884,-0.11554827899740851,1739137676.0090668,17.749983072280884,-0.023040806647581093,1739137676.009068,17.749983072280884,-0.16815826285987068,1739137676.00907,17.749983072280884,-0.040194745977543966,1739137676.009071,17.749983072280884,2.3373724801129443,1739137676.0090725,17.749983072280884,0.0,1739137676.009074,17.749983072280884,0.05294558239781422,1739137676.0090752,17.749983072280884,6.281123897231289,1739137676.0090766,17.749983072280884,2.28442689771513 +1739137676.029093,17.769983053207397,38.12277408410502,1739137676.0290956,17.769983053207397,0.06850819885602366,1739137676.0290983,17.769983053207397,37.65431464199208,1739137676.029101,17.769983053207397,46.51666594035279,1739137676.0291023,17.769983053207397,-0.08660344873852341,1739137676.0291038,17.769983053207397,-0.01847700663233179,1739137676.0291052,17.769983053207397,-0.130221189821644,1739137676.0291064,17.769983053207397,-0.02837820392763806,1739137676.0291078,17.769983053207397,2.3731121945133826,1739137676.0291092,17.769983053207397,0.0,1739137676.0291104,17.769983053207397,0.10997884737735351,1739137676.029112,17.769983053207397,6.280220078087066,1739137676.0291133,17.769983053207397,2.2902920583122963 +1739137676.0500252,17.78998303413391,38.12277408410502,1739137676.0500312,17.78998303413391,0.06850819885602366,1739137676.0500362,17.78998303413391,37.65431464199208,1739137676.0500422,17.78998303413391,46.51666594035279,1739137676.050045,17.78998303413391,-0.08660344873852341,1739137676.0500488,17.78998303413391,-0.01847700663233179,1739137676.0500517,17.78998303413391,-0.130221189821644,1739137676.0500546,17.78998303413391,-0.02837820392763806,1739137676.0500574,17.78998303413391,2.3731121945133826,1739137676.0500605,17.78998303413391,0.0,1739137676.0500638,17.78998303413391,0.0828201362010863,1739137676.0500665,17.78998303413391,6.280220078087066,1739137676.0500686,17.78998303413391,2.2902920583122963 +1739137676.069076,17.809983015060425,38.12277408410502,1739137676.0690784,17.809983015060425,0.06850819885602366,1739137676.0690813,17.809983015060425,37.65431464199208,1739137676.069084,17.809983015060425,46.51666594035279,1739137676.0690851,17.809983015060425,-0.08660344873852341,1739137676.0690868,17.809983015060425,-0.01847700663233179,1739137676.069088,17.809983015060425,-0.130221189821644,1739137676.0690892,17.809983015060425,-0.02837820392763806,1739137676.0690906,17.809983015060425,2.3731121945133826,1739137676.069092,17.809983015060425,0.0,1739137676.0690935,17.809983015060425,0.0828201362010863,1739137676.069095,17.809983015060425,6.280220078087066,1739137676.0690958,17.809983015060425,2.2902920583122963 +1739137676.090918,17.82998299598694,38.12277408410502,1739137676.0909216,17.82998299598694,0.06850819885602366,1739137676.0909264,17.82998299598694,37.65431464199208,1739137676.0909324,17.82998299598694,46.51666594035279,1739137676.0909355,17.82998299598694,-0.08660344873852341,1739137676.0909405,17.82998299598694,-0.01847700663233179,1739137676.0909438,17.82998299598694,-0.130221189821644,1739137676.0909476,17.82998299598694,-0.02837820392763806,1739137676.090951,17.82998299598694,2.3731121945133826,1739137676.0909543,17.82998299598694,0.0,1739137676.0909586,17.82998299598694,0.0828201362010863,1739137676.0909622,17.82998299598694,6.280220078087066,1739137676.0909657,17.82998299598694,2.2902920583122963 +1739137676.1089206,17.849982976913452,38.12277408410502,1739137676.1089227,17.849982976913452,0.06850819885602366,1739137676.108925,17.849982976913452,37.65431464199208,1739137676.1089277,17.849982976913452,46.51666594035279,1739137676.108929,17.849982976913452,-0.08660344873852341,1739137676.1089303,17.849982976913452,-0.01847700663233179,1739137676.1089315,17.849982976913452,-0.130221189821644,1739137676.108933,17.849982976913452,-0.02837820392763806,1739137676.1089342,17.849982976913452,2.3731121945133826,1739137676.1089354,17.849982976913452,0.0,1739137676.1089368,17.849982976913452,0.0828201362010863,1739137676.108938,17.849982976913452,6.280220078087066,1739137676.1089392,17.849982976913452,2.2902920583122963 +1739137676.1288822,17.869982957839966,38.12277408410502,1739137676.1288846,17.869982957839966,0.06850819885602366,1739137676.1288867,17.869982957839966,37.65431464199208,1739137676.1288893,17.869982957839966,46.51666594035279,1739137676.1288905,17.869982957839966,-0.08660344873852341,1739137676.128892,17.869982957839966,-0.01847700663233179,1739137676.1288934,17.869982957839966,-0.130221189821644,1739137676.1288946,17.869982957839966,-0.02837820392763806,1739137676.1288958,17.869982957839966,2.3731121945133826,1739137676.128897,17.869982957839966,0.0,1739137676.1288984,17.869982957839966,0.0828201362010863,1739137676.1288996,17.869982957839966,6.280220078087066,1739137676.1289005,17.869982957839966,2.2902920583122963 +1739137676.1489956,17.88998293876648,38.37521035774602,1739137676.1489975,17.88998293876648,0.06765587901392145,1739137676.1490002,17.88998293876648,37.68814025034013,1739137676.1490028,17.88998293876648,46.579188956122294,1739137676.1490037,17.88998293876648,-0.08277181714707467,1739137676.1490054,17.88998293876648,-0.018333890012364826,1739137676.1490066,17.88998293876648,-0.11868506050852007,1739137676.1490078,17.88998293876648,-0.027075747379429263,1739137676.1490092,17.88998293876648,2.3840881106150693,1739137676.1490104,17.88998293876648,0.0,1739137676.1490116,17.88998293876648,0.08543749564756987,1739137676.1490133,17.88998293876648,6.279316258942841,1739137676.1490142,17.88998293876648,2.2998969772312945 +1739137676.1689367,17.909982919692993,38.37521035774602,1739137676.1689386,17.909982919692993,0.06765587901392145,1739137676.1689415,17.909982919692993,37.68814025034013,1739137676.168944,17.909982919692993,46.579188956122294,1739137676.168945,17.909982919692993,-0.08277181714707467,1739137676.1689467,17.909982919692993,-0.018333890012364826,1739137676.1689482,17.909982919692993,-0.11868506050852007,1739137676.1689496,17.909982919692993,-0.027075747379429263,1739137676.1689508,17.909982919692993,2.3840881106150693,1739137676.168952,17.909982919692993,0.0,1739137676.1689534,17.909982919692993,0.08419113338377482,1739137676.1689546,17.909982919692993,6.279316258942841,1739137676.168956,17.909982919692993,2.2998969772312945 +1739137676.1890242,17.929982900619507,38.37521035774602,1739137676.1890266,17.929982900619507,0.06765587901392145,1739137676.1890295,17.929982900619507,37.68814025034013,1739137676.189032,17.929982900619507,46.579188956122294,1739137676.1890335,17.929982900619507,-0.08277181714707467,1739137676.1890352,17.929982900619507,-0.018333890012364826,1739137676.1890366,17.929982900619507,-0.11868506050852007,1739137676.189038,17.929982900619507,-0.027075747379429263,1739137676.189039,17.929982900619507,2.3840881106150693,1739137676.1890407,17.929982900619507,0.0,1739137676.1890419,17.929982900619507,0.08419113338377482,1739137676.1890435,17.929982900619507,6.279316258942841,1739137676.189045,17.929982900619507,2.2998969772312945 +1739137676.2091565,17.94998288154602,38.37521035774602,1739137676.2091594,17.94998288154602,0.06765587901392145,1739137676.2091625,17.94998288154602,37.68814025034013,1739137676.2091653,17.94998288154602,46.579188956122294,1739137676.2091668,17.94998288154602,-0.08277181714707467,1739137676.2091687,17.94998288154602,-0.018333890012364826,1739137676.2091703,17.94998288154602,-0.11868506050852007,1739137676.2091718,17.94998288154602,-0.027075747379429263,1739137676.2091732,17.94998288154602,2.3840881106150693,1739137676.2091749,17.94998288154602,0.0,1739137676.2091763,17.94998288154602,0.08419113338377482,1739137676.209178,17.94998288154602,6.279316258942841,1739137676.2091794,17.94998288154602,2.2998969772312945 +1739137676.2291293,17.969982862472534,38.37521035774602,1739137676.2291315,17.969982862472534,0.06765587901392145,1739137676.2291346,17.969982862472534,37.68814025034013,1739137676.2291374,17.969982862472534,46.579188956122294,1739137676.2291389,17.969982862472534,-0.08277181714707467,1739137676.2291408,17.969982862472534,-0.018333890012364826,1739137676.2291422,17.969982862472534,-0.11868506050852007,1739137676.2291436,17.969982862472534,-0.027075747379429263,1739137676.229145,17.969982862472534,2.3840881106150693,1739137676.2291467,17.969982862472534,0.0,1739137676.2291481,17.969982862472534,0.08419113338377482,1739137676.2291496,17.969982862472534,6.279316258942841,1739137676.2291512,17.969982862472534,2.2998969772312945 +1739137676.249158,17.989982843399048,38.628658243673605,1739137676.2491608,17.989982843399048,0.0665710712023202,1739137676.2491639,17.989982843399048,37.953405255294285,1739137676.249167,17.989982843399048,46.87139559737297,1739137676.2491684,17.989982843399048,-0.062467033552252436,1739137676.24917,17.989982843399048,-0.015653484949849587,1739137676.2491717,17.989982843399048,-0.08969529211910009,1739137676.2491732,17.989982843399048,-0.02027238801960468,1739137676.2491746,17.989982843399048,2.411894685120964,1739137676.2491763,17.989982843399048,0.0,1739137676.249178,17.989982843399048,0.11967709972910286,1739137676.2491794,17.989982843399048,6.278412439798617,1739137676.2491806,17.989982843399048,2.3091156730452553 +1739137676.2697194,18.00998282432556,38.628658243673605,1739137676.2697227,18.00998282432556,0.0665710712023202,1739137676.269727,18.00998282432556,37.953405255294285,1739137676.2697313,18.00998282432556,46.87139559737297,1739137676.2697334,18.00998282432556,-0.062467033552252436,1739137676.2697363,18.00998282432556,-0.015653484949849587,1739137676.2697384,18.00998282432556,-0.08969529211910009,1739137676.2697408,18.00998282432556,-0.02027238801960468,1739137676.269743,18.00998282432556,2.411894685120964,1739137676.269745,18.00998282432556,0.0,1739137676.2697473,18.00998282432556,0.10277901207570883,1739137676.2697492,18.00998282432556,6.278412439798617,1739137676.2697513,18.00998282432556,2.3091156730452553 +1739137676.290881,18.029982805252075,38.628658243673605,1739137676.2908857,18.029982805252075,0.0665710712023202,1739137676.290891,18.029982805252075,37.953405255294285,1739137676.290896,18.029982805252075,46.87139559737297,1739137676.290898,18.029982805252075,-0.062467033552252436,1739137676.2909012,18.029982805252075,-0.015653484949849587,1739137676.2909038,18.029982805252075,-0.08969529211910009,1739137676.2909064,18.029982805252075,-0.02027238801960468,1739137676.2909086,18.029982805252075,2.411894685120964,1739137676.2909114,18.029982805252075,0.0,1739137676.2909138,18.029982805252075,0.10277901207570883,1739137676.2909164,18.029982805252075,6.278412439798617,1739137676.2909188,18.029982805252075,2.3091156730452553 +1739137676.3101733,18.04998278617859,38.628658243673605,1739137676.3101778,18.04998278617859,0.0665710712023202,1739137676.3101826,18.04998278617859,37.953405255294285,1739137676.3101876,18.04998278617859,46.87139559737297,1739137676.3101904,18.04998278617859,-0.062467033552252436,1739137676.3101933,18.04998278617859,-0.015653484949849587,1739137676.3101962,18.04998278617859,-0.08969529211910009,1739137676.3101985,18.04998278617859,-0.02027238801960468,1739137676.310201,18.04998278617859,2.411894685120964,1739137676.3102036,18.04998278617859,0.0,1739137676.310206,18.04998278617859,0.10277901207570883,1739137676.3102088,18.04998278617859,6.278412439798617,1739137676.3102112,18.04998278617859,2.3091156730452553 +1739137676.3316605,18.069982767105103,38.628658243673605,1739137676.3316648,18.069982767105103,0.0665710712023202,1739137676.3316703,18.069982767105103,37.953405255294285,1739137676.331675,18.069982767105103,46.87139559737297,1739137676.3316774,18.069982767105103,-0.062467033552252436,1739137676.3316805,18.069982767105103,-0.015653484949849587,1739137676.331683,18.069982767105103,-0.08969529211910009,1739137676.331685,18.069982767105103,-0.02027238801960468,1739137676.3316875,18.069982767105103,2.411894685120964,1739137676.3316903,18.069982767105103,0.0,1739137676.3316925,18.069982767105103,0.10277901207570883,1739137676.3316953,18.069982767105103,6.278412439798617,1739137676.3316977,18.069982767105103,2.3091156730452553 +1739137676.3498044,18.089982748031616,38.628658243673605,1739137676.3498075,18.089982748031616,0.0665710712023202,1739137676.3498123,18.089982748031616,37.953405255294285,1739137676.3498156,18.089982748031616,46.87139559737297,1739137676.3498173,18.089982748031616,-0.062467033552252436,1739137676.3498197,18.089982748031616,-0.015653484949849587,1739137676.3498213,18.089982748031616,-0.08969529211910009,1739137676.3498232,18.089982748031616,-0.02027238801960468,1739137676.3498247,18.089982748031616,2.411894685120964,1739137676.3498268,18.089982748031616,0.0,1739137676.349829,18.089982748031616,0.10277901207570883,1739137676.3498306,18.089982748031616,6.278412439798617,1739137676.3498325,18.089982748031616,2.3091156730452553 +1739137676.3693724,18.10998272895813,38.88325316866012,1739137676.3693752,18.10998272895813,0.0652512227183717,1739137676.3693788,18.10998272895813,38.444886313477056,1739137676.3693821,18.10998272895813,47.39460650434527,1739137676.369384,18.10998272895813,-0.006770374440382271,1739137676.3693862,18.10998272895813,-0.008461624775333555,1739137676.3693879,18.10998272895813,-0.023704411426775575,1739137676.3693898,18.10998272895813,-0.0050256431794774075,1739137676.3693914,18.10998272895813,2.4764076140514515,1739137676.369393,18.10998272895813,0.0,1739137676.369395,18.10998272895813,0.20382076651924244,1739137676.3693967,18.10998272895813,6.277508620654394,1739137676.3693984,18.10998272895813,2.3207019927314136 +1739137676.3893876,18.129982709884644,38.88325316866012,1739137676.3893902,18.129982709884644,0.0652512227183717,1739137676.3893938,18.129982709884644,38.444886313477056,1739137676.3893976,18.129982709884644,47.39460650434527,1739137676.3893993,18.129982709884644,-0.006770374440382271,1739137676.3894014,18.129982709884644,-0.008461624775333555,1739137676.3894029,18.129982709884644,-0.023704411426775575,1739137676.3894043,18.129982709884644,-0.0050256431794774075,1739137676.389406,18.129982709884644,2.4764076140514515,1739137676.389408,18.129982709884644,0.0,1739137676.3894095,18.129982709884644,0.15570562132003785,1739137676.3894117,18.129982709884644,6.277508620654394,1739137676.3894134,18.129982709884644,2.3207019927314136 +1739137676.409343,18.149982690811157,38.88325316866012,1739137676.4093459,18.149982690811157,0.0652512227183717,1739137676.4093492,18.149982690811157,38.444886313477056,1739137676.4093528,18.149982690811157,47.39460650434527,1739137676.4093542,18.149982690811157,-0.006770374440382271,1739137676.4093564,18.149982690811157,-0.008461624775333555,1739137676.409358,18.149982690811157,-0.023704411426775575,1739137676.40936,18.149982690811157,-0.0050256431794774075,1739137676.4093614,18.149982690811157,2.4764076140514515,1739137676.4093635,18.149982690811157,0.0,1739137676.4093652,18.149982690811157,0.15570562132003785,1739137676.409367,18.149982690811157,6.277508620654394,1739137676.4093685,18.149982690811157,2.3207019927314136 +1739137676.4294555,18.16998267173767,38.88325316866012,1739137676.429459,18.16998267173767,0.0652512227183717,1739137676.4294631,18.16998267173767,38.444886313477056,1739137676.4294665,18.16998267173767,47.39460650434527,1739137676.4294682,18.16998267173767,-0.006770374440382271,1739137676.4294705,18.16998267173767,-0.008461624775333555,1739137676.429472,18.16998267173767,-0.023704411426775575,1739137676.429474,18.16998267173767,-0.0050256431794774075,1739137676.4294755,18.16998267173767,2.4764076140514515,1739137676.4294777,18.16998267173767,0.0,1739137676.4294791,18.16998267173767,0.15570562132003785,1739137676.429481,18.16998267173767,6.277508620654394,1739137676.4294827,18.16998267173767,2.3207019927314136 +1739137676.4495752,18.189982652664185,38.88325316866012,1739137676.4495783,18.189982652664185,0.0652512227183717,1739137676.4495819,18.189982652664185,38.444886313477056,1739137676.4495854,18.189982652664185,47.39460650434527,1739137676.4495869,18.189982652664185,-0.006770374440382271,1739137676.4495895,18.189982652664185,-0.008461624775333555,1739137676.4495914,18.189982652664185,-0.023704411426775575,1739137676.4495928,18.189982652664185,-0.0050256431794774075,1739137676.4495943,18.189982652664185,2.4764076140514515,1739137676.4495962,18.189982652664185,0.0,1739137676.4495978,18.189982652664185,0.15570562132003785,1739137676.4495997,18.189982652664185,6.277508620654394,1739137676.4496017,18.189982652664185,2.3207019927314136 +1739137676.4693863,18.2099826335907,39.13940722950316,1739137676.469389,18.2099826335907,0.06369171599507606,1739137676.4693923,18.2099826335907,38.478440935940775,1739137676.4693956,18.2099826335907,47.47985029349055,1739137676.4693975,18.2099826335907,0.0042079923434805155,1739137676.4693997,18.2099826335907,-0.007131841160212926,1739137676.4694016,18.2099826335907,-0.004598498983770666,1739137676.4694035,18.2099826335907,-0.0010153293961191279,1739137676.4694052,18.2099826335907,2.4954057276629156,1739137676.469407,18.2099826335907,0.0,1739137676.4694085,18.2099826335907,0.1586336215889711,1739137676.4694104,18.2099826335907,6.276604801510169,1739137676.469412,18.2099826335907,2.3381663926128007 +1739137676.4893632,18.229982614517212,39.13940722950316,1739137676.4893663,18.229982614517212,0.06369171599507606,1739137676.4893699,18.229982614517212,38.478440935940775,1739137676.4893734,18.229982614517212,47.47985029349055,1739137676.4893749,18.229982614517212,0.0042079923434805155,1739137676.4893773,18.229982614517212,-0.007131841160212926,1739137676.4893792,18.229982614517212,-0.004598498983770666,1739137676.4893806,18.229982614517212,-0.0010153293961191279,1739137676.4893825,18.229982614517212,2.4954057276629156,1739137676.4893844,18.229982614517212,0.0,1739137676.489386,18.229982614517212,0.1572393350501149,1739137676.4893878,18.229982614517212,6.276604801510169,1739137676.4893894,18.229982614517212,2.3381663926128007 +1739137676.5097032,18.249982595443726,39.13940722950316,1739137676.509707,18.249982595443726,0.06369171599507606,1739137676.5097115,18.249982595443726,38.478440935940775,1739137676.5097163,18.249982595443726,47.47985029349055,1739137676.5097182,18.249982595443726,0.0042079923434805155,1739137676.509721,18.249982595443726,-0.007131841160212926,1739137676.5097234,18.249982595443726,-0.004598498983770666,1739137676.5097258,18.249982595443726,-0.0010153293961191279,1739137676.5097277,18.249982595443726,2.4954057276629156,1739137676.50973,18.249982595443726,0.0,1739137676.5097322,18.249982595443726,0.1572393350501149,1739137676.5097346,18.249982595443726,6.276604801510169,1739137676.5097368,18.249982595443726,2.3381663926128007 +1739137676.5309215,18.26998257637024,39.13940722950316,1739137676.5309262,18.26998257637024,0.06369171599507606,1739137676.5309315,18.26998257637024,38.478440935940775,1739137676.530936,18.26998257637024,47.47985029349055,1739137676.5309381,18.26998257637024,0.0042079923434805155,1739137676.530941,18.26998257637024,-0.007131841160212926,1739137676.5309436,18.26998257637024,-0.004598498983770666,1739137676.530946,18.26998257637024,-0.0010153293961191279,1739137676.5309484,18.26998257637024,2.4954057276629156,1739137676.5309513,18.26998257637024,0.0,1739137676.5309532,18.26998257637024,0.1572393350501149,1739137676.5309558,18.26998257637024,6.276604801510169,1739137676.5309582,18.26998257637024,2.3381663926128007 +1739137676.5498824,18.289982557296753,39.13940722950316,1739137676.549886,18.289982557296753,0.06369171599507606,1739137676.5498908,18.289982557296753,38.478440935940775,1739137676.5498958,18.289982557296753,47.47985029349055,1739137676.5498977,18.289982557296753,0.0042079923434805155,1739137676.5499008,18.289982557296753,-0.007131841160212926,1739137676.5499032,18.289982557296753,-0.004598498983770666,1739137676.5499053,18.289982557296753,-0.0010153293961191279,1739137676.5499074,18.289982557296753,2.4954057276629156,1739137676.54991,18.289982557296753,0.0,1739137676.549912,18.289982557296753,0.1572393350501149,1739137676.5499144,18.289982557296753,6.276604801510169,1739137676.5499167,18.289982557296753,2.3381663926128007 +1739137676.5699024,18.309982538223267,39.13940722950316,1739137676.5699062,18.309982538223267,0.06369171599507606,1739137676.5699108,18.309982538223267,38.478440935940775,1739137676.569915,18.309982538223267,47.47985029349055,1739137676.5699172,18.309982538223267,0.0042079923434805155,1739137676.5699198,18.309982538223267,-0.007131841160212926,1739137676.569922,18.309982538223267,-0.004598498983770666,1739137676.569924,18.309982538223267,-0.0010153293961191279,1739137676.5699263,18.309982538223267,2.4954057276629156,1739137676.5699286,18.309982538223267,0.0,1739137676.5699308,18.309982538223267,0.1572393350501149,1739137676.5699337,18.309982538223267,6.276604801510169,1739137676.5699358,18.309982538223267,2.3381663926128007 +1739137676.5905077,18.32998251914978,39.397464163034236,1739137676.5905116,18.32998251914978,0.06188738309991404,1739137676.5905163,18.32998251914978,38.532839246300085,1739137676.5905206,18.32998251914978,47.58482124709604,1739137676.5905225,18.32998251914978,0.019769347940857804,1739137676.5905254,18.32998251914978,-0.0051442319177075245,1739137676.5905278,18.32998251914978,0.019159412171203764,1739137676.5905297,18.32998251914978,0.004390097128937851,1739137676.5905318,18.32998251914978,2.480913817253304,1739137676.5905344,18.32998251914978,0.0,1739137676.5905364,18.32998251914978,0.09665939942765073,1739137676.5905392,18.32998251914978,6.2757009823659455,1739137676.5905414,18.32998251914978,2.3554068150233656 +1739137676.6099815,18.349982500076294,39.397464163034236,1739137676.6099856,18.349982500076294,0.06188738309991404,1739137676.6099904,18.349982500076294,38.532839246300085,1739137676.6099951,18.349982500076294,47.58482124709604,1739137676.6099973,18.349982500076294,0.019769347940857804,1739137676.6100001,18.349982500076294,-0.0051442319177075245,1739137676.6100028,18.349982500076294,0.019159412171203764,1739137676.610005,18.349982500076294,0.004390097128937851,1739137676.610007,18.349982500076294,2.480913817253304,1739137676.6100097,18.349982500076294,0.0,1739137676.6100116,18.349982500076294,0.12550700222993827,1739137676.6100142,18.349982500076294,6.2757009823659455,1739137676.6100163,18.349982500076294,2.3554068150233656 +1739137676.630358,18.369982481002808,39.397464163034236,1739137676.6303618,18.369982481002808,0.06188738309991404,1739137676.6303668,18.369982481002808,38.532839246300085,1739137676.6303709,18.369982481002808,47.58482124709604,1739137676.630373,18.369982481002808,0.019769347940857804,1739137676.6303759,18.369982481002808,-0.0051442319177075245,1739137676.6303782,18.369982481002808,0.019159412171203764,1739137676.6303804,18.369982481002808,0.004390097128937851,1739137676.6303823,18.369982481002808,2.480913817253304,1739137676.6303847,18.369982481002808,0.0,1739137676.6303866,18.369982481002808,0.12550700222993827,1739137676.630389,18.369982481002808,6.2757009823659455,1739137676.6303911,18.369982481002808,2.3554068150233656 +1739137676.6536376,18.38998246192932,39.397464163034236,1739137676.6536427,18.38998246192932,0.06188738309991404,1739137676.6536484,18.38998246192932,38.532839246300085,1739137676.6536543,18.38998246192932,47.58482124709604,1739137676.6536567,18.38998246192932,0.019769347940857804,1739137676.65366,18.38998246192932,-0.0051442319177075245,1739137676.6536627,18.38998246192932,0.019159412171203764,1739137676.6536653,18.38998246192932,0.004390097128937851,1739137676.6536677,18.38998246192932,2.480913817253304,1739137676.6536703,18.38998246192932,0.0,1739137676.653673,18.38998246192932,0.12550700222993827,1739137676.6536758,18.38998246192932,6.2757009823659455,1739137676.6536784,18.38998246192932,2.3554068150233656 +1739137676.6709447,18.409982442855835,39.397464163034236,1739137676.670949,18.409982442855835,0.06188738309991404,1739137676.6709542,18.409982442855835,38.532839246300085,1739137676.670959,18.409982442855835,47.58482124709604,1739137676.6709616,18.409982442855835,0.019769347940857804,1739137676.6709647,18.409982442855835,-0.0051442319177075245,1739137676.6709673,18.409982442855835,0.019159412171203764,1739137676.67097,18.409982442855835,0.004390097128937851,1739137676.670972,18.409982442855835,2.480913817253304,1739137676.6709752,18.409982442855835,0.0,1739137676.6709776,18.409982442855835,0.12550700222993827,1739137676.6709805,18.409982442855835,6.2757009823659455,1739137676.6709828,18.409982442855835,2.3554068150233656 +1739137676.6913338,18.42998242378235,39.65722015541133,1739137676.6913385,18.42998242378235,0.059836418305550865,1739137676.6913438,18.42998242378235,39.1921047028425,1739137676.691349,18.42998242378235,48.27244386604969,1739137676.691352,18.42998242378235,0.14819870864203974,1739137676.691355,18.42998242378235,0.010256169199468515,1739137676.6913576,18.42998242378235,0.16062407099623655,1739137676.6913602,18.42998242378235,0.0332357339729802,1739137676.6913626,18.42998242378235,2.3444271901701623,1739137676.6913657,18.42998242378235,0.0,1739137676.6913679,18.42998242378235,-0.16076321962895287,1739137676.691371,18.42998242378235,6.274797163221722,1739137676.6913733,18.42998242378235,2.3688711884355698 +1739137676.710929,18.449982404708862,39.65722015541133,1739137676.710934,18.449982404708862,0.059836418305550865,1739137676.7109396,18.449982404708862,39.1921047028425,1739137676.7109447,18.449982404708862,48.27244386604969,1739137676.7109473,18.449982404708862,0.14819870864203974,1739137676.7109506,18.449982404708862,0.010256169199468515,1739137676.7109532,18.449982404708862,0.16062407099623655,1739137676.7109559,18.449982404708862,0.0332357339729802,1739137676.710958,18.449982404708862,2.3444271901701623,1739137676.7109609,18.449982404708862,0.0,1739137676.7109637,18.449982404708862,-0.02444399826540744,1739137676.7109666,18.449982404708862,6.274797163221722,1739137676.710969,18.449982404708862,2.3688711884355698 +1739137676.7304628,18.469982385635376,39.65722015541133,1739137676.7304773,18.469982385635376,0.059836418305550865,1739137676.7304847,18.469982385635376,39.1921047028425,1739137676.7304885,18.469982385635376,48.27244386604969,1739137676.7304904,18.469982385635376,0.14819870864203974,1739137676.7304924,18.469982385635376,0.010256169199468515,1739137676.730494,18.469982385635376,0.16062407099623655,1739137676.7304957,18.469982385635376,0.0332357339729802,1739137676.7304976,18.469982385635376,2.3444271901701623,1739137676.7304995,18.469982385635376,0.0,1739137676.7305014,18.469982385635376,-0.02444399826540744,1739137676.730503,18.469982385635376,6.274797163221722,1739137676.7305052,18.469982385635376,2.3688711884355698 +1739137676.7494752,18.48998236656189,39.65722015541133,1739137676.7494776,18.48998236656189,0.059836418305550865,1739137676.7494807,18.48998236656189,39.1921047028425,1739137676.749483,18.48998236656189,48.27244386604969,1739137676.7494843,18.48998236656189,0.14819870864203974,1739137676.7494857,18.48998236656189,0.010256169199468515,1739137676.7494874,18.48998236656189,0.16062407099623655,1739137676.7494884,18.48998236656189,0.0332357339729802,1739137676.7494895,18.48998236656189,2.3444271901701623,1739137676.749491,18.48998236656189,0.0,1739137676.749492,18.48998236656189,-0.02444399826540744,1739137676.7494936,18.48998236656189,6.274797163221722,1739137676.7494946,18.48998236656189,2.3688711884355698 +1739137676.7702782,18.509982347488403,39.65722015541133,1739137676.7702823,18.509982347488403,0.059836418305550865,1739137676.7702868,18.509982347488403,39.1921047028425,1739137676.7702923,18.509982347488403,48.27244386604969,1739137676.7702942,18.509982347488403,0.14819870864203974,1739137676.7702966,18.509982347488403,0.010256169199468515,1739137676.7702985,18.509982347488403,0.16062407099623655,1739137676.7703004,18.509982347488403,0.0332357339729802,1739137676.770302,18.509982347488403,2.3444271901701623,1739137676.7703042,18.509982347488403,0.0,1739137676.7703063,18.509982347488403,-0.02444399826540744,1739137676.7703083,18.509982347488403,6.274797163221722,1739137676.7703104,18.509982347488403,2.3688711884355698 +1739137676.7890584,18.529982328414917,39.65722015541133,1739137676.7890608,18.529982328414917,0.059836418305550865,1739137676.7890635,18.529982328414917,39.1921047028425,1739137676.7890654,18.529982328414917,48.27244386604969,1739137676.7890668,18.529982328414917,0.14819870864203974,1739137676.789068,18.529982328414917,0.010256169199468515,1739137676.7890694,18.529982328414917,0.16062407099623655,1739137676.7890706,18.529982328414917,0.0332357339729802,1739137676.7890718,18.529982328414917,2.3444271901701623,1739137676.7890732,18.529982328414917,0.0,1739137676.7890742,18.529982328414917,-0.02444399826540744,1739137676.7890754,18.529982328414917,6.274797163221722,1739137676.7890768,18.529982328414917,2.3688711884355698 +1739137676.8089116,18.54998230934143,39.91739417496299,1739137676.8089137,18.54998230934143,0.057575517611736515,1739137676.8089163,18.54998230934143,39.74712184220335,1739137676.8089187,18.54998230934143,48.79104871175898,1739137676.8089201,18.54998230934143,0.29371250158438794,1739137676.8089216,18.54998230934143,0.026604739549093485,1739137676.8089228,18.54998230934143,0.31520251721783976,1739137676.808924,18.54998230934143,0.06143384688784327,1739137676.808925,18.54998230934143,2.2038585820039414,1739137676.8089268,18.54998230934143,0.0,1739137676.808928,18.54998230934143,-0.2825370517733505,1739137676.8089292,18.54998230934143,6.274273989362517,1739137676.8089306,18.54998230934143,2.363494118331214 +1739137676.8290763,18.569982290267944,39.91739417496299,1739137676.8290782,18.569982290267944,0.057575517611736515,1739137676.8290806,18.569982290267944,39.74712184220335,1739137676.8290832,18.569982290267944,48.79104871175898,1739137676.8290842,18.569982290267944,0.29371250158438794,1739137676.8290856,18.569982290267944,0.026604739549093485,1739137676.829087,18.569982290267944,0.31520251721783976,1739137676.8290882,18.569982290267944,0.06143384688784327,1739137676.8290892,18.569982290267944,2.2038585820039414,1739137676.8290906,18.569982290267944,0.0,1739137676.8290915,18.569982290267944,-0.15963553632727256,1739137676.8290932,18.569982290267944,6.274273989362517,1739137676.8290942,18.569982290267944,2.363494118331214 +1739137676.849109,18.589982271194458,39.91739417496299,1739137676.849111,18.589982271194458,0.057575517611736515,1739137676.8491132,18.589982271194458,39.74712184220335,1739137676.8491158,18.589982271194458,48.79104871175898,1739137676.8491173,18.589982271194458,0.29371250158438794,1739137676.8491187,18.589982271194458,0.026604739549093485,1739137676.84912,18.589982271194458,0.31520251721783976,1739137676.849121,18.589982271194458,0.06143384688784327,1739137676.8491223,18.589982271194458,2.2038585820039414,1739137676.849124,18.589982271194458,0.0,1739137676.849125,18.589982271194458,-0.15963553632727256,1739137676.849126,18.589982271194458,6.274273989362517,1739137676.8491275,18.589982271194458,2.363494118331214 +1739137676.868954,18.60998225212097,39.91739417496299,1739137676.868956,18.60998225212097,0.057575517611736515,1739137676.868959,18.60998225212097,39.74712184220335,1739137676.8689613,18.60998225212097,48.79104871175898,1739137676.8689625,18.60998225212097,0.29371250158438794,1739137676.8689644,18.60998225212097,0.026604739549093485,1739137676.8689656,18.60998225212097,0.31520251721783976,1739137676.8689668,18.60998225212097,0.06143384688784327,1739137676.868968,18.60998225212097,2.2038585820039414,1739137676.8689694,18.60998225212097,0.0,1739137676.8689704,18.60998225212097,-0.15963553632727256,1739137676.868972,18.60998225212097,6.274273989362517,1739137676.868973,18.60998225212097,2.363494118331214 +1739137676.8890543,18.629982233047485,39.91739417496299,1739137676.8890564,18.629982233047485,0.057575517611736515,1739137676.8890593,18.629982233047485,39.74712184220335,1739137676.889062,18.629982233047485,48.79104871175898,1739137676.8890634,18.629982233047485,0.29371250158438794,1739137676.8890653,18.629982233047485,0.026604739549093485,1739137676.8890665,18.629982233047485,0.31520251721783976,1739137676.8890681,18.629982233047485,0.06143384688784327,1739137676.8890693,18.629982233047485,2.2038585820039414,1739137676.8890707,18.629982233047485,0.0,1739137676.8890722,18.629982233047485,-0.15963553632727256,1739137676.8890736,18.629982233047485,6.274273989362517,1739137676.889075,18.629982233047485,2.363494118331214 +1739137676.9090652,18.649982213974,40.1762646954286,1739137676.9090676,18.649982213974,0.05525903163754542,1739137676.9090705,18.649982213974,39.753334734694526,1739137676.909073,18.649982213974,48.73881389165743,1739137676.9090748,18.649982213974,0.27669216694455584,1739137676.9090762,18.649982213974,0.025854892878311,1739137676.9090776,18.649982213974,0.2970836280006951,1739137676.9090793,18.649982213974,0.062188662109820186,1739137676.9090805,18.649982213974,2.21988919099866,1739137676.9090824,18.649982213974,0.0,1739137676.9090834,18.649982213974,-0.09011750102103011,1739137676.909085,18.649982213974,6.27434913935433,1739137676.9090862,18.649982213974,2.3431105348928116 +1739137676.93348,18.669982194900513,40.1762646954286,1739137676.9334903,18.669982194900513,0.05525903163754542,1739137676.9335074,18.669982194900513,39.753334734694526,1739137676.9335341,18.669982194900513,48.73881389165743,1739137676.9335425,18.669982194900513,0.27669216694455584,1739137676.9335546,18.669982194900513,0.025854892878311,1739137676.933562,18.669982194900513,0.2970836280006951,1739137676.9335694,18.669982194900513,0.062188662109820186,1739137676.933582,18.669982194900513,2.21988919099866,1739137676.9335992,18.669982194900513,0.0,1739137676.9336123,18.669982194900513,-0.12322134389415185,1739137676.9336197,18.669982194900513,6.27434913935433,1739137676.9336245,18.669982194900513,2.3431105348928116 +1739137676.9593072,18.689982175827026,40.1762646954286,1739137676.9593172,18.689982175827026,0.05525903163754542,1739137676.959328,18.689982175827026,39.753334734694526,1739137676.9593413,18.689982175827026,48.73881389165743,1739137676.9593515,18.689982175827026,0.27669216694455584,1739137676.9593644,18.689982175827026,0.025854892878311,1739137676.9593759,18.689982175827026,0.2970836280006951,1739137676.9593873,18.689982175827026,0.062188662109820186,1739137676.959399,18.689982175827026,2.21988919099866,1739137676.9594102,18.689982175827026,0.0,1739137676.9594166,18.689982175827026,-0.12322134389415185,1739137676.9594233,18.689982175827026,6.27434913935433,1739137676.9594297,18.689982175827026,2.3431105348928116 +1739137676.9708652,18.70998215675354,40.1762646954286,1739137676.9708693,18.70998215675354,0.05525903163754542,1739137676.9708738,18.70998215675354,39.753334734694526,1739137676.970878,18.70998215675354,48.73881389165743,1739137676.9708803,18.70998215675354,0.27669216694455584,1739137676.9708827,18.70998215675354,0.025854892878311,1739137676.9708848,18.70998215675354,0.2970836280006951,1739137676.970887,18.70998215675354,0.062188662109820186,1739137676.9708889,18.70998215675354,2.21988919099866,1739137676.9708912,18.70998215675354,0.0,1739137676.9708936,18.70998215675354,-0.12322134389415185,1739137676.9708962,18.70998215675354,6.27434913935433,1739137676.9708982,18.70998215675354,2.3431105348928116 +1739137676.990085,18.729982137680054,40.1762646954286,1739137676.9900882,18.729982137680054,0.05525903163754542,1739137676.9900913,18.729982137680054,39.753334734694526,1739137676.9900944,18.729982137680054,48.73881389165743,1739137676.990096,18.729982137680054,0.27669216694455584,1739137676.990098,18.729982137680054,0.025854892878311,1739137676.9900994,18.729982137680054,0.2970836280006951,1739137676.9901013,18.729982137680054,0.062188662109820186,1739137676.9901028,18.729982137680054,2.21988919099866,1739137676.9901047,18.729982137680054,0.0,1739137676.9901059,18.729982137680054,-0.12322134389415185,1739137676.9901075,18.729982137680054,6.27434913935433,1739137676.9901092,18.729982137680054,2.3431105348928116 +1739137677.0090659,18.749982118606567,40.1762646954286,1739137677.0090685,18.749982118606567,0.05525903163754542,1739137677.0090714,18.749982118606567,39.753334734694526,1739137677.009074,18.749982118606567,48.73881389165743,1739137677.0090752,18.749982118606567,0.27669216694455584,1739137677.0090768,18.749982118606567,0.025854892878311,1739137677.009078,18.749982118606567,0.2970836280006951,1739137677.0090792,18.749982118606567,0.062188662109820186,1739137677.0090806,18.749982118606567,2.21988919099866,1739137677.0090818,18.749982118606567,0.0,1739137677.009083,18.749982118606567,-0.12322134389415185,1739137677.0090845,18.749982118606567,6.27434913935433,1739137677.0090857,18.749982118606567,2.3431105348928116 +1739137677.0292516,18.76998209953308,40.4334108695864,1739137677.029254,18.76998209953308,0.053077247984103515,1739137677.029257,18.76998209953308,39.75950624287431,1739137677.0292597,18.76998209953308,48.70901413036929,1739137677.0292614,18.76998209953308,0.26698213236752016,1739137677.029263,18.76998209953308,0.02584189454792605,1739137677.0292647,18.76998209953308,0.27993269080579397,1739137677.0292664,18.76998209953308,0.06273243539755369,1739137677.0292678,18.76998209953308,2.2351708219595556,1739137677.0292695,18.76998209953308,0.0,1739137677.0292711,18.76998209953308,-0.07017517036285023,1739137677.0292726,18.76998209953308,6.2752057901549785,1739137677.0292745,18.76998209953308,2.33060608757488 +1739137677.0490232,18.789982080459595,40.4334108695864,1739137677.0490255,18.789982080459595,0.053077247984103515,1739137677.0490284,18.789982080459595,39.75950624287431,1739137677.0490305,18.789982080459595,48.70901413036929,1739137677.0490322,18.789982080459595,0.26698213236752016,1739137677.0490336,18.789982080459595,0.02584189454792605,1739137677.0490353,18.789982080459595,0.27993269080579397,1739137677.0490363,18.789982080459595,0.06273243539755369,1739137677.0490375,18.789982080459595,2.2351708219595556,1739137677.049039,18.789982080459595,0.0,1739137677.04904,18.789982080459595,-0.09543526561532456,1739137677.0490415,18.789982080459595,6.2752057901549785,1739137677.0490427,18.789982080459595,2.33060608757488 +1739137677.0690286,18.80998206138611,40.4334108695864,1739137677.069031,18.80998206138611,0.053077247984103515,1739137677.0690336,18.80998206138611,39.75950624287431,1739137677.0690365,18.80998206138611,48.70901413036929,1739137677.0690382,18.80998206138611,0.26698213236752016,1739137677.0690398,18.80998206138611,0.02584189454792605,1739137677.0690415,18.80998206138611,0.27993269080579397,1739137677.069043,18.80998206138611,0.06273243539755369,1739137677.0690446,18.80998206138611,2.2351708219595556,1739137677.0690463,18.80998206138611,0.0,1739137677.0690477,18.80998206138611,-0.09543526561532456,1739137677.0690496,18.80998206138611,6.2752057901549785,1739137677.0690508,18.80998206138611,2.33060608757488 +1739137677.089111,18.829982042312622,40.4334108695864,1739137677.0891132,18.829982042312622,0.053077247984103515,1739137677.089116,18.829982042312622,39.75950624287431,1739137677.0891187,18.829982042312622,48.70901413036929,1739137677.0891206,18.829982042312622,0.26698213236752016,1739137677.0891223,18.829982042312622,0.02584189454792605,1739137677.0891237,18.829982042312622,0.27993269080579397,1739137677.0891254,18.829982042312622,0.06273243539755369,1739137677.0891266,18.829982042312622,2.2351708219595556,1739137677.0891283,18.829982042312622,0.0,1739137677.0891297,18.829982042312622,-0.09543526561532456,1739137677.0891314,18.829982042312622,6.2752057901549785,1739137677.0891325,18.829982042312622,2.33060608757488 +1739137677.1090798,18.849982023239136,40.4334108695864,1739137677.1090822,18.849982023239136,0.053077247984103515,1739137677.1090848,18.849982023239136,39.75950624287431,1739137677.109088,18.849982023239136,48.70901413036929,1739137677.1090896,18.849982023239136,0.26698213236752016,1739137677.1090915,18.849982023239136,0.02584189454792605,1739137677.1090932,18.849982023239136,0.27993269080579397,1739137677.1090946,18.849982023239136,0.06273243539755369,1739137677.1090963,18.849982023239136,2.2351708219595556,1739137677.1090982,18.849982023239136,0.0,1739137677.1090999,18.849982023239136,-0.09543526561532456,1739137677.1091013,18.849982023239136,6.2752057901549785,1739137677.109103,18.849982023239136,2.33060608757488 +1739137677.1290905,18.86998200416565,40.689263251149995,1739137677.129093,18.86998200416565,0.051154392256023584,1739137677.1290958,18.86998200416565,39.76564670003184,1739137677.1290984,18.86998200416565,48.685624799967805,1739137677.1291,18.86998200416565,0.25973070768240103,1739137677.1291015,18.86998200416565,0.02607798939972894,1739137677.1291032,18.86998200416565,0.26409850039204125,1739137677.1291044,18.86998200416565,0.06338876459876482,1739137677.1291056,18.86998200416565,2.2493725973677727,1739137677.1291075,18.86998200416565,0.0,1739137677.1291087,18.86998200416565,-0.04883192541985602,1739137677.1291103,18.86998200416565,6.276241191443693,1739137677.1291118,18.86998200416565,2.320396600633288 +1739137677.1491904,18.889981985092163,40.689263251149995,1739137677.149193,18.889981985092163,0.051154392256023584,1739137677.1491961,18.889981985092163,39.76564670003184,1739137677.149199,18.889981985092163,48.685624799967805,1739137677.1492007,18.889981985092163,0.25973070768240103,1739137677.1492026,18.889981985092163,0.02607798939972894,1739137677.1492047,18.889981985092163,0.26409850039204125,1739137677.1492062,18.889981985092163,0.06338876459876482,1739137677.1492078,18.889981985092163,2.2493725973677727,1739137677.1492095,18.889981985092163,0.0,1739137677.149211,18.889981985092163,-0.07102400326551539,1739137677.1492126,18.889981985092163,6.276241191443693,1739137677.1492143,18.889981985092163,2.320396600633288 +1739137677.169099,18.909981966018677,40.689263251149995,1739137677.1691015,18.909981966018677,0.051154392256023584,1739137677.1691046,18.909981966018677,39.76564670003184,1739137677.1691074,18.909981966018677,48.685624799967805,1739137677.169109,18.909981966018677,0.25973070768240103,1739137677.1691108,18.909981966018677,0.02607798939972894,1739137677.1691122,18.909981966018677,0.26409850039204125,1739137677.1691136,18.909981966018677,0.06338876459876482,1739137677.1691148,18.909981966018677,2.2493725973677727,1739137677.1691167,18.909981966018677,0.0,1739137677.169118,18.909981966018677,-0.07102400326551539,1739137677.1691198,18.909981966018677,6.276241191443693,1739137677.1691213,18.909981966018677,2.320396600633288 +1739137677.1894255,18.92998194694519,40.689263251149995,1739137677.1894286,18.92998194694519,0.051154392256023584,1739137677.1894321,18.92998194694519,39.76564670003184,1739137677.1894355,18.92998194694519,48.685624799967805,1739137677.189437,18.92998194694519,0.25973070768240103,1739137677.189439,18.92998194694519,0.02607798939972894,1739137677.189441,18.92998194694519,0.26409850039204125,1739137677.1894429,18.92998194694519,0.06338876459876482,1739137677.1894443,18.92998194694519,2.2493725973677727,1739137677.1894464,18.92998194694519,0.0,1739137677.1894479,18.92998194694519,-0.07102400326551539,1739137677.1894503,18.92998194694519,6.276241191443693,1739137677.189452,18.92998194694519,2.320396600633288 +1739137677.2094722,18.949981927871704,40.689263251149995,1739137677.2094753,18.949981927871704,0.051154392256023584,1739137677.209479,18.949981927871704,39.76564670003184,1739137677.209483,18.949981927871704,48.685624799967805,1739137677.209485,18.949981927871704,0.25973070768240103,1739137677.2094874,18.949981927871704,0.02607798939972894,1739137677.2094893,18.949981927871704,0.26409850039204125,1739137677.2094915,18.949981927871704,0.06338876459876482,1739137677.2094932,18.949981927871704,2.2493725973677727,1739137677.209495,18.949981927871704,0.0,1739137677.2094967,18.949981927871704,-0.07102400326551539,1739137677.209499,18.949981927871704,6.276241191443693,1739137677.209501,18.949981927871704,2.320396600633288 +1739137677.2293544,18.969981908798218,40.689263251149995,1739137677.2293575,18.969981908798218,0.051154392256023584,1739137677.229361,18.969981908798218,39.76564670003184,1739137677.2293644,18.969981908798218,48.685624799967805,1739137677.2293663,18.969981908798218,0.25973070768240103,1739137677.2293682,18.969981908798218,0.02607798939972894,1739137677.22937,18.969981908798218,0.26409850039204125,1739137677.2293715,18.969981908798218,0.06338876459876482,1739137677.2293732,18.969981908798218,2.2493725973677727,1739137677.2293751,18.969981908798218,0.0,1739137677.2293766,18.969981908798218,-0.07102400326551539,1739137677.2293782,18.969981908798218,6.276241191443693,1739137677.2293801,18.969981908798218,2.320396600633288 +1739137677.2492733,18.98998188972473,40.944154022855066,1739137677.2492762,18.98998188972473,0.04950599429888314,1739137677.2492795,18.98998188972473,40.23816776948314,1739137677.2492826,18.98998188972473,49.10860582454057,1739137677.2492843,18.98998188972473,0.4142382550318799,1739137677.2492862,18.98998188972473,0.04464352637292853,1739137677.2492878,18.98998188972473,0.41284540654572277,1739137677.2492895,18.98998188972473,0.0949104058392852,1739137677.2492907,18.98998188972473,2.119441412415096,1739137677.2492926,18.98998188972473,0.0,1739137677.249294,18.98998188972473,-0.30507077630368484,1739137677.249296,18.98998188972473,6.277291493312798,1739137677.2492974,18.98998188972473,2.313061288740297 +1739137677.2695653,19.009981870651245,40.944154022855066,1739137677.2695687,19.009981870651245,0.04950599429888314,1739137677.2695723,19.009981870651245,40.23816776948314,1739137677.2695758,19.009981870651245,49.10860582454057,1739137677.2695777,19.009981870651245,0.4142382550318799,1739137677.2695801,19.009981870651245,0.04464352637292853,1739137677.2695823,19.009981870651245,0.41284540654572277,1739137677.2695842,19.009981870651245,0.0949104058392852,1739137677.2695858,19.009981870651245,2.119441412415096,1739137677.269588,19.009981870651245,0.0,1739137677.2695897,19.009981870651245,-0.19361987632520083,1739137677.2695918,19.009981870651245,6.277291493312798,1739137677.2695932,19.009981870651245,2.313061288740297 +1739137677.2895062,19.02998185157776,40.944154022855066,1739137677.2895093,19.02998185157776,0.04950599429888314,1739137677.2895129,19.02998185157776,40.23816776948314,1739137677.289516,19.02998185157776,49.10860582454057,1739137677.2895179,19.02998185157776,0.4142382550318799,1739137677.2895198,19.02998185157776,0.04464352637292853,1739137677.2895217,19.02998185157776,0.41284540654572277,1739137677.2895231,19.02998185157776,0.0949104058392852,1739137677.2895248,19.02998185157776,2.119441412415096,1739137677.2895267,19.02998185157776,0.0,1739137677.2895284,19.02998185157776,-0.19361987632520083,1739137677.28953,19.02998185157776,6.277291493312798,1739137677.2895317,19.02998185157776,2.313061288740297 +1739137677.309374,19.049981832504272,40.944154022855066,1739137677.309377,19.049981832504272,0.04950599429888314,1739137677.3093805,19.049981832504272,40.23816776948314,1739137677.3093843,19.049981832504272,49.10860582454057,1739137677.3093863,19.049981832504272,0.4142382550318799,1739137677.3093889,19.049981832504272,0.04464352637292853,1739137677.3093908,19.049981832504272,0.41284540654572277,1739137677.309393,19.049981832504272,0.0949104058392852,1739137677.3093946,19.049981832504272,2.119441412415096,1739137677.3093967,19.049981832504272,0.0,1739137677.309399,19.049981832504272,-0.19361987632520083,1739137677.3094008,19.049981832504272,6.277291493312798,1739137677.3094027,19.049981832504272,2.313061288740297 +1739137677.329348,19.069981813430786,40.944154022855066,1739137677.329351,19.069981813430786,0.04950599429888314,1739137677.3293543,19.069981813430786,40.23816776948314,1739137677.3293576,19.069981813430786,49.10860582454057,1739137677.3293593,19.069981813430786,0.4142382550318799,1739137677.3293614,19.069981813430786,0.04464352637292853,1739137677.329363,19.069981813430786,0.41284540654572277,1739137677.3293648,19.069981813430786,0.0949104058392852,1739137677.3293662,19.069981813430786,2.119441412415096,1739137677.329368,19.069981813430786,0.0,1739137677.3293695,19.069981813430786,-0.19361987632520083,1739137677.3293715,19.069981813430786,6.277291493312798,1739137677.329373,19.069981813430786,2.313061288740297 +1739137677.3494976,19.0899817943573,41.197350736431034,1739137677.3495007,19.0899817943573,0.04815525560023559,1739137677.3495042,19.0899817943573,40.51243215030324,1739137677.3495078,19.0899817943573,49.295569515725255,1739137677.3495097,19.0899817943573,0.4955496595345645,1739137677.349512,19.0899817943573,0.055189922648434295,1739137677.3495142,19.0899817943573,0.48384466679328836,1739137677.3495164,19.0899817943573,0.1129248384367332,1739137677.349518,19.0899817943573,2.0600965799159505,1739137677.3495202,19.0899817943573,0.0,1739137677.3495219,19.0899817943573,-0.26213294545450105,1739137677.3495243,19.0899817943573,6.2786837099701325,1739137677.349526,19.0899817943573,2.2896042380587427 +1739137677.3694134,19.109981775283813,41.197350736431034,1739137677.3694167,19.109981775283813,0.04815525560023559,1739137677.3694205,19.109981775283813,40.51243215030324,1739137677.3694243,19.109981775283813,49.295569515725255,1739137677.3694265,19.109981775283813,0.4955496595345645,1739137677.3694286,19.109981775283813,0.055189922648434295,1739137677.369431,19.109981775283813,0.48384466679328836,1739137677.369433,19.109981775283813,0.1129248384367332,1739137677.3694348,19.109981775283813,2.0600965799159505,1739137677.3694367,19.109981775283813,0.0,1739137677.3694386,19.109981775283813,-0.22950765814279217,1739137677.3694408,19.109981775283813,6.2786837099701325,1739137677.3694425,19.109981775283813,2.2896042380587427 +1739137677.390158,19.129981756210327,41.197350736431034,1739137677.3901622,19.129981756210327,0.04815525560023559,1739137677.390167,19.129981756210327,40.51243215030324,1739137677.3901725,19.129981756210327,49.295569515725255,1739137677.3901746,19.129981756210327,0.4955496595345645,1739137677.3901777,19.129981756210327,0.055189922648434295,1739137677.3901803,19.129981756210327,0.48384466679328836,1739137677.3901827,19.129981756210327,0.1129248384367332,1739137677.3901849,19.129981756210327,2.0600965799159505,1739137677.390188,19.129981756210327,0.0,1739137677.3901904,19.129981756210327,-0.22950765814279217,1739137677.390193,19.129981756210327,6.2786837099701325,1739137677.3901951,19.129981756210327,2.2896042380587427 +1739137677.4113011,19.14998173713684,41.197350736431034,1739137677.4113061,19.14998173713684,0.04815525560023559,1739137677.4113126,19.14998173713684,40.51243215030324,1739137677.4113185,19.14998173713684,49.295569515725255,1739137677.4113214,19.14998173713684,0.4955496595345645,1739137677.411325,19.14998173713684,0.055189922648434295,1739137677.411328,19.14998173713684,0.48384466679328836,1739137677.4113307,19.14998173713684,0.1129248384367332,1739137677.4113336,19.14998173713684,2.0600965799159505,1739137677.411337,19.14998173713684,0.0,1739137677.4113398,19.14998173713684,-0.22950765814279217,1739137677.4113429,19.14998173713684,6.2786837099701325,1739137677.4113457,19.14998173713684,2.2896042380587427 +1739137677.4311185,19.169981718063354,41.197350736431034,1739137677.4311237,19.169981718063354,0.04815525560023559,1739137677.4311295,19.169981718063354,40.51243215030324,1739137677.4311366,19.169981718063354,49.295569515725255,1739137677.4311452,19.169981718063354,0.4955496595345645,1739137677.4311557,19.169981718063354,0.055189922648434295,1739137677.4311645,19.169981718063354,0.48384466679328836,1739137677.4311728,19.169981718063354,0.1129248384367332,1739137677.4311767,19.169981718063354,2.0600965799159505,1739137677.4311802,19.169981718063354,0.0,1739137677.4311829,19.169981718063354,-0.22950765814279217,1739137677.4311862,19.169981718063354,6.2786837099701325,1739137677.4311888,19.169981718063354,2.2896042380587427 +1739137677.4513159,19.189981698989868,41.197350736431034,1739137677.451322,19.189981698989868,0.04815525560023559,1739137677.4513283,19.189981698989868,40.51243215030324,1739137677.451334,19.189981698989868,49.295569515725255,1739137677.4513366,19.189981698989868,0.4955496595345645,1739137677.4513402,19.189981698989868,0.055189922648434295,1739137677.451343,19.189981698989868,0.48384466679328836,1739137677.451346,19.189981698989868,0.1129248384367332,1739137677.4513488,19.189981698989868,2.0600965799159505,1739137677.451352,19.189981698989868,0.0,1739137677.451355,19.189981698989868,-0.22950765814279217,1739137677.4513583,19.189981698989868,6.2786837099701325,1739137677.451361,19.189981698989868,2.2896042380587427 +1739137677.4715335,19.209981679916382,41.44788517567234,1739137677.4715395,19.209981679916382,0.04727063951236232,1739137677.471546,19.209981679916382,41.08315699745909,1739137677.4715514,19.209981679916382,49.731373568609314,1739137677.4715543,19.209981679916382,0.726527682227331,1739137677.4715579,19.209981679916382,0.08181826701677045,1739137677.471561,19.209981679916382,0.6974137380578525,1739137677.4715636,19.209981679916382,0.15493812213126051,1739137677.4715664,19.209981679916382,1.891415019764896,1739137677.4715698,19.209981679916382,0.0,1739137677.4715724,19.209981679916382,-0.5023349691558435,1739137677.4715755,19.209981679916382,6.280993194260398,1739137677.4715784,19.209981679916382,2.2638321568720343 +1739137677.4916453,19.229981660842896,41.44788517567234,1739137677.4916506,19.229981660842896,0.04727063951236232,1739137677.491657,19.229981660842896,41.08315699745909,1739137677.4916635,19.229981660842896,49.731373568609314,1739137677.491666,19.229981660842896,0.726527682227331,1739137677.4916697,19.229981660842896,0.08181826701677045,1739137677.4916725,19.229981660842896,0.6974137380578525,1739137677.4916756,19.229981660842896,0.15493812213126051,1739137677.4916782,19.229981660842896,1.891415019764896,1739137677.4916813,19.229981660842896,0.0,1739137677.4916842,19.229981660842896,-0.3724171371071383,1739137677.491687,19.229981660842896,6.280993194260398,1739137677.49169,19.229981660842896,2.2638321568720343 +1739137677.5111873,19.24998164176941,41.44788517567234,1739137677.51119,19.24998164176941,0.04727063951236232,1739137677.5111933,19.24998164176941,41.08315699745909,1739137677.5111966,19.24998164176941,49.731373568609314,1739137677.5111983,19.24998164176941,0.726527682227331,1739137677.5112002,19.24998164176941,0.08181826701677045,1739137677.5112019,19.24998164176941,0.6974137380578525,1739137677.5112035,19.24998164176941,0.15493812213126051,1739137677.5112052,19.24998164176941,1.891415019764896,1739137677.5112069,19.24998164176941,0.0,1739137677.5112085,19.24998164176941,-0.3724171371071383,1739137677.51121,19.24998164176941,6.280993194260398,1739137677.5112119,19.24998164176941,2.2638321568720343 +1739137677.529312,19.269981622695923,41.44788517567234,1739137677.5293143,19.269981622695923,0.04727063951236232,1739137677.529317,19.269981622695923,41.08315699745909,1739137677.5293195,19.269981622695923,49.731373568609314,1739137677.5293205,19.269981622695923,0.726527682227331,1739137677.529322,19.269981622695923,0.08181826701677045,1739137677.5293236,19.269981622695923,0.6974137380578525,1739137677.5293248,19.269981622695923,0.15493812213126051,1739137677.529326,19.269981622695923,1.891415019764896,1739137677.5293274,19.269981622695923,0.0,1739137677.5293283,19.269981622695923,-0.3724171371071383,1739137677.5293298,19.269981622695923,6.280993194260398,1739137677.529331,19.269981622695923,2.2638321568720343 +1739137677.549044,19.289981603622437,41.44788517567234,1739137677.549046,19.289981603622437,0.04727063951236232,1739137677.5490491,19.289981603622437,41.08315699745909,1739137677.5490518,19.289981603622437,49.731373568609314,1739137677.549053,19.289981603622437,0.726527682227331,1739137677.5490544,19.289981603622437,0.08181826701677045,1739137677.549056,19.289981603622437,0.6974137380578525,1739137677.5490572,19.289981603622437,0.15493812213126051,1739137677.5490587,19.289981603622437,1.891415019764896,1739137677.54906,19.289981603622437,0.0,1739137677.5490613,19.289981603622437,-0.3724171371071383,1739137677.5490627,19.289981603622437,6.280993194260398,1739137677.549064,19.289981603622437,2.2638321568720343 +1739137677.5689533,19.30998158454895,41.694811037007334,1739137677.5689554,19.30998158454895,0.047073494473995225,1739137677.568958,19.30998158454895,41.09352788363516,1739137677.5689604,19.30998158454895,49.63264954992677,1739137677.5689619,19.30998158454895,0.67063246576736,1739137677.5689633,19.30998158454895,0.07839426973542932,1739137677.5689647,19.30998158454895,0.6151519599439041,1739137677.568966,19.30998158454895,0.14891568375773695,1739137677.5689669,19.30998158454895,1.9546867450673848,1739137677.5689683,19.30998158454895,0.0,1739137677.5689692,19.30998158454895,-0.17283100956132674,1739137677.5689707,19.30998158454895,0.0010590620118554502,1739137677.568972,19.30998158454895,2.2225588152229268 +1739137677.5891337,19.329981565475464,41.694811037007334,1739137677.5891364,19.329981565475464,0.047073494473995225,1739137677.5891392,19.329981565475464,41.09352788363516,1739137677.5891418,19.329981565475464,49.63264954992677,1739137677.589143,19.329981565475464,0.67063246576736,1739137677.5891452,19.329981565475464,0.07839426973542932,1739137677.5891464,19.329981565475464,0.6151519599439041,1739137677.5891476,19.329981565475464,0.14891568375773695,1739137677.589149,19.329981565475464,1.9546867450673848,1739137677.5891504,19.329981565475464,0.0,1739137677.5891519,19.329981565475464,-0.26787207015554193,1739137677.5891533,19.329981565475464,0.0010590620118554502,1739137677.5891542,19.329981565475464,2.2225588152229268 +1739137677.6091726,19.349981546401978,41.694811037007334,1739137677.6091752,19.349981546401978,0.047073494473995225,1739137677.609178,19.349981546401978,41.09352788363516,1739137677.609181,19.349981546401978,49.63264954992677,1739137677.6091821,19.349981546401978,0.67063246576736,1739137677.6091857,19.349981546401978,0.07839426973542932,1739137677.609188,19.349981546401978,0.6151519599439041,1739137677.6091893,19.349981546401978,0.14891568375773695,1739137677.6091907,19.349981546401978,1.9546867450673848,1739137677.6091921,19.349981546401978,0.0,1739137677.6091936,19.349981546401978,-0.26787207015554193,1739137677.609195,19.349981546401978,0.0010590620118554502,1739137677.6091967,19.349981546401978,2.2225588152229268 +1739137677.629027,19.36998152732849,41.694811037007334,1739137677.629029,19.36998152732849,0.047073494473995225,1739137677.6290317,19.36998152732849,41.09352788363516,1739137677.6290343,19.36998152732849,49.63264954992677,1739137677.6290357,19.36998152732849,0.67063246576736,1739137677.6290374,19.36998152732849,0.07839426973542932,1739137677.6290388,19.36998152732849,0.6151519599439041,1739137677.6290405,19.36998152732849,0.14891568375773695,1739137677.6290417,19.36998152732849,1.9546867450673848,1739137677.629043,19.36998152732849,0.0,1739137677.6290443,19.36998152732849,-0.26787207015554193,1739137677.6290457,19.36998152732849,0.0010590620118554502,1739137677.6290472,19.36998152732849,2.2225588152229268 +1739137677.6490266,19.389981508255005,41.694811037007334,1739137677.6490288,19.389981508255005,0.047073494473995225,1739137677.6490319,19.389981508255005,41.09352788363516,1739137677.6490345,19.389981508255005,49.63264954992677,1739137677.649036,19.389981508255005,0.67063246576736,1739137677.6490376,19.389981508255005,0.07839426973542932,1739137677.649039,19.389981508255005,0.6151519599439041,1739137677.6490407,19.389981508255005,0.14891568375773695,1739137677.6490421,19.389981508255005,1.9546867450673848,1739137677.6490436,19.389981508255005,0.0,1739137677.6490448,19.389981508255005,-0.26787207015554193,1739137677.649046,19.389981508255005,0.0010590620118554502,1739137677.6490474,19.389981508255005,2.2225588152229268 +1739137677.6690164,19.40998148918152,41.694811037007334,1739137677.6690183,19.40998148918152,0.047073494473995225,1739137677.669021,19.40998148918152,41.09352788363516,1739137677.6690235,19.40998148918152,49.63264954992677,1739137677.6690247,19.40998148918152,0.67063246576736,1739137677.6690264,19.40998148918152,0.07839426973542932,1739137677.6690278,19.40998148918152,0.6151519599439041,1739137677.6690288,19.40998148918152,0.14891568375773695,1739137677.6690302,19.40998148918152,1.9546867450673848,1739137677.6690316,19.40998148918152,0.0,1739137677.669033,19.40998148918152,-0.26787207015554193,1739137677.6690342,19.40998148918152,0.0010590620118554502,1739137677.6690354,19.40998148918152,2.2225588152229268 +1739137677.6890666,19.429981470108032,41.93766921740288,1739137677.689069,19.429981470108032,0.04777475966298539,1739137677.6890717,19.429981470108032,41.10372792721177,1739137677.6890745,19.429981470108032,49.547610577127806,1739137677.6890757,19.429981470108032,0.6238637399916833,1739137677.6890771,19.429981470108032,0.07555804111534507,1739137677.6890788,19.429981470108032,0.5359867460953289,1739137677.68908,19.429981470108032,0.14124718928181984,1739137677.6890814,19.429981470108032,2.017574471887364,1739137677.6890826,19.429981470108032,0.0,1739137677.689084,19.429981470108032,-0.0795615351115958,1739137677.6890857,19.429981470108032,0.00526869025645286,1739137677.6890867,19.429981470108032,2.186807735148166 +1739137677.7091317,19.449981451034546,41.93766921740288,1739137677.709134,19.449981451034546,0.04777475966298539,1739137677.709137,19.449981451034546,41.10372792721177,1739137677.7091393,19.449981451034546,49.547610577127806,1739137677.7091408,19.449981451034546,0.6238637399916833,1739137677.7091422,19.449981451034546,0.07555804111534507,1739137677.7091436,19.449981451034546,0.5359867460953289,1739137677.7091448,19.449981451034546,0.14124718928181984,1739137677.709146,19.449981451034546,2.017574471887364,1739137677.7091477,19.449981451034546,0.0,1739137677.7091486,19.449981451034546,-0.1692332632608018,1739137677.7091503,19.449981451034546,0.00526869025645286,1739137677.7091515,19.449981451034546,2.186807735148166 +1739137677.7291098,19.46998143196106,41.93766921740288,1739137677.7291124,19.46998143196106,0.04777475966298539,1739137677.7291155,19.46998143196106,41.10372792721177,1739137677.729118,19.46998143196106,49.547610577127806,1739137677.7291198,19.46998143196106,0.6238637399916833,1739137677.7291214,19.46998143196106,0.07555804111534507,1739137677.729123,19.46998143196106,0.5359867460953289,1739137677.7291245,19.46998143196106,0.14124718928181984,1739137677.7291262,19.46998143196106,2.017574471887364,1739137677.7291276,19.46998143196106,0.0,1739137677.729129,19.46998143196106,-0.1692332632608018,1739137677.7291305,19.46998143196106,0.00526869025645286,1739137677.729132,19.46998143196106,2.186807735148166 +1739137677.749122,19.489981412887573,41.93766921740288,1739137677.749124,19.489981412887573,0.04777475966298539,1739137677.7491271,19.489981412887573,41.10372792721177,1739137677.74913,19.489981412887573,49.547610577127806,1739137677.7491314,19.489981412887573,0.6238637399916833,1739137677.7491333,19.489981412887573,0.07555804111534507,1739137677.7491348,19.489981412887573,0.5359867460953289,1739137677.7491364,19.489981412887573,0.14124718928181984,1739137677.7491374,19.489981412887573,2.017574471887364,1739137677.7491393,19.489981412887573,0.0,1739137677.7491405,19.489981412887573,-0.1692332632608018,1739137677.749142,19.489981412887573,0.00526869025645286,1739137677.7491436,19.489981412887573,2.186807735148166 +1739137677.7693734,19.509981393814087,41.93766921740288,1739137677.7693763,19.509981393814087,0.04777475966298539,1739137677.7693796,19.509981393814087,41.10372792721177,1739137677.7693827,19.509981393814087,49.547610577127806,1739137677.7693841,19.509981393814087,0.6238637399916833,1739137677.769386,19.509981393814087,0.07555804111534507,1739137677.7693875,19.509981393814087,0.5359867460953289,1739137677.7693892,19.509981393814087,0.14124718928181984,1739137677.7693903,19.509981393814087,2.017574471887364,1739137677.769392,19.509981393814087,0.0,1739137677.7693934,19.509981393814087,-0.1692332632608018,1739137677.769395,19.509981393814087,0.00526869025645286,1739137677.7693965,19.509981393814087,2.186807735148166 +1739137677.789575,19.5299813747406,42.17724785120647,1739137677.7895784,19.5299813747406,0.0495517168913544,1739137677.7895825,19.5299813747406,41.37112023667485,1739137677.7895865,19.5299813747406,49.73229252974956,1739137677.7895885,19.5299813747406,0.7270479764023204,1739137677.789591,19.5299813747406,0.0894354647321275,1739137677.7895927,19.5299813747406,0.6019007556306307,1739137677.789595,19.5299813747406,0.1605272722392284,1739137677.789597,19.5299813747406,1.9650750335833762,1739137677.789599,19.5299813747406,0.0,1739137677.7896008,19.5299813747406,-0.2339288002436924,1739137677.789603,19.5299813747406,0.010001645417842773,1739137677.789605,19.5299813747406,2.168196419874138 +1739137677.8098805,19.549981355667114,42.17724785120647,1739137677.8098843,19.549981355667114,0.0495517168913544,1739137677.809889,19.549981355667114,41.37112023667485,1739137677.8098934,19.549981355667114,49.73229252974956,1739137677.8098958,19.549981355667114,0.7270479764023204,1739137677.8098981,19.549981355667114,0.0894354647321275,1739137677.8099005,19.549981355667114,0.6019007556306307,1739137677.8099027,19.549981355667114,0.1605272722392284,1739137677.8099046,19.549981355667114,1.9650750335833762,1739137677.809907,19.549981355667114,0.0,1739137677.809909,19.549981355667114,-0.20312138629076193,1739137677.8099113,19.549981355667114,0.010001645417842773,1739137677.8099136,19.549981355667114,2.168196419874138 +1739137677.8302495,19.569981336593628,42.17724785120647,1739137677.8302531,19.569981336593628,0.0495517168913544,1739137677.8302577,19.569981336593628,41.37112023667485,1739137677.8302622,19.569981336593628,49.73229252974956,1739137677.8302648,19.569981336593628,0.7270479764023204,1739137677.8302674,19.569981336593628,0.0894354647321275,1739137677.8302698,19.569981336593628,0.6019007556306307,1739137677.830272,19.569981336593628,0.1605272722392284,1739137677.8302743,19.569981336593628,1.9650750335833762,1739137677.830277,19.569981336593628,0.0,1739137677.8302789,19.569981336593628,-0.20312138629076193,1739137677.8302815,19.569981336593628,0.010001645417842773,1739137677.8302834,19.569981336593628,2.168196419874138 +1739137677.8500168,19.58998131752014,42.17724785120647,1739137677.8500206,19.58998131752014,0.0495517168913544,1739137677.8500252,19.58998131752014,41.37112023667485,1739137677.8500297,19.58998131752014,49.73229252974956,1739137677.8500319,19.58998131752014,0.7270479764023204,1739137677.8500345,19.58998131752014,0.0894354647321275,1739137677.8500366,19.58998131752014,0.6019007556306307,1739137677.8500388,19.58998131752014,0.1605272722392284,1739137677.850041,19.58998131752014,1.9650750335833762,1739137677.8500433,19.58998131752014,0.0,1739137677.8500454,19.58998131752014,-0.20312138629076193,1739137677.8500478,19.58998131752014,0.010001645417842773,1739137677.8500497,19.58998131752014,2.168196419874138 +1739137677.869976,19.609981298446655,42.17724785120647,1739137677.8699799,19.609981298446655,0.0495517168913544,1739137677.8699846,19.609981298446655,41.37112023667485,1739137677.869989,19.609981298446655,49.73229252974956,1739137677.8699908,19.609981298446655,0.7270479764023204,1739137677.8699934,19.609981298446655,0.0894354647321275,1739137677.8699958,19.609981298446655,0.6019007556306307,1739137677.869998,19.609981298446655,0.1605272722392284,1739137677.8700001,19.609981298446655,1.9650750335833762,1739137677.8700027,19.609981298446655,0.0,1739137677.8700047,19.609981298446655,-0.20312138629076193,1739137677.870007,19.609981298446655,0.010001645417842773,1739137677.8700094,19.609981298446655,2.168196419874138 +1739137677.8902073,19.62998127937317,42.17724785120647,1739137677.890211,19.62998127937317,0.0495517168913544,1739137677.8902154,19.62998127937317,41.37112023667485,1739137677.8902197,19.62998127937317,49.73229252974956,1739137677.8902218,19.62998127937317,0.7270479764023204,1739137677.8902247,19.62998127937317,0.0894354647321275,1739137677.8902268,19.62998127937317,0.6019007556306307,1739137677.890229,19.62998127937317,0.1605272722392284,1739137677.8902311,19.62998127937317,1.9650750335833762,1739137677.8902338,19.62998127937317,0.0,1739137677.890236,19.62998127937317,-0.20312138629076193,1739137677.8902385,19.62998127937317,0.010001645417842773,1739137677.8902404,19.62998127937317,2.168196419874138 +1739137677.9094265,19.649981260299683,42.41455901304133,1739137677.909429,19.649981260299683,0.052461631479332915,1739137677.9094322,19.649981260299683,41.920720626590345,1739137677.909435,19.649981260299683,50.13690928537013,1739137677.9094365,19.649981260299683,0.9868899456423649,1739137677.9094381,19.649981260299683,0.1204176677482385,1739137677.9094398,19.649981260299683,0.8177571673221352,1739137677.909441,19.649981260299683,0.20725839737482107,1739137677.9094422,19.649981260299683,1.8025239279287404,1739137677.909444,19.649981260299683,0.0,1739137677.9094453,19.649981260299683,-0.4698232033568611,1739137677.909447,19.649981260299683,0.015095030943694023,1739137677.9094484,19.649981260299683,2.145346202573518 +1739137677.929235,19.669981241226196,42.41455901304133,1739137677.9292374,19.669981241226196,0.052461631479332915,1739137677.92924,19.669981241226196,41.920720626590345,1739137677.929243,19.669981241226196,50.13690928537013,1739137677.9292448,19.669981241226196,0.9868899456423649,1739137677.9292464,19.669981241226196,0.1204176677482385,1739137677.929248,19.669981241226196,0.8177571673221352,1739137677.9292495,19.669981241226196,0.20725839737482107,1739137677.9292507,19.669981241226196,1.8025239279287404,1739137677.9292526,19.669981241226196,0.0,1739137677.9292538,19.669981241226196,-0.34282227464477755,1739137677.9292555,19.669981241226196,0.015095030943694023,1739137677.929257,19.669981241226196,2.145346202573518 +1739137677.9491546,19.68998122215271,42.41455901304133,1739137677.9491568,19.68998122215271,0.052461631479332915,1739137677.9491599,19.68998122215271,41.920720626590345,1739137677.9491627,19.68998122215271,50.13690928537013,1739137677.9491644,19.68998122215271,0.9868899456423649,1739137677.949166,19.68998122215271,0.1204176677482385,1739137677.949168,19.68998122215271,0.8177571673221352,1739137677.9491694,19.68998122215271,0.20725839737482107,1739137677.9491706,19.68998122215271,1.8025239279287404,1739137677.9491723,19.68998122215271,0.0,1739137677.9491737,19.68998122215271,-0.34282227464477755,1739137677.9491754,19.68998122215271,0.015095030943694023,1739137677.9491765,19.68998122215271,2.145346202573518 +1739137677.9691203,19.709981203079224,42.41455901304133,1739137677.9691226,19.709981203079224,0.052461631479332915,1739137677.9691253,19.709981203079224,41.920720626590345,1739137677.9691281,19.709981203079224,50.13690928537013,1739137677.9691298,19.709981203079224,0.9868899456423649,1739137677.9691315,19.709981203079224,0.1204176677482385,1739137677.9691331,19.709981203079224,0.8177571673221352,1739137677.9691346,19.709981203079224,0.20725839737482107,1739137677.9691358,19.709981203079224,1.8025239279287404,1739137677.9691374,19.709981203079224,0.0,1739137677.9691386,19.709981203079224,-0.34282227464477755,1739137677.9691403,19.709981203079224,0.015095030943694023,1739137677.9691415,19.709981203079224,2.145346202573518 +1739137677.9892673,19.729981184005737,42.41455901304133,1739137677.98927,19.729981184005737,0.052461631479332915,1739137677.989273,19.729981184005737,41.920720626590345,1739137677.9892764,19.729981184005737,50.13690928537013,1739137677.9892783,19.729981184005737,0.9868899456423649,1739137677.98928,19.729981184005737,0.1204176677482385,1739137677.989282,19.729981184005737,0.8177571673221352,1739137677.9892836,19.729981184005737,0.20725839737482107,1739137677.9892852,19.729981184005737,1.8025239279287404,1739137677.9892867,19.729981184005737,0.0,1739137677.989288,19.729981184005737,-0.34282227464477755,1739137677.9892905,19.729981184005737,0.015095030943694023,1739137677.9892921,19.729981184005737,2.145346202573518 +1739137678.0091622,19.74998116493225,42.6485272225161,1739137678.0091648,19.74998116493225,0.056572460322919405,1739137678.0091677,19.74998116493225,41.925633958989316,1739137678.0091708,19.74998116493225,50.04365403077317,1739137678.0091724,19.74998116493225,0.9221201408737841,1739137678.0091746,19.74998116493225,0.11651287104561271,1739137678.009176,19.74998116493225,0.7120770147410128,1739137678.009178,19.74998116493225,0.19701211837963897,1739137678.0091794,19.74998116493225,1.8803537536536559,1739137678.0091813,19.74998116493225,0.0,1739137678.0091827,19.74998116493225,-0.11885556145711507,1739137678.0091846,19.74998116493225,0.020729284365117923,1739137678.009186,19.74998116493225,2.1058601841911884 +1739137678.029482,19.769981145858765,42.6485272225161,1739137678.0294847,19.769981145858765,0.056572460322919405,1739137678.0294883,19.769981145858765,41.925633958989316,1739137678.029492,19.769981145858765,50.04365403077317,1739137678.0294938,19.769981145858765,0.9221201408737841,1739137678.0294967,19.769981145858765,0.11651287104561271,1739137678.0294983,19.769981145858765,0.7120770147410128,1739137678.0295005,19.769981145858765,0.19701211837963897,1739137678.0295022,19.769981145858765,1.8803537536536559,1739137678.0295043,19.769981145858765,0.0,1739137678.0295062,19.769981145858765,-0.2255064305375325,1739137678.0295084,19.769981145858765,0.020729284365117923,1739137678.0295103,19.769981145858765,2.1058601841911884 +1739137678.0492544,19.78998112678528,42.6485272225161,1739137678.049257,19.78998112678528,0.056572460322919405,1739137678.0492601,19.78998112678528,41.925633958989316,1739137678.0492635,19.78998112678528,50.04365403077317,1739137678.0492651,19.78998112678528,0.9221201408737841,1739137678.049267,19.78998112678528,0.11651287104561271,1739137678.0492687,19.78998112678528,0.7120770147410128,1739137678.04927,19.78998112678528,0.19701211837963897,1739137678.0492716,19.78998112678528,1.8803537536536559,1739137678.0492733,19.78998112678528,0.0,1739137678.0492747,19.78998112678528,-0.2255064305375325,1739137678.0492764,19.78998112678528,0.020729284365117923,1739137678.049278,19.78998112678528,2.1058601841911884 +1739137678.0723186,19.809981107711792,42.6485272225161,1739137678.0723233,19.809981107711792,0.056572460322919405,1739137678.0723288,19.809981107711792,41.925633958989316,1739137678.0723348,19.809981107711792,50.04365403077317,1739137678.072338,19.809981107711792,0.9221201408737841,1739137678.0723422,19.809981107711792,0.11651287104561271,1739137678.0723462,19.809981107711792,0.7120770147410128,1739137678.07235,19.809981107711792,0.19701211837963897,1739137678.0723534,19.809981107711792,1.8803537536536559,1739137678.0723572,19.809981107711792,0.0,1739137678.0723608,19.809981107711792,-0.2255064305375325,1739137678.0723648,19.809981107711792,0.020729284365117923,1739137678.0723684,19.809981107711792,2.1058601841911884 +1739137678.0963695,19.839981079101562,42.6485272225161,1739137678.0963743,19.839981079101562,0.056572460322919405,1739137678.0963798,19.839981079101562,41.925633958989316,1739137678.0963845,19.839981079101562,50.04365403077317,1739137678.0963874,19.839981079101562,0.9221201408737841,1739137678.0963907,19.839981079101562,0.11651287104561271,1739137678.0963938,19.839981079101562,0.7120770147410128,1739137678.0963964,19.839981079101562,0.19701211837963897,1739137678.0963993,19.839981079101562,1.8803537536536559,1739137678.0964022,19.839981079101562,0.0,1739137678.096405,19.839981079101562,-0.2255064305375325,1739137678.0964084,19.839981079101562,0.020729284365117923,1739137678.0964117,19.839981079101562,2.1058601841911884 +1739137678.114209,19.859981060028076,42.87907191624414,1739137678.1142113,19.859981060028076,0.062025939499272376,1739137678.1142144,19.859981060028076,41.93047539755761,1739137678.114217,19.859981060028076,49.99122855050198,1739137678.1142182,19.859981060028076,0.887380364790467,1739137678.1142201,19.859981060028076,0.11553162296467887,1739137678.1142213,19.859981060028076,0.6308526166235313,1739137678.1142225,19.859981060028076,0.18877004664798372,1739137678.114224,19.859981060028076,1.9424492663796964,1739137678.1142254,19.859981060028076,0.0,1739137678.1142263,19.859981060028076,-0.06385789136055348,1739137678.114228,19.859981060028076,0.02730792261202259,1739137678.1142292,19.859981060028076,2.0832826910390723 +1739137678.129147,19.869981050491333,42.87907191624414,1739137678.1291513,19.869981050491333,0.062025939499272376,1739137678.129155,19.869981050491333,41.93047539755761,1739137678.1291578,19.869981050491333,49.99122855050198,1739137678.12916,19.869981050491333,0.887380364790467,1739137678.1291614,19.869981050491333,0.11553162296467887,1739137678.129163,19.869981050491333,0.6308526166235313,1739137678.129164,19.869981050491333,0.18877004664798372,1739137678.1291654,19.869981050491333,1.9424492663796964,1739137678.1291668,19.869981050491333,0.0,1739137678.1291678,19.869981050491333,-0.14083342465937587,1739137678.1291697,19.869981050491333,0.02730792261202259,1739137678.129171,19.869981050491333,2.0832826910390723 +1739137678.1491745,19.889981031417847,42.87907191624414,1739137678.1491766,19.889981031417847,0.062025939499272376,1739137678.149179,19.889981031417847,41.93047539755761,1739137678.1491814,19.889981031417847,49.99122855050198,1739137678.1491828,19.889981031417847,0.887380364790467,1739137678.1491842,19.889981031417847,0.11553162296467887,1739137678.1491854,19.889981031417847,0.6308526166235313,1739137678.1491868,19.889981031417847,0.18877004664798372,1739137678.1491878,19.889981031417847,1.9424492663796964,1739137678.1491892,19.889981031417847,0.0,1739137678.1491904,19.889981031417847,-0.14083342465937587,1739137678.1491916,19.889981031417847,0.02730792261202259,1739137678.149193,19.889981031417847,2.0832826910390723 +1739137678.1691308,19.90998101234436,42.87907191624414,1739137678.169133,19.90998101234436,0.062025939499272376,1739137678.1691356,19.90998101234436,41.93047539755761,1739137678.1691382,19.90998101234436,49.99122855050198,1739137678.1691391,19.90998101234436,0.887380364790467,1739137678.169141,19.90998101234436,0.11553162296467887,1739137678.169142,19.90998101234436,0.6308526166235313,1739137678.1691432,19.90998101234436,0.18877004664798372,1739137678.1691449,19.90998101234436,1.9424492663796964,1739137678.169146,19.90998101234436,0.0,1739137678.1691475,19.90998101234436,-0.14083342465937587,1739137678.169149,19.90998101234436,0.02730792261202259,1739137678.1691499,19.90998101234436,2.0832826910390723 +1739137678.1890397,19.929980993270874,42.87907191624414,1739137678.189042,19.929980993270874,0.062025939499272376,1739137678.1890447,19.929980993270874,41.93047539755761,1739137678.1890473,19.929980993270874,49.99122855050198,1739137678.1890483,19.929980993270874,0.887380364790467,1739137678.1890502,19.929980993270874,0.11553162296467887,1739137678.1890514,19.929980993270874,0.6308526166235313,1739137678.1890526,19.929980993270874,0.18877004664798372,1739137678.189054,19.929980993270874,1.9424492663796964,1739137678.1890554,19.929980993270874,0.0,1739137678.1890569,19.929980993270874,-0.14083342465937587,1739137678.1890583,19.929980993270874,0.02730792261202259,1739137678.1890595,19.929980993270874,2.0832826910390723 +1739137678.209006,19.949980974197388,42.87907191624414,1739137678.2090085,19.949980974197388,0.062025939499272376,1739137678.2090108,19.949980974197388,41.93047539755761,1739137678.2090132,19.949980974197388,49.99122855050198,1739137678.2090151,19.949980974197388,0.887380364790467,1739137678.2090166,19.949980974197388,0.11553162296467887,1739137678.2090178,19.949980974197388,0.6308526166235313,1739137678.2090192,19.949980974197388,0.18877004664798372,1739137678.2090201,19.949980974197388,1.9424492663796964,1739137678.2090218,19.949980974197388,0.0,1739137678.209023,19.949980974197388,-0.14083342465937587,1739137678.2090244,19.949980974197388,0.02730792261202259,1739137678.2090259,19.949980974197388,2.0832826910390723 +1739137678.2292473,19.9699809551239,43.107431216721594,1739137678.2292497,19.9699809551239,0.06897008968801988,1739137678.2292528,19.9699809551239,42.22326908706938,1739137678.2292554,19.9699809551239,50.195697760987564,1739137678.2292569,19.9699809551239,1.0291152696523544,1739137678.2292588,19.9699809551239,0.13463611603928602,1739137678.22926,19.9699809551239,0.7177930803473206,1739137678.2292616,19.9699809551239,0.21511410394562802,1739137678.2292628,19.9699809551239,1.8760593747472147,1739137678.2292645,19.9699809551239,0.0,1739137678.2292657,19.9699809551239,-0.23959396208272823,1739137678.2292674,19.9699809551239,0.03411838899456257,1739137678.2292688,19.9699809551239,2.068624485992524 +1739137678.2492495,19.989980936050415,43.107431216721594,1739137678.2492528,19.989980936050415,0.06897008968801988,1739137678.2492576,19.989980936050415,42.22326908706938,1739137678.2492614,19.989980936050415,50.195697760987564,1739137678.249263,19.989980936050415,1.0291152696523544,1739137678.2492664,19.989980936050415,0.13463611603928602,1739137678.2492688,19.989980936050415,0.7177930803473206,1739137678.2492707,19.989980936050415,0.21511410394562802,1739137678.2492723,19.989980936050415,1.8760593747472147,1739137678.249275,19.989980936050415,0.0,1739137678.2492769,19.989980936050415,-0.19256511124530906,1739137678.2492788,19.989980936050415,0.03411838899456257,1739137678.2492807,19.989980936050415,2.068624485992524 +1739137678.2693563,20.00998091697693,43.107431216721594,1739137678.2693586,20.00998091697693,0.06897008968801988,1739137678.269362,20.00998091697693,42.22326908706938,1739137678.269365,20.00998091697693,50.195697760987564,1739137678.2693665,20.00998091697693,1.0291152696523544,1739137678.2693682,20.00998091697693,0.13463611603928602,1739137678.2693698,20.00998091697693,0.7177930803473206,1739137678.269371,20.00998091697693,0.21511410394562802,1739137678.269373,20.00998091697693,1.8760593747472147,1739137678.2693746,20.00998091697693,0.0,1739137678.2693763,20.00998091697693,-0.19256511124530906,1739137678.2693777,20.00998091697693,0.03411838899456257,1739137678.2693794,20.00998091697693,2.068624485992524 +1739137678.2895176,20.029980897903442,43.107431216721594,1739137678.2895207,20.029980897903442,0.06897008968801988,1739137678.2895236,20.029980897903442,42.22326908706938,1739137678.289527,20.029980897903442,50.195697760987564,1739137678.2895288,20.029980897903442,1.0291152696523544,1739137678.289531,20.029980897903442,0.13463611603928602,1739137678.2895324,20.029980897903442,0.7177930803473206,1739137678.2895339,20.029980897903442,0.21511410394562802,1739137678.2895355,20.029980897903442,1.8760593747472147,1739137678.2895374,20.029980897903442,0.0,1739137678.289539,20.029980897903442,-0.19256511124530906,1739137678.2895408,20.029980897903442,0.03411838899456257,1739137678.2895422,20.029980897903442,2.068624485992524 +1739137678.3093712,20.049980878829956,43.107431216721594,1739137678.3093739,20.049980878829956,0.06897008968801988,1739137678.3093774,20.049980878829956,42.22326908706938,1739137678.3093805,20.049980878829956,50.195697760987564,1739137678.3093822,20.049980878829956,1.0291152696523544,1739137678.3093843,20.049980878829956,0.13463611603928602,1739137678.309386,20.049980878829956,0.7177930803473206,1739137678.3093874,20.049980878829956,0.21511410394562802,1739137678.309389,20.049980878829956,1.8760593747472147,1739137678.309391,20.049980878829956,0.0,1739137678.3093925,20.049980878829956,-0.19256511124530906,1739137678.3093941,20.049980878829956,0.03411838899456257,1739137678.3093958,20.049980878829956,2.068624485992524 +1739137678.3293107,20.06998085975647,43.107431216721594,1739137678.3293135,20.06998085975647,0.06897008968801988,1739137678.3293166,20.06998085975647,42.22326908706938,1739137678.3293197,20.06998085975647,50.195697760987564,1739137678.3293214,20.06998085975647,1.0291152696523544,1739137678.3293233,20.06998085975647,0.13463611603928602,1739137678.3293247,20.06998085975647,0.7177930803473206,1739137678.3293264,20.06998085975647,0.21511410394562802,1739137678.3293278,20.06998085975647,1.8760593747472147,1739137678.3293297,20.06998085975647,0.0,1739137678.3293312,20.06998085975647,-0.19256511124530906,1739137678.329333,20.06998085975647,0.03411838899456257,1739137678.3293343,20.06998085975647,2.068624485992524 +1739137678.3493288,20.089980840682983,43.33367643651347,1739137678.3493314,20.089980840682983,0.07742061506645115,1739137678.3493345,20.089980840682983,42.94327163595279,1739137678.3493376,20.089980840682983,50.69098669848922,1739137678.3493392,20.089980840682983,1.4551060628109074,1739137678.349341,20.089980840682983,0.18511025104953685,1739137678.3493428,20.089980840682983,1.0721252392983238,1739137678.349344,20.089980840682983,0.29298645209758667,1739137678.3493452,20.089980840682983,1.6281438703959659,1739137678.349347,20.089980840682983,0.0,1739137678.3493485,20.089980840682983,-0.6238236830636591,1739137678.3493502,20.089980840682983,0.04138300298503857,1739137678.3493516,20.089980840682983,2.046606226197265 +1739137678.3694205,20.109980821609497,43.33367643651347,1739137678.3694234,20.109980821609497,0.07742061506645115,1739137678.3694267,20.109980821609497,42.94327163595279,1739137678.3694298,20.109980821609497,50.69098669848922,1739137678.3694313,20.109980821609497,1.4551060628109074,1739137678.3694332,20.109980821609497,0.18511025104953685,1739137678.3694346,20.109980821609497,1.0721252392983238,1739137678.3694363,20.109980821609497,0.29298645209758667,1739137678.3694377,20.109980821609497,1.6281438703959659,1739137678.3694396,20.109980821609497,0.0,1739137678.369441,20.109980821609497,-0.4184623558012992,1739137678.3694427,20.109980821609497,0.04138300298503857,1739137678.3694441,20.109980821609497,2.046606226197265 +1739137678.3910394,20.12998080253601,43.33367643651347,1739137678.3910449,20.12998080253601,0.07742061506645115,1739137678.3910508,20.12998080253601,42.94327163595279,1739137678.3910573,20.12998080253601,50.69098669848922,1739137678.39106,20.12998080253601,1.4551060628109074,1739137678.3910644,20.12998080253601,0.18511025104953685,1739137678.3910682,20.12998080253601,1.0721252392983238,1739137678.3910718,20.12998080253601,0.29298645209758667,1739137678.3910751,20.12998080253601,1.6281438703959659,1739137678.3910785,20.12998080253601,0.0,1739137678.3910816,20.12998080253601,-0.4184623558012992,1739137678.3910854,20.12998080253601,0.04138300298503857,1739137678.3910885,20.12998080253601,2.046606226197265 +1739137678.41058,20.149980783462524,43.33367643651347,1739137678.4105842,20.149980783462524,0.07742061506645115,1739137678.4105892,20.149980783462524,42.94327163595279,1739137678.4105935,20.149980783462524,50.69098669848922,1739137678.410596,20.149980783462524,1.4551060628109074,1739137678.4105988,20.149980783462524,0.18511025104953685,1739137678.410601,20.149980783462524,1.0721252392983238,1739137678.410603,20.149980783462524,0.29298645209758667,1739137678.4106057,20.149980783462524,1.6281438703959659,1739137678.4106085,20.149980783462524,0.0,1739137678.4106107,20.149980783462524,-0.4184623558012992,1739137678.410613,20.149980783462524,0.04138300298503857,1739137678.4106154,20.149980783462524,2.046606226197265 +1739137678.4301133,20.169980764389038,43.33367643651347,1739137678.4301171,20.169980764389038,0.07742061506645115,1739137678.4301214,20.169980764389038,42.94327163595279,1739137678.4301252,20.169980764389038,50.69098669848922,1739137678.4301276,20.169980764389038,1.4551060628109074,1739137678.4301305,20.169980764389038,0.18511025104953685,1739137678.4301326,20.169980764389038,1.0721252392983238,1739137678.430135,20.169980764389038,0.29298645209758667,1739137678.4301372,20.169980764389038,1.6281438703959659,1739137678.4301395,20.169980764389038,0.0,1739137678.430142,20.169980764389038,-0.4184623558012992,1739137678.4301445,20.169980764389038,0.04138300298503857,1739137678.4301465,20.169980764389038,2.046606226197265 +1739137678.4501512,20.18998074531555,43.5563687350976,1739137678.4501548,20.18998074531555,0.0874353081692032,1739137678.450159,20.18998074531555,42.94772548192447,1739137678.4501636,20.18998074531555,50.60426945912025,1739137678.450166,20.18998074531555,1.3711460833043938,1739137678.4501688,20.18998074531555,0.18016584497071841,1739137678.4501715,20.18998074531555,0.9339209479304263,1739137678.4501736,20.18998074531555,0.27871205430237167,1739137678.450176,20.18998074531555,1.720684802715676,1739137678.4501786,20.18998074531555,0.0,1739137678.4501808,20.18998074531555,-0.16214758508728172,1739137678.4501836,20.18998074531555,0.04942802917577054,1739137678.450186,20.18998074531555,2.0048871014955805 +1739137678.470079,20.209980726242065,43.5563687350976,1739137678.4700825,20.209980726242065,0.0874353081692032,1739137678.4700866,20.209980726242065,42.94772548192447,1739137678.4700904,20.209980726242065,50.60426945912025,1739137678.4700928,20.209980726242065,1.3711460833043938,1739137678.4700954,20.209980726242065,0.18016584497071841,1739137678.4700978,20.209980726242065,0.9339209479304263,1739137678.4700997,20.209980726242065,0.27871205430237167,1739137678.470102,20.209980726242065,1.720684802715676,1739137678.4701047,20.209980726242065,0.0,1739137678.4701068,20.209980726242065,-0.28420229877990444,1739137678.4701095,20.209980726242065,0.04942802917577054,1739137678.4701114,20.209980726242065,2.0048871014955805 +1739137678.4892683,20.22998070716858,43.5563687350976,1739137678.4892714,20.22998070716858,0.0874353081692032,1739137678.4892743,20.22998070716858,42.94772548192447,1739137678.4892771,20.22998070716858,50.60426945912025,1739137678.4892786,20.22998070716858,1.3711460833043938,1739137678.4892802,20.22998070716858,0.18016584497071841,1739137678.489282,20.22998070716858,0.9339209479304263,1739137678.489283,20.22998070716858,0.27871205430237167,1739137678.4892845,20.22998070716858,1.720684802715676,1739137678.4892864,20.22998070716858,0.0,1739137678.4892876,20.22998070716858,-0.28420229877990444,1739137678.489289,20.22998070716858,0.04942802917577054,1739137678.4892902,20.22998070716858,2.0048871014955805 +1739137678.510057,20.249980688095093,43.5563687350976,1739137678.5100608,20.249980688095093,0.0874353081692032,1739137678.510065,20.249980688095093,42.94772548192447,1739137678.5100698,20.249980688095093,50.60426945912025,1739137678.510072,20.249980688095093,1.3711460833043938,1739137678.510075,20.249980688095093,0.18016584497071841,1739137678.510078,20.249980688095093,0.9339209479304263,1739137678.5100803,20.249980688095093,0.27871205430237167,1739137678.5100827,20.249980688095093,1.720684802715676,1739137678.5100858,20.249980688095093,0.0,1739137678.5100884,20.249980688095093,-0.28420229877990444,1739137678.5100913,20.249980688095093,0.04942802917577054,1739137678.5100942,20.249980688095093,2.0048871014955805 +1739137678.5299366,20.269980669021606,43.5563687350976,1739137678.529939,20.269980669021606,0.0874353081692032,1739137678.5299418,20.269980669021606,42.94772548192447,1739137678.5299447,20.269980669021606,50.60426945912025,1739137678.5299459,20.269980669021606,1.3711460833043938,1739137678.5299478,20.269980669021606,0.18016584497071841,1739137678.529949,20.269980669021606,0.9339209479304263,1739137678.5299501,20.269980669021606,0.27871205430237167,1739137678.5299516,20.269980669021606,1.720684802715676,1739137678.529953,20.269980669021606,0.0,1739137678.5299542,20.269980669021606,-0.28420229877990444,1739137678.5299559,20.269980669021606,0.04942802917577054,1739137678.529957,20.269980669021606,2.0048871014955805 +1739137678.5490563,20.28998064994812,43.5563687350976,1739137678.5490587,20.28998064994812,0.0874353081692032,1739137678.5490613,20.28998064994812,42.94772548192447,1739137678.549064,20.28998064994812,50.60426945912025,1739137678.549065,20.28998064994812,1.3711460833043938,1739137678.5490668,20.28998064994812,0.18016584497071841,1739137678.5490682,20.28998064994812,0.9339209479304263,1739137678.5490696,20.28998064994812,0.27871205430237167,1739137678.5490708,20.28998064994812,1.720684802715676,1739137678.5490723,20.28998064994812,0.0,1739137678.5490735,20.28998064994812,-0.28420229877990444,1739137678.549075,20.28998064994812,0.04942802917577054,1739137678.5490763,20.28998064994812,2.0048871014955805 +1739137678.5690858,20.309980630874634,43.77506266155175,1739137678.5690882,20.309980630874634,0.0991399069515202,1739137678.569091,20.309980630874634,42.95209936045356,1739137678.5690935,20.309980630874634,50.533196612634335,1739137678.569095,20.309980630874634,1.3053397722205562,1739137678.5690966,20.309980630874634,0.17662141554386204,1739137678.5690978,20.309980630874634,0.8087089996683426,1739137678.569099,20.309980630874634,0.26290402441641275,1739137678.5691001,20.309980630874634,1.809059563379505,1739137678.5691013,20.309980630874634,0.0,1739137678.5691025,20.309980630874634,-0.05106439072385309,1739137678.5691042,20.309980630874634,0.05854431771771553,1739137678.5691054,20.309980630874634,1.9711420610170154 +1739137678.5890954,20.329980611801147,43.77506266155175,1739137678.5890977,20.329980611801147,0.0991399069515202,1739137678.5891008,20.329980611801147,42.95209936045356,1739137678.5891035,20.329980611801147,50.533196612634335,1739137678.5891047,20.329980611801147,1.3053397722205562,1739137678.589106,20.329980611801147,0.17662141554386204,1739137678.5891078,20.329980611801147,0.8087089996683426,1739137678.589109,20.329980611801147,0.26290402441641275,1739137678.5891104,20.329980611801147,1.809059563379505,1739137678.5891116,20.329980611801147,0.0,1739137678.5891128,20.329980611801147,-0.16208249763751037,1739137678.5891142,20.329980611801147,0.05854431771771553,1739137678.5891154,20.329980611801147,1.9711420610170154 +1739137678.6090329,20.34998059272766,43.77506266155175,1739137678.609035,20.34998059272766,0.0991399069515202,1739137678.6090379,20.34998059272766,42.95209936045356,1739137678.60904,20.34998059272766,50.533196612634335,1739137678.6090417,20.34998059272766,1.3053397722205562,1739137678.6090431,20.34998059272766,0.17662141554386204,1739137678.6090446,20.34998059272766,0.8087089996683426,1739137678.6090457,20.34998059272766,0.26290402441641275,1739137678.609047,20.34998059272766,1.809059563379505,1739137678.6090484,20.34998059272766,0.0,1739137678.6090496,20.34998059272766,-0.16208249763751037,1739137678.6090512,20.34998059272766,0.05854431771771553,1739137678.6090527,20.34998059272766,1.9711420610170154 +1739137678.629089,20.369980573654175,43.77506266155175,1739137678.629092,20.369980573654175,0.0991399069515202,1739137678.629095,20.369980573654175,42.95209936045356,1739137678.629098,20.369980573654175,50.533196612634335,1739137678.6290998,20.369980573654175,1.3053397722205562,1739137678.6291015,20.369980573654175,0.17662141554386204,1739137678.629103,20.369980573654175,0.8087089996683426,1739137678.6291044,20.369980573654175,0.26290402441641275,1739137678.6291056,20.369980573654175,1.809059563379505,1739137678.6291077,20.369980573654175,0.0,1739137678.6291087,20.369980573654175,-0.16208249763751037,1739137678.6291106,20.369980573654175,0.05854431771771553,1739137678.6291118,20.369980573654175,1.9711420610170154 +1739137678.649286,20.38998055458069,43.77506266155175,1739137678.6492887,20.38998055458069,0.0991399069515202,1739137678.6492918,20.38998055458069,42.95209936045356,1739137678.6492949,20.38998055458069,50.533196612634335,1739137678.6492963,20.38998055458069,1.3053397722205562,1739137678.6492984,20.38998055458069,0.17662141554386204,1739137678.6492999,20.38998055458069,0.8087089996683426,1739137678.6493013,20.38998055458069,0.26290402441641275,1739137678.6493027,20.38998055458069,1.809059563379505,1739137678.6493046,20.38998055458069,0.0,1739137678.649306,20.38998055458069,-0.16208249763751037,1739137678.6493077,20.38998055458069,0.05854431771771553,1739137678.6493092,20.38998055458069,1.9711420610170154 +1739137678.6695008,20.409980535507202,43.99058361092546,1739137678.6695037,20.409980535507202,0.11273276109878427,1739137678.6695075,20.409980535507202,43.22210859572516,1739137678.669511,20.409980535507202,50.69141109156898,1739137678.6695127,20.409980535507202,1.4555203512935326,1739137678.6695147,20.409980535507202,0.1977717901690297,1739137678.6695166,20.409980535507202,0.8820714299501116,1739137678.669518,20.409980535507202,0.28919525474516844,1739137678.6695197,20.409980535507202,1.756744112796187,1739137678.6695216,20.409980535507202,0.0,1739137678.6695232,20.409980535507202,-0.2289611439958899,1739137678.669525,20.409980535507202,0.06834052417557988,1739137678.6695268,20.409980535507202,1.9538582664267425 +1739137678.6895802,20.429980516433716,43.99058361092546,1739137678.6895833,20.429980516433716,0.11273276109878427,1739137678.6895869,20.429980516433716,43.22210859572516,1739137678.6895902,20.429980516433716,50.69141109156898,1739137678.6895921,20.429980516433716,1.4555203512935326,1739137678.6895943,20.429980516433716,0.1977717901690297,1739137678.6895962,20.429980516433716,0.8820714299501116,1739137678.6895976,20.429980516433716,0.28919525474516844,1739137678.6895995,20.429980516433716,1.756744112796187,1739137678.6896014,20.429980516433716,0.0,1739137678.689603,20.429980516433716,-0.19711415363055562,1739137678.6896052,20.429980516433716,0.06834052417557988,1739137678.689607,20.429980516433716,1.9538582664267425 +1739137678.7094593,20.44998049736023,43.99058361092546,1739137678.709462,20.44998049736023,0.11273276109878427,1739137678.7094655,20.44998049736023,43.22210859572516,1739137678.709469,20.44998049736023,50.69141109156898,1739137678.709471,20.44998049736023,1.4555203512935326,1739137678.7094731,20.44998049736023,0.1977717901690297,1739137678.7094748,20.44998049736023,0.8820714299501116,1739137678.7094767,20.44998049736023,0.28919525474516844,1739137678.7094781,20.44998049736023,1.756744112796187,1739137678.7094803,20.44998049736023,0.0,1739137678.7094817,20.44998049736023,-0.19711415363055562,1739137678.7094839,20.44998049736023,0.06834052417557988,1739137678.7094853,20.44998049736023,1.9538582664267425 +1739137678.729643,20.469980478286743,43.99058361092546,1739137678.7296464,20.469980478286743,0.11273276109878427,1739137678.7296505,20.469980478286743,43.22210859572516,1739137678.729654,20.469980478286743,50.69141109156898,1739137678.729656,20.469980478286743,1.4555203512935326,1739137678.7296581,20.469980478286743,0.1977717901690297,1739137678.7296598,20.469980478286743,0.8820714299501116,1739137678.7296617,20.469980478286743,0.28919525474516844,1739137678.7296634,20.469980478286743,1.756744112796187,1739137678.7296655,20.469980478286743,0.0,1739137678.7296672,20.469980478286743,-0.19711415363055562,1739137678.729669,20.469980478286743,0.06834052417557988,1739137678.729671,20.469980478286743,1.9538582664267425 +1739137678.7494774,20.489980459213257,43.99058361092546,1739137678.7494802,20.489980459213257,0.11273276109878427,1739137678.7494838,20.489980459213257,43.22210859572516,1739137678.7494874,20.489980459213257,50.69141109156898,1739137678.7494888,20.489980459213257,1.4555203512935326,1739137678.7494912,20.489980459213257,0.1977717901690297,1739137678.749493,20.489980459213257,0.8820714299501116,1739137678.7494946,20.489980459213257,0.28919525474516844,1739137678.749496,20.489980459213257,1.756744112796187,1739137678.7494981,20.489980459213257,0.0,1739137678.7494996,20.489980459213257,-0.19711415363055562,1739137678.7495015,20.489980459213257,0.06834052417557988,1739137678.7495031,20.489980459213257,1.9538582664267425 +1739137678.7695725,20.50998044013977,43.99058361092546,1739137678.7695756,20.50998044013977,0.11273276109878427,1739137678.7695792,20.50998044013977,43.22210859572516,1739137678.7695823,20.50998044013977,50.69141109156898,1739137678.7695844,20.50998044013977,1.4555203512935326,1739137678.7695863,20.50998044013977,0.1977717901690297,1739137678.7695882,20.50998044013977,0.8820714299501116,1739137678.76959,20.50998044013977,0.28919525474516844,1739137678.7695916,20.50998044013977,1.756744112796187,1739137678.769594,20.50998044013977,0.0,1739137678.7695954,20.50998044013977,-0.19711415363055562,1739137678.7695973,20.50998044013977,0.06834052417557988,1739137678.769599,20.50998044013977,1.9538582664267425 +1739137678.7898703,20.529980421066284,44.203797388793866,1739137678.7898736,20.529980421066284,0.1283087578990756,1739137678.7898777,20.529980421066284,43.333418397390204,1739137678.7898812,20.529980421066284,50.72258747322512,1739137678.7898831,20.529980421066284,1.4874887435039377,1739137678.7898855,20.529980421066284,0.20555691898467676,1739137678.7898872,20.529980421066284,0.8428360783122648,1739137678.7898889,20.529980421066284,0.2910406407643154,1739137678.7898903,20.529980421066284,1.7845321866050576,1739137678.789893,20.529980421066284,0.0,1739137678.7898943,20.529980421066284,-0.10164801515131894,1739137678.7898962,20.529980421066284,0.07864512955614293,1739137678.789898,20.529980421066284,1.9316402904081706 +1739137678.8094614,20.549980401992798,44.203797388793866,1739137678.809464,20.549980401992798,0.1283087578990756,1739137678.8094676,20.549980401992798,43.333418397390204,1739137678.809471,20.549980401992798,50.72258747322512,1739137678.8094728,20.549980401992798,1.4874887435039377,1739137678.8094747,20.549980401992798,0.20555691898467676,1739137678.809477,20.549980401992798,0.8428360783122648,1739137678.8094788,20.549980401992798,0.2910406407643154,1739137678.8094804,20.549980401992798,1.7845321866050576,1739137678.8094826,20.549980401992798,0.0,1739137678.809484,20.549980401992798,-0.147108103803113,1739137678.809486,20.549980401992798,0.07864512955614293,1739137678.8094873,20.549980401992798,1.9316402904081706 +1739137678.829855,20.56998038291931,44.203797388793866,1739137678.8298583,20.56998038291931,0.1283087578990756,1739137678.8298624,20.56998038291931,43.333418397390204,1739137678.829866,20.56998038291931,50.72258747322512,1739137678.8298678,20.56998038291931,1.4874887435039377,1739137678.8298697,20.56998038291931,0.20555691898467676,1739137678.8298717,20.56998038291931,0.8428360783122648,1739137678.8298733,20.56998038291931,0.2910406407643154,1739137678.829875,20.56998038291931,1.7845321866050576,1739137678.8298771,20.56998038291931,0.0,1739137678.8298788,20.56998038291931,-0.147108103803113,1739137678.8298807,20.56998038291931,0.07864512955614293,1739137678.8298824,20.56998038291931,1.9316402904081706 +1739137678.849488,20.589980363845825,44.203797388793866,1739137678.8494911,20.589980363845825,0.1283087578990756,1739137678.8494945,20.589980363845825,43.333418397390204,1739137678.849498,20.589980363845825,50.72258747322512,1739137678.8494997,20.589980363845825,1.4874887435039377,1739137678.8495018,20.589980363845825,0.20555691898467676,1739137678.8495038,20.589980363845825,0.8428360783122648,1739137678.8495054,20.589980363845825,0.2910406407643154,1739137678.849507,20.589980363845825,1.7845321866050576,1739137678.8495092,20.589980363845825,0.0,1739137678.8495107,20.589980363845825,-0.147108103803113,1739137678.8495128,20.589980363845825,0.07864512955614293,1739137678.8495142,20.589980363845825,1.9316402904081706 +1739137678.8694615,20.60998034477234,44.203797388793866,1739137678.8694644,20.60998034477234,0.1283087578990756,1739137678.8694677,20.60998034477234,43.333418397390204,1739137678.869471,20.60998034477234,50.72258747322512,1739137678.8694727,20.60998034477234,1.4874887435039377,1739137678.869475,20.60998034477234,0.20555691898467676,1739137678.8694768,20.60998034477234,0.8428360783122648,1739137678.8694785,20.60998034477234,0.2910406407643154,1739137678.8694801,20.60998034477234,1.7845321866050576,1739137678.869482,20.60998034477234,0.0,1739137678.8694835,20.60998034477234,-0.147108103803113,1739137678.8694854,20.60998034477234,0.07864512955614293,1739137678.8694873,20.60998034477234,1.9316402904081706 +1739137678.8896017,20.629980325698853,44.414758515309224,1739137678.8896048,20.629980325698853,0.14599962838249603,1739137678.8896084,20.629980325698853,43.94991936012896,1739137678.8896117,20.629980325698853,51.084362777821546,1739137678.8896134,20.629980325698853,1.9262936336951386,1739137678.8896155,20.629980325698853,0.26084494268214575,1739137678.8896174,20.629980325698853,1.1755009640157572,1739137678.889619,20.629980325698853,0.376903281413843,1739137678.8896208,20.629980325698853,1.5621925984292124,1739137678.8896224,20.629980325698853,0.0,1739137678.8896244,20.629980325698853,-0.5416323022231441,1739137678.8896263,20.629980325698853,0.08972559356835688,1739137678.889628,20.629980325698853,1.9159561408894026 +1739137678.9094853,20.649980306625366,44.414758515309224,1739137678.9094882,20.649980306625366,0.14599962838249603,1739137678.9094918,20.649980306625366,43.94991936012896,1739137678.9094954,20.649980306625366,51.084362777821546,1739137678.9094973,20.649980306625366,1.9262936336951386,1739137678.9094994,20.649980306625366,0.26084494268214575,1739137678.9095016,20.649980306625366,1.1755009640157572,1739137678.9095032,20.649980306625366,0.376903281413843,1739137678.9095047,20.649980306625366,1.5621925984292124,1739137678.9095068,20.649980306625366,0.0,1739137678.9095087,20.649980306625366,-0.35376354246019015,1739137678.9095104,20.649980306625366,0.08972559356835688,1739137678.9095123,20.649980306625366,1.9159561408894026 +1739137678.929743,20.66998028755188,44.414758515309224,1739137678.9297464,20.66998028755188,0.14599962838249603,1739137678.9297504,20.66998028755188,43.94991936012896,1739137678.9297538,20.66998028755188,51.084362777821546,1739137678.9297557,20.66998028755188,1.9262936336951386,1739137678.9297578,20.66998028755188,0.26084494268214575,1739137678.9297597,20.66998028755188,1.1755009640157572,1739137678.929762,20.66998028755188,0.376903281413843,1739137678.9297633,20.66998028755188,1.5621925984292124,1739137678.9297655,20.66998028755188,0.0,1739137678.9297671,20.66998028755188,-0.35376354246019015,1739137678.929769,20.66998028755188,0.08972559356835688,1739137678.9297707,20.66998028755188,1.9159561408894026 +1739137678.9496474,20.689980268478394,44.414758515309224,1739137678.9496503,20.689980268478394,0.14599962838249603,1739137678.9496534,20.689980268478394,43.94991936012896,1739137678.9496565,20.689980268478394,51.084362777821546,1739137678.949658,20.689980268478394,1.9262936336951386,1739137678.9496596,20.689980268478394,0.26084494268214575,1739137678.9496615,20.689980268478394,1.1755009640157572,1739137678.9496627,20.689980268478394,0.376903281413843,1739137678.9496644,20.689980268478394,1.5621925984292124,1739137678.949666,20.689980268478394,0.0,1739137678.9496672,20.689980268478394,-0.35376354246019015,1739137678.9496691,20.689980268478394,0.08972559356835688,1739137678.9496706,20.689980268478394,1.9159561408894026 +1739137678.9689727,20.709980249404907,44.414758515309224,1739137678.9689748,20.709980249404907,0.14599962838249603,1739137678.9689772,20.709980249404907,43.94991936012896,1739137678.9689794,20.709980249404907,51.084362777821546,1739137678.9689806,20.709980249404907,1.9262936336951386,1739137678.968982,20.709980249404907,0.26084494268214575,1739137678.968983,20.709980249404907,1.1755009640157572,1739137678.9689844,20.709980249404907,0.376903281413843,1739137678.9689853,20.709980249404907,1.5621925984292124,1739137678.9689865,20.709980249404907,0.0,1739137678.9689877,20.709980249404907,-0.35376354246019015,1739137678.968989,20.709980249404907,0.08972559356835688,1739137678.9689898,20.709980249404907,1.9159561408894026 +1739137678.989057,20.72998023033142,44.414758515309224,1739137678.989059,20.72998023033142,0.14599962838249603,1739137678.9890616,20.72998023033142,43.94991936012896,1739137678.9890642,20.72998023033142,51.084362777821546,1739137678.9890654,20.72998023033142,1.9262936336951386,1739137678.989067,20.72998023033142,0.26084494268214575,1739137678.9890685,20.72998023033142,1.1755009640157572,1739137678.9890695,20.72998023033142,0.376903281413843,1739137678.989071,20.72998023033142,1.5621925984292124,1739137678.989072,20.72998023033142,0.0,1739137678.9890735,20.72998023033142,-0.35376354246019015,1739137678.9890747,20.72998023033142,0.08972559356835688,1739137678.989076,20.72998023033142,1.9159561408894026 +1739137679.0091126,20.749980211257935,44.62235436313886,1739137679.0091147,20.749980211257935,0.1657601819825123,1739137679.0091174,20.749980211257935,43.954071277085546,1739137679.00912,20.749980211257935,51.01562254366014,1739137679.0091212,20.749980211257935,1.8309571650086172,1739137679.0091226,20.749980211257935,0.25479981378063477,1739137679.009124,20.749980211257935,1.0096545615526342,1739137679.0091252,20.749980211257935,0.3536662119296304,1739137679.0091264,20.749980211257935,1.6693409490553903,1739137679.0091279,20.749980211257935,0.0,1739137679.0091293,20.749980211257935,-0.0717694267666491,1739137679.0091305,20.749980211257935,0.10137273266786412,1739137679.0091317,20.749980211257935,1.875393355137274 +1739137679.0291374,20.76998019218445,44.62235436313886,1739137679.02914,20.76998019218445,0.1657601819825123,1739137679.0291426,20.76998019218445,43.954071277085546,1739137679.029145,20.76998019218445,51.01562254366014,1739137679.0291464,20.76998019218445,1.8309571650086172,1739137679.0291479,20.76998019218445,0.25479981378063477,1739137679.0291495,20.76998019218445,1.0096545615526342,1739137679.0291505,20.76998019218445,0.3536662119296304,1739137679.029152,20.76998019218445,1.6693409490553903,1739137679.0291536,20.76998019218445,0.0,1739137679.0291545,20.76998019218445,-0.20605240608188358,1739137679.0291562,20.76998019218445,0.10137273266786412,1739137679.0291574,20.76998019218445,1.875393355137274 +1739137679.04908,20.789980173110962,44.62235436313886,1739137679.049082,20.789980173110962,0.1657601819825123,1739137679.0490847,20.789980173110962,43.954071277085546,1739137679.0490873,20.789980173110962,51.01562254366014,1739137679.0490887,20.789980173110962,1.8309571650086172,1739137679.0490904,20.789980173110962,0.25479981378063477,1739137679.0490916,20.789980173110962,1.0096545615526342,1739137679.049093,20.789980173110962,0.3536662119296304,1739137679.0490942,20.789980173110962,1.6693409490553903,1739137679.0490956,20.789980173110962,0.0,1739137679.049097,20.789980173110962,-0.20605240608188358,1739137679.0490983,20.789980173110962,0.10137273266786412,1739137679.0490994,20.789980173110962,1.875393355137274 +1739137679.0691714,20.809980154037476,44.62235436313886,1739137679.0691738,20.809980154037476,0.1657601819825123,1739137679.069177,20.809980154037476,43.954071277085546,1739137679.0691795,20.809980154037476,51.01562254366014,1739137679.069181,20.809980154037476,1.8309571650086172,1739137679.0691826,20.809980154037476,0.25479981378063477,1739137679.069184,20.809980154037476,1.0096545615526342,1739137679.0691853,20.809980154037476,0.3536662119296304,1739137679.069187,20.809980154037476,1.6693409490553903,1739137679.0691886,20.809980154037476,0.0,1739137679.0691898,20.809980154037476,-0.20605240608188358,1739137679.0691915,20.809980154037476,0.10137273266786412,1739137679.0691926,20.809980154037476,1.875393355137274 +1739137679.0893235,20.82998013496399,44.62235436313886,1739137679.0893261,20.82998013496399,0.1657601819825123,1739137679.0893295,20.82998013496399,43.954071277085546,1739137679.0893328,20.82998013496399,51.01562254366014,1739137679.0893342,20.82998013496399,1.8309571650086172,1739137679.0893362,20.82998013496399,0.25479981378063477,1739137679.0893376,20.82998013496399,1.0096545615526342,1739137679.089339,20.82998013496399,0.3536662119296304,1739137679.0893407,20.82998013496399,1.6693409490553903,1739137679.0893428,20.82998013496399,0.0,1739137679.0893443,20.82998013496399,-0.20605240608188358,1739137679.0893457,20.82998013496399,0.10137273266786412,1739137679.0893474,20.82998013496399,1.875393355137274 +1739137679.1092677,20.849980115890503,44.82644497314867,1739137679.1092703,20.849980115890503,0.18770182702144922,1739137679.1092737,20.849980115890503,43.958153089285744,1739137679.109277,20.849980115890503,50.98011799077567,1739137679.1092784,20.849980115890503,1.7834906543675597,1739137679.1092803,20.849980115890503,0.25373380307106697,1739137679.109282,20.849980115890503,0.8841119667790446,1739137679.1092832,20.849980115890503,0.33462454783625534,1739137679.1092849,20.849980115890503,1.7553108173897034,1739137679.1092865,20.849980115890503,0.0,1739137679.109288,20.849980115890503,-0.0016091479807811143,1739137679.1092894,20.849980115890503,0.11420942899017357,1739137679.109291,20.849980115890503,1.8542739464321478 +1739137679.1293106,20.869980096817017,44.82644497314867,1739137679.1293132,20.869980096817017,0.18770182702144922,1739137679.1293166,20.869980096817017,43.958153089285744,1739137679.1293194,20.869980096817017,50.98011799077567,1739137679.129321,20.869980096817017,1.7834906543675597,1739137679.129323,20.869980096817017,0.25373380307106697,1739137679.129325,20.869980096817017,0.8841119667790446,1739137679.1293266,20.869980096817017,0.33462454783625534,1739137679.129328,20.869980096817017,1.7553108173897034,1739137679.12933,20.869980096817017,0.0,1739137679.1293318,20.869980096817017,-0.09896312904244442,1739137679.1293333,20.869980096817017,0.11420942899017357,1739137679.1293347,20.869980096817017,1.8542739464321478 +1739137679.1493032,20.88998007774353,44.82644497314867,1739137679.1493058,20.88998007774353,0.18770182702144922,1739137679.149309,20.88998007774353,43.958153089285744,1739137679.149312,20.88998007774353,50.98011799077567,1739137679.1493134,20.88998007774353,1.7834906543675597,1739137679.1493156,20.88998007774353,0.25373380307106697,1739137679.1493173,20.88998007774353,0.8841119667790446,1739137679.1493187,20.88998007774353,0.33462454783625534,1739137679.1493201,20.88998007774353,1.7553108173897034,1739137679.149322,20.88998007774353,0.0,1739137679.1493232,20.88998007774353,-0.09896312904244442,1739137679.1493251,20.88998007774353,0.11420942899017357,1739137679.1493266,20.88998007774353,1.8542739464321478 +1739137679.1730154,20.909980058670044,44.82644497314867,1739137679.1730232,20.909980058670044,0.18770182702144922,1739137679.1730335,20.909980058670044,43.958153089285744,1739137679.1730435,20.909980058670044,50.98011799077567,1739137679.173048,20.909980058670044,1.7834906543675597,1739137679.173054,20.909980058670044,0.25373380307106697,1739137679.1730587,20.909980058670044,0.8841119667790446,1739137679.1730638,20.909980058670044,0.33462454783625534,1739137679.1730683,20.909980058670044,1.7553108173897034,1739137679.1730733,20.909980058670044,0.0,1739137679.173078,20.909980058670044,-0.09896312904244442,1739137679.173083,20.909980058670044,0.11420942899017357,1739137679.1730878,20.909980058670044,1.8542739464321478 +1739137679.1932075,20.929980039596558,44.82644497314867,1739137679.1932158,20.929980039596558,0.18770182702144922,1739137679.1932285,20.929980039596558,43.958153089285744,1739137679.193254,20.929980039596558,50.98011799077567,1739137679.1932678,20.929980039596558,1.7834906543675597,1739137679.193279,20.929980039596558,0.25373380307106697,1739137679.193284,20.929980039596558,0.8841119667790446,1739137679.1932886,20.929980039596558,0.33462454783625534,1739137679.193293,20.929980039596558,1.7553108173897034,1739137679.1932983,20.929980039596558,0.0,1739137679.1933033,20.929980039596558,-0.09896312904244442,1739137679.1933084,20.929980039596558,0.11420942899017357,1739137679.1933131,20.929980039596558,1.8542739464321478 +1739137679.214809,20.94998002052307,44.82644497314867,1739137679.2148168,20.94998002052307,0.18770182702144922,1739137679.214827,20.94998002052307,43.958153089285744,1739137679.2148368,20.94998002052307,50.98011799077567,1739137679.2148414,20.94998002052307,1.7834906543675597,1739137679.214847,20.94998002052307,0.25373380307106697,1739137679.2148519,20.94998002052307,0.8841119667790446,1739137679.2148564,20.94998002052307,0.33462454783625534,1739137679.2148604,20.94998002052307,1.7553108173897034,1739137679.214866,20.94998002052307,0.0,1739137679.2148705,20.94998002052307,-0.09896312904244442,1739137679.214876,20.94998002052307,0.11420942899017357,1739137679.2148805,20.94998002052307,1.8542739464321478 +1739137679.2440553,20.979979991912842,45.028582611986245,1739137679.2440603,20.979979991912842,0.21214385221562182,1739137679.2440658,20.979979991912842,44.985680205958914,1739137679.2440715,20.979979991912842,51.486382581608,1739137679.2440736,20.979979991912842,2.6440173293897007,1739137679.244077,20.979979991912842,0.36015449992066323,1739137679.2440798,20.979979991912842,1.5896835315005609,1739137679.2440825,20.979979991912842,0.5078800691320353,1739137679.244085,20.979979991912842,1.3236820951411519,1739137679.2440877,20.979979991912842,0.0,1739137679.2440906,20.979979991912842,-0.9059764389502523,1739137679.2440934,20.979979991912842,0.12769503973293997,1739137679.244096,20.979979991912842,1.8453662897835872 +1739137679.2632427,20.999979972839355,45.028582611986245,1739137679.2632463,20.999979972839355,0.21214385221562182,1739137679.26325,20.999979972839355,44.985680205958914,1739137679.2632537,20.999979972839355,51.486382581608,1739137679.2632556,20.999979972839355,2.6440173293897007,1739137679.2632577,20.999979972839355,0.36015449992066323,1739137679.26326,20.999979972839355,1.5896835315005609,1739137679.2632618,20.999979972839355,0.5078800691320353,1739137679.2632635,20.999979972839355,1.3236820951411519,1739137679.2632654,20.999979972839355,0.0,1739137679.263267,20.999979972839355,-0.5216841946424353,1739137679.2632694,20.999979972839355,0.12769503973293997,1739137679.263271,20.999979972839355,1.8453662897835872 +1739137679.2821457,21.01997995376587,45.028582611986245,1739137679.2821507,21.01997995376587,0.21214385221562182,1739137679.2821562,21.01997995376587,44.985680205958914,1739137679.2821598,21.01997995376587,51.486382581608,1739137679.2821615,21.01997995376587,2.6440173293897007,1739137679.2821631,21.01997995376587,0.36015449992066323,1739137679.2821646,21.01997995376587,1.5896835315005609,1739137679.282166,21.01997995376587,0.5078800691320353,1739137679.2821672,21.01997995376587,1.3236820951411519,1739137679.2821689,21.01997995376587,0.0,1739137679.28217,21.01997995376587,-0.5216841946424353,1739137679.2821717,21.01997995376587,0.12769503973293997,1739137679.282173,21.01997995376587,1.8453662897835872 +1739137679.3016768,21.039979934692383,45.028582611986245,1739137679.3016791,21.039979934692383,0.21214385221562182,1739137679.3016815,21.039979934692383,44.985680205958914,1739137679.301684,21.039979934692383,51.486382581608,1739137679.3016853,21.039979934692383,2.6440173293897007,1739137679.3016868,21.039979934692383,0.36015449992066323,1739137679.301688,21.039979934692383,1.5896835315005609,1739137679.3016894,21.039979934692383,0.5078800691320353,1739137679.3016903,21.039979934692383,1.3236820951411519,1739137679.301692,21.039979934692383,0.0,1739137679.301693,21.039979934692383,-0.5216841946424353,1739137679.3016944,21.039979934692383,0.12769503973293997,1739137679.3016958,21.039979934692383,1.8453662897835872 +1739137679.3217256,21.059979915618896,45.028582611986245,1739137679.321728,21.059979915618896,0.21214385221562182,1739137679.3217306,21.059979915618896,44.985680205958914,1739137679.3217332,21.059979915618896,51.486382581608,1739137679.3217344,21.059979915618896,2.6440173293897007,1739137679.3217359,21.059979915618896,0.36015449992066323,1739137679.3217375,21.059979915618896,1.5896835315005609,1739137679.3217387,21.059979915618896,0.5078800691320353,1739137679.3217402,21.059979915618896,1.3236820951411519,1739137679.3217413,21.059979915618896,0.0,1739137679.3217423,21.059979915618896,-0.5216841946424353,1739137679.3217437,21.059979915618896,0.12769503973293997,1739137679.321745,21.059979915618896,1.8453662897835872 +1739137679.3421853,21.07997989654541,45.22755492263093,1739137679.342188,21.07997989654541,0.23893566603730765,1739137679.3421907,21.07997989654541,45.021575597316414,1739137679.3421936,21.07997989654541,51.43607123541672,1739137679.342195,21.07997989654541,2.5343931301101708,1739137679.3421965,21.07997989654541,0.3541399628921684,1739137679.3421977,21.07997989654541,1.3969845769698872,1739137679.3421993,21.07997989654541,0.4854538934912831,1739137679.3422008,21.07997989654541,1.4297461357811674,1739137679.3422024,21.07997989654541,0.0,1739137679.3422036,21.07997989654541,-0.21959328229887623,1739137679.3422053,21.07997989654541,0.14149300004055962,1739137679.3422067,21.07997989654541,1.7931923053425405 +1739137679.3622537,21.099979877471924,45.22755492263093,1739137679.3622563,21.099979877471924,0.23893566603730765,1739137679.3622591,21.099979877471924,45.021575597316414,1739137679.3622618,21.099979877471924,51.43607123541672,1739137679.362263,21.099979877471924,2.5343931301101708,1739137679.3622649,21.099979877471924,0.3541399628921684,1739137679.3622663,21.099979877471924,1.3969845769698872,1739137679.3622675,21.099979877471924,0.4854538934912831,1739137679.3622687,21.099979877471924,1.4297461357811674,1739137679.36227,21.099979877471924,0.0,1739137679.3622715,21.099979877471924,-0.3634461695613731,1739137679.362273,21.099979877471924,0.14149300004055962,1739137679.3622744,21.099979877471924,1.7931923053425405 +1739137679.3824186,21.119979858398438,45.22755492263093,1739137679.3824208,21.119979858398438,0.23893566603730765,1739137679.3824236,21.119979858398438,45.021575597316414,1739137679.382426,21.119979858398438,51.43607123541672,1739137679.3824275,21.119979858398438,2.5343931301101708,1739137679.382429,21.119979858398438,0.3541399628921684,1739137679.3824306,21.119979858398438,1.3969845769698872,1739137679.3824317,21.119979858398438,0.4854538934912831,1739137679.382433,21.119979858398438,1.4297461357811674,1739137679.3824346,21.119979858398438,0.0,1739137679.3824358,21.119979858398438,-0.3634461695613731,1739137679.3824372,21.119979858398438,0.14149300004055962,1739137679.3824384,21.119979858398438,1.7931923053425405 +1739137679.4020295,21.13997983932495,45.22755492263093,1739137679.4020321,21.13997983932495,0.23893566603730765,1739137679.4020352,21.13997983932495,45.021575597316414,1739137679.4020379,21.13997983932495,51.43607123541672,1739137679.402039,21.13997983932495,2.5343931301101708,1739137679.4020405,21.13997983932495,0.3541399628921684,1739137679.402042,21.13997983932495,1.3969845769698872,1739137679.402043,21.13997983932495,0.4854538934912831,1739137679.402044,21.13997983932495,1.4297461357811674,1739137679.4020457,21.13997983932495,0.0,1739137679.402047,21.13997983932495,-0.3634461695613731,1739137679.4020486,21.13997983932495,0.14149300004055962,1739137679.4020498,21.13997983932495,1.7931923053425405 +1739137679.4276586,21.159979820251465,45.22755492263093,1739137679.4276667,21.159979820251465,0.23893566603730765,1739137679.4276767,21.159979820251465,45.021575597316414,1739137679.4276862,21.159979820251465,51.43607123541672,1739137679.4276905,21.159979820251465,2.5343931301101708,1739137679.4276965,21.159979820251465,0.3541399628921684,1739137679.427701,21.159979820251465,1.3969845769698872,1739137679.4277053,21.159979820251465,0.4854538934912831,1739137679.42771,21.159979820251465,1.4297461357811674,1739137679.427715,21.159979820251465,0.0,1739137679.4277194,21.159979820251465,-0.3634461695613731,1739137679.4277248,21.159979820251465,0.14149300004055962,1739137679.4277294,21.159979820251465,1.7931923053425405 +1739137679.4540236,21.17997980117798,45.42087445393377,1739137679.454032,21.17997980117798,0.26779995502146114,1739137679.454042,21.17997980117798,45.271912873188384,1739137679.4540513,21.17997980117798,51.49609974779118,1739137679.4540563,21.17997980117798,2.666227994951255,1739137679.4540622,21.17997980117798,0.3760054986659369,1739137679.4540672,21.17997980117798,1.4217301792413026,1739137679.4540718,21.17997980117798,0.5070101245484568,1739137679.4540765,21.17997980117798,1.4156639733840777,1739137679.454082,21.17997980117798,0.0,1739137679.4540865,21.17997980117798,-0.3232146444457363,1739137679.4540923,21.17997980117798,0.15657684805527367,1739137679.4540968,21.17997980117798,1.7580364965026956 +1739137679.476924,21.20997977256775,45.42087445393377,1739137679.476941,21.20997977256775,0.26779995502146114,1739137679.4769628,21.20997977256775,45.271912873188384,1739137679.4769874,21.20997977256775,51.49609974779118,1739137679.4770002,21.20997977256775,2.666227994951255,1739137679.4770172,21.20997977256775,0.3760054986659369,1739137679.4770308,21.20997977256775,1.4217301792413026,1739137679.477044,21.20997977256775,0.5070101245484568,1739137679.4770586,21.20997977256775,1.4156639733840777,1739137679.4770718,21.20997977256775,0.0,1739137679.477087,21.20997977256775,-0.3423725231186179,1739137679.4770994,21.20997977256775,0.15657684805527367,1739137679.4771125,21.20997977256775,1.7580364965026956 +1739137679.5129945,21.249979734420776,45.42087445393377,1739137679.512999,21.249979734420776,0.26779995502146114,1739137679.5130045,21.249979734420776,45.271912873188384,1739137679.513011,21.249979734420776,51.49609974779118,1739137679.5130143,21.249979734420776,2.666227994951255,1739137679.5130186,21.249979734420776,0.3760054986659369,1739137679.5130227,21.249979734420776,1.4217301792413026,1739137679.5130265,21.249979734420776,0.5070101245484568,1739137679.5130303,21.249979734420776,1.4156639733840777,1739137679.5130346,21.249979734420776,0.0,1739137679.5130384,21.249979734420776,-0.3423725231186179,1739137679.5130424,21.249979734420776,0.15657684805527367,1739137679.5130463,21.249979734420776,1.7580364965026956 +1739137679.5331287,21.26997971534729,45.42087445393377,1739137679.533132,21.26997971534729,0.26779995502146114,1739137679.5331364,21.26997971534729,45.271912873188384,1739137679.5331411,21.26997971534729,51.49609974779118,1739137679.533144,21.26997971534729,2.666227994951255,1739137679.5331476,21.26997971534729,0.3760054986659369,1739137679.5331507,21.26997971534729,1.4217301792413026,1739137679.533154,21.26997971534729,0.5070101245484568,1739137679.533157,21.26997971534729,1.4156639733840777,1739137679.5331604,21.26997971534729,0.0,1739137679.5331638,21.26997971534729,-0.3423725231186179,1739137679.5331671,21.26997971534729,0.15657684805527367,1739137679.5331702,21.26997971534729,1.7580364965026956 +1739137679.5527496,21.289979696273804,45.609938728229956,1739137679.5527532,21.289979696273804,0.2990708595858722,1739137679.5527577,21.289979696273804,45.45503145315455,1739137679.5527625,21.289979696273804,51.52615035854274,1739137679.5527654,21.289979696273804,2.738589765326698,1739137679.552769,21.289979696273804,0.39110291173686773,1739137679.5527725,21.289979696273804,1.3844856873145044,1739137679.5527756,21.289979696273804,0.5141786264390911,1739137679.5527787,21.289979696273804,1.4369121299232175,1739137679.552782,21.289979696273804,0.0,1739137679.5527854,21.289979696273804,-0.23514158126756898,1739137679.5527887,21.289979696273804,0.1730337974156024,1739137679.5527918,21.289979696273804,1.7231160899610798 +1739137679.5793622,21.309979677200317,45.609938728229956,1739137679.5793695,21.309979677200317,0.2990708595858722,1739137679.5793786,21.309979677200317,45.45503145315455,1739137679.5793893,21.309979677200317,51.52615035854274,1739137679.579395,21.309979677200317,2.738589765326698,1739137679.5794024,21.309979677200317,0.39110291173686773,1739137679.5794091,21.309979677200317,1.3844856873145044,1739137679.5794158,21.309979677200317,0.5141786264390911,1739137679.5794225,21.309979677200317,1.4369121299232175,1739137679.5794294,21.309979677200317,0.0,1739137679.579436,21.309979677200317,-0.2862039600378623,1739137679.579443,21.309979677200317,0.1730337974156024,1739137679.5794497,21.309979677200317,1.7231160899610798 +1739137679.5949633,21.32997965812683,45.609938728229956,1739137679.594968,21.32997965812683,0.2990708595858722,1739137679.5949752,21.32997965812683,45.45503145315455,1739137679.594983,21.32997965812683,51.52615035854274,1739137679.594987,21.32997965812683,2.738589765326698,1739137679.5949926,21.32997965812683,0.39110291173686773,1739137679.594997,21.32997965812683,1.3844856873145044,1739137679.595003,21.32997965812683,0.5141786264390911,1739137679.595007,21.32997965812683,1.4369121299232175,1739137679.5950115,21.32997965812683,0.0,1739137679.595016,21.32997965812683,-0.2862039600378623,1739137679.5950203,21.32997965812683,0.1730337974156024,1739137679.595026,21.32997965812683,1.7231160899610798 +1739137679.6126156,21.349979639053345,45.609938728229956,1739137679.6126192,21.349979639053345,0.2990708595858722,1739137679.612624,21.349979639053345,45.45503145315455,1739137679.6126287,21.349979639053345,51.52615035854274,1739137679.6126316,21.349979639053345,2.738589765326698,1739137679.6126354,21.349979639053345,0.39110291173686773,1739137679.6126387,21.349979639053345,1.3844856873145044,1739137679.6126418,21.349979639053345,0.5141786264390911,1739137679.6126451,21.349979639053345,1.4369121299232175,1739137679.6126482,21.349979639053345,0.0,1739137679.6126516,21.349979639053345,-0.2862039600378623,1739137679.612655,21.349979639053345,0.1730337974156024,1739137679.6126583,21.349979639053345,1.7231160899610798 +1739137679.6306107,21.36997961997986,45.609938728229956,1739137679.630613,21.36997961997986,0.2990708595858722,1739137679.6306155,21.36997961997986,45.45503145315455,1739137679.6306183,21.36997961997986,51.52615035854274,1739137679.6306193,21.36997961997986,2.738589765326698,1739137679.630621,21.36997961997986,0.39110291173686773,1739137679.6306221,21.36997961997986,1.3844856873145044,1739137679.6306236,21.36997961997986,0.5141786264390911,1739137679.6306248,21.36997961997986,1.4369121299232175,1739137679.630626,21.36997961997986,0.0,1739137679.6306274,21.36997961997986,-0.2862039600378623,1739137679.6306288,21.36997961997986,0.1730337974156024,1739137679.6306298,21.36997961997986,1.7231160899610798 +1739137679.6515086,21.389979600906372,45.609938728229956,1739137679.6515105,21.389979600906372,0.2990708595858722,1739137679.6515133,21.389979600906372,45.45503145315455,1739137679.651516,21.389979600906372,51.52615035854274,1739137679.6515172,21.389979600906372,2.738589765326698,1739137679.6515183,21.389979600906372,0.39110291173686773,1739137679.6515198,21.389979600906372,1.3844856873145044,1739137679.651521,21.389979600906372,0.5141786264390911,1739137679.6515222,21.389979600906372,1.4369121299232175,1739137679.6515236,21.389979600906372,0.0,1739137679.6515248,21.389979600906372,-0.2862039600378623,1739137679.6515262,21.389979600906372,0.1730337974156024,1739137679.6515272,21.389979600906372,1.7231160899610798 +1739137679.6711967,21.409979581832886,45.79467788610662,1739137679.671199,21.409979581832886,0.3328808230898188,1739137679.6712015,21.409979581832886,45.458575307117705,1739137679.671204,21.409979581832886,51.4873256589413,1739137679.6712053,21.409979581832886,2.6461729347229697,1739137679.671207,21.409979581832886,0.38598126895168994,1739137679.6712081,21.409979581832886,1.1910552347878773,1739137679.671209,21.409979581832886,0.480380077627943,1739137679.6712105,21.409979581832886,1.5525032651182036,1739137679.6712117,21.409979581832886,0.0,1739137679.6712132,21.409979581832886,0.0005193713877894024,1739137679.6712143,21.409979581832886,0.1909125051420368,1739137679.6712155,21.409979581832886,1.6885188816621066 +1739137679.6912746,21.4299795627594,45.79467788610662,1739137679.6912768,21.4299795627594,0.3328808230898188,1739137679.6912796,21.4299795627594,45.458575307117705,1739137679.6912823,21.4299795627594,51.4873256589413,1739137679.6912835,21.4299795627594,2.6461729347229697,1739137679.691285,21.4299795627594,0.38598126895168994,1739137679.6912863,21.4299795627594,1.1910552347878773,1739137679.6912875,21.4299795627594,0.480380077627943,1739137679.691289,21.4299795627594,1.5525032651182036,1739137679.6912904,21.4299795627594,0.0,1739137679.6912913,21.4299795627594,-0.13601561654390304,1739137679.691293,21.4299795627594,0.1909125051420368,1739137679.6912942,21.4299795627594,1.6885188816621066 +1739137679.7127826,21.449979543685913,45.79467788610662,1739137679.712786,21.449979543685913,0.3328808230898188,1739137679.7127903,21.449979543685913,45.458575307117705,1739137679.7127955,21.449979543685913,51.4873256589413,1739137679.712798,21.449979543685913,2.6461729347229697,1739137679.712802,21.449979543685913,0.38598126895168994,1739137679.7128053,21.449979543685913,1.1910552347878773,1739137679.7128086,21.449979543685913,0.480380077627943,1739137679.712812,21.449979543685913,1.5525032651182036,1739137679.7128153,21.449979543685913,0.0,1739137679.7128186,21.449979543685913,-0.13601561654390304,1739137679.7128222,21.449979543685913,0.1909125051420368,1739137679.7128253,21.449979543685913,1.6885188816621066 +1739137679.732443,21.469979524612427,45.79467788610662,1739137679.7324464,21.469979524612427,0.3328808230898188,1739137679.7324507,21.469979524612427,45.458575307117705,1739137679.732456,21.469979524612427,51.4873256589413,1739137679.7324588,21.469979524612427,2.6461729347229697,1739137679.7324624,21.469979524612427,0.38598126895168994,1739137679.7324657,21.469979524612427,1.1910552347878773,1739137679.732469,21.469979524612427,0.480380077627943,1739137679.7324722,21.469979524612427,1.5525032651182036,1739137679.7324753,21.469979524612427,0.0,1739137679.7324786,21.469979524612427,-0.13601561654390304,1739137679.732482,21.469979524612427,0.1909125051420368,1739137679.7324853,21.469979524612427,1.6885188816621066 +1739137679.7503498,21.48997950553894,45.79467788610662,1739137679.7503521,21.48997950553894,0.3328808230898188,1739137679.750355,21.48997950553894,45.458575307117705,1739137679.7503574,21.48997950553894,51.4873256589413,1739137679.7503588,21.48997950553894,2.6461729347229697,1739137679.7503603,21.48997950553894,0.38598126895168994,1739137679.7503617,21.48997950553894,1.1910552347878773,1739137679.7503629,21.48997950553894,0.480380077627943,1739137679.750364,21.48997950553894,1.5525032651182036,1739137679.7503655,21.48997950553894,0.0,1739137679.7503667,21.48997950553894,-0.13601561654390304,1739137679.750368,21.48997950553894,0.1909125051420368,1739137679.7503693,21.48997950553894,1.6885188816621066 +1739137679.7707617,21.509979486465454,45.976048465912804,1739137679.7707644,21.509979486465454,0.36956435575597535,1739137679.7707672,21.509979486465454,45.46205803166669,1739137679.7707705,21.509979486465454,51.47182492252684,1739137679.7707717,21.509979486465454,2.6111024179031332,1739137679.7707736,21.509979486465454,0.38726860676834185,1739137679.7707753,21.509979486465454,1.0452582705709614,1739137679.7707765,21.509979486465454,0.4522912405452123,1739137679.7707782,21.509979486465454,1.6457355442561683,1739137679.7707798,21.509979486465454,0.0,1739137679.7707815,21.509979486465454,0.06859067691742886,1739137679.7707832,21.509979486465454,0.2102372711394895,1739137679.7707846,21.509979486465454,1.6745764843250088 +1739137679.790665,21.529979467391968,45.976048465912804,1739137679.7906675,21.529979467391968,0.36956435575597535,1739137679.7906709,21.529979467391968,45.46205803166669,1739137679.790674,21.529979467391968,51.47182492252684,1739137679.7906752,21.529979467391968,2.6111024179031332,1739137679.7906773,21.529979467391968,0.38726860676834185,1739137679.7906787,21.529979467391968,1.0452582705709614,1739137679.7906804,21.529979467391968,0.4522912405452123,1739137679.7906818,21.529979467391968,1.6457355442561683,1739137679.7906837,21.529979467391968,0.0,1739137679.7906852,21.529979467391968,-0.028840940068840526,1739137679.790687,21.529979467391968,0.2102372711394895,1739137679.7906885,21.529979467391968,1.6745764843250088 +1739137679.8105485,21.54997944831848,45.976048465912804,1739137679.810551,21.54997944831848,0.36956435575597535,1739137679.8105547,21.54997944831848,45.46205803166669,1739137679.8105576,21.54997944831848,51.47182492252684,1739137679.8105593,21.54997944831848,2.6111024179031332,1739137679.8105612,21.54997944831848,0.38726860676834185,1739137679.8105633,21.54997944831848,1.0452582705709614,1739137679.8105648,21.54997944831848,0.4522912405452123,1739137679.8105662,21.54997944831848,1.6457355442561683,1739137679.8105679,21.54997944831848,0.0,1739137679.8105695,21.54997944831848,-0.028840940068840526,1739137679.8105712,21.54997944831848,0.2102372711394895,1739137679.8105729,21.54997944831848,1.6745764843250088 +1739137679.830698,21.569979429244995,45.976048465912804,1739137679.8307006,21.569979429244995,0.36956435575597535,1739137679.830704,21.569979429244995,45.46205803166669,1739137679.8307068,21.569979429244995,51.47182492252684,1739137679.8307087,21.569979429244995,2.6111024179031332,1739137679.8307104,21.569979429244995,0.38726860676834185,1739137679.830712,21.569979429244995,1.0452582705709614,1739137679.8307135,21.569979429244995,0.4522912405452123,1739137679.8307152,21.569979429244995,1.6457355442561683,1739137679.8307166,21.569979429244995,0.0,1739137679.8307183,21.569979429244995,-0.028840940068840526,1739137679.83072,21.569979429244995,0.2102372711394895,1739137679.8307216,21.569979429244995,1.6745764843250088 +1739137679.8526332,21.58997941017151,45.976048465912804,1739137679.852636,21.58997941017151,0.36956435575597535,1739137679.8526394,21.58997941017151,45.46205803166669,1739137679.8526425,21.58997941017151,51.47182492252684,1739137679.8526444,21.58997941017151,2.6111024179031332,1739137679.852646,21.58997941017151,0.38726860676834185,1739137679.852648,21.58997941017151,1.0452582705709614,1739137679.8526497,21.58997941017151,0.4522912405452123,1739137679.8526514,21.58997941017151,1.6457355442561683,1739137679.8526528,21.58997941017151,0.0,1739137679.8526542,21.58997941017151,-0.028840940068840526,1739137679.8526564,21.58997941017151,0.2102372711394895,1739137679.8526576,21.58997941017151,1.6745764843250088 +1739137679.873856,21.609979391098022,45.976048465912804,1739137679.8738644,21.609979391098022,0.36956435575597535,1739137679.8738742,21.609979391098022,45.46205803166669,1739137679.8738842,21.609979391098022,51.47182492252684,1739137679.8738887,21.609979391098022,2.6111024179031332,1739137679.8738945,21.609979391098022,0.38726860676834185,1739137679.8738992,21.609979391098022,1.0452582705709614,1739137679.873904,21.609979391098022,0.4522912405452123,1739137679.8739088,21.609979391098022,1.6457355442561683,1739137679.8739138,21.609979391098022,0.0,1739137679.8739183,21.609979391098022,-0.028840940068840526,1739137679.8739235,21.609979391098022,0.2102372711394895,1739137679.8739288,21.609979391098022,1.6745764843250088 +1739137679.9019954,21.629979372024536,46.15585966494635,1739137679.9020042,21.629979372024536,0.4096562629244307,1739137679.9020157,21.629979372024536,45.46551453635549,1739137679.9020295,21.629979372024536,51.47173222793801,1739137679.9020371,21.629979372024536,2.61090104689982,1739137679.902047,21.629979372024536,0.39259282546892005,1739137679.9020555,21.629979372024536,0.9293833202965187,1739137679.902064,21.629979372024536,0.4282932398217091,1739137679.902073,21.629979372024536,1.7238107695161775,1739137679.9020817,21.629979372024536,0.0,1739137679.9020905,21.629979372024536,0.12255249521926019,1739137679.9021,21.629979372024536,0.23035141446732255,1739137679.9021084,21.629979372024536,1.6733504223520477 +1739137679.9125755,21.64997935295105,46.15585966494635,1739137679.9125795,21.64997935295105,0.4096562629244307,1739137679.9125848,21.64997935295105,45.46551453635549,1739137679.9125903,21.64997935295105,51.47173222793801,1739137679.9125926,21.64997935295105,2.61090104689982,1739137679.912596,21.64997935295105,0.39259282546892005,1739137679.9125986,21.64997935295105,0.9293833202965187,1739137679.912601,21.64997935295105,0.4282932398217091,1739137679.9126036,21.64997935295105,1.7238107695161775,1739137679.9126065,21.64997935295105,0.0,1739137679.9126089,21.64997935295105,0.05046034716412984,1739137679.9126117,21.64997935295105,0.23035141446732255,1739137679.912614,21.64997935295105,1.6733504223520477 +1739137679.9337063,21.669979333877563,46.15585966494635,1739137679.9337134,21.669979333877563,0.4096562629244307,1739137679.9337213,21.669979333877563,45.46551453635549,1739137679.933729,21.669979333877563,51.47173222793801,1739137679.9337325,21.669979333877563,2.61090104689982,1739137679.9337373,21.669979333877563,0.39259282546892005,1739137679.933741,21.669979333877563,0.9293833202965187,1739137679.9337447,21.669979333877563,0.4282932398217091,1739137679.9337485,21.669979333877563,1.7238107695161775,1739137679.9337525,21.669979333877563,0.0,1739137679.9337564,21.669979333877563,0.05046034716412984,1739137679.9337754,21.669979333877563,0.23035141446732255,1739137679.9337783,21.669979333877563,1.6733504223520477 +1739137679.952138,21.689979314804077,46.15585966494635,1739137679.9521422,21.689979314804077,0.4096562629244307,1739137679.952148,21.689979314804077,45.46551453635549,1739137679.9521534,21.689979314804077,51.47173222793801,1739137679.9521558,21.689979314804077,2.61090104689982,1739137679.9521594,21.689979314804077,0.39259282546892005,1739137679.9521623,21.689979314804077,0.9293833202965187,1739137679.9521651,21.689979314804077,0.4282932398217091,1739137679.9521677,21.689979314804077,1.7238107695161775,1739137679.9521708,21.689979314804077,0.0,1739137679.9521735,21.689979314804077,0.05046034716412984,1739137679.9521763,21.689979314804077,0.23035141446732255,1739137679.9521792,21.689979314804077,1.6733504223520477 +1739137679.9754388,21.70997929573059,46.15585966494635,1739137679.9754448,21.70997929573059,0.4096562629244307,1739137679.9754522,21.70997929573059,45.46551453635549,1739137679.975461,21.70997929573059,51.47173222793801,1739137679.975466,21.70997929573059,2.61090104689982,1739137679.9754722,21.70997929573059,0.39259282546892005,1739137679.9754777,21.70997929573059,0.9293833202965187,1739137679.9754832,21.70997929573059,0.4282932398217091,1739137679.9754887,21.70997929573059,1.7238107695161775,1739137679.9754946,21.70997929573059,0.0,1739137679.9755003,21.70997929573059,0.05046034716412984,1739137679.975506,21.70997929573059,0.23035141446732255,1739137679.9755118,21.70997929573059,1.6733504223520477 +1739137679.993154,21.729979276657104,46.33485045594347,1739137679.9931583,21.729979276657104,0.45336335356740154,1739137679.9931633,21.729979276657104,45.46895906847509,1739137679.9931688,21.729979276657104,51.47886635141364,1739137679.993172,21.729979276657104,2.626837374659758,1739137679.993176,21.729979276657104,0.39977222020844605,1739137679.9931796,21.729979276657104,0.8306852584929323,1739137679.9931831,21.729979276657104,0.40664204477230026,1739137679.9931867,21.729979276657104,1.7932267102318193,1739137679.9931903,21.729979276657104,0.0,1739137679.9931939,21.729979276657104,0.17406212090571657,1739137679.9931982,21.729979276657104,0.2504655577951556,1739137679.9932015,21.729979276657104,1.6780226062242474 +1739137680.0125818,21.749979257583618,46.33485045594347,1739137680.0125854,21.749979257583618,0.45336335356740154,1739137680.01259,21.749979257583618,45.46895906847509,1739137680.0125947,21.749979257583618,51.47886635141364,1739137680.0125976,21.749979257583618,2.626837374659758,1739137680.012601,21.749979257583618,0.39977222020844605,1739137680.0126042,21.749979257583618,0.8306852584929323,1739137680.0126073,21.749979257583618,0.40664204477230026,1739137680.0126107,21.749979257583618,1.7932267102318193,1739137680.0126135,21.749979257583618,0.0,1739137680.0126169,21.749979257583618,0.11520410400757197,1739137680.0126202,21.749979257583618,0.2504655577951556,1739137680.0126233,21.749979257583618,1.6780226062242474 +1739137680.0328448,21.769979238510132,46.33485045594347,1739137680.0328486,21.769979238510132,0.45336335356740154,1739137680.0328526,21.769979238510132,45.46895906847509,1739137680.0328574,21.769979238510132,51.47886635141364,1739137680.0328603,21.769979238510132,2.626837374659758,1739137680.0328639,21.769979238510132,0.39977222020844605,1739137680.0328665,21.769979238510132,0.8306852584929323,1739137680.0328698,21.769979238510132,0.40664204477230026,1739137680.032873,21.769979238510132,1.7932267102318193,1739137680.0328765,21.769979238510132,0.0,1739137680.0328794,21.769979238510132,0.11520410400757197,1739137680.0328827,21.769979238510132,0.2504655577951556,1739137680.032886,21.769979238510132,1.6780226062242474 +1739137680.0520482,21.789979219436646,46.33485045594347,1739137680.0520515,21.789979219436646,0.45336335356740154,1739137680.0520556,21.789979219436646,45.46895906847509,1739137680.0520604,21.789979219436646,51.47886635141364,1739137680.0520632,21.789979219436646,2.626837374659758,1739137680.0520668,21.789979219436646,0.39977222020844605,1739137680.05207,21.789979219436646,0.8306852584929323,1739137680.0520732,21.789979219436646,0.40664204477230026,1739137680.0520763,21.789979219436646,1.7932267102318193,1739137680.0520797,21.789979219436646,0.0,1739137680.0520828,21.789979219436646,0.11520410400757197,1739137680.052086,21.789979219436646,0.2504655577951556,1739137680.0520895,21.789979219436646,1.6780226062242474 +1739137680.0722365,21.80997920036316,46.33485045594347,1739137680.0722396,21.80997920036316,0.45336335356740154,1739137680.0722437,21.80997920036316,45.46895906847509,1739137680.0722492,21.80997920036316,51.47886635141364,1739137680.0722518,21.80997920036316,2.626837374659758,1739137680.0722551,21.80997920036316,0.39977222020844605,1739137680.0722585,21.80997920036316,0.8306852584929323,1739137680.0722616,21.80997920036316,0.40664204477230026,1739137680.072265,21.80997920036316,1.7932267102318193,1739137680.0722682,21.80997920036316,0.0,1739137680.0722713,21.80997920036316,0.11520410400757197,1739137680.0722747,21.80997920036316,0.2504655577951556,1739137680.072278,21.80997920036316,1.6780226062242474 +1739137680.0924187,21.829979181289673,46.33485045594347,1739137680.0924222,21.829979181289673,0.45336335356740154,1739137680.0924265,21.829979181289673,45.46895906847509,1739137680.092431,21.829979181289673,51.47886635141364,1739137680.092434,21.829979181289673,2.626837374659758,1739137680.0924373,21.829979181289673,0.39977222020844605,1739137680.0924404,21.829979181289673,0.8306852584929323,1739137680.0924435,21.829979181289673,0.40664204477230026,1739137680.0924466,21.829979181289673,1.7932267102318193,1739137680.0924494,21.829979181289673,0.0,1739137680.0924525,21.829979181289673,0.11520410400757197,1739137680.0924559,21.829979181289673,0.2504655577951556,1739137680.092459,21.829979181289673,1.6780226062242474 +1739137680.112456,21.849979162216187,46.51396262218837,1739137680.1124594,21.849979162216187,0.5009384850450935,1739137680.1124637,21.849979162216187,45.73723550178864,1739137680.1124685,21.849979162216187,51.59211238910007,1739137680.1124713,21.849979162216187,2.9149158177543706,1739137680.112475,21.849979162216187,0.44374653020128124,1739137680.112478,21.849979162216187,0.9688083339302446,1739137680.1124814,21.849979162216187,0.46688635643138476,1739137680.1124845,21.849979162216187,1.6968394918399843,1739137680.1124878,21.849979162216187,0.0,1739137680.1124907,21.849979162216187,-0.09512939304233362,1739137680.112494,21.849979162216187,0.27057970112298896,1739137680.1124973,21.849979162216187,1.6918100267295897 +1739137680.1321886,21.8699791431427,46.51396262218837,1739137680.1321917,21.8699791431427,0.5009384850450935,1739137680.1321964,21.8699791431427,45.73723550178864,1739137680.1322014,21.8699791431427,51.59211238910007,1739137680.132204,21.8699791431427,2.9149158177543706,1739137680.1322076,21.8699791431427,0.44374653020128124,1739137680.132211,21.8699791431427,0.9688083339302446,1739137680.132214,21.8699791431427,0.46688635643138476,1739137680.1322172,21.8699791431427,1.6968394918399843,1739137680.1322205,21.8699791431427,0.0,1739137680.1322236,21.8699791431427,0.005029465110394593,1739137680.1322272,21.8699791431427,0.27057970112298896,1739137680.13223,21.8699791431427,1.6918100267295897 +1739137680.1520534,21.889979124069214,46.51396262218837,1739137680.1520562,21.889979124069214,0.5009384850450935,1739137680.1520605,21.889979124069214,45.73723550178864,1739137680.152065,21.889979124069214,51.59211238910007,1739137680.152068,21.889979124069214,2.9149158177543706,1739137680.1520712,21.889979124069214,0.44374653020128124,1739137680.1520743,21.889979124069214,0.9688083339302446,1739137680.152077,21.889979124069214,0.46688635643138476,1739137680.15208,21.889979124069214,1.6968394918399843,1739137680.1520832,21.889979124069214,0.0,1739137680.1520863,21.889979124069214,0.005029465110394593,1739137680.1520894,21.889979124069214,0.27057970112298896,1739137680.1520925,21.889979124069214,1.6918100267295897 +1739137680.1729028,21.909979104995728,46.51396262218837,1739137680.1729066,21.909979104995728,0.5009384850450935,1739137680.172911,21.909979104995728,45.73723550178864,1739137680.172916,21.909979104995728,51.59211238910007,1739137680.1729186,21.909979104995728,2.9149158177543706,1739137680.172922,21.909979104995728,0.44374653020128124,1739137680.172925,21.909979104995728,0.9688083339302446,1739137680.172928,21.909979104995728,0.46688635643138476,1739137680.1729307,21.909979104995728,1.6968394918399843,1739137680.172934,21.909979104995728,0.0,1739137680.1729372,21.909979104995728,0.005029465110394593,1739137680.1729405,21.909979104995728,0.27057970112298896,1739137680.1729436,21.909979104995728,1.6918100267295897 +1739137680.1906617,21.92997908592224,46.51396262218837,1739137680.1906643,21.92997908592224,0.5009384850450935,1739137680.1906667,21.92997908592224,45.73723550178864,1739137680.1906693,21.92997908592224,51.59211238910007,1739137680.1906705,21.92997908592224,2.9149158177543706,1739137680.1906722,21.92997908592224,0.44374653020128124,1739137680.1906734,21.92997908592224,0.9688083339302446,1739137680.1906748,21.92997908592224,0.46688635643138476,1739137680.1906757,21.92997908592224,1.6968394918399843,1739137680.1906772,21.92997908592224,0.0,1739137680.1906786,21.92997908592224,0.005029465110394593,1739137680.1906798,21.92997908592224,0.27057970112298896,1739137680.190681,21.92997908592224,1.6918100267295897 +1739137680.2106886,21.949979066848755,46.69279327518093,1739137680.2106905,21.949979066848755,0.5523080964635501,1739137680.2106931,21.949979066848755,45.93200057211111,1739137680.2106955,21.949979066848755,51.649927763456375,1739137680.2106967,21.949979066848755,3.0997523318504387,1739137680.2106981,21.949979066848755,0.4747013356935656,1739137680.2106996,21.949979066848755,1.019767663584299,1739137680.2107008,21.949979066848755,0.4995892255133365,1739137680.210702,21.949979066848755,1.6626017030445894,1739137680.2107034,21.949979066848755,0.0,1739137680.2107043,21.949979066848755,-0.05965222520745756,1739137680.2107058,21.949979066848755,0.2906938444508223,1739137680.2107067,21.949979066848755,1.6914531079524286 +1739137680.2303257,21.96997904777527,46.69279327518093,1739137680.2303278,21.96997904777527,0.5523080964635501,1739137680.2303307,21.96997904777527,45.93200057211111,1739137680.230333,21.96997904777527,51.649927763456375,1739137680.2303348,21.96997904777527,3.0997523318504387,1739137680.2303362,21.96997904777527,0.4747013356935656,1739137680.2303379,21.96997904777527,1.019767663584299,1739137680.2303393,21.96997904777527,0.4995892255133365,1739137680.2303407,21.96997904777527,1.6626017030445894,1739137680.2303421,21.96997904777527,0.0,1739137680.2303433,21.96997904777527,-0.028851404907839218,1739137680.230345,21.96997904777527,0.2906938444508223,1739137680.2303464,21.96997904777527,1.6914531079524286 +1739137680.250414,21.989979028701782,46.69279327518093,1739137680.250416,21.989979028701782,0.5523080964635501,1739137680.2504191,21.989979028701782,45.93200057211111,1739137680.2504222,21.989979028701782,51.649927763456375,1739137680.250424,21.989979028701782,3.0997523318504387,1739137680.2504256,21.989979028701782,0.4747013356935656,1739137680.2504272,21.989979028701782,1.019767663584299,1739137680.2504287,21.989979028701782,0.4995892255133365,1739137680.25043,21.989979028701782,1.6626017030445894,1739137680.2504315,21.989979028701782,0.0,1739137680.250433,21.989979028701782,-0.028851404907839218,1739137680.2504346,21.989979028701782,0.2906938444508223,1739137680.2504358,21.989979028701782,1.6914531079524286 +1739137680.2706833,22.009979009628296,46.69279327518093,1739137680.2706857,22.009979009628296,0.5523080964635501,1739137680.2706883,22.009979009628296,45.93200057211111,1739137680.270691,22.009979009628296,51.649927763456375,1739137680.270692,22.009979009628296,3.0997523318504387,1739137680.2706938,22.009979009628296,0.4747013356935656,1739137680.2706952,22.009979009628296,1.019767663584299,1739137680.2706964,22.009979009628296,0.4995892255133365,1739137680.2706978,22.009979009628296,1.6626017030445894,1739137680.270699,22.009979009628296,0.0,1739137680.2707002,22.009979009628296,-0.028851404907839218,1739137680.270702,22.009979009628296,0.2906938444508223,1739137680.2707028,22.009979009628296,1.6914531079524286 +1739137680.2911124,22.02997899055481,46.69279327518093,1739137680.2911148,22.02997899055481,0.5523080964635501,1739137680.2911174,22.02997899055481,45.93200057211111,1739137680.2911196,22.02997899055481,51.649927763456375,1739137680.2911205,22.02997899055481,3.0997523318504387,1739137680.2911222,22.02997899055481,0.4747013356935656,1739137680.2911234,22.02997899055481,1.019767663584299,1739137680.2911248,22.02997899055481,0.4995892255133365,1739137680.2911258,22.02997899055481,1.6626017030445894,1739137680.291127,22.02997899055481,0.0,1739137680.2911284,22.02997899055481,-0.028851404907839218,1739137680.2911298,22.02997899055481,0.2906938444508223,1739137680.291131,22.02997899055481,1.6914531079524286 +1739137680.310441,22.049978971481323,46.69279327518093,1739137680.3104439,22.049978971481323,0.5523080964635501,1739137680.3104465,22.049978971481323,45.93200057211111,1739137680.3104494,22.049978971481323,51.649927763456375,1739137680.310451,22.049978971481323,3.0997523318504387,1739137680.310453,22.049978971481323,0.4747013356935656,1739137680.3104548,22.049978971481323,1.019767663584299,1739137680.3104563,22.049978971481323,0.4995892255133365,1739137680.3104577,22.049978971481323,1.6626017030445894,1739137680.3104594,22.049978971481323,0.0,1739137680.3104606,22.049978971481323,-0.028851404907839218,1739137680.3104622,22.049978971481323,0.2906938444508223,1739137680.3104637,22.049978971481323,1.6914531079524286 +1739137680.3303049,22.069978952407837,46.87033197657631,1739137680.3303068,22.069978952407837,0.6072307231299447,1739137680.3303096,22.069978952407837,46.92302265585855,1739137680.330312,22.069978952407837,51.80771032885702,1739137680.3303132,22.069978952407837,4.064496248283381,1739137680.3303146,22.069978952407837,0.6108755646476445,1739137680.3303163,22.069978952407837,1.777787760358674,1739137680.3303173,22.069978952407837,0.6108,1739137680.3303185,22.069978952407837,1.2277406713373715,1739137680.3303196,22.069978952407837,0.0,1739137680.3303208,22.069978952407837,-0.8518408478826878,1739137680.3303223,22.069978952407837,0.3114748748379626,1739137680.3303235,22.069978952407837,1.6876815886989942 +1739137680.3504577,22.08997893333435,46.87033197657631,1739137680.3504598,22.08997893333435,0.6072307231299447,1739137680.3504624,22.08997893333435,46.92302265585855,1739137680.3504653,22.08997893333435,51.80771032885702,1739137680.3504667,22.08997893333435,4.064496248283381,1739137680.3504815,22.08997893333435,0.6108755646476445,1739137680.350507,22.08997893333435,1.777787760358674,1739137680.3505082,22.08997893333435,0.6108,1739137680.3505096,22.08997893333435,1.2277406713373715,1739137680.350511,22.08997893333435,0.0,1739137680.3505123,22.08997893333435,-0.4599409173616227,1739137680.350514,22.08997893333435,0.3114748748379626,1739137680.3505151,22.08997893333435,1.6876815886989942 +1739137680.370558,22.109978914260864,46.87033197657631,1739137680.37056,22.109978914260864,0.6072307231299447,1739137680.3705626,22.109978914260864,46.92302265585855,1739137680.3705654,22.109978914260864,51.80771032885702,1739137680.3705666,22.109978914260864,4.064496248283381,1739137680.3705685,22.109978914260864,0.6108755646476445,1739137680.3705697,22.109978914260864,1.777787760358674,1739137680.370571,22.109978914260864,0.6108,1739137680.3705723,22.109978914260864,1.2277406713373715,1739137680.3705738,22.109978914260864,0.0,1739137680.3705752,22.109978914260864,-0.4599409173616227,1739137680.3705764,22.109978914260864,0.3114748748379626,1739137680.3705776,22.109978914260864,1.6876815886989942 +1739137680.3903968,22.129978895187378,46.87033197657631,1739137680.3903992,22.129978895187378,0.6072307231299447,1739137680.390402,22.129978895187378,46.92302265585855,1739137680.390405,22.129978895187378,51.80771032885702,1739137680.3904064,22.129978895187378,4.064496248283381,1739137680.3904083,22.129978895187378,0.6108755646476445,1739137680.3904097,22.129978895187378,1.777787760358674,1739137680.3904114,22.129978895187378,0.6108,1739137680.3904126,22.129978895187378,1.2277406713373715,1739137680.390414,22.129978895187378,0.0,1739137680.3904157,22.129978895187378,-0.4599409173616227,1739137680.390417,22.129978895187378,0.3114748748379626,1739137680.3904185,22.129978895187378,1.6876815886989942 +1739137680.4104037,22.14997887611389,46.87033197657631,1739137680.4104059,22.14997887611389,0.6072307231299447,1739137680.4104085,22.14997887611389,46.92302265585855,1739137680.4104111,22.14997887611389,51.80771032885702,1739137680.4104123,22.14997887611389,4.064496248283381,1739137680.4104137,22.14997887611389,0.6108755646476445,1739137680.4104152,22.14997887611389,1.777787760358674,1739137680.4104164,22.14997887611389,0.6108,1739137680.4104173,22.14997887611389,1.2277406713373715,1739137680.410419,22.14997887611389,0.0,1739137680.4104202,22.14997887611389,-0.4599409173616227,1739137680.4104218,22.14997887611389,0.3114748748379626,1739137680.410423,22.14997887611389,1.6876815886989942 +1739137680.4305754,22.169978857040405,47.04385873409026,1739137680.4305775,22.169978857040405,0.6649792758861954,1739137680.43058,22.169978857040405,46.92643516135683,1739137680.4305825,22.169978857040405,51.79771083487528,1739137680.430584,22.169978857040405,3.9065771360709127,1739137680.4305856,22.169978857040405,0.5984670070099708,1739137680.4305868,22.169978857040405,1.5071471648986308,1739137680.4305882,22.169978857040405,0.6108,1739137680.4305894,22.169978857040405,1.3681122445098062,1739137680.4305906,22.169978857040405,0.0,1739137680.430592,22.169978857040405,-0.08908259226650772,1739137680.4305935,22.169978857040405,0.33343923360450983,1739137680.430595,22.169978857040405,1.6337941274216203 +1739137680.4507122,22.18997883796692,47.04385873409026,1739137680.4507148,22.18997883796692,0.6649792758861954,1739137680.450718,22.18997883796692,46.92643516135683,1739137680.4507205,22.18997883796692,51.79771083487528,1739137680.4507217,22.18997883796692,3.9065771360709127,1739137680.4507236,22.18997883796692,0.5984670070099708,1739137680.450725,22.18997883796692,1.5071471648986308,1739137680.4507267,22.18997883796692,0.6108,1739137680.450728,22.18997883796692,1.3681122445098062,1739137680.4507291,22.18997883796692,0.0,1739137680.4507306,22.18997883796692,-0.26568188291181416,1739137680.450732,22.18997883796692,0.33343923360450983,1739137680.4507334,22.18997883796692,1.6337941274216203 +1739137680.470392,22.209978818893433,47.04385873409026,1739137680.4703941,22.209978818893433,0.6649792758861954,1739137680.470397,22.209978818893433,46.92643516135683,1739137680.4703994,22.209978818893433,51.79771083487528,1739137680.4704008,22.209978818893433,3.9065771360709127,1739137680.4704022,22.209978818893433,0.5984670070099708,1739137680.4704037,22.209978818893433,1.5071471648986308,1739137680.470405,22.209978818893433,0.6108,1739137680.4704068,22.209978818893433,1.3681122445098062,1739137680.4704082,22.209978818893433,0.0,1739137680.4704092,22.209978818893433,-0.26568188291181416,1739137680.4704108,22.209978818893433,0.33343923360450983,1739137680.470412,22.209978818893433,1.6337941274216203 +1739137680.490979,22.229978799819946,47.04385873409026,1739137680.4909816,22.229978799819946,0.6649792758861954,1739137680.490985,22.229978799819946,46.92643516135683,1739137680.4909878,22.229978799819946,51.79771083487528,1739137680.490989,22.229978799819946,3.9065771360709127,1739137680.4909906,22.229978799819946,0.5984670070099708,1739137680.490992,22.229978799819946,1.5071471648986308,1739137680.4909937,22.229978799819946,0.6108,1739137680.490995,22.229978799819946,1.3681122445098062,1739137680.4909966,22.229978799819946,0.0,1739137680.4909978,22.229978799819946,-0.26568188291181416,1739137680.4909995,22.229978799819946,0.33343923360450983,1739137680.491001,22.229978799819946,1.6337941274216203 +1739137680.5104177,22.24997878074646,47.04385873409026,1739137680.51042,22.24997878074646,0.6649792758861954,1739137680.5104227,22.24997878074646,46.92643516135683,1739137680.510425,22.24997878074646,51.79771083487528,1739137680.5104263,22.24997878074646,3.9065771360709127,1739137680.5104282,22.24997878074646,0.5984670070099708,1739137680.5104294,22.24997878074646,1.5071471648986308,1739137680.5104308,22.24997878074646,0.6108,1739137680.5104318,22.24997878074646,1.3681122445098062,1739137680.5104332,22.24997878074646,0.0,1739137680.5104346,22.24997878074646,-0.26568188291181416,1739137680.5104363,22.24997878074646,0.33343923360450983,1739137680.5104377,22.24997878074646,1.6337941274216203 +1739137680.530991,22.269978761672974,47.04385873409026,1739137680.5309937,22.269978761672974,0.6649792758861954,1739137680.5309966,22.269978761672974,46.92643516135683,1739137680.5309987,22.269978761672974,51.79771083487528,1739137680.5310001,22.269978761672974,3.9065771360709127,1739137680.5310016,22.269978761672974,0.5984670070099708,1739137680.531003,22.269978761672974,1.5071471648986308,1739137680.5310042,22.269978761672974,0.6108,1739137680.5310056,22.269978761672974,1.3681122445098062,1739137680.531007,22.269978761672974,0.0,1739137680.5310082,22.269978761672974,-0.26568188291181416,1739137680.5310094,22.269978761672974,0.33343923360450983,1739137680.5310109,22.269978761672974,1.6337941274216203 +1739137680.5503573,22.289978742599487,47.21184044381579,1739137680.5503592,22.289978742599487,0.7251602382258655,1739137680.5503616,22.289978742599487,46.929747175766295,1739137680.550364,22.289978742599487,51.788939231150685,1739137680.5503652,22.289978742599487,3.8220507729066115,1739137680.5503666,22.289978742599487,0.5948518564919476,1739137680.550368,22.289978742599487,1.3015564155848744,1739137680.5503693,22.289978742599487,0.6108,1739137680.5503705,22.289978742599487,1.485376336856152,1739137680.550372,22.289978742599487,0.0,1739137680.5503728,22.289978742599487,0.014372059142004734,1739137680.550374,22.289978742599487,0.35710012660206103,1739137680.5503752,22.289978742599487,1.6043633643584654 +1739137680.5707417,22.309978723526,47.21184044381579,1739137680.570744,22.309978723526,0.7251602382258655,1739137680.5707467,22.309978723526,46.929747175766295,1739137680.5707493,22.309978723526,51.788939231150685,1739137680.5707502,22.309978723526,3.8220507729066115,1739137680.570752,22.309978723526,0.5948518564919476,1739137680.5707533,22.309978723526,1.3015564155848744,1739137680.5707545,22.309978723526,0.6108,1739137680.5707555,22.309978723526,1.485376336856152,1739137680.5707572,22.309978723526,0.0,1739137680.570758,22.309978723526,-0.11898702750231349,1739137680.5707598,22.309978723526,0.35710012660206103,1739137680.570761,22.309978723526,1.6043633643584654 +1739137680.591273,22.329978704452515,47.21184044381579,1739137680.5912752,22.329978704452515,0.7251602382258655,1739137680.591278,22.329978704452515,46.929747175766295,1739137680.5912807,22.329978704452515,51.788939231150685,1739137680.591282,22.329978704452515,3.8220507729066115,1739137680.5912836,22.329978704452515,0.5948518564919476,1739137680.5912848,22.329978704452515,1.3015564155848744,1739137680.591286,22.329978704452515,0.6108,1739137680.5912871,22.329978704452515,1.485376336856152,1739137680.5912886,22.329978704452515,0.0,1739137680.5912895,22.329978704452515,-0.11898702750231349,1739137680.591291,22.329978704452515,0.35710012660206103,1739137680.5912924,22.329978704452515,1.6043633643584654 +1739137680.6104443,22.34997868537903,47.21184044381579,1739137680.6104467,22.34997868537903,0.7251602382258655,1739137680.6104493,22.34997868537903,46.929747175766295,1739137680.6104522,22.34997868537903,51.788939231150685,1739137680.6104536,22.34997868537903,3.8220507729066115,1739137680.610455,22.34997868537903,0.5948518564919476,1739137680.6104565,22.34997868537903,1.3015564155848744,1739137680.610458,22.34997868537903,0.6108,1739137680.610459,22.34997868537903,1.485376336856152,1739137680.6104605,22.34997868537903,0.0,1739137680.6104617,22.34997868537903,-0.11898702750231349,1739137680.6104631,22.34997868537903,0.35710012660206103,1739137680.6104646,22.34997868537903,1.6043633643584654 +1739137680.6306467,22.369978666305542,47.21184044381579,1739137680.6306489,22.369978666305542,0.7251602382258655,1739137680.6306515,22.369978666305542,46.929747175766295,1739137680.6306539,22.369978666305542,51.788939231150685,1739137680.630655,22.369978666305542,3.8220507729066115,1739137680.6306565,22.369978666305542,0.5948518564919476,1739137680.6306577,22.369978666305542,1.3015564155848744,1739137680.630659,22.369978666305542,0.6108,1739137680.63066,22.369978666305542,1.485376336856152,1739137680.6306617,22.369978666305542,0.0,1739137680.6306627,22.369978666305542,-0.11898702750231349,1739137680.6306643,22.369978666305542,0.35710012660206103,1739137680.6306655,22.369978666305542,1.6043633643584654 +1739137680.6503947,22.389978647232056,47.37589705339015,1739137680.6503973,22.389978647232056,0.7885080538314018,1739137680.6504,22.389978647232056,47.319456946808465,1739137680.6504025,22.389978647232056,51.811757817478004,1739137680.6504037,22.389978647232056,4.174175972903104,1739137680.6504054,22.389978647232056,0.6519269172484825,1739137680.6504066,22.389978647232056,1.485189979713963,1739137680.650408,22.389978647232056,0.6108,1739137680.650409,22.389978647232056,1.3801811242160353,1739137680.6504104,22.389978647232056,0.0,1739137680.6504118,22.389978647232056,-0.2964454943526272,1739137680.650416,22.389978647232056,0.3825308155297683,1739137680.6504216,22.389978647232056,1.5921225445217029 +1739137680.6752539,22.40997862815857,47.37589705339015,1739137680.675264,22.40997862815857,0.7885080538314018,1739137680.6752748,22.40997862815857,47.319456946808465,1739137680.675285,22.40997862815857,51.811757817478004,1739137680.6752899,22.40997862815857,4.174175972903104,1739137680.675296,22.40997862815857,0.6519269172484825,1739137680.675301,22.40997862815857,1.485189979713963,1739137680.675306,22.40997862815857,0.6108,1739137680.675311,22.40997862815857,1.3801811242160353,1739137680.6753163,22.40997862815857,0.0,1739137680.6753209,22.40997862815857,-0.21194142030566754,1739137680.6753342,22.40997862815857,0.3825308155297683,1739137680.6753495,22.40997862815857,1.5921225445217029 +1739137680.7016613,22.429978609085083,47.37589705339015,1739137680.7016747,22.429978609085083,0.7885080538314018,1739137680.7016916,22.429978609085083,47.319456946808465,1739137680.7017112,22.429978609085083,51.811757817478004,1739137680.701722,22.429978609085083,4.174175972903104,1739137680.701736,22.429978609085083,0.6519269172484825,1739137680.7017484,22.429978609085083,1.485189979713963,1739137680.7017608,22.429978609085083,0.6108,1739137680.7017732,22.429978609085083,1.3801811242160353,1739137680.7017858,22.429978609085083,0.0,1739137680.7017984,22.429978609085083,-0.21194142030566754,1739137680.7018118,22.429978609085083,0.3825308155297683,1739137680.701824,22.429978609085083,1.5921225445217029 +1739137680.7198966,22.449978590011597,47.37589705339015,1739137680.7199063,22.449978590011597,0.7885080538314018,1739137680.7199163,22.449978590011597,47.319456946808465,1739137680.7199264,22.449978590011597,51.811757817478004,1739137680.7199311,22.449978590011597,4.174175972903104,1739137680.7199376,22.449978590011597,0.6519269172484825,1739137680.7199426,22.449978590011597,1.485189979713963,1739137680.7199478,22.449978590011597,0.6108,1739137680.7199523,22.449978590011597,1.3801811242160353,1739137680.719958,22.449978590011597,0.0,1739137680.7199628,22.449978590011597,-0.21194142030566754,1739137680.7199686,22.449978590011597,0.3825308155297683,1739137680.719973,22.449978590011597,1.5921225445217029 +1739137680.7538774,22.479978561401367,47.37589705339015,1739137680.7538824,22.479978561401367,0.7885080538314018,1739137680.7538877,22.479978561401367,47.319456946808465,1739137680.7538931,22.479978561401367,51.811757817478004,1739137680.753896,22.479978561401367,4.174175972903104,1739137680.753899,22.479978561401367,0.6519269172484825,1739137680.7539015,22.479978561401367,1.485189979713963,1739137680.753904,22.479978561401367,0.6108,1739137680.7539067,22.479978561401367,1.3801811242160353,1739137680.7539098,22.479978561401367,0.0,1739137680.7539122,22.479978561401367,-0.21194142030566754,1739137680.753915,22.479978561401367,0.3825308155297683,1739137680.7539177,22.479978561401367,1.5921225445217029 +1739137680.7717881,22.509978532791138,47.53601435803696,1739137680.7717915,22.509978532791138,0.8552096499548014,1739137680.771795,22.509978532791138,47.60258594040884,1739137680.7717988,22.509978532791138,51.812129997252015,1739137680.7718005,22.509978532791138,4.35706037922139,1739137680.771803,22.509978532791138,0.6861791035269119,1739137680.7718046,22.509978532791138,1.508695978063114,1739137680.7718067,22.509978532791138,0.6108,1739137680.7718081,22.509978532791138,1.3672649269023252,1739137680.7718103,22.509978532791138,0.0,1739137680.7718122,22.509978532791138,-0.17281985747160217,1739137680.771814,22.509978532791138,0.40970373706576446,1739137680.771816,22.509978532791138,1.5587141093153583 +1739137680.7909691,22.52997851371765,47.53601435803696,1739137680.790972,22.52997851371765,0.8552096499548014,1739137680.7909746,22.52997851371765,47.60258594040884,1739137680.7909775,22.52997851371765,51.812129997252015,1739137680.790979,22.52997851371765,4.35706037922139,1739137680.7909808,22.52997851371765,0.6861791035269119,1739137680.7909822,22.52997851371765,1.508695978063114,1739137680.7909834,22.52997851371765,0.6108,1739137680.7909846,22.52997851371765,1.3672649269023252,1739137680.7909863,22.52997851371765,0.0,1739137680.7909875,22.52997851371765,-0.1914491824130331,1739137680.7909892,22.52997851371765,0.40970373706576446,1739137680.7909904,22.52997851371765,1.5587141093153583 +1739137680.8116605,22.549978494644165,47.53601435803696,1739137680.811663,22.549978494644165,0.8552096499548014,1739137680.8116658,22.549978494644165,47.60258594040884,1739137680.8116682,22.549978494644165,51.812129997252015,1739137680.8116696,22.549978494644165,4.35706037922139,1739137680.811671,22.549978494644165,0.6861791035269119,1739137680.8116722,22.549978494644165,1.508695978063114,1739137680.8116734,22.549978494644165,0.6108,1739137680.8116746,22.549978494644165,1.3672649269023252,1739137680.8116765,22.549978494644165,0.0,1739137680.8116777,22.549978494644165,-0.1914491824130331,1739137680.811679,22.549978494644165,0.40970373706576446,1739137680.8116803,22.549978494644165,1.5587141093153583 +1739137680.8306222,22.56997847557068,47.53601435803696,1739137680.8306243,22.56997847557068,0.8552096499548014,1739137680.830627,22.56997847557068,47.60258594040884,1739137680.8306293,22.56997847557068,51.812129997252015,1739137680.8306305,22.56997847557068,4.35706037922139,1739137680.8306322,22.56997847557068,0.6861791035269119,1739137680.8306334,22.56997847557068,1.508695978063114,1739137680.8306348,22.56997847557068,0.6108,1739137680.830636,22.56997847557068,1.3672649269023252,1739137680.8306375,22.56997847557068,0.0,1739137680.830639,22.56997847557068,-0.1914491824130331,1739137680.83064,22.56997847557068,0.40970373706576446,1739137680.8306415,22.56997847557068,1.5587141093153583 +1739137680.85102,22.589978456497192,47.53601435803696,1739137680.851023,22.589978456497192,0.8552096499548014,1739137680.8510258,22.589978456497192,47.60258594040884,1739137680.8510284,22.589978456497192,51.812129997252015,1739137680.85103,22.589978456497192,4.35706037922139,1739137680.8510315,22.589978456497192,0.6861791035269119,1739137680.8510327,22.589978456497192,1.508695978063114,1739137680.8510342,22.589978456497192,0.6108,1739137680.8510354,22.589978456497192,1.3672649269023252,1739137680.851037,22.589978456497192,0.0,1739137680.8510382,22.589978456497192,-0.1914491824130331,1739137680.8510396,22.589978456497192,0.40970373706576446,1739137680.851041,22.589978456497192,1.5587141093153583 +1739137680.872723,22.609978437423706,47.691380696091834,1739137680.8727267,22.609978437423706,0.9250061784086654,1739137680.8727317,22.609978437423706,47.705256615402504,1739137680.872737,22.609978437423706,51.811573553781464,1739137680.8727398,22.609978437423706,4.3946165260525305,1739137680.8727438,22.609978437423706,0.6998892140600791,1739137680.8727474,22.609978437423706,1.398186472811284,1739137680.872751,22.609978437423706,0.6108,1739137680.8727543,22.609978437423706,1.4290589386083485,1739137680.8727584,22.609978437423706,0.0,1739137680.872762,22.609978437423706,-0.032045455221658414,1739137680.8727655,22.609978437423706,0.43730895126667974,1739137680.8727694,22.609978437423706,1.5370109685064548 +1739137680.8906605,22.62997841835022,47.691380696091834,1739137680.8906662,22.62997841835022,0.9250061784086654,1739137680.890672,22.62997841835022,47.705256615402504,1739137680.8906753,22.62997841835022,51.811573553781464,1739137680.8906765,22.62997841835022,4.3946165260525305,1739137680.8906782,22.62997841835022,0.6998892140600791,1739137680.8906796,22.62997841835022,1.398186472811284,1739137680.8906808,22.62997841835022,0.6108,1739137680.8906822,22.62997841835022,1.4290589386083485,1739137680.890684,22.62997841835022,0.0,1739137680.890685,22.62997841835022,-0.10795202989810626,1739137680.8906865,22.62997841835022,0.43730895126667974,1739137680.8906877,22.62997841835022,1.5370109685064548 +1739137680.9103518,22.649978399276733,47.691380696091834,1739137680.9103558,22.649978399276733,0.9250061784086654,1739137680.9103603,22.649978399276733,47.705256615402504,1739137680.9103642,22.649978399276733,51.811573553781464,1739137680.9103668,22.649978399276733,4.3946165260525305,1739137680.9103699,22.649978399276733,0.6998892140600791,1739137680.9103723,22.649978399276733,1.398186472811284,1739137680.9103808,22.649978399276733,0.6108,1739137680.9103827,22.649978399276733,1.4290589386083485,1739137680.9103856,22.649978399276733,0.0,1739137680.9103878,22.649978399276733,-0.10795202989810626,1739137680.91039,22.649978399276733,0.43730895126667974,1739137680.910396,22.649978399276733,1.5370109685064548 +1739137680.9303255,22.669978380203247,47.691380696091834,1739137680.9303277,22.669978380203247,0.9250061784086654,1739137680.9303303,22.669978380203247,47.705256615402504,1739137680.930333,22.669978380203247,51.811573553781464,1739137680.930334,22.669978380203247,4.3946165260525305,1739137680.9303358,22.669978380203247,0.6998892140600791,1739137680.9303372,22.669978380203247,1.398186472811284,1739137680.9303386,22.669978380203247,0.6108,1739137680.9303398,22.669978380203247,1.4290589386083485,1739137680.9303415,22.669978380203247,0.0,1739137680.9303427,22.669978380203247,-0.10795202989810626,1739137680.9303439,22.669978380203247,0.43730895126667974,1739137680.930345,22.669978380203247,1.5370109685064548 +1739137680.954106,22.68997836112976,47.691380696091834,1739137680.9541147,22.68997836112976,0.9250061784086654,1739137680.9541242,22.68997836112976,47.705256615402504,1739137680.9541342,22.68997836112976,51.811573553781464,1739137680.9541392,22.68997836112976,4.3946165260525305,1739137680.954145,22.68997836112976,0.6998892140600791,1739137680.95415,22.68997836112976,1.398186472811284,1739137680.9541545,22.68997836112976,0.6108,1739137680.954159,22.68997836112976,1.4290589386083485,1739137680.9541645,22.68997836112976,0.0,1739137680.9541693,22.68997836112976,-0.10795202989810626,1739137680.9541745,22.68997836112976,0.43730895126667974,1739137680.954179,22.68997836112976,1.5370109685064548 +1739137680.9749618,22.709978342056274,47.691380696091834,1739137680.9749699,22.709978342056274,0.9250061784086654,1739137680.9749794,22.709978342056274,47.705256615402504,1739137680.9749897,22.709978342056274,51.811573553781464,1739137680.9749942,22.709978342056274,4.3946165260525305,1739137680.975,22.709978342056274,0.6998892140600791,1739137680.975005,22.709978342056274,1.398186472811284,1739137680.9750094,22.709978342056274,0.6108,1739137680.9750142,22.709978342056274,1.4290589386083485,1739137680.9750195,22.709978342056274,0.0,1739137680.9750242,22.709978342056274,-0.10795202989810626,1739137680.9750295,22.709978342056274,0.43730895126667974,1739137680.975034,22.709978342056274,1.5370109685064548 +1739137681.00787,22.729978322982788,47.84322335608759,1739137681.0078783,22.729978322982788,0.9983247197067042,1739137681.007888,22.729978322982788,47.88344323281679,1739137681.0078974,22.729978322982788,51.80632862262217,1739137681.007902,22.729978322982788,4.541742038045361,1739137681.0079079,22.729978322982788,0.7295465409416487,1739137681.0079129,22.729978322982788,1.390476483048391,1739137681.007918,22.729978322982788,0.6108,1739137681.0079224,22.729978322982788,1.4334729534265722,1739137681.007928,22.729978322982788,0.0,1739137681.0079324,22.729978322982788,-0.07982267431087696,1739137681.0079374,22.729978322982788,0.464914165467595,1739137681.0079422,22.729978322982788,1.5266905656608198 +1739137681.0273063,22.75997829437256,47.84322335608759,1739137681.027315,22.75997829437256,0.9983247197067042,1739137681.0273247,22.75997829437256,47.88344323281679,1739137681.0273347,22.75997829437256,51.80632862262217,1739137681.027339,22.75997829437256,4.541742038045361,1739137681.027345,22.75997829437256,0.7295465409416487,1739137681.0273497,22.75997829437256,1.390476483048391,1739137681.0273545,22.75997829437256,0.6108,1739137681.027359,22.75997829437256,1.4334729534265722,1739137681.0273643,22.75997829437256,0.0,1739137681.027369,22.75997829437256,-0.09321761223424763,1739137681.027374,22.75997829437256,0.464914165467595,1739137681.0273788,22.75997829437256,1.5266905656608198 +1739137681.0585458,22.779978275299072,47.84322335608759,1739137681.0585544,22.779978275299072,0.9983247197067042,1739137681.0585647,22.779978275299072,47.88344323281679,1739137681.0585744,22.779978275299072,51.80632862262217,1739137681.058579,22.779978275299072,4.541742038045361,1739137681.0585847,22.779978275299072,0.7295465409416487,1739137681.0585895,22.779978275299072,1.390476483048391,1739137681.0585938,22.779978275299072,0.6108,1739137681.0585985,22.779978275299072,1.4334729534265722,1739137681.0586042,22.779978275299072,0.0,1739137681.058609,22.779978275299072,-0.09321761223424763,1739137681.058614,22.779978275299072,0.464914165467595,1739137681.0586185,22.779978275299072,1.5266905656608198 +1739137681.078455,22.809978246688843,47.84322335608759,1739137681.0784643,22.809978246688843,0.9983247197067042,1739137681.078513,22.809978246688843,47.88344323281679,1739137681.0785403,22.809978246688843,51.80632862262217,1739137681.0785475,22.809978246688843,4.541742038045361,1739137681.0785549,22.809978246688843,0.7295465409416487,1739137681.07856,22.809978246688843,1.390476483048391,1739137681.0785646,22.809978246688843,0.6108,1739137681.0785694,22.809978246688843,1.4334729534265722,1739137681.0785747,22.809978246688843,0.0,1739137681.0785792,22.809978246688843,-0.09321761223424763,1739137681.0785844,22.809978246688843,0.464914165467595,1739137681.0785892,22.809978246688843,1.5266905656608198 +1739137681.099261,22.829978227615356,47.99191467854332,1739137681.099266,22.829978227615356,1.0752531598294643,1739137681.0992715,22.829978227615356,47.886576081703936,1739137681.0992765,22.829978227615356,51.80760946678779,1739137681.0992792,22.829978227615356,4.514239663335945,1739137681.0992825,22.829978227615356,0.7335185233144185,1739137681.0992854,22.829978227615356,1.226002542453564,1739137681.0992875,22.829978227615356,0.6108,1739137681.0992901,22.829978227615356,1.530951924625337,1739137681.099293,22.829978227615356,0.0,1739137681.0992954,22.829978227615356,0.11239422876624099,1739137681.0992982,22.829978227615356,0.4925193796685103,1739137681.0993009,22.829978227615356,1.5164681452460662 +1739137681.120069,22.84997820854187,47.99191467854332,1739137681.120074,22.84997820854187,1.0752531598294643,1739137681.120079,22.84997820854187,47.886576081703936,1739137681.120084,22.84997820854187,51.80760946678779,1739137681.1200862,22.84997820854187,4.514239663335945,1739137681.120089,22.84997820854187,0.7335185233144185,1739137681.1200914,22.84997820854187,1.226002542453564,1739137681.1200936,22.84997820854187,0.6108,1739137681.1200957,22.84997820854187,1.530951924625337,1739137681.1200984,22.84997820854187,0.0,1739137681.1201003,22.84997820854187,0.0144837793792707,1739137681.1201026,22.84997820854187,0.4925193796685103,1739137681.120105,22.84997820854187,1.5164681452460662 +1739137681.1389308,22.869978189468384,47.99191467854332,1739137681.1389368,22.869978189468384,1.0752531598294643,1739137681.1389437,22.869978189468384,47.886576081703936,1739137681.138951,22.869978189468384,51.80760946678779,1739137681.1389558,22.869978189468384,4.514239663335945,1739137681.138961,22.869978189468384,0.7335185233144185,1739137681.1389678,22.869978189468384,1.226002542453564,1739137681.1389737,22.869978189468384,0.6108,1739137681.138978,22.869978189468384,1.530951924625337,1739137681.1389823,22.869978189468384,0.0,1739137681.1389866,22.869978189468384,0.0144837793792707,1739137681.1389914,22.869978189468384,0.4925193796685103,1739137681.138996,22.869978189468384,1.5164681452460662 +1739137681.1574833,22.889978170394897,47.99191467854332,1739137681.1574874,22.889978170394897,1.0752531598294643,1739137681.1574914,22.889978170394897,47.886576081703936,1739137681.1574957,22.889978170394897,51.80760946678779,1739137681.1574981,22.889978170394897,4.514239663335945,1739137681.1575007,22.889978170394897,0.7335185233144185,1739137681.157503,22.889978170394897,1.226002542453564,1739137681.1575048,22.889978170394897,0.6108,1739137681.1575067,22.889978170394897,1.530951924625337,1739137681.157509,22.889978170394897,0.0,1739137681.1575112,22.889978170394897,0.0144837793792707,1739137681.1575134,22.889978170394897,0.4925193796685103,1739137681.1575153,22.889978170394897,1.5164681452460662 +1739137681.1771982,22.90997815132141,47.99191467854332,1739137681.1772017,22.90997815132141,1.0752531598294643,1739137681.177206,22.90997815132141,47.886576081703936,1739137681.17721,22.90997815132141,51.80760946678779,1739137681.1772122,22.90997815132141,4.514239663335945,1739137681.1772149,22.90997815132141,0.7335185233144185,1739137681.177217,22.90997815132141,1.226002542453564,1739137681.177219,22.90997815132141,0.6108,1739137681.1772206,22.90997815132141,1.530951924625337,1739137681.177223,22.90997815132141,0.0,1739137681.1772249,22.90997815132141,0.0144837793792707,1739137681.1772273,22.90997815132141,0.4925193796685103,1739137681.1772294,22.90997815132141,1.5164681452460662 +1739137681.1978252,22.929978132247925,47.99191467854332,1739137681.1978288,22.929978132247925,1.0752531598294643,1739137681.1978335,22.929978132247925,47.886576081703936,1739137681.1978378,22.929978132247925,51.80760946678779,1739137681.1978402,22.929978132247925,4.514239663335945,1739137681.1978424,22.929978132247925,0.7335185233144185,1739137681.1978447,22.929978132247925,1.226002542453564,1739137681.197847,22.929978132247925,0.6108,1739137681.1978486,22.929978132247925,1.530951924625337,1739137681.1978512,22.929978132247925,0.0,1739137681.197853,22.929978132247925,0.0144837793792707,1739137681.1978557,22.929978132247925,0.4925193796685103,1739137681.1978579,22.929978132247925,1.5164681452460662 +1739137681.2170212,22.94997811317444,48.13819346235161,1739137681.2170246,22.94997811317444,1.1561319226195756,1739137681.2170281,22.94997811317444,47.88967889364746,1739137681.2170317,22.94997811317444,51.80700580360543,1739137681.2170336,22.94997811317444,4.53084040085084,1739137681.2170358,22.94997811317444,0.7436671703595392,1739137681.217038,22.94997811317444,1.1050711404634599,1739137681.2170393,22.94997811317444,0.6108,1739137681.2170408,22.94997811317444,1.6068283637824534,1739137681.217043,22.94997811317444,0.0,1739137681.2170446,22.94997811317444,0.15074229024226515,1739137681.2170465,22.94997811317444,0.5201245938694251,1739137681.2170482,22.94997811317444,1.5209711111259538 +1739137681.2367291,22.969978094100952,48.13819346235161,1739137681.236732,22.969978094100952,1.1561319226195756,1739137681.2367346,22.969978094100952,47.88967889364746,1739137681.2367373,22.969978094100952,51.80700580360543,1739137681.2367384,22.969978094100952,4.53084040085084,1739137681.2367404,22.969978094100952,0.7436671703595392,1739137681.2367415,22.969978094100952,1.1050711404634599,1739137681.236743,22.969978094100952,0.6108,1739137681.2367442,22.969978094100952,1.6068283637824534,1739137681.2367463,22.969978094100952,0.0,1739137681.2367475,22.969978094100952,0.08585725265649957,1739137681.2367492,22.969978094100952,0.5201245938694251,1739137681.2367504,22.969978094100952,1.5209711111259538 +1739137681.25683,22.989978075027466,48.13819346235161,1739137681.2568324,22.989978075027466,1.1561319226195756,1739137681.2568347,22.989978075027466,47.88967889364746,1739137681.2568374,22.989978075027466,51.80700580360543,1739137681.2568386,22.989978075027466,4.53084040085084,1739137681.2568402,22.989978075027466,0.7436671703595392,1739137681.2568414,22.989978075027466,1.1050711404634599,1739137681.2568426,22.989978075027466,0.6108,1739137681.256844,22.989978075027466,1.6068283637824534,1739137681.2568455,22.989978075027466,0.0,1739137681.2568467,22.989978075027466,0.08585725265649957,1739137681.256848,22.989978075027466,0.5201245938694251,1739137681.256849,22.989978075027466,1.5209711111259538 +1739137681.2776105,23.00997805595398,48.13819346235161,1739137681.2776127,23.00997805595398,1.1561319226195756,1739137681.2776153,23.00997805595398,47.88967889364746,1739137681.277618,23.00997805595398,51.80700580360543,1739137681.2776191,23.00997805595398,4.53084040085084,1739137681.2776208,23.00997805595398,0.7436671703595392,1739137681.277622,23.00997805595398,1.1050711404634599,1739137681.2776234,23.00997805595398,0.6108,1739137681.2776246,23.00997805595398,1.6068283637824534,1739137681.277626,23.00997805595398,0.0,1739137681.2776275,23.00997805595398,0.08585725265649957,1739137681.2776287,23.00997805595398,0.5201245938694251,1739137681.2776299,23.00997805595398,1.5209711111259538 +1739137681.2965262,23.029978036880493,48.13819346235161,1739137681.2965286,23.029978036880493,1.1561319226195756,1739137681.2965312,23.029978036880493,47.88967889364746,1739137681.296534,23.029978036880493,51.80700580360543,1739137681.2965355,23.029978036880493,4.53084040085084,1739137681.2965372,23.029978036880493,0.7436671703595392,1739137681.2965384,23.029978036880493,1.1050711404634599,1739137681.2965395,23.029978036880493,0.6108,1739137681.2965407,23.029978036880493,1.6068283637824534,1739137681.2965422,23.029978036880493,0.0,1739137681.2965436,23.029978036880493,0.08585725265649957,1739137681.296545,23.029978036880493,0.5201245938694251,1739137681.296546,23.029978036880493,1.5209711111259538 +1739137681.3162677,23.049978017807007,48.2827535186882,1739137681.3162704,23.049978017807007,1.2413549166853741,1739137681.3162732,23.049978017807007,48.56388924016312,1739137681.3162756,23.049978017807007,51.70656459217419,1739137681.3162773,23.049978017807007,5.2269665121243944,1739137681.3162787,23.049978017807007,0.8610758025907366,1739137681.3162804,23.049978017807007,1.619600896537859,1739137681.3162816,23.049978017807007,0.6108,1739137681.3162832,23.049978017807007,1.3079360668155304,1739137681.3162847,23.049978017807007,0.0,1739137681.3162863,23.049978017807007,-0.5038152423470939,1739137681.3162878,23.049978017807007,0.5477298080703398,1739137681.316289,23.049978017807007,1.530954742700284 +1739137681.3362312,23.06997799873352,48.2827535186882,1739137681.3362343,23.06997799873352,1.2413549166853741,1739137681.3362374,23.06997799873352,48.56388924016312,1739137681.33624,23.06997799873352,51.70656459217419,1739137681.3362417,23.06997799873352,5.2269665121243944,1739137681.3362434,23.06997799873352,0.8610758025907366,1739137681.336245,23.06997799873352,1.619600896537859,1739137681.3362463,23.06997799873352,0.6108,1739137681.3362474,23.06997799873352,1.3079360668155304,1739137681.336249,23.06997799873352,0.0,1739137681.3362503,23.06997799873352,-0.22301867588475366,1739137681.336252,23.06997799873352,0.5477298080703398,1739137681.3362532,23.06997799873352,1.530954742700284 +1739137681.3561964,23.089977979660034,48.2827535186882,1739137681.3561993,23.089977979660034,1.2413549166853741,1739137681.3562021,23.089977979660034,48.56388924016312,1739137681.356205,23.089977979660034,51.70656459217419,1739137681.3562064,23.089977979660034,5.2269665121243944,1739137681.356208,23.089977979660034,0.8610758025907366,1739137681.3562095,23.089977979660034,1.619600896537859,1739137681.3562112,23.089977979660034,0.6108,1739137681.3562124,23.089977979660034,1.3079360668155304,1739137681.356214,23.089977979660034,0.0,1739137681.3562152,23.089977979660034,-0.22301867588475366,1739137681.356217,23.089977979660034,0.5477298080703398,1739137681.356218,23.089977979660034,1.530954742700284 +1739137681.3763554,23.109977960586548,48.2827535186882,1739137681.3763578,23.109977960586548,1.2413549166853741,1739137681.3763607,23.109977960586548,48.56388924016312,1739137681.3763633,23.109977960586548,51.70656459217419,1739137681.3763645,23.109977960586548,5.2269665121243944,1739137681.3763664,23.109977960586548,0.8610758025907366,1739137681.3763676,23.109977960586548,1.619600896537859,1739137681.376369,23.109977960586548,0.6108,1739137681.3763702,23.109977960586548,1.3079360668155304,1739137681.3763716,23.109977960586548,0.0,1739137681.376373,23.109977960586548,-0.22301867588475366,1739137681.3763745,23.109977960586548,0.5477298080703398,1739137681.376376,23.109977960586548,1.530954742700284 +1739137681.3964171,23.12997794151306,48.2827535186882,1739137681.3964195,23.12997794151306,1.2413549166853741,1739137681.3964226,23.12997794151306,48.56388924016312,1739137681.3964255,23.12997794151306,51.70656459217419,1739137681.396427,23.12997794151306,5.2269665121243944,1739137681.3964288,23.12997794151306,0.8610758025907366,1739137681.3964303,23.12997794151306,1.619600896537859,1739137681.396432,23.12997794151306,0.6108,1739137681.3964334,23.12997794151306,1.3079360668155304,1739137681.396435,23.12997794151306,0.0,1739137681.3964365,23.12997794151306,-0.22301867588475366,1739137681.3964381,23.12997794151306,0.5477298080703398,1739137681.3964396,23.12997794151306,1.530954742700284 +1739137681.4168315,23.149977922439575,48.2827535186882,1739137681.4168346,23.149977922439575,1.2413549166853741,1739137681.4168375,23.149977922439575,48.56388924016312,1739137681.4168406,23.149977922439575,51.70656459217419,1739137681.416842,23.149977922439575,5.2269665121243944,1739137681.416844,23.149977922439575,0.8610758025907366,1739137681.416845,23.149977922439575,1.619600896537859,1739137681.4168465,23.149977922439575,0.6108,1739137681.416848,23.149977922439575,1.3079360668155304,1739137681.4168496,23.149977922439575,0.0,1739137681.416851,23.149977922439575,-0.22301867588475366,1739137681.4168525,23.149977922439575,0.5477298080703398,1739137681.4168537,23.149977922439575,1.530954742700284 +1739137681.437873,23.16997790336609,48.42368977788374,1739137681.4378774,23.16997790336609,1.3297587809735694,1739137681.4378824,23.16997790336609,48.753877795453704,1739137681.4378872,23.16997790336609,51.688195098983385,1739137681.4378896,23.16997790336609,5.304060257535323,1739137681.4378927,23.16997790336609,0.8831400144640593,1739137681.4378948,23.16997790336609,1.5582096367515823,1739137681.4378972,23.16997790336609,0.6108,1739137681.4378996,23.16997790336609,1.340452008921046,1739137681.437902,23.16997790336609,0.0,1739137681.4379044,23.16997790336609,-0.09047488986570279,1739137681.437907,23.16997790336609,0.5753350222712544,1739137681.4379094,23.16997790336609,1.4940430188965088 +1739137681.459141,23.189977884292603,48.42368977788374,1739137681.4591458,23.189977884292603,1.3297587809735694,1739137681.4591506,23.189977884292603,48.753877795453704,1739137681.4591556,23.189977884292603,51.688195098983385,1739137681.4591577,23.189977884292603,5.304060257535323,1739137681.4591608,23.189977884292603,0.8831400144640593,1739137681.459164,23.189977884292603,1.5582096367515823,1739137681.4591663,23.189977884292603,0.6108,1739137681.4591684,23.189977884292603,1.340452008921046,1739137681.459171,23.189977884292603,0.0,1739137681.4591737,23.189977884292603,-0.1535910099754627,1739137681.4591763,23.189977884292603,0.5753350222712544,1739137681.4591784,23.189977884292603,1.4940430188965088 +1739137681.4777694,23.209977865219116,48.42368977788374,1739137681.477774,23.209977865219116,1.3297587809735694,1739137681.4777787,23.209977865219116,48.753877795453704,1739137681.4777832,23.209977865219116,51.688195098983385,1739137681.4777853,23.209977865219116,5.304060257535323,1739137681.4777882,23.209977865219116,0.8831400144640593,1739137681.4777904,23.209977865219116,1.5582096367515823,1739137681.4777927,23.209977865219116,0.6108,1739137681.4777951,23.209977865219116,1.340452008921046,1739137681.4777973,23.209977865219116,0.0,1739137681.4777997,23.209977865219116,-0.1535910099754627,1739137681.4778023,23.209977865219116,0.5753350222712544,1739137681.4778047,23.209977865219116,1.4940430188965088 +1739137681.4985776,23.22997784614563,48.42368977788374,1739137681.498584,23.22997784614563,1.3297587809735694,1739137681.4985907,23.22997784614563,48.753877795453704,1739137681.4985983,23.22997784614563,51.688195098983385,1739137681.4986024,23.22997784614563,5.304060257535323,1739137681.4986098,23.22997784614563,0.8831400144640593,1739137681.4986143,23.22997784614563,1.5582096367515823,1739137681.4986186,23.22997784614563,0.6108,1739137681.4986224,23.22997784614563,1.340452008921046,1739137681.4986274,23.22997784614563,0.0,1739137681.4986315,23.22997784614563,-0.1535910099754627,1739137681.498636,23.22997784614563,0.5753350222712544,1739137681.49864,23.22997784614563,1.4940430188965088 +1739137681.5177083,23.249977827072144,48.42368977788374,1739137681.5177119,23.249977827072144,1.3297587809735694,1739137681.5177157,23.249977827072144,48.753877795453704,1739137681.5177193,23.249977827072144,51.688195098983385,1739137681.5177214,23.249977827072144,5.304060257535323,1739137681.5177236,23.249977827072144,0.8831400144640593,1739137681.5177257,23.249977827072144,1.5582096367515823,1739137681.5177274,23.249977827072144,0.6108,1739137681.5177293,23.249977827072144,1.340452008921046,1739137681.5177317,23.249977827072144,0.0,1739137681.5177333,23.249977827072144,-0.1535910099754627,1739137681.5177357,23.249977827072144,0.5753350222712544,1739137681.5177374,23.249977827072144,1.4940430188965088 +1739137681.5367653,23.269977807998657,48.55971059186856,1739137681.536768,23.269977807998657,1.4204109037340782,1739137681.536771,23.269977807998657,49.011608156311326,1739137681.5367742,23.269977807998657,51.6343232577466,1739137681.5367754,23.269977807998657,5.50362954806299,1739137681.5367773,23.269977807998657,0.9253859477427072,1739137681.5367787,23.269977807998657,1.6197218333961194,1739137681.53678,23.269977807998657,0.6108,1739137681.5367813,23.269977807998657,1.3078727972743762,1739137681.5367827,23.269977807998657,0.0,1739137681.5367844,23.269977807998657,-0.18333903187284167,1739137681.5367858,23.269977807998657,0.6029402364721691,1739137681.5367873,23.269977807998657,1.4770460973577784 +1739137681.5562189,23.28997778892517,48.55971059186856,1739137681.5562215,23.28997778892517,1.4204109037340782,1739137681.556224,23.28997778892517,49.011608156311326,1739137681.5562265,23.28997778892517,51.6343232577466,1739137681.556228,23.28997778892517,5.50362954806299,1739137681.5562296,23.28997778892517,0.9253859477427072,1739137681.556231,23.28997778892517,1.6197218333961194,1739137681.5562322,23.28997778892517,0.6108,1739137681.5562334,23.28997778892517,1.3078727972743762,1739137681.5562353,23.28997778892517,0.0,1739137681.5562363,23.28997778892517,-0.16917330008340214,1739137681.5562382,23.28997778892517,0.6029402364721691,1739137681.5562394,23.28997778892517,1.4770460973577784 +1739137681.5762653,23.309977769851685,48.55971059186856,1739137681.5762677,23.309977769851685,1.4204109037340782,1739137681.5762706,23.309977769851685,49.011608156311326,1739137681.5762732,23.309977769851685,51.6343232577466,1739137681.5762744,23.309977769851685,5.50362954806299,1739137681.576276,23.309977769851685,0.9253859477427072,1739137681.5762775,23.309977769851685,1.6197218333961194,1739137681.5762784,23.309977769851685,0.6108,1739137681.5762799,23.309977769851685,1.3078727972743762,1739137681.576281,23.309977769851685,0.0,1739137681.5762827,23.309977769851685,-0.16917330008340214,1739137681.5762842,23.309977769851685,0.6029402364721691,1739137681.5762851,23.309977769851685,1.4770460973577784 +1739137681.5971627,23.3299777507782,48.55971059186856,1739137681.5971653,23.3299777507782,1.4204109037340782,1739137681.5971684,23.3299777507782,49.011608156311326,1739137681.5971708,23.3299777507782,51.6343232577466,1739137681.5971725,23.3299777507782,5.50362954806299,1739137681.597175,23.3299777507782,0.9253859477427072,1739137681.597176,23.3299777507782,1.6197218333961194,1739137681.5971773,23.3299777507782,0.6108,1739137681.5971787,23.3299777507782,1.3078727972743762,1739137681.5971801,23.3299777507782,0.0,1739137681.5971816,23.3299777507782,-0.16917330008340214,1739137681.597183,23.3299777507782,0.6029402364721691,1739137681.5971842,23.3299777507782,1.4770460973577784 +1739137681.6168168,23.349977731704712,48.55971059186856,1739137681.6168196,23.349977731704712,1.4204109037340782,1739137681.6168242,23.349977731704712,49.011608156311326,1739137681.6168272,23.349977731704712,51.6343232577466,1739137681.6168287,23.349977731704712,5.50362954806299,1739137681.6168303,23.349977731704712,0.9253859477427072,1739137681.616832,23.349977731704712,1.6197218333961194,1739137681.6168332,23.349977731704712,0.6108,1739137681.6168346,23.349977731704712,1.3078727972743762,1739137681.6168368,23.349977731704712,0.0,1739137681.6168387,23.349977731704712,-0.16917330008340214,1739137681.6168401,23.349977731704712,0.6029402364721691,1739137681.6168418,23.349977731704712,1.4770460973577784 +1739137681.6376765,23.369977712631226,48.55971059186856,1739137681.6376805,23.369977712631226,1.4204109037340782,1739137681.6376853,23.369977712631226,49.011608156311326,1739137681.6376905,23.369977712631226,51.6343232577466,1739137681.6376936,23.369977712631226,5.50362954806299,1739137681.6376977,23.369977712631226,0.9253859477427072,1739137681.6377013,23.369977712631226,1.6197218333961194,1739137681.6377046,23.369977712631226,0.6108,1739137681.637708,23.369977712631226,1.3078727972743762,1739137681.6377122,23.369977712631226,0.0,1739137681.6377158,23.369977712631226,-0.16917330008340214,1739137681.6377199,23.369977712631226,0.6029402364721691,1739137681.6377232,23.369977712631226,1.4770460973577784 +1739137681.6574154,23.38997769355774,48.69158890933314,1739137681.6574204,23.38997769355774,1.5136588491542398,1739137681.6574242,23.38997769355774,49.193263757117805,1739137681.6574295,23.38997769355774,51.5965854519165,1739137681.6574333,23.38997769355774,5.623009978306918,1739137681.6574373,23.38997769355774,0.9554388713671591,1739137681.6574395,23.38997769355774,1.6064041463005296,1739137681.6574414,23.38997769355774,0.6108,1739137681.6574438,23.38997769355774,1.3148585237683543,1739137681.6574464,23.38997769355774,0.0,1739137681.6574504,23.38997769355774,-0.1199144321851235,1739137681.6574547,23.38997769355774,0.6305454506730838,1739137681.6574576,23.38997769355774,1.4582295714321671 +1739137681.6777804,23.409977674484253,48.69158890933314,1739137681.6777833,23.409977674484253,1.5136588491542398,1739137681.677786,23.409977674484253,49.193263757117805,1739137681.677789,23.409977674484253,51.5965854519165,1739137681.6777902,23.409977674484253,5.623009978306918,1739137681.677792,23.409977674484253,0.9554388713671591,1739137681.6777935,23.409977674484253,1.6064041463005296,1739137681.677795,23.409977674484253,0.6108,1739137681.6777961,23.409977674484253,1.3148585237683543,1739137681.6777976,23.409977674484253,0.0,1739137681.6777987,23.409977674484253,-0.1433710476638128,1739137681.6778002,23.409977674484253,0.6305454506730838,1739137681.6778014,23.409977674484253,1.4582295714321671 +1739137681.697853,23.429977655410767,48.69158890933314,1739137681.697856,23.429977655410767,1.5136588491542398,1739137681.697859,23.429977655410767,49.193263757117805,1739137681.6978617,23.429977655410767,51.5965854519165,1739137681.6978633,23.429977655410767,5.623009978306918,1739137681.6978652,23.429977655410767,0.9554388713671591,1739137681.6978664,23.429977655410767,1.6064041463005296,1739137681.697868,23.429977655410767,0.6108,1739137681.6978693,23.429977655410767,1.3148585237683543,1739137681.6978712,23.429977655410767,0.0,1739137681.6978726,23.429977655410767,-0.1433710476638128,1739137681.6978748,23.429977655410767,0.6305454506730838,1739137681.6978762,23.429977655410767,1.4582295714321671 +1739137681.717878,23.44997763633728,48.69158890933314,1739137681.7178814,23.44997763633728,1.5136588491542398,1739137681.7178853,23.44997763633728,49.193263757117805,1739137681.7178888,23.44997763633728,51.5965854519165,1739137681.7178905,23.44997763633728,5.623009978306918,1739137681.7178931,23.44997763633728,0.9554388713671591,1739137681.7178946,23.44997763633728,1.6064041463005296,1739137681.7178965,23.44997763633728,0.6108,1739137681.717898,23.44997763633728,1.3148585237683543,1739137681.7178998,23.44997763633728,0.0,1739137681.7179012,23.44997763633728,-0.1433710476638128,1739137681.7179034,23.44997763633728,0.6305454506730838,1739137681.717905,23.44997763633728,1.4582295714321671 +1739137681.7369244,23.469977617263794,48.69158890933314,1739137681.7369313,23.469977617263794,1.5136588491542398,1739137681.736938,23.469977617263794,49.193263757117805,1739137681.7369466,23.469977617263794,51.5965854519165,1739137681.73695,23.469977617263794,5.623009978306918,1739137681.7369568,23.469977617263794,0.9554388713671591,1739137681.736962,23.469977617263794,1.6064041463005296,1739137681.7369676,23.469977617263794,0.6108,1739137681.7369716,23.469977617263794,1.3148585237683543,1739137681.7369766,23.469977617263794,0.0,1739137681.7369823,23.469977617263794,-0.1433710476638128,1739137681.7369876,23.469977617263794,0.6305454506730838,1739137681.7369936,23.469977617263794,1.4582295714321671 +1739137681.7572992,23.489977598190308,48.81933354010169,1739137681.7573025,23.489977598190308,1.6093811310322232,1739137681.7573059,23.489977598190308,49.390901742295874,1739137681.7573092,23.489977598190308,51.54555918660137,1739137681.7573109,23.489977598190308,5.765307863982075,1739137681.7573133,23.489977598190308,0.9902252162390134,1739137681.7573152,23.489977598190308,1.6203473272771576,1739137681.7573168,23.489977598190308,0.6108,1739137681.7573185,23.489977598190308,1.3075456116338577,1739137681.7573206,23.489977598190308,0.0,1739137681.7573223,23.489977598190308,-0.1277720676747602,1739137681.757324,23.489977598190308,0.6581506648739984,1739137681.757326,23.489977598190308,1.4427457687283458 +1739137681.7771072,23.50997757911682,48.81933354010169,1739137681.777112,23.50997757911682,1.6093811310322232,1739137681.7771168,23.50997757911682,49.390901742295874,1739137681.7771204,23.50997757911682,51.54555918660137,1739137681.777122,23.50997757911682,5.765307863982075,1739137681.7771244,23.50997757911682,0.9902252162390134,1739137681.7771258,23.50997757911682,1.6203473272771576,1739137681.7771277,23.50997757911682,0.6108,1739137681.7771292,23.50997757911682,1.3075456116338577,1739137681.7771316,23.50997757911682,0.0,1739137681.777133,23.50997757911682,-0.13520015709448807,1739137681.777135,23.50997757911682,0.6581506648739984,1739137681.7771363,23.50997757911682,1.4427457687283458 +1739137681.7971272,23.529977560043335,48.81933354010169,1739137681.797131,23.529977560043335,1.6093811310322232,1739137681.7971346,23.529977560043335,49.390901742295874,1739137681.797138,23.529977560043335,51.54555918660137,1739137681.7971394,23.529977560043335,5.765307863982075,1739137681.7971418,23.529977560043335,0.9902252162390134,1739137681.7971432,23.529977560043335,1.6203473272771576,1739137681.797145,23.529977560043335,0.6108,1739137681.7971466,23.529977560043335,1.3075456116338577,1739137681.7971485,23.529977560043335,0.0,1739137681.79715,23.529977560043335,-0.13520015709448807,1739137681.797152,23.529977560043335,0.6581506648739984,1739137681.7971535,23.529977560043335,1.4427457687283458 +1739137681.817826,23.54997754096985,48.81933354010169,1739137681.8178337,23.54997754096985,1.6093811310322232,1739137681.8178413,23.54997754096985,49.390901742295874,1739137681.817851,23.54997754096985,51.54555918660137,1739137681.8178544,23.54997754096985,5.765307863982075,1739137681.8178573,23.54997754096985,0.9902252162390134,1739137681.8178594,23.54997754096985,1.6203473272771576,1739137681.817861,23.54997754096985,0.6108,1739137681.8178635,23.54997754096985,1.3075456116338577,1739137681.8178654,23.54997754096985,0.0,1739137681.8178673,23.54997754096985,-0.13520015709448807,1739137681.8178694,23.54997754096985,0.6581506648739984,1739137681.8178716,23.54997754096985,1.4427457687283458 +1739137681.8379767,23.569977521896362,48.81933354010169,1739137681.8379807,23.569977521896362,1.6093811310322232,1739137681.837985,23.569977521896362,49.390901742295874,1739137681.8379889,23.569977521896362,51.54555918660137,1739137681.837991,23.569977521896362,5.765307863982075,1739137681.837993,23.569977521896362,0.9902252162390134,1739137681.8379953,23.569977521896362,1.6203473272771576,1739137681.837997,23.569977521896362,0.6108,1739137681.8379993,23.569977521896362,1.3075456116338577,1739137681.8380017,23.569977521896362,0.0,1739137681.8380036,23.569977521896362,-0.13520015709448807,1739137681.8380058,23.569977521896362,0.6581506648739984,1739137681.8380072,23.569977521896362,1.4427457687283458 +1739137681.8572075,23.589977502822876,48.81933354010169,1739137681.8572114,23.589977502822876,1.6093811310322232,1739137681.8572164,23.589977502822876,49.390901742295874,1739137681.8572204,23.589977502822876,51.54555918660137,1739137681.8572226,23.589977502822876,5.765307863982075,1739137681.857225,23.589977502822876,0.9902252162390134,1739137681.8572268,23.589977502822876,1.6203473272771576,1739137681.8572285,23.589977502822876,0.6108,1739137681.8572304,23.589977502822876,1.3075456116338577,1739137681.8572323,23.589977502822876,0.0,1739137681.8572342,23.589977502822876,-0.13520015709448807,1739137681.8572366,23.589977502822876,0.6581506648739984,1739137681.8572385,23.589977502822876,1.4427457687283458 +1739137681.877296,23.60997748374939,48.94308703014309,1739137681.8773005,23.60997748374939,1.7075614100909924,1739137681.877305,23.60997748374939,49.65265229875719,1739137681.8773093,23.60997748374939,51.46589836812411,1739137681.8773112,23.60997748374939,5.967955560990066,1739137681.8773139,23.60997748374939,1.0361655883150405,1739137681.877316,23.60997748374939,1.6997010507919779,1739137681.877318,23.60997748374939,0.6108,1739137681.8773196,23.60997748374939,1.266693942718309,1739137681.877322,23.60997748374939,0.0,1739137681.8773239,23.60997748374939,-0.18519074586886664,1739137681.8773258,23.60997748374939,0.6857558790749131,1739137681.877328,23.60997748374939,1.4280796344219975 +1739137681.8970377,23.629977464675903,48.94308703014309,1739137681.8970428,23.629977464675903,1.7075614100909924,1739137681.897047,23.629977464675903,49.65265229875719,1739137681.8970509,23.629977464675903,51.46589836812411,1739137681.8970528,23.629977464675903,5.967955560990066,1739137681.897055,23.629977464675903,1.0361655883150405,1739137681.897057,23.629977464675903,1.6997010507919779,1739137681.8970587,23.629977464675903,0.6108,1739137681.897061,23.629977464675903,1.266693942718309,1739137681.8970633,23.629977464675903,0.0,1739137681.897065,23.629977464675903,-0.16138569170368844,1739137681.8970673,23.629977464675903,0.6857558790749131,1739137681.8970692,23.629977464675903,1.4280796344219975 +1739137681.9175382,23.649977445602417,48.94308703014309,1739137681.9175417,23.649977445602417,1.7075614100909924,1739137681.9175465,23.649977445602417,49.65265229875719,1739137681.9175506,23.649977445602417,51.46589836812411,1739137681.917553,23.649977445602417,5.967955560990066,1739137681.917555,23.649977445602417,1.0361655883150405,1739137681.9175572,23.649977445602417,1.6997010507919779,1739137681.9175591,23.649977445602417,0.6108,1739137681.9175608,23.649977445602417,1.266693942718309,1739137681.917563,23.649977445602417,0.0,1739137681.9175646,23.649977445602417,-0.16138569170368844,1739137681.9175668,23.649977445602417,0.6857558790749131,1739137681.9175684,23.649977445602417,1.4280796344219975 +1739137681.9376032,23.66997742652893,48.94308703014309,1739137681.937607,23.66997742652893,1.7075614100909924,1739137681.9376116,23.66997742652893,49.65265229875719,1739137681.9376156,23.66997742652893,51.46589836812411,1739137681.9376178,23.66997742652893,5.967955560990066,1739137681.9376202,23.66997742652893,1.0361655883150405,1739137681.9376223,23.66997742652893,1.6997010507919779,1739137681.937624,23.66997742652893,0.6108,1739137681.937626,23.66997742652893,1.266693942718309,1739137681.9376278,23.66997742652893,0.0,1739137681.9376297,23.66997742652893,-0.16138569170368844,1739137681.9376318,23.66997742652893,0.6857558790749131,1739137681.9376335,23.66997742652893,1.4280796344219975 +1739137681.9572673,23.689977407455444,48.94308703014309,1739137681.957271,23.689977407455444,1.7075614100909924,1739137681.9572752,23.689977407455444,49.65265229875719,1739137681.9572787,23.689977407455444,51.46589836812411,1739137681.9572809,23.689977407455444,5.967955560990066,1739137681.957283,23.689977407455444,1.0361655883150405,1739137681.9572852,23.689977407455444,1.6997010507919779,1739137681.9572868,23.689977407455444,0.6108,1739137681.9572885,23.689977407455444,1.266693942718309,1739137681.9572906,23.689977407455444,0.0,1739137681.9572926,23.689977407455444,-0.16138569170368844,1739137681.9572947,23.689977407455444,0.6857558790749131,1739137681.9572964,23.689977407455444,1.4280796344219975 +1739137681.977328,23.709977388381958,49.062717478015095,1739137681.9773319,23.709977388381958,1.8079724299244981,1739137681.9773364,23.709977388381958,49.766760732741105,1739137681.97734,23.709977388381958,51.442749059043656,1739137681.977342,23.709977388381958,6.02380225829523,1739137681.9773443,23.709977388381958,1.0568536854501371,1739137681.9773464,23.709977388381958,1.6304275153879906,1739137681.9773479,23.709977388381958,0.6108,1739137681.9773495,23.709977388381958,1.302284103868259,1739137681.9773517,23.709977388381958,0.0,1739137681.9773533,23.709977388381958,-0.05929740236597524,1739137681.9773555,23.709977388381958,0.7133610932758278,1739137681.9773571,23.709977388381958,1.410195001631996 +1739137681.9972408,23.72997736930847,49.062717478015095,1739137681.9972448,23.72997736930847,1.8079724299244981,1739137681.99725,23.72997736930847,49.766760732741105,1739137681.9972537,23.72997736930847,51.442749059043656,1739137681.9972556,23.72997736930847,6.02380225829523,1739137681.9972582,23.72997736930847,1.0568536854501371,1739137681.99726,23.72997736930847,1.6304275153879906,1739137681.9972618,23.72997736930847,0.6108,1739137681.997264,23.72997736930847,1.302284103868259,1739137681.9972658,23.72997736930847,0.0,1739137681.9972677,23.72997736930847,-0.10791089776373686,1739137681.9972699,23.72997736930847,0.7133610932758278,1739137681.9972715,23.72997736930847,1.410195001631996 +1739137682.0173092,23.749977350234985,49.062717478015095,1739137682.0173132,23.749977350234985,1.8079724299244981,1739137682.0173175,23.749977350234985,49.766760732741105,1739137682.0173223,23.749977350234985,51.442749059043656,1739137682.0173242,23.749977350234985,6.02380225829523,1739137682.0173266,23.749977350234985,1.0568536854501371,1739137682.0173285,23.749977350234985,1.6304275153879906,1739137682.0173304,23.749977350234985,0.6108,1739137682.0173323,23.749977350234985,1.302284103868259,1739137682.0173342,23.749977350234985,0.0,1739137682.0173361,23.749977350234985,-0.10791089776373686,1739137682.0173383,23.749977350234985,0.7133610932758278,1739137682.0173402,23.749977350234985,1.410195001631996 +1739137682.0375826,23.7699773311615,49.062717478015095,1739137682.0375865,23.7699773311615,1.8079724299244981,1739137682.0375907,23.7699773311615,49.766760732741105,1739137682.0375946,23.7699773311615,51.442749059043656,1739137682.0375965,23.7699773311615,6.02380225829523,1739137682.037599,23.7699773311615,1.0568536854501371,1739137682.0376008,23.7699773311615,1.6304275153879906,1739137682.037603,23.7699773311615,0.6108,1739137682.0376046,23.7699773311615,1.302284103868259,1739137682.0376067,23.7699773311615,0.0,1739137682.0376086,23.7699773311615,-0.10791089776373686,1739137682.0376112,23.7699773311615,0.7133610932758278,1739137682.0376132,23.7699773311615,1.410195001631996 +1739137682.0579276,23.789977312088013,49.062717478015095,1739137682.0579317,23.789977312088013,1.8079724299244981,1739137682.0579357,23.789977312088013,49.766760732741105,1739137682.0579395,23.789977312088013,51.442749059043656,1739137682.057941,23.789977312088013,6.02380225829523,1739137682.0579433,23.789977312088013,1.0568536854501371,1739137682.0579453,23.789977312088013,1.6304275153879906,1739137682.0579472,23.789977312088013,0.6108,1739137682.0579488,23.789977312088013,1.302284103868259,1739137682.0579507,23.789977312088013,0.0,1739137682.0579524,23.789977312088013,-0.10791089776373686,1739137682.057955,23.789977312088013,0.7133610932758278,1739137682.057957,23.789977312088013,1.410195001631996 +1739137682.077628,23.809977293014526,49.062717478015095,1739137682.0776317,23.809977293014526,1.8079724299244981,1739137682.0776367,23.809977293014526,49.766760732741105,1739137682.0776408,23.809977293014526,51.442749059043656,1739137682.0776424,23.809977293014526,6.02380225829523,1739137682.0776446,23.809977293014526,1.0568536854501371,1739137682.0776465,23.809977293014526,1.6304275153879906,1739137682.0776484,23.809977293014526,0.6108,1739137682.0776498,23.809977293014526,1.302284103868259,1739137682.0776522,23.809977293014526,0.0,1739137682.0776541,23.809977293014526,-0.10791089776373686,1739137682.0776563,23.809977293014526,0.7133610932758278,1739137682.0776582,23.809977293014526,1.410195001631996 +1739137682.0977232,23.82997727394104,49.178356471369334,1739137682.0977268,23.82997727394104,1.9106071775142688,1739137682.097731,23.82997727394104,50.03296388323789,1739137682.0977352,23.82997727394104,51.34533275353099,1739137682.097737,23.82997727394104,6.236082209345108,1739137682.0977395,23.82997727394104,1.106365061991114,1739137682.0977414,23.82997727394104,1.728695917298325,1739137682.097743,23.82997727394104,0.6108,1739137682.097745,23.82997727394104,1.252087758606266,1739137682.0977468,23.82997727394104,0.0,1739137682.0977488,23.82997727394104,-0.18300977472384466,1739137682.097751,23.82997727394104,0.7409663074767424,1739137682.0977526,23.82997727394104,1.3993361454847313 +1739137682.1176789,23.849977254867554,49.178356471369334,1739137682.1176834,23.849977254867554,1.9106071775142688,1739137682.117689,23.849977254867554,50.03296388323789,1739137682.117693,23.849977254867554,51.34533275353099,1739137682.1176946,23.849977254867554,6.236082209345108,1739137682.1176975,23.849977254867554,1.106365061991114,1739137682.1176994,23.849977254867554,1.728695917298325,1739137682.1177013,23.849977254867554,0.6108,1739137682.1177032,23.849977254867554,1.252087758606266,1739137682.1177056,23.849977254867554,0.0,1739137682.1177073,23.849977254867554,-0.1472483868784653,1739137682.1177094,23.849977254867554,0.7409663074767424,1739137682.1177113,23.849977254867554,1.3993361454847313 +1739137682.138193,23.869977235794067,49.178356471369334,1739137682.138199,23.869977235794067,1.9106071775142688,1739137682.1382067,23.869977235794067,50.03296388323789,1739137682.1382146,23.869977235794067,51.34533275353099,1739137682.1382184,23.869977235794067,6.236082209345108,1739137682.1382241,23.869977235794067,1.106365061991114,1739137682.1382287,23.869977235794067,1.728695917298325,1739137682.1382337,23.869977235794067,0.6108,1739137682.138238,23.869977235794067,1.252087758606266,1739137682.138243,23.869977235794067,0.0,1739137682.1382477,23.869977235794067,-0.1472483868784653,1739137682.1382527,23.869977235794067,0.7409663074767424,1739137682.1382577,23.869977235794067,1.3993361454847313 +1739137682.1587987,23.88997721672058,49.178356471369334,1739137682.158802,23.88997721672058,1.9106071775142688,1739137682.1588063,23.88997721672058,50.03296388323789,1739137682.1588101,23.88997721672058,51.34533275353099,1739137682.158812,23.88997721672058,6.236082209345108,1739137682.158815,23.88997721672058,1.106365061991114,1739137682.1588168,23.88997721672058,1.728695917298325,1739137682.1588185,23.88997721672058,0.6108,1739137682.1588202,23.88997721672058,1.252087758606266,1739137682.158822,23.88997721672058,0.0,1739137682.158824,23.88997721672058,-0.1472483868784653,1739137682.1588259,23.88997721672058,0.7409663074767424,1739137682.1588278,23.88997721672058,1.3993361454847313 +1739137682.1800213,23.909977197647095,49.178356471369334,1739137682.1800263,23.909977197647095,1.9106071775142688,1739137682.1800327,23.909977197647095,50.03296388323789,1739137682.18004,23.909977197647095,51.34533275353099,1739137682.180044,23.909977197647095,6.236082209345108,1739137682.1800492,23.909977197647095,1.106365061991114,1739137682.180054,23.909977197647095,1.728695917298325,1739137682.1800585,23.909977197647095,0.6108,1739137682.180063,23.909977197647095,1.252087758606266,1739137682.1800675,23.909977197647095,0.0,1739137682.1800723,23.909977197647095,-0.1472483868784653,1739137682.180077,23.909977197647095,0.7409663074767424,1739137682.1800816,23.909977197647095,1.3993361454847313 +1739137682.1995103,23.92997717857361,49.29000881863023,1739137682.1995156,23.92997717857361,2.015351656690597,1739137682.199522,23.92997717857361,50.15582905674688,1739137682.1995292,23.92997717857361,51.31168657045129,1739137682.1995332,23.92997717857361,6.301458470693735,1739137682.1995382,23.92997717857361,1.1300589807363437,1739137682.1995428,23.92997717857361,1.6760144186480628,1739137682.1995473,23.92997717857361,0.6108,1739137682.1995523,23.92997717857361,1.2787524630426832,1739137682.1995568,23.92997717857361,0.0,1739137682.1995614,23.92997717857361,-0.06494577635824403,1739137682.1995664,23.92997717857361,0.7685715216776571,1739137682.1995707,23.92997717857361,1.3828899782742565 +1739137682.216942,23.949977159500122,49.29000881863023,1739137682.2169456,23.949977159500122,2.015351656690597,1739137682.2169492,23.949977159500122,50.15582905674688,1739137682.2169528,23.949977159500122,51.31168657045129,1739137682.2169547,23.949977159500122,6.301458470693735,1739137682.2169564,23.949977159500122,1.1300589807363437,1739137682.2169583,23.949977159500122,1.6760144186480628,1739137682.2169597,23.949977159500122,0.6108,1739137682.216961,23.949977159500122,1.2787524630426832,1739137682.216963,23.949977159500122,0.0,1739137682.2169647,23.949977159500122,-0.10413751523157333,1739137682.2169664,23.949977159500122,0.7685715216776571,1739137682.2169678,23.949977159500122,1.3828899782742565 +1739137682.2368202,23.969977140426636,49.29000881863023,1739137682.2368236,23.969977140426636,2.015351656690597,1739137682.2368279,23.969977140426636,50.15582905674688,1739137682.2368312,23.969977140426636,51.31168657045129,1739137682.2368333,23.969977140426636,6.301458470693735,1739137682.2368352,23.969977140426636,1.1300589807363437,1739137682.2368374,23.969977140426636,1.6760144186480628,1739137682.2368386,23.969977140426636,0.6108,1739137682.2368402,23.969977140426636,1.2787524630426832,1739137682.2368424,23.969977140426636,0.0,1739137682.236844,23.969977140426636,-0.10413751523157333,1739137682.236846,23.969977140426636,0.7685715216776571,1739137682.2368479,23.969977140426636,1.3828899782742565 +1739137682.2571692,23.98997712135315,49.29000881863023,1739137682.2571735,23.98997712135315,2.015351656690597,1739137682.257178,23.98997712135315,50.15582905674688,1739137682.2571814,23.98997712135315,51.31168657045129,1739137682.2571838,23.98997712135315,6.301458470693735,1739137682.257186,23.98997712135315,1.1300589807363437,1739137682.2571878,23.98997712135315,1.6760144186480628,1739137682.25719,23.98997712135315,0.6108,1739137682.2571914,23.98997712135315,1.2787524630426832,1739137682.2571938,23.98997712135315,0.0,1739137682.2571952,23.98997712135315,-0.10413751523157333,1739137682.2571971,23.98997712135315,0.7685715216776571,1739137682.2571993,23.98997712135315,1.3828899782742565 +1739137682.2836595,24.009977102279663,49.29000881863023,1739137682.2836688,24.009977102279663,2.015351656690597,1739137682.2836792,24.009977102279663,50.15582905674688,1739137682.2836897,24.009977102279663,51.31168657045129,1739137682.2836955,24.009977102279663,6.301458470693735,1739137682.2837017,24.009977102279663,1.1300589807363437,1739137682.283707,24.009977102279663,1.6760144186480628,1739137682.2837112,24.009977102279663,0.6108,1739137682.2837157,24.009977102279663,1.2787524630426832,1739137682.283722,24.009977102279663,0.0,1739137682.283727,24.009977102279663,-0.10413751523157333,1739137682.2837324,24.009977102279663,0.7685715216776571,1739137682.2837372,24.009977102279663,1.3828899782742565 +1739137682.3050978,24.029977083206177,49.29000881863023,1739137682.3051054,24.029977083206177,2.015351656690597,1739137682.3051128,24.029977083206177,50.15582905674688,1739137682.3051198,24.029977083206177,51.31168657045129,1739137682.3051233,24.029977083206177,6.301458470693735,1739137682.3051276,24.029977083206177,1.1300589807363437,1739137682.3051312,24.029977083206177,1.6760144186480628,1739137682.305135,24.029977083206177,0.6108,1739137682.3051383,24.029977083206177,1.2787524630426832,1739137682.3051434,24.029977083206177,0.0,1739137682.3051548,24.029977083206177,-0.10413751523157333,1739137682.3051653,24.029977083206177,0.7685715216776571,1739137682.3051727,24.029977083206177,1.3828899782742565 +1739137682.3289702,24.04997706413269,49.39767712625177,1739137682.3289764,24.04997706413269,2.122098656114739,1739137682.3289838,24.04997706413269,50.41408245371316,1739137682.3289907,24.04997706413269,51.201321668707756,1739137682.3289943,24.04997706413269,6.49905995676986,1739137682.3289983,24.04997706413269,1.179922397103182,1739137682.329002,24.04997706413269,1.7723988280691279,1739137682.3290052,24.04997706413269,0.6108,1739137682.3290088,24.04997706413269,1.2303900102719363,1739137682.329013,24.04997706413269,0.0,1739137682.3290162,24.04997706413269,-0.17616705076434389,1739137682.3290203,24.04997706413269,0.7961767358785717,1739137682.3290236,24.04997706413269,1.3722572650769047 +1739137682.3453395,24.069977045059204,49.39767712625177,1739137682.3453455,24.069977045059204,2.122098656114739,1739137682.3453515,24.069977045059204,50.41408245371316,1739137682.3453567,24.069977045059204,51.201321668707756,1739137682.3453596,24.069977045059204,6.49905995676986,1739137682.3453631,24.069977045059204,1.179922397103182,1739137682.3453658,24.069977045059204,1.7723988280691279,1739137682.3453686,24.069977045059204,0.6108,1739137682.3453712,24.069977045059204,1.2303900102719363,1739137682.3453739,24.069977045059204,0.0,1739137682.3453765,24.069977045059204,-0.14186725480496842,1739137682.3453796,24.069977045059204,0.7961767358785717,1739137682.3453822,24.069977045059204,1.3722572650769047 +1739137682.3644505,24.089977025985718,49.39767712625177,1739137682.364456,24.089977025985718,2.122098656114739,1739137682.3644626,24.089977025985718,50.41408245371316,1739137682.3644683,24.089977025985718,51.201321668707756,1739137682.3644712,24.089977025985718,6.49905995676986,1739137682.3644753,24.089977025985718,1.179922397103182,1739137682.364478,24.089977025985718,1.7723988280691279,1739137682.3644807,24.089977025985718,0.6108,1739137682.3644834,24.089977025985718,1.2303900102719363,1739137682.3644867,24.089977025985718,0.0,1739137682.3644896,24.089977025985718,-0.14186725480496842,1739137682.364493,24.089977025985718,0.7961767358785717,1739137682.3644953,24.089977025985718,1.3722572650769047 +1739137682.384068,24.10997700691223,49.39767712625177,1739137682.3840742,24.10997700691223,2.122098656114739,1739137682.3840814,24.10997700691223,50.41408245371316,1739137682.3840868,24.10997700691223,51.201321668707756,1739137682.3840892,24.10997700691223,6.49905995676986,1739137682.3840933,24.10997700691223,1.179922397103182,1739137682.3840961,24.10997700691223,1.7723988280691279,1739137682.3840988,24.10997700691223,0.6108,1739137682.3841016,24.10997700691223,1.2303900102719363,1739137682.3841047,24.10997700691223,0.0,1739137682.3841074,24.10997700691223,-0.14186725480496842,1739137682.3841112,24.10997700691223,0.7961767358785717,1739137682.3841136,24.10997700691223,1.3722572650769047 +1739137682.4027834,24.129976987838745,49.39767712625177,1739137682.4027894,24.129976987838745,2.122098656114739,1739137682.402795,24.129976987838745,50.41408245371316,1739137682.4028006,24.129976987838745,51.201321668707756,1739137682.4028032,24.129976987838745,6.49905995676986,1739137682.4028065,24.129976987838745,1.179922397103182,1739137682.4028099,24.129976987838745,1.7723988280691279,1739137682.4028127,24.129976987838745,0.6108,1739137682.4028153,24.129976987838745,1.2303900102719363,1739137682.4028182,24.129976987838745,0.0,1739137682.4028208,24.129976987838745,-0.14186725480496842,1739137682.402824,24.129976987838745,0.7961767358785717,1739137682.4028263,24.129976987838745,1.3722572650769047 +1739137682.4236054,24.14997696876526,49.50137223321509,1739137682.4236102,24.14997696876526,2.2307421089530273,1739137682.4236155,24.14997696876526,50.573573093288125,1739137682.4236207,24.14997696876526,51.1429552799556,1739137682.423623,24.14997696876526,6.5959357290727,1739137682.4236262,24.14997696876526,1.2110949928334482,1739137682.4236288,24.14997696876526,1.7614724498483096,1739137682.4236314,24.14997696876526,0.6108,1739137682.4236336,24.14997696876526,1.2357792613369076,1739137682.4236367,24.14997696876526,0.0,1739137682.4236393,24.14997696876526,-0.10206073337698582,1739137682.4236422,24.14997696876526,0.8237819500794864,1739137682.4236443,24.14997696876526,1.3567954905772692 +1739137682.4429889,24.169976949691772,49.50137223321509,1739137682.4429924,24.169976949691772,2.2307421089530273,1739137682.4429967,24.169976949691772,50.573573093288125,1739137682.4430008,24.169976949691772,51.1429552799556,1739137682.4430032,24.169976949691772,6.5959357290727,1739137682.443006,24.169976949691772,1.2110949928334482,1739137682.443008,24.169976949691772,1.7614724498483096,1739137682.44301,24.169976949691772,0.6108,1739137682.443012,24.169976949691772,1.2357792613369076,1739137682.4430144,24.169976949691772,0.0,1739137682.4430165,24.169976949691772,-0.1210162292403616,1739137682.4430187,24.169976949691772,0.8237819500794864,1739137682.4430208,24.169976949691772,1.3567954905772692 +1739137682.4614217,24.189976930618286,49.50137223321509,1739137682.461425,24.189976930618286,2.2307421089530273,1739137682.4614284,24.189976930618286,50.573573093288125,1739137682.461432,24.189976930618286,51.1429552799556,1739137682.4614336,24.189976930618286,6.5959357290727,1739137682.4614356,24.189976930618286,1.2110949928334482,1739137682.4614375,24.189976930618286,1.7614724498483096,1739137682.461439,24.189976930618286,0.6108,1739137682.4614403,24.189976930618286,1.2357792613369076,1739137682.461442,24.189976930618286,0.0,1739137682.4614437,24.189976930618286,-0.1210162292403616,1739137682.4614453,24.189976930618286,0.8237819500794864,1739137682.461447,24.189976930618286,1.3567954905772692 +1739137682.4831238,24.2099769115448,49.50137223321509,1739137682.483126,24.2099769115448,2.2307421089530273,1739137682.4831288,24.2099769115448,50.573573093288125,1739137682.4831314,24.2099769115448,51.1429552799556,1739137682.4831324,24.2099769115448,6.5959357290727,1739137682.483134,24.2099769115448,1.2110949928334482,1739137682.4831352,24.2099769115448,1.7614724498483096,1739137682.4831364,24.2099769115448,0.6108,1739137682.4831378,24.2099769115448,1.2357792613369076,1739137682.4831393,24.2099769115448,0.0,1739137682.4831405,24.2099769115448,-0.1210162292403616,1739137682.483142,24.2099769115448,0.8237819500794864,1739137682.483143,24.2099769115448,1.3567954905772692 +1739137682.5012228,24.229976892471313,49.50137223321509,1739137682.5012252,24.229976892471313,2.2307421089530273,1739137682.501228,24.229976892471313,50.573573093288125,1739137682.5012302,24.229976892471313,51.1429552799556,1739137682.501232,24.229976892471313,6.5959357290727,1739137682.5012333,24.229976892471313,1.2110949928334482,1739137682.5012348,24.229976892471313,1.7614724498483096,1739137682.501236,24.229976892471313,0.6108,1739137682.5012372,24.229976892471313,1.2357792613369076,1739137682.5012386,24.229976892471313,0.0,1739137682.5012398,24.229976892471313,-0.1210162292403616,1739137682.5012414,24.229976892471313,0.8237819500794864,1739137682.5012426,24.229976892471313,1.3567954905772692 +1739137682.5213838,24.249976873397827,49.50137223321509,1739137682.521386,24.249976873397827,2.2307421089530273,1739137682.5213883,24.249976873397827,50.573573093288125,1739137682.5213912,24.249976873397827,51.1429552799556,1739137682.5213923,24.249976873397827,6.5959357290727,1739137682.521394,24.249976873397827,1.2110949928334482,1739137682.5213952,24.249976873397827,1.7614724498483096,1739137682.5213964,24.249976873397827,0.6108,1739137682.5213976,24.249976873397827,1.2357792613369076,1739137682.521399,24.249976873397827,0.0,1739137682.5214002,24.249976873397827,-0.1210162292403616,1739137682.5214016,24.249976873397827,0.8237819500794864,1739137682.521403,24.249976873397827,1.3567954905772692 +1739137682.5484848,24.26997685432434,49.60097491812516,1739137682.5484934,24.26997685432434,2.341040001118232,1739137682.548503,24.26997685432434,50.81214145671798,1739137682.548513,24.26997685432434,51.034534799559616,1739137682.5485182,24.26997685432434,6.763845083975562,1739137682.5485237,24.26997685432434,1.2573523181942343,1739137682.548529,24.26997685432434,1.8360479387051525,1739137682.5485337,24.26997685432434,0.6108,1739137682.5485384,24.26997685432434,1.1994601209997613,1739137682.5485437,24.26997685432434,0.0,1739137682.5485487,24.26997685432434,-0.16575554131939602,1739137682.548554,24.26997685432434,0.8513871642804011,1739137682.5485585,24.26997685432434,1.3439112173533065 +1739137682.5659091,24.289976835250854,49.60097491812516,1739137682.5659177,24.289976835250854,2.341040001118232,1739137682.5659277,24.289976835250854,50.81214145671798,1739137682.565938,24.289976835250854,51.034534799559616,1739137682.565943,24.289976835250854,6.763845083975562,1739137682.565949,24.289976835250854,1.2573523181942343,1739137682.5659537,24.289976835250854,1.8360479387051525,1739137682.5659587,24.289976835250854,0.6108,1739137682.5659633,24.289976835250854,1.1994601209997613,1739137682.5659688,24.289976835250854,0.0,1739137682.565973,24.289976835250854,-0.14445109635354525,1739137682.5659783,24.289976835250854,0.8513871642804011,1739137682.565983,24.289976835250854,1.3439112173533065 +1739137682.5847282,24.309976816177368,49.60097491812516,1739137682.5847328,24.309976816177368,2.341040001118232,1739137682.584738,24.309976816177368,50.81214145671798,1739137682.5847433,24.309976816177368,51.034534799559616,1739137682.5847456,24.309976816177368,6.763845083975562,1739137682.5847492,24.309976816177368,1.2573523181942343,1739137682.5847578,24.309976816177368,1.8360479387051525,1739137682.5847604,24.309976816177368,0.6108,1739137682.5847626,24.309976816177368,1.1994601209997613,1739137682.5847654,24.309976816177368,0.0,1739137682.584768,24.309976816177368,-0.14445109635354525,1739137682.5847712,24.309976816177368,0.8513871642804011,1739137682.5847735,24.309976816177368,1.3439112173533065 +1739137682.6038566,24.329976797103882,49.60097491812516,1739137682.6038601,24.329976797103882,2.341040001118232,1739137682.603865,24.329976797103882,50.81214145671798,1739137682.6038692,24.329976797103882,51.034534799559616,1739137682.6038713,24.329976797103882,6.763845083975562,1739137682.6038737,24.329976797103882,1.2573523181942343,1739137682.603876,24.329976797103882,1.8360479387051525,1739137682.6038783,24.329976797103882,0.6108,1739137682.6038802,24.329976797103882,1.1994601209997613,1739137682.6038828,24.329976797103882,0.0,1739137682.6038847,24.329976797103882,-0.14445109635354525,1739137682.603887,24.329976797103882,0.8513871642804011,1739137682.6038892,24.329976797103882,1.3439112173533065 +1739137682.6237566,24.349976778030396,49.60097491812516,1739137682.6237602,24.349976778030396,2.341040001118232,1739137682.6237643,24.349976778030396,50.81214145671798,1739137682.6237679,24.349976778030396,51.034534799559616,1739137682.6237695,24.349976778030396,6.763845083975562,1739137682.623772,24.349976778030396,1.2573523181942343,1739137682.6237738,24.349976778030396,1.8360479387051525,1739137682.6237755,24.349976778030396,0.6108,1739137682.6237774,24.349976778030396,1.1994601209997613,1739137682.6237793,24.349976778030396,0.0,1739137682.623781,24.349976778030396,-0.14445109635354525,1739137682.6237829,24.349976778030396,0.8513871642804011,1739137682.6237848,24.349976778030396,1.3439112173533065 +1739137682.642426,24.36997675895691,49.69646095479642,1739137682.6424289,24.36997675895691,2.4528328646656634,1739137682.642432,24.36997675895691,51.03357268383682,1739137682.6424353,24.36997675895691,50.93377224386993,1739137682.642437,24.36997675895691,6.9049497483368905,1739137682.642439,24.36997675895691,1.2997218329202913,1739137682.6424406,24.36997675895691,1.8872784290726956,1739137682.6424417,24.36997675895691,0.6108,1739137682.6424432,24.36997675895691,1.1751306821291398,1739137682.642445,24.36997675895691,0.0,1739137682.6424463,24.36997675895691,-0.1603342815896523,1739137682.6424482,24.36997675895691,0.8789923784813157,1739137682.6424496,24.36997675895691,1.3279015383995274 +1739137682.6703682,24.389976739883423,49.69646095479642,1739137682.6703765,24.389976739883423,2.4528328646656634,1739137682.670386,24.389976739883423,51.03357268383682,1739137682.6703956,24.389976739883423,50.93377224386993,1739137682.6704001,24.389976739883423,6.9049497483368905,1739137682.670406,24.389976739883423,1.2997218329202913,1739137682.670411,24.389976739883423,1.8872784290726956,1739137682.6704156,24.389976739883423,0.6108,1739137682.6704202,24.389976739883423,1.1751306821291398,1739137682.6704254,24.389976739883423,0.0,1739137682.6704302,24.389976739883423,-0.15277085627038756,1739137682.6704357,24.389976739883423,0.8789923784813157,1739137682.6704402,24.389976739883423,1.3279015383995274 +1739137682.687342,24.409976720809937,49.69646095479642,1739137682.68735,24.409976720809937,2.4528328646656634,1739137682.6873598,24.409976720809937,51.03357268383682,1739137682.687369,24.409976720809937,50.93377224386993,1739137682.6873739,24.409976720809937,6.9049497483368905,1739137682.6873794,24.409976720809937,1.2997218329202913,1739137682.6873846,24.409976720809937,1.8872784290726956,1739137682.687389,24.409976720809937,0.6108,1739137682.6873934,24.409976720809937,1.1751306821291398,1739137682.6873987,24.409976720809937,0.0,1739137682.6874034,24.409976720809937,-0.15277085627038756,1739137682.687409,24.409976720809937,0.8789923784813157,1739137682.6874135,24.409976720809937,1.3279015383995274 +1739137682.7149723,24.42997670173645,49.69646095479642,1739137682.714978,24.42997670173645,2.4528328646656634,1739137682.7149851,24.42997670173645,51.03357268383682,1739137682.714992,24.42997670173645,50.93377224386993,1739137682.7149954,24.42997670173645,6.9049497483368905,1739137682.715,24.42997670173645,1.2997218329202913,1739137682.7150033,24.42997670173645,1.8872784290726956,1739137682.7150068,24.42997670173645,0.6108,1739137682.7150097,24.42997670173645,1.1751306821291398,1739137682.7150137,24.42997670173645,0.0,1739137682.7150168,24.42997670173645,-0.15277085627038756,1739137682.7150207,24.42997670173645,0.8789923784813157,1739137682.7150242,24.42997670173645,1.3279015383995274 +1739137682.7356637,24.449976682662964,49.69646095479642,1739137682.7356722,24.449976682662964,2.4528328646656634,1739137682.7356837,24.449976682662964,51.03357268383682,1739137682.7356973,24.449976682662964,50.93377224386993,1739137682.7357047,24.449976682662964,6.9049497483368905,1739137682.735714,24.449976682662964,1.2997218329202913,1739137682.7357228,24.449976682662964,1.8872784290726956,1739137682.7357314,24.449976682662964,0.6108,1739137682.73574,24.449976682662964,1.1751306821291398,1739137682.7357485,24.449976682662964,0.0,1739137682.7357574,24.449976682662964,-0.15277085627038756,1739137682.7357662,24.449976682662964,0.8789923784813157,1739137682.735775,24.449976682662964,1.3279015383995274 +1739137682.7668006,24.479976654052734,49.78768471945053,1739137682.766809,24.479976654052734,2.565806246331558,1739137682.766821,24.479976654052734,51.33067205234033,1739137682.7668345,24.479976654052734,50.781754683155974,1739137682.7668421,24.479976654052734,7.098550005148474,1739137682.7668517,24.479976654052734,1.3549055404784087,1739137682.7668602,24.479976654052734,2.011370420812555,1739137682.766869,24.479976654052734,0.6108,1739137682.7668774,24.479976654052734,1.1182249517246672,1739137682.7668862,24.479976654052734,0.0,1739137682.7668948,24.479976654052734,-0.22901936832388003,1739137682.7669039,24.479976654052734,0.9065975926822304,1739137682.7669125,24.479976654052734,1.3109354866471308 +1739137682.7852,24.499976634979248,49.78768471945053,1739137682.785206,24.499976634979248,2.565806246331558,1739137682.7852132,24.499976634979248,51.33067205234033,1739137682.7852201,24.499976634979248,50.781754683155974,1739137682.7852235,24.499976634979248,7.098550005148474,1739137682.785228,24.499976634979248,1.3549055404784087,1739137682.7852314,24.499976634979248,2.011370420812555,1739137682.7852347,24.499976634979248,0.6108,1739137682.7852378,24.499976634979248,1.1182249517246672,1739137682.7852414,24.499976634979248,0.0,1739137682.7852447,24.499976634979248,-0.1927105349224636,1739137682.7852485,24.499976634979248,0.9065975926822304,1739137682.7852519,24.499976634979248,1.3109354866471308 +1739137682.802361,24.51997661590576,49.78768471945053,1739137682.8023672,24.51997661590576,2.565806246331558,1739137682.8023741,24.51997661590576,51.33067205234033,1739137682.8023808,24.51997661590576,50.781754683155974,1739137682.8023841,24.51997661590576,7.098550005148474,1739137682.8023877,24.51997661590576,1.3549055404784087,1739137682.8023915,24.51997661590576,2.011370420812555,1739137682.8023946,24.51997661590576,0.6108,1739137682.802398,24.51997661590576,1.1182249517246672,1739137682.8024018,24.51997661590576,0.0,1739137682.8024054,24.51997661590576,-0.1927105349224636,1739137682.802409,24.51997661590576,0.9065975926822304,1739137682.8024123,24.51997661590576,1.3109354866471308 +1739137682.8231802,24.539976596832275,49.78768471945053,1739137682.8231847,24.539976596832275,2.565806246331558,1739137682.8231902,24.539976596832275,51.33067205234033,1739137682.8231955,24.539976596832275,50.781754683155974,1739137682.8231978,24.539976596832275,7.098550005148474,1739137682.8232012,24.539976596832275,1.3549055404784087,1739137682.8232038,24.539976596832275,2.011370420812555,1739137682.8232067,24.539976596832275,0.6108,1739137682.823209,24.539976596832275,1.1182249517246672,1739137682.8232117,24.539976596832275,0.0,1739137682.8232143,24.539976596832275,-0.1927105349224636,1739137682.8232172,24.539976596832275,0.9065975926822304,1739137682.8232198,24.539976596832275,1.3109354866471308 +1739137682.8407812,24.55997657775879,49.78768471945053,1739137682.8407848,24.55997657775879,2.565806246331558,1739137682.8407881,24.55997657775879,51.33067205234033,1739137682.8407912,24.55997657775879,50.781754683155974,1739137682.840793,24.55997657775879,7.098550005148474,1739137682.8407948,24.55997657775879,1.3549055404784087,1739137682.8407967,24.55997657775879,2.011370420812555,1739137682.8407981,24.55997657775879,0.6108,1739137682.8407998,24.55997657775879,1.1182249517246672,1739137682.8408015,24.55997657775879,0.0,1739137682.8408031,24.55997657775879,-0.1927105349224636,1739137682.8408048,24.55997657775879,0.9065975926822304,1739137682.8408065,24.55997657775879,1.3109354866471308 +1739137682.8601682,24.579976558685303,49.78768471945053,1739137682.860171,24.579976558685303,2.565806246331558,1739137682.860174,24.579976558685303,51.33067205234033,1739137682.8601763,24.579976558685303,50.781754683155974,1739137682.8601778,24.579976558685303,7.098550005148474,1739137682.8601794,24.579976558685303,1.3549055404784087,1739137682.8601809,24.579976558685303,2.011370420812555,1739137682.860182,24.579976558685303,0.6108,1739137682.860183,24.579976558685303,1.1182249517246672,1739137682.8601847,24.579976558685303,0.0,1739137682.8601859,24.579976558685303,-0.1927105349224636,1739137682.860187,24.579976558685303,0.9065975926822304,1739137682.8601885,24.579976558685303,1.3109354866471308 +1739137682.8800592,24.599976539611816,49.8742062428176,1739137682.8800616,24.599976539611816,2.6792177625256395,1739137682.8800647,24.599976539611816,51.575242771501145,1739137682.8800673,24.599976539611816,50.681773016674875,1739137682.8800685,24.599976539611816,7.212517411824386,1739137682.8800704,24.599976539611816,1.3945045775574885,1739137682.8800716,24.599976539611816,2.0454787782876034,1739137682.8800726,24.599976539611816,0.6108,1739137682.880074,24.599976539611816,1.103072227122087,1739137682.8800752,24.599976539611816,0.0,1739137682.8800766,24.599976539611816,-0.1624898380185119,1739137682.8800783,24.599976539611816,0.934202806883145,1739137682.8800795,24.599976539611816,1.2799528803789406 +1739137682.9007156,24.61997652053833,49.8742062428176,1739137682.9007175,24.61997652053833,2.6792177625256395,1739137682.9007204,24.61997652053833,51.575242771501145,1739137682.900723,24.61997652053833,50.681773016674875,1739137682.9007242,24.61997652053833,7.212517411824386,1739137682.9007258,24.61997652053833,1.3945045775574885,1739137682.900727,24.61997652053833,2.0454787782876034,1739137682.9007282,24.61997652053833,0.6108,1739137682.9007297,24.61997652053833,1.103072227122087,1739137682.9007308,24.61997652053833,0.0,1739137682.9007323,24.61997652053833,-0.17688065325685365,1739137682.9007337,24.61997652053833,0.934202806883145,1739137682.900735,24.61997652053833,1.2799528803789406 +1739137682.9204657,24.639976501464844,49.8742062428176,1739137682.9204686,24.639976501464844,2.6792177625256395,1739137682.9204712,24.639976501464844,51.575242771501145,1739137682.920474,24.639976501464844,50.681773016674875,1739137682.9204755,24.639976501464844,7.212517411824386,1739137682.9204776,24.639976501464844,1.3945045775574885,1739137682.9204793,24.639976501464844,2.0454787782876034,1739137682.9204805,24.639976501464844,0.6108,1739137682.9204814,24.639976501464844,1.103072227122087,1739137682.920483,24.639976501464844,0.0,1739137682.920484,24.639976501464844,-0.17688065325685365,1739137682.9204857,24.639976501464844,0.934202806883145,1739137682.920487,24.639976501464844,1.2799528803789406 +1739137682.9408386,24.659976482391357,49.8742062428176,1739137682.9408412,24.659976482391357,2.6792177625256395,1739137682.9408445,24.659976482391357,51.575242771501145,1739137682.9408476,24.659976482391357,50.681773016674875,1739137682.940849,24.659976482391357,7.212517411824386,1739137682.9408507,24.659976482391357,1.3945045775574885,1739137682.940852,24.659976482391357,2.0454787782876034,1739137682.9408534,24.659976482391357,0.6108,1739137682.9408543,24.659976482391357,1.103072227122087,1739137682.9408557,24.659976482391357,0.0,1739137682.9408572,24.659976482391357,-0.17688065325685365,1739137682.9408586,24.659976482391357,0.934202806883145,1739137682.9408598,24.659976482391357,1.2799528803789406 +1739137682.9613464,24.689976453781128,49.8742062428176,1739137682.9613485,24.689976453781128,2.6792177625256395,1739137682.9613512,24.689976453781128,51.575242771501145,1739137682.961354,24.689976453781128,50.681773016674875,1739137682.9613552,24.689976453781128,7.212517411824386,1739137682.9613569,24.689976453781128,1.3945045775574885,1739137682.961358,24.689976453781128,2.0454787782876034,1739137682.9613593,24.689976453781128,0.6108,1739137682.961361,24.689976453781128,1.103072227122087,1739137682.9613624,24.689976453781128,0.0,1739137682.9613638,24.689976453781128,-0.17688065325685365,1739137682.961365,24.689976453781128,0.934202806883145,1739137682.9613662,24.689976453781128,1.2799528803789406 +1739137682.9806042,24.699976444244385,49.955864139873455,1739137682.9806066,24.699976444244385,2.792617675412232,1739137682.980609,24.699976444244385,51.70733448474989,1739137682.9806116,24.699976444244385,50.63329002306172,1739137682.9806128,24.699976444244385,7.2653638748627305,1739137682.9806147,24.699976444244385,1.4204823660445463,1739137682.980616,24.699976444244385,2.0029373828954484,1739137682.9806175,24.699976444244385,0.6108,1739137682.9806185,24.699976444244385,1.1220033341575124,1739137682.9806201,24.699976444244385,0.0,1739137682.9806213,24.699976444244385,-0.10231923720624067,1739137682.9806228,24.699976444244385,0.9618080210840597,1739137682.9806242,24.699976444244385,1.2598280253148562 +1739137683.0004237,24.7199764251709,49.955864139873455,1739137683.000426,24.7199764251709,2.792617675412232,1739137683.0004292,24.7199764251709,51.70733448474989,1739137683.0004315,24.7199764251709,50.63329002306172,1739137683.000433,24.7199764251709,7.2653638748627305,1739137683.0004346,24.7199764251709,1.4204823660445463,1739137683.000436,24.7199764251709,2.0029373828954484,1739137683.0004373,24.7199764251709,0.6108,1739137683.0004385,24.7199764251709,1.1220033341575124,1739137683.0004401,24.7199764251709,0.0,1739137683.0004413,24.7199764251709,-0.13782469115734375,1739137683.0004425,24.7199764251709,0.9618080210840597,1739137683.000444,24.7199764251709,1.2598280253148562 +1739137683.0203686,24.739976406097412,49.955864139873455,1739137683.020371,24.739976406097412,2.792617675412232,1739137683.0203738,24.739976406097412,51.70733448474989,1739137683.0203762,24.739976406097412,50.63329002306172,1739137683.0203776,24.739976406097412,7.2653638748627305,1739137683.0203793,24.739976406097412,1.4204823660445463,1739137683.0203807,24.739976406097412,2.0029373828954484,1739137683.020382,24.739976406097412,0.6108,1739137683.0203831,24.739976406097412,1.1220033341575124,1739137683.0203848,24.739976406097412,0.0,1739137683.0203857,24.739976406097412,-0.13782469115734375,1739137683.0203874,24.739976406097412,0.9618080210840597,1739137683.0203886,24.739976406097412,1.2598280253148562 +1739137683.040586,24.759976387023926,49.955864139873455,1739137683.0405884,24.759976387023926,2.792617675412232,1739137683.0405908,24.759976387023926,51.70733448474989,1739137683.0405936,24.759976387023926,50.63329002306172,1739137683.0405946,24.759976387023926,7.2653638748627305,1739137683.0405965,24.759976387023926,1.4204823660445463,1739137683.0405977,24.759976387023926,2.0029373828954484,1739137683.040599,24.759976387023926,0.6108,1739137683.0406003,24.759976387023926,1.1220033341575124,1739137683.0406015,24.759976387023926,0.0,1739137683.040603,24.759976387023926,-0.13782469115734375,1739137683.0406044,24.759976387023926,0.9618080210840597,1739137683.0406058,24.759976387023926,1.2598280253148562 +1739137683.060437,24.77997636795044,49.955864139873455,1739137683.0604393,24.77997636795044,2.792617675412232,1739137683.0604422,24.77997636795044,51.70733448474989,1739137683.0604446,24.77997636795044,50.63329002306172,1739137683.060446,24.77997636795044,7.2653638748627305,1739137683.0604477,24.77997636795044,1.4204823660445463,1739137683.0604494,24.77997636795044,2.0029373828954484,1739137683.0604506,24.77997636795044,0.6108,1739137683.0604517,24.77997636795044,1.1220033341575124,1739137683.0604534,24.77997636795044,0.0,1739137683.0604544,24.77997636795044,-0.13782469115734375,1739137683.060456,24.77997636795044,0.9618080210840597,1739137683.0604572,24.77997636795044,1.2598280253148562 +1739137683.0931413,24.799976348876953,49.955864139873455,1739137683.0931437,24.799976348876953,2.792617675412232,1739137683.093147,24.799976348876953,51.70733448474989,1739137683.0931497,24.799976348876953,50.63329002306172,1739137683.0931513,24.799976348876953,7.2653638748627305,1739137683.093153,24.799976348876953,1.4204823660445463,1739137683.093173,24.799976348876953,2.0029373828954484,1739137683.093174,24.799976348876953,0.6108,1739137683.0931754,24.799976348876953,1.1220033341575124,1739137683.093177,24.799976348876953,0.0,1739137683.0931783,24.799976348876953,-0.13782469115734375,1739137683.09318,24.799976348876953,0.9618080210840597,1739137683.0931811,24.799976348876953,1.2598280253148562 +1739137683.104488,24.819976329803467,50.033318823565445,1739137683.1044912,24.819976329803467,2.9066956209519876,1739137683.1044955,24.819976329803467,51.97696853704713,1739137683.1045005,24.819976329803467,50.47640499013168,1739137683.1045032,24.819976329803467,7.428595009868322,1739137683.1045067,24.819976329803467,1.4731213986921068,1739137683.10451,24.819976329803467,2.1130493083985677,1739137683.104513,24.819976329803467,0.6108,1739137683.104516,24.819976329803467,1.0736574619833208,1739137683.1045196,24.819976329803467,0.0,1739137683.104523,24.819976329803467,-0.20263266677665423,1739137683.1045263,24.819976329803467,0.9894132352849744,1739137683.1045294,24.819976329803467,1.2454291725724789 +1739137683.1250467,24.83997631072998,50.033318823565445,1739137683.1250503,24.83997631072998,2.9066956209519876,1739137683.125055,24.83997631072998,51.97696853704713,1739137683.12506,24.83997631072998,50.47640499013168,1739137683.125063,24.83997631072998,7.428595009868322,1739137683.1250668,24.83997631072998,1.4731213986921068,1739137683.12507,24.83997631072998,2.1130493083985677,1739137683.1250732,24.83997631072998,0.6108,1739137683.1250765,24.83997631072998,1.0736574619833208,1739137683.1250799,24.83997631072998,0.0,1739137683.1250832,24.83997631072998,-0.17177171058915808,1739137683.1250865,24.83997631072998,0.9894132352849744,1739137683.12509,24.83997631072998,1.2454291725724789 +1739137683.1429899,24.859976291656494,50.033318823565445,1739137683.142992,24.859976291656494,2.9066956209519876,1739137683.1429946,24.859976291656494,51.97696853704713,1739137683.1429973,24.859976291656494,50.47640499013168,1739137683.1429985,24.859976291656494,7.428595009868322,1739137683.1430001,24.859976291656494,1.4731213986921068,1739137683.1430013,24.859976291656494,2.1130493083985677,1739137683.1430025,24.859976291656494,0.6108,1739137683.143004,24.859976291656494,1.0736574619833208,1739137683.1430051,24.859976291656494,0.0,1739137683.1430066,24.859976291656494,-0.17177171058915808,1739137683.1430078,24.859976291656494,0.9894132352849744,1739137683.143009,24.859976291656494,1.2454291725724789 +1739137683.16328,24.879976272583008,50.033318823565445,1739137683.1632824,24.879976272583008,2.9066956209519876,1739137683.163285,24.879976272583008,51.97696853704713,1739137683.1632876,24.879976272583008,50.47640499013168,1739137683.1632888,24.879976272583008,7.428595009868322,1739137683.1632903,24.879976272583008,1.4731213986921068,1739137683.1632917,24.879976272583008,2.1130493083985677,1739137683.163293,24.879976272583008,0.6108,1739137683.1632943,24.879976272583008,1.0736574619833208,1739137683.1632957,24.879976272583008,0.0,1739137683.163297,24.879976272583008,-0.17177171058915808,1739137683.1632984,24.879976272583008,0.9894132352849744,1739137683.1632996,24.879976272583008,1.2454291725724789 +1739137683.182726,24.89997625350952,50.033318823565445,1739137683.1827283,24.89997625350952,2.9066956209519876,1739137683.1827307,24.89997625350952,51.97696853704713,1739137683.1827333,24.89997625350952,50.47640499013168,1739137683.1827345,24.89997625350952,7.428595009868322,1739137683.1827362,24.89997625350952,1.4731213986921068,1739137683.1827374,24.89997625350952,2.1130493083985677,1739137683.1827388,24.89997625350952,0.6108,1739137683.18274,24.89997625350952,1.0736574619833208,1739137683.1827412,24.89997625350952,0.0,1739137683.1827426,24.89997625350952,-0.17177171058915808,1739137683.182744,24.89997625350952,0.9894132352849744,1739137683.182745,24.89997625350952,1.2454291725724789 +1739137683.203494,24.919976234436035,50.106528882117765,1739137683.2034962,24.919976234436035,3.02119711474481,1739137683.2034993,24.919976234436035,52.146269203503635,1739137683.2035022,24.919976234436035,50.397997697205184,1739137683.2035031,24.919976234436035,7.502202118571232,1739137683.2035046,24.919976234436035,1.5058424166396798,1739137683.2035062,24.919976234436035,2.1086724687211076,1739137683.2035074,24.919976234436035,0.6108,1739137683.2035089,24.919976234436035,1.075538798996725,1739137683.20351,24.919976234436035,0.0,1739137683.2035112,24.919976234436035,-0.12888424710285454,1739137683.203513,24.919976234436035,1.0170184494858892,1739137683.203514,24.919976234436035,1.224845657961711 +1739137683.223026,24.93997621536255,50.106528882117765,1739137683.2230282,24.93997621536255,3.02119711474481,1739137683.2230308,24.93997621536255,52.146269203503635,1739137683.2230334,24.93997621536255,50.397997697205184,1739137683.2230346,24.93997621536255,7.502202118571232,1739137683.2230365,24.93997621536255,1.5058424166396798,1739137683.2230375,24.93997621536255,2.1086724687211076,1739137683.2230387,24.93997621536255,0.6108,1739137683.22304,24.93997621536255,1.075538798996725,1739137683.2230413,24.93997621536255,0.0,1739137683.2230425,24.93997621536255,-0.14930685896498597,1739137683.223044,24.93997621536255,1.0170184494858892,1739137683.223045,24.93997621536255,1.224845657961711 +1739137683.2427843,24.959976196289062,50.106528882117765,1739137683.2427866,24.959976196289062,3.02119711474481,1739137683.2427893,24.959976196289062,52.146269203503635,1739137683.242792,24.959976196289062,50.397997697205184,1739137683.2427933,24.959976196289062,7.502202118571232,1739137683.2427948,24.959976196289062,1.5058424166396798,1739137683.242796,24.959976196289062,2.1086724687211076,1739137683.2427974,24.959976196289062,0.6108,1739137683.2427983,24.959976196289062,1.075538798996725,1739137683.2427998,24.959976196289062,0.0,1739137683.2428012,24.959976196289062,-0.14930685896498597,1739137683.2428026,24.959976196289062,1.0170184494858892,1739137683.2428038,24.959976196289062,1.224845657961711 +1739137683.2632341,24.979976177215576,50.106528882117765,1739137683.2632363,24.979976177215576,3.02119711474481,1739137683.2632391,24.979976177215576,52.146269203503635,1739137683.2632418,24.979976177215576,50.397997697205184,1739137683.263243,24.979976177215576,7.502202118571232,1739137683.2632446,24.979976177215576,1.5058424166396798,1739137683.2632458,24.979976177215576,2.1086724687211076,1739137683.263247,24.979976177215576,0.6108,1739137683.2632484,24.979976177215576,1.075538798996725,1739137683.2632496,24.979976177215576,0.0,1739137683.2632508,24.979976177215576,-0.14930685896498597,1739137683.2632525,24.979976177215576,1.0170184494858892,1739137683.2632535,24.979976177215576,1.224845657961711 +1739137683.2831092,24.99997615814209,50.106528882117765,1739137683.283111,24.99997615814209,3.02119711474481,1739137683.2831137,24.99997615814209,52.146269203503635,1739137683.2831163,24.99997615814209,50.397997697205184,1739137683.2831175,24.99997615814209,7.502202118571232,1739137683.2831192,24.99997615814209,1.5058424166396798,1739137683.2831204,24.99997615814209,2.1086724687211076,1739137683.2831216,24.99997615814209,0.6108,1739137683.283123,24.99997615814209,1.075538798996725,1739137683.2831242,24.99997615814209,0.0,1739137683.2831254,24.99997615814209,-0.14930685896498597,1739137683.283127,24.99997615814209,1.0170184494858892,1739137683.2831283,24.99997615814209,1.224845657961711 +1739137683.3031135,25.019976139068604,50.106528882117765,1739137683.3031156,25.019976139068604,3.02119711474481,1739137683.3031182,25.019976139068604,52.146269203503635,1739137683.3031209,25.019976139068604,50.397997697205184,1739137683.3031223,25.019976139068604,7.502202118571232,1739137683.3031237,25.019976139068604,1.5058424166396798,1739137683.3031251,25.019976139068604,2.1086724687211076,1739137683.3031263,25.019976139068604,0.6108,1739137683.3031275,25.019976139068604,1.075538798996725,1739137683.3031292,25.019976139068604,0.0,1739137683.3031301,25.019976139068604,-0.14930685896498597,1739137683.3031318,25.019976139068604,1.0170184494858892,1739137683.3031332,25.019976139068604,1.224845657961711 +1739137683.3378782,25.039976119995117,50.17554116215263,1739137683.337887,25.039976119995117,3.1359987093608392,1739137683.337897,25.039976119995117,52.313408715124154,1739137683.3379068,25.039976119995117,50.30930329411329,1739137683.3379118,25.039976119995117,7.58192999071591,1739137683.337918,25.039976119995117,1.5407189852320948,1739137683.337923,25.039976119995117,2.117199601687645,1739137683.3379276,25.039976119995117,0.6108,1739137683.3379323,25.039976119995117,1.071876543315601,1739137683.337938,25.039976119995117,0.0,1739137683.337943,25.039976119995117,-0.12583463764400835,1739137683.337948,25.039976119995117,1.0446236636868038,1739137683.3379529,25.039976119995117,1.2088884347912205 +1739137683.350956,25.05997610092163,50.17554116215263,1739137683.350964,25.05997610092163,3.1359987093608392,1739137683.3509734,25.05997610092163,52.313408715124154,1739137683.350983,25.05997610092163,50.30930329411329,1739137683.3509874,25.05997610092163,7.58192999071591,1739137683.3509932,25.05997610092163,1.5407189852320948,1739137683.3509982,25.05997610092163,2.117199601687645,1739137683.3510032,25.05997610092163,0.6108,1739137683.3510077,25.05997610092163,1.071876543315601,1739137683.351013,25.05997610092163,0.0,1739137683.3510175,25.05997610092163,-0.13701189147561954,1739137683.351023,25.05997610092163,1.0446236636868038,1739137683.3510275,25.05997610092163,1.2088884347912205 +1739137683.3803577,25.0899760723114,50.17554116215263,1739137683.3803635,25.0899760723114,3.1359987093608392,1739137683.3803704,25.0899760723114,52.313408715124154,1739137683.3803773,25.0899760723114,50.30930329411329,1739137683.3803804,25.0899760723114,7.58192999071591,1739137683.3803842,25.0899760723114,1.5407189852320948,1739137683.3803875,25.0899760723114,2.117199601687645,1739137683.3803906,25.0899760723114,0.6108,1739137683.380394,25.0899760723114,1.071876543315601,1739137683.3803978,25.0899760723114,0.0,1739137683.380401,25.0899760723114,-0.13701189147561954,1739137683.3804047,25.0899760723114,1.0446236636868038,1739137683.380408,25.0899760723114,1.2088884347912205 +1739137683.3962524,25.109976053237915,50.17554116215263,1739137683.396256,25.109976053237915,3.1359987093608392,1739137683.3962603,25.109976053237915,52.313408715124154,1739137683.3962646,25.109976053237915,50.30930329411329,1739137683.3962667,25.109976053237915,7.58192999071591,1739137683.3962693,25.109976053237915,1.5407189852320948,1739137683.3962717,25.109976053237915,2.117199601687645,1739137683.3962736,25.109976053237915,0.6108,1739137683.3962758,25.109976053237915,1.071876543315601,1739137683.396278,25.109976053237915,0.0,1739137683.39628,25.109976053237915,-0.13701189147561954,1739137683.3962824,25.109976053237915,1.0446236636868038,1739137683.3962843,25.109976053237915,1.2088884347912205 +1739137683.4160867,25.12997603416443,50.17554116215263,1739137683.4160907,25.12997603416443,3.1359987093608392,1739137683.4160953,25.12997603416443,52.313408715124154,1739137683.4160993,25.12997603416443,50.30930329411329,1739137683.4161015,25.12997603416443,7.58192999071591,1739137683.416104,25.12997603416443,1.5407189852320948,1739137683.4161062,25.12997603416443,2.117199601687645,1739137683.4161084,25.12997603416443,0.6108,1739137683.4161103,25.12997603416443,1.071876543315601,1739137683.4161127,25.12997603416443,0.0,1739137683.4161148,25.12997603416443,-0.13701189147561954,1739137683.416117,25.12997603416443,1.0446236636868038,1739137683.4161189,25.12997603416443,1.2088884347912205 +1739137683.435275,25.149976015090942,50.24050777338204,1739137683.4352775,25.149976015090942,3.251154121485314,1739137683.4352803,25.149976015090942,52.63514363436452,1739137683.435283,25.149976015090942,50.09460296473714,1739137683.4352844,25.149976015090942,7.756362438730421,1739137683.435286,25.149976015090942,1.603170818751657,1739137683.4352875,25.149976015090942,2.282389435501056,1739137683.4352887,25.149976015090942,0.6108,1739137683.4352899,25.149976015090942,1.003340524832101,1739137683.4352913,25.149976015090942,0.0,1739137683.435293,25.149976015090942,-0.23919049648572252,1739137683.4352944,25.149976015090942,1.0722288778877185,1739137683.4352958,25.149976015090942,1.193874518435535 +1739137683.4546933,25.169975996017456,50.24050777338204,1739137683.4546967,25.169975996017456,3.251154121485314,1739137683.4547002,25.169975996017456,52.63514363436452,1739137683.4547029,25.169975996017456,50.09460296473714,1739137683.4547043,25.169975996017456,7.756362438730421,1739137683.4547064,25.169975996017456,1.603170818751657,1739137683.4547076,25.169975996017456,2.282389435501056,1739137683.4547093,25.169975996017456,0.6108,1739137683.4547105,25.169975996017456,1.003340524832101,1739137683.4547122,25.169975996017456,0.0,1739137683.4547136,25.169975996017456,-0.19053399360343404,1739137683.4547153,25.169975996017456,1.0722288778877185,1739137683.4547164,25.169975996017456,1.193874518435535 +1739137683.4739828,25.18997597694397,50.24050777338204,1739137683.4739847,25.18997597694397,3.251154121485314,1739137683.4739873,25.18997597694397,52.63514363436452,1739137683.4739897,25.18997597694397,50.09460296473714,1739137683.473991,25.18997597694397,7.756362438730421,1739137683.4739923,25.18997597694397,1.603170818751657,1739137683.4739938,25.18997597694397,2.282389435501056,1739137683.4739947,25.18997597694397,0.6108,1739137683.473996,25.18997597694397,1.003340524832101,1739137683.4739974,25.18997597694397,0.0,1739137683.4739983,25.18997597694397,-0.19053399360343404,1739137683.4739995,25.18997597694397,1.0722288778877185,1739137683.474001,25.18997597694397,1.193874518435535 +1739137683.4937828,25.209975957870483,50.24050777338204,1739137683.4937847,25.209975957870483,3.251154121485314,1739137683.493787,25.209975957870483,52.63514363436452,1739137683.4937894,25.209975957870483,50.09460296473714,1739137683.4937904,25.209975957870483,7.756362438730421,1739137683.493792,25.209975957870483,1.603170818751657,1739137683.4937935,25.209975957870483,2.282389435501056,1739137683.493795,25.209975957870483,0.6108,1739137683.4937959,25.209975957870483,1.003340524832101,1739137683.493797,25.209975957870483,0.0,1739137683.4937985,25.209975957870483,-0.19053399360343404,1739137683.4937997,25.209975957870483,1.0722288778877185,1739137683.4938006,25.209975957870483,1.193874518435535 +1739137683.5141504,25.229975938796997,50.24050777338204,1739137683.5141523,25.229975938796997,3.251154121485314,1739137683.5141547,25.229975938796997,52.63514363436452,1739137683.514157,25.229975938796997,50.09460296473714,1739137683.514158,25.229975938796997,7.756362438730421,1739137683.5141597,25.229975938796997,1.603170818751657,1739137683.5141609,25.229975938796997,2.282389435501056,1739137683.514162,25.229975938796997,0.6108,1739137683.5141633,25.229975938796997,1.003340524832101,1739137683.5141644,25.229975938796997,0.0,1739137683.5141659,25.229975938796997,-0.19053399360343404,1739137683.514167,25.229975938796997,1.0722288778877185,1739137683.514168,25.229975938796997,1.193874518435535 +1739137683.5345132,25.24997591972351,50.301275789854685,1739137683.5345154,25.24997591972351,3.3661676140682317,1739137683.5345185,25.24997591972351,52.63705766334304,1739137683.5345209,25.24997591972351,50.15793620308245,1739137683.534522,25.24997591972351,7.707603657217129,1739137683.5345237,25.24997591972351,1.6038009673477427,1739137683.5345252,25.24997591972351,2.097634946975986,1739137683.534526,25.24997591972351,0.6108,1739137683.5345275,25.24997591972351,1.080297809956438,1739137683.534529,25.24997591972351,0.0,1739137683.5345304,25.24997591972351,0.008467814788095648,1739137683.5345318,25.24997591972351,1.0998340920886331,1739137683.534533,25.24997591972351,1.1665928084072361 +1739137683.5541031,25.269975900650024,50.301275789854685,1739137683.5541053,25.269975900650024,3.3661676140682317,1739137683.5541081,25.269975900650024,52.63705766334304,1739137683.554111,25.269975900650024,50.15793620308245,1739137683.5541124,25.269975900650024,7.707603657217129,1739137683.5541146,25.269975900650024,1.6038009673477427,1739137683.554116,25.269975900650024,2.097634946975986,1739137683.5541177,25.269975900650024,0.6108,1739137683.554119,25.269975900650024,1.080297809956438,1739137683.5541208,25.269975900650024,0.0,1739137683.5541222,25.269975900650024,-0.08629499845079813,1739137683.5541239,25.269975900650024,1.0998340920886331,1739137683.5541253,25.269975900650024,1.1665928084072361 +1739137683.5738347,25.289975881576538,50.301275789854685,1739137683.573837,25.289975881576538,3.3661676140682317,1739137683.5738404,25.289975881576538,52.63705766334304,1739137683.5738432,25.289975881576538,50.15793620308245,1739137683.5738447,25.289975881576538,7.707603657217129,1739137683.5738466,25.289975881576538,1.6038009673477427,1739137683.573848,25.289975881576538,2.097634946975986,1739137683.5738497,25.289975881576538,0.6108,1739137683.5738509,25.289975881576538,1.080297809956438,1739137683.5738523,25.289975881576538,0.0,1739137683.573854,25.289975881576538,-0.08629499845079813,1739137683.5738556,25.289975881576538,1.0998340920886331,1739137683.5738573,25.289975881576538,1.1665928084072361 +1739137683.5944211,25.30997586250305,50.301275789854685,1739137683.5944242,25.30997586250305,3.3661676140682317,1739137683.594428,25.30997586250305,52.63705766334304,1739137683.5944316,25.30997586250305,50.15793620308245,1739137683.5944338,25.30997586250305,7.707603657217129,1739137683.5944364,25.30997586250305,1.6038009673477427,1739137683.5944383,25.30997586250305,2.097634946975986,1739137683.5944402,25.30997586250305,0.6108,1739137683.5944421,25.30997586250305,1.080297809956438,1739137683.5944443,25.30997586250305,0.0,1739137683.5944462,25.30997586250305,-0.08629499845079813,1739137683.594448,25.30997586250305,1.0998340920886331,1739137683.5944502,25.30997586250305,1.1665928084072361 +1739137683.615285,25.329975843429565,50.301275789854685,1739137683.6152885,25.329975843429565,3.3661676140682317,1739137683.6152928,25.329975843429565,52.63705766334304,1739137683.6152964,25.329975843429565,50.15793620308245,1739137683.6152983,25.329975843429565,7.707603657217129,1739137683.6153007,25.329975843429565,1.6038009673477427,1739137683.6153026,25.329975843429565,2.097634946975986,1739137683.6153045,25.329975843429565,0.6108,1739137683.6153064,25.329975843429565,1.080297809956438,1739137683.6153088,25.329975843429565,0.0,1739137683.6153107,25.329975843429565,-0.08629499845079813,1739137683.6153126,25.329975843429565,1.0998340920886331,1739137683.615315,25.329975843429565,1.1665928084072361 +1739137683.6353672,25.34997582435608,50.301275789854685,1739137683.635371,25.34997582435608,3.3661676140682317,1739137683.6353755,25.34997582435608,52.63705766334304,1739137683.6353796,25.34997582435608,50.15793620308245,1739137683.6353815,25.34997582435608,7.707603657217129,1739137683.6353838,25.34997582435608,1.6038009673477427,1739137683.6353858,25.34997582435608,2.097634946975986,1739137683.6353877,25.34997582435608,0.6108,1739137683.6353893,25.34997582435608,1.080297809956438,1739137683.6353915,25.34997582435608,0.0,1739137683.6353936,25.34997582435608,-0.08629499845079813,1739137683.6353955,25.34997582435608,1.0998340920886331,1739137683.6353977,25.34997582435608,1.1665928084072361 +1739137683.6558175,25.369975805282593,50.3579330373304,1739137683.655821,25.369975805282593,3.4809756756667927,1739137683.655825,25.369975805282593,53.008041401410146,1739137683.6558287,25.369975805282593,49.876063593515305,1739137683.6558306,25.369975805282593,7.911968342082279,1739137683.6558328,25.369975805282593,1.6791204055835809,1739137683.655835,25.369975805282593,2.3360628129519143,1739137683.6558366,25.369975805282593,0.6108,1739137683.6558385,25.369975805282593,0.9820290453588211,1739137683.6558404,25.369975805282593,0.0,1739137683.6558423,25.369975805282593,-0.25943649424295234,1739137683.6558444,25.369975805282593,1.1274393062895478,1739137683.6558464,25.369975805282593,1.159017167085612 +1739137683.6753457,25.389975786209106,50.3579330373304,1739137683.6753492,25.389975786209106,3.4809756756667927,1739137683.6753533,25.389975786209106,53.008041401410146,1739137683.675357,25.389975786209106,49.876063593515305,1739137683.675359,25.389975786209106,7.911968342082279,1739137683.6753616,25.389975786209106,1.6791204055835809,1739137683.6753635,25.389975786209106,2.3360628129519143,1739137683.6753654,25.389975786209106,0.6108,1739137683.675367,25.389975786209106,0.9820290453588211,1739137683.6753695,25.389975786209106,0.0,1739137683.6753712,25.389975786209106,-0.1769881217267909,1739137683.6753733,25.389975786209106,1.1274393062895478,1739137683.6753752,25.389975786209106,1.159017167085612 +1739137683.6956012,25.40997576713562,50.3579330373304,1739137683.6956058,25.40997576713562,3.4809756756667927,1739137683.6956103,25.40997576713562,53.008041401410146,1739137683.6956148,25.40997576713562,49.876063593515305,1739137683.695617,25.40997576713562,7.911968342082279,1739137683.6956196,25.40997576713562,1.6791204055835809,1739137683.6956222,25.40997576713562,2.3360628129519143,1739137683.6956244,25.40997576713562,0.6108,1739137683.6956265,25.40997576713562,0.9820290453588211,1739137683.695629,25.40997576713562,0.0,1739137683.6956308,25.40997576713562,-0.1769881217267909,1739137683.6956334,25.40997576713562,1.1274393062895478,1739137683.6956353,25.40997576713562,1.159017167085612 +1739137683.7181256,25.429975748062134,50.3579330373304,1739137683.7181296,25.429975748062134,3.4809756756667927,1739137683.7181342,25.429975748062134,53.008041401410146,1739137683.7181387,25.429975748062134,49.876063593515305,1739137683.7181406,25.429975748062134,7.911968342082279,1739137683.7181435,25.429975748062134,1.6791204055835809,1739137683.7181458,25.429975748062134,2.3360628129519143,1739137683.718148,25.429975748062134,0.6108,1739137683.7181501,25.429975748062134,0.9820290453588211,1739137683.7181528,25.429975748062134,0.0,1739137683.7181547,25.429975748062134,-0.1769881217267909,1739137683.7181573,25.429975748062134,1.1274393062895478,1739137683.7181594,25.429975748062134,1.159017167085612 +1739137683.735398,25.449975728988647,50.3579330373304,1739137683.7354019,25.449975728988647,3.4809756756667927,1739137683.7354066,25.449975728988647,53.008041401410146,1739137683.735411,25.449975728988647,49.876063593515305,1739137683.7354133,25.449975728988647,7.911968342082279,1739137683.7354162,25.449975728988647,1.6791204055835809,1739137683.7354183,25.449975728988647,2.3360628129519143,1739137683.7354207,25.449975728988647,0.6108,1739137683.7354226,25.449975728988647,0.9820290453588211,1739137683.7354252,25.449975728988647,0.0,1739137683.7354276,25.449975728988647,-0.1769881217267909,1739137683.73543,25.449975728988647,1.1274393062895478,1739137683.7354321,25.449975728988647,1.159017167085612 +1739137683.7574987,25.46997570991516,50.410703859267464,1739137683.7575037,25.46997570991516,3.595778165820356,1739137683.7575097,25.46997570991516,53.16178412517051,1739137683.7575161,25.46997570991516,49.8127132435108,1739137683.757519,25.46997570991516,7.953176822182295,1739137683.7575233,25.46997570991516,1.7071800754502304,1739137683.7575269,25.46997570991516,2.3069061657898216,1739137683.7575302,25.46997570991516,0.6108,1739137683.7575336,25.46997570991516,0.9935491621282504,1739137683.7575371,25.46997570991516,0.0,1739137683.75754,25.46997570991516,-0.10525130545551561,1739137683.7575436,25.46997570991516,1.1550445204904625,1739137683.757547,25.46997570991516,1.1329608733489884 +1739137683.7761588,25.489975690841675,50.410703859267464,1739137683.7761626,25.489975690841675,3.595778165820356,1739137683.7761674,25.489975690841675,53.16178412517051,1739137683.776172,25.489975690841675,49.8127132435108,1739137683.7761745,25.489975690841675,7.953176822182295,1739137683.7761776,25.489975690841675,1.7071800754502304,1739137683.7761812,25.489975690841675,2.3069061657898216,1739137683.776184,25.489975690841675,0.6108,1739137683.7761867,25.489975690841675,0.9935491621282504,1739137683.7761889,25.489975690841675,0.0,1739137683.7761917,25.489975690841675,-0.13941171122073803,1739137683.7761946,25.489975690841675,1.1550445204904625,1739137683.7761972,25.489975690841675,1.1329608733489884 +1739137683.795746,25.50997567176819,50.410703859267464,1739137683.7957497,25.50997567176819,3.595778165820356,1739137683.7957537,25.50997567176819,53.16178412517051,1739137683.7957582,25.50997567176819,49.8127132435108,1739137683.7957606,25.50997567176819,7.953176822182295,1739137683.7957637,25.50997567176819,1.7071800754502304,1739137683.7957664,25.50997567176819,2.3069061657898216,1739137683.7957685,25.50997567176819,0.6108,1739137683.7957714,25.50997567176819,0.9935491621282504,1739137683.795774,25.50997567176819,0.0,1739137683.7957766,25.50997567176819,-0.13941171122073803,1739137683.795779,25.50997567176819,1.1550445204904625,1739137683.7957814,25.50997567176819,1.1329608733489884 +1739137683.8153284,25.529975652694702,50.410703859267464,1739137683.815332,25.529975652694702,3.595778165820356,1739137683.8153362,25.529975652694702,53.16178412517051,1739137683.81534,25.529975652694702,49.8127132435108,1739137683.8153424,25.529975652694702,7.953176822182295,1739137683.815345,25.529975652694702,1.7071800754502304,1739137683.8153477,25.529975652694702,2.3069061657898216,1739137683.81535,25.529975652694702,0.6108,1739137683.8153522,25.529975652694702,0.9935491621282504,1739137683.815355,25.529975652694702,0.0,1739137683.8153574,25.529975652694702,-0.13941171122073803,1739137683.8153598,25.529975652694702,1.1550445204904625,1739137683.8153622,25.529975652694702,1.1329608733489884 +1739137683.8357913,25.549975633621216,50.410703859267464,1739137683.8357956,25.549975633621216,3.595778165820356,1739137683.8358004,25.549975633621216,53.16178412517051,1739137683.8358052,25.549975633621216,49.8127132435108,1739137683.8358078,25.549975633621216,7.953176822182295,1739137683.835811,25.549975633621216,1.7071800754502304,1739137683.8358133,25.549975633621216,2.3069061657898216,1739137683.8358161,25.549975633621216,0.6108,1739137683.8358185,25.549975633621216,0.9935491621282504,1739137683.835821,25.549975633621216,0.0,1739137683.835823,25.549975633621216,-0.13941171122073803,1739137683.8358254,25.549975633621216,1.1550445204904625,1739137683.835828,25.549975633621216,1.1329608733489884 +1739137683.8556619,25.56997561454773,50.410703859267464,1739137683.8556645,25.56997561454773,3.595778165820356,1739137683.8556669,25.56997561454773,53.16178412517051,1739137683.8556697,25.56997561454773,49.8127132435108,1739137683.855671,25.56997561454773,7.953176822182295,1739137683.8556726,25.56997561454773,1.7071800754502304,1739137683.8556738,25.56997561454773,2.3069061657898216,1739137683.8556752,25.56997561454773,0.6108,1739137683.8556764,25.56997561454773,0.9935491621282504,1739137683.8556778,25.56997561454773,0.0,1739137683.8556793,25.56997561454773,-0.13941171122073803,1739137683.8556805,25.56997561454773,1.1550445204904625,1739137683.855682,25.56997561454773,1.1329608733489884 +1739137683.8771272,25.589975595474243,50.45934059766865,1739137683.8771312,25.589975595474243,3.709785788230123,1739137683.8771365,25.589975595474243,53.313904769896084,1739137683.877141,25.589975595474243,49.71984477411448,1739137683.8771436,25.589975595474243,8.010868538543125,1739137683.877147,25.589975595474243,1.7410640821602592,1739137683.8771493,25.589975595474243,2.312332261882134,1739137683.8771517,25.589975595474243,0.6108,1739137683.8771544,25.589975595474243,0.9913950633528101,1739137683.877157,25.589975595474243,0.0,1739137683.8771594,25.589975595474243,-0.11629732903442806,1739137683.8771622,25.589975595474243,1.1826497346913771,1739137683.8771646,25.589975595474243,1.1186992465457903 +1739137683.8938434,25.609975576400757,50.45934059766865,1739137683.8938456,25.609975576400757,3.709785788230123,1739137683.8938477,25.609975576400757,53.313904769896084,1739137683.8938506,25.609975576400757,49.71984477411448,1739137683.893852,25.609975576400757,8.010868538543125,1739137683.8938534,25.609975576400757,1.7410640821602592,1739137683.8938546,25.609975576400757,2.312332261882134,1739137683.893856,25.609975576400757,0.6108,1739137683.8938572,25.609975576400757,0.9913950633528101,1739137683.8938587,25.609975576400757,0.0,1739137683.8938599,25.609975576400757,-0.1273041831929802,1739137683.893861,25.609975576400757,1.1826497346913771,1739137683.8938625,25.609975576400757,1.1186992465457903 +1739137683.913771,25.62997555732727,50.45934059766865,1739137683.9137752,25.62997555732727,3.709785788230123,1739137683.9137864,25.62997555732727,53.313904769896084,1739137683.9137902,25.62997555732727,49.71984477411448,1739137683.9137928,25.62997555732727,8.010868538543125,1739137683.9137948,25.62997555732727,1.7410640821602592,1739137683.9137971,25.62997555732727,2.312332261882134,1739137683.9137993,25.62997555732727,0.6108,1739137683.9138012,25.62997555732727,0.9913950633528101,1739137683.913804,25.62997555732727,0.0,1739137683.913809,25.62997555732727,-0.1273041831929802,1739137683.9138114,25.62997555732727,1.1826497346913771,1739137683.9138174,25.62997555732727,1.1186992465457903 +1739137683.9337611,25.649975538253784,50.45934059766865,1739137683.9337633,25.649975538253784,3.709785788230123,1739137683.933766,25.649975538253784,53.313904769896084,1739137683.9337685,25.649975538253784,49.71984477411448,1739137683.9337697,25.649975538253784,8.010868538543125,1739137683.9337714,25.649975538253784,1.7410640821602592,1739137683.9337728,25.649975538253784,2.312332261882134,1739137683.9337738,25.649975538253784,0.6108,1739137683.9337752,25.649975538253784,0.9913950633528101,1739137683.9337766,25.649975538253784,0.0,1739137683.9337776,25.649975538253784,-0.1273041831929802,1739137683.9337792,25.649975538253784,1.1826497346913771,1739137683.9337802,25.649975538253784,1.1186992465457903 +1739137683.9537537,25.669975519180298,50.45934059766865,1739137683.9537556,25.669975519180298,3.709785788230123,1739137683.9537582,25.669975519180298,53.313904769896084,1739137683.9537609,25.669975519180298,49.71984477411448,1739137683.953762,25.669975519180298,8.010868538543125,1739137683.9537637,25.669975519180298,1.7410640821602592,1739137683.9537652,25.669975519180298,2.312332261882134,1739137683.9537663,25.669975519180298,0.6108,1739137683.9537675,25.669975519180298,0.9913950633528101,1739137683.953769,25.669975519180298,0.0,1739137683.9537702,25.669975519180298,-0.1273041831929802,1739137683.9537716,25.669975519180298,1.1826497346913771,1739137683.9537728,25.669975519180298,1.1186992465457903 +1739137683.973809,25.68997550010681,50.50422261043049,1739137683.9738111,25.68997550010681,3.8235980149593765,1739137683.9738138,25.68997550010681,53.536265484506764,1739137683.9738162,25.68997550010681,49.563724644107474,1739137683.9738176,25.68997550010681,8.10078655775956,1739137683.973819,25.68997550010681,1.787238803378104,1739137683.9738204,25.68997550010681,2.3889397979334306,1739137683.9738216,25.68997550010681,0.6108,1739137683.973823,25.68997550010681,0.9614764691658434,1739137683.9738245,25.68997550010681,0.0,1739137683.9738255,25.68997550010681,-0.157573061023746,1739137683.973827,25.68997550010681,1.2102549488922918,1739137683.973828,25.68997550010681,1.1046357716413036 +1739137683.9937596,25.709975481033325,50.50422261043049,1739137683.993762,25.709975481033325,3.8235980149593765,1739137683.9937646,25.709975481033325,53.536265484506764,1739137683.9937673,25.709975481033325,49.563724644107474,1739137683.9937685,25.709975481033325,8.10078655775956,1739137683.99377,25.709975481033325,1.787238803378104,1739137683.9937713,25.709975481033325,2.3889397979334306,1739137683.9937725,25.709975481033325,0.6108,1739137683.9937735,25.709975481033325,0.9614764691658434,1739137683.9937751,25.709975481033325,0.0,1739137683.993776,25.709975481033325,-0.14315930247546016,1739137683.9937778,25.709975481033325,1.2102549488922918,1739137683.9937787,25.709975481033325,1.1046357716413036 +1739137684.020034,25.72997546195984,50.50422261043049,1739137684.0200424,25.72997546195984,3.8235980149593765,1739137684.0200531,25.72997546195984,53.536265484506764,1739137684.020063,25.72997546195984,49.563724644107474,1739137684.0200677,25.72997546195984,8.10078655775956,1739137684.0200734,25.72997546195984,1.787238803378104,1739137684.020079,25.72997546195984,2.3889397979334306,1739137684.0200834,25.72997546195984,0.6108,1739137684.020088,25.72997546195984,0.9614764691658434,1739137684.0200934,25.72997546195984,0.0,1739137684.020098,25.72997546195984,-0.14315930247546016,1739137684.0201035,25.72997546195984,1.2102549488922918,1739137684.0201077,25.72997546195984,1.1046357716413036 +1739137684.0468025,25.749975442886353,50.50422261043049,1739137684.0468116,25.749975442886353,3.8235980149593765,1739137684.0468218,25.749975442886353,53.536265484506764,1739137684.0468316,25.749975442886353,49.563724644107474,1739137684.0468364,25.749975442886353,8.10078655775956,1739137684.0468423,25.749975442886353,1.787238803378104,1739137684.0468473,25.749975442886353,2.3889397979334306,1739137684.0468519,25.749975442886353,0.6108,1739137684.0468564,25.749975442886353,0.9614764691658434,1739137684.0468616,25.749975442886353,0.0,1739137684.0468662,25.749975442886353,-0.14315930247546016,1739137684.0468712,25.749975442886353,1.2102549488922918,1739137684.046876,25.749975442886353,1.1046357716413036 +1739137684.0633018,25.769975423812866,50.50422261043049,1739137684.0633063,25.769975423812866,3.8235980149593765,1739137684.0633116,25.769975423812866,53.536265484506764,1739137684.0633166,25.769975423812866,49.563724644107474,1739137684.063319,25.769975423812866,8.10078655775956,1739137684.063322,25.769975423812866,1.787238803378104,1739137684.0633247,25.769975423812866,2.3889397979334306,1739137684.0633273,25.769975423812866,0.6108,1739137684.0633295,25.769975423812866,0.9614764691658434,1739137684.0633323,25.769975423812866,0.0,1739137684.063335,25.769975423812866,-0.14315930247546016,1739137684.0633378,25.769975423812866,1.2102549488922918,1739137684.0633402,25.769975423812866,1.1046357716413036 +1739137684.0820572,25.78997540473938,50.50422261043049,1739137684.0820608,25.78997540473938,3.8235980149593765,1739137684.082065,25.78997540473938,53.536265484506764,1739137684.082069,25.78997540473938,49.563724644107474,1739137684.0820713,25.78997540473938,8.10078655775956,1739137684.0820737,25.78997540473938,1.787238803378104,1739137684.0820756,25.78997540473938,2.3889397979334306,1739137684.0820777,25.78997540473938,0.6108,1739137684.0820794,25.78997540473938,0.9614764691658434,1739137684.0820818,25.78997540473938,0.0,1739137684.082084,25.78997540473938,-0.14315930247546016,1739137684.082086,25.78997540473938,1.2102549488922918,1739137684.0820882,25.78997540473938,1.1046357716413036 +1739137684.1025395,25.809975385665894,50.54538421276898,1739137684.1025434,25.809975385665894,3.9370553198332843,1739137684.1025476,25.809975385665894,53.68988037750998,1739137684.1025517,25.809975385665894,49.470636400642036,1739137684.102554,25.809975385665894,8.150804354105297,1739137684.1025567,25.809975385665894,1.8205291889917408,1739137684.1025586,25.809975385665894,2.392864770278904,1739137684.1025608,25.809975385665894,0.6108,1739137684.102563,25.809975385665894,0.9599681460800215,1739137684.1025655,25.809975385665894,0.0,1739137684.1025677,25.809975385665894,-0.11553675186566854,1739137684.10257,25.809975385665894,1.2378601630932065,1739137684.1025722,25.809975385665894,1.0886585000449611 +1739137684.1224334,25.829975366592407,50.54538421276898,1739137684.1224375,25.829975366592407,3.9370553198332843,1739137684.1224418,25.829975366592407,53.68988037750998,1739137684.122446,25.829975366592407,49.470636400642036,1739137684.1224487,25.829975366592407,8.150804354105297,1739137684.1224508,25.829975366592407,1.8205291889917408,1739137684.1224532,25.829975366592407,2.392864770278904,1739137684.1224554,25.829975366592407,0.6108,1739137684.122457,25.829975366592407,0.9599681460800215,1739137684.1224594,25.829975366592407,0.0,1739137684.122461,25.829975366592407,-0.12869035396493966,1739137684.1224635,25.829975366592407,1.2378601630932065,1739137684.1224656,25.829975366592407,1.0886585000449611 +1739137684.1413007,25.84997534751892,50.54538421276898,1739137684.1413038,25.84997534751892,3.9370553198332843,1739137684.1413074,25.84997534751892,53.68988037750998,1739137684.1413107,25.84997534751892,49.470636400642036,1739137684.1413126,25.84997534751892,8.150804354105297,1739137684.1413145,25.84997534751892,1.8205291889917408,1739137684.1413164,25.84997534751892,2.392864770278904,1739137684.141318,25.84997534751892,0.6108,1739137684.1413195,25.84997534751892,0.9599681460800215,1739137684.1413217,25.84997534751892,0.0,1739137684.141323,25.84997534751892,-0.12869035396493966,1739137684.1413248,25.84997534751892,1.2378601630932065,1739137684.1413267,25.84997534751892,1.0886585000449611 +1739137684.1619148,25.869975328445435,50.54538421276898,1739137684.1619167,25.869975328445435,3.9370553198332843,1739137684.161919,25.869975328445435,53.68988037750998,1739137684.1619215,25.869975328445435,49.470636400642036,1739137684.161923,25.869975328445435,8.150804354105297,1739137684.1619244,25.869975328445435,1.8205291889917408,1739137684.1619256,25.869975328445435,2.392864770278904,1739137684.1619267,25.869975328445435,0.6108,1739137684.1619277,25.869975328445435,0.9599681460800215,1739137684.161929,25.869975328445435,0.0,1739137684.1619306,25.869975328445435,-0.12869035396493966,1739137684.161932,25.869975328445435,1.2378601630932065,1739137684.161933,25.869975328445435,1.0886585000449611 +1739137684.1811743,25.88997530937195,50.54538421276898,1739137684.1811767,25.88997530937195,3.9370553198332843,1739137684.181179,25.88997530937195,53.68988037750998,1739137684.1811817,25.88997530937195,49.470636400642036,1739137684.1811829,25.88997530937195,8.150804354105297,1739137684.1811845,25.88997530937195,1.8205291889917408,1739137684.181186,25.88997530937195,2.392864770278904,1739137684.1811872,25.88997530937195,0.6108,1739137684.181188,25.88997530937195,0.9599681460800215,1739137684.1811895,25.88997530937195,0.0,1739137684.1811907,25.88997530937195,-0.12869035396493966,1739137684.181192,25.88997530937195,1.2378601630932065,1739137684.181193,25.88997530937195,1.0886585000449611 +1739137684.201455,25.909975290298462,50.58288100642708,1739137684.2014575,25.909975290298462,4.050047507019993,1739137684.2014601,25.909975290298462,53.84405508713024,1739137684.2014627,25.909975290298462,49.370085865810196,1739137684.2014642,25.909975290298462,8.200680216445729,1739137684.2014656,25.909975290298462,1.855077504371349,1739137684.2014668,25.909975290298462,2.404417214616533,1739137684.201468,25.909975290298462,0.6108,1739137684.201469,25.909975290298462,0.9555423881903863,1739137684.2014701,25.909975290298462,0.0,1739137684.2014716,25.909975290298462,-0.11045791024647741,1739137684.2014728,25.909975290298462,1.2654653772941211,1739137684.201474,25.909975290298462,1.0746824188303727 +1739137684.2271369,25.929975271224976,50.58288100642708,1739137684.227145,25.929975271224976,4.050047507019993,1739137684.227155,25.929975271224976,53.84405508713024,1739137684.2271647,25.929975271224976,49.370085865810196,1739137684.2271698,25.929975271224976,8.200680216445729,1739137684.227176,25.929975271224976,1.855077504371349,1739137684.2271807,25.929975271224976,2.404417214616533,1739137684.2271857,25.929975271224976,0.6108,1739137684.2271903,25.929975271224976,0.9555423881903863,1739137684.2271957,25.929975271224976,0.0,1739137684.2272005,25.929975271224976,-0.11914003063998646,1739137684.227206,25.929975271224976,1.2654653772941211,1739137684.2272105,25.929975271224976,1.0746824188303727 +1739137684.2482004,25.94997525215149,50.58288100642708,1739137684.2482095,25.94997525215149,4.050047507019993,1739137684.2482207,25.94997525215149,53.84405508713024,1739137684.2482345,25.94997525215149,49.370085865810196,1739137684.248242,25.94997525215149,8.200680216445729,1739137684.2482514,25.94997525215149,1.855077504371349,1739137684.24826,25.94997525215149,2.404417214616533,1739137684.2482686,25.94997525215149,0.6108,1739137684.248277,25.94997525215149,0.9555423881903863,1739137684.2482858,25.94997525215149,0.0,1739137684.2482944,25.94997525215149,-0.11914003063998646,1739137684.2483034,25.94997525215149,1.2654653772941211,1739137684.248312,25.94997525215149,1.0746824188303727 +1739137684.263885,25.969975233078003,50.58288100642708,1739137684.2638896,25.969975233078003,4.050047507019993,1739137684.263895,25.969975233078003,53.84405508713024,1739137684.2639,25.969975233078003,49.370085865810196,1739137684.2639027,25.969975233078003,8.200680216445729,1739137684.263906,25.969975233078003,1.855077504371349,1739137684.2639086,25.969975233078003,2.404417214616533,1739137684.2639115,25.969975233078003,0.6108,1739137684.2639136,25.969975233078003,0.9555423881903863,1739137684.2639167,25.969975233078003,0.0,1739137684.2639194,25.969975233078003,-0.11914003063998646,1739137684.2639222,25.969975233078003,1.2654653772941211,1739137684.2639248,25.969975233078003,1.0746824188303727 +1739137684.2834237,25.989975214004517,50.58288100642708,1739137684.2834263,25.989975214004517,4.050047507019993,1739137684.2834294,25.989975214004517,53.84405508713024,1739137684.2834325,25.989975214004517,49.370085865810196,1739137684.283434,25.989975214004517,8.200680216445729,1739137684.2834358,25.989975214004517,1.855077504371349,1739137684.2834373,25.989975214004517,2.404417214616533,1739137684.283439,25.989975214004517,0.6108,1739137684.2834406,25.989975214004517,0.9555423881903863,1739137684.2834423,25.989975214004517,0.0,1739137684.2834437,25.989975214004517,-0.11914003063998646,1739137684.2834456,25.989975214004517,1.2654653772941211,1739137684.2834473,25.989975214004517,1.0746824188303727 +1739137684.302508,26.00997519493103,50.58288100642708,1739137684.3025105,26.00997519493103,4.050047507019993,1739137684.3025134,26.00997519493103,53.84405508713024,1739137684.3025162,26.00997519493103,49.370085865810196,1739137684.3025177,26.00997519493103,8.200680216445729,1739137684.3025193,26.00997519493103,1.855077504371349,1739137684.3025208,26.00997519493103,2.404417214616533,1739137684.3025222,26.00997519493103,0.6108,1739137684.3025234,26.00997519493103,0.9555423881903863,1739137684.302525,26.00997519493103,0.0,1739137684.3025262,26.00997519493103,-0.11914003063998646,1739137684.3025277,26.00997519493103,1.2654653772941211,1739137684.302529,26.00997519493103,1.0746824188303727 +1739137684.3228362,26.029975175857544,50.61681807531633,1739137684.3228385,26.029975175857544,4.1626170727846965,1739137684.3228412,26.029975175857544,53.99495152601004,1739137684.3228436,26.029975175857544,49.26807063136422,1739137684.3228452,26.029975175857544,8.24745090624259,1739137684.3228467,26.029975175857544,1.8897099561136068,1739137684.322848,26.029975175857544,2.4170012016398417,1739137684.3228493,26.029975175857544,0.6108,1739137684.3228505,26.029975175857544,0.9507446600249274,1739137684.322852,26.029975175857544,0.0,1739137684.322853,26.029975175857544,-0.10369831634166347,1739137684.3228548,26.029975175857544,1.2930705914950358,1739137684.322856,26.029975175857544,1.0617961773247517 +1739137684.3425987,26.049975156784058,50.61681807531633,1739137684.3426013,26.049975156784058,4.1626170727846965,1739137684.3426037,26.049975156784058,53.99495152601004,1739137684.3426065,26.049975156784058,49.26807063136422,1739137684.342608,26.049975156784058,8.24745090624259,1739137684.3426094,26.049975156784058,1.8897099561136068,1739137684.3426104,26.049975156784058,2.4170012016398417,1739137684.3426118,26.049975156784058,0.6108,1739137684.342613,26.049975156784058,0.9507446600249274,1739137684.3426142,26.049975156784058,0.0,1739137684.3426154,26.049975156784058,-0.11105151729982432,1739137684.342617,26.049975156784058,1.2930705914950358,1739137684.3426182,26.049975156784058,1.0617961773247517 +1739137684.3628871,26.06997513771057,50.61681807531633,1739137684.3628893,26.06997513771057,4.1626170727846965,1739137684.3628922,26.06997513771057,53.99495152601004,1739137684.3628945,26.06997513771057,49.26807063136422,1739137684.362896,26.06997513771057,8.24745090624259,1739137684.3628974,26.06997513771057,1.8897099561136068,1739137684.3628993,26.06997513771057,2.4170012016398417,1739137684.3629003,26.06997513771057,0.6108,1739137684.3629014,26.06997513771057,0.9507446600249274,1739137684.3629029,26.06997513771057,0.0,1739137684.362904,26.06997513771057,-0.11105151729982432,1739137684.3629053,26.06997513771057,1.2930705914950358,1739137684.362907,26.06997513771057,1.0617961773247517 +1739137684.3821828,26.089975118637085,50.61681807531633,1739137684.3821852,26.089975118637085,4.1626170727846965,1739137684.3821878,26.089975118637085,53.99495152601004,1739137684.38219,26.089975118637085,49.26807063136422,1739137684.3821914,26.089975118637085,8.24745090624259,1739137684.3821929,26.089975118637085,1.8897099561136068,1739137684.3821943,26.089975118637085,2.4170012016398417,1739137684.3821955,26.089975118637085,0.6108,1739137684.3821964,26.089975118637085,0.9507446600249274,1739137684.382198,26.089975118637085,0.0,1739137684.3821993,26.089975118637085,-0.11105151729982432,1739137684.3822005,26.089975118637085,1.2930705914950358,1739137684.382202,26.089975118637085,1.0617961773247517 +1739137684.4025464,26.1099750995636,50.61681807531633,1739137684.4025486,26.1099750995636,4.1626170727846965,1739137684.402551,26.1099750995636,53.99495152601004,1739137684.4025536,26.1099750995636,49.26807063136422,1739137684.4025552,26.1099750995636,8.24745090624259,1739137684.402557,26.1099750995636,1.8897099561136068,1739137684.4025583,26.1099750995636,2.4170012016398417,1739137684.4025593,26.1099750995636,0.6108,1739137684.4025605,26.1099750995636,0.9507446600249274,1739137684.4025621,26.1099750995636,0.0,1739137684.4025633,26.1099750995636,-0.11105151729982432,1739137684.4025645,26.1099750995636,1.2930705914950358,1739137684.402566,26.1099750995636,1.0617961773247517 +1739137684.4283974,26.129975080490112,50.647272120182734,1739137684.4284053,26.129975080490112,4.274744730749342,1739137684.428415,26.129975080490112,54.165039237714254,1739137684.428425,26.129975080490112,49.14560149216678,1739137684.42843,26.129975080490112,8.301301884481202,1739137684.428436,26.129975080490112,1.9277611437049114,1739137684.4284408,26.129975080490112,2.4515989118429293,1739137684.4284456,26.129975080490112,0.6108,1739137684.4284503,26.129975080490112,0.9376778496248559,1739137684.4284556,26.129975080490112,0.0,1739137684.4284606,26.129975080490112,-0.11290240107087289,1739137684.4284658,26.129975080490112,1.3206758056959504,1739137684.4284706,26.129975080490112,1.0496988770311353 +1739137684.4470282,26.149975061416626,50.647272120182734,1739137684.4470367,26.149975061416626,4.274744730749342,1739137684.447046,26.149975061416626,54.165039237714254,1739137684.4470558,26.149975061416626,49.14560149216678,1739137684.447061,26.149975061416626,8.301301884481202,1739137684.4470665,26.149975061416626,1.9277611437049114,1739137684.4470718,26.149975061416626,2.4515989118429293,1739137684.4470766,26.149975061416626,0.6108,1739137684.4470813,26.149975061416626,0.9376778496248559,1739137684.4470868,26.149975061416626,0.0,1739137684.4470913,26.149975061416626,-0.1120210274062794,1739137684.4470966,26.149975061416626,1.3206758056959504,1739137684.447101,26.149975061416626,1.0496988770311353 +1739137684.474049,26.16997504234314,50.647272120182734,1739137684.4740546,26.16997504234314,4.274744730749342,1739137684.4740615,26.16997504234314,54.165039237714254,1739137684.474068,26.16997504234314,49.14560149216678,1739137684.474071,26.16997504234314,8.301301884481202,1739137684.474075,26.16997504234314,1.9277611437049114,1739137684.4740784,26.16997504234314,2.4515989118429293,1739137684.4740818,26.16997504234314,0.6108,1739137684.4740849,26.16997504234314,0.9376778496248559,1739137684.4740884,26.16997504234314,0.0,1739137684.4740915,26.16997504234314,-0.1120210274062794,1739137684.4740953,26.16997504234314,1.3206758056959504,1739137684.4740984,26.16997504234314,1.0496988770311353 +1739137684.4937508,26.19997501373291,50.647272120182734,1739137684.4937565,26.19997501373291,4.274744730749342,1739137684.4937637,26.19997501373291,54.165039237714254,1739137684.4937701,26.19997501373291,49.14560149216678,1739137684.4937735,26.19997501373291,8.301301884481202,1739137684.4937775,26.19997501373291,1.9277611437049114,1739137684.4937809,26.19997501373291,2.4515989118429293,1739137684.493784,26.19997501373291,0.6108,1739137684.493787,26.19997501373291,0.9376778496248559,1739137684.4937909,26.19997501373291,0.0,1739137684.4937942,26.19997501373291,-0.1120210274062794,1739137684.4937978,26.19997501373291,1.3206758056959504,1739137684.493801,26.19997501373291,1.0496988770311353 +1739137684.517864,26.219974994659424,50.647272120182734,1739137684.5178685,26.219974994659424,4.274744730749342,1739137684.5178738,26.219974994659424,54.165039237714254,1739137684.5178797,26.219974994659424,49.14560149216678,1739137684.5178888,26.219974994659424,8.301301884481202,1739137684.5178933,26.219974994659424,1.9277611437049114,1739137684.5178971,26.219974994659424,2.4515989118429293,1739137684.5179014,26.219974994659424,0.6108,1739137684.5179052,26.219974994659424,0.9376778496248559,1739137684.5179093,26.219974994659424,0.0,1739137684.5179133,26.219974994659424,-0.1120210274062794,1739137684.5179174,26.219974994659424,1.3206758056959504,1739137684.5179212,26.219974994659424,1.0496988770311353 +1739137684.537237,26.239974975585938,50.67430364312668,1739137684.537242,26.239974975585938,4.386364982381933,1739137684.5372472,26.239974975585938,54.29832884567831,1739137684.5372527,26.239974975585938,49.05632523793481,1739137684.5372558,26.239974975585938,8.337669904826079,1739137684.5372596,26.239974975585938,1.959447889975874,1739137684.5372634,26.239974975585938,2.4500761142953853,1739137684.5372665,26.239974975585938,0.6108,1739137684.5372698,26.239974975585938,0.9382491810235195,1739137684.5372736,26.239974975585938,0.0,1739137684.5372772,26.239974975585938,-0.08745568568828181,1739137684.5372813,26.239974975585938,1.348281019896865,1739137684.5372849,26.239974975585938,1.0374026543258323 +1739137684.5575287,26.25997495651245,50.67430364312668,1739137684.5575328,26.25997495651245,4.386364982381933,1739137684.5575373,26.25997495651245,54.29832884567831,1739137684.5575423,26.25997495651245,49.05632523793481,1739137684.5575457,26.25997495651245,8.337669904826079,1739137684.5575492,26.25997495651245,1.959447889975874,1739137684.5575526,26.25997495651245,2.4500761142953853,1739137684.557556,26.25997495651245,0.6108,1739137684.557559,26.25997495651245,0.9382491810235195,1739137684.5575626,26.25997495651245,0.0,1739137684.5575657,26.25997495651245,-0.09915347330231283,1739137684.5575693,26.25997495651245,1.348281019896865,1739137684.5575726,26.25997495651245,1.0374026543258323 +1739137684.5769608,26.279974937438965,50.67430364312668,1739137684.5769646,26.279974937438965,4.386364982381933,1739137684.5769691,26.279974937438965,54.29832884567831,1739137684.5769744,26.279974937438965,49.05632523793481,1739137684.5769773,26.279974937438965,8.337669904826079,1739137684.576981,26.279974937438965,1.959447889975874,1739137684.5769844,26.279974937438965,2.4500761142953853,1739137684.5769877,26.279974937438965,0.6108,1739137684.576991,26.279974937438965,0.9382491810235195,1739137684.5769944,26.279974937438965,0.0,1739137684.5769982,26.279974937438965,-0.09915347330231283,1739137684.5770018,26.279974937438965,1.348281019896865,1739137684.5770051,26.279974937438965,1.0374026543258323 +1739137684.5975559,26.29997491836548,50.67430364312668,1739137684.5975611,26.29997491836548,4.386364982381933,1739137684.5975673,26.29997491836548,54.29832884567831,1739137684.5975742,26.29997491836548,49.05632523793481,1739137684.5975778,26.29997491836548,8.337669904826079,1739137684.597582,26.29997491836548,1.959447889975874,1739137684.5975862,26.29997491836548,2.4500761142953853,1739137684.5975902,26.29997491836548,0.6108,1739137684.597594,26.29997491836548,0.9382491810235195,1739137684.5975978,26.29997491836548,0.0,1739137684.5976021,26.29997491836548,-0.09915347330231283,1739137684.5976064,26.29997491836548,1.348281019896865,1739137684.5976112,26.29997491836548,1.0374026543258323 +1739137684.6171982,26.319974899291992,50.67430364312668,1739137684.6172032,26.319974899291992,4.386364982381933,1739137684.6172092,26.319974899291992,54.29832884567831,1739137684.6172142,26.319974899291992,49.05632523793481,1739137684.6172173,26.319974899291992,8.337669904826079,1739137684.617221,26.319974899291992,1.959447889975874,1739137684.6172245,26.319974899291992,2.4500761142953853,1739137684.617228,26.319974899291992,0.6108,1739137684.6172316,26.319974899291992,0.9382491810235195,1739137684.6172352,26.319974899291992,0.0,1739137684.6172388,26.319974899291992,-0.09915347330231283,1739137684.617243,26.319974899291992,1.348281019896865,1739137684.6172473,26.319974899291992,1.0374026543258323 +1739137684.6343236,26.339974880218506,50.67430364312668,1739137684.6343262,26.339974880218506,4.386364982381933,1739137684.634329,26.339974880218506,54.29832884567831,1739137684.6343317,26.339974880218506,49.05632523793481,1739137684.6343331,26.339974880218506,8.337669904826079,1739137684.6343348,26.339974880218506,1.959447889975874,1739137684.634336,26.339974880218506,2.4500761142953853,1739137684.6343372,26.339974880218506,0.6108,1739137684.6343386,26.339974880218506,0.9382491810235195,1739137684.6343398,26.339974880218506,0.0,1739137684.634341,26.339974880218506,-0.09915347330231283,1739137684.6343424,26.339974880218506,1.348281019896865,1739137684.6343436,26.339974880218506,1.0374026543258323 +1739137684.655649,26.35997486114502,50.697981345216164,1739137684.6556516,26.35997486114502,4.497458437621557,1739137684.6556544,26.35997486114502,54.45561369994337,1739137684.655657,26.35997486114502,48.93929773057915,1739137684.6556585,26.35997486114502,8.382638351032819,1739137684.6556604,26.35997486114502,1.9958639689338362,1739137684.6556618,26.35997486114502,2.4778582533168114,1739137684.655663,26.35997486114502,0.6108,1739137684.6556642,26.35997486114502,0.9278802741417207,1739137684.6556659,26.35997486114502,0.0,1739137684.6556673,26.35997486114502,-0.09864351285331155,1739137684.655669,26.35997486114502,1.3758862340977798,1739137684.6556702,26.35997486114502,1.0267666254253889 +1739137684.6741724,26.379974842071533,50.697981345216164,1739137684.6741745,26.379974842071533,4.497458437621557,1739137684.6741772,26.379974842071533,54.45561369994337,1739137684.6741798,26.379974842071533,48.93929773057915,1739137684.6741812,26.379974842071533,8.382638351032819,1739137684.6741827,26.379974842071533,1.9958639689338362,1739137684.6741838,26.379974842071533,2.4778582533168114,1739137684.6741855,26.379974842071533,0.6108,1739137684.6741865,26.379974842071533,0.9278802741417207,1739137684.6741881,26.379974842071533,0.0,1739137684.674189,26.379974842071533,-0.09888635128366818,1739137684.6741905,26.379974842071533,1.3758862340977798,1739137684.674192,26.379974842071533,1.0267666254253889 +1739137684.6941109,26.399974822998047,50.697981345216164,1739137684.6941133,26.399974822998047,4.497458437621557,1739137684.694116,26.399974822998047,54.45561369994337,1739137684.6941187,26.399974822998047,48.93929773057915,1739137684.69412,26.399974822998047,8.382638351032819,1739137684.6941214,26.399974822998047,1.9958639689338362,1739137684.6941228,26.399974822998047,2.4778582533168114,1739137684.694124,26.399974822998047,0.6108,1739137684.6941254,26.399974822998047,0.9278802741417207,1739137684.6941268,26.399974822998047,0.0,1739137684.6941278,26.399974822998047,-0.09888635128366818,1739137684.6941295,26.399974822998047,1.3758862340977798,1739137684.6941307,26.399974822998047,1.0267666254253889 +1739137684.7141333,26.41997480392456,50.697981345216164,1739137684.7141356,26.41997480392456,4.497458437621557,1739137684.7141383,26.41997480392456,54.45561369994337,1739137684.714141,26.41997480392456,48.93929773057915,1739137684.7141423,26.41997480392456,8.382638351032819,1739137684.714144,26.41997480392456,1.9958639689338362,1739137684.7141454,26.41997480392456,2.4778582533168114,1739137684.7141469,26.41997480392456,0.6108,1739137684.7141478,26.41997480392456,0.9278802741417207,1739137684.7141495,26.41997480392456,0.0,1739137684.7141507,26.41997480392456,-0.09888635128366818,1739137684.7141519,26.41997480392456,1.3758862340977798,1739137684.7141533,26.41997480392456,1.0267666254253889 +1739137684.7342017,26.439974784851074,50.697981345216164,1739137684.7342038,26.439974784851074,4.497458437621557,1739137684.7342064,26.439974784851074,54.45561369994337,1739137684.734209,26.439974784851074,48.93929773057915,1739137684.7342105,26.439974784851074,8.382638351032819,1739137684.7342122,26.439974784851074,1.9958639689338362,1739137684.7342134,26.439974784851074,2.4778582533168114,1739137684.7342145,26.439974784851074,0.6108,1739137684.734216,26.439974784851074,0.9278802741417207,1739137684.7342174,26.439974784851074,0.0,1739137684.7342186,26.439974784851074,-0.09888635128366818,1739137684.7342198,26.439974784851074,1.3758862340977798,1739137684.734221,26.439974784851074,1.0267666254253889 +1739137684.7541664,26.459974765777588,50.718367965779514,1739137684.7541683,26.459974765777588,4.6079933189960425,1739137684.7541711,26.459974765777588,54.61626284924845,1739137684.7541738,26.459974765777588,48.81780403210549,1739137684.754175,26.459974765777588,8.423438689565716,1739137684.7541766,26.459974765777588,2.032941804909973,1739137684.7541778,26.459974765777588,2.50939547457422,1739137684.754179,26.459974765777588,0.6108,1739137684.7541804,26.459974765777588,0.9162486877712765,1739137684.7541816,26.459974765777588,0.0,1739137684.7541828,26.459974765777588,-0.10042196037487078,1739137684.7541845,26.459974765777588,1.4034914482986944,1739137684.7541857,26.459974765777588,1.0159394053564774 +1739137684.7741442,26.4799747467041,50.718367965779514,1739137684.7741463,26.4799747467041,4.6079933189960425,1739137684.7741492,26.4799747467041,54.61626284924845,1739137684.774152,26.4799747467041,48.81780403210549,1739137684.7741532,26.4799747467041,8.423438689565716,1739137684.7741547,26.4799747467041,2.032941804909973,1739137684.7741563,26.4799747467041,2.50939547457422,1739137684.7741575,26.4799747467041,0.6108,1739137684.7741585,26.4799747467041,0.9162486877712765,1739137684.7741601,26.4799747467041,0.0,1739137684.7741613,26.4799747467041,-0.09969071758520087,1739137684.774163,26.4799747467041,1.4034914482986944,1739137684.7741642,26.4799747467041,1.0159394053564774 +1739137684.7941685,26.499974727630615,50.718367965779514,1739137684.7941706,26.499974727630615,4.6079933189960425,1739137684.7941737,26.499974727630615,54.61626284924845,1739137684.7941766,26.499974727630615,48.81780403210549,1739137684.7941778,26.499974727630615,8.423438689565716,1739137684.7941794,26.499974727630615,2.032941804909973,1739137684.7941809,26.499974727630615,2.50939547457422,1739137684.794182,26.499974727630615,0.6108,1739137684.7941835,26.499974727630615,0.9162486877712765,1739137684.794185,26.499974727630615,0.0,1739137684.7941864,26.499974727630615,-0.09969071758520087,1739137684.7941875,26.499974727630615,1.4034914482986944,1739137684.7941892,26.499974727630615,1.0159394053564774 +1739137684.8142447,26.51997470855713,50.718367965779514,1739137684.814247,26.51997470855713,4.6079933189960425,1739137684.8142495,26.51997470855713,54.61626284924845,1739137684.8142517,26.51997470855713,48.81780403210549,1739137684.814253,26.51997470855713,8.423438689565716,1739137684.8142545,26.51997470855713,2.032941804909973,1739137684.8142562,26.51997470855713,2.50939547457422,1739137684.8142574,26.51997470855713,0.6108,1739137684.8142583,26.51997470855713,0.9162486877712765,1739137684.8142602,26.51997470855713,0.0,1739137684.8142614,26.51997470855713,-0.09969071758520087,1739137684.8142629,26.51997470855713,1.4034914482986944,1739137684.814264,26.51997470855713,1.0159394053564774 +1739137684.8341758,26.539974689483643,50.718367965779514,1739137684.834178,26.539974689483643,4.6079933189960425,1739137684.8341813,26.539974689483643,54.61626284924845,1739137684.834184,26.539974689483643,48.81780403210549,1739137684.8341851,26.539974689483643,8.423438689565716,1739137684.8341868,26.539974689483643,2.032941804909973,1739137684.834188,26.539974689483643,2.50939547457422,1739137684.8341894,26.539974689483643,0.6108,1739137684.8341906,26.539974689483643,0.9162486877712765,1739137684.834192,26.539974689483643,0.0,1739137684.8341932,26.539974689483643,-0.09969071758520087,1739137684.8341947,26.539974689483643,1.4034914482986944,1739137684.8341959,26.539974689483643,1.0159394053564774 +1739137684.8541558,26.559974670410156,50.718367965779514,1739137684.8541582,26.559974670410156,4.6079933189960425,1739137684.8541608,26.559974670410156,54.61626284924845,1739137684.8541634,26.559974670410156,48.81780403210549,1739137684.854165,26.559974670410156,8.423438689565716,1739137684.8541665,26.559974670410156,2.032941804909973,1739137684.8541682,26.559974670410156,2.50939547457422,1739137684.8541694,26.559974670410156,0.6108,1739137684.8541706,26.559974670410156,0.9162486877712765,1739137684.854172,26.559974670410156,0.0,1739137684.8541732,26.559974670410156,-0.09969071758520087,1739137684.8541746,26.559974670410156,1.4034914482986944,1739137684.854176,26.559974670410156,1.0159394053564774 +1739137684.8743427,26.57997465133667,50.73551125438063,1739137684.8743453,26.57997465133667,4.717865232728295,1739137684.8743484,26.57997465133667,54.7772165034654,1739137684.874351,26.57997465133667,48.69540018552399,1739137684.8743527,26.57997465133667,8.461279944342804,1739137684.8743544,26.57997465133667,2.0697823754975997,1739137684.8743563,26.57997465133667,2.541490467522438,1739137684.8743575,26.57997465133667,0.6108,1739137684.874359,26.57997465133667,0.9045610730080955,1739137684.8743603,26.57997465133667,0.0,1739137684.8743615,26.57997465133667,-0.10111403083307435,1739137684.8743632,26.57997465133667,1.431096662499609,1739137684.8743646,26.57997465133667,1.0049973352893218 +1739137684.894241,26.599974632263184,50.73551125438063,1739137684.8942435,26.599974632263184,4.717865232728295,1739137684.8942463,26.599974632263184,54.7772165034654,1739137684.8942494,26.599974632263184,48.69540018552399,1739137684.894251,26.599974632263184,8.461279944342804,1739137684.8942528,26.599974632263184,2.0697823754975997,1739137684.8942544,26.599974632263184,2.541490467522438,1739137684.8942559,26.599974632263184,0.6108,1739137684.8942568,26.599974632263184,0.9045610730080955,1739137684.8942587,26.599974632263184,0.0,1739137684.89426,26.599974632263184,-0.10043626228122626,1739137684.8942616,26.599974632263184,1.431096662499609,1739137684.8942628,26.599974632263184,1.0049973352893218 +1739137684.914318,26.619974613189697,50.73551125438063,1739137684.9143207,26.619974613189697,4.717865232728295,1739137684.9143238,26.619974613189697,54.7772165034654,1739137684.9143264,26.619974613189697,48.69540018552399,1739137684.914328,26.619974613189697,8.461279944342804,1739137684.9143298,26.619974613189697,2.0697823754975997,1739137684.9143314,26.619974613189697,2.541490467522438,1739137684.9143326,26.619974613189697,0.6108,1739137684.914334,26.619974613189697,0.9045610730080955,1739137684.9143355,26.619974613189697,0.0,1739137684.914337,26.619974613189697,-0.10043626228122626,1739137684.9143388,26.619974613189697,1.431096662499609,1739137684.91434,26.619974613189697,1.0049973352893218 +1739137684.9342775,26.63997459411621,50.73551125438063,1739137684.9342802,26.63997459411621,4.717865232728295,1739137684.9342833,26.63997459411621,54.7772165034654,1739137684.934286,26.63997459411621,48.69540018552399,1739137684.9342875,26.63997459411621,8.461279944342804,1739137684.9342895,26.63997459411621,2.0697823754975997,1739137684.9342911,26.63997459411621,2.541490467522438,1739137684.9342926,26.63997459411621,0.6108,1739137684.9342937,26.63997459411621,0.9045610730080955,1739137684.9342952,26.63997459411621,0.0,1739137684.9342966,26.63997459411621,-0.10043626228122626,1739137684.934298,26.63997459411621,1.431096662499609,1739137684.9342995,26.63997459411621,1.0049973352893218 +1739137684.9543362,26.659974575042725,50.73551125438063,1739137684.9543388,26.659974575042725,4.717865232728295,1739137684.954342,26.659974575042725,54.7772165034654,1739137684.9543445,26.659974575042725,48.69540018552399,1739137684.954346,26.659974575042725,8.461279944342804,1739137684.9543478,26.659974575042725,2.0697823754975997,1739137684.954349,26.659974575042725,2.541490467522438,1739137684.9543507,26.659974575042725,0.6108,1739137684.954352,26.659974575042725,0.9045610730080955,1739137684.9543533,26.659974575042725,0.0,1739137684.9543548,26.659974575042725,-0.10043626228122626,1739137684.9543562,26.659974575042725,1.431096662499609,1739137684.9543579,26.659974575042725,1.0049973352893218 +1739137684.9745333,26.67997455596924,50.74946245374451,1739137684.9745362,26.67997455596924,4.826972262133442,1739137684.9745393,26.67997455596924,54.86034809563574,1739137684.9745424,26.67997455596924,48.64725094849894,1739137684.9745438,26.67997455596924,8.475152852306552,1739137684.9745457,26.67997455596924,2.093558691632779,1739137684.9745471,26.67997455596924,2.497102944303978,1739137684.9745488,26.67997455596924,0.6108,1739137684.9745502,26.67997455596924,0.920764987915106,1739137684.9745522,26.67997455596924,0.0,1739137684.9745533,26.67997455596924,-0.04848654699561661,1739137684.9745553,26.67997455596924,1.4587018767005238,1739137684.9745564,26.67997455596924,0.9939895069282345 +1739137685.001506,26.699974536895752,50.74946245374451,1739137685.0015147,26.699974536895752,4.826972262133442,1739137685.001525,26.699974536895752,54.86034809563574,1739137685.0015347,26.699974536895752,48.64725094849894,1739137685.0015392,26.699974536895752,8.475152852306552,1739137685.0015457,26.699974536895752,2.093558691632779,1739137685.001551,26.699974536895752,2.497102944303978,1739137685.0015554,26.699974536895752,0.6108,1739137685.0015602,26.699974536895752,0.920764987915106,1739137685.001566,26.699974536895752,0.0,1739137685.0015705,26.699974536895752,-0.07322451901312854,1739137685.0015757,26.699974536895752,1.4587018767005238,1739137685.0015802,26.699974536895752,0.9939895069282345 +1739137685.0205781,26.719974517822266,50.74946245374451,1739137685.0205872,26.719974517822266,4.826972262133442,1739137685.0205975,26.719974517822266,54.86034809563574,1739137685.0206072,26.719974517822266,48.64725094849894,1739137685.0206118,26.719974517822266,8.475152852306552,1739137685.0206177,26.719974517822266,2.093558691632779,1739137685.0206227,26.719974517822266,2.497102944303978,1739137685.0206275,26.719974517822266,0.6108,1739137685.020632,26.719974517822266,0.920764987915106,1739137685.0206378,26.719974517822266,0.0,1739137685.0206423,26.719974517822266,-0.07322451901312854,1739137685.0206478,26.719974517822266,1.4587018767005238,1739137685.0206523,26.719974517822266,0.9939895069282345 +1739137685.0473926,26.749974489212036,50.74946245374451,1739137685.0474014,26.749974489212036,4.826972262133442,1739137685.0474114,26.749974489212036,54.86034809563574,1739137685.0474212,26.749974489212036,48.64725094849894,1739137685.0474265,26.749974489212036,8.475152852306552,1739137685.0474331,26.749974489212036,2.093558691632779,1739137685.0474386,26.749974489212036,2.497102944303978,1739137685.0474434,26.749974489212036,0.6108,1739137685.0474482,26.749974489212036,0.920764987915106,1739137685.0474532,26.749974489212036,0.0,1739137685.0474577,26.749974489212036,-0.07322451901312854,1739137685.047463,26.749974489212036,1.4587018767005238,1739137685.0474675,26.749974489212036,0.9939895069282345 +1739137685.069746,26.76997447013855,50.74946245374451,1739137685.0697505,26.76997447013855,4.826972262133442,1739137685.0697563,26.76997447013855,54.86034809563574,1739137685.0697615,26.76997447013855,48.64725094849894,1739137685.069764,26.76997447013855,8.475152852306552,1739137685.0697672,26.76997447013855,2.093558691632779,1739137685.0697696,26.76997447013855,2.497102944303978,1739137685.0697722,26.76997447013855,0.6108,1739137685.0697749,26.76997447013855,0.920764987915106,1739137685.0697777,26.76997447013855,0.0,1739137685.06978,26.76997447013855,-0.07322451901312854,1739137685.069783,26.76997447013855,1.4587018767005238,1739137685.0697856,26.76997447013855,0.9939895069282345 +1739137685.0900004,26.79997444152832,50.76029698227533,1739137685.0900035,26.79997444152832,4.935432579716261,1739137685.0900068,26.79997444152832,54.96551200282525,1739137685.09001,26.79997444152832,48.567047801052325,1739137685.0900114,26.79997444152832,8.49763685471061,1739137685.0900135,26.79997444152832,2.122680034340535,1739137685.090015,26.79997444152832,2.4860356298603414,1739137685.0900166,26.79997444152832,0.6108,1739137685.0900183,26.79997444152832,0.9248501819287389,1739137685.0900202,26.79997444152832,0.0,1739137685.0900216,26.79997444152832,-0.05150986515950852,1739137685.0900235,26.79997444152832,1.4863070909014384,1739137685.090025,26.79997444152832,0.986700363612554 +1739137685.1089137,26.819974422454834,50.76029698227533,1739137685.1089165,26.819974422454834,4.935432579716261,1739137685.1089196,26.819974422454834,54.96551200282525,1739137685.1089227,26.819974422454834,48.567047801052325,1739137685.108924,26.819974422454834,8.49763685471061,1739137685.1089256,26.819974422454834,2.122680034340535,1739137685.108927,26.819974422454834,2.4860356298603414,1739137685.1089284,26.819974422454834,0.6108,1739137685.1089299,26.819974422454834,0.9248501819287389,1739137685.1089313,26.819974422454834,0.0,1739137685.1089325,26.819974422454834,-0.061850181683815064,1739137685.1089344,26.819974422454834,1.4863070909014384,1739137685.1089356,26.819974422454834,0.986700363612554 +1739137685.1282606,26.839974403381348,50.76029698227533,1739137685.128263,26.839974403381348,4.935432579716261,1739137685.1282656,26.839974403381348,54.96551200282525,1739137685.1282682,26.839974403381348,48.567047801052325,1739137685.1282697,26.839974403381348,8.49763685471061,1739137685.128271,26.839974403381348,2.122680034340535,1739137685.1282723,26.839974403381348,2.4860356298603414,1739137685.1282737,26.839974403381348,0.6108,1739137685.1282747,26.839974403381348,0.9248501819287389,1739137685.128276,26.839974403381348,0.0,1739137685.1282775,26.839974403381348,-0.061850181683815064,1739137685.1282787,26.839974403381348,1.4863070909014384,1739137685.1282802,26.839974403381348,0.986700363612554 +1739137685.148046,26.85997438430786,50.76029698227533,1739137685.1480484,26.85997438430786,4.935432579716261,1739137685.148051,26.85997438430786,54.96551200282525,1739137685.1480534,26.85997438430786,48.567047801052325,1739137685.1480548,26.85997438430786,8.49763685471061,1739137685.1480563,26.85997438430786,2.122680034340535,1739137685.1480575,26.85997438430786,2.4860356298603414,1739137685.1480587,26.85997438430786,0.6108,1739137685.1480598,26.85997438430786,0.9248501819287389,1739137685.1480613,26.85997438430786,0.0,1739137685.1480625,26.85997438430786,-0.061850181683815064,1739137685.1480637,26.85997438430786,1.4863070909014384,1739137685.148065,26.85997438430786,0.986700363612554 +1739137685.1680448,26.879974365234375,50.76029698227533,1739137685.1680477,26.879974365234375,4.935432579716261,1739137685.1680503,26.879974365234375,54.96551200282525,1739137685.1680527,26.879974365234375,48.567047801052325,1739137685.168054,26.879974365234375,8.49763685471061,1739137685.1680553,26.879974365234375,2.122680034340535,1739137685.1680565,26.879974365234375,2.4860356298603414,1739137685.168058,26.879974365234375,0.6108,1739137685.168059,26.879974365234375,0.9248501819287389,1739137685.1680603,26.879974365234375,0.0,1739137685.1680617,26.879974365234375,-0.061850181683815064,1739137685.168063,26.879974365234375,1.4863070909014384,1739137685.168064,26.879974365234375,0.986700363612554 +1739137685.1883295,26.89997434616089,50.768076049603806,1739137685.1883318,26.89997434616089,5.0433534487965925,1739137685.1883347,26.89997434616089,55.17868316661841,1739137685.1883373,26.89997434616089,48.379677593763724,1739137685.188339,26.89997434616089,8.544376973737982,1739137685.1883404,26.89997434616089,2.1694758631278632,1739137685.1883419,26.89997434616089,2.5835802304318705,1739137685.188343,26.89997434616089,0.6108,1739137685.1883442,26.89997434616089,0.889459450022635,1739137685.188346,26.89997434616089,0.0,1739137685.188347,26.89997434616089,-0.11665744633824912,1739137685.1883488,26.89997434616089,1.513912305102353,1739137685.1883497,26.89997434616089,0.9800181858689456 +1739137685.2082014,26.919974327087402,50.768076049603806,1739137685.2082036,26.919974327087402,5.0433534487965925,1739137685.2082064,26.919974327087402,55.17868316661841,1739137685.2082086,26.919974327087402,48.379677593763724,1739137685.20821,26.919974327087402,8.544376973737982,1739137685.2082117,26.919974327087402,2.1694758631278632,1739137685.208213,26.919974327087402,2.5835802304318705,1739137685.2082143,26.919974327087402,0.6108,1739137685.2082152,26.919974327087402,0.889459450022635,1739137685.208217,26.919974327087402,0.0,1739137685.208218,26.919974327087402,-0.09055873584631058,1739137685.2082193,26.919974327087402,1.513912305102353,1739137685.2082207,26.919974327087402,0.9800181858689456 +1739137685.2280788,26.939974308013916,50.768076049603806,1739137685.228082,26.939974308013916,5.0433534487965925,1739137685.2280853,26.939974308013916,55.17868316661841,1739137685.2280881,26.939974308013916,48.379677593763724,1739137685.2280896,26.939974308013916,8.544376973737982,1739137685.228092,26.939974308013916,2.1694758631278632,1739137685.2280936,26.939974308013916,2.5835802304318705,1739137685.2280953,26.939974308013916,0.6108,1739137685.228097,26.939974308013916,0.889459450022635,1739137685.2280986,26.939974308013916,0.0,1739137685.2281,26.939974308013916,-0.09055873584631058,1739137685.2281022,26.939974308013916,1.513912305102353,1739137685.2281036,26.939974308013916,0.9800181858689456 +1739137685.2480865,26.95997428894043,50.768076049603806,1739137685.2480893,26.95997428894043,5.0433534487965925,1739137685.2480927,26.95997428894043,55.17868316661841,1739137685.248095,26.95997428894043,48.379677593763724,1739137685.2480965,26.95997428894043,8.544376973737982,1739137685.2480981,26.95997428894043,2.1694758631278632,1739137685.2480993,26.95997428894043,2.5835802304318705,1739137685.2481008,26.95997428894043,0.6108,1739137685.248102,26.95997428894043,0.889459450022635,1739137685.2481034,26.95997428894043,0.0,1739137685.2481048,26.95997428894043,-0.09055873584631058,1739137685.2481062,26.95997428894043,1.513912305102353,1739137685.2481074,26.95997428894043,0.9800181858689456 +1739137685.268094,26.979974269866943,50.768076049603806,1739137685.2680964,26.979974269866943,5.0433534487965925,1739137685.2680998,26.979974269866943,55.17868316661841,1739137685.2681024,26.979974269866943,48.379677593763724,1739137685.2681038,26.979974269866943,8.544376973737982,1739137685.2681057,26.979974269866943,2.1694758631278632,1739137685.2681074,26.979974269866943,2.5835802304318705,1739137685.2681088,26.979974269866943,0.6108,1739137685.26811,26.979974269866943,0.889459450022635,1739137685.2681117,26.979974269866943,0.0,1739137685.268113,26.979974269866943,-0.09055873584631058,1739137685.2681143,26.979974269866943,1.513912305102353,1739137685.2681162,26.979974269866943,0.9800181858689456 +1739137685.288081,26.999974250793457,50.768076049603806,1739137685.2880836,26.999974250793457,5.0433534487965925,1739137685.2880862,26.999974250793457,55.17868316661841,1739137685.288089,26.999974250793457,48.379677593763724,1739137685.2880905,26.999974250793457,8.544376973737982,1739137685.2880924,26.999974250793457,2.1694758631278632,1739137685.2880938,26.999974250793457,2.5835802304318705,1739137685.288095,26.999974250793457,0.6108,1739137685.2880962,26.999974250793457,0.889459450022635,1739137685.2880983,26.999974250793457,0.0,1739137685.2880998,26.999974250793457,-0.09055873584631058,1739137685.2881014,26.999974250793457,1.513912305102353,1739137685.2881026,26.999974250793457,0.9800181858689456 +1739137685.3081508,27.01997423171997,50.77283222448061,1739137685.308153,27.01997423171997,5.150500085625293,1739137685.3081555,27.01997423171997,55.24828864184797,1739137685.3081582,27.01997423171997,48.342212553869814,1739137685.3081596,27.01997423171997,8.552157489226035,1739137685.308161,27.01997423171997,2.1912140520841707,1739137685.3081622,27.01997423171997,2.5291601654778,1739137685.3081636,27.01997423171997,0.6108,1739137685.3081648,27.01997423171997,0.9090334977105129,1739137685.308166,27.01997423171997,0.0,1739137685.3081675,27.01997423171997,-0.03324878447120698,1739137685.3081686,27.01997423171997,1.5415175193032677,1739137685.30817,27.01997423171997,0.9695727488502639 +1739137685.3281095,27.039974212646484,50.77283222448061,1739137685.3281128,27.039974212646484,5.150500085625293,1739137685.328116,27.039974212646484,55.24828864184797,1739137685.3281188,27.039974212646484,48.342212553869814,1739137685.32812,27.039974212646484,8.552157489226035,1739137685.3281221,27.039974212646484,2.1912140520841707,1739137685.3281236,27.039974212646484,2.5291601654778,1739137685.328125,27.039974212646484,0.6108,1739137685.3281262,27.039974212646484,0.9090334977105129,1739137685.3281279,27.039974212646484,0.0,1739137685.3281293,27.039974212646484,-0.060539251139751005,1739137685.3281307,27.039974212646484,1.5415175193032677,1739137685.3281324,27.039974212646484,0.9695727488502639 +1739137685.3527112,27.059974193572998,50.77283222448061,1739137685.35272,27.059974193572998,5.150500085625293,1739137685.3527303,27.059974193572998,55.24828864184797,1739137685.35274,27.059974193572998,48.342212553869814,1739137685.352745,27.059974193572998,8.552157489226035,1739137685.352751,27.059974193572998,2.1912140520841707,1739137685.3527558,27.059974193572998,2.5291601654778,1739137685.3527603,27.059974193572998,0.6108,1739137685.352765,27.059974193572998,0.9090334977105129,1739137685.3527706,27.059974193572998,0.0,1739137685.3527753,27.059974193572998,-0.060539251139751005,1739137685.3527808,27.059974193572998,1.5415175193032677,1739137685.3527853,27.059974193572998,0.9695727488502639 +1739137685.3764086,27.069974184036255,50.77283222448061,1739137685.3764162,27.069974184036255,5.150500085625293,1739137685.3764238,27.069974184036255,55.24828864184797,1739137685.3764307,27.069974184036255,48.342212553869814,1739137685.3764343,27.069974184036255,8.552157489226035,1739137685.3764389,27.069974184036255,2.1912140520841707,1739137685.3764424,27.069974184036255,2.5291601654778,1739137685.376446,27.069974184036255,0.6108,1739137685.3764493,27.069974184036255,0.9090334977105129,1739137685.3764536,27.069974184036255,0.0,1739137685.3764572,27.069974184036255,-0.060539251139751005,1739137685.376461,27.069974184036255,1.5415175193032677,1739137685.3764648,27.069974184036255,0.9695727488502639 +1739137685.3935153,27.099974155426025,50.77283222448061,1739137685.3935192,27.099974155426025,5.150500085625293,1739137685.3935232,27.099974155426025,55.24828864184797,1739137685.3935273,27.099974155426025,48.342212553869814,1739137685.3935294,27.099974155426025,8.552157489226035,1739137685.3935318,27.099974155426025,2.1912140520841707,1739137685.3935342,27.099974155426025,2.5291601654778,1739137685.393536,27.099974155426025,0.6108,1739137685.393538,27.099974155426025,0.9090334977105129,1739137685.3935406,27.099974155426025,0.0,1739137685.3935428,27.099974155426025,-0.060539251139751005,1739137685.393545,27.099974155426025,1.5415175193032677,1739137685.393547,27.099974155426025,0.9695727488502639 +1739137685.4144228,27.11997413635254,50.77461278034805,1739137685.4144263,27.11997413635254,5.256819627645475,1739137685.4144306,27.11997413635254,55.42065765519113,1739137685.4144351,27.11997413635254,48.19166035039588,1739137685.414437,27.11997413635254,8.580556608267354,1739137685.4144397,27.11997413635254,2.231431384812351,1739137685.414442,27.11997413635254,2.588511393952703,1739137685.414444,27.11997413635254,0.6108,1739137685.4144459,27.11997413635254,0.8877067511625438,1739137685.4144487,27.11997413635254,0.0,1739137685.4144506,27.11997413635254,-0.08906521054774813,1739137685.414453,27.11997413635254,1.5691227335041824,1739137685.414455,27.11997413635254,0.9631881647303075 +1739137685.4325895,27.139974117279053,50.77461278034805,1739137685.4325922,27.139974117279053,5.256819627645475,1739137685.4325953,27.139974117279053,55.42065765519113,1739137685.4325984,27.139974117279053,48.19166035039588,1739137685.4325998,27.139974117279053,8.580556608267354,1739137685.432602,27.139974117279053,2.231431384812351,1739137685.4326031,27.139974117279053,2.588511393952703,1739137685.4326048,27.139974117279053,0.6108,1739137685.4326062,27.139974117279053,0.8877067511625438,1739137685.4326084,27.139974117279053,0.0,1739137685.4326096,27.139974117279053,-0.07548141356776372,1739137685.4326112,27.139974117279053,1.5691227335041824,1739137685.4326127,27.139974117279053,0.9631881647303075 +1739137685.4520504,27.159974098205566,50.77461278034805,1739137685.4520535,27.159974098205566,5.256819627645475,1739137685.452058,27.159974098205566,55.42065765519113,1739137685.4520617,27.159974098205566,48.19166035039588,1739137685.4520633,27.159974098205566,8.580556608267354,1739137685.452065,27.159974098205566,2.231431384812351,1739137685.4520667,27.159974098205566,2.588511393952703,1739137685.4520679,27.159974098205566,0.6108,1739137685.4520693,27.159974098205566,0.8877067511625438,1739137685.452071,27.159974098205566,0.0,1739137685.4520721,27.159974098205566,-0.07548141356776372,1739137685.4520738,27.159974098205566,1.5691227335041824,1739137685.452075,27.159974098205566,0.9631881647303075 +1739137685.4726834,27.17997407913208,50.77461278034805,1739137685.4726858,27.17997407913208,5.256819627645475,1739137685.4726887,27.17997407913208,55.42065765519113,1739137685.4726915,27.17997407913208,48.19166035039588,1739137685.472693,27.17997407913208,8.580556608267354,1739137685.4726949,27.17997407913208,2.231431384812351,1739137685.4727125,27.17997407913208,2.588511393952703,1739137685.4727137,27.17997407913208,0.6108,1739137685.4727147,27.17997407913208,0.8877067511625438,1739137685.4727163,27.17997407913208,0.0,1739137685.4727175,27.17997407913208,-0.07548141356776372,1739137685.4727192,27.17997407913208,1.5691227335041824,1739137685.4727204,27.17997407913208,0.9631881647303075 +1739137685.4930813,27.199974060058594,50.77461278034805,1739137685.493084,27.199974060058594,5.256819627645475,1739137685.4930866,27.199974060058594,55.42065765519113,1739137685.493089,27.199974060058594,48.19166035039588,1739137685.4930906,27.199974060058594,8.580556608267354,1739137685.4930918,27.199974060058594,2.231431384812351,1739137685.4930935,27.199974060058594,2.588511393952703,1739137685.493095,27.199974060058594,0.6108,1739137685.493096,27.199974060058594,0.8877067511625438,1739137685.4930975,27.199974060058594,0.0,1739137685.4930987,27.199974060058594,-0.07548141356776372,1739137685.4931004,27.199974060058594,1.5691227335041824,1739137685.4931018,27.199974060058594,0.9631881647303075 +1739137685.511991,27.219974040985107,50.77461278034805,1739137685.5119932,27.219974040985107,5.256819627645475,1739137685.5119958,27.219974040985107,55.42065765519113,1739137685.5119987,27.219974040985107,48.19166035039588,1739137685.512,27.219974040985107,8.580556608267354,1739137685.5120015,27.219974040985107,2.231431384812351,1739137685.5120032,27.219974040985107,2.588511393952703,1739137685.5120044,27.219974040985107,0.6108,1739137685.5120053,27.219974040985107,0.8877067511625438,1739137685.512007,27.219974040985107,0.0,1739137685.5120082,27.219974040985107,-0.07548141356776372,1739137685.5120096,27.219974040985107,1.5691227335041824,1739137685.512011,27.219974040985107,0.9631881647303075 +1739137685.5318727,27.23997402191162,50.773467615854464,1739137685.5318754,27.23997402191162,5.362320768245528,1739137685.5318782,27.23997402191162,55.56329867975735,1739137685.5318809,27.23997402191162,48.076038558064845,1739137685.5318823,27.23997402191162,8.598503076008015,1739137685.531884,27.23997402191162,2.2656459201958987,1739137685.5318854,27.23997402191162,2.6126121190655187,1739137685.5318866,27.23997402191162,0.6108,1739137685.5318878,27.23997402191162,0.879190117971216,1739137685.5318894,27.23997402191162,0.0,1739137685.5318906,27.23997402191162,-0.07542882778618012,1739137685.5318923,27.23997402191162,1.596727947705097,1739137685.5318935,27.23997402191162,0.9546439866182783 +1739137685.551724,27.259974002838135,50.773467615854464,1739137685.5517263,27.259974002838135,5.362320768245528,1739137685.551729,27.259974002838135,55.56329867975735,1739137685.5517318,27.259974002838135,48.076038558064845,1739137685.551733,27.259974002838135,8.598503076008015,1739137685.5517344,27.259974002838135,2.2656459201958987,1739137685.5517359,27.259974002838135,2.6126121190655187,1739137685.5517368,27.259974002838135,0.6108,1739137685.551738,27.259974002838135,0.879190117971216,1739137685.5517395,27.259974002838135,0.0,1739137685.5517406,27.259974002838135,-0.07545386864706227,1739137685.5517423,27.259974002838135,1.596727947705097,1739137685.5517435,27.259974002838135,0.9546439866182783 +1739137685.5716672,27.27997398376465,50.773467615854464,1739137685.5716698,27.27997398376465,5.362320768245528,1739137685.5716727,27.27997398376465,55.56329867975735,1739137685.571675,27.27997398376465,48.076038558064845,1739137685.5716767,27.27997398376465,8.598503076008015,1739137685.5716784,27.27997398376465,2.2656459201958987,1739137685.57168,27.27997398376465,2.6126121190655187,1739137685.5716813,27.27997398376465,0.6108,1739137685.5716825,27.27997398376465,0.879190117971216,1739137685.5716841,27.27997398376465,0.0,1739137685.5716853,27.27997398376465,-0.07545386864706227,1739137685.571687,27.27997398376465,1.596727947705097,1739137685.571688,27.27997398376465,0.9546439866182783 +1739137685.5916805,27.299973964691162,50.773467615854464,1739137685.591683,27.299973964691162,5.362320768245528,1739137685.5916855,27.299973964691162,55.56329867975735,1739137685.5916884,27.299973964691162,48.076038558064845,1739137685.5916898,27.299973964691162,8.598503076008015,1739137685.5916915,27.299973964691162,2.2656459201958987,1739137685.5916927,27.299973964691162,2.6126121190655187,1739137685.591694,27.299973964691162,0.6108,1739137685.5916953,27.299973964691162,0.879190117971216,1739137685.591697,27.299973964691162,0.0,1739137685.5916982,27.299973964691162,-0.07545386864706227,1739137685.5916996,27.299973964691162,1.596727947705097,1739137685.591701,27.299973964691162,0.9546439866182783 +1739137685.6116977,27.319973945617676,50.773467615854464,1739137685.6117003,27.319973945617676,5.362320768245528,1739137685.6117032,27.319973945617676,55.56329867975735,1739137685.6117058,27.319973945617676,48.076038558064845,1739137685.6117074,27.319973945617676,8.598503076008015,1739137685.6117089,27.319973945617676,2.2656459201958987,1739137685.6117103,27.319973945617676,2.6126121190655187,1739137685.6117115,27.319973945617676,0.6108,1739137685.6117127,27.319973945617676,0.879190117971216,1739137685.6117144,27.319973945617676,0.0,1739137685.6117156,27.319973945617676,-0.07545386864706227,1739137685.6117172,27.319973945617676,1.596727947705097,1739137685.6117184,27.319973945617676,0.9546439866182783 +1739137685.631887,27.33997392654419,50.7694459634849,1739137685.631889,27.33997392654419,5.466837434492836,1739137685.6318922,27.33997392654419,55.66038907499292,1739137685.631895,27.33997392654419,48.00437690528746,1739137685.6318965,27.33997392654419,8.60800285119908,1739137685.6318984,27.33997392654419,2.2926024921557286,1739137685.6318998,27.33997392654419,2.5930196613732406,1739137685.6319013,27.33997392654419,0.6108,1739137685.6319025,27.33997392654419,0.8861073858991197,1739137685.631904,27.33997392654419,0.0,1739137685.6319056,27.33997392654419,-0.0464690695131281,1739137685.6319072,27.33997392654419,1.6243331619060117,1739137685.6319087,27.33997392654419,0.9463787476089692 +1739137685.6518226,27.359973907470703,50.7694459634849,1739137685.6518252,27.359973907470703,5.466837434492836,1739137685.6518285,27.359973907470703,55.66038907499292,1739137685.6518314,27.359973907470703,48.00437690528746,1739137685.6518328,27.359973907470703,8.60800285119908,1739137685.6518347,27.359973907470703,2.2926024921557286,1739137685.6518362,27.359973907470703,2.5930196613732406,1739137685.6518373,27.359973907470703,0.6108,1739137685.651839,27.359973907470703,0.8861073858991197,1739137685.6518404,27.359973907470703,0.0,1739137685.6518419,27.359973907470703,-0.06027136170984948,1739137685.6518435,27.359973907470703,1.6243331619060117,1739137685.6518452,27.359973907470703,0.9463787476089692 +1739137685.6719162,27.379973888397217,50.7694459634849,1739137685.6719193,27.379973888397217,5.466837434492836,1739137685.6719222,27.379973888397217,55.66038907499292,1739137685.671925,27.379973888397217,48.00437690528746,1739137685.6719263,27.379973888397217,8.60800285119908,1739137685.6719282,27.379973888397217,2.2926024921557286,1739137685.6719296,27.379973888397217,2.5930196613732406,1739137685.671931,27.379973888397217,0.6108,1739137685.6719325,27.379973888397217,0.8861073858991197,1739137685.6719341,27.379973888397217,0.0,1739137685.671936,27.379973888397217,-0.06027136170984948,1739137685.6719375,27.379973888397217,1.6243331619060117,1739137685.6719391,27.379973888397217,0.9463787476089692 +1739137685.6918042,27.39997386932373,50.7694459634849,1739137685.6918068,27.39997386932373,5.466837434492836,1739137685.69181,27.39997386932373,55.66038907499292,1739137685.6918128,27.39997386932373,48.00437690528746,1739137685.6918144,27.39997386932373,8.60800285119908,1739137685.6918159,27.39997386932373,2.2926024921557286,1739137685.6918178,27.39997386932373,2.5930196613732406,1739137685.691819,27.39997386932373,0.6108,1739137685.6918204,27.39997386932373,0.8861073858991197,1739137685.6918218,27.39997386932373,0.0,1739137685.6918232,27.39997386932373,-0.06027136170984948,1739137685.691825,27.39997386932373,1.6243331619060117,1739137685.691826,27.39997386932373,0.9463787476089692 +1739137685.7118623,27.419973850250244,50.7694459634849,1739137685.711865,27.419973850250244,5.466837434492836,1739137685.7118676,27.419973850250244,55.66038907499292,1739137685.7118704,27.419973850250244,48.00437690528746,1739137685.711872,27.419973850250244,8.60800285119908,1739137685.7118738,27.419973850250244,2.2926024921557286,1739137685.7118754,27.419973850250244,2.5930196613732406,1739137685.7118766,27.419973850250244,0.6108,1739137685.711878,27.419973850250244,0.8861073858991197,1739137685.71188,27.419973850250244,0.0,1739137685.7118812,27.419973850250244,-0.06027136170984948,1739137685.7118828,27.419973850250244,1.6243331619060117,1739137685.7118843,27.419973850250244,0.9463787476089692 +1739137685.7317586,27.439973831176758,50.7694459634849,1739137685.731761,27.439973831176758,5.466837434492836,1739137685.7317643,27.439973831176758,55.66038907499292,1739137685.731767,27.439973831176758,48.00437690528746,1739137685.7317686,27.439973831176758,8.60800285119908,1739137685.7317705,27.439973831176758,2.2926024921557286,1739137685.7317722,27.439973831176758,2.5930196613732406,1739137685.7317734,27.439973831176758,0.6108,1739137685.731775,27.439973831176758,0.8861073858991197,1739137685.7317767,27.439973831176758,0.0,1739137685.7317784,27.439973831176758,-0.06027136170984948,1739137685.7317798,27.439973831176758,1.6243331619060117,1739137685.7317815,27.439973831176758,0.9463787476089692 +1739137685.7518604,27.45997381210327,50.76259338849607,1739137685.751863,27.45997381210327,5.57040471335884,1739137685.7518659,27.45997381210327,55.736368263966845,1739137685.751869,27.45997381210327,47.94779466341515,1739137685.7518704,27.45997381210327,8.614723100365795,1739137685.7518723,27.45997381210327,2.3170414294330097,1739137685.7518737,27.45997381210327,2.558786190612786,1739137685.7518752,27.45997381210327,0.6108,1739137685.7518764,27.45997381210327,0.8983246554179252,1739137685.7518783,27.45997381210327,0.0,1739137685.7518795,27.45997381210327,-0.02485754485094685,1739137685.7518811,27.45997381210327,1.6519383761069264,1739137685.7518826,27.45997381210327,0.9400459310068054 +1739137685.7719405,27.479973793029785,50.76259338849607,1739137685.7719429,27.479973793029785,5.57040471335884,1739137685.771946,27.479973793029785,55.736368263966845,1739137685.771949,27.479973793029785,47.94779466341515,1739137685.7719505,27.479973793029785,8.614723100365795,1739137685.7719526,27.479973793029785,2.3170414294330097,1739137685.771954,27.479973793029785,2.558786190612786,1739137685.7719555,27.479973793029785,0.6108,1739137685.771957,27.479973793029785,0.8983246554179252,1739137685.7719586,27.479973793029785,0.0,1739137685.7719598,27.479973793029785,-0.04172127558888028,1739137685.771962,27.479973793029785,1.6519383761069264,1739137685.7719634,27.479973793029785,0.9400459310068054 +1739137685.7961106,27.4999737739563,50.76259338849607,1739137685.7961195,27.4999737739563,5.57040471335884,1739137685.7961297,27.4999737739563,55.736368263966845,1739137685.7961402,27.4999737739563,47.94779466341515,1739137685.7961454,27.4999737739563,8.614723100365795,1739137685.7961514,27.4999737739563,2.3170414294330097,1739137685.7961566,27.4999737739563,2.558786190612786,1739137685.796162,27.4999737739563,0.6108,1739137685.7961662,27.4999737739563,0.8983246554179252,1739137685.7961721,27.4999737739563,0.0,1739137685.7961767,27.4999737739563,-0.04172127558888028,1739137685.796182,27.4999737739563,1.6519383761069264,1739137685.7961867,27.4999737739563,0.9400459310068054 +1739137685.8178313,27.519973754882812,50.76259338849607,1739137685.8178408,27.519973754882812,5.57040471335884,1739137685.8178525,27.519973754882812,55.736368263966845,1739137685.817863,27.519973754882812,47.94779466341515,1739137685.8178682,27.519973754882812,8.614723100365795,1739137685.8178768,27.519973754882812,2.3170414294330097,1739137685.817882,27.519973754882812,2.558786190612786,1739137685.8178875,27.519973754882812,0.6108,1739137685.8178923,27.519973754882812,0.8983246554179252,1739137685.8178985,27.519973754882812,0.0,1739137685.8179042,27.519973754882812,-0.04172127558888028,1739137685.8179102,27.519973754882812,1.6519383761069264,1739137685.8179154,27.519973754882812,0.9400459310068054 +1739137685.835186,27.539973735809326,50.76259338849607,1739137685.835192,27.539973735809326,5.57040471335884,1739137685.835199,27.539973735809326,55.736368263966845,1739137685.8352058,27.539973735809326,47.94779466341515,1739137685.8352094,27.539973735809326,8.614723100365795,1739137685.8352134,27.539973735809326,2.3170414294330097,1739137685.8352165,27.539973735809326,2.558786190612786,1739137685.8352199,27.539973735809326,0.6108,1739137685.8352232,27.539973735809326,0.8983246554179252,1739137685.8352268,27.539973735809326,0.0,1739137685.83523,27.539973735809326,-0.04172127558888028,1739137685.8352342,27.539973735809326,1.6519383761069264,1739137685.8352373,27.539973735809326,0.9400459310068054 +1739137685.8558958,27.55997371673584,50.752941367956645,1739137685.8559,27.55997371673584,5.67313563006347,1739137685.8559048,27.55997371673584,55.737967139840656,1739137685.855909,27.55997371673584,47.95937726616389,1739137685.8559115,27.55997371673584,8.613420057556564,1739137685.8559136,27.55997371673584,2.3306116177317833,1739137685.8559158,27.55997371673584,2.4579440385835736,1739137685.8559182,27.55997371673584,0.6108,1739137685.85592,27.55997371673584,0.9353009932726263,1739137685.8559225,27.55997371673584,0.0,1739137685.8559244,27.55997371673584,0.03730466077285331,1739137685.8559272,27.55997371673584,1.679543590307841,1739137685.8559294,27.55997371673584,0.9356277495658021 +1739137685.8739936,27.579973697662354,50.752941367956645,1739137685.8739972,27.579973697662354,5.67313563006347,1739137685.8740013,27.579973697662354,55.737967139840656,1739137685.8740048,27.579973697662354,47.95937726616389,1739137685.8740063,27.579973697662354,8.613420057556564,1739137685.8740087,27.579973697662354,2.3306116177317833,1739137685.8740103,27.579973697662354,2.4579440385835736,1739137685.8740122,27.579973697662354,0.6108,1739137685.874014,27.579973697662354,0.9353009932726263,1739137685.874016,27.579973697662354,0.0,1739137685.8740175,27.579973697662354,-0.00032675629317580057,1739137685.8740196,27.579973697662354,1.679543590307841,1739137685.8740213,27.579973697662354,0.9356277495658021 +1739137685.8935854,27.599973678588867,50.752941367956645,1739137685.8935885,27.599973678588867,5.67313563006347,1739137685.8935924,27.599973678588867,55.737967139840656,1739137685.893596,27.599973678588867,47.95937726616389,1739137685.8935976,27.599973678588867,8.613420057556564,1739137685.8935997,27.599973678588867,2.3306116177317833,1739137685.8936014,27.599973678588867,2.4579440385835736,1739137685.8936033,27.599973678588867,0.6108,1739137685.8936052,27.599973678588867,0.9353009932726263,1739137685.893607,27.599973678588867,0.0,1739137685.8936088,27.599973678588867,-0.00032675629317580057,1739137685.8936105,27.599973678588867,1.679543590307841,1739137685.8936124,27.599973678588867,0.9356277495658021 +1739137685.9127147,27.61997365951538,50.752941367956645,1739137685.9127178,27.61997365951538,5.67313563006347,1739137685.9127216,27.61997365951538,55.737967139840656,1739137685.9127254,27.61997365951538,47.95937726616389,1739137685.9127276,27.61997365951538,8.613420057556564,1739137685.9127295,27.61997365951538,2.3306116177317833,1739137685.9127314,27.61997365951538,2.4579440385835736,1739137685.912733,27.61997365951538,0.6108,1739137685.912735,27.61997365951538,0.9353009932726263,1739137685.9127371,27.61997365951538,0.0,1739137685.9127388,27.61997365951538,-0.00032675629317580057,1739137685.9127407,27.61997365951538,1.679543590307841,1739137685.9127424,27.61997365951538,0.9356277495658021 +1739137685.93236,27.639973640441895,50.752941367956645,1739137685.9323633,27.639973640441895,5.67313563006347,1739137685.9323668,27.639973640441895,55.737967139840656,1739137685.9323704,27.639973640441895,47.95937726616389,1739137685.9323719,27.639973640441895,8.613420057556564,1739137685.932374,27.639973640441895,2.3306116177317833,1739137685.932376,27.639973640441895,2.4579440385835736,1739137685.9323773,27.639973640441895,0.6108,1739137685.9323785,27.639973640441895,0.9353009932726263,1739137685.9323804,27.639973640441895,0.0,1739137685.932382,27.639973640441895,-0.00032675629317580057,1739137685.932384,27.639973640441895,1.679543590307841,1739137685.9323857,27.639973640441895,0.9356277495658021 +1739137685.9522135,27.659973621368408,50.752941367956645,1739137685.9522169,27.659973621368408,5.67313563006347,1739137685.9522202,27.659973621368408,55.737967139840656,1739137685.9522233,27.659973621368408,47.95937726616389,1739137685.952225,27.659973621368408,8.613420057556564,1739137685.9522274,27.659973621368408,2.3306116177317833,1739137685.9522288,27.659973621368408,2.4579440385835736,1739137685.9522305,27.659973621368408,0.6108,1739137685.952232,27.659973621368408,0.9353009932726263,1739137685.9522338,27.659973621368408,0.0,1739137685.9522352,27.659973621368408,-0.00032675629317580057,1739137685.952237,27.659973621368408,1.679543590307841,1739137685.9522383,27.659973621368408,0.9356277495658021 +1739137685.9728353,27.679973602294922,50.74048024299335,1739137685.9728382,27.679973602294922,5.7753642650763215,1739137685.9728417,27.679973602294922,56.04262550102264,1739137685.9728448,27.679973602294922,47.65355690830571,1739137685.9728463,27.679973602294922,8.636638440494126,1739137685.9728484,27.679973602294922,2.3941120285615556,1739137685.97285,27.679973602294922,2.669337703150642,1739137685.9728515,27.679973602294922,0.6108,1739137685.972853,27.679973602294922,0.8594657107364999,1739137685.9728553,27.679973602294922,0.0,1739137685.9728565,27.679973602294922,-0.14646237076453233,1739137685.9728584,27.679973602294922,1.7071488045087557,1739137685.9728599,27.679973602294922,0.9363396588950718 +1739137685.9927604,27.699973583221436,50.74048024299335,1739137685.9927628,27.699973583221436,5.7753642650763215,1739137685.9927664,27.699973583221436,56.04262550102264,1739137685.9927695,27.699973583221436,47.65355690830571,1739137685.9927714,27.699973583221436,8.636638440494126,1739137685.992773,27.699973583221436,2.3941120285615556,1739137685.9927747,27.699973583221436,2.669337703150642,1739137685.9927762,27.699973583221436,0.6108,1739137685.9927776,27.699973583221436,0.8594657107364999,1739137685.9927793,27.699973583221436,0.0,1739137685.9927807,27.699973583221436,-0.07687394815857185,1739137685.9927824,27.699973583221436,1.7071488045087557,1739137685.9927838,27.699973583221436,0.9363396588950718 +1739137686.0127745,27.71997356414795,50.74048024299335,1739137686.0127773,27.71997356414795,5.7753642650763215,1739137686.0127802,27.71997356414795,56.04262550102264,1739137686.0127833,27.71997356414795,47.65355690830571,1739137686.0127852,27.71997356414795,8.636638440494126,1739137686.0127869,27.71997356414795,2.3941120285615556,1739137686.0127885,27.71997356414795,2.669337703150642,1739137686.01279,27.71997356414795,0.6108,1739137686.0127916,27.71997356414795,0.8594657107364999,1739137686.0127935,27.71997356414795,0.0,1739137686.0127954,27.71997356414795,-0.07687394815857185,1739137686.012797,27.71997356414795,1.7071488045087557,1739137686.0127988,27.71997356414795,0.9363396588950718 +1739137686.0363371,27.739973545074463,50.74048024299335,1739137686.036345,27.739973545074463,5.7753642650763215,1739137686.036355,27.739973545074463,56.04262550102264,1739137686.0363655,27.739973545074463,47.65355690830571,1739137686.0363705,27.739973545074463,8.636638440494126,1739137686.0363762,27.739973545074463,2.3941120285615556,1739137686.036381,27.739973545074463,2.669337703150642,1739137686.0363858,27.739973545074463,0.6108,1739137686.0363903,27.739973545074463,0.8594657107364999,1739137686.0363958,27.739973545074463,0.0,1739137686.0364006,27.739973545074463,-0.07687394815857185,1739137686.0364058,27.739973545074463,1.7071488045087557,1739137686.0364103,27.739973545074463,0.9363396588950718 +1739137686.057428,27.759973526000977,50.74048024299335,1739137686.057436,27.759973526000977,5.7753642650763215,1739137686.057446,27.759973526000977,56.04262550102264,1739137686.0574558,27.759973526000977,47.65355690830571,1739137686.0574605,27.759973526000977,8.636638440494126,1739137686.0574663,27.759973526000977,2.3941120285615556,1739137686.057471,27.759973526000977,2.669337703150642,1739137686.0574756,27.759973526000977,0.6108,1739137686.05748,27.759973526000977,0.8594657107364999,1739137686.0574858,27.759973526000977,0.0,1739137686.0574903,27.759973526000977,-0.07687394815857185,1739137686.0574956,27.759973526000977,1.7071488045087557,1739137686.0575001,27.759973526000977,0.9363396588950718 +1739137686.0797446,27.769973516464233,50.74048024299335,1739137686.0797527,27.769973516464233,5.7753642650763215,1739137686.0797627,27.769973516464233,56.04262550102264,1739137686.0797722,27.769973516464233,47.65355690830571,1739137686.0797768,27.769973516464233,8.636638440494126,1739137686.0797827,27.769973516464233,2.3941120285615556,1739137686.0797875,27.769973516464233,2.669337703150642,1739137686.0797925,27.769973516464233,0.6108,1739137686.079797,27.769973516464233,0.8594657107364999,1739137686.0798023,27.769973516464233,0.0,1739137686.0798073,27.769973516464233,-0.07687394815857185,1739137686.0798123,27.769973516464233,1.7071488045087557,1739137686.0798173,27.769973516464233,0.9363396588950718 +1739137686.0982032,27.799973487854004,50.72527213672508,1739137686.0982082,27.799973487854004,5.876760564452901,1739137686.0982137,27.799973487854004,56.14181338770503,1739137686.098219,27.799973487854004,47.58158648377162,1739137686.0982215,27.799973487854004,8.639679444347678,1739137686.0982246,27.799973487854004,2.420569992846557,1739137686.0982273,27.799973487854004,2.6505508304841237,1739137686.0982296,27.799973487854004,0.6108,1739137686.0982323,27.799973487854004,0.8659487084257922,1739137686.0982351,27.799973487854004,0.0,1739137686.098238,27.799973487854004,-0.04721796549606604,1739137686.0982409,27.799973487854004,1.7347540187096704,1739137686.0982432,27.799973487854004,0.9272885774823212 +1739137686.1162217,27.819973468780518,50.72527213672508,1739137686.1162245,27.819973468780518,5.876760564452901,1739137686.116228,27.819973468780518,56.14181338770503,1739137686.116232,27.819973468780518,47.58158648377162,1739137686.1162338,27.819973468780518,8.639679444347678,1739137686.1162357,27.819973468780518,2.420569992846557,1739137686.1162376,27.819973468780518,2.6505508304841237,1739137686.1162393,27.819973468780518,0.6108,1739137686.116241,27.819973468780518,0.8659487084257922,1739137686.1162426,27.819973468780518,0.0,1739137686.1162446,27.819973468780518,-0.061339869056528995,1739137686.1162462,27.819973468780518,1.7347540187096704,1739137686.1162481,27.819973468780518,0.9272885774823212 +1739137686.13401,27.83997344970703,50.72527213672508,1739137686.1340125,27.83997344970703,5.876760564452901,1739137686.134015,27.83997344970703,56.14181338770503,1739137686.1340175,27.83997344970703,47.58158648377162,1739137686.134019,27.83997344970703,8.639679444347678,1739137686.1340203,27.83997344970703,2.420569992846557,1739137686.134022,27.83997344970703,2.6505508304841237,1739137686.1340232,27.83997344970703,0.6108,1739137686.1340241,27.83997344970703,0.8659487084257922,1739137686.1340258,27.83997344970703,0.0,1739137686.134027,27.83997344970703,-0.061339869056528995,1739137686.1340282,27.83997344970703,1.7347540187096704,1739137686.1340294,27.83997344970703,0.9272885774823212 +1739137686.1539283,27.859973430633545,50.72527213672508,1739137686.1539302,27.859973430633545,5.876760564452901,1739137686.1539326,27.859973430633545,56.14181338770503,1739137686.1539354,27.859973430633545,47.58158648377162,1739137686.1539366,27.859973430633545,8.639679444347678,1739137686.1539383,27.859973430633545,2.420569992846557,1739137686.1539395,27.859973430633545,2.6505508304841237,1739137686.1539407,27.859973430633545,0.6108,1739137686.1539419,27.859973430633545,0.8659487084257922,1739137686.1539433,27.859973430633545,0.0,1739137686.1539443,27.859973430633545,-0.061339869056528995,1739137686.1539457,27.859973430633545,1.7347540187096704,1739137686.1539469,27.859973430633545,0.9272885774823212 +1739137686.1748707,27.87997341156006,50.72527213672508,1739137686.1748729,27.87997341156006,5.876760564452901,1739137686.1748755,27.87997341156006,56.14181338770503,1739137686.174878,27.87997341156006,47.58158648377162,1739137686.1748793,27.87997341156006,8.639679444347678,1739137686.1748807,27.87997341156006,2.420569992846557,1739137686.174882,27.87997341156006,2.6505508304841237,1739137686.1748834,27.87997341156006,0.6108,1739137686.1748843,27.87997341156006,0.8659487084257922,1739137686.174886,27.87997341156006,0.0,1739137686.174887,27.87997341156006,-0.061339869056528995,1739137686.1748884,27.87997341156006,1.7347540187096704,1739137686.1748898,27.87997341156006,0.9272885774823212 +1739137686.1942654,27.899973392486572,50.70742415490982,1739137686.1942677,27.899973392486572,5.9768362238451775,1739137686.1942701,27.899973392486572,56.22652457968857,1739137686.1942728,27.899973392486572,47.51711924694303,1739137686.194274,27.899973392486572,8.641440019064733,1739137686.1942756,27.899973392486572,2.4457424604010485,1739137686.194277,27.899973392486572,2.6246243330039634,1739137686.1942785,27.899973392486572,0.6108,1739137686.1942794,27.899973392486572,0.8749758427184329,1739137686.1942809,27.899973392486572,0.0,1739137686.194282,27.899973392486572,-0.031239624017504502,1739137686.1942835,27.899973392486572,1.762359232910585,1739137686.1942852,27.899973392486572,0.9205489239147086 +1739137686.2150464,27.919973373413086,50.70742415490982,1739137686.2150488,27.919973373413086,5.9768362238451775,1739137686.2150512,27.919973373413086,56.22652457968857,1739137686.2150538,27.919973373413086,47.51711924694303,1739137686.215055,27.919973373413086,8.641440019064733,1739137686.2150567,27.919973373413086,2.4457424604010485,1739137686.2150578,27.919973373413086,2.6246243330039634,1739137686.2150593,27.919973373413086,0.6108,1739137686.2150602,27.919973373413086,0.8749758427184329,1739137686.2150617,27.919973373413086,0.0,1739137686.215063,27.919973373413086,-0.04557308119627568,1739137686.2150645,27.919973373413086,1.762359232910585,1739137686.215066,27.919973373413086,0.9205489239147086 +1739137686.2349813,27.9399733543396,50.70742415490982,1739137686.2349834,27.9399733543396,5.9768362238451775,1739137686.234986,27.9399733543396,56.22652457968857,1739137686.2349885,27.9399733543396,47.51711924694303,1739137686.2349901,27.9399733543396,8.641440019064733,1739137686.2349916,27.9399733543396,2.4457424604010485,1739137686.234993,27.9399733543396,2.6246243330039634,1739137686.2349942,27.9399733543396,0.6108,1739137686.2349951,27.9399733543396,0.8749758427184329,1739137686.2349968,27.9399733543396,0.0,1739137686.234998,27.9399733543396,-0.04557308119627568,1739137686.2349992,27.9399733543396,1.762359232910585,1739137686.2350006,27.9399733543396,0.9205489239147086 +1739137686.2546823,27.959973335266113,50.70742415490982,1739137686.2546844,27.959973335266113,5.9768362238451775,1739137686.254687,27.959973335266113,56.22652457968857,1739137686.2546895,27.959973335266113,47.51711924694303,1739137686.254691,27.959973335266113,8.641440019064733,1739137686.2546923,27.959973335266113,2.4457424604010485,1739137686.254694,27.959973335266113,2.6246243330039634,1739137686.254695,27.959973335266113,0.6108,1739137686.2546961,27.959973335266113,0.8749758427184329,1739137686.2546978,27.959973335266113,0.0,1739137686.2546988,27.959973335266113,-0.04557308119627568,1739137686.2547002,27.959973335266113,1.762359232910585,1739137686.2547016,27.959973335266113,0.9205489239147086 +1739137686.2739336,27.979973316192627,50.70742415490982,1739137686.273936,27.979973316192627,5.9768362238451775,1739137686.273939,27.979973316192627,56.22652457968857,1739137686.2739413,27.979973316192627,47.51711924694303,1739137686.2739427,27.979973316192627,8.641440019064733,1739137686.2739444,27.979973316192627,2.4457424604010485,1739137686.2739456,27.979973316192627,2.6246243330039634,1739137686.2739472,27.979973316192627,0.6108,1739137686.2739484,27.979973316192627,0.8749758427184329,1739137686.2739499,27.979973316192627,0.0,1739137686.2739515,27.979973316192627,-0.04557308119627568,1739137686.2739527,27.979973316192627,1.762359232910585,1739137686.2739542,27.979973316192627,0.9205489239147086 +1739137686.2938643,27.99997329711914,50.68694972344385,1739137686.2938662,27.99997329711914,6.0757556445634044,1739137686.2938688,27.99997329711914,56.38721586205835,1739137686.2938714,27.99997329711914,47.37102763914809,1739137686.2938726,27.99997329711914,8.641410610758308,1739137686.2938745,27.99997329711914,2.4830715007729482,1739137686.2938757,27.99997329711914,2.678781910633212,1739137686.293877,27.99997329711914,0.6108,1739137686.2938783,27.99997329711914,0.8562250466926112,1739137686.2938795,27.99997329711914,0.0,1739137686.293881,27.99997329711914,-0.07208627969136971,1739137686.2938824,27.99997329711914,1.7899644471114997,1739137686.2938833,27.99997329711914,0.9156859874603611 +1739137686.313814,28.019973278045654,50.68694972344385,1739137686.3138163,28.019973278045654,6.0757556445634044,1739137686.313819,28.019973278045654,56.38721586205835,1739137686.3138216,28.019973278045654,47.37102763914809,1739137686.3138227,28.019973278045654,8.641410610758308,1739137686.3138242,28.019973278045654,2.4830715007729482,1739137686.3138256,28.019973278045654,2.678781910633212,1739137686.3138268,28.019973278045654,0.6108,1739137686.313828,28.019973278045654,0.8562250466926112,1739137686.31383,28.019973278045654,0.0,1739137686.313831,28.019973278045654,-0.05946094076774988,1739137686.3138325,28.019973278045654,1.7899644471114997,1739137686.3138337,28.019973278045654,0.9156859874603611 +1739137686.333763,28.039973258972168,50.68694972344385,1739137686.333765,28.039973258972168,6.0757556445634044,1739137686.3337677,28.039973258972168,56.38721586205835,1739137686.3337703,28.039973258972168,47.37102763914809,1739137686.3337717,28.039973258972168,8.641410610758308,1739137686.3337734,28.039973258972168,2.4830715007729482,1739137686.3337746,28.039973258972168,2.678781910633212,1739137686.3337758,28.039973258972168,0.6108,1739137686.3337774,28.039973258972168,0.8562250466926112,1739137686.3337789,28.039973258972168,0.0,1739137686.3337803,28.039973258972168,-0.05946094076774988,1739137686.3337815,28.039973258972168,1.7899644471114997,1739137686.3337827,28.039973258972168,0.9156859874603611 +1739137686.359747,28.05997323989868,50.68694972344385,1739137686.3597553,28.05997323989868,6.0757556445634044,1739137686.3597655,28.05997323989868,56.38721586205835,1739137686.3597753,28.05997323989868,47.37102763914809,1739137686.35978,28.05997323989868,8.641410610758308,1739137686.3597865,28.05997323989868,2.4830715007729482,1739137686.3597913,28.05997323989868,2.678781910633212,1739137686.3597965,28.05997323989868,0.6108,1739137686.359801,28.05997323989868,0.8562250466926112,1739137686.3598065,28.05997323989868,0.0,1739137686.359811,28.05997323989868,-0.05946094076774988,1739137686.3598166,28.05997323989868,1.7899644471114997,1739137686.3598208,28.05997323989868,0.9156859874603611 +1739137686.3797216,28.079973220825195,50.68694972344385,1739137686.3797302,28.079973220825195,6.0757556445634044,1739137686.37974,28.079973220825195,56.38721586205835,1739137686.3797498,28.079973220825195,47.37102763914809,1739137686.3797545,28.079973220825195,8.641410610758308,1739137686.3797607,28.079973220825195,2.4830715007729482,1739137686.3797655,28.079973220825195,2.678781910633212,1739137686.37977,28.079973220825195,0.6108,1739137686.3797746,28.079973220825195,0.8562250466926112,1739137686.3797796,28.079973220825195,0.0,1739137686.3797843,28.079973220825195,-0.05946094076774988,1739137686.3797896,28.079973220825195,1.7899644471114997,1739137686.379794,28.079973220825195,0.9156859874603611 +1739137686.4009016,28.089973211288452,50.68694972344385,1739137686.40091,28.089973211288452,6.0757556445634044,1739137686.4009192,28.089973211288452,56.38721586205835,1739137686.4009287,28.089973211288452,47.37102763914809,1739137686.4009337,28.089973211288452,8.641410610758308,1739137686.4009395,28.089973211288452,2.4830715007729482,1739137686.4009442,28.089973211288452,2.678781910633212,1739137686.4009488,28.089973211288452,0.6108,1739137686.400953,28.089973211288452,0.8562250466926112,1739137686.4009585,28.089973211288452,0.0,1739137686.400963,28.089973211288452,-0.05946094076774988,1739137686.4009686,28.089973211288452,1.7899644471114997,1739137686.400973,28.089973211288452,0.9156859874603611 +1739137686.4212987,28.109973192214966,50.6639011322738,1739137686.4213169,28.109973192214966,6.173445477539664,1739137686.4213352,28.109973192214966,56.47148336216177,1739137686.4213538,28.109973192214966,47.30708115080961,1739137686.421363,28.109973192214966,8.640181567969478,1739137686.4213796,28.109973192214966,2.5078627233351414,1739137686.4213924,28.109973192214966,2.652562140917971,1739137686.4214025,28.109973192214966,0.6108,1739137686.421413,28.109973192214966,0.8652523119282894,1739137686.4214234,28.109973192214966,0.0,1739137686.421434,28.109973192214966,-0.029303855139824808,1739137686.4214451,28.109973192214966,1.8175696613124144,1739137686.4214559,28.109973192214966,0.9089166912075021 +1739137686.4524515,28.139973163604736,50.6639011322738,1739137686.45246,28.139973163604736,6.173445477539664,1739137686.4524708,28.139973163604736,56.47148336216177,1739137686.4524808,28.139973163604736,47.30708115080961,1739137686.4524856,28.139973163604736,8.640181567969478,1739137686.452492,28.139973163604736,2.5078627233351414,1739137686.4524972,28.139973163604736,2.652562140917971,1739137686.4525018,28.139973163604736,0.6108,1739137686.4525063,28.139973163604736,0.8652523119282894,1739137686.4525118,28.139973163604736,0.0,1739137686.4525166,28.139973163604736,-0.04366437927921263,1739137686.4525218,28.139973163604736,1.8175696613124144,1739137686.4525263,28.139973163604736,0.9089166912075021 +1739137686.4738927,28.15997314453125,50.6639011322738,1739137686.4739008,28.15997314453125,6.173445477539664,1739137686.4739108,28.15997314453125,56.47148336216177,1739137686.473921,28.15997314453125,47.30708115080961,1739137686.4739258,28.15997314453125,8.640181567969478,1739137686.473932,28.15997314453125,2.5078627233351414,1739137686.4739368,28.15997314453125,2.652562140917971,1739137686.4739416,28.15997314453125,0.6108,1739137686.473946,28.15997314453125,0.8652523119282894,1739137686.4739518,28.15997314453125,0.0,1739137686.4739563,28.15997314453125,-0.04366437927921263,1739137686.473962,28.15997314453125,1.8175696613124144,1739137686.4739666,28.15997314453125,0.9089166912075021 +1739137686.508381,28.18997311592102,50.6639011322738,1739137686.508391,28.18997311592102,6.173445477539664,1739137686.5084023,28.18997311592102,56.47148336216177,1739137686.5084152,28.18997311592102,47.30708115080961,1739137686.5084224,28.18997311592102,8.640181567969478,1739137686.5084317,28.18997311592102,2.5078627233351414,1739137686.5084393,28.18997311592102,2.652562140917971,1739137686.5084472,28.18997311592102,0.6108,1739137686.5084555,28.18997311592102,0.8652523119282894,1739137686.508463,28.18997311592102,0.0,1739137686.5084698,28.18997311592102,-0.04366437927921263,1739137686.5084774,28.18997311592102,1.8175696613124144,1739137686.5084856,28.18997311592102,0.9089166912075021 +1739137686.5253923,28.21997308731079,50.63831439636545,1739137686.525397,28.21997308731079,6.269896036106671,1739137686.525402,28.21997308731079,56.57820372469276,1739137686.525407,28.21997308731079,47.21308583431823,1739137686.5254097,28.21997308731079,8.63654286329837,1739137686.5254128,28.21997308731079,2.5369693073378454,1739137686.5254157,28.21997308731079,2.655863576978383,1739137686.5254185,28.21997308731079,0.6108,1739137686.5254211,28.21997308731079,0.8641104359867342,1739137686.5254235,28.21997308731079,0.0,1739137686.5254261,28.21997308731079,-0.03779627008551273,1739137686.525429,28.21997308731079,1.845174875513329,1739137686.5254316,28.21997308731079,0.9047010451794271 +1739137686.5436668,28.239973068237305,50.63831439636545,1739137686.5436702,28.239973068237305,6.269896036106671,1739137686.5436745,28.239973068237305,56.57820372469276,1739137686.5436778,28.239973068237305,47.21308583431823,1739137686.5436792,28.239973068237305,8.63654286329837,1739137686.5436819,28.239973068237305,2.5369693073378454,1739137686.5436833,28.239973068237305,2.655863576978383,1739137686.5436852,28.239973068237305,0.6108,1739137686.5436864,28.239973068237305,0.8641104359867342,1739137686.5436888,28.239973068237305,0.0,1739137686.5436902,28.239973068237305,-0.04059060919269286,1739137686.543692,28.239973068237305,1.845174875513329,1739137686.5436935,28.239973068237305,0.9047010451794271 +1739137686.562165,28.25997304916382,50.63831439636545,1739137686.5621681,28.25997304916382,6.269896036106671,1739137686.5621715,28.25997304916382,56.57820372469276,1739137686.5621746,28.25997304916382,47.21308583431823,1739137686.5621762,28.25997304916382,8.63654286329837,1739137686.5621784,28.25997304916382,2.5369693073378454,1739137686.5621798,28.25997304916382,2.655863576978383,1739137686.5621815,28.25997304916382,0.6108,1739137686.5621827,28.25997304916382,0.8641104359867342,1739137686.5621848,28.25997304916382,0.0,1739137686.5621862,28.25997304916382,-0.04059060919269286,1739137686.5621884,28.25997304916382,1.845174875513329,1739137686.5621898,28.25997304916382,0.9047010451794271 +1739137686.5819116,28.279973030090332,50.63831439636545,1739137686.5819147,28.279973030090332,6.269896036106671,1739137686.5819178,28.279973030090332,56.57820372469276,1739137686.5819209,28.279973030090332,47.21308583431823,1739137686.5819223,28.279973030090332,8.63654286329837,1739137686.5819242,28.279973030090332,2.5369693073378454,1739137686.5819256,28.279973030090332,2.655863576978383,1739137686.5819268,28.279973030090332,0.6108,1739137686.5819285,28.279973030090332,0.8641104359867342,1739137686.58193,28.279973030090332,0.0,1739137686.5819314,28.279973030090332,-0.04059060919269286,1739137686.581933,28.279973030090332,1.845174875513329,1739137686.5819345,28.279973030090332,0.9047010451794271 +1739137686.6018872,28.299973011016846,50.63831439636545,1739137686.60189,28.299973011016846,6.269896036106671,1739137686.6018932,28.299973011016846,56.57820372469276,1739137686.601896,28.299973011016846,47.21308583431823,1739137686.6018975,28.299973011016846,8.63654286329837,1739137686.6018991,28.299973011016846,2.5369693073378454,1739137686.6019008,28.299973011016846,2.655863576978383,1739137686.6019018,28.299973011016846,0.6108,1739137686.6019032,28.299973011016846,0.8641104359867342,1739137686.6019046,28.299973011016846,0.0,1739137686.6019058,28.299973011016846,-0.04059060919269286,1739137686.6019075,28.299973011016846,1.845174875513329,1739137686.6019087,28.299973011016846,0.9047010451794271 +1739137686.6219556,28.31997299194336,50.63831439636545,1739137686.6219585,28.31997299194336,6.269896036106671,1739137686.621962,28.31997299194336,56.57820372469276,1739137686.6219647,28.31997299194336,47.21308583431823,1739137686.6219666,28.31997299194336,8.63654286329837,1739137686.6219687,28.31997299194336,2.5369693073378454,1739137686.6219702,28.31997299194336,2.655863576978383,1739137686.6219714,28.31997299194336,0.6108,1739137686.6219728,28.31997299194336,0.8641104359867342,1739137686.6219745,28.31997299194336,0.0,1739137686.621976,28.31997299194336,-0.04059060919269286,1739137686.6219773,28.31997299194336,1.845174875513329,1739137686.621979,28.31997299194336,0.9047010451794271 +1739137686.6420743,28.339972972869873,50.61021399649361,1739137686.6420777,28.339972972869873,6.365133425003426,1739137686.6420808,28.339972972869873,56.724505839296825,1739137686.642084,28.339972972869873,47.08020821403156,1739137686.642085,28.339972972869873,8.628775096131038,1739137686.642087,28.339972972869873,2.5713880778538374,1739137686.6420882,28.339972972869873,2.6970267577815865,1739137686.6420898,28.339972972869873,0.6108,1739137686.642091,28.339972972869873,0.8499991145208623,1739137686.642093,28.339972972869873,0.0,1739137686.6420946,28.339972972869873,-0.05914134095912346,1739137686.642096,28.339972972869873,1.8727800897142437,1739137686.6420977,28.339972972869873,0.9003067692736352 +1739137686.6616526,28.359972953796387,50.61021399649361,1739137686.6616552,28.359972953796387,6.365133425003426,1739137686.661658,28.359972953796387,56.724505839296825,1739137686.661661,28.359972953796387,47.08020821403156,1739137686.6616626,28.359972953796387,8.628775096131038,1739137686.6616642,28.359972953796387,2.5713880778538374,1739137686.6616654,28.359972953796387,2.6970267577815865,1739137686.6616669,28.359972953796387,0.6108,1739137686.661668,28.359972953796387,0.8499991145208623,1739137686.6616697,28.359972953796387,0.0,1739137686.6616712,28.359972953796387,-0.05030765475277288,1739137686.6616724,28.359972953796387,1.8727800897142437,1739137686.661674,28.359972953796387,0.9003067692736352 +1739137686.682492,28.3799729347229,50.61021399649361,1739137686.682496,28.3799729347229,6.365133425003426,1739137686.6825016,28.3799729347229,56.724505839296825,1739137686.682507,28.3799729347229,47.08020821403156,1739137686.6825101,28.3799729347229,8.628775096131038,1739137686.6825147,28.3799729347229,2.5713880778538374,1739137686.6825182,28.3799729347229,2.6970267577815865,1739137686.6825223,28.3799729347229,0.6108,1739137686.6825264,28.3799729347229,0.8499991145208623,1739137686.6825302,28.3799729347229,0.0,1739137686.6825337,28.3799729347229,-0.05030765475277288,1739137686.6825373,28.3799729347229,1.8727800897142437,1739137686.682541,28.3799729347229,0.9003067692736352 +1739137686.7013066,28.399972915649414,50.61021399649361,1739137686.701309,28.399972915649414,6.365133425003426,1739137686.7013118,28.399972915649414,56.724505839296825,1739137686.701315,28.399972915649414,47.08020821403156,1739137686.701316,28.399972915649414,8.628775096131038,1739137686.7013178,28.399972915649414,2.5713880778538374,1739137686.7013195,28.399972915649414,2.6970267577815865,1739137686.7013206,28.399972915649414,0.6108,1739137686.701322,28.399972915649414,0.8499991145208623,1739137686.7013235,28.399972915649414,0.0,1739137686.7013247,28.399972915649414,-0.05030765475277288,1739137686.7013264,28.399972915649414,1.8727800897142437,1739137686.7013276,28.399972915649414,0.9003067692736352 +1739137686.721639,28.419972896575928,50.61021399649361,1739137686.7216418,28.419972896575928,6.365133425003426,1739137686.7216449,28.419972896575928,56.724505839296825,1739137686.721648,28.419972896575928,47.08020821403156,1739137686.7216494,28.419972896575928,8.628775096131038,1739137686.7216508,28.419972896575928,2.5713880778538374,1739137686.7216525,28.419972896575928,2.6970267577815865,1739137686.7216537,28.419972896575928,0.6108,1739137686.7216551,28.419972896575928,0.8499991145208623,1739137686.7216566,28.419972896575928,0.0,1739137686.7216578,28.419972896575928,-0.05030765475277288,1739137686.7216594,28.419972896575928,1.8727800897142437,1739137686.7216609,28.419972896575928,0.9003067692736352 +1739137686.7425654,28.43997287750244,50.579665102579334,1739137686.7425678,28.43997287750244,6.459038863528107,1739137686.7425706,28.43997287750244,56.81125615130957,1739137686.7425733,28.43997287750244,47.01053187139763,1739137686.7425747,28.43997287750244,8.622310961168989,1739137686.7425764,28.43997287750244,2.5966957378101467,1739137686.7425776,28.43997287750244,2.6768742458709807,1739137686.742579,28.43997287750244,0.6108,1739137686.7425802,28.43997287750244,0.8568786521729712,1739137686.7425818,28.43997287750244,0.0,1739137686.7425833,28.43997287750244,-0.026499782228819616,1739137686.742585,28.43997287750244,1.9003853039151584,1739137686.7425861,28.43997287750244,0.894715522219425 +1739137686.7613654,28.459972858428955,50.579665102579334,1739137686.7613678,28.459972858428955,6.459038863528107,1739137686.7613707,28.459972858428955,56.81125615130957,1739137686.7613735,28.459972858428955,47.01053187139763,1739137686.7613747,28.459972858428955,8.622310961168989,1739137686.7613766,28.459972858428955,2.5966957378101467,1739137686.7613778,28.459972858428955,2.6768742458709807,1739137686.761379,28.459972858428955,0.6108,1739137686.7613804,28.459972858428955,0.8568786521729712,1739137686.7613819,28.459972858428955,0.0,1739137686.761383,28.459972858428955,-0.03783687004645375,1739137686.761385,28.459972858428955,1.9003853039151584,1739137686.7613862,28.459972858428955,0.894715522219425 +1739137686.7820637,28.47997283935547,50.579665102579334,1739137686.782066,28.47997283935547,6.459038863528107,1739137686.7820692,28.47997283935547,56.81125615130957,1739137686.7820725,28.47997283935547,47.01053187139763,1739137686.782074,28.47997283935547,8.622310961168989,1739137686.7820754,28.47997283935547,2.5966957378101467,1739137686.7820766,28.47997283935547,2.6768742458709807,1739137686.782078,28.47997283935547,0.6108,1739137686.7820792,28.47997283935547,0.8568786521729712,1739137686.7820807,28.47997283935547,0.0,1739137686.782082,28.47997283935547,-0.03783687004645375,1739137686.7820835,28.47997283935547,1.9003853039151584,1739137686.7820852,28.47997283935547,0.894715522219425 +1739137686.801828,28.499972820281982,50.579665102579334,1739137686.80183,28.499972820281982,6.459038863528107,1739137686.8018327,28.499972820281982,56.81125615130957,1739137686.8018358,28.499972820281982,47.01053187139763,1739137686.8018372,28.499972820281982,8.622310961168989,1739137686.8018389,28.499972820281982,2.5966957378101467,1739137686.8018403,28.499972820281982,2.6768742458709807,1739137686.8018417,28.499972820281982,0.6108,1739137686.801843,28.499972820281982,0.8568786521729712,1739137686.8018446,28.499972820281982,0.0,1739137686.8018458,28.499972820281982,-0.03783687004645375,1739137686.801847,28.499972820281982,1.9003853039151584,1739137686.8018484,28.499972820281982,0.894715522219425 +1739137686.8211265,28.519972801208496,50.579665102579334,1739137686.8211288,28.519972801208496,6.459038863528107,1739137686.821132,28.519972801208496,56.81125615130957,1739137686.8211353,28.519972801208496,47.01053187139763,1739137686.821137,28.519972801208496,8.622310961168989,1739137686.8211389,28.519972801208496,2.5966957378101467,1739137686.8211408,28.519972801208496,2.6768742458709807,1739137686.8211424,28.519972801208496,0.6108,1739137686.821144,28.519972801208496,0.8568786521729712,1739137686.8211458,28.519972801208496,0.0,1739137686.8211474,28.519972801208496,-0.03783687004645375,1739137686.821149,28.519972801208496,1.9003853039151584,1739137686.8211508,28.519972801208496,0.894715522219425 +1739137686.8408873,28.53997278213501,50.579665102579334,1739137686.84089,28.53997278213501,6.459038863528107,1739137686.8408926,28.53997278213501,56.81125615130957,1739137686.8408954,28.53997278213501,47.01053187139763,1739137686.8408973,28.53997278213501,8.622310961168989,1739137686.840899,28.53997278213501,2.5966957378101467,1739137686.8409004,28.53997278213501,2.6768742458709807,1739137686.8409016,28.53997278213501,0.6108,1739137686.8409028,28.53997278213501,0.8568786521729712,1739137686.8409045,28.53997278213501,0.0,1739137686.8409057,28.53997278213501,-0.03783687004645375,1739137686.8409073,28.53997278213501,1.9003853039151584,1739137686.8409085,28.53997278213501,0.894715522219425 +1739137686.8611846,28.559972763061523,50.54670999884047,1739137686.8611867,28.559972763061523,6.551575227760157,1739137686.8611896,28.559972763061523,56.8979530620266,1739137686.8611925,28.559972763061523,46.936026743378164,1739137686.8611937,28.559972763061523,8.61437834292227,1739137686.8611958,28.559972763061523,2.6225393394430854,1739137686.8611972,28.559972763061523,2.6615298141028725,1739137686.8611987,28.559972763061523,0.6108,1739137686.8611999,28.559972763061523,0.8621541519252428,1739137686.8612018,28.559972763061523,0.0,1739137686.8612032,28.559972763061523,-0.020276707332449725,1739137686.8612046,28.559972763061523,1.927990518116073,1739137686.861206,28.559972763061523,0.8907928456796339 +1739137686.8860784,28.579972743988037,50.54670999884047,1739137686.886087,28.579972743988037,6.551575227760157,1739137686.886097,28.579972743988037,56.8979530620266,1739137686.8861067,28.579972743988037,46.936026743378164,1739137686.8861113,28.579972743988037,8.61437834292227,1739137686.8861172,28.579972743988037,2.6225393394430854,1739137686.886122,28.579972743988037,2.6615298141028725,1739137686.8861265,28.579972743988037,0.6108,1739137686.8861313,28.579972743988037,0.8621541519252428,1739137686.8861363,28.579972743988037,0.0,1739137686.8861413,28.579972743988037,-0.028638693754391098,1739137686.8861463,28.579972743988037,1.927990518116073,1739137686.8861508,28.579972743988037,0.8907928456796339 +1739137686.905727,28.59997272491455,50.54670999884047,1739137686.9057362,28.59997272491455,6.551575227760157,1739137686.9057462,28.59997272491455,56.8979530620266,1739137686.905756,28.59997272491455,46.936026743378164,1739137686.9057605,28.59997272491455,8.61437834292227,1739137686.9057665,28.59997272491455,2.6225393394430854,1739137686.9057713,28.59997272491455,2.6615298141028725,1739137686.9057755,28.59997272491455,0.6108,1739137686.9057803,28.59997272491455,0.8621541519252428,1739137686.9057853,28.59997272491455,0.0,1739137686.90579,28.59997272491455,-0.028638693754391098,1739137686.9057956,28.59997272491455,1.927990518116073,1739137686.9058,28.59997272491455,0.8907928456796339 +1739137686.937388,28.619972705841064,50.54670999884047,1739137686.9373958,28.619972705841064,6.551575227760157,1739137686.9374056,28.619972705841064,56.8979530620266,1739137686.937415,28.619972705841064,46.936026743378164,1739137686.93742,28.619972705841064,8.61437834292227,1739137686.9374256,28.619972705841064,2.6225393394430854,1739137686.9374309,28.619972705841064,2.6615298141028725,1739137686.9374354,28.619972705841064,0.6108,1739137686.9374397,28.619972705841064,0.8621541519252428,1739137686.9374452,28.619972705841064,0.0,1739137686.9374497,28.619972705841064,-0.028638693754391098,1739137686.937455,28.619972705841064,1.927990518116073,1739137686.9374595,28.619972705841064,0.8907928456796339 +1739137686.9573154,28.649972677230835,50.54670999884047,1739137686.9573214,28.649972677230835,6.551575227760157,1739137686.9573286,28.649972677230835,56.8979530620266,1739137686.9573352,28.649972677230835,46.936026743378164,1739137686.9573386,28.649972677230835,8.61437834292227,1739137686.9573426,28.649972677230835,2.6225393394430854,1739137686.9573462,28.649972677230835,2.6615298141028725,1739137686.9573493,28.649972677230835,0.6108,1739137686.9573526,28.649972677230835,0.8621541519252428,1739137686.9573562,28.649972677230835,0.0,1739137686.9573596,28.649972677230835,-0.028638693754391098,1739137686.9573631,28.649972677230835,1.927990518116073,1739137686.9573665,28.649972677230835,0.8907928456796339 +1739137686.9816415,28.66997265815735,50.51135659725123,1739137686.9816453,28.66997265815735,6.642796272788658,1739137686.9816499,28.66997265815735,57.06139616848157,1739137686.9816542,28.66997265815735,46.7826634334219,1739137686.9816563,28.66997265815735,8.597818156129355,1739137686.9816594,28.66997265815735,2.6586802439986,1739137686.9816618,28.66997265815735,2.722164955383397,1739137686.981664,28.66997265815735,0.6108,1739137686.9816658,28.66997265815735,0.8414949636982201,1739137686.9816682,28.66997265815735,0.0,1739137686.9816704,28.66997265815735,-0.06223327034622193,1739137686.9816728,28.66997265815735,1.9555957323169877,1739137686.981675,28.66997265815735,0.8877308086283477 +1739137687.0007696,28.69997262954712,50.51135659725123,1739137687.0007727,28.69997262954712,6.642796272788658,1739137687.0007756,28.69997262954712,57.06139616848157,1739137687.000779,28.69997262954712,46.7826634334219,1739137687.0007806,28.69997262954712,8.597818156129355,1739137687.0007825,28.69997262954712,2.6586802439986,1739137687.0007846,28.69997262954712,2.722164955383397,1739137687.000786,28.69997262954712,0.6108,1739137687.0007877,28.69997262954712,0.8414949636982201,1739137687.0007894,28.69997262954712,0.0,1739137687.0007913,28.69997262954712,-0.04623584493012767,1739137687.000793,28.69997262954712,1.9555957323169877,1739137687.000795,28.69997262954712,0.8877308086283477 +1739137687.0211005,28.719972610473633,50.51135659725123,1739137687.0211034,28.719972610473633,6.642796272788658,1739137687.0211065,28.719972610473633,57.06139616848157,1739137687.021109,28.719972610473633,46.7826634334219,1739137687.0211105,28.719972610473633,8.597818156129355,1739137687.0211122,28.719972610473633,2.6586802439986,1739137687.0211139,28.719972610473633,2.722164955383397,1739137687.021115,28.719972610473633,0.6108,1739137687.0211165,28.719972610473633,0.8414949636982201,1739137687.0211182,28.719972610473633,0.0,1739137687.021119,28.719972610473633,-0.04623584493012767,1739137687.0211205,28.719972610473633,1.9555957323169877,1739137687.021122,28.719972610473633,0.8877308086283477 +1739137687.0403159,28.739972591400146,50.51135659725123,1739137687.0403183,28.739972591400146,6.642796272788658,1739137687.040321,28.739972591400146,57.06139616848157,1739137687.0403235,28.739972591400146,46.7826634334219,1739137687.0403252,28.739972591400146,8.597818156129355,1739137687.0403266,28.739972591400146,2.6586802439986,1739137687.040328,28.739972591400146,2.722164955383397,1739137687.0403292,28.739972591400146,0.6108,1739137687.0403304,28.739972591400146,0.8414949636982201,1739137687.040332,28.739972591400146,0.0,1739137687.0403333,28.739972591400146,-0.04623584493012767,1739137687.040335,28.739972591400146,1.9555957323169877,1739137687.0403361,28.739972591400146,0.8877308086283477 +1739137687.05985,28.75997257232666,50.51135659725123,1739137687.0598524,28.75997257232666,6.642796272788658,1739137687.0598547,28.75997257232666,57.06139616848157,1739137687.0598574,28.75997257232666,46.7826634334219,1739137687.0598588,28.75997257232666,8.597818156129355,1739137687.05986,28.75997257232666,2.6586802439986,1739137687.0598614,28.75997257232666,2.722164955383397,1739137687.0598629,28.75997257232666,0.6108,1739137687.059864,28.75997257232666,0.8414949636982201,1739137687.0598652,28.75997257232666,0.0,1739137687.0598667,28.75997257232666,-0.04623584493012767,1739137687.059868,28.75997257232666,1.9555957323169877,1739137687.0598695,28.75997257232666,0.8877308086283477 +1739137687.0803971,28.779972553253174,50.47366529127613,1739137687.0804,28.779972553253174,6.732611493875972,1739137687.0804029,28.779972553253174,57.14635458553966,1739137687.0804057,28.779972553253174,46.71335787430878,1739137687.0804071,28.779972553253174,8.589045300545415,1739137687.0804088,28.779972553253174,2.6830041416155566,1739137687.08041,28.779972553253174,2.7009582641720997,1739137687.0804117,28.779972553253174,0.6108,1739137687.0804126,28.779972553253174,0.8486634542472409,1739137687.0804143,28.779972553253174,0.0,1739137687.0804157,28.779972553253174,-0.022941557558003894,1739137687.0804174,28.779972553253174,1.9832009465179024,1739137687.0804186,28.779972553253174,0.8826975351426942 +1739137687.0998914,28.799972534179688,50.47366529127613,1739137687.0998936,28.799972534179688,6.732611493875972,1739137687.0998964,28.799972534179688,57.14635458553966,1739137687.099899,28.799972534179688,46.71335787430878,1739137687.0999005,28.799972534179688,8.589045300545415,1739137687.099902,28.799972534179688,2.6830041416155566,1739137687.099904,28.799972534179688,2.7009582641720997,1739137687.099905,28.799972534179688,0.6108,1739137687.0999062,28.799972534179688,0.8486634542472409,1739137687.0999079,28.799972534179688,0.0,1739137687.099909,28.799972534179688,-0.034034080895453345,1739137687.0999107,28.799972534179688,1.9832009465179024,1739137687.099912,28.799972534179688,0.8826975351426942 +1739137687.1205592,28.8199725151062,50.47366529127613,1739137687.1205618,28.8199725151062,6.732611493875972,1739137687.1205652,28.8199725151062,57.14635458553966,1739137687.1205685,28.8199725151062,46.71335787430878,1739137687.1205702,28.8199725151062,8.589045300545415,1739137687.120572,28.8199725151062,2.6830041416155566,1739137687.120574,28.8199725151062,2.7009582641720997,1739137687.1205752,28.8199725151062,0.6108,1739137687.1205769,28.8199725151062,0.8486634542472409,1739137687.1205785,28.8199725151062,0.0,1739137687.1205802,28.8199725151062,-0.034034080895453345,1739137687.1205816,28.8199725151062,1.9832009465179024,1739137687.120583,28.8199725151062,0.8826975351426942 +1739137687.144593,28.839972496032715,50.47366529127613,1739137687.1446009,28.839972496032715,6.732611493875972,1739137687.144611,28.839972496032715,57.14635458553966,1739137687.1446207,28.839972496032715,46.71335787430878,1739137687.1446252,28.839972496032715,8.589045300545415,1739137687.1446311,28.839972496032715,2.6830041416155566,1739137687.1446357,28.839972496032715,2.7009582641720997,1739137687.1446402,28.839972496032715,0.6108,1739137687.144645,28.839972496032715,0.8486634542472409,1739137687.1446502,28.839972496032715,0.0,1739137687.144655,28.839972496032715,-0.034034080895453345,1739137687.1446605,28.839972496032715,1.9832009465179024,1739137687.144665,28.839972496032715,0.8826975351426942 +1739137687.1645312,28.85997247695923,50.47366529127613,1739137687.164539,28.85997247695923,6.732611493875972,1739137687.1645489,28.85997247695923,57.14635458553966,1739137687.1645584,28.85997247695923,46.71335787430878,1739137687.1645632,28.85997247695923,8.589045300545415,1739137687.1645691,28.85997247695923,2.6830041416155566,1739137687.1645741,28.85997247695923,2.7009582641720997,1739137687.1645787,28.85997247695923,0.6108,1739137687.164583,28.85997247695923,0.8486634542472409,1739137687.1645882,28.85997247695923,0.0,1739137687.164593,28.85997247695923,-0.034034080895453345,1739137687.164598,28.85997247695923,1.9832009465179024,1739137687.1646025,28.85997247695923,0.8826975351426942 +1739137687.200441,28.899972438812256,50.433710708090885,1739137687.2004435,28.899972438812256,6.820906036502532,1739137687.2004464,28.899972438812256,57.231475656769966,1739137687.2004497,28.899972438812256,46.639777629864795,1739137687.2004514,28.899972438812256,8.579260022104645,1739137687.2004533,28.899972438812256,2.7075980854018087,1739137687.2004552,28.899972438812256,2.683583370503965,1739137687.2004566,28.899972438812256,0.6108,1739137687.200458,28.899972438812256,0.8545821727554539,1739137687.2004602,28.899972438812256,0.0,1739137687.2004616,28.899972438812256,-0.015807857339240932,1739137687.2004633,28.899972438812256,2.010806160718817,1739137687.200465,28.899972438812256,0.8790691885047005 +1739137687.2227092,28.91997241973877,50.433710708090885,1739137687.2227125,28.91997241973877,6.820906036502532,1739137687.2227166,28.91997241973877,57.231475656769966,1739137687.2227218,28.91997241973877,46.639777629864795,1739137687.2227247,28.91997241973877,8.579260022104645,1739137687.222728,28.91997241973877,2.7075980854018087,1739137687.2227314,28.91997241973877,2.683583370503965,1739137687.2227345,28.91997241973877,0.6108,1739137687.2227376,28.91997241973877,0.8545821727554539,1739137687.2227407,28.91997241973877,0.0,1739137687.222744,28.91997241973877,-0.02448701574924661,1739137687.2227473,28.91997241973877,2.010806160718817,1739137687.2227504,28.91997241973877,0.8790691885047005 +1739137687.2423759,28.939972400665283,50.433710708090885,1739137687.2423797,28.939972400665283,6.820906036502532,1739137687.2423842,28.939972400665283,57.231475656769966,1739137687.2423892,28.939972400665283,46.639777629864795,1739137687.2423923,28.939972400665283,8.579260022104645,1739137687.2423959,28.939972400665283,2.7075980854018087,1739137687.2423992,28.939972400665283,2.683583370503965,1739137687.2424026,28.939972400665283,0.6108,1739137687.242406,28.939972400665283,0.8545821727554539,1739137687.2424095,28.939972400665283,0.0,1739137687.2424128,28.939972400665283,-0.02448701574924661,1739137687.2424161,28.939972400665283,2.010806160718817,1739137687.2424197,28.939972400665283,0.8790691885047005 +1739137687.2601843,28.959972381591797,50.433710708090885,1739137687.260187,28.959972381591797,6.820906036502532,1739137687.2601898,28.959972381591797,57.231475656769966,1739137687.2601924,28.959972381591797,46.639777629864795,1739137687.2601938,28.959972381591797,8.579260022104645,1739137687.2601955,28.959972381591797,2.7075980854018087,1739137687.2601972,28.959972381591797,2.683583370503965,1739137687.2601984,28.959972381591797,0.6108,1739137687.2601998,28.959972381591797,0.8545821727554539,1739137687.2602015,28.959972381591797,0.0,1739137687.2602026,28.959972381591797,-0.02448701574924661,1739137687.260204,28.959972381591797,2.010806160718817,1739137687.2602053,28.959972381591797,0.8790691885047005 +1739137687.2801793,28.97997236251831,50.433710708090885,1739137687.2801816,28.97997236251831,6.820906036502532,1739137687.2801847,28.97997236251831,57.231475656769966,1739137687.2801874,28.97997236251831,46.639777629864795,1739137687.280189,28.97997236251831,8.579260022104645,1739137687.2801905,28.97997236251831,2.7075980854018087,1739137687.280192,28.97997236251831,2.683583370503965,1739137687.2801933,28.97997236251831,0.6108,1739137687.2801945,28.97997236251831,0.8545821727554539,1739137687.2801967,28.97997236251831,0.0,1739137687.2801979,28.97997236251831,-0.02448701574924661,1739137687.2801995,28.97997236251831,2.010806160718817,1739137687.2802007,28.97997236251831,0.8790691885047005 +1739137687.3009872,28.999972343444824,50.39149073079984,1739137687.3009894,28.999972343444824,6.907741767844222,1739137687.3009923,28.999972343444824,57.316852733744895,1739137687.3009949,28.999972343444824,46.56358628190775,1739137687.300996,28.999972343444824,8.566291282026851,1739137687.3009982,28.999972343444824,2.732730810631102,1739137687.3009996,28.999972343444824,2.669357529200648,1739137687.3010013,28.999972343444824,0.6108,1739137687.3010023,28.999972343444824,0.8594588948394626,1739137687.3010037,28.999972343444824,0.0,1739137687.301005,28.999972343444824,-0.010028793430122569,1739137687.3010063,28.999972343444824,2.0384113749197317,1739137687.3010075,28.999972343444824,0.8763725594798906 +1739137687.3204958,29.019972324371338,50.39149073079984,1739137687.3204992,29.019972324371338,6.907741767844222,1739137687.320514,29.019972324371338,57.316852733744895,1739137687.3205194,29.019972324371338,46.56358628190775,1739137687.320528,29.019972324371338,8.566291282026851,1739137687.3205304,29.019972324371338,2.732730810631102,1739137687.3205342,29.019972324371338,2.669357529200648,1739137687.3205369,29.019972324371338,0.6108,1739137687.3205395,29.019972324371338,0.8594588948394626,1739137687.320542,29.019972324371338,0.0,1739137687.3205445,29.019972324371338,-0.016913664640427983,1739137687.3205462,29.019972324371338,2.0384113749197317,1739137687.320549,29.019972324371338,0.8763725594798906 +1739137687.3409128,29.03997230529785,50.39149073079984,1739137687.3409154,29.03997230529785,6.907741767844222,1739137687.3409185,29.03997230529785,57.316852733744895,1739137687.3409214,29.03997230529785,46.56358628190775,1739137687.3409226,29.03997230529785,8.566291282026851,1739137687.3409243,29.03997230529785,2.732730810631102,1739137687.3409257,29.03997230529785,2.669357529200648,1739137687.340927,29.03997230529785,0.6108,1739137687.340928,29.03997230529785,0.8594588948394626,1739137687.3409295,29.03997230529785,0.0,1739137687.3409307,29.03997230529785,-0.016913664640427983,1739137687.3409321,29.03997230529785,2.0384113749197317,1739137687.3409333,29.03997230529785,0.8763725594798906 +1739137687.3603892,29.059972286224365,50.39149073079984,1739137687.3603916,29.059972286224365,6.907741767844222,1739137687.3603945,29.059972286224365,57.316852733744895,1739137687.3603976,29.059972286224365,46.56358628190775,1739137687.3603988,29.059972286224365,8.566291282026851,1739137687.3604004,29.059972286224365,2.732730810631102,1739137687.3604019,29.059972286224365,2.669357529200648,1739137687.3604033,29.059972286224365,0.6108,1739137687.3604043,29.059972286224365,0.8594588948394626,1739137687.360406,29.059972286224365,0.0,1739137687.3604074,29.059972286224365,-0.016913664640427983,1739137687.3604085,29.059972286224365,2.0384113749197317,1739137687.36041,29.059972286224365,0.8763725594798906 +1739137687.3803167,29.07997226715088,50.39149073079984,1739137687.380319,29.07997226715088,6.907741767844222,1739137687.3803222,29.07997226715088,57.316852733744895,1739137687.3803248,29.07997226715088,46.56358628190775,1739137687.380326,29.07997226715088,8.566291282026851,1739137687.380328,29.07997226715088,2.732730810631102,1739137687.3803294,29.07997226715088,2.669357529200648,1739137687.3803308,29.07997226715088,0.6108,1739137687.3803322,29.07997226715088,0.8594588948394626,1739137687.380334,29.07997226715088,0.0,1739137687.380335,29.07997226715088,-0.016913664640427983,1739137687.3803372,29.07997226715088,2.0384113749197317,1739137687.3803384,29.07997226715088,0.8763725594798906 +1739137687.400897,29.099972248077393,50.34700352332246,1739137687.4008994,29.099972248077393,6.993160690176007,1739137687.4009018,29.099972248077393,57.42060114832555,1739137687.4009047,29.099972248077393,46.46696046007848,1739137687.4009066,29.099972248077393,8.547839592675118,1739137687.400908,29.099972248077393,2.7604950442765666,1739137687.4009097,29.099972248077393,2.675087428283515,1739137687.4009109,29.099972248077393,0.6108,1739137687.400912,29.099972248077393,0.8574913054252227,1739137687.4009135,29.099972248077393,0.0,1739137687.4009147,29.099972248077393,-0.01725128599763001,1739137687.4009163,29.099972248077393,2.0660165891206463,1739137687.4009175,29.099972248077393,0.8745818192676819 +1739137687.4205012,29.119972229003906,50.34700352332246,1739137687.4205034,29.119972229003906,6.993160690176007,1739137687.420506,29.119972229003906,57.42060114832555,1739137687.4205086,29.119972229003906,46.46696046007848,1739137687.42051,29.119972229003906,8.547839592675118,1739137687.4205117,29.119972229003906,2.7604950442765666,1739137687.420513,29.119972229003906,2.675087428283515,1739137687.4205143,29.119972229003906,0.6108,1739137687.4205155,29.119972229003906,0.8574913054252227,1739137687.4205172,29.119972229003906,0.0,1739137687.4205182,29.119972229003906,-0.017090513842459187,1739137687.4205196,29.119972229003906,2.0660165891206463,1739137687.420521,29.119972229003906,0.8745818192676819 +1739137687.4404233,29.13997220993042,50.34700352332246,1739137687.4404252,29.13997220993042,6.993160690176007,1739137687.4404283,29.13997220993042,57.42060114832555,1739137687.4404316,29.13997220993042,46.46696046007848,1739137687.4404328,29.13997220993042,8.547839592675118,1739137687.4404345,29.13997220993042,2.7604950442765666,1739137687.440436,29.13997220993042,2.675087428283515,1739137687.4404373,29.13997220993042,0.6108,1739137687.4404385,29.13997220993042,0.8574913054252227,1739137687.4404404,29.13997220993042,0.0,1739137687.4404414,29.13997220993042,-0.017090513842459187,1739137687.4404428,29.13997220993042,2.0660165891206463,1739137687.4404442,29.13997220993042,0.8745818192676819 +1739137687.4610665,29.159972190856934,50.34700352332246,1739137687.4610689,29.159972190856934,6.993160690176007,1739137687.461072,29.159972190856934,57.42060114832555,1739137687.4610744,29.159972190856934,46.46696046007848,1739137687.4610758,29.159972190856934,8.547839592675118,1739137687.4610777,29.159972190856934,2.7604950442765666,1739137687.4610791,29.159972190856934,2.675087428283515,1739137687.4610806,29.159972190856934,0.6108,1739137687.4610815,29.159972190856934,0.8574913054252227,1739137687.4610832,29.159972190856934,0.0,1739137687.4610844,29.159972190856934,-0.017090513842459187,1739137687.461086,29.159972190856934,2.0660165891206463,1739137687.4610872,29.159972190856934,0.8745818192676819 +1739137687.484821,29.179972171783447,50.34700352332246,1739137687.4848297,29.179972171783447,6.993160690176007,1739137687.4848402,29.179972171783447,57.42060114832555,1739137687.48485,29.179972171783447,46.46696046007848,1739137687.4848545,29.179972171783447,8.547839592675118,1739137687.4848607,29.179972171783447,2.7604950442765666,1739137687.4848661,29.179972171783447,2.675087428283515,1739137687.4848707,29.179972171783447,0.6108,1739137687.4848752,29.179972171783447,0.8574913054252227,1739137687.4848807,29.179972171783447,0.0,1739137687.4848855,29.179972171783447,-0.017090513842459187,1739137687.484891,29.179972171783447,2.0660165891206463,1739137687.4848955,29.179972171783447,0.8745818192676819 +1739137687.5058472,29.19997215270996,50.34700352332246,1739137687.5058563,29.19997215270996,6.993160690176007,1739137687.5058663,29.19997215270996,57.42060114832555,1739137687.5058768,29.19997215270996,46.46696046007848,1739137687.5058813,29.19997215270996,8.547839592675118,1739137687.5058875,29.19997215270996,2.7604950442765666,1739137687.5058925,29.19997215270996,2.675087428283515,1739137687.5058973,29.19997215270996,0.6108,1739137687.505902,29.19997215270996,0.8574913054252227,1739137687.5059073,29.19997215270996,0.0,1739137687.505912,29.19997215270996,-0.017090513842459187,1739137687.505917,29.19997215270996,2.0660165891206463,1739137687.5059218,29.19997215270996,0.8745818192676819 +1739137687.538614,29.219972133636475,50.30027407413696,1739137687.5386267,29.219972133636475,7.077142160571775,1739137687.5386422,29.219972133636475,57.559786478614676,1739137687.538662,29.219972133636475,46.33642957345665,1739137687.5386698,29.219972133636475,8.51958080447132,1739137687.53868,29.219972133636475,2.792589796531289,1739137687.5386887,29.219972133636475,2.714068516244137,1739137687.5386975,29.219972133636475,0.6108,1739137687.538706,29.219972133636475,0.8442246265260323,1739137687.538715,29.219972133636475,0.0,1739137687.5387235,29.219972133636475,-0.03883479732919634,1739137687.5387325,29.219972133636475,2.093621803321561,1739137687.5387416,29.219972133636475,0.8727049979747704 +1739137687.553621,29.249972105026245,50.30027407413696,1739137687.5536258,29.249972105026245,7.077142160571775,1739137687.5536318,29.249972105026245,57.559786478614676,1739137687.553639,29.249972105026245,46.33642957345665,1739137687.5536427,29.249972105026245,8.51958080447132,1739137687.5536478,29.249972105026245,2.792589796531289,1739137687.5536525,29.249972105026245,2.714068516244137,1739137687.553657,29.249972105026245,0.6108,1739137687.5536613,29.249972105026245,0.8442246265260323,1739137687.5536664,29.249972105026245,0.0,1739137687.553671,29.249972105026245,-0.028480371448738162,1739137687.5536754,29.249972105026245,2.093621803321561,1739137687.5536804,29.249972105026245,0.8727049979747704 +1739137687.5725517,29.26997208595276,50.30027407413696,1739137687.5725553,29.26997208595276,7.077142160571775,1739137687.5725596,29.26997208595276,57.559786478614676,1739137687.5725641,29.26997208595276,46.33642957345665,1739137687.572567,29.26997208595276,8.51958080447132,1739137687.5725706,29.26997208595276,2.792589796531289,1739137687.572574,29.26997208595276,2.714068516244137,1739137687.572577,29.26997208595276,0.6108,1739137687.57258,29.26997208595276,0.8442246265260323,1739137687.572584,29.26997208595276,0.0,1739137687.572587,29.26997208595276,-0.028480371448738162,1739137687.5725906,29.26997208595276,2.093621803321561,1739137687.5725937,29.26997208595276,0.8727049979747704 +1739137687.590848,29.289972066879272,50.30027407413696,1739137687.5908523,29.289972066879272,7.077142160571775,1739137687.5908573,29.289972066879272,57.559786478614676,1739137687.5908625,29.289972066879272,46.33642957345665,1739137687.5908654,29.289972066879272,8.51958080447132,1739137687.5908694,29.289972066879272,2.792589796531289,1739137687.5908728,29.289972066879272,2.714068516244137,1739137687.5908759,29.289972066879272,0.6108,1739137687.5908792,29.289972066879272,0.8442246265260323,1739137687.5908825,29.289972066879272,0.0,1739137687.5908859,29.289972066879272,-0.028480371448738162,1739137687.5908895,29.289972066879272,2.093621803321561,1739137687.5908928,29.289972066879272,0.8727049979747704 +1739137687.6107872,29.309972047805786,50.30027407413696,1739137687.6107905,29.309972047805786,7.077142160571775,1739137687.6107945,29.309972047805786,57.559786478614676,1739137687.6107993,29.309972047805786,46.33642957345665,1739137687.6108022,29.309972047805786,8.51958080447132,1739137687.6108057,29.309972047805786,2.792589796531289,1739137687.6108088,29.309972047805786,2.714068516244137,1739137687.610812,29.309972047805786,0.6108,1739137687.6108153,29.309972047805786,0.8442246265260323,1739137687.6108186,29.309972047805786,0.0,1739137687.6108217,29.309972047805786,-0.028480371448738162,1739137687.610825,29.309972047805786,2.093621803321561,1739137687.6108284,29.309972047805786,0.8727049979747704 +1739137687.6309822,29.3299720287323,50.25137852231089,1739137687.6309857,29.3299720287323,7.159576367029505,1739137687.63099,29.3299720287323,57.630417192002206,1739137687.630995,29.3299720287323,46.27684449243063,1739137687.6309977,29.3299720287323,8.505074555045729,1739137687.6310012,29.3299720287323,2.8151725976793314,1739137687.6310043,29.3299720287323,2.6837239899541525,1739137687.6310074,29.3299720287323,0.6108,1739137687.6310108,29.3299720287323,0.8545341057571886,1739137687.6310143,29.3299720287323,0.0,1739137687.6310177,29.3299720287323,-0.0028814297973518872,1739137687.631021,29.3299720287323,2.1212270175224757,1739137687.6310244,29.3299720287323,0.869605513858913 +1739137687.649516,29.349972009658813,50.25137852231089,1739137687.6495192,29.349972009658813,7.159576367029505,1739137687.649523,29.349972009658813,57.630417192002206,1739137687.6495278,29.349972009658813,46.27684449243063,1739137687.6495304,29.349972009658813,8.505074555045729,1739137687.6495337,29.349972009658813,2.8151725976793314,1739137687.6495368,29.349972009658813,2.6837239899541525,1739137687.64954,29.349972009658813,0.6108,1739137687.6495428,29.349972009658813,0.8545341057571886,1739137687.649546,29.349972009658813,0.0,1739137687.649549,29.349972009658813,-0.01507140810172447,1739137687.649552,29.349972009658813,2.1212270175224757,1739137687.6495552,29.349972009658813,0.869605513858913 +1739137687.6708837,29.369971990585327,50.25137852231089,1739137687.6708868,29.369971990585327,7.159576367029505,1739137687.670891,29.369971990585327,57.630417192002206,1739137687.6708956,29.369971990585327,46.27684449243063,1739137687.6708982,29.369971990585327,8.505074555045729,1739137687.6709015,29.369971990585327,2.8151725976793314,1739137687.6709046,29.369971990585327,2.6837239899541525,1739137687.6709077,29.369971990585327,0.6108,1739137687.6709104,29.369971990585327,0.8545341057571886,1739137687.6709137,29.369971990585327,0.0,1739137687.6709168,29.369971990585327,-0.01507140810172447,1739137687.6709201,29.369971990585327,2.1212270175224757,1739137687.6709232,29.369971990585327,0.869605513858913 +1739137687.6903222,29.38997197151184,50.25137852231089,1739137687.6903253,29.38997197151184,7.159576367029505,1739137687.690329,29.38997197151184,57.630417192002206,1739137687.6903338,29.38997197151184,46.27684449243063,1739137687.6903365,29.38997197151184,8.505074555045729,1739137687.6903398,29.38997197151184,2.8151725976793314,1739137687.690343,29.38997197151184,2.6837239899541525,1739137687.690346,29.38997197151184,0.6108,1739137687.6903489,29.38997197151184,0.8545341057571886,1739137687.6903522,29.38997197151184,0.0,1739137687.690355,29.38997197151184,-0.01507140810172447,1739137687.6903582,29.38997197151184,2.1212270175224757,1739137687.6903613,29.38997197151184,0.869605513858913 +1739137687.7106788,29.409971952438354,50.25137852231089,1739137687.710682,29.409971952438354,7.159576367029505,1739137687.7106862,29.409971952438354,57.630417192002206,1739137687.710691,29.409971952438354,46.27684449243063,1739137687.710694,29.409971952438354,8.505074555045729,1739137687.710698,29.409971952438354,2.8151725976793314,1739137687.710701,29.409971952438354,2.6837239899541525,1739137687.7107043,29.409971952438354,0.6108,1739137687.7107077,29.409971952438354,0.8545341057571886,1739137687.7107112,29.409971952438354,0.0,1739137687.7107143,29.409971952438354,-0.01507140810172447,1739137687.710718,29.409971952438354,2.1212270175224757,1739137687.7107213,29.409971952438354,0.869605513858913 +1739137687.7306237,29.429971933364868,50.20036794315919,1739137687.730627,29.429971933364868,7.240404257608981,1739137687.730631,29.429971933364868,57.72896589038903,1739137687.730636,29.429971933364868,46.185960982307705,1739137687.7306383,29.429971933364868,8.481369375043819,1739137687.7306416,29.429971933364868,2.841782836062151,1739137687.7306447,29.429971933364868,2.684177489630888,1739137687.7306478,29.429971933364868,0.6108,1739137687.730651,29.429971933364868,0.8543791074396628,1739137687.730654,29.429971933364868,0.0,1739137687.730657,29.429971933364868,-0.01242542849176789,1739137687.7306602,29.429971933364868,2.1488322317233903,1739137687.730663,29.429971933364868,0.8680645268513068 +1739137687.7484705,29.449971914291382,50.20036794315919,1739137687.748473,29.449971914291382,7.240404257608981,1739137687.7484756,29.449971914291382,57.72896589038903,1739137687.7484782,29.449971914291382,46.185960982307705,1739137687.7484796,29.449971914291382,8.481369375043819,1739137687.7484813,29.449971914291382,2.841782836062151,1739137687.7484825,29.449971914291382,2.684177489630888,1739137687.748484,29.449971914291382,0.6108,1739137687.7484848,29.449971914291382,0.8543791074396628,1739137687.7484865,29.449971914291382,0.0,1739137687.7484877,29.449971914291382,-0.013685419411643918,1739137687.7484891,29.449971914291382,2.1488322317233903,1739137687.7484903,29.449971914291382,0.8680645268513068 +1739137687.7685385,29.469971895217896,50.20036794315919,1739137687.7685406,29.469971895217896,7.240404257608981,1739137687.7685435,29.469971895217896,57.72896589038903,1739137687.768546,29.469971895217896,46.185960982307705,1739137687.7685475,29.469971895217896,8.481369375043819,1739137687.7685492,29.469971895217896,2.841782836062151,1739137687.7685504,29.469971895217896,2.684177489630888,1739137687.7685516,29.469971895217896,0.6108,1739137687.768553,29.469971895217896,0.8543791074396628,1739137687.7685542,29.469971895217896,0.0,1739137687.7685554,29.469971895217896,-0.013685419411643918,1739137687.768557,29.469971895217896,2.1488322317233903,1739137687.7685583,29.469971895217896,0.8680645268513068 +1739137687.7885222,29.48997187614441,50.20036794315919,1739137687.7885244,29.48997187614441,7.240404257608981,1739137687.788527,29.48997187614441,57.72896589038903,1739137687.7885296,29.48997187614441,46.185960982307705,1739137687.7885308,29.48997187614441,8.481369375043819,1739137687.7885325,29.48997187614441,2.841782836062151,1739137687.788534,29.48997187614441,2.684177489630888,1739137687.7885354,29.48997187614441,0.6108,1739137687.7885368,29.48997187614441,0.8543791074396628,1739137687.7885382,29.48997187614441,0.0,1739137687.7885394,29.48997187614441,-0.013685419411643918,1739137687.7885406,29.48997187614441,2.1488322317233903,1739137687.788542,29.48997187614441,0.8680645268513068 +1739137687.8085535,29.509971857070923,50.20036794315919,1739137687.8085558,29.509971857070923,7.240404257608981,1739137687.8085587,29.509971857070923,57.72896589038903,1739137687.808561,29.509971857070923,46.185960982307705,1739137687.8085625,29.509971857070923,8.481369375043819,1739137687.808564,29.509971857070923,2.841782836062151,1739137687.8085656,29.509971857070923,2.684177489630888,1739137687.8085666,29.509971857070923,0.6108,1739137687.8085678,29.509971857070923,0.8543791074396628,1739137687.8085692,29.509971857070923,0.0,1739137687.8085704,29.509971857070923,-0.013685419411643918,1739137687.8085716,29.509971857070923,2.1488322317233903,1739137687.808573,29.509971857070923,0.8680645268513068 +1739137687.8285081,29.529971837997437,50.20036794315919,1739137687.828511,29.529971837997437,7.240404257608981,1739137687.8285139,29.529971837997437,57.72896589038903,1739137687.8285167,29.529971837997437,46.185960982307705,1739137687.8285177,29.529971837997437,8.481369375043819,1739137687.8285196,29.529971837997437,2.841782836062151,1739137687.828521,29.529971837997437,2.684177489630888,1739137687.8285222,29.529971837997437,0.6108,1739137687.8285236,29.529971837997437,0.8543791074396628,1739137687.828525,29.529971837997437,0.0,1739137687.8285263,29.529971837997437,-0.013685419411643918,1739137687.828528,29.529971837997437,2.1488322317233903,1739137687.8285291,29.529971837997437,0.8680645268513068 +1739137687.848488,29.54997181892395,50.14723881932111,1739137687.8484902,29.54997181892395,7.31965464764477,1739137687.8484929,29.54997181892395,57.876477680226635,1739137687.8484952,29.54997181892395,46.050197376132715,1739137687.8484967,29.54997181892395,8.436359371847539,1739137687.848498,29.54997181892395,2.8754928707188667,1739137687.8484998,29.54997181892395,2.7326024963521367,1739137687.848501,29.54997181892395,0.6108,1739137687.8485022,29.54997181892395,0.8379890321881255,1739137687.8485038,29.54997181892395,0.0,1739137687.848505,29.54997181892395,-0.042159098467555445,1739137687.8485067,29.54997181892395,2.176437445924305,1739137687.8485076,29.54997181892395,0.8665892290938879 +1739137687.8685386,29.569971799850464,50.14723881932111,1739137687.8685415,29.569971799850464,7.31965464764477,1739137687.8685443,29.569971799850464,57.876477680226635,1739137687.8685467,29.569971799850464,46.050197376132715,1739137687.8685482,29.569971799850464,8.436359371847539,1739137687.86855,29.569971799850464,2.8754928707188667,1739137687.8685515,29.569971799850464,2.7326024963521367,1739137687.8685527,29.569971799850464,0.6108,1739137687.8685539,29.569971799850464,0.8379890321881255,1739137687.8685553,29.569971799850464,0.0,1739137687.8685565,29.569971799850464,-0.02860019690576243,1739137687.8685582,29.569971799850464,2.176437445924305,1739137687.8685594,29.569971799850464,0.8665892290938879 +1739137687.8885055,29.589971780776978,50.14723881932111,1739137687.8885076,29.589971780776978,7.31965464764477,1739137687.8885102,29.589971780776978,57.876477680226635,1739137687.8885133,29.589971780776978,46.050197376132715,1739137687.8885145,29.589971780776978,8.436359371847539,1739137687.8885164,29.589971780776978,2.8754928707188667,1739137687.8885179,29.589971780776978,2.7326024963521367,1739137687.8885193,29.589971780776978,0.6108,1739137687.8885205,29.589971780776978,0.8379890321881255,1739137687.888522,29.589971780776978,0.0,1739137687.8885233,29.589971780776978,-0.02860019690576243,1739137687.8885248,29.589971780776978,2.176437445924305,1739137687.888526,29.589971780776978,0.8665892290938879 +1739137687.9084888,29.60997176170349,50.14723881932111,1739137687.908491,29.60997176170349,7.31965464764477,1739137687.9084938,29.60997176170349,57.876477680226635,1739137687.9084964,29.60997176170349,46.050197376132715,1739137687.9084978,29.60997176170349,8.436359371847539,1739137687.9084997,29.60997176170349,2.8754928707188667,1739137687.908501,29.60997176170349,2.7326024963521367,1739137687.9085023,29.60997176170349,0.6108,1739137687.9085035,29.60997176170349,0.8379890321881255,1739137687.9085052,29.60997176170349,0.0,1739137687.9085064,29.60997176170349,-0.02860019690576243,1739137687.9085078,29.60997176170349,2.176437445924305,1739137687.9085093,29.60997176170349,0.8665892290938879 +1739137687.928577,29.629971742630005,50.14723881932111,1739137687.9285798,29.629971742630005,7.31965464764477,1739137687.928583,29.629971742630005,57.876477680226635,1739137687.9285858,29.629971742630005,46.050197376132715,1739137687.928587,29.629971742630005,8.436359371847539,1739137687.9285886,29.629971742630005,2.8754928707188667,1739137687.92859,29.629971742630005,2.7326024963521367,1739137687.9285913,29.629971742630005,0.6108,1739137687.9285927,29.629971742630005,0.8379890321881255,1739137687.928594,29.629971742630005,0.0,1739137687.9285955,29.629971742630005,-0.02860019690576243,1739137687.928597,29.629971742630005,2.176437445924305,1739137687.9285982,29.629971742630005,0.8665892290938879 +1739137687.9486356,29.64997172355652,50.092090399979035,1739137687.948638,29.64997172355652,7.397201218498916,1739137687.9486413,29.64997172355652,57.97754129519696,1739137687.9486442,29.64997172355652,45.964612340344445,1739137687.9486456,29.64997172355652,8.404643884660572,1739137687.9486475,29.64997172355652,2.9021916808317787,1739137687.948649,29.64997172355652,2.7310351183970756,1739137687.9486501,29.64997172355652,0.6108,1739137687.9486516,29.64997172355652,0.8385145751300492,1739137687.9486532,29.64997172355652,0.0,1739137687.9486547,29.64997172355652,-0.02138097669622712,1739137687.948656,29.64997172355652,2.2040426601252197,1739137687.9486578,29.64997172355652,0.863333277452873 +1739137687.9697506,29.669971704483032,50.092090399979035,1739137687.9697535,29.669971704483032,7.397201218498916,1739137687.9697576,29.669971704483032,57.97754129519696,1739137687.9697607,29.669971704483032,45.964612340344445,1739137687.9697626,29.669971704483032,8.404643884660572,1739137687.9697647,29.669971704483032,2.9021916808317787,1739137687.9697664,29.669971704483032,2.7310351183970756,1739137687.969768,29.669971704483032,0.6108,1739137687.9697695,29.669971704483032,0.8385145751300492,1739137687.9697716,29.669971704483032,0.0,1739137687.9697733,29.669971704483032,-0.024818702322823794,1739137687.9697752,29.669971704483032,2.2040426601252197,1739137687.9697769,29.669971704483032,0.863333277452873 +1739137687.9891162,29.689971685409546,50.092090399979035,1739137687.9891195,29.689971685409546,7.397201218498916,1739137687.989123,29.689971685409546,57.97754129519696,1739137687.9891267,29.689971685409546,45.964612340344445,1739137687.989128,29.689971685409546,8.404643884660572,1739137687.9891303,29.689971685409546,2.9021916808317787,1739137687.989132,29.689971685409546,2.7310351183970756,1739137687.9891336,29.689971685409546,0.6108,1739137687.989135,29.689971685409546,0.8385145751300492,1739137687.989137,29.689971685409546,0.0,1739137687.9891386,29.689971685409546,-0.024818702322823794,1739137687.989141,29.689971685409546,2.2040426601252197,1739137687.9891424,29.689971685409546,0.863333277452873 +1739137688.0090837,29.70997166633606,50.092090399979035,1739137688.0090864,29.70997166633606,7.397201218498916,1739137688.00909,29.70997166633606,57.97754129519696,1739137688.0090935,29.70997166633606,45.964612340344445,1739137688.0090952,29.70997166633606,8.404643884660572,1739137688.0090976,29.70997166633606,2.9021916808317787,1739137688.0090992,29.70997166633606,2.7310351183970756,1739137688.009101,29.70997166633606,0.6108,1739137688.0091023,29.70997166633606,0.8385145751300492,1739137688.0091045,29.70997166633606,0.0,1739137688.0091062,29.70997166633606,-0.024818702322823794,1739137688.0091083,29.70997166633606,2.2040426601252197,1739137688.0091097,29.70997166633606,0.863333277452873 +1739137688.0326374,29.729971647262573,50.092090399979035,1739137688.0326424,29.729971647262573,7.397201218498916,1739137688.032648,29.729971647262573,57.97754129519696,1739137688.032655,29.729971647262573,45.964612340344445,1739137688.032659,29.729971647262573,8.404643884660572,1739137688.0326638,29.729971647262573,2.9021916808317787,1739137688.0326679,29.729971647262573,2.7310351183970756,1739137688.0326722,29.729971647262573,0.6108,1739137688.0326767,29.729971647262573,0.8385145751300492,1739137688.0326815,29.729971647262573,0.0,1739137688.0326858,29.729971647262573,-0.024818702322823794,1739137688.0326905,29.729971647262573,2.2040426601252197,1739137688.0326948,29.729971647262573,0.863333277452873 +1739137688.0492556,29.749971628189087,50.092090399979035,1739137688.0492601,29.749971628189087,7.397201218498916,1739137688.0492656,29.749971628189087,57.97754129519696,1739137688.049272,29.749971628189087,45.964612340344445,1739137688.0492754,29.749971628189087,8.404643884660572,1739137688.0492795,29.749971628189087,2.9021916808317787,1739137688.0492833,29.749971628189087,2.7310351183970756,1739137688.0492873,29.749971628189087,0.6108,1739137688.0492914,29.749971628189087,0.8385145751300492,1739137688.0492952,29.749971628189087,0.0,1739137688.049299,29.749971628189087,-0.024818702322823794,1739137688.0493033,29.749971628189087,2.2040426601252197,1739137688.049307,29.749971628189087,0.863333277452873 +1739137688.0690186,29.7699716091156,50.0350167428955,1739137688.0690215,29.7699716091156,7.472938115173475,1739137688.0690246,29.7699716091156,58.063068279595306,1739137688.0690274,29.7699716091156,45.893078417404105,1739137688.0690289,29.7699716091156,8.374645787943658,1739137688.0690308,29.7699716091156,2.9272354488243235,1739137688.0690322,29.7699716091156,2.7164768537545982,1739137688.0690336,29.7699716091156,0.6108,1739137688.069035,29.7699716091156,0.8434117469924232,1739137688.0690367,29.7699716091156,0.0,1739137688.0690382,29.7699716091156,-0.010405534203001176,1739137688.0690396,29.7699716091156,2.2316478743261343,1739137688.0690413,29.7699716091156,0.8606806980143926 +1739137688.0925899,29.789971590042114,50.0350167428955,1739137688.0925963,29.789971590042114,7.472938115173475,1739137688.0926034,29.789971590042114,58.063068279595306,1739137688.0926106,29.789971590042114,45.893078417404105,1739137688.0926137,29.789971590042114,8.374645787943658,1739137688.0926178,29.789971590042114,2.9272354488243235,1739137688.0926213,29.789971590042114,2.7164768537545982,1739137688.0926247,29.789971590042114,0.6108,1739137688.0926278,29.789971590042114,0.8434117469924232,1739137688.0926313,29.789971590042114,0.0,1739137688.0926347,29.789971590042114,-0.01726895102196946,1739137688.0926383,29.789971590042114,2.2316478743261343,1739137688.0926414,29.789971590042114,0.8606806980143926 +1739137688.1136377,29.809971570968628,50.0350167428955,1739137688.113643,29.809971570968628,7.472938115173475,1739137688.11365,29.809971570968628,58.063068279595306,1739137688.1136587,29.809971570968628,45.893078417404105,1739137688.1136632,29.809971570968628,8.374645787943658,1739137688.1136694,29.809971570968628,2.9272354488243235,1739137688.1136746,29.809971570968628,2.7164768537545982,1739137688.1136801,29.809971570968628,0.6108,1739137688.1136856,29.809971570968628,0.8434117469924232,1739137688.1136909,29.809971570968628,0.0,1739137688.1136963,29.809971570968628,-0.01726895102196946,1739137688.1137018,29.809971570968628,2.2316478743261343,1739137688.1137075,29.809971570968628,0.8606806980143926 +1739137688.129032,29.82997155189514,50.0350167428955,1739137688.129035,29.82997155189514,7.472938115173475,1739137688.129038,29.82997155189514,58.063068279595306,1739137688.1290412,29.82997155189514,45.893078417404105,1739137688.1290424,29.82997155189514,8.374645787943658,1739137688.1290443,29.82997155189514,2.9272354488243235,1739137688.1290457,29.82997155189514,2.7164768537545982,1739137688.1290472,29.82997155189514,0.6108,1739137688.1290483,29.82997155189514,0.8434117469924232,1739137688.1290498,29.82997155189514,0.0,1739137688.1290514,29.82997155189514,-0.01726895102196946,1739137688.1290529,29.82997155189514,2.2316478743261343,1739137688.1290543,29.82997155189514,0.8606806980143926 +1739137688.1492295,29.849971532821655,50.0350167428955,1739137688.1492324,29.849971532821655,7.472938115173475,1739137688.1492357,29.849971532821655,58.063068279595306,1739137688.1492383,29.849971532821655,45.893078417404105,1739137688.1492398,29.849971532821655,8.374645787943658,1739137688.1492417,29.849971532821655,2.9272354488243235,1739137688.1492429,29.849971532821655,2.7164768537545982,1739137688.149245,29.849971532821655,0.6108,1739137688.149246,29.849971532821655,0.8434117469924232,1739137688.1492474,29.849971532821655,0.0,1739137688.1492488,29.849971532821655,-0.01726895102196946,1739137688.1492503,29.849971532821655,2.2316478743261343,1739137688.149252,29.849971532821655,0.8606806980143926 +1739137688.1697028,29.86997151374817,49.97603169717384,1739137688.1697052,29.86997151374817,7.5468732593135215,1739137688.1697085,29.86997151374817,58.15016830689908,1739137688.169711,29.86997151374817,45.818015808048386,1739137688.1697125,29.86997151374817,8.34262227530314,1739137688.1697145,29.86997151374817,2.952501926145435,1739137688.1697156,29.86997151374817,2.7053577820332406,1739137688.1697173,29.86997151374817,0.6108,1739137688.1697183,29.86997151374817,0.8471712835886049,1739137688.1697206,29.86997151374817,0.0,1739137688.1697218,29.86997151374817,-0.006598111039511512,1739137688.169723,29.86997151374817,2.259253088527049,1739137688.1697247,29.86997151374817,0.8588507495390743 +1739137688.1886818,29.889971494674683,49.97603169717384,1739137688.1886847,29.889971494674683,7.5468732593135215,1739137688.1886878,29.889971494674683,58.15016830689908,1739137688.1886904,29.889971494674683,45.818015808048386,1739137688.1886919,29.889971494674683,8.34262227530314,1739137688.1886938,29.889971494674683,2.952501926145435,1739137688.1886952,29.889971494674683,2.7053577820332406,1739137688.1886969,29.889971494674683,0.6108,1739137688.1886983,29.889971494674683,0.8471712835886049,1739137688.1887,29.889971494674683,0.0,1739137688.1887012,29.889971494674683,-0.011679465950469314,1739137688.1887023,29.889971494674683,2.259253088527049,1739137688.1887043,29.889971494674683,0.8588507495390743 +1739137688.2088003,29.909971475601196,49.97603169717384,1739137688.2088032,29.909971475601196,7.5468732593135215,1739137688.208807,29.909971475601196,58.15016830689908,1739137688.20881,29.909971475601196,45.818015808048386,1739137688.2088118,29.909971475601196,8.34262227530314,1739137688.208814,29.909971475601196,2.952501926145435,1739137688.2088153,29.909971475601196,2.7053577820332406,1739137688.2088165,29.909971475601196,0.6108,1739137688.2088182,29.909971475601196,0.8471712835886049,1739137688.2088203,29.909971475601196,0.0,1739137688.2088215,29.909971475601196,-0.011679465950469314,1739137688.208823,29.909971475601196,2.259253088527049,1739137688.2088246,29.909971475601196,0.8588507495390743 +1739137688.228927,29.92997145652771,49.97603169717384,1739137688.2289295,29.92997145652771,7.5468732593135215,1739137688.2289326,29.92997145652771,58.15016830689908,1739137688.2289355,29.92997145652771,45.818015808048386,1739137688.2289367,29.92997145652771,8.34262227530314,1739137688.2289386,29.92997145652771,2.952501926145435,1739137688.22894,29.92997145652771,2.7053577820332406,1739137688.2289412,29.92997145652771,0.6108,1739137688.2289429,29.92997145652771,0.8471712835886049,1739137688.2289443,29.92997145652771,0.0,1739137688.228946,29.92997145652771,-0.011679465950469314,1739137688.2289474,29.92997145652771,2.259253088527049,1739137688.2289488,29.92997145652771,0.8588507495390743 +1739137688.2488346,29.949971437454224,49.97603169717384,1739137688.2488387,29.949971437454224,7.5468732593135215,1739137688.2488434,29.949971437454224,58.15016830689908,1739137688.248848,29.949971437454224,45.818015808048386,1739137688.2488503,29.949971437454224,8.34262227530314,1739137688.248853,29.949971437454224,2.952501926145435,1739137688.2488556,29.949971437454224,2.7053577820332406,1739137688.2488573,29.949971437454224,0.6108,1739137688.2488594,29.949971437454224,0.8471712835886049,1739137688.2488618,29.949971437454224,0.0,1739137688.2488637,29.949971437454224,-0.011679465950469314,1739137688.248866,29.949971437454224,2.259253088527049,1739137688.2488687,29.949971437454224,0.8588507495390743 +1739137688.2692854,29.969971418380737,49.97603169717384,1739137688.2692878,29.969971418380737,7.5468732593135215,1739137688.2692912,29.969971418380737,58.15016830689908,1739137688.2692943,29.969971418380737,45.818015808048386,1739137688.269296,29.969971418380737,8.34262227530314,1739137688.2692974,29.969971418380737,2.952501926145435,1739137688.269299,29.969971418380737,2.7053577820332406,1739137688.2693005,29.969971418380737,0.6108,1739137688.2693021,29.969971418380737,0.8471712835886049,1739137688.2693038,29.969971418380737,0.0,1739137688.269305,29.969971418380737,-0.011679465950469314,1739137688.2693067,29.969971418380737,2.259253088527049,1739137688.2693079,29.969971418380737,0.8588507495390743 +1739137688.2887547,29.98997139930725,49.91513487542911,1739137688.2887576,29.98997139930725,7.619025753536224,1739137688.2887607,29.98997139930725,58.23349916033809,1739137688.2887633,29.98997139930725,45.74526798687405,1739137688.288765,29.98997139930725,8.309863783256125,1739137688.2887666,29.98997139930725,2.9774100852564858,1739137688.2887683,29.98997139930725,2.692254094272802,1739137688.2887695,29.98997139930725,0.6108,1739137688.288771,29.98997139930725,0.8516233683334878,1739137688.2887723,29.98997139930725,0.0,1739137688.2887733,29.98997139930725,-0.000928340306895932,1739137688.288775,29.98997139930725,2.2868583027279636,1739137688.2887762,29.98997139930725,0.8576712948376376 +1739137688.3087022,30.009971380233765,49.91513487542911,1739137688.3087053,30.009971380233765,7.619025753536224,1739137688.3087084,30.009971380233765,58.23349916033809,1739137688.3087118,30.009971380233765,45.74526798687405,1739137688.3087132,30.009971380233765,8.309863783256125,1739137688.308715,30.009971380233765,2.9774100852564858,1739137688.3087168,30.009971380233765,2.692254094272802,1739137688.3087184,30.009971380233765,0.6108,1739137688.3087199,30.009971380233765,0.8516233683334878,1739137688.3087213,30.009971380233765,0.0,1739137688.3087234,30.009971380233765,-0.006047926504149759,1739137688.3087254,30.009971380233765,2.2868583027279636,1739137688.3087268,30.009971380233765,0.8576712948376376 +1739137688.3289,30.02997136116028,49.91513487542911,1739137688.3289027,30.02997136116028,7.619025753536224,1739137688.3289058,30.02997136116028,58.23349916033809,1739137688.3289084,30.02997136116028,45.74526798687405,1739137688.3289099,30.02997136116028,8.309863783256125,1739137688.3289118,30.02997136116028,2.9774100852564858,1739137688.3289132,30.02997136116028,2.692254094272802,1739137688.3289144,30.02997136116028,0.6108,1739137688.3289156,30.02997136116028,0.8516233683334878,1739137688.3289175,30.02997136116028,0.0,1739137688.3289187,30.02997136116028,-0.006047926504149759,1739137688.3289201,30.02997136116028,2.2868583027279636,1739137688.3289213,30.02997136116028,0.8576712948376376 +1739137688.3486598,30.049971342086792,49.91513487542911,1739137688.3486626,30.049971342086792,7.619025753536224,1739137688.348666,30.049971342086792,58.23349916033809,1739137688.3486686,30.049971342086792,45.74526798687405,1739137688.34867,30.049971342086792,8.309863783256125,1739137688.3486717,30.049971342086792,2.9774100852564858,1739137688.3486733,30.049971342086792,2.692254094272802,1739137688.3486748,30.049971342086792,0.6108,1739137688.3486762,30.049971342086792,0.8516233683334878,1739137688.3486779,30.049971342086792,0.0,1739137688.348679,30.049971342086792,-0.006047926504149759,1739137688.3486807,30.049971342086792,2.2868583027279636,1739137688.3486822,30.049971342086792,0.8576712948376376 +1739137688.368677,30.069971323013306,49.91513487542911,1739137688.3686798,30.069971323013306,7.619025753536224,1739137688.3686836,30.069971323013306,58.23349916033809,1739137688.368687,30.069971323013306,45.74526798687405,1739137688.368688,30.069971323013306,8.309863783256125,1739137688.36869,30.069971323013306,2.9774100852564858,1739137688.3686914,30.069971323013306,2.692254094272802,1739137688.3686926,30.069971323013306,0.6108,1739137688.368694,30.069971323013306,0.8516233683334878,1739137688.3686955,30.069971323013306,0.0,1739137688.368697,30.069971323013306,-0.006047926504149759,1739137688.3686984,30.069971323013306,2.2868583027279636,1739137688.3686996,30.069971323013306,0.8576712948376376 +1739137688.3889577,30.08997130393982,49.85233972269201,1739137688.388961,30.08997130393982,7.689391227157039,1739137688.3889644,30.08997130393982,58.23508194721262,1739137688.3889675,30.08997130393982,45.74550871516724,1739137688.388969,30.08997130393982,8.309977812447638,1739137688.388971,30.08997130393982,2.9916165106577477,1739137688.3889728,30.08997130393982,2.6024582432205112,1739137688.3889744,30.08997130393982,0.6108,1739137688.3889759,30.08997130393982,0.8827682543637678,1739137688.3889778,30.08997130393982,0.0,1739137688.3889792,30.08997130393982,0.05458725576018303,1739137688.388981,30.08997130393982,2.3144635169288783,1739137688.3889825,30.08997130393982,0.8570549093437136 +1739137688.4089298,30.109971284866333,49.85233972269201,1739137688.408933,30.109971284866333,7.689391227157039,1739137688.4089363,30.109971284866333,58.23508194721262,1739137688.4089394,30.109971284866333,45.74550871516724,1739137688.408941,30.109971284866333,8.309977812447638,1739137688.408943,30.109971284866333,2.9916165106577477,1739137688.4089444,30.109971284866333,2.6024582432205112,1739137688.408946,30.109971284866333,0.6108,1739137688.4089475,30.109971284866333,0.8827682543637678,1739137688.408949,30.109971284866333,0.0,1739137688.4089506,30.109971284866333,0.02571334502005418,1739137688.4089522,30.109971284866333,2.3144635169288783,1739137688.408954,30.109971284866333,0.8570549093437136 +1739137688.4293044,30.129971265792847,49.85233972269201,1739137688.4293072,30.129971265792847,7.689391227157039,1739137688.4293106,30.129971265792847,58.23508194721262,1739137688.4293132,30.129971265792847,45.74550871516724,1739137688.4293149,30.129971265792847,8.309977812447638,1739137688.4293168,30.129971265792847,2.9916165106577477,1739137688.4293187,30.129971265792847,2.6024582432205112,1739137688.42932,30.129971265792847,0.6108,1739137688.4293218,30.129971265792847,0.8827682543637678,1739137688.4293234,30.129971265792847,0.0,1739137688.429325,30.129971265792847,0.02571334502005418,1739137688.4293265,30.129971265792847,2.3144635169288783,1739137688.4293282,30.129971265792847,0.8570549093437136 +1739137688.4655054,30.14997124671936,49.85233972269201,1739137688.4655125,30.14997124671936,7.689391227157039,1739137688.4655204,30.14997124671936,58.23508194721262,1739137688.4655282,30.14997124671936,45.74550871516724,1739137688.4655316,30.14997124671936,8.309977812447638,1739137688.465536,30.14997124671936,2.9916165106577477,1739137688.46554,30.14997124671936,2.6024582432205112,1739137688.4655437,30.14997124671936,0.6108,1739137688.465547,30.14997124671936,0.8827682543637678,1739137688.4655514,30.14997124671936,0.0,1739137688.4655547,30.14997124671936,0.02571334502005418,1739137688.4655592,30.14997124671936,2.3144635169288783,1739137688.4655626,30.14997124671936,0.8570549093437136 +1739137688.4951522,30.189971208572388,49.85233972269201,1739137688.495156,30.189971208572388,7.689391227157039,1739137688.4951596,30.189971208572388,58.23508194721262,1739137688.495163,30.189971208572388,45.74550871516724,1739137688.4951644,30.189971208572388,8.309977812447638,1739137688.4951668,30.189971208572388,2.9916165106577477,1739137688.4951687,30.189971208572388,2.6024582432205112,1739137688.4951706,30.189971208572388,0.6108,1739137688.495172,30.189971208572388,0.8827682543637678,1739137688.4951742,30.189971208572388,0.0,1739137688.4951756,30.189971208572388,0.02571334502005418,1739137688.4951777,30.189971208572388,2.3144635169288783,1739137688.4951794,30.189971208572388,0.8570549093437136 +1739137688.5152729,30.2099711894989,49.78751711862978,1739137688.5152762,30.2099711894989,7.75811098106986,1739137688.5152798,30.2099711894989,58.46304392568513,1739137688.5152838,30.2099711894989,45.53237162530983,1739137688.5152857,30.2099711894989,8.20380574523293,1739137688.5152879,30.2099711894989,3.0372306512371994,1739137688.5152895,30.2099711894989,2.7403721077597423,1739137688.5152915,30.2099711894989,0.6108,1739137688.5152931,30.2099711894989,0.8353887352828067,1739137688.515295,30.2099711894989,0.0,1739137688.5152967,30.2099711894989,-0.07121565773574198,1739137688.5152988,30.2099711894989,2.342068731129793,1739137688.5153003,30.2099711894989,0.8604477019823144 +1739137688.5383458,30.229971170425415,49.78751711862978,1739137688.5383508,30.229971170425415,7.75811098106986,1739137688.5383582,30.229971170425415,58.46304392568513,1739137688.5383663,30.229971170425415,45.53237162530983,1739137688.5383708,30.229971170425415,8.20380574523293,1739137688.538376,30.229971170425415,3.0372306512371994,1739137688.5383816,30.229971170425415,2.7403721077597423,1739137688.5383878,30.229971170425415,0.6108,1739137688.5383923,30.229971170425415,0.8353887352828067,1739137688.538398,30.229971170425415,0.0,1739137688.5384033,30.229971170425415,-0.02505896669950769,1739137688.5384083,30.229971170425415,2.342068731129793,1739137688.5384128,30.229971170425415,0.8604477019823144 +1739137688.5552175,30.24997115135193,49.78751711862978,1739137688.5552204,30.24997115135193,7.75811098106986,1739137688.5552244,30.24997115135193,58.46304392568513,1739137688.5552282,30.24997115135193,45.53237162530983,1739137688.5552301,30.24997115135193,8.20380574523293,1739137688.5552325,30.24997115135193,3.0372306512371994,1739137688.555234,30.24997115135193,2.7403721077597423,1739137688.5552359,30.24997115135193,0.6108,1739137688.5552373,30.24997115135193,0.8353887352828067,1739137688.5552397,30.24997115135193,0.0,1739137688.5552416,30.24997115135193,-0.02505896669950769,1739137688.5552435,30.24997115135193,2.342068731129793,1739137688.5552452,30.24997115135193,0.8604477019823144 +1739137688.5793777,30.269971132278442,49.78751711862978,1739137688.579385,30.269971132278442,7.75811098106986,1739137688.579394,30.269971132278442,58.46304392568513,1739137688.579404,30.269971132278442,45.53237162530983,1739137688.5794098,30.269971132278442,8.20380574523293,1739137688.5794177,30.269971132278442,3.0372306512371994,1739137688.5794241,30.269971132278442,2.7403721077597423,1739137688.5794296,30.269971132278442,0.6108,1739137688.579436,30.269971132278442,0.8353887352828067,1739137688.5794427,30.269971132278442,0.0,1739137688.5794485,30.269971132278442,-0.02505896669950769,1739137688.5794554,30.269971132278442,2.342068731129793,1739137688.5794618,30.269971132278442,0.8604477019823144 +1739137688.5950103,30.289971113204956,49.78751711862978,1739137688.5950131,30.289971113204956,7.75811098106986,1739137688.595017,30.289971113204956,58.46304392568513,1739137688.5950205,30.289971113204956,45.53237162530983,1739137688.595022,30.289971113204956,8.20380574523293,1739137688.5950243,30.289971113204956,3.0372306512371994,1739137688.5950263,30.289971113204956,2.7403721077597423,1739137688.595028,30.289971113204956,0.6108,1739137688.5950296,30.289971113204956,0.8353887352828067,1739137688.5950315,30.289971113204956,0.0,1739137688.5950332,30.289971113204956,-0.02505896669950769,1739137688.595035,30.289971113204956,2.342068731129793,1739137688.595037,30.289971113204956,0.8604477019823144 +1739137688.618156,30.30997109413147,49.7208151872925,1739137688.6181614,30.30997109413147,7.825024978674989,1739137688.6181679,30.30997109413147,58.47439746245241,1739137688.6181753,30.30997109413147,45.5307308117066,1739137688.6181793,30.30997109413147,8.202920569473294,1739137688.6181848,30.30997109413147,3.051647931277607,1739137688.6181898,30.30997109413147,2.6518416625381778,1739137688.6181946,30.30997109413147,0.6108,1739137688.6181998,30.30997109413147,0.8655017060967086,1739137688.6182046,30.30997109413147,0.0,1739137688.6182098,30.30997109413147,0.03846803360878115,1739137688.6182146,30.30997109413147,2.3696739453307076,1739137688.6182196,30.30997109413147,0.857284640127364 +1739137688.635758,30.329971075057983,49.7208151872925,1739137688.6357608,30.329971075057983,7.825024978674989,1739137688.6357646,30.329971075057983,58.47439746245241,1739137688.6357684,30.329971075057983,45.5307308117066,1739137688.6357698,30.329971075057983,8.202920569473294,1739137688.6357722,30.329971075057983,3.051647931277607,1739137688.635774,30.329971075057983,2.6518416625381778,1739137688.6357756,30.329971075057983,0.6108,1739137688.635777,30.329971075057983,0.8655017060967086,1739137688.6357791,30.329971075057983,0.0,1739137688.6357808,30.329971075057983,0.008217065969344572,1739137688.635783,30.329971075057983,2.3696739453307076,1739137688.6357844,30.329971075057983,0.857284640127364 +1739137688.6588204,30.349971055984497,49.7208151872925,1739137688.6588252,30.349971055984497,7.825024978674989,1739137688.6588316,30.349971055984497,58.47439746245241,1739137688.6588387,30.349971055984497,45.5307308117066,1739137688.6588428,30.349971055984497,8.202920569473294,1739137688.658848,30.349971055984497,3.051647931277607,1739137688.6588526,30.349971055984497,2.6518416625381778,1739137688.6588576,30.349971055984497,0.6108,1739137688.6588619,30.349971055984497,0.8655017060967086,1739137688.658867,30.349971055984497,0.0,1739137688.6588717,30.349971055984497,0.008217065969344572,1739137688.6588764,30.349971055984497,2.3696739453307076,1739137688.658881,30.349971055984497,0.857284640127364 +1739137688.6770263,30.36997103691101,49.7208151872925,1739137688.6770306,30.36997103691101,7.825024978674989,1739137688.6770358,30.36997103691101,58.47439746245241,1739137688.6770408,30.36997103691101,45.5307308117066,1739137688.677044,30.36997103691101,8.202920569473294,1739137688.677048,30.36997103691101,3.051647931277607,1739137688.677052,30.36997103691101,2.6518416625381778,1739137688.6770556,30.36997103691101,0.6108,1739137688.677059,30.36997103691101,0.8655017060967086,1739137688.6770627,30.36997103691101,0.0,1739137688.677066,30.36997103691101,0.008217065969344572,1739137688.6770697,30.36997103691101,2.3696739453307076,1739137688.6770735,30.36997103691101,0.857284640127364 +1739137688.696614,30.389971017837524,49.7208151872925,1739137688.6966183,30.389971017837524,7.825024978674989,1739137688.696624,30.389971017837524,58.47439746245241,1739137688.6966298,30.389971017837524,45.5307308117066,1739137688.6966329,30.389971017837524,8.202920569473294,1739137688.6966372,30.389971017837524,3.051647931277607,1739137688.6966405,30.389971017837524,2.6518416625381778,1739137688.696644,30.389971017837524,0.6108,1739137688.696648,30.389971017837524,0.8655017060967086,1739137688.6966515,30.389971017837524,0.0,1739137688.6966548,30.389971017837524,0.008217065969344572,1739137688.6966584,30.389971017837524,2.3696739453307076,1739137688.696662,30.389971017837524,0.857284640127364 +1739137688.7172155,30.409970998764038,49.7208151872925,1739137688.7172194,30.409970998764038,7.825024978674989,1739137688.7172418,30.409970998764038,58.47439746245241,1739137688.7172472,30.409970998764038,45.5307308117066,1739137688.7172716,30.409970998764038,8.202920569473294,1739137688.7172756,30.409970998764038,3.051647931277607,1739137688.717279,30.409970998764038,2.6518416625381778,1739137688.7172992,30.409970998764038,0.6108,1739137688.7173026,30.409970998764038,0.8655017060967086,1739137688.717306,30.409970998764038,0.0,1739137688.717309,30.409970998764038,0.008217065969344572,1739137688.7173126,30.409970998764038,2.3696739453307076,1739137688.717316,30.409970998764038,0.857284640127364 +1739137688.735186,30.42997097969055,49.65234899266343,1739137688.7351892,30.42997097969055,7.890016381677933,1739137688.7351923,30.42997097969055,58.59123725140011,1739137688.735195,30.42997097969055,45.42453518797941,1739137688.735196,30.42997097969055,8.144226841108194,1739137688.735198,30.42997097969055,3.0815368475927563,1739137688.7351995,30.42997097969055,2.6772190639038307,1739137688.7352011,30.42997097969055,0.6108,1739137688.735202,30.42997097969055,0.856760473438697,1739137688.7352035,30.42997097969055,0.0,1739137688.7352047,30.42997097969055,-0.011338240988176143,1739137688.7352061,30.42997097969055,2.3972791595316223,1739137688.7352073,30.42997097969055,0.8587866588429418 +1739137688.7557979,30.449970960617065,49.65234899266343,1739137688.7558,30.449970960617065,7.890016381677933,1739137688.7558029,30.449970960617065,58.59123725140011,1739137688.7558055,30.449970960617065,45.42453518797941,1739137688.7558067,30.449970960617065,8.144226841108194,1739137688.7558086,30.449970960617065,3.0815368475927563,1739137688.7558098,30.449970960617065,2.6772190639038307,1739137688.755811,30.449970960617065,0.6108,1739137688.7558124,30.449970960617065,0.856760473438697,1739137688.7558136,30.449970960617065,0.0,1739137688.755815,30.449970960617065,-0.002026185404244818,1739137688.7558162,30.449970960617065,2.3972791595316223,1739137688.7558174,30.449970960617065,0.8587866588429418 +1739137688.7747319,30.46997094154358,49.65234899266343,1739137688.774734,30.46997094154358,7.890016381677933,1739137688.7747366,30.46997094154358,58.59123725140011,1739137688.7747393,30.46997094154358,45.42453518797941,1739137688.7747405,30.46997094154358,8.144226841108194,1739137688.7747421,30.46997094154358,3.0815368475927563,1739137688.7747433,30.46997094154358,2.6772190639038307,1739137688.7747445,30.46997094154358,0.6108,1739137688.774746,30.46997094154358,0.856760473438697,1739137688.7747474,30.46997094154358,0.0,1739137688.7747483,30.46997094154358,-0.002026185404244818,1739137688.77475,30.46997094154358,2.3972791595316223,1739137688.7747512,30.46997094154358,0.8587866588429418 +1739137688.7942386,30.489970922470093,49.65234899266343,1739137688.7942407,30.489970922470093,7.890016381677933,1739137688.7942433,30.489970922470093,58.59123725140011,1739137688.7942464,30.489970922470093,45.42453518797941,1739137688.7942476,30.489970922470093,8.144226841108194,1739137688.7942495,30.489970922470093,3.0815368475927563,1739137688.7942507,30.489970922470093,2.6772190639038307,1739137688.794252,30.489970922470093,0.6108,1739137688.7942533,30.489970922470093,0.856760473438697,1739137688.7942548,30.489970922470093,0.0,1739137688.7942562,30.489970922470093,-0.002026185404244818,1739137688.7942574,30.489970922470093,2.3972791595316223,1739137688.7942586,30.489970922470093,0.8587866588429418 +1739137688.8142285,30.509970903396606,49.65234899266343,1739137688.8142307,30.509970903396606,7.890016381677933,1739137688.8142333,30.509970903396606,58.59123725140011,1739137688.8142362,30.509970903396606,45.42453518797941,1739137688.814237,30.509970903396606,8.144226841108194,1739137688.814239,30.509970903396606,3.0815368475927563,1739137688.8142402,30.509970903396606,2.6772190639038307,1739137688.8142416,30.509970903396606,0.6108,1739137688.8142428,30.509970903396606,0.856760473438697,1739137688.814244,30.509970903396606,0.0,1739137688.8142455,30.509970903396606,-0.002026185404244818,1739137688.814247,30.509970903396606,2.3972791595316223,1739137688.814248,30.509970903396606,0.8587866588429418 +1739137688.8342183,30.52997088432312,49.58208592736001,1739137688.8342202,30.52997088432312,7.953119971065927,1739137688.834223,30.52997088432312,58.75932626429677,1739137688.8342257,30.52997088432312,45.281102124429914,1739137688.8342268,30.52997088432312,8.05891857108566,1739137688.8342288,30.52997088432312,3.1169989156971107,1739137688.83423,30.52997088432312,2.7455744583351844,1739137688.8342311,30.52997088432312,0.6108,1739137688.8342323,30.52997088432312,0.8336521487487747,1739137688.8342338,30.52997088432312,0.0,1739137688.8342352,30.52997088432312,-0.04537988776226934,1739137688.8342364,30.52997088432312,2.424884373732537,1739137688.8342378,30.52997088432312,0.8583874060276613 +1739137688.8541405,30.549970865249634,49.58208592736001,1739137688.8541424,30.549970865249634,7.953119971065927,1739137688.854145,30.549970865249634,58.75932626429677,1739137688.8541481,30.549970865249634,45.281102124429914,1739137688.8541493,30.549970865249634,8.05891857108566,1739137688.854151,30.549970865249634,3.1169989156971107,1739137688.8541522,30.549970865249634,2.7455744583351844,1739137688.8541536,30.549970865249634,0.6108,1739137688.854155,30.549970865249634,0.8336521487487747,1739137688.8541563,30.549970865249634,0.0,1739137688.8541577,30.549970865249634,-0.02473525727888659,1739137688.854159,30.549970865249634,2.424884373732537,1739137688.8541603,30.549970865249634,0.8583874060276613 +1739137688.874182,30.569970846176147,49.58208592736001,1739137688.8741841,30.569970846176147,7.953119971065927,1739137688.874187,30.569970846176147,58.75932626429677,1739137688.87419,30.569970846176147,45.281102124429914,1739137688.8741913,30.569970846176147,8.05891857108566,1739137688.874193,30.569970846176147,3.1169989156971107,1739137688.8741944,30.569970846176147,2.7455744583351844,1739137688.8741958,30.569970846176147,0.6108,1739137688.874197,30.569970846176147,0.8336521487487747,1739137688.8741992,30.569970846176147,0.0,1739137688.8742003,30.569970846176147,-0.02473525727888659,1739137688.8742015,30.569970846176147,2.424884373732537,1739137688.8742032,30.569970846176147,0.8583874060276613 +1739137688.8941915,30.58997082710266,49.58208592736001,1739137688.894194,30.58997082710266,7.953119971065927,1739137688.8941967,30.58997082710266,58.75932626429677,1739137688.8941994,30.58997082710266,45.281102124429914,1739137688.8942006,30.58997082710266,8.05891857108566,1739137688.894202,30.58997082710266,3.1169989156971107,1739137688.8942037,30.58997082710266,2.7455744583351844,1739137688.8942049,30.58997082710266,0.6108,1739137688.8942063,30.58997082710266,0.8336521487487747,1739137688.8942077,30.58997082710266,0.0,1739137688.894209,30.58997082710266,-0.02473525727888659,1739137688.8942106,30.58997082710266,2.424884373732537,1739137688.8942118,30.58997082710266,0.8583874060276613 +1739137688.9141665,30.609970808029175,49.58208592736001,1739137688.9141686,30.609970808029175,7.953119971065927,1739137688.9141715,30.609970808029175,58.75932626429677,1739137688.9141738,30.609970808029175,45.281102124429914,1739137688.9141753,30.609970808029175,8.05891857108566,1739137688.914177,30.609970808029175,3.1169989156971107,1739137688.9141784,30.609970808029175,2.7455744583351844,1739137688.9141796,30.609970808029175,0.6108,1739137688.9141808,30.609970808029175,0.8336521487487747,1739137688.9141822,30.609970808029175,0.0,1739137688.9141834,30.609970808029175,-0.02473525727888659,1739137688.914185,30.609970808029175,2.424884373732537,1739137688.9141862,30.609970808029175,0.8583874060276613 +1739137688.934161,30.62997078895569,49.58208592736001,1739137688.9341636,30.62997078895569,7.953119971065927,1739137688.9341662,30.62997078895569,58.75932626429677,1739137688.9341688,30.62997078895569,45.281102124429914,1739137688.9341705,30.62997078895569,8.05891857108566,1739137688.9341722,30.62997078895569,3.1169989156971107,1739137688.9341736,30.62997078895569,2.7455744583351844,1739137688.9341753,30.62997078895569,0.6108,1739137688.9341764,30.62997078895569,0.8336521487487747,1739137688.934178,30.62997078895569,0.0,1739137688.934179,30.62997078895569,-0.02473525727888659,1739137688.9341805,30.62997078895569,2.424884373732537,1739137688.934182,30.62997078895569,0.8583874060276613 +1739137688.9541776,30.649970769882202,49.510257264947896,1739137688.9541798,30.649970769882202,8.014134057522634,1739137688.9541829,30.649970769882202,58.847246703018115,1739137688.9541855,30.649970769882202,45.21440556701427,1739137688.9541867,30.649970769882202,8.017438701395225,1739137688.9541883,30.649970769882202,3.140823389785291,1739137688.9541898,30.649970769882202,2.728945970749602,1739137688.9541912,30.649970769882202,0.6108,1739137688.9541924,30.649970769882202,0.8392155802907133,1739137688.9541936,30.649970769882202,0.0,1739137688.954195,30.649970769882202,-0.008153917843409004,1739137688.9541965,30.649970769882202,2.4524895879334516,1739137688.9541976,30.649970769882202,0.8552653780001153 +1739137688.9741957,30.669970750808716,49.510257264947896,1739137688.974198,30.669970750808716,8.014134057522634,1739137688.9742012,30.669970750808716,58.847246703018115,1739137688.9742036,30.669970750808716,45.21440556701427,1739137688.9742053,30.669970750808716,8.017438701395225,1739137688.9742067,30.669970750808716,3.140823389785291,1739137688.9742084,30.669970750808716,2.728945970749602,1739137688.9742095,30.669970750808716,0.6108,1739137688.9742107,30.669970750808716,0.8392155802907133,1739137688.9742124,30.669970750808716,0.0,1739137688.9742136,30.669970750808716,-0.01604979770940196,1739137688.974215,30.669970750808716,2.4524895879334516,1739137688.9742162,30.669970750808716,0.8552653780001153 +1739137688.9942045,30.68997073173523,49.510257264947896,1739137688.9942067,30.68997073173523,8.014134057522634,1739137688.9942093,30.68997073173523,58.847246703018115,1739137688.9942122,30.68997073173523,45.21440556701427,1739137688.9942133,30.68997073173523,8.017438701395225,1739137688.9942153,30.68997073173523,3.140823389785291,1739137688.9942164,30.68997073173523,2.728945970749602,1739137688.9942183,30.68997073173523,0.6108,1739137688.9942195,30.68997073173523,0.8392155802907133,1739137688.9942207,30.68997073173523,0.0,1739137688.9942222,30.68997073173523,-0.01604979770940196,1739137688.9942234,30.68997073173523,2.4524895879334516,1739137688.9942245,30.68997073173523,0.8552653780001153 +1739137689.01449,30.709970712661743,49.510257264947896,1739137689.0144928,30.709970712661743,8.014134057522634,1739137689.0144958,30.709970712661743,58.847246703018115,1739137689.0144985,30.709970712661743,45.21440556701427,1739137689.0145001,30.709970712661743,8.017438701395225,1739137689.0145018,30.709970712661743,3.140823389785291,1739137689.0145035,30.709970712661743,2.728945970749602,1739137689.014505,30.709970712661743,0.6108,1739137689.0145063,30.709970712661743,0.8392155802907133,1739137689.0145078,30.709970712661743,0.0,1739137689.014509,30.709970712661743,-0.01604979770940196,1739137689.0145109,30.709970712661743,2.4524895879334516,1739137689.014512,30.709970712661743,0.8552653780001153 +1739137689.0345037,30.729970693588257,49.510257264947896,1739137689.0345066,30.729970693588257,8.014134057522634,1739137689.03451,30.729970693588257,58.847246703018115,1739137689.0345132,30.729970693588257,45.21440556701427,1739137689.0345147,30.729970693588257,8.017438701395225,1739137689.0345166,30.729970693588257,3.140823389785291,1739137689.034518,30.729970693588257,2.728945970749602,1739137689.0345201,30.729970693588257,0.6108,1739137689.0345213,30.729970693588257,0.8392155802907133,1739137689.0345232,30.729970693588257,0.0,1739137689.034525,30.729970693588257,-0.01604979770940196,1739137689.0345268,30.729970693588257,2.4524895879334516,1739137689.0345283,30.729970693588257,0.8552653780001153 +1739137689.0543892,30.74997067451477,49.43696791318969,1739137689.0543919,30.74997067451477,8.072984451827974,1739137689.0543954,30.74997067451477,58.93562054353728,1739137689.0543985,30.74997067451477,45.145082752471914,1739137689.0544002,30.74997067451477,7.971234724891657,1739137689.0544024,30.74997067451477,-3.1178896263780485,1739137689.054404,30.74997067451477,2.716790675162695,1739137689.0544057,30.74997067451477,0.6108,1739137689.054407,30.74997067451477,0.8433058813723232,1739137689.054409,30.74997067451477,0.0,1739137689.0544105,30.74997067451477,-0.005020897461249423,1739137689.0544121,30.74997067451477,2.4800948021343663,1739137689.0544136,30.74997067451477,0.8535786387181311 +1739137689.074492,30.769970655441284,49.43696791318969,1739137689.0744948,30.769970655441284,8.072984451827974,1739137689.0745006,30.769970655441284,58.93562054353728,1739137689.0745084,30.769970655441284,45.145082752471914,1739137689.0745103,30.769970655441284,7.971234724891657,1739137689.0745127,30.769970655441284,-3.1178896263780485,1739137689.0745142,30.769970655441284,2.716790675162695,1739137689.0745158,30.769970655441284,0.6108,1739137689.0745173,30.769970655441284,0.8433058813723232,1739137689.0745194,30.769970655441284,0.0,1739137689.0745208,30.769970655441284,-0.010272757345807904,1739137689.0745227,30.769970655441284,2.4800948021343663,1739137689.0745242,30.769970655441284,0.8535786387181311 +1739137689.0943675,30.789970636367798,49.43696791318969,1739137689.0943701,30.789970636367798,8.072984451827974,1739137689.094374,30.789970636367798,58.93562054353728,1739137689.094377,30.789970636367798,45.145082752471914,1739137689.0943787,30.789970636367798,7.971234724891657,1739137689.0943806,30.789970636367798,-3.1178896263780485,1739137689.094382,30.789970636367798,2.716790675162695,1739137689.0943837,30.789970636367798,0.6108,1739137689.0943851,30.789970636367798,0.8433058813723232,1739137689.094387,30.789970636367798,0.0,1739137689.0943885,30.789970636367798,-0.010272757345807904,1739137689.0943902,30.789970636367798,2.4800948021343663,1739137689.0943918,30.789970636367798,0.8535786387181311 +1739137689.1143272,30.80997061729431,49.43696791318969,1739137689.1143298,30.80997061729431,8.072984451827974,1739137689.1143332,30.80997061729431,58.93562054353728,1739137689.1143363,30.80997061729431,45.145082752471914,1739137689.1143382,30.80997061729431,7.971234724891657,1739137689.11434,30.80997061729431,-3.1178896263780485,1739137689.1143417,30.80997061729431,2.716790675162695,1739137689.1143432,30.80997061729431,0.6108,1739137689.1143446,30.80997061729431,0.8433058813723232,1739137689.1143465,30.80997061729431,0.0,1739137689.114348,30.80997061729431,-0.010272757345807904,1739137689.1143496,30.80997061729431,2.4800948021343663,1739137689.114351,30.80997061729431,0.8535786387181311 +1739137689.1343858,30.829970598220825,49.43696791318969,1739137689.1343887,30.829970598220825,8.072984451827974,1739137689.134392,30.829970598220825,58.93562054353728,1739137689.1343951,30.829970598220825,45.145082752471914,1739137689.134397,30.829970598220825,7.971234724891657,1739137689.1343987,30.829970598220825,-3.1178896263780485,1739137689.1344008,30.829970598220825,2.716790675162695,1739137689.134402,30.829970598220825,0.6108,1739137689.1344035,30.829970598220825,0.8433058813723232,1739137689.1344054,30.829970598220825,0.0,1739137689.1344073,30.829970598220825,-0.010272757345807904,1739137689.1344087,30.829970598220825,2.4800948021343663,1739137689.1344101,30.829970598220825,0.8535786387181311 +1739137689.1543708,30.84997057914734,49.43696791318969,1739137689.1543734,30.84997057914734,8.072984451827974,1739137689.1543767,30.84997057914734,58.93562054353728,1739137689.1543798,30.84997057914734,45.145082752471914,1739137689.1543813,30.84997057914734,7.971234724891657,1739137689.1543834,30.84997057914734,-3.1178896263780485,1739137689.154385,30.84997057914734,2.716790675162695,1739137689.154387,30.84997057914734,0.6108,1739137689.1543884,30.84997057914734,0.8433058813723232,1739137689.1543903,30.84997057914734,0.0,1739137689.1543915,30.84997057914734,-0.010272757345807904,1739137689.1543934,30.84997057914734,2.4800948021343663,1739137689.1543949,30.84997057914734,0.8535786387181311 +1739137689.174361,30.869970560073853,49.36220058897294,1739137689.1743636,30.869970560073853,8.129699459472342,1739137689.174367,30.869970560073853,59.02460678476629,1739137689.17437,30.869970560073853,45.074396761416594,1739137689.1743715,30.869970560073853,7.922397700136424,1739137689.1743736,30.869970560073853,-3.0932834312146658,1739137689.1743758,30.869970560073853,2.706633498747824,1739137689.1743772,30.869970560073853,0.6108,1739137689.1743786,30.869970560073853,0.8467390936417354,1739137689.1743805,30.869970560073853,0.0,1739137689.174382,30.869970560073853,-0.0017676311059442512,1739137689.1743839,30.869970560073853,2.507700016335281,1739137689.1743853,30.869970560073853,0.8525567868850834 +1739137689.194362,30.889970541000366,49.36220058897294,1739137689.1943648,30.889970541000366,8.129699459472342,1739137689.1943684,30.889970541000366,59.02460678476629,1739137689.1943712,30.889970541000366,45.074396761416594,1739137689.1943731,30.889970541000366,7.922397700136424,1739137689.1943753,30.889970541000366,-3.0932834312146658,1739137689.1943767,30.889970541000366,2.706633498747824,1739137689.1943781,30.889970541000366,0.6108,1739137689.1943798,30.889970541000366,0.8467390936417354,1739137689.1943815,30.889970541000366,0.0,1739137689.1943831,30.889970541000366,-0.005817693243348021,1739137689.1943846,30.889970541000366,2.507700016335281,1739137689.1943862,30.889970541000366,0.8525567868850834 +1739137689.21436,30.90997052192688,49.36220058897294,1739137689.2143629,30.90997052192688,8.129699459472342,1739137689.2143664,30.90997052192688,59.02460678476629,1739137689.2143698,30.90997052192688,45.074396761416594,1739137689.2143714,30.90997052192688,7.922397700136424,1739137689.2143734,30.90997052192688,-3.0932834312146658,1739137689.214375,30.90997052192688,2.706633498747824,1739137689.2143764,30.90997052192688,0.6108,1739137689.2143779,30.90997052192688,0.8467390936417354,1739137689.2143798,30.90997052192688,0.0,1739137689.2143812,30.90997052192688,-0.005817693243348021,1739137689.2143831,30.90997052192688,2.507700016335281,1739137689.2143846,30.90997052192688,0.8525567868850834 +1739137689.2343998,30.929970502853394,49.36220058897294,1739137689.2344027,30.929970502853394,8.129699459472342,1739137689.2344055,30.929970502853394,59.02460678476629,1739137689.2344089,30.929970502853394,45.074396761416594,1739137689.2344105,30.929970502853394,7.922397700136424,1739137689.2344124,30.929970502853394,-3.0932834312146658,1739137689.2344143,30.929970502853394,2.706633498747824,1739137689.2344158,30.929970502853394,0.6108,1739137689.2344172,30.929970502853394,0.8467390936417354,1739137689.234419,30.929970502853394,0.0,1739137689.2344205,30.929970502853394,-0.005817693243348021,1739137689.2344224,30.929970502853394,2.507700016335281,1739137689.2344244,30.929970502853394,0.8525567868850834 +1739137689.254375,30.949970483779907,49.36220058897294,1739137689.2543778,30.949970483779907,8.129699459472342,1739137689.2543814,30.949970483779907,59.02460678476629,1739137689.2543843,30.949970483779907,45.074396761416594,1739137689.2543862,30.949970483779907,7.922397700136424,1739137689.2543883,30.949970483779907,-3.0932834312146658,1739137689.25439,30.949970483779907,2.706633498747824,1739137689.2543917,30.949970483779907,0.6108,1739137689.254393,30.949970483779907,0.8467390936417354,1739137689.2543948,30.949970483779907,0.0,1739137689.2543964,30.949970483779907,-0.005817693243348021,1739137689.254398,30.949970483779907,2.507700016335281,1739137689.2543998,30.949970483779907,0.8525567868850834 +1739137689.2743986,30.96997046470642,49.28597382168696,1739137689.274401,30.96997046470642,8.184273518445135,1739137689.2744043,30.96997046470642,59.1108585170931,1739137689.2744076,30.96997046470642,45.006010910890794,1739137689.2744093,30.96997046470642,7.8728588887244735,1739137689.2744112,30.96997046470642,-3.0689595923971775,1739137689.2744129,30.96997046470642,2.6947216050346987,1739137689.2744143,30.96997046470642,0.6108,1739137689.274416,30.96997046470642,0.8507832270826292,1739137689.2744176,30.96997046470642,0.0,1739137689.2744193,30.96997046470642,0.0030499808698527245,1739137689.2744212,30.96997046470642,2.5353052305361956,1739137689.274423,30.96997046470642,0.8519559502808687 +1739137689.2943518,30.989970445632935,49.28597382168696,1739137689.2943547,30.989970445632935,8.184273518445135,1739137689.2943578,30.989970445632935,59.1108585170931,1739137689.294361,30.989970445632935,45.006010910890794,1739137689.2943625,30.989970445632935,7.8728588887244735,1739137689.294365,30.989970445632935,-3.0689595923971775,1739137689.2943668,30.989970445632935,2.6947216050346987,1739137689.2943683,30.989970445632935,0.6108,1739137689.2943697,30.989970445632935,0.8507832270826292,1739137689.2943716,30.989970445632935,0.0,1739137689.294373,30.989970445632935,-0.001172723198239467,1739137689.294375,30.989970445632935,2.5353052305361956,1739137689.2943764,30.989970445632935,0.8519559502808687 +1739137689.3144946,31.00997042655945,49.28597382168696,1739137689.3144975,31.00997042655945,8.184273518445135,1739137689.3145008,31.00997042655945,59.1108585170931,1739137689.3145041,31.00997042655945,45.006010910890794,1739137689.3145058,31.00997042655945,7.8728588887244735,1739137689.3145077,31.00997042655945,-3.0689595923971775,1739137689.3145094,31.00997042655945,2.6947216050346987,1739137689.314511,31.00997042655945,0.6108,1739137689.3145127,31.00997042655945,0.8507832270826292,1739137689.3145142,31.00997042655945,0.0,1739137689.3145163,31.00997042655945,-0.001172723198239467,1739137689.314518,31.00997042655945,2.5353052305361956,1739137689.3145196,31.00997042655945,0.8519559502808687 +1739137689.3343947,31.029970407485962,49.28597382168696,1739137689.334397,31.029970407485962,8.184273518445135,1739137689.3344004,31.029970407485962,59.1108585170931,1739137689.3344035,31.029970407485962,45.006010910890794,1739137689.3344054,31.029970407485962,7.8728588887244735,1739137689.334407,31.029970407485962,-3.0689595923971775,1739137689.334409,31.029970407485962,2.6947216050346987,1739137689.3344104,31.029970407485962,0.6108,1739137689.334412,31.029970407485962,0.8507832270826292,1739137689.3344138,31.029970407485962,0.0,1739137689.3344154,31.029970407485962,-0.001172723198239467,1739137689.334417,31.029970407485962,2.5353052305361956,1739137689.3344188,31.029970407485962,0.8519559502808687 +1739137689.354369,31.049970388412476,49.28597382168696,1739137689.3543715,31.049970388412476,8.184273518445135,1739137689.354375,31.049970388412476,59.1108585170931,1739137689.354378,31.049970388412476,45.006010910890794,1739137689.35438,31.049970388412476,7.8728588887244735,1739137689.354382,31.049970388412476,-3.0689595923971775,1739137689.354384,31.049970388412476,2.6947216050346987,1739137689.3543854,31.049970388412476,0.6108,1739137689.354387,31.049970388412476,0.8507832270826292,1739137689.354389,31.049970388412476,0.0,1739137689.3543906,31.049970388412476,-0.001172723198239467,1739137689.3543923,31.049970388412476,2.5353052305361956,1739137689.354394,31.049970388412476,0.8519559502808687 +1739137689.374392,31.06997036933899,49.28597382168696,1739137689.374395,31.06997036933899,8.184273518445135,1739137689.3743982,31.06997036933899,59.1108585170931,1739137689.3744013,31.06997036933899,45.006010910890794,1739137689.3744028,31.06997036933899,7.8728588887244735,1739137689.3744051,31.06997036933899,-3.0689595923971775,1739137689.3744068,31.06997036933899,2.6947216050346987,1739137689.3744085,31.06997036933899,0.6108,1739137689.37441,31.06997036933899,0.8507832270826292,1739137689.3744118,31.06997036933899,0.0,1739137689.3744135,31.06997036933899,-0.001172723198239467,1739137689.3744152,31.06997036933899,2.5353052305361956,1739137689.3744166,31.06997036933899,0.8519559502808687 +1739137689.3944135,31.089970350265503,49.20829877234723,1739137689.3944163,31.089970350265503,8.236703059590432,1739137689.3944197,31.089970350265503,59.11246832467055,1739137689.394423,31.089970350265503,45.004828110403686,1739137689.394425,31.089970350265503,7.871976201793795,1739137689.3944268,31.089970350265503,-3.0550413976491497,1739137689.3944287,31.089970350265503,2.604310654768733,1739137689.3944302,31.089970350265503,0.6108,1739137689.3944318,31.089970350265503,0.8821143965929058,1739137689.3944335,31.089970350265503,0.0,1739137689.3944352,31.089970350265503,0.058726596309131934,1739137689.3944368,31.089970350265503,2.5629104447371103,1739137689.394438,31.089970350265503,0.8519113000122088 +1739137689.4143658,31.109970331192017,49.20829877234723,1739137689.4143686,31.109970331192017,8.236703059590432,1739137689.4143717,31.109970331192017,59.11246832467055,1739137689.4143748,31.109970331192017,45.004828110403686,1739137689.4143765,31.109970331192017,7.871976201793795,1739137689.4143784,31.109970331192017,-3.0550413976491497,1739137689.41438,31.109970331192017,2.604310654768733,1739137689.4143815,31.109970331192017,0.6108,1739137689.4143832,31.109970331192017,0.8821143965929058,1739137689.4143848,31.109970331192017,0.0,1739137689.4143865,31.109970331192017,0.030203096580696975,1739137689.414388,31.109970331192017,2.5629104447371103,1739137689.4143896,31.109970331192017,0.8519113000122088 +1739137689.4343722,31.12997031211853,49.20829877234723,1739137689.4343753,31.12997031211853,8.236703059590432,1739137689.4343784,31.12997031211853,59.11246832467055,1739137689.4343817,31.12997031211853,45.004828110403686,1739137689.4343834,31.12997031211853,7.871976201793795,1739137689.4343853,31.12997031211853,-3.0550413976491497,1739137689.4343872,31.12997031211853,2.604310654768733,1739137689.4343886,31.12997031211853,0.6108,1739137689.4343903,31.12997031211853,0.8821143965929058,1739137689.4343922,31.12997031211853,0.0,1739137689.434394,31.12997031211853,0.030203096580696975,1739137689.4343953,31.12997031211853,2.5629104447371103,1739137689.4343972,31.12997031211853,0.8519113000122088 +1739137689.454661,31.149970293045044,49.20829877234723,1739137689.4546638,31.149970293045044,8.236703059590432,1739137689.4546673,31.149970293045044,59.11246832467055,1739137689.4546711,31.149970293045044,45.004828110403686,1739137689.454673,31.149970293045044,7.871976201793795,1739137689.4546754,31.149970293045044,-3.0550413976491497,1739137689.4546776,31.149970293045044,2.604310654768733,1739137689.4546793,31.149970293045044,0.6108,1739137689.4546812,31.149970293045044,0.8821143965929058,1739137689.454683,31.149970293045044,0.0,1739137689.454685,31.149970293045044,0.030203096580696975,1739137689.4546869,31.149970293045044,2.5629104447371103,1739137689.4546888,31.149970293045044,0.8519113000122088 +1739137689.4750526,31.169970273971558,49.20829877234723,1739137689.4750562,31.169970273971558,8.236703059590432,1739137689.4750605,31.169970273971558,59.11246832467055,1739137689.4750645,31.169970273971558,45.004828110403686,1739137689.4750667,31.169970273971558,7.871976201793795,1739137689.4750693,31.169970273971558,-3.0550413976491497,1739137689.4750717,31.169970273971558,2.604310654768733,1739137689.4750736,31.169970273971558,0.6108,1739137689.4750752,31.169970273971558,0.8821143965929058,1739137689.4750776,31.169970273971558,0.0,1739137689.4750795,31.169970273971558,0.030203096580696975,1739137689.4750817,31.169970273971558,2.5629104447371103,1739137689.4750836,31.169970273971558,0.8519113000122088 +1739137689.494877,31.18997025489807,49.12905678573655,1739137689.4948804,31.18997025489807,8.287062463583563,1739137689.494885,31.18997025489807,59.11408871228427,1739137689.494889,31.18997025489807,44.994953778620506,1739137689.494891,31.18997025489807,7.864607297477986,1739137689.494894,31.18997025489807,-3.0397582691916187,1739137689.4948962,31.18997025489807,2.524552743464121,1739137689.4948978,31.18997025489807,0.6108,1739137689.4949,31.18997025489807,0.910710362820339,1739137689.4949024,31.18997025489807,0.0,1739137689.4949043,31.18997025489807,0.07798603656720723,1739137689.4949067,31.18997025489807,2.590515658938025,1739137689.4949088,31.18997025489807,0.8554781185656024 +1739137689.5149114,31.209970235824585,49.12905678573655,1739137689.514915,31.209970235824585,8.287062463583563,1739137689.5149195,31.209970235824585,59.11408871228427,1739137689.5149236,31.209970235824585,44.994953778620506,1739137689.5149255,31.209970235824585,7.864607297477986,1739137689.514928,31.209970235824585,-3.0397582691916187,1739137689.5149305,31.209970235824585,2.524552743464121,1739137689.5149324,31.209970235824585,0.6108,1739137689.5149343,31.209970235824585,0.910710362820339,1739137689.5149367,31.209970235824585,0.0,1739137689.5149384,31.209970235824585,0.05523224425473661,1739137689.5149407,31.209970235824585,2.590515658938025,1739137689.5149426,31.209970235824585,0.8554781185656024 +1739137689.5350995,31.2299702167511,49.12905678573655,1739137689.535104,31.2299702167511,8.287062463583563,1739137689.535109,31.2299702167511,59.11408871228427,1739137689.5351133,31.2299702167511,44.994953778620506,1739137689.5351155,31.2299702167511,7.864607297477986,1739137689.535118,31.2299702167511,-3.0397582691916187,1739137689.5351207,31.2299702167511,2.524552743464121,1739137689.5351226,31.2299702167511,0.6108,1739137689.535125,31.2299702167511,0.910710362820339,1739137689.5351274,31.2299702167511,0.0,1739137689.535129,31.2299702167511,0.05523224425473661,1739137689.5351317,31.2299702167511,2.590515658938025,1739137689.5351336,31.2299702167511,0.8554781185656024 +1739137689.5548542,31.249970197677612,49.12905678573655,1739137689.5548575,31.249970197677612,8.287062463583563,1739137689.5548615,31.249970197677612,59.11408871228427,1739137689.5548656,31.249970197677612,44.994953778620506,1739137689.554868,31.249970197677612,7.864607297477986,1739137689.5548706,31.249970197677612,-3.0397582691916187,1739137689.554873,31.249970197677612,2.524552743464121,1739137689.554875,31.249970197677612,0.6108,1739137689.5548766,31.249970197677612,0.910710362820339,1739137689.554879,31.249970197677612,0.0,1739137689.554881,31.249970197677612,0.05523224425473661,1739137689.554883,31.249970197677612,2.590515658938025,1739137689.5548851,31.249970197677612,0.8554781185656024 +1739137689.5752227,31.269970178604126,49.12905678573655,1739137689.5752265,31.269970178604126,8.287062463583563,1739137689.575231,31.269970178604126,59.11408871228427,1739137689.5752351,31.269970178604126,44.994953778620506,1739137689.5752368,31.269970178604126,7.864607297477986,1739137689.5752394,31.269970178604126,-3.0397582691916187,1739137689.575242,31.269970178604126,2.524552743464121,1739137689.575244,31.269970178604126,0.6108,1739137689.5752459,31.269970178604126,0.910710362820339,1739137689.5752482,31.269970178604126,0.0,1739137689.5752501,31.269970178604126,0.05523224425473661,1739137689.5752525,31.269970178604126,2.590515658938025,1739137689.5752544,31.269970178604126,0.8554781185656024 +1739137689.5954463,31.28997015953064,49.12905678573655,1739137689.59545,31.28997015953064,8.287062463583563,1739137689.5954547,31.28997015953064,59.11408871228427,1739137689.595459,31.28997015953064,44.994953778620506,1739137689.595461,31.28997015953064,7.864607297477986,1739137689.5954635,31.28997015953064,-3.0397582691916187,1739137689.5954654,31.28997015953064,2.524552743464121,1739137689.5954676,31.28997015953064,0.6108,1739137689.5954692,31.28997015953064,0.910710362820339,1739137689.5954714,31.28997015953064,0.0,1739137689.5954733,31.28997015953064,0.05523224425473661,1739137689.5954754,31.28997015953064,2.590515658938025,1739137689.5954776,31.28997015953064,0.8554781185656024 +1739137689.6149795,31.309970140457153,49.047977569241674,1739137689.614983,31.309970140457153,8.335499924034043,1739137689.6149874,31.309970140457153,59.37503867308886,1739137689.6149912,31.309970140457153,44.77515980796674,1739137689.614993,31.309970140457153,7.690444840972451,1739137689.6149955,31.309970140457153,-2.9917569808994418,1739137689.6149979,31.309970140457153,2.6946139782383303,1739137689.6149995,31.309970140457153,0.6108,1739137689.6150017,31.309970140457153,0.8508198547003001,1739137689.6150038,31.309970140457153,0.0,1739137689.6150057,31.309970140457153,-0.07152739833129874,1739137689.615008,31.309970140457153,2.6181208731389396,1739137689.61501,31.309970140457153,0.8619854883134814 +1739137689.6350582,31.329970121383667,49.047977569241674,1739137689.635062,31.329970121383667,8.335499924034043,1739137689.6350665,31.329970121383667,59.37503867308886,1739137689.6350713,31.329970121383667,44.77515980796674,1739137689.6350732,31.329970121383667,7.690444840972451,1739137689.6350758,31.329970121383667,-2.9917569808994418,1739137689.6350784,31.329970121383667,2.6946139782383303,1739137689.6350803,31.329970121383667,0.6108,1739137689.6350825,31.329970121383667,0.8508198547003001,1739137689.635085,31.329970121383667,0.0,1739137689.6350873,31.329970121383667,-0.011165633613181347,1739137689.6350896,31.329970121383667,2.6181208731389396,1739137689.635092,31.329970121383667,0.8619854883134814 +1739137689.654951,31.34997010231018,49.047977569241674,1739137689.6549551,31.34997010231018,8.335499924034043,1739137689.6549594,31.34997010231018,59.37503867308886,1739137689.6549635,31.34997010231018,44.77515980796674,1739137689.6549654,31.34997010231018,7.690444840972451,1739137689.654968,31.34997010231018,-2.9917569808994418,1739137689.6549702,31.34997010231018,2.6946139782383303,1739137689.6549718,31.34997010231018,0.6108,1739137689.654974,31.34997010231018,0.8508198547003001,1739137689.6549764,31.34997010231018,0.0,1739137689.654978,31.34997010231018,-0.011165633613181347,1739137689.6549804,31.34997010231018,2.6181208731389396,1739137689.654982,31.34997010231018,0.8619854883134814 +1739137689.6751795,31.369970083236694,49.047977569241674,1739137689.675184,31.369970083236694,8.335499924034043,1739137689.6751885,31.369970083236694,59.37503867308886,1739137689.6751928,31.369970083236694,44.77515980796674,1739137689.675195,31.369970083236694,7.690444840972451,1739137689.6751976,31.369970083236694,-2.9917569808994418,1739137689.6752,31.369970083236694,2.6946139782383303,1739137689.6752021,31.369970083236694,0.6108,1739137689.6752038,31.369970083236694,0.8508198547003001,1739137689.6752064,31.369970083236694,0.0,1739137689.6752088,31.369970083236694,-0.011165633613181347,1739137689.675211,31.369970083236694,2.6181208731389396,1739137689.675213,31.369970083236694,0.8619854883134814 +1739137689.6949158,31.389970064163208,49.047977569241674,1739137689.6949193,31.389970064163208,8.335499924034043,1739137689.694924,31.389970064163208,59.37503867308886,1739137689.6949282,31.389970064163208,44.77515980796674,1739137689.69493,31.389970064163208,7.690444840972451,1739137689.6949327,31.389970064163208,-2.9917569808994418,1739137689.6949348,31.389970064163208,2.6946139782383303,1739137689.6949368,31.389970064163208,0.6108,1739137689.6949387,31.389970064163208,0.8508198547003001,1739137689.694941,31.389970064163208,0.0,1739137689.6949427,31.389970064163208,-0.011165633613181347,1739137689.6949449,31.389970064163208,2.6181208731389396,1739137689.6949468,31.389970064163208,0.8619854883134814 +1739137689.7148871,31.40997004508972,48.965356380209364,1739137689.7148905,31.40997004508972,8.381815702615507,1739137689.7148945,31.40997004508972,59.187943675405,1739137689.7148986,31.40997004508972,44.92489926003391,1739137689.714901,31.40997004508972,7.811240337298932,1739137689.7149034,31.40997004508972,-3.001304730634907,1739137689.7149053,31.40997004508972,2.424278756311694,1739137689.7149074,31.40997004508972,0.6108,1739137689.714909,31.40997004508972,0.9479810459500935,1739137689.7149115,31.40997004508972,0.0,1739137689.7149136,31.40997004508972,0.17770169134834318,1739137689.7149158,31.40997004508972,2.6457260873398543,1739137689.714918,31.40997004508972,0.8602162209393941 +1739137689.7357192,31.429970026016235,48.965356380209364,1739137689.7357225,31.429970026016235,8.381815702615507,1739137689.7357266,31.429970026016235,59.187943675405,1739137689.7357306,31.429970026016235,44.92489926003391,1739137689.7357326,31.429970026016235,7.811240337298932,1739137689.735735,31.429970026016235,-3.001304730634907,1739137689.7357373,31.429970026016235,2.424278756311694,1739137689.7357395,31.429970026016235,0.6108,1739137689.7357411,31.429970026016235,0.9479810459500935,1739137689.7357435,31.429970026016235,0.0,1739137689.7357454,31.429970026016235,0.08776482501069938,1739137689.7357476,31.429970026016235,2.6457260873398543,1739137689.7357497,31.429970026016235,0.8602162209393941 +1739137689.7545035,31.44997000694275,48.965356380209364,1739137689.7545063,31.44997000694275,8.381815702615507,1739137689.75451,31.44997000694275,59.187943675405,1739137689.7545135,31.44997000694275,44.92489926003391,1739137689.754515,31.44997000694275,7.811240337298932,1739137689.7545176,31.44997000694275,-3.001304730634907,1739137689.754519,31.44997000694275,2.424278756311694,1739137689.754521,31.44997000694275,0.6108,1739137689.7545223,31.44997000694275,0.9479810459500935,1739137689.7545242,31.44997000694275,0.0,1739137689.7545257,31.44997000694275,0.08776482501069938,1739137689.7545278,31.44997000694275,2.6457260873398543,1739137689.7545295,31.44997000694275,0.8602162209393941 +1739137689.7746909,31.469969987869263,48.965356380209364,1739137689.7746942,31.469969987869263,8.381815702615507,1739137689.774698,31.469969987869263,59.187943675405,1739137689.7747016,31.469969987869263,44.92489926003391,1739137689.7747033,31.469969987869263,7.811240337298932,1739137689.7747054,31.469969987869263,-3.001304730634907,1739137689.7747073,31.469969987869263,2.424278756311694,1739137689.774709,31.469969987869263,0.6108,1739137689.7747104,31.469969987869263,0.9479810459500935,1739137689.7747123,31.469969987869263,0.0,1739137689.774714,31.469969987869263,0.08776482501069938,1739137689.774716,31.469969987869263,2.6457260873398543,1739137689.7747178,31.469969987869263,0.8602162209393941 +1739137689.7945218,31.489969968795776,48.965356380209364,1739137689.794525,31.489969968795776,8.381815702615507,1739137689.7945282,31.489969968795776,59.187943675405,1739137689.7945318,31.489969968795776,44.92489926003391,1739137689.7945337,31.489969968795776,7.811240337298932,1739137689.7945359,31.489969968795776,-3.001304730634907,1739137689.7945375,31.489969968795776,2.424278756311694,1739137689.7945392,31.489969968795776,0.6108,1739137689.794541,31.489969968795776,0.9479810459500935,1739137689.7945428,31.489969968795776,0.0,1739137689.7945445,31.489969968795776,0.08776482501069938,1739137689.7945464,31.489969968795776,2.6457260873398543,1739137689.794548,31.489969968795776,0.8602162209393941 +1739137689.8146226,31.50996994972229,48.965356380209364,1739137689.8146255,31.50996994972229,8.381815702615507,1739137689.814629,31.50996994972229,59.187943675405,1739137689.8146324,31.50996994972229,44.92489926003391,1739137689.8146343,31.50996994972229,7.811240337298932,1739137689.8146362,31.50996994972229,-3.001304730634907,1739137689.8146381,31.50996994972229,2.424278756311694,1739137689.8146398,31.50996994972229,0.6108,1739137689.8146415,31.50996994972229,0.9479810459500935,1739137689.8146434,31.50996994972229,0.0,1739137689.814645,31.50996994972229,0.08776482501069938,1739137689.814647,31.50996994972229,2.6457260873398543,1739137689.8146489,31.50996994972229,0.8602162209393941 +1739137689.8347461,31.529969930648804,48.88099499828842,1739137689.8347511,31.529969930648804,8.426088545285841,1739137689.8347578,31.529969930648804,59.20284081495059,1739137689.8347635,31.529969930648804,44.88621200343047,1739137689.8347678,31.529969930648804,7.780969602744378,1739137689.8347733,31.529969930648804,-2.981484571434506,1739137689.8347766,31.529969930648804,2.3786619882409266,1739137689.8347814,31.529969930648804,0.6108,1739137689.8347855,31.529969930648804,0.9654373543014467,1739137689.8347914,31.529969930648804,0.0,1739137689.8347964,31.529969930648804,0.09930970525052861,1739137689.834799,31.529969930648804,2.673331301540769,1739137689.834801,31.529969930648804,0.8716252138161582 +1739137689.8545017,31.549969911575317,48.88099499828842,1739137689.8545046,31.549969911575317,8.426088545285841,1739137689.854508,31.549969911575317,59.20284081495059,1739137689.8545115,31.549969911575317,44.88621200343047,1739137689.8545132,31.549969911575317,7.780969602744378,1739137689.8545156,31.549969911575317,-2.981484571434506,1739137689.8545172,31.549969911575317,2.3786619882409266,1739137689.8545191,31.549969911575317,0.6108,1739137689.8545206,31.549969911575317,0.9654373543014467,1739137689.8545227,31.549969911575317,0.0,1739137689.8545244,31.549969911575317,0.09381214048528852,1739137689.8545263,31.549969911575317,2.673331301540769,1739137689.8545277,31.549969911575317,0.8716252138161582 +1739137689.8745542,31.56996989250183,48.88099499828842,1739137689.8745575,31.56996989250183,8.426088545285841,1739137689.8745613,31.56996989250183,59.20284081495059,1739137689.874565,31.56996989250183,44.88621200343047,1739137689.8745666,31.56996989250183,7.780969602744378,1739137689.874569,31.56996989250183,-2.981484571434506,1739137689.8745708,31.56996989250183,2.3786619882409266,1739137689.8745723,31.56996989250183,0.6108,1739137689.8745737,31.56996989250183,0.9654373543014467,1739137689.8745759,31.56996989250183,0.0,1739137689.874578,31.56996989250183,0.09381214048528852,1739137689.8745797,31.56996989250183,2.673331301540769,1739137689.8745813,31.56996989250183,0.8716252138161582 +1739137689.8945317,31.589969873428345,48.88099499828842,1739137689.8945348,31.589969873428345,8.426088545285841,1739137689.8945384,31.589969873428345,59.20284081495059,1739137689.894542,31.589969873428345,44.88621200343047,1739137689.8945436,31.589969873428345,7.780969602744378,1739137689.8945456,31.589969873428345,-2.981484571434506,1739137689.8945475,31.589969873428345,2.3786619882409266,1739137689.894549,31.589969873428345,0.6108,1739137689.8945506,31.589969873428345,0.9654373543014467,1739137689.8945525,31.589969873428345,0.0,1739137689.8945541,31.589969873428345,0.09381214048528852,1739137689.8945558,31.589969873428345,2.673331301540769,1739137689.8945577,31.589969873428345,0.8716252138161582 +1739137689.9394734,31.619969844818115,48.88099499828842,1739137689.939478,31.619969844818115,8.426088545285841,1739137689.9394836,31.619969844818115,59.20284081495059,1739137689.939488,31.619969844818115,44.88621200343047,1739137689.9394903,31.619969844818115,7.780969602744378,1739137689.9394932,31.619969844818115,-2.981484571434506,1739137689.9394956,31.619969844818115,2.3786619882409266,1739137689.9394982,31.619969844818115,0.6108,1739137689.9395003,31.619969844818115,0.9654373543014467,1739137689.9395032,31.619969844818115,0.0,1739137689.939505,31.619969844818115,0.09381214048528852,1739137689.9395077,31.619969844818115,2.673331301540769,1739137689.9395103,31.619969844818115,0.8716252138161582 +1739137689.9496398,31.63996982574463,48.794437855683384,1739137689.9496427,31.63996982574463,8.468509153516514,1739137689.949646,31.63996982574463,59.082334809069835,1739137689.9496489,31.63996982574463,44.956869761123414,1739137689.9496505,31.63996982574463,7.83594481541355,1739137689.949652,31.63996982574463,-2.978226970069481,1739137689.9496534,31.63996982574463,2.208986218088387,1739137689.949655,31.63996982574463,0.6108,1739137689.9496562,31.63996982574463,1.0332366404005815,1739137689.949658,31.63996982574463,0.0,1739137689.949659,31.63996982574463,0.20353352485874163,1739137689.949661,31.63996982574463,2.7009365157416836,1739137689.9496624,31.63996982574463,0.8819514199152235 +1739137689.9702604,31.6699697971344,48.794437855683384,1739137689.9702628,31.6699697971344,8.468509153516514,1739137689.9702654,31.6699697971344,59.082334809069835,1739137689.970268,31.6699697971344,44.956869761123414,1739137689.9702694,31.6699697971344,7.83594481541355,1739137689.9702709,31.6699697971344,-2.978226970069481,1739137689.9702725,31.6699697971344,2.208986218088387,1739137689.9702737,31.6699697971344,0.6108,1739137689.9702752,31.6699697971344,1.0332366404005815,1739137689.9702768,31.6699697971344,0.0,1739137689.9702783,31.6699697971344,0.15128522048535797,1739137689.9702797,31.6699697971344,2.7009365157416836,1739137689.970281,31.6699697971344,0.8819514199152235 +1739137689.988895,31.689969778060913,48.794437855683384,1739137689.9888973,31.689969778060913,8.468509153516514,1739137689.9889004,31.689969778060913,59.082334809069835,1739137689.9889028,31.689969778060913,44.956869761123414,1739137689.9889207,31.689969778060913,7.83594481541355,1739137689.9889224,31.689969778060913,-2.978226970069481,1739137689.9889235,31.689969778060913,2.208986218088387,1739137689.9889252,31.689969778060913,0.6108,1739137689.9889262,31.689969778060913,1.0332366404005815,1739137689.9889278,31.689969778060913,0.0,1739137689.988929,31.689969778060913,0.15128522048535797,1739137689.9889305,31.689969778060913,2.7009365157416836,1739137689.988932,31.689969778060913,0.8819514199152235 +1739137690.0103416,31.709969758987427,48.794437855683384,1739137690.010345,31.709969758987427,8.468509153516514,1739137690.0103493,31.709969758987427,59.082334809069835,1739137690.0103543,31.709969758987427,44.956869761123414,1739137690.010357,31.709969758987427,7.83594481541355,1739137690.0103605,31.709969758987427,-2.978226970069481,1739137690.0103636,31.709969758987427,2.208986218088387,1739137690.010367,31.709969758987427,0.6108,1739137690.01037,31.709969758987427,1.0332366404005815,1739137690.0103734,31.709969758987427,0.0,1739137690.0103765,31.709969758987427,0.15128522048535797,1739137690.0103798,31.709969758987427,2.7009365157416836,1739137690.0103831,31.709969758987427,0.8819514199152235 +1739137690.0297892,31.72996973991394,48.794437855683384,1739137690.029792,31.72996973991394,8.468509153516514,1739137690.0297952,31.72996973991394,59.082334809069835,1739137690.0297976,31.72996973991394,44.956869761123414,1739137690.029799,31.72996973991394,7.83594481541355,1739137690.0298004,31.72996973991394,-2.978226970069481,1739137690.029802,31.72996973991394,2.208986218088387,1739137690.0298035,31.72996973991394,0.6108,1739137690.0298045,31.72996973991394,1.0332366404005815,1739137690.0298064,31.72996973991394,0.0,1739137690.0298076,31.72996973991394,0.15128522048535797,1739137690.029809,31.72996973991394,2.7009365157416836,1739137690.0298102,31.72996973991394,0.8819514199152235 +1739137690.0502427,31.749969720840454,48.705362938102006,1739137690.0502462,31.749969720840454,8.509152017139451,1739137690.0502505,31.749969720840454,59.23327226175589,1739137690.0502553,31.749969720840454,44.79762602061158,1739137690.0502582,31.749969720840454,7.709049673318963,1739137690.0502617,31.749969720840454,-2.939635653646278,1739137690.050265,31.749969720840454,2.3014013050126967,1739137690.0502682,31.749969720840454,0.6108,1739137690.0502713,31.749969720840454,0.9957393124629604,1739137690.0502746,31.749969720840454,0.0,1739137690.050278,31.749969720840454,0.04616368088511514,1739137690.0502815,31.749969720840454,2.7285417299425982,1739137690.0502849,31.749969720840454,0.8995177305716211 +1739137690.0702794,31.769969701766968,48.705362938102006,1739137690.0702832,31.769969701766968,8.509152017139451,1739137690.070288,31.769969701766968,59.23327226175589,1739137690.0702927,31.769969701766968,44.79762602061158,1739137690.0702956,31.769969701766968,7.709049673318963,1739137690.070299,31.769969701766968,-2.939635653646278,1739137690.0703022,31.769969701766968,2.3014013050126967,1739137690.0703056,31.769969701766968,0.6108,1739137690.0703087,31.769969701766968,0.9957393124629604,1739137690.070312,31.769969701766968,0.0,1739137690.0703154,31.769969701766968,0.09622158189133934,1739137690.070319,31.769969701766968,2.7285417299425982,1739137690.070322,31.769969701766968,0.8995177305716211 +1739137690.0881586,31.78996968269348,48.705362938102006,1739137690.0881612,31.78996968269348,8.509152017139451,1739137690.0881639,31.78996968269348,59.23327226175589,1739137690.0881667,31.78996968269348,44.79762602061158,1739137690.088168,31.78996968269348,7.709049673318963,1739137690.0881698,31.78996968269348,-2.939635653646278,1739137690.0881712,31.78996968269348,2.3014013050126967,1739137690.0881724,31.78996968269348,0.6108,1739137690.0881739,31.78996968269348,0.9957393124629604,1739137690.088175,31.78996968269348,0.0,1739137690.0881767,31.78996968269348,0.09622158189133934,1739137690.0881782,31.78996968269348,2.7285417299425982,1739137690.0881793,31.78996968269348,0.8995177305716211 +1739137690.1082654,31.809969663619995,48.705362938102006,1739137690.1082685,31.809969663619995,8.509152017139451,1739137690.1082716,31.809969663619995,59.23327226175589,1739137690.1082742,31.809969663619995,44.79762602061158,1739137690.1082754,31.809969663619995,7.709049673318963,1739137690.1082776,31.809969663619995,-2.939635653646278,1739137690.108279,31.809969663619995,2.3014013050126967,1739137690.1082804,31.809969663619995,0.6108,1739137690.1082814,31.809969663619995,0.9957393124629604,1739137690.108283,31.809969663619995,0.0,1739137690.1082845,31.809969663619995,0.09622158189133934,1739137690.108286,31.809969663619995,2.7285417299425982,1739137690.1082873,31.809969663619995,0.8995177305716211 +1739137690.1302788,31.82996964454651,48.705362938102006,1739137690.1302822,31.82996964454651,8.509152017139451,1739137690.1302867,31.82996964454651,59.23327226175589,1739137690.1302917,31.82996964454651,44.79762602061158,1739137690.1302946,31.82996964454651,7.709049673318963,1739137690.1302981,31.82996964454651,-2.939635653646278,1739137690.1303015,31.82996964454651,2.3014013050126967,1739137690.1303048,31.82996964454651,0.6108,1739137690.130308,31.82996964454651,0.9957393124629604,1739137690.1303115,31.82996964454651,0.0,1739137690.1303146,31.82996964454651,0.09622158189133934,1739137690.1303182,31.82996964454651,2.7285417299425982,1739137690.1303215,31.82996964454651,0.8995177305716211 +1739137690.148173,31.849969625473022,48.61379044680492,1739137690.1481755,31.849969625473022,8.547919899115684,1739137690.1481779,31.849969625473022,59.24884827245784,1739137690.1481807,31.849969625473022,44.76263014401923,1739137690.148182,31.849969625473022,7.6794534085419235,1739137690.1481836,31.849969625473022,-2.9197949811029567,1739137690.1481848,31.849969625473022,2.2526770727405983,1739137690.1481862,31.849969625473022,0.6108,1739137690.1481874,31.849969625473022,1.0153363153443546,1739137690.1481886,31.849969625473022,0.0,1739137690.14819,31.849969625473022,0.11437491260380728,1739137690.1481915,31.849969625473022,2.756146944143513,1739137690.148193,31.849969625473022,0.9096058502552399 +1739137690.1681879,31.869969606399536,48.61379044680492,1739137690.168191,31.869969606399536,8.547919899115684,1739137690.168194,31.869969606399536,59.24884827245784,1739137690.1681972,31.869969606399536,44.76263014401923,1739137690.1681986,31.869969606399536,7.6794534085419235,1739137690.1682005,31.869969606399536,-2.9197949811029567,1739137690.168202,31.869969606399536,2.2526770727405983,1739137690.1682036,31.869969606399536,0.6108,1739137690.1682045,31.869969606399536,1.0153363153443546,1739137690.1682065,31.869969606399536,0.0,1739137690.1682076,31.869969606399536,0.10573046508911477,1739137690.1682096,31.869969606399536,2.756146944143513,1739137690.168211,31.869969606399536,0.9096058502552399 +1739137690.1881733,31.88996958732605,48.61379044680492,1739137690.1881764,31.88996958732605,8.547919899115684,1739137690.1881793,31.88996958732605,59.24884827245784,1739137690.188182,31.88996958732605,44.76263014401923,1739137690.1881833,31.88996958732605,7.6794534085419235,1739137690.188185,31.88996958732605,-2.9197949811029567,1739137690.1881864,31.88996958732605,2.2526770727405983,1739137690.1881876,31.88996958732605,0.6108,1739137690.188189,31.88996958732605,1.0153363153443546,1739137690.1881902,31.88996958732605,0.0,1739137690.1881914,31.88996958732605,0.10573046508911477,1739137690.188193,31.88996958732605,2.756146944143513,1739137690.1881943,31.88996958732605,0.9096058502552399 +1739137690.2081413,31.909969568252563,48.61379044680492,1739137690.2081437,31.909969568252563,8.547919899115684,1739137690.2081463,31.909969568252563,59.24884827245784,1739137690.208149,31.909969568252563,44.76263014401923,1739137690.2081504,31.909969568252563,7.6794534085419235,1739137690.2081518,31.909969568252563,-2.9197949811029567,1739137690.2081532,31.909969568252563,2.2526770727405983,1739137690.2081544,31.909969568252563,0.6108,1739137690.2081556,31.909969568252563,1.0153363153443546,1739137690.2081568,31.909969568252563,0.0,1739137690.2081585,31.909969568252563,0.10573046508911477,1739137690.2081597,31.909969568252563,2.756146944143513,1739137690.208161,31.909969568252563,0.9096058502552399 +1739137690.2288244,31.929969549179077,48.61379044680492,1739137690.2288265,31.929969549179077,8.547919899115684,1739137690.2288296,31.929969549179077,59.24884827245784,1739137690.2288325,31.929969549179077,44.76263014401923,1739137690.2288337,31.929969549179077,7.6794534085419235,1739137690.2288353,31.929969549179077,-2.9197949811029567,1739137690.2288368,31.929969549179077,2.2526770727405983,1739137690.2288382,31.929969549179077,0.6108,1739137690.2288394,31.929969549179077,1.0153363153443546,1739137690.228841,31.929969549179077,0.0,1739137690.2288423,31.929969549179077,0.10573046508911477,1739137690.2288437,31.929969549179077,2.756146944143513,1739137690.2288451,31.929969549179077,0.9096058502552399 +1739137690.2483642,31.94996953010559,48.61379044680492,1739137690.248367,31.94996953010559,8.547919899115684,1739137690.2483706,31.94996953010559,59.24884827245784,1739137690.2483737,31.94996953010559,44.76263014401923,1739137690.248375,31.94996953010559,7.6794534085419235,1739137690.2483768,31.94996953010559,-2.9197949811029567,1739137690.2483783,31.94996953010559,2.2526770727405983,1739137690.24838,31.94996953010559,0.6108,1739137690.2483811,31.94996953010559,1.0153363153443546,1739137690.2483833,31.94996953010559,0.0,1739137690.2483845,31.94996953010559,0.10573046508911477,1739137690.2483866,31.94996953010559,2.756146944143513,1739137690.248388,31.94996953010559,0.9096058502552399 +1739137690.2685127,31.969969511032104,48.520056328326916,1739137690.2685158,31.969969511032104,8.584585600656304,1739137690.2685192,31.969969511032104,59.264598856298804,1739137690.2685223,31.969969511032104,44.72472473854704,1739137690.2685235,31.969969511032104,7.6452764036079826,1739137690.2685254,31.969969511032104,-2.8989770939859527,1739137690.2685268,31.969969511032104,2.209132781313675,1739137690.2685285,31.969969511032104,0.6108,1739137690.2685297,31.969969511032104,1.0331760683783238,1739137690.2685316,31.969969511032104,0.0,1739137690.2685328,31.969969511032104,0.11733248997423086,1739137690.2685354,31.969969511032104,2.7837521583444276,1739137690.2685366,31.969969511032104,0.9213683549187773 +1739137690.2882407,31.989969491958618,48.520056328326916,1739137690.288244,31.989969491958618,8.584585600656304,1739137690.2882469,31.989969491958618,59.264598856298804,1739137690.2882502,31.989969491958618,44.72472473854704,1739137690.2882516,31.989969491958618,7.6452764036079826,1739137690.2882535,31.989969491958618,-2.8989770939859527,1739137690.2882547,31.989969491958618,2.209132781313675,1739137690.2882562,31.989969491958618,0.6108,1739137690.2882576,31.989969491958618,1.0331760683783238,1739137690.288259,31.989969491958618,0.0,1739137690.2882605,31.989969491958618,0.11180771345954643,1739137690.288262,31.989969491958618,2.7837521583444276,1739137690.2882633,31.989969491958618,0.9213683549187773 +1739137690.3084235,32.00996947288513,48.520056328326916,1739137690.3084264,32.00996947288513,8.584585600656304,1739137690.3084292,32.00996947288513,59.264598856298804,1739137690.3084323,32.00996947288513,44.72472473854704,1739137690.3084338,32.00996947288513,7.6452764036079826,1739137690.3084354,32.00996947288513,-2.8989770939859527,1739137690.308437,32.00996947288513,2.209132781313675,1739137690.3084383,32.00996947288513,0.6108,1739137690.3084397,32.00996947288513,1.0331760683783238,1739137690.3084414,32.00996947288513,0.0,1739137690.3084428,32.00996947288513,0.11180771345954643,1739137690.3084445,32.00996947288513,2.7837521583444276,1739137690.3084457,32.00996947288513,0.9213683549187773 +1739137690.328757,32.029969453811646,48.520056328326916,1739137690.3287604,32.029969453811646,8.584585600656304,1739137690.3287635,32.029969453811646,59.264598856298804,1739137690.3287668,32.029969453811646,44.72472473854704,1739137690.3287683,32.029969453811646,7.6452764036079826,1739137690.3287702,32.029969453811646,-2.8989770939859527,1739137690.3287718,32.029969453811646,2.209132781313675,1739137690.328773,32.029969453811646,0.6108,1739137690.3287747,32.029969453811646,1.0331760683783238,1739137690.3287766,32.029969453811646,0.0,1739137690.328778,32.029969453811646,0.11180771345954643,1739137690.3287795,32.029969453811646,2.7837521583444276,1739137690.328781,32.029969453811646,0.9213683549187773 +1739137690.3482242,32.04996943473816,48.520056328326916,1739137690.3482265,32.04996943473816,8.584585600656304,1739137690.3482294,32.04996943473816,59.264598856298804,1739137690.3482323,32.04996943473816,44.72472473854704,1739137690.3482335,32.04996943473816,7.6452764036079826,1739137690.3482354,32.04996943473816,-2.8989770939859527,1739137690.3482368,32.04996943473816,2.209132781313675,1739137690.3482382,32.04996943473816,0.6108,1739137690.34824,32.04996943473816,1.0331760683783238,1739137690.3482413,32.04996943473816,0.0,1739137690.3482428,32.04996943473816,0.11180771345954643,1739137690.3482442,32.04996943473816,2.7837521583444276,1739137690.3482456,32.04996943473816,0.9213683549187773 +1739137690.368492,32.06996941566467,48.42411003202487,1739137690.3684947,32.06996941566467,8.619094483951542,1739137690.3684988,32.06996941566467,59.127692084486235,1739137690.3685017,32.06996941566467,44.80003928313028,1739137690.368503,32.06996941566467,7.711048156342264,1739137690.368505,32.06996941566467,-2.896087219019544,1739137690.3685067,32.06996941566467,2.0341425163769116,1739137690.368508,32.06996941566467,0.6108,1739137690.3685098,32.06996941566467,1.1080854710905639,1739137690.3685114,32.06996941566467,0.0,1739137690.368513,32.06996941566467,0.2313380088717591,1739137690.368515,32.06996941566467,2.8113573725453422,1739137690.3685164,32.06996941566467,0.9336666789439702 +1739137690.3882146,32.08996939659119,48.42411003202487,1739137690.3882167,32.08996939659119,8.619094483951542,1739137690.3882196,32.08996939659119,59.127692084486235,1739137690.3882227,32.08996939659119,44.80003928313028,1739137690.388224,32.08996939659119,7.711048156342264,1739137690.3882256,32.08996939659119,-2.896087219019544,1739137690.388227,32.08996939659119,2.0341425163769116,1739137690.3882287,32.08996939659119,0.6108,1739137690.3882298,32.08996939659119,1.1080854710905639,1739137690.3882315,32.08996939659119,0.0,1739137690.3882327,32.08996939659119,0.17441879214659373,1739137690.3882341,32.08996939659119,2.8113573725453422,1739137690.3882356,32.08996939659119,0.9336666789439702 +1739137690.4082236,32.1099693775177,48.42411003202487,1739137690.4082263,32.1099693775177,8.619094483951542,1739137690.408229,32.1099693775177,59.127692084486235,1739137690.4082322,32.1099693775177,44.80003928313028,1739137690.4082334,32.1099693775177,7.711048156342264,1739137690.4082353,32.1099693775177,-2.896087219019544,1739137690.4082367,32.1099693775177,2.0341425163769116,1739137690.4082384,32.1099693775177,0.6108,1739137690.4082396,32.1099693775177,1.1080854710905639,1739137690.408241,32.1099693775177,0.0,1739137690.4082425,32.1099693775177,0.17441879214659373,1739137690.4082441,32.1099693775177,2.8113573725453422,1739137690.4082458,32.1099693775177,0.9336666789439702 +1739137690.4284039,32.129969358444214,48.42411003202487,1739137690.428407,32.129969358444214,8.619094483951542,1739137690.4284103,32.129969358444214,59.127692084486235,1739137690.4284136,32.129969358444214,44.80003928313028,1739137690.428415,32.129969358444214,7.711048156342264,1739137690.428417,32.129969358444214,-2.896087219019544,1739137690.4284186,32.129969358444214,2.0341425163769116,1739137690.42842,32.129969358444214,0.6108,1739137690.4284213,32.129969358444214,1.1080854710905639,1739137690.4284232,32.129969358444214,0.0,1739137690.4284244,32.129969358444214,0.17441879214659373,1739137690.4284263,32.129969358444214,2.8113573725453422,1739137690.4284277,32.129969358444214,0.9336666789439702 +1739137690.4484236,32.14996933937073,48.42411003202487,1739137690.4484262,32.14996933937073,8.619094483951542,1739137690.4484293,32.14996933937073,59.127692084486235,1739137690.4484322,32.14996933937073,44.80003928313028,1739137690.4484336,32.14996933937073,7.711048156342264,1739137690.4484355,32.14996933937073,-2.896087219019544,1739137690.448437,32.14996933937073,2.0341425163769116,1739137690.4484382,32.14996933937073,0.6108,1739137690.4484398,32.14996933937073,1.1080854710905639,1739137690.4484413,32.14996933937073,0.0,1739137690.4484427,32.14996933937073,0.17441879214659373,1739137690.4484441,32.14996933937073,2.8113573725453422,1739137690.4484458,32.14996933937073,0.9336666789439702 +1739137690.470573,32.16996932029724,48.42411003202487,1739137690.470577,32.16996932029724,8.619094483951542,1739137690.4705818,32.16996932029724,59.127692084486235,1739137690.4705875,32.16996932029724,44.80003928313028,1739137690.4705904,32.16996932029724,7.711048156342264,1739137690.4705944,32.16996932029724,-2.896087219019544,1739137690.470598,32.16996932029724,2.0341425163769116,1739137690.4706016,32.16996932029724,0.6108,1739137690.4706051,32.16996932029724,1.1080854710905639,1739137690.470609,32.16996932029724,0.0,1739137690.4706125,32.16996932029724,0.17441879214659373,1739137690.4706163,32.16996932029724,2.8113573725453422,1739137690.47062,32.16996932029724,0.9336666789439702 +1739137690.48828,32.189969301223755,48.32553562389986,1739137690.4882827,32.189969301223755,8.65150293886177,1739137690.4882858,32.189969301223755,59.36422461958428,1739137690.4882882,32.189969301223755,44.579187576121704,1739137690.48829,32.189969301223755,7.5122000695969895,1739137690.4882925,32.189969301223755,-2.846369259577272,1739137690.488294,32.189969301223755,2.2040591094382544,1739137690.488295,32.189969301223755,0.6108,1739137690.4882963,32.189969301223755,1.035274996056173,1739137690.488298,32.189969301223755,0.0,1739137690.4882994,32.189969301223755,-0.003244418193693477,1739137690.4883008,32.189969301223755,2.838962586746257,1739137690.488302,32.189969301223755,0.9539178432542154 +1739137690.5080552,32.20996928215027,48.32553562389986,1739137690.5080578,32.20996928215027,8.65150293886177,1739137690.5080607,32.20996928215027,59.36422461958428,1739137690.5080636,32.20996928215027,44.579187576121704,1739137690.5080647,32.20996928215027,7.5122000695969895,1739137690.5080664,32.20996928215027,-2.846369259577272,1739137690.5080678,32.20996928215027,2.2040591094382544,1739137690.508069,32.20996928215027,0.6108,1739137690.5080705,32.20996928215027,1.035274996056173,1739137690.508072,32.20996928215027,0.0,1739137690.5080733,32.20996928215027,0.08135715280195754,1739137690.5080748,32.20996928215027,2.838962586746257,1739137690.5080762,32.20996928215027,0.9539178432542154 +1739137690.5283482,32.22996926307678,48.32553562389986,1739137690.5283508,32.22996926307678,8.65150293886177,1739137690.5283535,32.22996926307678,59.36422461958428,1739137690.5283558,32.22996926307678,44.579187576121704,1739137690.5283577,32.22996926307678,7.5122000695969895,1739137690.5283592,32.22996926307678,-2.846369259577272,1739137690.5283604,32.22996926307678,2.2040591094382544,1739137690.528362,32.22996926307678,0.6108,1739137690.5283632,32.22996926307678,1.035274996056173,1739137690.528365,32.22996926307678,0.0,1739137690.5283659,32.22996926307678,0.08135715280195754,1739137690.5283673,32.22996926307678,2.838962586746257,1739137690.5283687,32.22996926307678,0.9539178432542154 +1739137690.548127,32.249969244003296,48.32553562389986,1739137690.5481298,32.249969244003296,8.65150293886177,1739137690.548133,32.249969244003296,59.36422461958428,1739137690.5481355,32.249969244003296,44.579187576121704,1739137690.548137,32.249969244003296,7.5122000695969895,1739137690.5481389,32.249969244003296,-2.846369259577272,1739137690.5481403,32.249969244003296,2.2040591094382544,1739137690.5481417,32.249969244003296,0.6108,1739137690.5481431,32.249969244003296,1.035274996056173,1739137690.548145,32.249969244003296,0.0,1739137690.5481465,32.249969244003296,0.08135715280195754,1739137690.5481477,32.249969244003296,2.838962586746257,1739137690.548149,32.249969244003296,0.9539178432542154 +1739137690.56868,32.26996922492981,48.32553562389986,1739137690.5686822,32.26996922492981,8.65150293886177,1739137690.5686848,32.26996922492981,59.36422461958428,1739137690.5686874,32.26996922492981,44.579187576121704,1739137690.5686886,32.26996922492981,7.5122000695969895,1739137690.5686905,32.26996922492981,-2.846369259577272,1739137690.5686917,32.26996922492981,2.2040591094382544,1739137690.568693,32.26996922492981,0.6108,1739137690.5686944,32.26996922492981,1.035274996056173,1739137690.5686958,32.26996922492981,0.0,1739137690.568697,32.26996922492981,0.08135715280195754,1739137690.5686984,32.26996922492981,2.838962586746257,1739137690.5686996,32.26996922492981,0.9539178432542154 +1739137690.5882208,32.28996920585632,48.2246132819328,1739137690.5882244,32.28996920585632,8.681626503334064,1739137690.5882277,32.28996920585632,59.45198386661118,1739137690.588231,32.28996920585632,44.49887923702274,1739137690.5882325,32.28996920585632,7.433879237022743,1739137690.5882342,32.28996920585632,-2.8184330196169243,1739137690.5882359,32.28996920585632,2.2126557709969163,1739137690.588237,32.28996920585632,0.6108,1739137690.5882385,32.28996920585632,1.0317211463022384,1739137690.5882404,32.28996920585632,0.0,1739137690.5882416,32.28996920585632,0.05901981608814188,1739137690.5882432,32.28996920585632,2.8665678009471716,1739137690.5882444,32.28996920585632,0.9620644978939552 +1739137690.6081352,32.30996918678284,48.2246132819328,1739137690.6081378,32.30996918678284,8.681626503334064,1739137690.6081405,32.30996918678284,59.45198386661118,1739137690.6081433,32.30996918678284,44.49887923702274,1739137690.6081443,32.30996918678284,7.433879237022743,1739137690.6081462,32.30996918678284,-2.8184330196169243,1739137690.6081474,32.30996918678284,2.2126557709969163,1739137690.608149,32.30996918678284,0.6108,1739137690.60815,32.30996918678284,1.0317211463022384,1739137690.6081514,32.30996918678284,0.0,1739137690.608153,32.30996918678284,0.06965664840828323,1739137690.6081545,32.30996918678284,2.8665678009471716,1739137690.608156,32.30996918678284,0.9620644978939552 +1739137690.6282806,32.32996916770935,48.2246132819328,1739137690.6282828,32.32996916770935,8.681626503334064,1739137690.6282854,32.32996916770935,59.45198386661118,1739137690.628288,32.32996916770935,44.49887923702274,1739137690.6282895,32.32996916770935,7.433879237022743,1739137690.6282911,32.32996916770935,-2.8184330196169243,1739137690.6282923,32.32996916770935,2.2126557709969163,1739137690.6282935,32.32996916770935,0.6108,1739137690.6282947,32.32996916770935,1.0317211463022384,1739137690.6282961,32.32996916770935,0.0,1739137690.6282976,32.32996916770935,0.06965664840828323,1739137690.6282988,32.32996916770935,2.8665678009471716,1739137690.6283,32.32996916770935,0.9620644978939552 +1739137690.6480799,32.349969148635864,48.2246132819328,1739137690.6480823,32.349969148635864,8.681626503334064,1739137690.6480849,32.349969148635864,59.45198386661118,1739137690.648088,32.349969148635864,44.49887923702274,1739137690.6480894,32.349969148635864,7.433879237022743,1739137690.648091,32.349969148635864,-2.8184330196169243,1739137690.6480925,32.349969148635864,2.2126557709969163,1739137690.6480937,32.349969148635864,0.6108,1739137690.648095,32.349969148635864,1.0317211463022384,1739137690.6480966,32.349969148635864,0.0,1739137690.6480978,32.349969148635864,0.06965664840828323,1739137690.6480992,32.349969148635864,2.8665678009471716,1739137690.6481004,32.349969148635864,0.9620644978939552 +1739137690.6700554,32.36996912956238,48.2246132819328,1739137690.6700587,32.36996912956238,8.681626503334064,1739137690.670063,32.36996912956238,59.45198386661118,1739137690.6700683,32.36996912956238,44.49887923702274,1739137690.6700714,32.36996912956238,7.433879237022743,1739137690.670075,32.36996912956238,-2.8184330196169243,1739137690.6700783,32.36996912956238,2.2126557709969163,1739137690.6700816,32.36996912956238,0.6108,1739137690.6700847,32.36996912956238,1.0317211463022384,1739137690.670088,32.36996912956238,0.0,1739137690.6700912,32.36996912956238,0.06965664840828323,1739137690.6700952,32.36996912956238,2.8665678009471716,1739137690.6700985,32.36996912956238,0.9620644978939552 +1739137690.6880844,32.38996911048889,48.2246132819328,1739137690.688087,32.38996911048889,8.681626503334064,1739137690.68809,32.38996911048889,59.45198386661118,1739137690.6880927,32.38996911048889,44.49887923702274,1739137690.688094,32.38996911048889,7.433879237022743,1739137690.6880958,32.38996911048889,-2.8184330196169243,1739137690.6880972,32.38996911048889,2.2126557709969163,1739137690.6880987,32.38996911048889,0.6108,1739137690.6880999,32.38996911048889,1.0317211463022384,1739137690.6881013,32.38996911048889,0.0,1739137690.6881027,32.38996911048889,0.06965664840828323,1739137690.6881042,32.38996911048889,2.8665678009471716,1739137690.6881056,32.38996911048889,0.9620644978939552 +1739137690.7082133,32.409969091415405,48.122063721724764,1739137690.7082157,32.409969091415405,8.709177123163895,1739137690.708219,32.409969091415405,59.53909973393019,1739137690.7082217,32.409969091415405,44.42308557198397,1739137690.7082233,32.409969091415405,7.355015231367353,1739137690.7082248,32.409969091415405,-2.790655568831423,1739137690.7082262,32.409969091415405,2.2188152183365712,1739137690.7082274,32.409969091415405,0.6108,1739137690.7082286,32.409969091415405,1.0291823422844817,1739137690.7082305,32.409969091415405,0.0,1739137690.708232,32.409969091415405,0.05063597601855431,1739137690.708233,32.409969091415405,2.8941730151480862,1739137690.7082345,32.409969091415405,0.9694888986985986 +1739137690.7302423,32.42996907234192,48.122063721724764,1739137690.7302458,32.42996907234192,8.709177123163895,1739137690.7302504,32.42996907234192,59.53909973393019,1739137690.7302554,32.42996907234192,44.42308557198397,1739137690.7302582,32.42996907234192,7.355015231367353,1739137690.7302618,32.42996907234192,-2.790655568831423,1739137690.730265,32.42996907234192,2.2188152183365712,1739137690.7302685,32.42996907234192,0.6108,1739137690.7302718,32.42996907234192,1.0291823422844817,1739137690.7302752,32.42996907234192,0.0,1739137690.7302785,32.42996907234192,0.05969344358588313,1739137690.730282,32.42996907234192,2.8941730151480862,1739137690.7302854,32.42996907234192,0.9694888986985986 +1739137690.7481961,32.44996905326843,48.122063721724764,1739137690.7481987,32.44996905326843,8.709177123163895,1739137690.7482018,32.44996905326843,59.53909973393019,1739137690.7482045,32.44996905326843,44.42308557198397,1739137690.748206,32.44996905326843,7.355015231367353,1739137690.7482073,32.44996905326843,-2.790655568831423,1739137690.748209,32.44996905326843,2.2188152183365712,1739137690.7482102,32.44996905326843,0.6108,1739137690.7482111,32.44996905326843,1.0291823422844817,1739137690.748213,32.44996905326843,0.0,1739137690.748214,32.44996905326843,0.05969344358588313,1739137690.748216,32.44996905326843,2.8941730151480862,1739137690.748217,32.44996905326843,0.9694888986985986 +1739137690.768477,32.469969034194946,48.122063721724764,1739137690.7684793,32.469969034194946,8.709177123163895,1739137690.7684817,32.469969034194946,59.53909973393019,1739137690.7684844,32.469969034194946,44.42308557198397,1739137690.7684855,32.469969034194946,7.355015231367353,1739137690.7684872,32.469969034194946,-2.790655568831423,1739137690.7684884,32.469969034194946,2.2188152183365712,1739137690.7684898,32.469969034194946,0.6108,1739137690.768491,32.469969034194946,1.0291823422844817,1739137690.7684925,32.469969034194946,0.0,1739137690.7684937,32.469969034194946,0.05969344358588313,1739137690.7684953,32.469969034194946,2.8941730151480862,1739137690.7684968,32.469969034194946,0.9694888986985986 +1739137690.7880974,32.48996901512146,48.122063721724764,1739137690.7880998,32.48996901512146,8.709177123163895,1739137690.7881026,32.48996901512146,59.53909973393019,1739137690.7881055,32.48996901512146,44.42308557198397,1739137690.788107,32.48996901512146,7.355015231367353,1739137690.7881088,32.48996901512146,-2.790655568831423,1739137690.7881103,32.48996901512146,2.2188152183365712,1739137690.7881117,32.48996901512146,0.6108,1739137690.7881129,32.48996901512146,1.0291823422844817,1739137690.788114,32.48996901512146,0.0,1739137690.7881157,32.48996901512146,0.05969344358588313,1739137690.788117,32.48996901512146,2.8941730151480862,1739137690.7881184,32.48996901512146,0.9694888986985986 +1739137690.8082647,32.509968996047974,48.018037976677114,1739137690.808268,32.509968996047974,8.734067601421195,1739137690.8082712,32.509968996047974,59.62526134253064,1739137690.808274,32.509968996047974,44.35169115477723,1739137690.8082752,32.509968996047974,7.27730187886867,1739137690.8082771,32.509968996047974,-2.7633863157376224,1739137690.8082788,32.509968996047974,2.221154409890724,1739137690.80828,32.509968996047974,0.6108,1739137690.8082817,32.509968996047974,1.0282198108067042,1739137690.8082829,32.509968996047974,0.0,1739137690.8082845,32.509968996047974,0.04552834270017582,1739137690.808286,32.509968996047974,2.921778229349001,1739137690.8082871,32.509968996047974,0.9759461786009105 +1739137690.8287392,32.52996897697449,48.018037976677114,1739137690.8287427,32.52996897697449,8.734067601421195,1739137690.8287458,32.52996897697449,59.62526134253064,1739137690.828749,32.52996897697449,44.35169115477723,1739137690.8287506,32.52996897697449,7.27730187886867,1739137690.828753,32.52996897697449,-2.7633863157376224,1739137690.828755,32.52996897697449,2.221154409890724,1739137690.8287563,32.52996897697449,0.6108,1739137690.8287578,32.52996897697449,1.0282198108067042,1739137690.8287592,32.52996897697449,0.0,1739137690.8287606,32.52996897697449,0.05227363220579373,1739137690.828762,32.52996897697449,2.921778229349001,1739137690.8287637,32.52996897697449,0.9759461786009105 +1739137690.8504355,32.549968957901,48.018037976677114,1739137690.8504398,32.549968957901,8.734067601421195,1739137690.8504446,32.549968957901,59.62526134253064,1739137690.8504503,32.549968957901,44.35169115477723,1739137690.8504531,32.549968957901,7.27730187886867,1739137690.8504572,32.549968957901,-2.7633863157376224,1739137690.8504608,32.549968957901,2.221154409890724,1739137690.8504643,32.549968957901,0.6108,1739137690.8504868,32.549968957901,1.0282198108067042,1739137690.8504922,32.549968957901,0.0,1739137690.8504965,32.549968957901,0.05227363220579373,1739137690.8505013,32.549968957901,2.921778229349001,1739137690.8505058,32.549968957901,0.9759461786009105 +1739137690.8682075,32.569968938827515,48.018037976677114,1739137690.8682096,32.569968938827515,8.734067601421195,1739137690.8682122,32.569968938827515,59.62526134253064,1739137690.8682153,32.569968938827515,44.35169115477723,1739137690.8682168,32.569968938827515,7.27730187886867,1739137690.8682184,32.569968938827515,-2.7633863157376224,1739137690.8682196,32.569968938827515,2.221154409890724,1739137690.868221,32.569968938827515,0.6108,1739137690.8682222,32.569968938827515,1.0282198108067042,1739137690.8682237,32.569968938827515,0.0,1739137690.868225,32.569968938827515,0.05227363220579373,1739137690.8682265,32.569968938827515,2.921778229349001,1739137690.868228,32.569968938827515,0.9759461786009105 +1739137690.8881335,32.58996891975403,48.018037976677114,1739137690.8881364,32.58996891975403,8.734067601421195,1739137690.8881395,32.58996891975403,59.62526134253064,1739137690.8881423,32.58996891975403,44.35169115477723,1739137690.8881438,32.58996891975403,7.27730187886867,1739137690.8881457,32.58996891975403,-2.7633863157376224,1739137690.8881469,32.58996891975403,2.221154409890724,1739137690.8881483,32.58996891975403,0.6108,1739137690.8881497,32.58996891975403,1.0282198108067042,1739137690.8881514,32.58996891975403,0.0,1739137690.8881526,32.58996891975403,0.05227363220579373,1739137690.888154,32.58996891975403,2.921778229349001,1739137690.8881557,32.58996891975403,0.9759461786009105 +1739137690.908107,32.60996890068054,48.018037976677114,1739137690.90811,32.60996890068054,8.734067601421195,1739137690.908113,32.60996890068054,59.62526134253064,1739137690.9081156,32.60996890068054,44.35169115477723,1739137690.908117,32.60996890068054,7.27730187886867,1739137690.9081185,32.60996890068054,-2.7633863157376224,1739137690.90812,32.60996890068054,2.221154409890724,1739137690.9081213,32.60996890068054,0.6108,1739137690.9081225,32.60996890068054,1.0282198108067042,1739137690.908124,32.60996890068054,0.0,1739137690.9081252,32.60996890068054,0.05227363220579373,1739137690.9081273,32.60996890068054,2.921778229349001,1739137690.9081285,32.60996890068054,0.9759461786009105 +1739137690.928769,32.629968881607056,47.91271635420337,1739137690.928771,32.629968881607056,8.756213873251665,1739137690.9287739,32.629968881607056,59.78765174913872,1739137690.9287767,32.629968881607056,44.23469690871908,1739137690.928778,32.629968881607056,7.141606608101788,1739137690.9287798,32.629968881607056,-2.7279337533054178,1739137690.928781,32.629968881607056,2.2874779219982626,1739137690.9287827,32.629968881607056,0.6108,1739137690.9287837,32.629968881607056,1.0013004078728591,1739137690.928785,32.629968881607056,0.0,1739137690.9287865,32.629968881607056,-0.00980149850089054,1739137690.928788,32.629968881607056,2.9493834435499156,1739137690.9287891,32.629968881607056,0.9815423055566356 +1739137690.9481595,32.64996886253357,47.91271635420337,1739137690.9481623,32.64996886253357,8.756213873251665,1739137690.9481657,32.64996886253357,59.78765174913872,1739137690.9481685,32.64996886253357,44.23469690871908,1739137690.94817,32.64996886253357,7.141606608101788,1739137690.9481716,32.64996886253357,-2.7279337533054178,1739137690.948173,32.64996886253357,2.2874779219982626,1739137690.9481742,32.64996886253357,0.6108,1739137690.948176,32.64996886253357,1.0013004078728591,1739137690.9481773,32.64996886253357,0.0,1739137690.9481785,32.64996886253357,0.019758102316223547,1739137690.94818,32.64996886253357,2.9493834435499156,1739137690.9481812,32.64996886253357,0.9815423055566356 +1739137690.9687116,32.66996884346008,47.91271635420337,1739137690.9687142,32.66996884346008,8.756213873251665,1739137690.9687173,32.66996884346008,59.78765174913872,1739137690.9687204,32.66996884346008,44.23469690871908,1739137690.9687219,32.66996884346008,7.141606608101788,1739137690.9687238,32.66996884346008,-2.7279337533054178,1739137690.9687252,32.66996884346008,2.2874779219982626,1739137690.9687269,32.66996884346008,0.6108,1739137690.968728,32.66996884346008,1.0013004078728591,1739137690.9687295,32.66996884346008,0.0,1739137690.9687312,32.66996884346008,0.019758102316223547,1739137690.9687328,32.66996884346008,2.9493834435499156,1739137690.9687345,32.66996884346008,0.9815423055566356 +1739137690.9885669,32.6899688243866,47.91271635420337,1739137690.9885705,32.6899688243866,8.756213873251665,1739137690.988574,32.6899688243866,59.78765174913872,1739137690.9885776,32.6899688243866,44.23469690871908,1739137690.9885793,32.6899688243866,7.141606608101788,1739137690.9885814,32.6899688243866,-2.7279337533054178,1739137690.9885828,32.6899688243866,2.2874779219982626,1739137690.988585,32.6899688243866,0.6108,1739137690.9885862,32.6899688243866,1.0013004078728591,1739137690.988588,32.6899688243866,0.0,1739137690.9885893,32.6899688243866,0.019758102316223547,1739137690.9885917,32.6899688243866,2.9493834435499156,1739137690.9885933,32.6899688243866,0.9815423055566356 +1739137691.008399,32.70996880531311,47.91271635420337,1739137691.0084014,32.70996880531311,8.756213873251665,1739137691.0084043,32.70996880531311,59.78765174913872,1739137691.008407,32.70996880531311,44.23469690871908,1739137691.0084085,32.70996880531311,7.141606608101788,1739137691.0084102,32.70996880531311,-2.7279337533054178,1739137691.0084116,32.70996880531311,2.2874779219982626,1739137691.008413,32.70996880531311,0.6108,1739137691.0084147,32.70996880531311,1.0013004078728591,1739137691.0084162,32.70996880531311,0.0,1739137691.0084176,32.70996880531311,0.019758102316223547,1739137691.0084193,32.70996880531311,2.9493834435499156,1739137691.008421,32.70996880531311,0.9815423055566356 +1739137691.0287023,32.729968786239624,47.80639892930404,1739137691.0287051,32.729968786239624,8.775522778968732,1739137691.028708,32.729968786239624,59.87285348616018,1739137691.0287106,32.729968786239624,44.177185949875735,1739137691.0287123,32.729968786239624,7.071230416150364,1739137691.028714,32.729968786239624,-2.702556295130096,1739137691.0287156,32.729968786239624,2.2759449734680874,1739137691.028717,32.729968786239624,0.6108,1739137691.0287182,32.729968786239624,1.005930257251861,1739137691.0287201,32.729968786239624,0.0,1739137691.0287213,32.729968786239624,0.024975040048281806,1739137691.028723,32.729968786239624,2.97698865775083,1739137691.0287244,32.729968786239624,0.983439474507459 +1739137691.0488443,32.74996876716614,47.80639892930404,1739137691.0488465,32.74996876716614,8.775522778968732,1739137691.0488493,32.74996876716614,59.87285348616018,1739137691.0488522,32.74996876716614,44.177185949875735,1739137691.0488539,32.74996876716614,7.071230416150364,1739137691.0488555,32.74996876716614,-2.702556295130096,1739137691.048857,32.74996876716614,2.2759449734680874,1739137691.0488584,32.74996876716614,0.6108,1739137691.0488598,32.74996876716614,1.005930257251861,1739137691.0488615,32.74996876716614,0.0,1739137691.048863,32.74996876716614,0.02249078274440186,1739137691.0488646,32.74996876716614,2.97698865775083,1739137691.0488658,32.74996876716614,0.983439474507459 +1739137691.068883,32.76996874809265,47.80639892930404,1739137691.0688856,32.76996874809265,8.775522778968732,1739137691.0688887,32.76996874809265,59.87285348616018,1739137691.0688913,32.76996874809265,44.177185949875735,1739137691.068893,32.76996874809265,7.071230416150364,1739137691.0688946,32.76996874809265,-2.702556295130096,1739137691.068896,32.76996874809265,2.2759449734680874,1739137691.0688975,32.76996874809265,0.6108,1739137691.068899,32.76996874809265,1.005930257251861,1739137691.0689003,32.76996874809265,0.0,1739137691.0689018,32.76996874809265,0.02249078274440186,1739137691.0689034,32.76996874809265,2.97698865775083,1739137691.0689046,32.76996874809265,0.983439474507459 +1739137691.0885625,32.789968729019165,47.80639892930404,1739137691.088567,32.789968729019165,8.775522778968732,1739137691.0885746,32.789968729019165,59.87285348616018,1739137691.088593,32.789968729019165,44.177185949875735,1739137691.0885968,32.789968729019165,7.071230416150364,1739137691.0885992,32.789968729019165,-2.702556295130096,1739137691.0886018,32.789968729019165,2.2759449734680874,1739137691.088605,32.789968729019165,0.6108,1739137691.0886068,32.789968729019165,1.005930257251861,1739137691.0886168,32.789968729019165,0.0,1739137691.0886185,32.789968729019165,0.02249078274440186,1739137691.0886207,32.789968729019165,2.97698865775083,1739137691.0886292,32.789968729019165,0.983439474507459 +1739137691.1083775,32.80996870994568,47.80639892930404,1739137691.1083803,32.80996870994568,8.775522778968732,1739137691.1083837,32.80996870994568,59.87285348616018,1739137691.108387,32.80996870994568,44.177185949875735,1739137691.1083887,32.80996870994568,7.071230416150364,1739137691.1083906,32.80996870994568,-2.702556295130096,1739137691.1083922,32.80996870994568,2.2759449734680874,1739137691.1083937,32.80996870994568,0.6108,1739137691.108395,32.80996870994568,1.005930257251861,1739137691.1083968,32.80996870994568,0.0,1739137691.1083984,32.80996870994568,0.02249078274440186,1739137691.1084,32.80996870994568,2.97698865775083,1739137691.1084018,32.80996870994568,0.983439474507459 +1739137691.1291878,32.82996869087219,47.80639892930404,1739137691.1291902,32.82996869087219,8.775522778968732,1739137691.129193,32.82996869087219,59.87285348616018,1739137691.1291957,32.82996869087219,44.177185949875735,1739137691.1291974,32.82996869087219,7.071230416150364,1739137691.129199,32.82996869087219,-2.702556295130096,1739137691.1292007,32.82996869087219,2.2759449734680874,1739137691.129202,32.82996869087219,0.6108,1739137691.1292036,32.82996869087219,1.005930257251861,1739137691.129205,32.82996869087219,0.0,1739137691.1292062,32.82996869087219,0.02249078274440186,1739137691.1292078,32.82996869087219,2.97698865775083,1739137691.129209,32.82996869087219,0.983439474507459 +1739137691.1507075,32.849968671798706,47.69934538685268,1739137691.15071,32.849968671798706,8.791926923252829,1739137691.1507132,32.849968671798706,59.9577997530382,1739137691.1507158,32.849968671798706,44.12158941668177,1739137691.1507175,32.849968671798706,6.997315047488433,1739137691.1507194,32.849968671798706,-2.676663746663074,1739137691.150721,32.849968671798706,2.2664133734099394,1739137691.1507225,32.849968671798706,0.6108,1739137691.150724,32.849968671798706,1.0097728277255527,1739137691.1507254,32.849968671798706,0.0,1739137691.1507268,32.849968671798706,0.02502573044667528,1739137691.150729,32.849968671798706,3.004593871951745,1739137691.1507301,32.849968671798706,0.9859542158353494 +1739137691.16867,32.86996865272522,47.69934538685268,1739137691.1686726,32.86996865272522,8.791926923252829,1739137691.1686754,32.86996865272522,59.9577997530382,1739137691.168678,32.86996865272522,44.12158941668177,1739137691.1686795,32.86996865272522,6.997315047488433,1739137691.1686811,32.86996865272522,-2.676663746663074,1739137691.1686828,32.86996865272522,2.2664133734099394,1739137691.1686842,32.86996865272522,0.6108,1739137691.1686857,32.86996865272522,1.0097728277255527,1739137691.1686873,32.86996865272522,0.0,1739137691.1686885,32.86996865272522,0.02381861189020329,1739137691.1686902,32.86996865272522,3.004593871951745,1739137691.1686914,32.86996865272522,0.9859542158353494 +1739137691.188274,32.88996863365173,47.69934538685268,1739137691.1882775,32.88996863365173,8.791926923252829,1739137691.188282,32.88996863365173,59.9577997530382,1739137691.188285,32.88996863365173,44.12158941668177,1739137691.1882868,32.88996863365173,6.997315047488433,1739137691.1882887,32.88996863365173,-2.676663746663074,1739137691.1882904,32.88996863365173,2.2664133734099394,1739137691.1882918,32.88996863365173,0.6108,1739137691.1882935,32.88996863365173,1.0097728277255527,1739137691.188295,32.88996863365173,0.0,1739137691.1882968,32.88996863365173,0.02381861189020329,1739137691.1882985,32.88996863365173,3.004593871951745,1739137691.1883,32.88996863365173,0.9859542158353494 +1739137691.208293,32.90996861457825,47.69934538685268,1739137691.2082956,32.90996861457825,8.791926923252829,1739137691.208299,32.90996861457825,59.9577997530382,1739137691.208302,32.90996861457825,44.12158941668177,1739137691.208304,32.90996861457825,6.997315047488433,1739137691.2083056,32.90996861457825,-2.676663746663074,1739137691.2083073,32.90996861457825,2.2664133734099394,1739137691.2083085,32.90996861457825,0.6108,1739137691.2083101,32.90996861457825,1.0097728277255527,1739137691.2083116,32.90996861457825,0.0,1739137691.2083132,32.90996861457825,0.02381861189020329,1739137691.208315,32.90996861457825,3.004593871951745,1739137691.208316,32.90996861457825,0.9859542158353494 +1739137691.2285633,32.92996859550476,47.69934538685268,1739137691.2285657,32.92996859550476,8.791926923252829,1739137691.2285688,32.92996859550476,59.9577997530382,1739137691.2285717,32.92996859550476,44.12158941668177,1739137691.228573,32.92996859550476,6.997315047488433,1739137691.2285752,32.92996859550476,-2.676663746663074,1739137691.2285767,32.92996859550476,2.2664133734099394,1739137691.2285783,32.92996859550476,0.6108,1739137691.2285795,32.92996859550476,1.0097728277255527,1739137691.2285814,32.92996859550476,0.0,1739137691.2285826,32.92996859550476,0.02381861189020329,1739137691.2285843,32.92996859550476,3.004593871951745,1739137691.2285857,32.92996859550476,0.9859542158353494 +1739137691.2503142,32.949968576431274,47.59160226630709,1739137691.2503183,32.949968576431274,8.805404649238355,1739137691.2503235,32.949968576431274,59.97718084806166,1739137691.250329,32.949968576431274,44.10521160104179,1739137691.2503324,32.949968576431274,6.975547064675794,1739137691.2503364,32.949968576431274,-2.658257526843241,1739137691.25034,32.949968576431274,2.1995480800770073,1739137691.250344,32.949968576431274,0.6108,1739137691.2503476,32.949968576431274,1.0371447448088371,1739137691.2503514,32.949968576431274,0.0,1739137691.250355,32.949968576431274,0.07107228549427723,1739137691.2503588,32.949968576431274,3.0321990861526595,1739137691.2503624,32.949968576431274,0.9885742198904457 +1739137691.2706754,32.96996855735779,47.59160226630709,1739137691.2706778,32.96996855735779,8.805404649238355,1739137691.270681,32.96996855735779,59.97718084806166,1739137691.2706833,32.96996855735779,44.10521160104179,1739137691.270685,32.96996855735779,6.975547064675794,1739137691.2706864,32.96996855735779,-2.658257526843241,1739137691.2706878,32.96996855735779,2.1995480800770073,1739137691.2706892,32.96996855735779,0.6108,1739137691.2706904,32.96996855735779,1.0371447448088371,1739137691.270692,32.96996855735779,0.0,1739137691.2706933,32.96996855735779,0.04857052491839142,1739137691.270695,32.96996855735779,3.0321990861526595,1739137691.2706964,32.96996855735779,0.9885742198904457 +1739137691.2884989,32.9899685382843,47.59160226630709,1739137691.288502,32.9899685382843,8.805404649238355,1739137691.2885056,32.9899685382843,59.97718084806166,1739137691.288509,32.9899685382843,44.10521160104179,1739137691.2885108,32.9899685382843,6.975547064675794,1739137691.288513,32.9899685382843,-2.658257526843241,1739137691.2885146,32.9899685382843,2.1995480800770073,1739137691.2885163,32.9899685382843,0.6108,1739137691.2885184,32.9899685382843,1.0371447448088371,1739137691.28852,32.9899685382843,0.0,1739137691.288522,32.9899685382843,0.04857052491839142,1739137691.2885237,32.9899685382843,3.0321990861526595,1739137691.2885253,32.9899685382843,0.9885742198904457 +1739137691.3086224,33.009968519210815,47.59160226630709,1739137691.3086252,33.009968519210815,8.805404649238355,1739137691.3086286,33.009968519210815,59.97718084806166,1739137691.3086317,33.009968519210815,44.10521160104179,1739137691.3086329,33.009968519210815,6.975547064675794,1739137691.308635,33.009968519210815,-2.658257526843241,1739137691.3086364,33.009968519210815,2.1995480800770073,1739137691.3086379,33.009968519210815,0.6108,1739137691.3086393,33.009968519210815,1.0371447448088371,1739137691.3086407,33.009968519210815,0.0,1739137691.3086424,33.009968519210815,0.04857052491839142,1739137691.3086438,33.009968519210815,3.0321990861526595,1739137691.3086455,33.009968519210815,0.9885742198904457 +1739137691.328897,33.02996850013733,47.59160226630709,1739137691.3288994,33.02996850013733,8.805404649238355,1739137691.3289025,33.02996850013733,59.97718084806166,1739137691.328905,33.02996850013733,44.10521160104179,1739137691.3289068,33.02996850013733,6.975547064675794,1739137691.3289082,33.02996850013733,-2.658257526843241,1739137691.3289099,33.02996850013733,2.1995480800770073,1739137691.328911,33.02996850013733,0.6108,1739137691.3289125,33.02996850013733,1.0371447448088371,1739137691.3289142,33.02996850013733,0.0,1739137691.3289154,33.02996850013733,0.04857052491839142,1739137691.328917,33.02996850013733,3.0321990861526595,1739137691.3289185,33.02996850013733,0.9885742198904457 +1739137691.3484392,33.04996848106384,47.59160226630709,1739137691.3484423,33.04996848106384,8.805404649238355,1739137691.3484461,33.04996848106384,59.97718084806166,1739137691.3484492,33.04996848106384,44.10521160104179,1739137691.348451,33.04996848106384,6.975547064675794,1739137691.3484528,33.04996848106384,-2.658257526843241,1739137691.3484545,33.04996848106384,2.1995480800770073,1739137691.348456,33.04996848106384,0.6108,1739137691.3484576,33.04996848106384,1.0371447448088371,1739137691.348459,33.04996848106384,0.0,1739137691.3484612,33.04996848106384,0.04857052491839142,1739137691.3484628,33.04996848106384,3.0321990861526595,1739137691.3484647,33.04996848106384,0.9885742198904457 +1739137691.3684516,33.069968461990356,47.483064184147274,1739137691.368454,33.069968461990356,8.815947665332754,1739137691.368457,33.069968461990356,60.201123758594,1739137691.3684597,33.069968461990356,43.96670455135334,1739137691.3684614,33.069968461990356,6.778065859739667,1739137691.368463,33.069968461990356,-2.6163508498506043,1739137691.3684645,33.069968461990356,2.3183462994627013,1739137691.3684657,33.069968461990356,0.6108,1739137691.3684669,33.069968461990356,0.9890130147801994,1739137691.3684688,33.069968461990356,0.0,1739137691.36847,33.069968461990356,-0.054335130057438605,1739137691.3684716,33.069968461990356,3.059804300353574,1739137691.3684728,33.069968461990356,0.9943454275130065 +1739137691.388482,33.08996844291687,47.483064184147274,1739137691.3884852,33.08996844291687,8.815947665332754,1739137691.3884885,33.08996844291687,60.201123758594,1739137691.3884916,33.08996844291687,43.96670455135334,1739137691.3884928,33.08996844291687,6.778065859739667,1739137691.3884945,33.08996844291687,-2.6163508498506043,1739137691.3884962,33.08996844291687,2.3183462994627013,1739137691.3884976,33.08996844291687,0.6108,1739137691.3884993,33.08996844291687,0.9890130147801994,1739137691.3885007,33.08996844291687,0.0,1739137691.3885021,33.08996844291687,-0.005332412732807046,1739137691.3885036,33.08996844291687,3.059804300353574,1739137691.388505,33.08996844291687,0.9943454275130065 +1739137691.4084802,33.109968423843384,47.483064184147274,1739137691.4084828,33.109968423843384,8.815947665332754,1739137691.4084861,33.109968423843384,60.201123758594,1739137691.408489,33.109968423843384,43.96670455135334,1739137691.4084904,33.109968423843384,6.778065859739667,1739137691.4084923,33.109968423843384,-2.6163508498506043,1739137691.4084938,33.109968423843384,2.3183462994627013,1739137691.4084957,33.109968423843384,0.6108,1739137691.4084969,33.109968423843384,0.9890130147801994,1739137691.4084985,33.109968423843384,0.0,1739137691.4085,33.109968423843384,-0.005332412732807046,1739137691.4085014,33.109968423843384,3.059804300353574,1739137691.408503,33.109968423843384,0.9943454275130065 +1739137691.428927,33.1299684047699,47.483064184147274,1739137691.4289296,33.1299684047699,8.815947665332754,1739137691.4289327,33.1299684047699,60.201123758594,1739137691.4289355,33.1299684047699,43.96670455135334,1739137691.428937,33.1299684047699,6.778065859739667,1739137691.4289389,33.1299684047699,-2.6163508498506043,1739137691.42894,33.1299684047699,2.3183462994627013,1739137691.4289412,33.1299684047699,0.6108,1739137691.428943,33.1299684047699,0.9890130147801994,1739137691.4289443,33.1299684047699,0.0,1739137691.428946,33.1299684047699,-0.005332412732807046,1739137691.4289474,33.1299684047699,3.059804300353574,1739137691.4289489,33.1299684047699,0.9943454275130065 +1739137691.4485626,33.14996838569641,47.483064184147274,1739137691.448566,33.14996838569641,8.815947665332754,1739137691.448569,33.14996838569641,60.201123758594,1739137691.4485722,33.14996838569641,43.96670455135334,1739137691.4485736,33.14996838569641,6.778065859739667,1739137691.4485755,33.14996838569641,-2.6163508498506043,1739137691.448577,33.14996838569641,2.3183462994627013,1739137691.448579,33.14996838569641,0.6108,1739137691.4485803,33.14996838569641,0.9890130147801994,1739137691.4485822,33.14996838569641,0.0,1739137691.4485836,33.14996838569641,-0.005332412732807046,1739137691.4485853,33.14996838569641,3.059804300353574,1739137691.4485867,33.14996838569641,0.9943454275130065 +1739137691.4688916,33.169968366622925,47.37401061224123,1739137691.468894,33.169968366622925,8.82351102059642,1739137691.468897,33.169968366622925,60.2846358592276,1739137691.4688997,33.169968366622925,43.9238766212808,1739137691.4689012,33.169968366622925,6.709995150721289,1739137691.4689028,33.169968366622925,-2.591967556316371,1739137691.4689045,33.169968366622925,2.2972618190638885,1739137691.4689057,33.169968366622925,0.6108,1739137691.468907,33.169968366622925,0.9973894177605441,1739137691.4689085,33.169968366622925,0.0,1739137691.46891,33.169968366622925,0.012620493706255462,1739137691.4689116,33.169968366622925,3.087409514554489,1739137691.4689128,33.169968366622925,0.9933179313911116 +1739137691.4884818,33.18996834754944,47.37401061224123,1739137691.4884849,33.18996834754944,8.82351102059642,1739137691.488488,33.18996834754944,60.2846358592276,1739137691.4884908,33.18996834754944,43.9238766212808,1739137691.4884925,33.18996834754944,6.709995150721289,1739137691.4884944,33.18996834754944,-2.591967556316371,1739137691.4884958,33.18996834754944,2.2972618190638885,1739137691.4884975,33.18996834754944,0.6108,1739137691.4884987,33.18996834754944,0.9973894177605441,1739137691.4885,33.18996834754944,0.0,1739137691.4885015,33.18996834754944,0.004071486369432553,1739137691.4885032,33.18996834754944,3.087409514554489,1739137691.4885046,33.18996834754944,0.9933179313911116 +1739137691.508449,33.20996832847595,47.37401061224123,1739137691.5084522,33.20996832847595,8.82351102059642,1739137691.5084553,33.20996832847595,60.2846358592276,1739137691.508458,33.20996832847595,43.9238766212808,1739137691.5084598,33.20996832847595,6.709995150721289,1739137691.5084617,33.20996832847595,-2.591967556316371,1739137691.5084631,33.20996832847595,2.2972618190638885,1739137691.5084646,33.20996832847595,0.6108,1739137691.508466,33.20996832847595,0.9973894177605441,1739137691.5084674,33.20996832847595,0.0,1739137691.5084686,33.20996832847595,0.004071486369432553,1739137691.5084705,33.20996832847595,3.087409514554489,1739137691.5084717,33.20996832847595,0.9933179313911116 +1739137691.5284207,33.229968309402466,47.37401061224123,1739137691.5284238,33.229968309402466,8.82351102059642,1739137691.5284276,33.229968309402466,60.2846358592276,1739137691.5284307,33.229968309402466,43.9238766212808,1739137691.528432,33.229968309402466,6.709995150721289,1739137691.528434,33.229968309402466,-2.591967556316371,1739137691.5284355,33.229968309402466,2.2972618190638885,1739137691.5284367,33.229968309402466,0.6108,1739137691.528438,33.229968309402466,0.9973894177605441,1739137691.52844,33.229968309402466,0.0,1739137691.5284417,33.229968309402466,0.004071486369432553,1739137691.5284433,33.229968309402466,3.087409514554489,1739137691.528445,33.229968309402466,0.9933179313911116 +1739137691.5484834,33.24996829032898,47.37401061224123,1739137691.5484865,33.24996829032898,8.82351102059642,1739137691.5484896,33.24996829032898,60.2846358592276,1739137691.5484922,33.24996829032898,43.9238766212808,1739137691.5484939,33.24996829032898,6.709995150721289,1739137691.5484955,33.24996829032898,-2.591967556316371,1739137691.5484974,33.24996829032898,2.2972618190638885,1739137691.5484986,33.24996829032898,0.6108,1739137691.5485003,33.24996829032898,0.9973894177605441,1739137691.5485017,33.24996829032898,0.0,1739137691.5485034,33.24996829032898,0.004071486369432553,1739137691.5485048,33.24996829032898,3.087409514554489,1739137691.548506,33.24996829032898,0.9933179313911116 +1739137691.5708852,33.26996827125549,47.37401061224123,1739137691.5708888,33.26996827125549,8.82351102059642,1739137691.5708933,33.26996827125549,60.2846358592276,1739137691.5708985,33.26996827125549,43.9238766212808,1739137691.5709012,33.26996827125549,6.709995150721289,1739137691.570905,33.26996827125549,-2.591967556316371,1739137691.5709083,33.26996827125549,2.2972618190638885,1739137691.5709116,33.26996827125549,0.6108,1739137691.570915,33.26996827125549,0.9973894177605441,1739137691.5709183,33.26996827125549,0.0,1739137691.5709217,33.26996827125549,0.004071486369432553,1739137691.570925,33.26996827125549,3.087409514554489,1739137691.5709283,33.26996827125549,0.9933179313911116 +1739137691.5881543,33.28996825218201,47.264805256680866,1739137691.5881567,33.28996825218201,8.828060307126469,1739137691.5881593,33.28996825218201,60.336109976014775,1739137691.5881617,33.28996825218201,43.89576672316869,1739137691.5881634,33.28996825218201,6.664683673167445,1739137691.5881648,33.28996825218201,-2.570766510692539,1739137691.5881662,33.28996825218201,2.252144100760697,1739137691.5881674,33.28996825218201,0.6108,1739137691.5881686,33.28996825218201,1.0155527967417404,1739137691.58817,33.28996825218201,0.0,1739137691.5881712,33.28996825218201,0.03757075547088261,1739137691.588173,33.28996825218201,3.1150147287554035,1739137691.588174,33.28996825218201,0.9939340821450515 +1739137691.6082397,33.30996823310852,47.264805256680866,1739137691.6082425,33.30996823310852,8.828060307126469,1739137691.6082451,33.30996823310852,60.336109976014775,1739137691.6082478,33.30996823310852,43.89576672316869,1739137691.6082492,33.30996823310852,6.664683673167445,1739137691.6082506,33.30996823310852,-2.570766510692539,1739137691.6082518,33.30996823310852,2.252144100760697,1739137691.6082532,33.30996823310852,0.6108,1739137691.6082544,33.30996823310852,1.0155527967417404,1739137691.608256,33.30996823310852,0.0,1739137691.608257,33.30996823310852,0.02161871459668885,1739137691.6082585,33.30996823310852,3.1150147287554035,1739137691.6082597,33.30996823310852,0.9939340821450515 +1739137691.6304293,33.329968214035034,47.264805256680866,1739137691.6304333,33.329968214035034,8.828060307126469,1739137691.6304379,33.329968214035034,60.336109976014775,1739137691.630443,33.329968214035034,43.89576672316869,1739137691.6304457,33.329968214035034,6.664683673167445,1739137691.6304498,33.329968214035034,-2.570766510692539,1739137691.630453,33.329968214035034,2.252144100760697,1739137691.6304562,33.329968214035034,0.6108,1739137691.6304595,33.329968214035034,1.0155527967417404,1739137691.630463,33.329968214035034,0.0,1739137691.6304662,33.329968214035034,0.02161871459668885,1739137691.6304786,33.329968214035034,3.1150147287554035,1739137691.6304822,33.329968214035034,0.9939340821450515 +1739137691.6482282,33.34996819496155,47.264805256680866,1739137691.648231,33.34996819496155,8.828060307126469,1739137691.6482337,33.34996819496155,60.336109976014775,1739137691.6482365,33.34996819496155,43.89576672316869,1739137691.6482377,33.34996819496155,6.664683673167445,1739137691.6482394,33.34996819496155,-2.570766510692539,1739137691.6482408,33.34996819496155,2.252144100760697,1739137691.6482422,33.34996819496155,0.6108,1739137691.6482434,33.34996819496155,1.0155527967417404,1739137691.6482446,33.34996819496155,0.0,1739137691.6482463,33.34996819496155,0.02161871459668885,1739137691.6482475,33.34996819496155,3.1150147287554035,1739137691.648249,33.34996819496155,0.9939340821450515 +1739137691.6704805,33.36996817588806,47.264805256680866,1739137691.6704845,33.36996817588806,8.828060307126469,1739137691.6705132,33.36996817588806,60.336109976014775,1739137691.6705186,33.36996817588806,43.89576672316869,1739137691.6705356,33.36996817588806,6.664683673167445,1739137691.6705399,33.36996817588806,-2.570766510692539,1739137691.6705432,33.36996817588806,2.252144100760697,1739137691.6705463,33.36996817588806,0.6108,1739137691.6705494,33.36996817588806,1.0155527967417404,1739137691.670553,33.36996817588806,0.0,1739137691.6705563,33.36996817588806,0.02161871459668885,1739137691.6705604,33.36996817588806,3.1150147287554035,1739137691.6705637,33.36996817588806,0.9939340821450515 +1739137691.6884048,33.389968156814575,47.1553585518476,1739137691.6884072,33.389968156814575,8.829595299338928,1739137691.68841,33.389968156814575,60.52551798830007,1739137691.6884127,33.389968156814575,43.797737879534026,1739137691.6884146,33.389968156814575,6.493887053698224,1739137691.688416,33.389968156814575,-2.533796251945822,1739137691.6884172,33.389968156814575,2.3322577657701653,1739137691.6884186,33.389968156814575,0.6108,1739137691.6884198,33.389968156814575,0.9835248501321863,1739137691.6884215,33.389968156814575,0.0,1739137691.6884224,33.389968156814575,-0.044321668584363726,1739137691.6884239,33.389968156814575,3.142619942956318,1739137691.688425,33.389968156814575,0.9964463205636113 +1739137691.7083087,33.40996813774109,47.1553585518476,1739137691.7083113,33.40996813774109,8.829595299338928,1739137691.7083142,33.40996813774109,60.52551798830007,1739137691.7083173,33.40996813774109,43.797737879534026,1739137691.7083182,33.40996813774109,6.493887053698224,1739137691.70832,33.40996813774109,-2.533796251945822,1739137691.7083216,33.40996813774109,2.3322577657701653,1739137691.7083228,33.40996813774109,0.6108,1739137691.7083242,33.40996813774109,0.9835248501321863,1739137691.7083254,33.40996813774109,0.0,1739137691.7083268,33.40996813774109,-0.012921470431424997,1739137691.7083285,33.40996813774109,3.142619942956318,1739137691.7083297,33.40996813774109,0.9964463205636113 +1739137691.7303019,33.4299681186676,47.1553585518476,1739137691.730305,33.4299681186676,8.829595299338928,1739137691.7303095,33.4299681186676,60.52551798830007,1739137691.7303143,33.4299681186676,43.797737879534026,1739137691.730317,33.4299681186676,6.493887053698224,1739137691.7303207,33.4299681186676,-2.533796251945822,1739137691.7303238,33.4299681186676,2.3322577657701653,1739137691.730327,33.4299681186676,0.6108,1739137691.7303302,33.4299681186676,0.9835248501321863,1739137691.7303333,33.4299681186676,0.0,1739137691.7303364,33.4299681186676,-0.012921470431424997,1739137691.7303398,33.4299681186676,3.142619942956318,1739137691.730343,33.4299681186676,0.9964463205636113 +1739137691.7483253,33.449968099594116,47.1553585518476,1739137691.748328,33.449968099594116,8.829595299338928,1739137691.7483306,33.449968099594116,60.52551798830007,1739137691.748333,33.449968099594116,43.797737879534026,1739137691.7483344,33.449968099594116,6.493887053698224,1739137691.7483358,33.449968099594116,-2.533796251945822,1739137691.7483373,33.449968099594116,2.3322577657701653,1739137691.7483385,33.449968099594116,0.6108,1739137691.7483397,33.449968099594116,0.9835248501321863,1739137691.7483413,33.449968099594116,0.0,1739137691.7483425,33.449968099594116,-0.012921470431424997,1739137691.7483437,33.449968099594116,3.142619942956318,1739137691.7483451,33.449968099594116,0.9964463205636113 +1739137691.7687938,33.46996808052063,47.1553585518476,1739137691.7687962,33.46996808052063,8.829595299338928,1739137691.7687988,33.46996808052063,60.52551798830007,1739137691.7688012,33.46996808052063,43.797737879534026,1739137691.7688024,33.46996808052063,6.493887053698224,1739137691.7688038,33.46996808052063,-2.533796251945822,1739137691.768805,33.46996808052063,2.3322577657701653,1739137691.7688065,33.46996808052063,0.6108,1739137691.7688076,33.46996808052063,0.9835248501321863,1739137691.7688088,33.46996808052063,0.0,1739137691.7688103,33.46996808052063,-0.012921470431424997,1739137691.7688117,33.46996808052063,3.142619942956318,1739137691.768813,33.46996808052063,0.9964463205636113 +1739137691.7882907,33.489968061447144,47.1553585518476,1739137691.7882931,33.489968061447144,8.829595299338928,1739137691.788296,33.489968061447144,60.52551798830007,1739137691.7882986,33.489968061447144,43.797737879534026,1739137691.7883,33.489968061447144,6.493887053698224,1739137691.7883015,33.489968061447144,-2.533796251945822,1739137691.7883031,33.489968061447144,2.3322577657701653,1739137691.7883043,33.489968061447144,0.6108,1739137691.7883058,33.489968061447144,0.9835248501321863,1739137691.788307,33.489968061447144,0.0,1739137691.7883081,33.489968061447144,-0.012921470431424997,1739137691.7883096,33.489968061447144,3.142619942956318,1739137691.7883108,33.489968061447144,0.9964463205636113 +1739137691.8086202,33.50996804237366,47.045893387227416,1739137691.808623,33.50996804237366,8.828109670790692,1739137691.8086262,33.50996804237366,60.60818154367622,1739137691.8086288,33.50996804237366,43.7614962924676,1739137691.8086302,33.50996804237366,6.426483763664837,1739137691.8086321,33.50996804237366,-2.510217683446033,1739137691.8086333,33.50996804237366,2.306613860918437,1739137691.808635,33.50996804237366,0.6108,1739137691.8086362,33.50996804237366,0.9936653366238123,1739137691.8086376,33.50996804237366,0.0,1739137691.8086393,33.50996804237366,0.010332670975924687,1739137691.808641,33.50996804237366,3.170225157157233,1739137691.8086424,33.50996804237366,0.9944060718497043 +1739137691.8283968,33.52996802330017,47.045893387227416,1739137691.8283992,33.52996802330017,8.828109670790692,1739137691.8284023,33.52996802330017,60.60818154367622,1739137691.8284047,33.52996802330017,43.7614962924676,1739137691.8284063,33.52996802330017,6.426483763664837,1739137691.828408,33.52996802330017,-2.510217683446033,1739137691.8284094,33.52996802330017,2.306613860918437,1739137691.8284109,33.52996802330017,0.6108,1739137691.828412,33.52996802330017,0.9936653366238123,1739137691.8284137,33.52996802330017,0.0,1739137691.828415,33.52996802330017,-0.0007407352258920197,1739137691.8284166,33.52996802330017,3.170225157157233,1739137691.8284178,33.52996802330017,0.9944060718497043 +1739137691.8485155,33.549968004226685,47.045893387227416,1739137691.8485181,33.549968004226685,8.828109670790692,1739137691.8485212,33.549968004226685,60.60818154367622,1739137691.848524,33.549968004226685,43.7614962924676,1739137691.8485253,33.549968004226685,6.426483763664837,1739137691.8485272,33.549968004226685,-2.510217683446033,1739137691.8485286,33.549968004226685,2.306613860918437,1739137691.8485298,33.549968004226685,0.6108,1739137691.8485312,33.549968004226685,0.9936653366238123,1739137691.8485332,33.549968004226685,0.0,1739137691.8485348,33.549968004226685,-0.0007407352258920197,1739137691.8485363,33.549968004226685,3.170225157157233,1739137691.8485377,33.549968004226685,0.9944060718497043 +1739137691.8683605,33.5699679851532,47.045893387227416,1739137691.8683627,33.5699679851532,8.828109670790692,1739137691.8683653,33.5699679851532,60.60818154367622,1739137691.8683681,33.5699679851532,43.7614962924676,1739137691.8683693,33.5699679851532,6.426483763664837,1739137691.8683712,33.5699679851532,-2.510217683446033,1739137691.8683724,33.5699679851532,2.306613860918437,1739137691.8683739,33.5699679851532,0.6108,1739137691.8683755,33.5699679851532,0.9936653366238123,1739137691.868377,33.5699679851532,0.0,1739137691.8683784,33.5699679851532,-0.0007407352258920197,1739137691.8683798,33.5699679851532,3.170225157157233,1739137691.8683815,33.5699679851532,0.9944060718497043 +1739137691.8884227,33.58996796607971,47.045893387227416,1739137691.888425,33.58996796607971,8.828109670790692,1739137691.8884284,33.58996796607971,60.60818154367622,1739137691.8884315,33.58996796607971,43.7614962924676,1739137691.8884332,33.58996796607971,6.426483763664837,1739137691.8884346,33.58996796607971,-2.510217683446033,1739137691.8884363,33.58996796607971,2.306613860918437,1739137691.8884377,33.58996796607971,0.6108,1739137691.8884387,33.58996796607971,0.9936653366238123,1739137691.8884406,33.58996796607971,0.0,1739137691.8884418,33.58996796607971,-0.0007407352258920197,1739137691.8884435,33.58996796607971,3.170225157157233,1739137691.8884447,33.58996796607971,0.9944060718497043 +1739137691.9087484,33.609967947006226,46.93660218979064,1739137691.9087512,33.609967947006226,8.823606454828651,1739137691.9087546,33.609967947006226,60.69050275586816,1739137691.9087586,33.609967947006226,43.723655306569746,1739137691.9087603,33.609967947006226,6.353310613139494,1739137691.9087627,33.609967947006226,-2.486132059572797,1739137691.9087646,33.609967947006226,2.2857969208147786,1739137691.908767,33.609967947006226,0.6108,1739137691.9087691,33.609967947006226,1.0019739091470345,1739137691.908771,33.609967947006226,0.0,1739137691.908773,33.609967947006226,0.015084023722600978,1739137691.9087749,33.609967947006226,3.1978303713581475,1739137691.9087768,33.609967947006226,0.994425488688079 +1739137691.928623,33.62996792793274,46.93660218979064,1739137691.9286253,33.62996792793274,8.823606454828651,1739137691.9286287,33.62996792793274,60.69050275586816,1739137691.9286318,33.62996792793274,43.723655306569746,1739137691.9286335,33.62996792793274,6.353310613139494,1739137691.9286351,33.62996792793274,-2.486132059572797,1739137691.928637,33.62996792793274,2.2857969208147786,1739137691.9286385,33.62996792793274,0.6108,1739137691.92864,33.62996792793274,1.0019739091470345,1739137691.9286416,33.62996792793274,0.0,1739137691.928643,33.62996792793274,0.00754842045895554,1739137691.928645,33.62996792793274,3.1978303713581475,1739137691.9286463,33.62996792793274,0.994425488688079 +1739137691.9487174,33.64996790885925,46.93660218979064,1739137691.9487207,33.64996790885925,8.823606454828651,1739137691.948724,33.64996790885925,60.69050275586816,1739137691.9487271,33.64996790885925,43.723655306569746,1739137691.9487286,33.64996790885925,6.353310613139494,1739137691.9487305,33.64996790885925,-2.486132059572797,1739137691.9487321,33.64996790885925,2.2857969208147786,1739137691.9487338,33.64996790885925,0.6108,1739137691.9487352,33.64996790885925,1.0019739091470345,1739137691.948737,33.64996790885925,0.0,1739137691.9487386,33.64996790885925,0.00754842045895554,1739137691.94874,33.64996790885925,3.1978303713581475,1739137691.9487417,33.64996790885925,0.994425488688079 +1739137691.9687846,33.66996788978577,46.93660218979064,1739137691.9687872,33.66996788978577,8.823606454828651,1739137691.9687905,33.66996788978577,60.69050275586816,1739137691.9687936,33.66996788978577,43.723655306569746,1739137691.968795,33.66996788978577,6.353310613139494,1739137691.968797,33.66996788978577,-2.486132059572797,1739137691.9687984,33.66996788978577,2.2857969208147786,1739137691.9688,33.66996788978577,0.6108,1739137691.9688013,33.66996788978577,1.0019739091470345,1739137691.9688032,33.66996788978577,0.0,1739137691.9688046,33.66996788978577,0.00754842045895554,1739137691.968806,33.66996788978577,3.1978303713581475,1739137691.9688077,33.66996788978577,0.994425488688079 +1739137691.9887388,33.68996787071228,46.93660218979064,1739137691.9887419,33.68996787071228,8.823606454828651,1739137691.9887455,33.68996787071228,60.69050275586816,1739137691.9887486,33.68996787071228,43.723655306569746,1739137691.9887502,33.68996787071228,6.353310613139494,1739137691.9887524,33.68996787071228,-2.486132059572797,1739137691.988754,33.68996787071228,2.2857969208147786,1739137691.9887555,33.68996787071228,0.6108,1739137691.988757,33.68996787071228,1.0019739091470345,1739137691.9887588,33.68996787071228,0.0,1739137691.9887602,33.68996787071228,0.00754842045895554,1739137691.9887621,33.68996787071228,3.1978303713581475,1739137691.9887633,33.68996787071228,0.994425488688079 +1739137692.0086927,33.709967851638794,46.93660218979064,1739137692.0086956,33.709967851638794,8.823606454828651,1739137692.008699,33.709967851638794,60.69050275586816,1739137692.008702,33.709967851638794,43.723655306569746,1739137692.0087032,33.709967851638794,6.353310613139494,1739137692.0087054,33.709967851638794,-2.486132059572797,1739137692.008707,33.709967851638794,2.2857969208147786,1739137692.0087087,33.709967851638794,0.6108,1739137692.00871,33.709967851638794,1.0019739091470345,1739137692.008712,33.709967851638794,0.0,1739137692.0087135,33.709967851638794,0.00754842045895554,1739137692.0087152,33.709967851638794,3.1978303713581475,1739137692.0087168,33.709967851638794,0.994425488688079 +1739137692.0292406,33.72996783256531,46.82742194455661,1739137692.0292435,33.72996783256531,8.81608433106488,1739137692.029247,33.72996783256531,60.78777078284683,1739137692.02925,33.72996783256531,43.67937863147804,1739137692.0292513,33.72996783256531,6.263427165204505,1739137692.0292535,33.72996783256531,-2.4602580880867055,1739137692.029255,33.72996783256531,2.28005823870938,1739137692.0292568,33.72996783256531,0.6108,1739137692.029258,33.72996783256531,1.0042765548632964,1739137692.0292597,33.72996783256531,0.0,1739137692.0292614,33.72996783256531,0.01007892325643936,1739137692.0292628,33.72996783256531,3.225435585559062,1739137692.0292645,33.72996783256531,0.9954026335409433 +1739137692.0487,33.74996781349182,46.82742194455661,1739137692.0487032,33.74996781349182,8.81608433106488,1739137692.0487068,33.74996781349182,60.78777078284683,1739137692.0487099,33.74996781349182,43.67937863147804,1739137692.0487115,33.74996781349182,6.263427165204505,1739137692.0487137,33.74996781349182,-2.4602580880867055,1739137692.0487154,33.74996781349182,2.28005823870938,1739137692.0487168,33.74996781349182,0.6108,1739137692.0487185,33.74996781349182,1.0042765548632964,1739137692.0487201,33.74996781349182,0.0,1739137692.048722,33.74996781349182,0.008873921322353095,1739137692.0487235,33.74996781349182,3.225435585559062,1739137692.048725,33.74996781349182,0.9954026335409433 +1739137692.0692663,33.769967794418335,46.82742194455661,1739137692.069269,33.769967794418335,8.81608433106488,1739137692.0692723,33.769967794418335,60.78777078284683,1739137692.0692756,33.769967794418335,43.67937863147804,1739137692.0692773,33.769967794418335,6.263427165204505,1739137692.069279,33.769967794418335,-2.4602580880867055,1739137692.0692809,33.769967794418335,2.28005823870938,1739137692.0692823,33.769967794418335,0.6108,1739137692.0692837,33.769967794418335,1.0042765548632964,1739137692.0692856,33.769967794418335,0.0,1739137692.0692868,33.769967794418335,0.008873921322353095,1739137692.0692887,33.769967794418335,3.225435585559062,1739137692.0692902,33.769967794418335,0.9954026335409433 +1739137692.0887008,33.78996777534485,46.82742194455661,1739137692.0887034,33.78996777534485,8.81608433106488,1739137692.0887067,33.78996777534485,60.78777078284683,1739137692.0887098,33.78996777534485,43.67937863147804,1739137692.0887115,33.78996777534485,6.263427165204505,1739137692.0887134,33.78996777534485,-2.4602580880867055,1739137692.088715,33.78996777534485,2.28005823870938,1739137692.0887165,33.78996777534485,0.6108,1739137692.0887182,33.78996777534485,1.0042765548632964,1739137692.0887198,33.78996777534485,0.0,1739137692.088721,33.78996777534485,0.008873921322353095,1739137692.088723,33.78996777534485,3.225435585559062,1739137692.0887244,33.78996777534485,0.9954026335409433 +1739137692.108642,33.80996775627136,46.82742194455661,1739137692.1086452,33.80996775627136,8.81608433106488,1739137692.1086485,33.80996775627136,60.78777078284683,1739137692.1086516,33.80996775627136,43.67937863147804,1739137692.108653,33.80996775627136,6.263427165204505,1739137692.1086547,33.80996775627136,-2.4602580880867055,1739137692.1086564,33.80996775627136,2.28005823870938,1739137692.1086578,33.80996775627136,0.6108,1739137692.1086595,33.80996775627136,1.0042765548632964,1739137692.1086612,33.80996775627136,0.0,1739137692.1086626,33.80996775627136,0.008873921322353095,1739137692.1086643,33.80996775627136,3.225435585559062,1739137692.108666,33.80996775627136,0.9954026335409433 +1739137692.1287472,33.829967737197876,46.71839025506525,1739137692.1287498,33.829967737197876,8.805541763654523,1739137692.128753,33.829967737197876,60.99919662658323,1739137692.128756,33.829967737197876,43.59138240117155,1739137692.1287575,33.829967737197876,6.067991168120788,1739137692.1287594,33.829967737197876,-2.4225057489208064,1739137692.1287608,33.829967737197876,2.3727888098843595,1739137692.1287625,33.829967737197876,0.6108,1739137692.128764,33.829967737197876,0.9677080948595027,1739137692.1287653,33.829967737197876,0.0,1739137692.128767,33.829967737197876,-0.06281496153085578,1739137692.1287687,33.829967737197876,3.253040799759977,1739137692.1287704,33.829967737197876,0.9963854760737129 +1739137692.1487012,33.84996771812439,46.71839025506525,1739137692.1487043,33.84996771812439,8.805541763654523,1739137692.1487079,33.84996771812439,60.99919662658323,1739137692.148711,33.84996771812439,43.59138240117155,1739137692.1487126,33.84996771812439,6.067991168120788,1739137692.1487145,33.84996771812439,-2.4225057489208064,1739137692.1487162,33.84996771812439,2.3727888098843595,1739137692.1487179,33.84996771812439,0.6108,1739137692.1487193,33.84996771812439,0.9677080948595027,1739137692.1487212,33.84996771812439,0.0,1739137692.148723,33.84996771812439,-0.02867738121421015,1739137692.1487248,33.84996771812439,3.253040799759977,1739137692.1487262,33.84996771812439,0.9963854760737129 +1739137692.1688285,33.8699676990509,46.71839025506525,1739137692.1688313,33.8699676990509,8.805541763654523,1739137692.1688344,33.8699676990509,60.99919662658323,1739137692.1688375,33.8699676990509,43.59138240117155,1739137692.1688392,33.8699676990509,6.067991168120788,1739137692.168841,33.8699676990509,-2.4225057489208064,1739137692.1688428,33.8699676990509,2.3727888098843595,1739137692.168844,33.8699676990509,0.6108,1739137692.1688457,33.8699676990509,0.9677080948595027,1739137692.1688476,33.8699676990509,0.0,1739137692.168849,33.8699676990509,-0.02867738121421015,1739137692.1688507,33.8699676990509,3.253040799759977,1739137692.1688523,33.8699676990509,0.9963854760737129 +1739137692.188695,33.88996767997742,46.71839025506525,1739137692.1886978,33.88996767997742,8.805541763654523,1739137692.1887012,33.88996767997742,60.99919662658323,1739137692.1887045,33.88996767997742,43.59138240117155,1739137692.1887062,33.88996767997742,6.067991168120788,1739137692.188708,33.88996767997742,-2.4225057489208064,1739137692.1887097,33.88996767997742,2.3727888098843595,1739137692.1887112,33.88996767997742,0.6108,1739137692.1887124,33.88996767997742,0.9677080948595027,1739137692.1887143,33.88996767997742,0.0,1739137692.1887157,33.88996767997742,-0.02867738121421015,1739137692.1887176,33.88996767997742,3.253040799759977,1739137692.188719,33.88996767997742,0.9963854760737129 +1739137692.208665,33.90996766090393,46.71839025506525,1739137692.2086678,33.90996766090393,8.805541763654523,1739137692.208671,33.90996766090393,60.99919662658323,1739137692.208674,33.90996766090393,43.59138240117155,1739137692.2086756,33.90996766090393,6.067991168120788,1739137692.2086773,33.90996766090393,-2.4225057489208064,1739137692.2086792,33.90996766090393,2.3727888098843595,1739137692.2086804,33.90996766090393,0.6108,1739137692.208682,33.90996766090393,0.9677080948595027,1739137692.2086837,33.90996766090393,0.0,1739137692.2086854,33.90996766090393,-0.02867738121421015,1739137692.208687,33.90996766090393,3.253040799759977,1739137692.2086885,33.90996766090393,0.9963854760737129 +1739137692.2285883,33.929967641830444,46.71839025506525,1739137692.228591,33.929967641830444,8.805541763654523,1739137692.228594,33.929967641830444,60.99919662658323,1739137692.2285972,33.929967641830444,43.59138240117155,1739137692.2285988,33.929967641830444,6.067991168120788,1739137692.2286005,33.929967641830444,-2.4225057489208064,1739137692.2286024,33.929967641830444,2.3727888098843595,1739137692.2286038,33.929967641830444,0.6108,1739137692.2286055,33.929967641830444,0.9677080948595027,1739137692.228607,33.929967641830444,0.0,1739137692.2286086,33.929967641830444,-0.02867738121421015,1739137692.22861,33.929967641830444,3.253040799759977,1739137692.2286115,33.929967641830444,0.9963854760737129 +1739137692.2487664,33.94996762275696,46.6098530069655,1739137692.2487693,33.94996762275696,8.792015097086498,1739137692.2487726,33.94996762275696,61.00774401584997,1739137692.2487757,33.94996762275696,43.59247423696149,1739137692.2487774,33.94996762275696,6.070697022034996,1739137692.2487795,33.94996762275696,-2.407739023958493,1739137692.248781,33.94996762275696,2.2768251395107697,1739137692.2487824,33.94996762275696,0.6108,1739137692.2487838,33.94996762275696,1.0055761653259605,1739137692.2487857,33.94996762275696,0.0,1739137692.2487872,33.94996762275696,0.05091229468626657,1739137692.2487888,33.94996762275696,3.2806460139608915,1739137692.2487903,33.94996762275696,0.9925637352392258 +1739137692.2687206,33.96996760368347,46.6098530069655,1739137692.2687232,33.96996760368347,8.792015097086498,1739137692.2687263,33.96996760368347,61.00774401584997,1739137692.2687297,33.96996760368347,43.59247423696149,1739137692.2687309,33.96996760368347,6.070697022034996,1739137692.268733,33.96996760368347,-2.407739023958493,1739137692.2687345,33.96996760368347,2.2768251395107697,1739137692.2687356,33.96996760368347,0.6108,1739137692.2687373,33.96996760368347,1.0055761653259605,1739137692.2687387,33.96996760368347,0.0,1739137692.2687404,33.96996760368347,0.013012430086734694,1739137692.268742,33.96996760368347,3.2806460139608915,1739137692.2687435,33.96996760368347,0.9925637352392258 +1739137692.288765,33.989967584609985,46.6098530069655,1739137692.288768,33.989967584609985,8.792015097086498,1739137692.2887714,33.989967584609985,61.00774401584997,1739137692.2887747,33.989967584609985,43.59247423696149,1739137692.2887762,33.989967584609985,6.070697022034996,1739137692.288778,33.989967584609985,-2.407739023958493,1739137692.2887797,33.989967584609985,2.2768251395107697,1739137692.2887814,33.989967584609985,0.6108,1739137692.2887828,33.989967584609985,1.0055761653259605,1739137692.2887847,33.989967584609985,0.0,1739137692.2887862,33.989967584609985,0.013012430086734694,1739137692.288788,33.989967584609985,3.2806460139608915,1739137692.2887893,33.989967584609985,0.9925637352392258 +1739137692.3088286,34.0099675655365,46.6098530069655,1739137692.3088317,34.0099675655365,8.792015097086498,1739137692.3088353,34.0099675655365,61.00774401584997,1739137692.3088384,34.0099675655365,43.59247423696149,1739137692.30884,34.0099675655365,6.070697022034996,1739137692.3088417,34.0099675655365,-2.407739023958493,1739137692.3088434,34.0099675655365,2.2768251395107697,1739137692.3088448,34.0099675655365,0.6108,1739137692.3088462,34.0099675655365,1.0055761653259605,1739137692.3088481,34.0099675655365,0.0,1739137692.3088496,34.0099675655365,0.013012430086734694,1739137692.3088512,34.0099675655365,3.2806460139608915,1739137692.3088527,34.0099675655365,0.9925637352392258 +1739137692.3285966,34.02996754646301,46.6098530069655,1739137692.328599,34.02996754646301,8.792015097086498,1739137692.3286023,34.02996754646301,61.00774401584997,1739137692.3286054,34.02996754646301,43.59247423696149,1739137692.328607,34.02996754646301,6.070697022034996,1739137692.3286088,34.02996754646301,-2.407739023958493,1739137692.3286104,34.02996754646301,2.2768251395107697,1739137692.3286119,34.02996754646301,0.6108,1739137692.3286133,34.02996754646301,1.0055761653259605,1739137692.328615,34.02996754646301,0.0,1739137692.3286164,34.02996754646301,0.013012430086734694,1739137692.3286183,34.02996754646301,3.2806460139608915,1739137692.3286197,34.02996754646301,0.9925637352392258 +1739137692.3487735,34.049967527389526,46.50183342936755,1739137692.348776,34.049967527389526,8.775512070394658,1739137692.3487794,34.049967527389526,61.08776467811592,1739137692.3487825,34.049967527389526,43.56054564751683,1739137692.3487842,34.049967527389526,5.991569648193889,1739137692.3487859,34.049967527389526,-2.383670374557316,1739137692.3487878,34.049967527389526,2.2574449171602864,1739137692.3487895,34.049967527389526,0.6108,1739137692.3487911,34.049967527389526,1.0134017744146566,1739137692.3487926,34.049967527389526,0.0,1739137692.3487942,34.049967527389526,0.024575924645132707,1739137692.348796,34.049967527389526,3.308251228161806,1739137692.348797,34.049967527389526,0.9943322785004152 +1739137692.3686957,34.06996750831604,46.50183342936755,1739137692.3686986,34.06996750831604,8.775512070394658,1739137692.3687017,34.06996750831604,61.08776467811592,1739137692.3687048,34.06996750831604,43.56054564751683,1739137692.3687062,34.06996750831604,5.991569648193889,1739137692.3687081,34.06996750831604,-2.383670374557316,1739137692.3687098,34.06996750831604,2.2574449171602864,1739137692.3687112,34.06996750831604,0.6108,1739137692.3687127,34.06996750831604,1.0134017744146566,1739137692.3687146,34.06996750831604,0.0,1739137692.368716,34.06996750831604,0.019069495914241452,1739137692.3687177,34.06996750831604,3.308251228161806,1739137692.368719,34.06996750831604,0.9943322785004152 +1739137692.38869,34.089967489242554,46.50183342936755,1739137692.3886926,34.089967489242554,8.775512070394658,1739137692.388696,34.089967489242554,61.08776467811592,1739137692.388699,34.089967489242554,43.56054564751683,1739137692.3887007,34.089967489242554,5.991569648193889,1739137692.3887024,34.089967489242554,-2.383670374557316,1739137692.388704,34.089967489242554,2.2574449171602864,1739137692.3887055,34.089967489242554,0.6108,1739137692.3887072,34.089967489242554,1.0134017744146566,1739137692.3887086,34.089967489242554,0.0,1739137692.3887103,34.089967489242554,0.019069495914241452,1739137692.388712,34.089967489242554,3.308251228161806,1739137692.3887131,34.089967489242554,0.9943322785004152 +1739137692.4087217,34.10996747016907,46.50183342936755,1739137692.408725,34.10996747016907,8.775512070394658,1739137692.4087284,34.10996747016907,61.08776467811592,1739137692.4087317,34.10996747016907,43.56054564751683,1739137692.4087331,34.10996747016907,5.991569648193889,1739137692.408735,34.10996747016907,-2.383670374557316,1739137692.4087367,34.10996747016907,2.2574449171602864,1739137692.4087384,34.10996747016907,0.6108,1739137692.4087398,34.10996747016907,1.0134017744146566,1739137692.408742,34.10996747016907,0.0,1739137692.4087434,34.10996747016907,0.019069495914241452,1739137692.408745,34.10996747016907,3.308251228161806,1739137692.4087465,34.10996747016907,0.9943322785004152 +1739137692.4288075,34.12996745109558,46.50183342936755,1739137692.42881,34.12996745109558,8.775512070394658,1739137692.428813,34.12996745109558,61.08776467811592,1739137692.428816,34.12996745109558,43.56054564751683,1739137692.4288177,34.12996745109558,5.991569648193889,1739137692.4288194,34.12996745109558,-2.383670374557316,1739137692.428821,34.12996745109558,2.2574449171602864,1739137692.4288225,34.12996745109558,0.6108,1739137692.428824,34.12996745109558,1.0134017744146566,1739137692.4288256,34.12996745109558,0.0,1739137692.428827,34.12996745109558,0.019069495914241452,1739137692.4288287,34.12996745109558,3.308251228161806,1739137692.4288301,34.12996745109558,0.9943322785004152 +1739137692.4487567,34.149967432022095,46.50183342936755,1739137692.4487596,34.149967432022095,8.775512070394658,1739137692.448763,34.149967432022095,61.08776467811592,1739137692.448766,34.149967432022095,43.56054564751683,1739137692.4487674,34.149967432022095,5.991569648193889,1739137692.4487696,34.149967432022095,-2.383670374557316,1739137692.4487712,34.149967432022095,2.2574449171602864,1739137692.448773,34.149967432022095,0.6108,1739137692.448774,34.149967432022095,1.0134017744146566,1739137692.448776,34.149967432022095,0.0,1739137692.4487774,34.149967432022095,0.019069495914241452,1739137692.4487793,34.149967432022095,3.308251228161806,1739137692.4487808,34.149967432022095,0.9943322785004152 +1739137692.4686017,34.16996741294861,46.394098732730086,1739137692.4686043,34.16996741294861,8.755995402331223,1739137692.468607,34.16996741294861,61.239776403642004,1739137692.4686096,34.16996741294861,43.50466060450018,1739137692.4686108,34.16996741294861,5.843158918181057,1739137692.468613,34.16996741294861,-2.352161894245087,1739137692.468614,34.16996741294861,2.3002568533785843,1739137692.4686155,34.16996741294861,0.6108,1739137692.4686167,34.16996741294861,0.9961952470073243,1739137692.4686182,34.16996741294861,0.0,1739137692.4686196,34.16996741294861,-0.01797882665100322,1739137692.468621,34.16996741294861,3.335856442362721,1739137692.4686224,34.16996741294861,0.996532006480942 +1739137692.488249,34.18996739387512,46.394098732730086,1739137692.4882517,34.18996739387512,8.755995402331223,1739137692.4882545,34.18996739387512,61.239776403642004,1739137692.488257,34.18996739387512,43.50466060450018,1739137692.4882584,34.18996739387512,5.843158918181057,1739137692.4882598,34.18996739387512,-2.352161894245087,1739137692.4882615,34.18996739387512,2.3002568533785843,1739137692.4882624,34.18996739387512,0.6108,1739137692.4882634,34.18996739387512,0.9961952470073243,1739137692.488265,34.18996739387512,0.0,1739137692.488266,34.18996739387512,-0.0003367594736176649,1739137692.4882674,34.18996739387512,3.335856442362721,1739137692.4882686,34.18996739387512,0.996532006480942 +1739137692.5086567,34.209967374801636,46.394098732730086,1739137692.5086596,34.209967374801636,8.755995402331223,1739137692.508663,34.209967374801636,61.239776403642004,1739137692.508666,34.209967374801636,43.50466060450018,1739137692.5086677,34.209967374801636,5.843158918181057,1739137692.5086696,34.209967374801636,-2.352161894245087,1739137692.5086713,34.209967374801636,2.3002568533785843,1739137692.5086727,34.209967374801636,0.6108,1739137692.5086744,34.209967374801636,0.9961952470073243,1739137692.5086758,34.209967374801636,0.0,1739137692.508677,34.209967374801636,-0.0003367594736176649,1739137692.508679,34.209967374801636,3.335856442362721,1739137692.5086803,34.209967374801636,0.996532006480942 +1739137692.5310578,34.22996735572815,46.394098732730086,1739137692.5310614,34.22996735572815,8.755995402331223,1739137692.5310667,34.22996735572815,61.239776403642004,1739137692.5310726,34.22996735572815,43.50466060450018,1739137692.531076,34.22996735572815,5.843158918181057,1739137692.53108,34.22996735572815,-2.352161894245087,1739137692.5310838,34.22996735572815,2.3002568533785843,1739137692.5310876,34.22996735572815,0.6108,1739137692.5310915,34.22996735572815,0.9961952470073243,1739137692.5310955,34.22996735572815,0.0,1739137692.5310993,34.22996735572815,-0.0003367594736176649,1739137692.5311031,34.22996735572815,3.335856442362721,1739137692.5311072,34.22996735572815,0.996532006480942 +1739137692.5487995,34.24996733665466,46.394098732730086,1739137692.5488026,34.24996733665466,8.755995402331223,1739137692.548806,34.24996733665466,61.239776403642004,1739137692.5488088,34.24996733665466,43.50466060450018,1739137692.5488102,34.24996733665466,5.843158918181057,1739137692.5488124,34.24996733665466,-2.352161894245087,1739137692.5488138,34.24996733665466,2.3002568533785843,1739137692.548815,34.24996733665466,0.6108,1739137692.5488167,34.24996733665466,0.9961952470073243,1739137692.5488183,34.24996733665466,0.0,1739137692.5488198,34.24996733665466,-0.0003367594736176649,1739137692.5488214,34.24996733665466,3.335856442362721,1739137692.548823,34.24996733665466,0.996532006480942 +1739137692.5689535,34.26996731758118,46.28683178081947,1739137692.5689564,34.26996731758118,8.73348964582555,1739137692.5689595,34.26996731758118,61.31993689492492,1739137692.5689626,34.26996731758118,43.478006452792066,1739137692.568964,34.26996731758118,5.7681849495775275,1739137692.568966,34.26996731758118,-2.3291010445052307,1739137692.5689673,34.26996731758118,2.274527781014912,1739137692.5689688,34.26996731758118,0.6108,1739137692.5689702,34.26996731758118,1.006500657617604,1739137692.5689719,34.26996731758118,0.0,1739137692.5689733,34.26996731758118,0.01971231582526018,1739137692.5689747,34.26996731758118,3.3634616565636355,1739137692.5689762,34.26996731758118,0.9963355252753305 +1739137692.5887065,34.28996729850769,46.28683178081947,1739137692.5887094,34.28996729850769,8.73348964582555,1739137692.5887127,34.28996729850769,61.31993689492492,1739137692.5887156,34.28996729850769,43.478006452792066,1739137692.588717,34.28996729850769,5.7681849495775275,1739137692.588719,34.28996729850769,-2.3291010445052307,1739137692.5887203,34.28996729850769,2.274527781014912,1739137692.588722,34.28996729850769,0.6108,1739137692.5887232,34.28996729850769,1.006500657617604,1739137692.588725,34.28996729850769,0.0,1739137692.5887263,34.28996729850769,0.010165132342273564,1739137692.5887277,34.28996729850769,3.3634616565636355,1739137692.5887294,34.28996729850769,0.9963355252753305 +1739137692.608729,34.309967279434204,46.28683178081947,1739137692.608732,34.309967279434204,8.73348964582555,1739137692.6087353,34.309967279434204,61.31993689492492,1739137692.608738,34.309967279434204,43.478006452792066,1739137692.6087396,34.309967279434204,5.7681849495775275,1739137692.6087415,34.309967279434204,-2.3291010445052307,1739137692.6087432,34.309967279434204,2.274527781014912,1739137692.6087446,34.309967279434204,0.6108,1739137692.6087463,34.309967279434204,1.006500657617604,1739137692.6087477,34.309967279434204,0.0,1739137692.6087494,34.309967279434204,0.010165132342273564,1739137692.6087508,34.309967279434204,3.3634616565636355,1739137692.6087525,34.309967279434204,0.9963355252753305 +1739137692.6309905,34.32996726036072,46.28683178081947,1739137692.6309943,34.32996726036072,8.73348964582555,1739137692.6309993,34.32996726036072,61.31993689492492,1739137692.6310055,34.32996726036072,43.478006452792066,1739137692.6310089,34.32996726036072,5.7681849495775275,1739137692.631013,34.32996726036072,-2.3291010445052307,1739137692.6310167,34.32996726036072,2.274527781014912,1739137692.6310205,34.32996726036072,0.6108,1739137692.6310244,34.32996726036072,1.006500657617604,1739137692.6310282,34.32996726036072,0.0,1739137692.631032,34.32996726036072,0.010165132342273564,1739137692.6310358,34.32996726036072,3.3634616565636355,1739137692.6310399,34.32996726036072,0.9963355252753305 +1739137692.6486998,34.34996724128723,46.28683178081947,1739137692.6487033,34.34996724128723,8.73348964582555,1739137692.6487062,34.34996724128723,61.31993689492492,1739137692.6487095,34.34996724128723,43.478006452792066,1739137692.6487112,34.34996724128723,5.7681849495775275,1739137692.6487129,34.34996724128723,-2.3291010445052307,1739137692.6487145,34.34996724128723,2.274527781014912,1739137692.648716,34.34996724128723,0.6108,1739137692.6487176,34.34996724128723,1.006500657617604,1739137692.6487193,34.34996724128723,0.0,1739137692.6487207,34.34996724128723,0.010165132342273564,1739137692.6487224,34.34996724128723,3.3634616565636355,1739137692.6487236,34.34996724128723,0.9963355252753305 +1739137692.668246,34.369967222213745,46.28683178081947,1739137692.6682482,34.369967222213745,8.73348964582555,1739137692.6682508,34.369967222213745,61.31993689492492,1739137692.6682534,34.369967222213745,43.478006452792066,1739137692.6682546,34.369967222213745,5.7681849495775275,1739137692.6682563,34.369967222213745,-2.3291010445052307,1739137692.6682575,34.369967222213745,2.274527781014912,1739137692.668259,34.369967222213745,0.6108,1739137692.6682599,34.369967222213745,1.006500657617604,1739137692.6682613,34.369967222213745,0.0,1739137692.668263,34.369967222213745,0.010165132342273564,1739137692.6682644,34.369967222213745,3.3634616565636355,1739137692.6682656,34.369967222213745,0.9963355252753305 +1739137692.6887848,34.38996720314026,46.1801639278166,1739137692.6887882,34.38996720314026,8.708016274099773,1739137692.6887913,34.38996720314026,61.400361377705124,1739137692.6887946,34.38996720314026,43.450841326065024,1739137692.688796,34.38996720314026,5.6883446698223015,1739137692.688798,34.38996720314026,-2.305733051854571,1739137692.6887994,34.38996720314026,2.2523350184198594,1739137692.688801,34.38996720314026,0.6108,1739137692.6888025,34.38996720314026,1.0154752449178965,1739137692.6888046,34.38996720314026,0.0,1739137692.6888058,34.38996720314026,0.024809098910818124,1739137692.6888077,34.38996720314026,3.39106687076455,1739137692.6888092,34.38996720314026,0.9976394669041495 +1739137692.709707,34.40996718406677,46.1801639278166,1739137692.7097106,34.40996718406677,8.708016274099773,1739137692.7097151,34.40996718406677,61.400361377705124,1739137692.7097197,34.40996718406677,43.450841326065024,1739137692.7097218,34.40996718406677,5.6883446698223015,1739137692.7097247,34.40996718406677,-2.305733051854571,1739137692.709727,34.40996718406677,2.2523350184198594,1739137692.7097292,34.40996718406677,0.6108,1739137692.7097313,34.40996718406677,1.0154752449178965,1739137692.709734,34.40996718406677,0.0,1739137692.7097359,34.40996718406677,0.017835778013747028,1739137692.7097383,34.40996718406677,3.39106687076455,1739137692.7097404,34.40996718406677,0.9976394669041495 +1739137692.7299008,34.429967164993286,46.1801639278166,1739137692.7299047,34.429967164993286,8.708016274099773,1739137692.7299092,34.429967164993286,61.400361377705124,1739137692.7299142,34.429967164993286,43.450841326065024,1739137692.7299163,34.429967164993286,5.6883446698223015,1739137692.729919,34.429967164993286,-2.305733051854571,1739137692.7299213,34.429967164993286,2.2523350184198594,1739137692.7299232,34.429967164993286,0.6108,1739137692.7299256,34.429967164993286,1.0154752449178965,1739137692.7299283,34.429967164993286,0.0,1739137692.7299302,34.429967164993286,0.017835778013747028,1739137692.7299328,34.429967164993286,3.39106687076455,1739137692.7299352,34.429967164993286,0.9976394669041495 +1739137692.7501981,34.4499671459198,46.1801639278166,1739137692.750202,34.4499671459198,8.708016274099773,1739137692.750206,34.4499671459198,61.400361377705124,1739137692.7502103,34.4499671459198,43.450841326065024,1739137692.7502127,34.4499671459198,5.6883446698223015,1739137692.750215,34.4499671459198,-2.305733051854571,1739137692.7502174,34.4499671459198,2.2523350184198594,1739137692.7502196,34.4499671459198,0.6108,1739137692.7502215,34.4499671459198,1.0154752449178965,1739137692.750224,34.4499671459198,0.0,1739137692.7502263,34.4499671459198,0.017835778013747028,1739137692.7502284,34.4499671459198,3.39106687076455,1739137692.7502306,34.4499671459198,0.9976394669041495 +1739137692.770811,34.46996712684631,46.1801639278166,1739137692.770815,34.46996712684631,8.708016274099773,1739137692.7708197,34.46996712684631,61.400361377705124,1739137692.7708242,34.46996712684631,43.450841326065024,1739137692.7708263,34.46996712684631,5.6883446698223015,1739137692.770829,34.46996712684631,-2.305733051854571,1739137692.770831,34.46996712684631,2.2523350184198594,1739137692.7708333,34.46996712684631,0.6108,1739137692.7708352,34.46996712684631,1.0154752449178965,1739137692.7708378,34.46996712684631,0.0,1739137692.7708402,34.46996712684631,0.017835778013747028,1739137692.7708423,34.46996712684631,3.39106687076455,1739137692.7708447,34.46996712684631,0.9976394669041495 +1739137692.7903874,34.48996710777283,46.07407420288958,1739137692.7903912,34.48996710777283,8.679563763200838,1739137692.7903957,34.48996710777283,61.552731900658856,1739137692.7904,34.48996710777283,43.404611006266734,1739137692.790402,34.48996710777283,5.536839897716914,1739137692.7904048,34.48996710777283,-2.2749481573883275,1739137692.790407,34.48996710777283,2.292630146321888,1739137692.7904088,34.48996710777283,0.6108,1739137692.790411,34.48996710777283,0.9992389630810049,1739137692.7904139,34.48996710777283,0.0,1739137692.7904158,34.48996710777283,-0.01701074146170125,1739137692.7904181,34.48996710777283,3.418672084965465,1739137692.7904203,34.48996710777283,0.9996561155508891 +1739137692.8096802,34.50996708869934,46.07407420288958,1739137692.8096838,34.50996708869934,8.679563763200838,1739137692.8096886,34.50996708869934,61.552731900658856,1739137692.8096926,34.50996708869934,43.404611006266734,1739137692.809695,34.50996708869934,5.536839897716914,1739137692.8096976,34.50996708869934,-2.2749481573883275,1739137692.8096995,34.50996708869934,2.292630146321888,1739137692.8097017,34.50996708869934,0.6108,1739137692.8097036,34.50996708869934,0.9992389630810049,1739137692.809706,34.50996708869934,0.0,1739137692.809708,34.50996708869934,-0.0004171524698841633,1739137692.8097103,34.50996708869934,3.418672084965465,1739137692.8097124,34.50996708869934,0.9996561155508891 +1739137692.8306878,34.529967069625854,46.07407420288958,1739137692.8306916,34.529967069625854,8.679563763200838,1739137692.830696,34.529967069625854,61.552731900658856,1739137692.8307006,34.529967069625854,43.404611006266734,1739137692.8307025,34.529967069625854,5.536839897716914,1739137692.8307052,34.529967069625854,-2.2749481573883275,1739137692.8307076,34.529967069625854,2.292630146321888,1739137692.8307097,34.529967069625854,0.6108,1739137692.830712,34.529967069625854,0.9992389630810049,1739137692.8307145,34.529967069625854,0.0,1739137692.8307166,34.529967069625854,-0.0004171524698841633,1739137692.8307192,34.529967069625854,3.418672084965465,1739137692.8307214,34.529967069625854,0.9996561155508891 +1739137692.8495862,34.54996705055237,46.07407420288958,1739137692.8495893,34.54996705055237,8.679563763200838,1739137692.8495932,34.54996705055237,61.552731900658856,1739137692.8495967,34.54996705055237,43.404611006266734,1739137692.8495986,34.54996705055237,5.536839897716914,1739137692.849601,34.54996705055237,-2.2749481573883275,1739137692.8496032,34.54996705055237,2.292630146321888,1739137692.8496048,34.54996705055237,0.6108,1739137692.8496068,34.54996705055237,0.9992389630810049,1739137692.8496087,34.54996705055237,0.0,1739137692.8496106,34.54996705055237,-0.0004171524698841633,1739137692.8496122,34.54996705055237,3.418672084965465,1739137692.8496144,34.54996705055237,0.9996561155508891 +1739137692.8694167,34.56996703147888,46.07407420288958,1739137692.8694196,34.56996703147888,8.679563763200838,1739137692.869423,34.56996703147888,61.552731900658856,1739137692.8694263,34.56996703147888,43.404611006266734,1739137692.8694277,34.56996703147888,5.536839897716914,1739137692.8694298,34.56996703147888,-2.2749481573883275,1739137692.8694313,34.56996703147888,2.292630146321888,1739137692.869433,34.56996703147888,0.6108,1739137692.8694344,34.56996703147888,0.9992389630810049,1739137692.8694363,34.56996703147888,0.0,1739137692.8694377,34.56996703147888,-0.0004171524698841633,1739137692.8694396,34.56996703147888,3.418672084965465,1739137692.869441,34.56996703147888,0.9996561155508891 +1739137692.8887374,34.589967012405396,46.07407420288958,1739137692.8887415,34.589967012405396,8.679563763200838,1739137692.8887453,34.589967012405396,61.552731900658856,1739137692.888749,34.589967012405396,43.404611006266734,1739137692.8887508,34.589967012405396,5.536839897716914,1739137692.8887534,34.589967012405396,-2.2749481573883275,1739137692.8887558,34.589967012405396,2.292630146321888,1739137692.8887575,34.589967012405396,0.6108,1739137692.8887591,34.589967012405396,0.9992389630810049,1739137692.8887608,34.589967012405396,0.0,1739137692.8887625,34.589967012405396,-0.0004171524698841633,1739137692.8887641,34.589967012405396,3.418672084965465,1739137692.888766,34.589967012405396,0.9996561155508891 +1739137692.9087708,34.60996699333191,45.9687275278242,1739137692.9087741,34.60996699333191,8.648169799888635,1739137692.9087784,34.60996699333191,61.70883176880054,1739137692.9087818,34.60996699333191,43.36478244129562,1739137692.9087834,34.60996699333191,5.38707760242944,1739137692.908785,34.60996699333191,-2.2446150307923207,1739137692.9087873,34.60996699333191,2.3297278884395918,1739137692.9087887,34.60996699333191,0.6108,1739137692.9087903,34.60996699333191,0.9845206327777594,1739137692.908792,34.60996699333191,0.0,1739137692.9087937,34.60996699333191,-0.027799126079230106,1739137692.9087956,34.60996699333191,3.4462772991663795,1739137692.9087973,34.60996699333191,0.999280717291349 +1739137692.929271,34.62996697425842,45.9687275278242,1739137692.9292738,34.62996697425842,8.648169799888635,1739137692.929277,34.62996697425842,61.70883176880054,1739137692.92928,34.62996697425842,43.36478244129562,1739137692.9292815,34.62996697425842,5.38707760242944,1739137692.9292836,34.62996697425842,-2.2446150307923207,1739137692.929285,34.62996697425842,2.3297278884395918,1739137692.9292867,34.62996697425842,0.6108,1739137692.9292881,34.62996697425842,0.9845206327777594,1739137692.92929,34.62996697425842,0.0,1739137692.9292915,34.62996697425842,-0.014760084513589677,1739137692.9292936,34.62996697425842,3.4462772991663795,1739137692.9292948,34.62996697425842,0.999280717291349 +1739137692.9493456,34.64996695518494,45.9687275278242,1739137692.9493492,34.64996695518494,8.648169799888635,1739137692.949353,34.64996695518494,61.70883176880054,1739137692.9493563,34.64996695518494,43.36478244129562,1739137692.9493577,34.64996695518494,5.38707760242944,1739137692.9493601,34.64996695518494,-2.2446150307923207,1739137692.9493618,34.64996695518494,2.3297278884395918,1739137692.9493637,34.64996695518494,0.6108,1739137692.9493651,34.64996695518494,0.9845206327777594,1739137692.9493673,34.64996695518494,0.0,1739137692.9493692,34.64996695518494,-0.014760084513589677,1739137692.9493709,34.64996695518494,3.4462772991663795,1739137692.9493725,34.64996695518494,0.999280717291349 +1739137692.9690726,34.66996693611145,45.9687275278242,1739137692.9690754,34.66996693611145,8.648169799888635,1739137692.9690788,34.66996693611145,61.70883176880054,1739137692.9690819,34.66996693611145,43.36478244129562,1739137692.9690833,34.66996693611145,5.38707760242944,1739137692.9690852,34.66996693611145,-2.2446150307923207,1739137692.9690866,34.66996693611145,2.3297278884395918,1739137692.9690883,34.66996693611145,0.6108,1739137692.9690897,34.66996693611145,0.9845206327777594,1739137692.9690917,34.66996693611145,0.0,1739137692.969093,34.66996693611145,-0.014760084513589677,1739137692.9690948,34.66996693611145,3.4462772991663795,1739137692.9690962,34.66996693611145,0.999280717291349 +1739137692.9887285,34.689966917037964,45.9687275278242,1739137692.988732,34.689966917037964,8.648169799888635,1739137692.9887354,34.689966917037964,61.70883176880054,1739137692.9887395,34.689966917037964,43.36478244129562,1739137692.9887412,34.689966917037964,5.38707760242944,1739137692.988743,34.689966917037964,-2.2446150307923207,1739137692.9887447,34.689966917037964,2.3297278884395918,1739137692.9887462,34.689966917037964,0.6108,1739137692.988748,34.689966917037964,0.9845206327777594,1739137692.9887497,34.689966917037964,0.0,1739137692.9887514,34.689966917037964,-0.014760084513589677,1739137692.9887533,34.689966917037964,3.4462772991663795,1739137692.9887552,34.689966917037964,0.999280717291349 +1739137693.0087981,34.70996689796448,45.86437894928507,1739137693.0088012,34.70996689796448,8.613910476513986,1739137693.0088048,34.70996689796448,61.78831048304058,1739137693.0088084,34.70996689796448,43.34581643887702,1739137693.00881,34.70996689796448,5.315265755508096,1739137693.0088122,34.70996689796448,-2.2228906500500205,1739137693.008814,34.70996689796448,2.2966253138903623,1739137693.0088155,34.70996689796448,0.6108,1739137693.0088174,34.70996689796448,0.9976433874995527,1739137693.008819,34.70996689796448,0.0,1739137693.0088208,34.70996689796448,0.013603749208394803,1739137693.0088224,34.70996689796448,3.473882513367294,1739137693.008824,34.70996689796448,0.9975462325249511 +1739137693.0292583,34.72996687889099,45.86437894928507,1739137693.029261,34.72996687889099,8.613910476513986,1739137693.0292645,34.72996687889099,61.78831048304058,1739137693.0292675,34.72996687889099,43.34581643887702,1739137693.029269,34.72996687889099,5.315265755508096,1739137693.029271,34.72996687889099,-2.2228906500500205,1739137693.0292723,34.72996687889099,2.2966253138903623,1739137693.0292737,34.72996687889099,0.6108,1739137693.0292757,34.72996687889099,0.9976433874995527,1739137693.029277,34.72996687889099,0.0,1739137693.0292788,34.72996687889099,9.715497460160982e-05,1739137693.0292804,34.72996687889099,3.473882513367294,1739137693.029282,34.72996687889099,0.9975462325249511 +1739137693.048811,34.749966859817505,45.86437894928507,1739137693.048814,34.749966859817505,8.613910476513986,1739137693.0488176,34.749966859817505,61.78831048304058,1739137693.0488212,34.749966859817505,43.34581643887702,1739137693.048823,34.749966859817505,5.315265755508096,1739137693.048825,34.749966859817505,-2.2228906500500205,1739137693.048827,34.749966859817505,2.2966253138903623,1739137693.0488286,34.749966859817505,0.6108,1739137693.0488303,34.749966859817505,0.9976433874995527,1739137693.048832,34.749966859817505,0.0,1739137693.0488336,34.749966859817505,9.715497460160982e-05,1739137693.0488353,34.749966859817505,3.473882513367294,1739137693.0488374,34.749966859817505,0.9975462325249511 +1739137693.0694346,34.76996684074402,45.86437894928507,1739137693.0694375,34.76996684074402,8.613910476513986,1739137693.0694408,34.76996684074402,61.78831048304058,1739137693.0694442,34.76996684074402,43.34581643887702,1739137693.0694454,34.76996684074402,5.315265755508096,1739137693.0694475,34.76996684074402,-2.2228906500500205,1739137693.069449,34.76996684074402,2.2966253138903623,1739137693.0694509,34.76996684074402,0.6108,1739137693.069452,34.76996684074402,0.9976433874995527,1739137693.0694537,34.76996684074402,0.0,1739137693.0694554,34.76996684074402,9.715497460160982e-05,1739137693.069457,34.76996684074402,3.473882513367294,1739137693.0694587,34.76996684074402,0.9975462325249511 +1739137693.088981,34.78996682167053,45.86437894928507,1739137693.088984,34.78996682167053,8.613910476513986,1739137693.0889876,34.78996682167053,61.78831048304058,1739137693.088991,34.78996682167053,43.34581643887702,1739137693.0889926,34.78996682167053,5.315265755508096,1739137693.0889945,34.78996682167053,-2.2228906500500205,1739137693.0889962,34.78996682167053,2.2966253138903623,1739137693.0889976,34.78996682167053,0.6108,1739137693.0889993,34.78996682167053,0.9976433874995527,1739137693.089001,34.78996682167053,0.0,1739137693.0890028,34.78996682167053,9.715497460160982e-05,1739137693.0890045,34.78996682167053,3.473882513367294,1739137693.0890062,34.78996682167053,0.9975462325249511 +1739137693.1087687,34.809966802597046,45.86437894928507,1739137693.108772,34.809966802597046,8.613910476513986,1739137693.1087759,34.809966802597046,61.78831048304058,1739137693.1087792,34.809966802597046,43.34581643887702,1739137693.1087809,34.809966802597046,5.315265755508096,1739137693.1087828,34.809966802597046,-2.2228906500500205,1739137693.108785,34.809966802597046,2.2966253138903623,1739137693.1087863,34.809966802597046,0.6108,1739137693.108788,34.809966802597046,0.9976433874995527,1739137693.1087897,34.809966802597046,0.0,1739137693.1087914,34.809966802597046,9.715497460160982e-05,1739137693.1087933,34.809966802597046,3.473882513367294,1739137693.108795,34.809966802597046,0.9975462325249511 +1739137693.129317,34.82996678352356,45.761087324703496,1739137693.12932,34.82996678352356,8.576809180126396,1739137693.129323,34.82996678352356,61.85487594610839,1739137693.1293263,34.82996678352356,43.331049525145104,1739137693.1293278,34.82996678352356,5.249501872650082,1739137693.1293297,34.82996678352356,-2.2015903973349094,1739137693.1293314,34.82996678352356,2.258338241285203,1739137693.1293328,34.82996678352356,0.6108,1739137693.1293342,34.82996678352356,1.0130397206034625,1739137693.129336,34.82996678352356,0.0,1739137693.1293375,34.82996678352356,0.028957546956438332,1739137693.1293392,34.82996678352356,3.501487727568209,1739137693.1293406,34.82996678352356,0.997825224313153 +1739137693.1489587,34.84996676445007,45.761087324703496,1739137693.1489618,34.84996676445007,8.576809180126396,1739137693.1489656,34.84996676445007,61.85487594610839,1739137693.1489692,34.84996676445007,43.331049525145104,1739137693.1489708,34.84996676445007,5.249501872650082,1739137693.1489727,34.84996676445007,-2.2015903973349094,1739137693.1489747,34.84996676445007,2.258338241285203,1739137693.148976,34.84996676445007,0.6108,1739137693.1489778,34.84996676445007,1.0130397206034625,1739137693.1489794,34.84996676445007,0.0,1739137693.148981,34.84996676445007,0.015214496290309465,1739137693.1489828,34.84996676445007,3.501487727568209,1739137693.1489844,34.84996676445007,0.997825224313153 +1739137693.1690595,34.86996674537659,45.761087324703496,1739137693.1690626,34.86996674537659,8.576809180126396,1739137693.169066,34.86996674537659,61.85487594610839,1739137693.169069,34.86996674537659,43.331049525145104,1739137693.1690705,34.86996674537659,5.249501872650082,1739137693.1690726,34.86996674537659,-2.2015903973349094,1739137693.169074,34.86996674537659,2.258338241285203,1739137693.169076,34.86996674537659,0.6108,1739137693.1690772,34.86996674537659,1.0130397206034625,1739137693.1690793,34.86996674537659,0.0,1739137693.1690805,34.86996674537659,0.015214496290309465,1739137693.1690824,34.86996674537659,3.501487727568209,1739137693.1690838,34.86996674537659,0.997825224313153 +1739137693.1887422,34.8899667263031,45.761087324703496,1739137693.1887455,34.8899667263031,8.576809180126396,1739137693.1887493,34.8899667263031,61.85487594610839,1739137693.1887524,34.8899667263031,43.331049525145104,1739137693.1887538,34.8899667263031,5.249501872650082,1739137693.188756,34.8899667263031,-2.2015903973349094,1739137693.1887574,34.8899667263031,2.258338241285203,1739137693.188759,34.8899667263031,0.6108,1739137693.1887605,34.8899667263031,1.0130397206034625,1739137693.1887627,34.8899667263031,0.0,1739137693.188764,34.8899667263031,0.015214496290309465,1739137693.188766,34.8899667263031,3.501487727568209,1739137693.1887677,34.8899667263031,0.997825224313153 +1739137693.208865,34.909966707229614,45.761087324703496,1739137693.2088678,34.909966707229614,8.576809180126396,1739137693.2088716,34.909966707229614,61.85487594610839,1739137693.208875,34.909966707229614,43.331049525145104,1739137693.2088764,34.909966707229614,5.249501872650082,1739137693.2088783,34.909966707229614,-2.2015903973349094,1739137693.2088802,34.909966707229614,2.258338241285203,1739137693.2088816,34.909966707229614,0.6108,1739137693.2088833,34.909966707229614,1.0130397206034625,1739137693.208885,34.909966707229614,0.0,1739137693.2088869,34.909966707229614,0.015214496290309465,1739137693.2088885,34.909966707229614,3.501487727568209,1739137693.2088904,34.909966707229614,0.997825224313153 +1739137693.2293491,34.92996668815613,45.658769584670914,1739137693.229352,34.92996668815613,8.536835563922896,1739137693.2293553,34.92996668815613,61.95219611626112,1739137693.2293584,34.92996668815613,43.30949688074641,1739137693.2293599,34.92996668815613,5.149100268232582,1739137693.229362,34.92996668815613,-2.1771222782795103,1739137693.2293634,34.92996668815613,2.2488248993874125,1739137693.229365,34.92996668815613,0.6108,1739137693.2293665,34.92996668815613,1.016902021908587,1739137693.229368,34.92996668815613,0.0,1739137693.2293696,34.92996668815613,0.019169431054027283,1739137693.2293715,34.92996668815613,3.5290929417691235,1739137693.2293735,34.92996668815613,0.9996158940637889 +1739137693.2487423,34.94996666908264,45.658769584670914,1739137693.2487454,34.94996666908264,8.536835563922896,1739137693.248749,34.94996666908264,61.95219611626112,1739137693.2487524,34.94996666908264,43.30949688074641,1739137693.248754,34.94996666908264,5.149100268232582,1739137693.248756,34.94996666908264,-2.1771222782795103,1739137693.248758,34.94996666908264,2.2488248993874125,1739137693.24876,34.94996666908264,0.6108,1739137693.2487617,34.94996666908264,1.016902021908587,1739137693.2487633,34.94996666908264,0.0,1739137693.248765,34.94996666908264,0.017286127844797994,1739137693.2487667,34.94996666908264,3.5290929417691235,1739137693.2487683,34.94996666908264,0.9996158940637889 +1739137693.2688613,34.969966650009155,45.658769584670914,1739137693.2688637,34.969966650009155,8.536835563922896,1739137693.2688673,34.969966650009155,61.95219611626112,1739137693.2688704,34.969966650009155,43.30949688074641,1739137693.268872,34.969966650009155,5.149100268232582,1739137693.268874,34.969966650009155,-2.1771222782795103,1739137693.2688756,34.969966650009155,2.2488248993874125,1739137693.268877,34.969966650009155,0.6108,1739137693.2688787,34.969966650009155,1.016902021908587,1739137693.2688804,34.969966650009155,0.0,1739137693.268882,34.969966650009155,0.017286127844797994,1739137693.268884,34.969966650009155,3.5290929417691235,1739137693.2688856,34.969966650009155,0.9996158940637889 +1739137693.2887516,34.98996663093567,45.658769584670914,1739137693.2887552,34.98996663093567,8.536835563922896,1739137693.2887585,34.98996663093567,61.95219611626112,1739137693.288762,34.98996663093567,43.30949688074641,1739137693.288764,34.98996663093567,5.149100268232582,1739137693.288766,34.98996663093567,-2.1771222782795103,1739137693.2887676,34.98996663093567,2.2488248993874125,1739137693.2887692,34.98996663093567,0.6108,1739137693.288771,34.98996663093567,1.016902021908587,1739137693.2887728,34.98996663093567,0.0,1739137693.2887745,34.98996663093567,0.017286127844797994,1739137693.2887762,34.98996663093567,3.5290929417691235,1739137693.2887778,34.98996663093567,0.9996158940637889 +1739137693.3089054,35.00996661186218,45.658769584670914,1739137693.3089085,35.00996661186218,8.536835563922896,1739137693.308912,35.00996661186218,61.95219611626112,1739137693.3089166,35.00996661186218,43.30949688074641,1739137693.308918,35.00996661186218,5.149100268232582,1739137693.3089201,35.00996661186218,-2.1771222782795103,1739137693.3089218,35.00996661186218,2.2488248993874125,1739137693.3089235,35.00996661186218,0.6108,1739137693.308925,35.00996661186218,1.016902021908587,1739137693.3089268,35.00996661186218,0.0,1739137693.3089285,35.00996661186218,0.017286127844797994,1739137693.3089304,35.00996661186218,3.5290929417691235,1739137693.308932,35.00996661186218,0.9996158940637889 +1739137693.329443,35.029966592788696,45.658769584670914,1739137693.3294456,35.029966592788696,8.536835563922896,1739137693.329449,35.029966592788696,61.95219611626112,1739137693.329452,35.029966592788696,43.30949688074641,1739137693.3294535,35.029966592788696,5.149100268232582,1739137693.3294556,35.029966592788696,-2.1771222782795103,1739137693.3294575,35.029966592788696,2.2488248993874125,1739137693.329459,35.029966592788696,0.6108,1739137693.3294604,35.029966592788696,1.016902021908587,1739137693.329462,35.029966592788696,0.0,1739137693.3294635,35.029966592788696,0.017286127844797994,1739137693.3294654,35.029966592788696,3.5290929417691235,1739137693.3294668,35.029966592788696,0.9996158940637889 +1739137693.3487837,35.04996657371521,45.557406562524314,1739137693.3487875,35.04996657371521,8.493973693224582,1739137693.3487911,35.04996657371521,62.03362008193364,1739137693.3487942,35.04996657371521,43.292437990853955,1739137693.348796,35.04996657371521,5.063565150611375,1739137693.3487978,35.04996657371521,-2.1543518476990413,1739137693.3487995,35.04996657371521,2.2256457133824887,1739137693.3488014,35.04996657371521,0.6108,1739137693.3488028,35.04996657371521,1.0263742502070032,1739137693.3488047,35.04996657371521,0.0,1739137693.3488061,35.04996657371521,0.03168064082914191,1739137693.3488083,35.04996657371521,3.556698155970038,1739137693.3488097,35.04996657371521,1.001548142794545 +1739137693.3693724,35.069966554641724,45.557406562524314,1739137693.3693752,35.069966554641724,8.493973693224582,1739137693.3693786,35.069966554641724,62.03362008193364,1739137693.3693817,35.069966554641724,43.292437990853955,1739137693.369383,35.069966554641724,5.063565150611375,1739137693.3693852,35.069966554641724,-2.1543518476990413,1739137693.3693867,35.069966554641724,2.2256457133824887,1739137693.3693883,35.069966554641724,0.6108,1739137693.3693898,35.069966554641724,1.0263742502070032,1739137693.3693917,35.069966554641724,0.0,1739137693.3693929,35.069966554641724,0.024826107412458276,1739137693.3693948,35.069966554641724,3.556698155970038,1739137693.3693962,35.069966554641724,1.001548142794545 +1739137693.3888328,35.08996653556824,45.557406562524314,1739137693.3888361,35.08996653556824,8.493973693224582,1739137693.3888404,35.08996653556824,62.03362008193364,1739137693.3888438,35.08996653556824,43.292437990853955,1739137693.3888452,35.08996653556824,5.063565150611375,1739137693.3888476,35.08996653556824,-2.1543518476990413,1739137693.3888497,35.08996653556824,2.2256457133824887,1739137693.3888516,35.08996653556824,0.6108,1739137693.3888533,35.08996653556824,1.0263742502070032,1739137693.388855,35.08996653556824,0.0,1739137693.3888566,35.08996653556824,0.024826107412458276,1739137693.3888586,35.08996653556824,3.556698155970038,1739137693.3888602,35.08996653556824,1.001548142794545 +1739137693.4089348,35.10996651649475,45.557406562524314,1739137693.4089382,35.10996651649475,8.493973693224582,1739137693.4089417,35.10996651649475,62.03362008193364,1739137693.4089448,35.10996651649475,43.292437990853955,1739137693.408947,35.10996651649475,5.063565150611375,1739137693.4089487,35.10996651649475,-2.1543518476990413,1739137693.4089506,35.10996651649475,2.2256457133824887,1739137693.4089518,35.10996651649475,0.6108,1739137693.4089534,35.10996651649475,1.0263742502070032,1739137693.408955,35.10996651649475,0.0,1739137693.4089568,35.10996651649475,0.024826107412458276,1739137693.4089587,35.10996651649475,3.556698155970038,1739137693.4089603,35.10996651649475,1.001548142794545 +1739137693.4313512,35.129966497421265,45.557406562524314,1739137693.4313557,35.129966497421265,8.493973693224582,1739137693.431361,35.129966497421265,62.03362008193364,1739137693.4313674,35.129966497421265,43.292437990853955,1739137693.431371,35.129966497421265,5.063565150611375,1739137693.4313753,35.129966497421265,-2.1543518476990413,1739137693.4313796,35.129966497421265,2.2256457133824887,1739137693.4313836,35.129966497421265,0.6108,1739137693.4313877,35.129966497421265,1.0263742502070032,1739137693.431392,35.129966497421265,0.0,1739137693.4313958,35.129966497421265,0.024826107412458276,1739137693.4314008,35.129966497421265,3.556698155970038,1739137693.4314048,35.129966497421265,1.001548142794545 +1739137693.4489038,35.14996647834778,45.45703389354035,1739137693.4489074,35.14996647834778,8.448224675381354,1739137693.448911,35.14996647834778,62.18972219996905,1739137693.4489138,35.14996647834778,43.26151017046218,1739137693.4489155,35.14996647834778,4.902054764027131,1739137693.4489174,35.14996647834778,-2.1251600239445865,1739137693.4489193,35.14996647834778,2.2637555954619466,1739137693.4489207,35.14996647834778,0.6108,1739137693.4489224,35.14996647834778,1.0108468993347643,1739137693.4489238,35.14996647834778,0.0,1739137693.4489255,35.14996647834778,-0.010126953628409065,1739137693.4489272,35.14996647834778,3.584303370170953,1739137693.4489288,35.14996647834778,1.0043295298672414 +1739137693.4708576,35.16996645927429,45.45703389354035,1739137693.470861,35.16996645927429,8.448224675381354,1739137693.4708652,35.16996645927429,62.18972219996905,1739137693.4708703,35.16996645927429,43.26151017046218,1739137693.4708729,35.16996645927429,4.902054764027131,1739137693.4708765,35.16996645927429,-2.1251600239445865,1739137693.4708798,35.16996645927429,2.2637555954619466,1739137693.470883,35.16996645927429,0.6108,1739137693.470886,35.16996645927429,1.0108468993347643,1739137693.4708893,35.16996645927429,0.0,1739137693.4708924,35.16996645927429,0.006517369467522904,1739137693.4708958,35.16996645927429,3.584303370170953,1739137693.4708989,35.16996645927429,1.0043295298672414 +1739137693.4883556,35.189966440200806,45.45703389354035,1739137693.488359,35.189966440200806,8.448224675381354,1739137693.4883645,35.189966440200806,62.18972219996905,1739137693.4883673,35.189966440200806,43.26151017046218,1739137693.4883687,35.189966440200806,4.902054764027131,1739137693.4883702,35.189966440200806,-2.1251600239445865,1739137693.4883716,35.189966440200806,2.2637555954619466,1739137693.4883728,35.189966440200806,0.6108,1739137693.4883745,35.189966440200806,1.0108468993347643,1739137693.4883761,35.189966440200806,0.0,1739137693.4883773,35.189966440200806,0.006517369467522904,1739137693.4883788,35.189966440200806,3.584303370170953,1739137693.4883802,35.189966440200806,1.0043295298672414 +1739137693.5083964,35.20996642112732,45.45703389354035,1739137693.5083985,35.20996642112732,8.448224675381354,1739137693.5084014,35.20996642112732,62.18972219996905,1739137693.5084043,35.20996642112732,43.26151017046218,1739137693.5084054,35.20996642112732,4.902054764027131,1739137693.508407,35.20996642112732,-2.1251600239445865,1739137693.5084083,35.20996642112732,2.2637555954619466,1739137693.5084095,35.20996642112732,0.6108,1739137693.5084112,35.20996642112732,1.0108468993347643,1739137693.5084124,35.20996642112732,0.0,1739137693.5084138,35.20996642112732,0.006517369467522904,1739137693.5084152,35.20996642112732,3.584303370170953,1739137693.5084164,35.20996642112732,1.0043295298672414 +1739137693.530577,35.22996640205383,45.45703389354035,1739137693.5305803,35.22996640205383,8.448224675381354,1739137693.5305843,35.22996640205383,62.18972219996905,1739137693.530589,35.22996640205383,43.26151017046218,1739137693.530592,35.22996640205383,4.902054764027131,1739137693.5305955,35.22996640205383,-2.1251600239445865,1739137693.5305986,35.22996640205383,2.2637555954619466,1739137693.530602,35.22996640205383,0.6108,1739137693.530605,35.22996640205383,1.0108468993347643,1739137693.5306084,35.22996640205383,0.0,1739137693.5306115,35.22996640205383,0.006517369467522904,1739137693.530615,35.22996640205383,3.584303370170953,1739137693.5306182,35.22996640205383,1.0043295298672414 +1739137693.5483756,35.24996638298035,45.45703389354035,1739137693.5483785,35.24996638298035,8.448224675381354,1739137693.548381,35.24996638298035,62.18972219996905,1739137693.5483837,35.24996638298035,43.26151017046218,1739137693.548385,35.24996638298035,4.902054764027131,1739137693.5483866,35.24996638298035,-2.1251600239445865,1739137693.5483878,35.24996638298035,2.2637555954619466,1739137693.5483892,35.24996638298035,0.6108,1739137693.5483902,35.24996638298035,1.0108468993347643,1739137693.5483916,35.24996638298035,0.0,1739137693.5483932,35.24996638298035,0.006517369467522904,1739137693.5483944,35.24996638298035,3.584303370170953,1739137693.5483959,35.24996638298035,1.0043295298672414 +1739137693.5709596,35.26996636390686,45.35780931039604,1739137693.570963,35.26996636390686,8.399648428788865,1739137693.5709672,35.26996636390686,62.273056830694685,1739137693.5709724,35.26996636390686,43.24620520047047,1739137693.5709753,35.26996636390686,4.818966864107971,1739137693.5709786,35.26996636390686,-2.103623660336243,1739137693.570982,35.26996636390686,2.234998369898113,1739137693.5709853,35.26996636390686,0.6108,1739137693.5709882,35.26996636390686,1.0225416932671574,1739137693.5709915,35.26996636390686,0.0,1739137693.5709946,35.26996636390686,0.028111234410080087,1739137693.570998,35.26996636390686,3.6119085843718675,1739137693.5710015,35.26996636390686,1.0047132568235733 +1739137693.5883772,35.289966344833374,45.35780931039604,1739137693.58838,35.289966344833374,8.399648428788865,1739137693.5883827,35.289966344833374,62.273056830694685,1739137693.588385,35.289966344833374,43.24620520047047,1739137693.5883868,35.289966344833374,4.818966864107971,1739137693.5883884,35.289966344833374,-2.103623660336243,1739137693.5883896,35.289966344833374,2.234998369898113,1739137693.5883908,35.289966344833374,0.6108,1739137693.5883923,35.289966344833374,1.0225416932671574,1739137693.5883937,35.289966344833374,0.0,1739137693.5883946,35.289966344833374,0.017828436443584117,1739137693.5883963,35.289966344833374,3.6119085843718675,1739137693.5883973,35.289966344833374,1.0047132568235733 +1739137693.6089897,35.30996632575989,45.35780931039604,1739137693.6089933,35.30996632575989,8.399648428788865,1739137693.6089966,35.30996632575989,62.273056830694685,1739137693.6089995,35.30996632575989,43.24620520047047,1739137693.6090007,35.30996632575989,4.818966864107971,1739137693.6090024,35.30996632575989,-2.103623660336243,1739137693.6090038,35.30996632575989,2.234998369898113,1739137693.609005,35.30996632575989,0.6108,1739137693.6090064,35.30996632575989,1.0225416932671574,1739137693.6090076,35.30996632575989,0.0,1739137693.6090095,35.30996632575989,0.017828436443584117,1739137693.6090107,35.30996632575989,3.6119085843718675,1739137693.6090121,35.30996632575989,1.0047132568235733 +1739137693.6283588,35.3299663066864,45.35780931039604,1739137693.6283617,35.3299663066864,8.399648428788865,1739137693.6283646,35.3299663066864,62.273056830694685,1739137693.6283674,35.3299663066864,43.24620520047047,1739137693.6283686,35.3299663066864,4.818966864107971,1739137693.6283703,35.3299663066864,-2.103623660336243,1739137693.628372,35.3299663066864,2.234998369898113,1739137693.6283736,35.3299663066864,0.6108,1739137693.6283748,35.3299663066864,1.0225416932671574,1739137693.628376,35.3299663066864,0.0,1739137693.6283774,35.3299663066864,0.017828436443584117,1739137693.6283789,35.3299663066864,3.6119085843718675,1739137693.6283808,35.3299663066864,1.0047132568235733 +1739137693.6483402,35.349966287612915,45.35780931039604,1739137693.6483428,35.349966287612915,8.399648428788865,1739137693.6483457,35.349966287612915,62.273056830694685,1739137693.648348,35.349966287612915,43.24620520047047,1739137693.6483498,35.349966287612915,4.818966864107971,1739137693.648351,35.349966287612915,-2.103623660336243,1739137693.6483526,35.349966287612915,2.234998369898113,1739137693.648354,35.349966287612915,0.6108,1739137693.648355,35.349966287612915,1.0225416932671574,1739137693.6483567,35.349966287612915,0.0,1739137693.6483579,35.349966287612915,0.017828436443584117,1739137693.6483595,35.349966287612915,3.6119085843718675,1739137693.6483607,35.349966287612915,1.0047132568235733 +1739137693.6685274,35.36996626853943,45.25983778990668,1739137693.6685302,35.36996626853943,8.348285650446918,1739137693.6685333,35.36996626853943,62.356822881657244,1739137693.668536,35.36996626853943,43.22929653233182,1739137693.6685374,35.36996626853943,4.730667880563645,1739137693.6685393,35.36996626853943,-2.082267946166389,1739137693.668541,35.36996626853943,2.2085701459773714,1739137693.6685424,35.36996626853943,0.6108,1739137693.6685438,35.36996626853943,1.0334086150910191,1739137693.6685455,35.36996626853943,0.0,1739137693.668547,35.36996626853943,0.03466816745709625,1739137693.6685483,35.36996626853943,3.639513798572782,1739137693.6685498,35.36996626853943,1.0067593711699694 +1739137693.689758,35.38996624946594,45.25983778990668,1739137693.6897612,35.38996624946594,8.348285650446918,1739137693.6897652,35.38996624946594,62.356822881657244,1739137693.6897693,35.38996624946594,43.22929653233182,1739137693.689771,35.38996624946594,4.730667880563645,1739137693.6897733,35.38996624946594,-2.082267946166389,1739137693.6897755,35.38996624946594,2.2085701459773714,1739137693.6897771,35.38996624946594,0.6108,1739137693.689779,35.38996624946594,1.0334086150910191,1739137693.689781,35.38996624946594,0.0,1739137693.6897829,35.38996624946594,0.026649243921049726,1739137693.6897848,35.38996624946594,3.639513798572782,1739137693.6897867,35.38996624946594,1.0067593711699694 +1739137693.709463,35.409966230392456,45.25983778990668,1739137693.7094662,35.409966230392456,8.348285650446918,1739137693.7094698,35.409966230392456,62.356822881657244,1739137693.7094736,35.409966230392456,43.22929653233182,1739137693.7094753,35.409966230392456,4.730667880563645,1739137693.7094777,35.409966230392456,-2.082267946166389,1739137693.7094793,35.409966230392456,2.2085701459773714,1739137693.7094812,35.409966230392456,0.6108,1739137693.709483,35.409966230392456,1.0334086150910191,1739137693.709485,35.409966230392456,0.0,1739137693.709487,35.409966230392456,0.026649243921049726,1739137693.709489,35.409966230392456,3.639513798572782,1739137693.709491,35.409966230392456,1.0067593711699694 +1739137693.7300587,35.42996621131897,45.25983778990668,1739137693.730062,35.42996621131897,8.348285650446918,1739137693.7300656,35.42996621131897,62.356822881657244,1739137693.7300692,35.42996621131897,43.22929653233182,1739137693.7300713,35.42996621131897,4.730667880563645,1739137693.7300737,35.42996621131897,-2.082267946166389,1739137693.7300754,35.42996621131897,2.2085701459773714,1739137693.7300775,35.42996621131897,0.6108,1739137693.730079,35.42996621131897,1.0334086150910191,1739137693.7300813,35.42996621131897,0.0,1739137693.730083,35.42996621131897,0.026649243921049726,1739137693.7300851,35.42996621131897,3.639513798572782,1739137693.7300873,35.42996621131897,1.0067593711699694 +1739137693.7489836,35.44996619224548,45.25983778990668,1739137693.7489865,35.44996619224548,8.348285650446918,1739137693.7489896,35.44996619224548,62.356822881657244,1739137693.748993,35.44996619224548,43.22929653233182,1739137693.7489946,35.44996619224548,4.730667880563645,1739137693.748997,35.44996619224548,-2.082267946166389,1739137693.7489984,35.44996619224548,2.2085701459773714,1739137693.7489998,35.44996619224548,0.6108,1739137693.7490015,35.44996619224548,1.0334086150910191,1739137693.7490034,35.44996619224548,0.0,1739137693.7490048,35.44996619224548,0.026649243921049726,1739137693.7490065,35.44996619224548,3.639513798572782,1739137693.7490082,35.44996619224548,1.0067593711699694 +1739137693.7684877,35.469966173172,45.25983778990668,1739137693.76849,35.469966173172,8.348285650446918,1739137693.768493,35.469966173172,62.356822881657244,1739137693.7684956,35.469966173172,43.22929653233182,1739137693.7684972,35.469966173172,4.730667880563645,1739137693.768499,35.469966173172,-2.082267946166389,1739137693.7685006,35.469966173172,2.2085701459773714,1739137693.7685018,35.469966173172,0.6108,1739137693.768503,35.469966173172,1.0334086150910191,1739137693.7685046,35.469966173172,0.0,1739137693.768506,35.469966173172,0.026649243921049726,1739137693.7685077,35.469966173172,3.639513798572782,1739137693.7685091,35.469966173172,1.0067593711699694 +1739137693.788599,35.48996615409851,45.16307489435204,1739137693.788602,35.48996615409851,8.294100016298206,1739137693.7886057,35.48996615409851,62.52111649438861,1739137693.7886086,35.48996615409851,43.19830067888014,1739137693.78861,35.48996615409851,4.559927720263149,1739137693.788612,35.48996615409851,-2.055152697011959,1739137693.7886133,35.48996615409851,2.2446179505500585,1739137693.788615,35.48996615409851,0.6108,1739137693.7886162,35.48996615409851,1.0186146844326662,1739137693.7886176,35.48996615409851,0.0,1739137693.7886193,35.48996615409851,-0.007474624586212487,1739137693.7886207,35.48996615409851,3.667119012773697,1739137693.7886221,35.48996615409851,1.0098398397076245 +1739137693.8088458,35.509966135025024,45.16307489435204,1739137693.8088489,35.509966135025024,8.294100016298206,1739137693.808852,35.509966135025024,62.52111649438861,1739137693.808855,35.509966135025024,43.19830067888014,1739137693.8088562,35.509966135025024,4.559927720263149,1739137693.8088584,35.509966135025024,-2.055152697011959,1739137693.8088596,35.509966135025024,2.2446179505500585,1739137693.8088615,35.509966135025024,0.6108,1739137693.8088627,35.509966135025024,1.0186146844326662,1739137693.8088646,35.509966135025024,0.0,1739137693.8088658,35.509966135025024,0.008774844725041753,1739137693.8088672,35.509966135025024,3.667119012773697,1739137693.808869,35.509966135025024,1.0098398397076245 +1739137693.8285053,35.52996611595154,45.16307489435204,1739137693.828508,35.52996611595154,8.294100016298206,1739137693.828511,35.52996611595154,62.52111649438861,1739137693.8285139,35.52996611595154,43.19830067888014,1739137693.8285155,35.52996611595154,4.559927720263149,1739137693.8285174,35.52996611595154,-2.055152697011959,1739137693.8285189,35.52996611595154,2.2446179505500585,1739137693.8285205,35.52996611595154,0.6108,1739137693.8285217,35.52996611595154,1.0186146844326662,1739137693.8285236,35.52996611595154,0.0,1739137693.8285248,35.52996611595154,0.008774844725041753,1739137693.8285263,35.52996611595154,3.667119012773697,1739137693.8285277,35.52996611595154,1.0098398397076245 +1739137693.84866,35.54996609687805,45.16307489435204,1739137693.8486629,35.54996609687805,8.294100016298206,1739137693.8486662,35.54996609687805,62.52111649438861,1739137693.8486688,35.54996609687805,43.19830067888014,1739137693.8486705,35.54996609687805,4.559927720263149,1739137693.8486722,35.54996609687805,-2.055152697011959,1739137693.8486738,35.54996609687805,2.2446179505500585,1739137693.8486753,35.54996609687805,0.6108,1739137693.848677,35.54996609687805,1.0186146844326662,1739137693.8486784,35.54996609687805,0.0,1739137693.84868,35.54996609687805,0.008774844725041753,1739137693.8486814,35.54996609687805,3.667119012773697,1739137693.848683,35.54996609687805,1.0098398397076245 +1739137693.8685026,35.569966077804565,45.16307489435204,1739137693.868505,35.569966077804565,8.294100016298206,1739137693.8685079,35.569966077804565,62.52111649438861,1739137693.868511,35.569966077804565,43.19830067888014,1739137693.8685126,35.569966077804565,4.559927720263149,1739137693.868514,35.569966077804565,-2.055152697011959,1739137693.8685155,35.569966077804565,2.2446179505500585,1739137693.8685172,35.569966077804565,0.6108,1739137693.8685186,35.569966077804565,1.0186146844326662,1739137693.8685205,35.569966077804565,0.0,1739137693.8685217,35.569966077804565,0.008774844725041753,1739137693.8685234,35.569966077804565,3.667119012773697,1739137693.8685246,35.569966077804565,1.0098398397076245 +1739137693.888873,35.58996605873108,45.067659045205104,1739137693.8888755,35.58996605873108,8.237154213499519,1739137693.8888788,35.58996605873108,62.55433023893376,1739137693.8888814,35.58996605873108,43.19189977848949,1739137693.8888829,35.58996605873108,4.5248507861224265,1739137693.8888848,35.58996605873108,-2.0386604228826606,1739137693.8888862,35.58996605873108,2.1732993814619728,1739137693.888888,35.58996605873108,0.6108,1739137693.888889,35.58996605873108,1.0480915922754817,1739137693.888891,35.58996605873108,0.0,1739137693.8888922,35.58996605873108,0.06349469227144014,1739137693.8888936,35.58996605873108,3.6947242269746114,1739137693.888895,35.58996605873108,1.0106539832808827 +1739137693.9086897,35.60996603965759,45.067659045205104,1739137693.9086926,35.60996603965759,8.237154213499519,1739137693.9086955,35.60996603965759,62.55433023893376,1739137693.9086983,35.60996603965759,43.19189977848949,1739137693.9087,35.60996603965759,4.5248507861224265,1739137693.9087014,35.60996603965759,-2.0386604228826606,1739137693.9087033,35.60996603965759,2.1732993814619728,1739137693.9087045,35.60996603965759,0.6108,1739137693.9087057,35.60996603965759,1.0480915922754817,1739137693.9087074,35.60996603965759,0.0,1739137693.9087088,35.60996603965759,0.037437608994598914,1739137693.9087107,35.60996603965759,3.6947242269746114,1739137693.908712,35.60996603965759,1.0106539832808827 +1739137693.9290626,35.629966020584106,45.067659045205104,1739137693.9290652,35.629966020584106,8.237154213499519,1739137693.929068,35.629966020584106,62.55433023893376,1739137693.9290707,35.629966020584106,43.19189977848949,1739137693.9290721,35.629966020584106,4.5248507861224265,1739137693.9290736,35.629966020584106,-2.0386604228826606,1739137693.9290752,35.629966020584106,2.1732993814619728,1739137693.9290764,35.629966020584106,0.6108,1739137693.929078,35.629966020584106,1.0480915922754817,1739137693.9290795,35.629966020584106,0.0,1739137693.9290807,35.629966020584106,0.037437608994598914,1739137693.9290824,35.629966020584106,3.6947242269746114,1739137693.9290836,35.629966020584106,1.0106539832808827 +1739137693.9486883,35.64996600151062,45.067659045205104,1739137693.948691,35.64996600151062,8.237154213499519,1739137693.9486942,35.64996600151062,62.55433023893376,1739137693.948697,35.64996600151062,43.19189977848949,1739137693.9486985,35.64996600151062,4.5248507861224265,1739137693.9487004,35.64996600151062,-2.0386604228826606,1739137693.948702,35.64996600151062,2.1732993814619728,1739137693.9487038,35.64996600151062,0.6108,1739137693.948705,35.64996600151062,1.0480915922754817,1739137693.9487069,35.64996600151062,0.0,1739137693.9487083,35.64996600151062,0.037437608994598914,1739137693.9487102,35.64996600151062,3.6947242269746114,1739137693.9487114,35.64996600151062,1.0106539832808827 +1739137693.9689493,35.669965982437134,45.067659045205104,1739137693.9689522,35.669965982437134,8.237154213499519,1739137693.9689548,35.669965982437134,62.55433023893376,1739137693.9689574,35.669965982437134,43.19189977848949,1739137693.968959,35.669965982437134,4.5248507861224265,1739137693.968961,35.669965982437134,-2.0386604228826606,1739137693.9689627,35.669965982437134,2.1732993814619728,1739137693.968964,35.669965982437134,0.6108,1739137693.9689653,35.669965982437134,1.0480915922754817,1739137693.968967,35.669965982437134,0.0,1739137693.9689684,35.669965982437134,0.037437608994598914,1739137693.96897,35.669965982437134,3.6947242269746114,1739137693.9689713,35.669965982437134,1.0106539832808827 +1739137693.988609,35.68996596336365,45.067659045205104,1739137693.9886117,35.68996596336365,8.237154213499519,1739137693.9886148,35.68996596336365,62.55433023893376,1739137693.9886177,35.68996596336365,43.19189977848949,1739137693.988619,35.68996596336365,4.5248507861224265,1739137693.988621,35.68996596336365,-2.0386604228826606,1739137693.988623,35.68996596336365,2.1732993814619728,1739137693.988624,35.68996596336365,0.6108,1739137693.988625,35.68996596336365,1.0480915922754817,1739137693.9886267,35.68996596336365,0.0,1739137693.988628,35.68996596336365,0.037437608994598914,1739137693.9886296,35.68996596336365,3.6947242269746114,1739137693.988631,35.68996596336365,1.0106539832808827 +1739137694.0088096,35.70996594429016,44.97359338062784,1739137694.008813,35.70996594429016,8.177431567361067,1739137694.0088158,35.70996594429016,62.76528199370682,1739137694.0088186,35.70996594429016,43.15084079040914,1739137694.0088203,35.70996594429016,4.303817548848734,1739137694.008822,35.70996594429016,-2.0106125758633877,1739137694.0088239,35.70996594429016,2.2385333572980555,1739137694.0088253,35.70996594429016,0.6108,1739137694.0088267,35.70996594429016,1.0210968462104728,1739137694.0088284,35.70996594429016,0.0,1739137694.0088296,35.70996594429016,-0.022920473899585098,1739137694.0088315,35.70996594429016,3.722329441175526,1739137694.008833,35.70996594429016,1.0152753615168681 +1739137694.028828,35.729965925216675,44.97359338062784,1739137694.0288308,35.729965925216675,8.177431567361067,1739137694.0288339,35.729965925216675,62.76528199370682,1739137694.028837,35.729965925216675,43.15084079040914,1739137694.0288384,35.729965925216675,4.303817548848734,1739137694.0288403,35.729965925216675,-2.0106125758633877,1739137694.0288415,35.729965925216675,2.2385333572980555,1739137694.028843,35.729965925216675,0.6108,1739137694.0288444,35.729965925216675,1.0210968462104728,1739137694.028846,35.729965925216675,0.0,1739137694.0288475,35.729965925216675,0.005821484693604662,1739137694.0288491,35.729965925216675,3.722329441175526,1739137694.0288503,35.729965925216675,1.0152753615168681 +1739137694.048816,35.74996590614319,44.97359338062784,1739137694.0488193,35.74996590614319,8.177431567361067,1739137694.0488222,35.74996590614319,62.76528199370682,1739137694.0488253,35.74996590614319,43.15084079040914,1739137694.048827,35.74996590614319,4.303817548848734,1739137694.0488288,35.74996590614319,-2.0106125758633877,1739137694.0488305,35.74996590614319,2.2385333572980555,1739137694.048832,35.74996590614319,0.6108,1739137694.0488336,35.74996590614319,1.0210968462104728,1739137694.0488353,35.74996590614319,0.0,1739137694.048837,35.74996590614319,0.005821484693604662,1739137694.0488384,35.74996590614319,3.722329441175526,1739137694.04884,35.74996590614319,1.0152753615168681 +1739137694.069028,35.7699658870697,44.97359338062784,1739137694.0690303,35.7699658870697,8.177431567361067,1739137694.0690336,35.7699658870697,62.76528199370682,1739137694.0690365,35.7699658870697,43.15084079040914,1739137694.0690382,35.7699658870697,4.303817548848734,1739137694.0690398,35.7699658870697,-2.0106125758633877,1739137694.0690415,35.7699658870697,2.2385333572980555,1739137694.069043,35.7699658870697,0.6108,1739137694.069044,35.7699658870697,1.0210968462104728,1739137694.069046,35.7699658870697,0.0,1739137694.0690472,35.7699658870697,0.005821484693604662,1739137694.0690491,35.7699658870697,3.722329441175526,1739137694.0690506,35.7699658870697,1.0152753615168681 +1739137694.0888264,35.789965867996216,44.97359338062784,1739137694.088829,35.789965867996216,8.177431567361067,1739137694.0888321,35.789965867996216,62.76528199370682,1739137694.0888355,35.789965867996216,43.15084079040914,1739137694.0888374,35.789965867996216,4.303817548848734,1739137694.088839,35.789965867996216,-2.0106125758633877,1739137694.088841,35.789965867996216,2.2385333572980555,1739137694.0888422,35.789965867996216,0.6108,1739137694.088844,35.789965867996216,1.0210968462104728,1739137694.0888455,35.789965867996216,0.0,1739137694.0888472,35.789965867996216,0.005821484693604662,1739137694.088849,35.789965867996216,3.722329441175526,1739137694.0888507,35.789965867996216,1.0152753615168681 +1739137694.1104007,35.80996584892273,44.88098926789418,1739137694.1104038,35.80996584892273,8.114986401205387,1739137694.110407,35.80996584892273,62.774628250149334,1739137694.1104105,35.80996584892273,43.14890971708051,1739137694.110412,35.80996584892273,4.293518491096019,1739137694.1104138,35.80996584892273,-1.9963494967919646,1739137694.1104155,35.80996584892273,2.1459871741604397,1739137694.1104171,35.80996584892273,0.6108,1739137694.1104183,35.80996584892273,1.0596046450785175,1739137694.1104202,35.80996584892273,0.0,1739137694.1104214,35.80996584892273,0.0786158674504481,1739137694.1104233,35.80996584892273,3.7499346553764408,1739137694.1104248,35.80996584892273,1.0156527867332295 +1739137694.1287012,35.82996582984924,44.88098926789418,1739137694.1287036,35.82996582984924,8.114986401205387,1739137694.128707,35.82996582984924,62.774628250149334,1739137694.1287098,35.82996582984924,43.14890971708051,1739137694.1287112,35.82996582984924,4.293518491096019,1739137694.1287131,35.82996582984924,-1.9963494967919646,1739137694.1287148,35.82996582984924,2.1459871741604397,1739137694.1287162,35.82996582984924,0.6108,1739137694.1287177,35.82996582984924,1.0596046450785175,1739137694.128719,35.82996582984924,0.0,1739137694.128721,35.82996582984924,0.04395185834528803,1739137694.1287227,35.82996582984924,3.7499346553764408,1739137694.1287239,35.82996582984924,1.0156527867332295 +1739137694.1488016,35.84996581077576,44.88098926789418,1739137694.1488047,35.84996581077576,8.114986401205387,1739137694.148808,35.84996581077576,62.774628250149334,1739137694.148811,35.84996581077576,43.14890971708051,1739137694.1488125,35.84996581077576,4.293518491096019,1739137694.1488147,35.84996581077576,-1.9963494967919646,1739137694.148816,35.84996581077576,2.1459871741604397,1739137694.1488173,35.84996581077576,0.6108,1739137694.148819,35.84996581077576,1.0596046450785175,1739137694.1488206,35.84996581077576,0.0,1739137694.1488223,35.84996581077576,0.04395185834528803,1739137694.1488237,35.84996581077576,3.7499346553764408,1739137694.1488252,35.84996581077576,1.0156527867332295 +1739137694.1689975,35.86996579170227,44.88098926789418,1739137694.1690001,35.86996579170227,8.114986401205387,1739137694.1690032,35.86996579170227,62.774628250149334,1739137694.1690059,35.86996579170227,43.14890971708051,1739137694.1690073,35.86996579170227,4.293518491096019,1739137694.1690092,35.86996579170227,-1.9963494967919646,1739137694.1690106,35.86996579170227,2.1459871741604397,1739137694.1690123,35.86996579170227,0.6108,1739137694.1690135,35.86996579170227,1.0596046450785175,1739137694.169015,35.86996579170227,0.0,1739137694.1690164,35.86996579170227,0.04395185834528803,1739137694.169018,35.86996579170227,3.7499346553764408,1739137694.1690195,35.86996579170227,1.0156527867332295 +1739137694.1885657,35.889965772628784,44.88098926789418,1739137694.1885688,35.889965772628784,8.114986401205387,1739137694.188572,35.889965772628784,62.774628250149334,1739137694.1885753,35.889965772628784,43.14890971708051,1739137694.1885765,35.889965772628784,4.293518491096019,1739137694.1885786,35.889965772628784,-1.9963494967919646,1739137694.18858,35.889965772628784,2.1459871741604397,1739137694.1885817,35.889965772628784,0.6108,1739137694.1885831,35.889965772628784,1.0596046450785175,1739137694.188585,35.889965772628784,0.0,1739137694.1885862,35.889965772628784,0.04395185834528803,1739137694.1885881,35.889965772628784,3.7499346553764408,1739137694.1885898,35.889965772628784,1.0156527867332295 +1739137694.2087147,35.9099657535553,44.88098926789418,1739137694.2087176,35.9099657535553,8.114986401205387,1739137694.208721,35.9099657535553,62.774628250149334,1739137694.208724,35.9099657535553,43.14890971708051,1739137694.2087252,35.9099657535553,4.293518491096019,1739137694.2087274,35.9099657535553,-1.9963494967919646,1739137694.208729,35.9099657535553,2.1459871741604397,1739137694.2087307,35.9099657535553,0.6108,1739137694.208732,35.9099657535553,1.0596046450785175,1739137694.2087338,35.9099657535553,0.0,1739137694.208735,35.9099657535553,0.04395185834528803,1739137694.2087367,35.9099657535553,3.7499346553764408,1739137694.2087383,35.9099657535553,1.0156527867332295 +1739137694.231054,35.92996573448181,44.789873124944336,1739137694.2310565,35.92996573448181,8.049813653043303,1739137694.2310593,35.92996573448181,62.93878417496096,1739137694.231062,35.92996573448181,43.114352226342646,1739137694.2310634,35.92996573448181,4.116180160006082,1739137694.2310648,35.92996573448181,-1.9734691438323482,1739137694.2310662,35.92996573448181,2.169486800295379,1739137694.2310677,35.92996573448181,0.6108,1739137694.2310688,35.92996573448181,1.0496911853874087,1739137694.2310705,35.92996573448181,0.0,1739137694.2310717,35.92996573448181,0.014513940449493503,1739137694.2310734,35.92996573448181,3.7775398695773554,1739137694.2310746,35.92996573448181,1.0211591817944257 +1739137694.2485118,35.949965715408325,44.789873124944336,1739137694.2485147,35.949965715408325,8.049813653043303,1739137694.248518,35.949965715408325,62.93878417496096,1739137694.2485204,35.949965715408325,43.114352226342646,1739137694.2485218,35.949965715408325,4.116180160006082,1739137694.2485235,35.949965715408325,-1.9734691438323482,1739137694.2485251,35.949965715408325,2.169486800295379,1739137694.2485263,35.949965715408325,0.6108,1739137694.2485275,35.949965715408325,1.0496911853874087,1739137694.2485292,35.949965715408325,0.0,1739137694.2485301,35.949965715408325,0.028532003592983024,1739137694.2485318,35.949965715408325,3.7775398695773554,1739137694.248533,35.949965715408325,1.0211591817944257 +1739137694.2689984,35.96996569633484,44.789873124944336,1739137694.2690015,35.96996569633484,8.049813653043303,1739137694.269005,35.96996569633484,62.93878417496096,1739137694.2690244,35.96996569633484,43.114352226342646,1739137694.2690256,35.96996569633484,4.116180160006082,1739137694.269027,35.96996569633484,-1.9734691438323482,1739137694.269029,35.96996569633484,2.169486800295379,1739137694.26903,35.96996569633484,0.6108,1739137694.269032,35.96996569633484,1.0496911853874087,1739137694.2690337,35.96996569633484,0.0,1739137694.269035,35.96996569633484,0.028532003592983024,1739137694.2690365,35.96996569633484,3.7775398695773554,1739137694.269038,35.96996569633484,1.0211591817944257 +1739137694.2885435,35.98996567726135,44.789873124944336,1739137694.288546,35.98996567726135,8.049813653043303,1739137694.288549,35.98996567726135,62.93878417496096,1739137694.2885516,35.98996567726135,43.114352226342646,1739137694.288553,35.98996567726135,4.116180160006082,1739137694.2885544,35.98996567726135,-1.9734691438323482,1739137694.288556,35.98996567726135,2.169486800295379,1739137694.2885573,35.98996567726135,0.6108,1739137694.2885582,35.98996567726135,1.0496911853874087,1739137694.28856,35.98996567726135,0.0,1739137694.288561,35.98996567726135,0.028532003592983024,1739137694.2885625,35.98996567726135,3.7775398695773554,1739137694.2885637,35.98996567726135,1.0211591817944257 +1739137694.3087046,36.009965658187866,44.789873124944336,1739137694.3087072,36.009965658187866,8.049813653043303,1739137694.30871,36.009965658187866,62.93878417496096,1739137694.3087127,36.009965658187866,43.114352226342646,1739137694.308714,36.009965658187866,4.116180160006082,1739137694.3087158,36.009965658187866,-1.9734691438323482,1739137694.308717,36.009965658187866,2.169486800295379,1739137694.3087184,36.009965658187866,0.6108,1739137694.3087196,36.009965658187866,1.0496911853874087,1739137694.308721,36.009965658187866,0.0,1739137694.3087227,36.009965658187866,0.028532003592983024,1739137694.3087242,36.009965658187866,3.7775398695773554,1739137694.3087254,36.009965658187866,1.0211591817944257 +1739137694.328845,36.02996563911438,44.7002342682755,1739137694.3288474,36.02996563911438,7.981881505118608,1739137694.3288503,36.02996563911438,63.028214966213916,1739137694.3288527,36.02996563911438,43.094573030562664,1739137694.3288543,36.02996563911438,4.019764029772847,1739137694.3288558,36.02996563911438,-1.9558232032769671,1739137694.3288572,36.02996563911438,2.132434727367873,1739137694.3288584,36.02996563911438,0.6108,1739137694.3288596,36.02996563911438,1.0653643367860293,1739137694.3288612,36.02996563911438,0.0,1739137694.3288622,36.02996563911438,0.052729895773950895,1739137694.3288639,36.02996563911438,3.80514508377827,1739137694.328865,36.02996563911438,1.024157252568687 +1739137694.3491156,36.049965620040894,44.7002342682755,1739137694.3491192,36.049965620040894,7.981881505118608,1739137694.349123,36.049965620040894,63.028214966213916,1739137694.3491268,36.049965620040894,43.094573030562664,1739137694.3491285,36.049965620040894,4.019764029772847,1739137694.349131,36.049965620040894,-1.9558232032769671,1739137694.3491328,36.049965620040894,2.132434727367873,1739137694.3491344,36.049965620040894,0.6108,1739137694.349136,36.049965620040894,1.0653643367860293,1739137694.349138,36.049965620040894,0.0,1739137694.3491397,36.049965620040894,0.041207084217342205,1739137694.3491416,36.049965620040894,3.80514508377827,1739137694.3491435,36.049965620040894,1.024157252568687 +1739137694.3690696,36.06996560096741,44.7002342682755,1739137694.3690724,36.06996560096741,7.981881505118608,1739137694.3690758,36.06996560096741,63.028214966213916,1739137694.369079,36.06996560096741,43.094573030562664,1739137694.3690805,36.06996560096741,4.019764029772847,1739137694.3690825,36.06996560096741,-1.9558232032769671,1739137694.3690841,36.06996560096741,2.132434727367873,1739137694.3690858,36.06996560096741,0.6108,1739137694.3690872,36.06996560096741,1.0653643367860293,1739137694.3690891,36.06996560096741,0.0,1739137694.3690906,36.06996560096741,0.041207084217342205,1739137694.3690925,36.06996560096741,3.80514508377827,1739137694.369094,36.06996560096741,1.024157252568687 +1739137694.3910794,36.08996558189392,44.7002342682755,1739137694.3910823,36.08996558189392,7.981881505118608,1739137694.3910859,36.08996558189392,63.028214966213916,1739137694.3910892,36.08996558189392,43.094573030562664,1739137694.3910909,36.08996558189392,4.019764029772847,1739137694.3910928,36.08996558189392,-1.9558232032769671,1739137694.3910944,36.08996558189392,2.132434727367873,1739137694.391096,36.08996558189392,0.6108,1739137694.3910978,36.08996558189392,1.0653643367860293,1739137694.3910997,36.08996558189392,0.0,1739137694.3911011,36.08996558189392,0.041207084217342205,1739137694.391103,36.08996558189392,3.80514508377827,1739137694.3911047,36.08996558189392,1.024157252568687 +1739137694.4121032,36.109965562820435,44.7002342682755,1739137694.412108,36.109965562820435,7.981881505118608,1739137694.4121134,36.109965562820435,63.028214966213916,1739137694.41212,36.109965562820435,43.094573030562664,1739137694.4121237,36.109965562820435,4.019764029772847,1739137694.4121282,36.109965562820435,-1.9558232032769671,1739137694.4121323,36.109965562820435,2.132434727367873,1739137694.4121368,36.109965562820435,0.6108,1739137694.4121408,36.109965562820435,1.0653643367860293,1739137694.4121451,36.109965562820435,0.0,1739137694.4121492,36.109965562820435,0.041207084217342205,1739137694.4121535,36.109965562820435,3.80514508377827,1739137694.412158,36.109965562820435,1.024157252568687 +1739137694.4292104,36.12996554374695,44.7002342682755,1739137694.4292135,36.12996554374695,7.981881505118608,1739137694.4292169,36.12996554374695,63.028214966213916,1739137694.4292202,36.12996554374695,43.094573030562664,1739137694.4292216,36.12996554374695,4.019764029772847,1739137694.4292238,36.12996554374695,-1.9558232032769671,1739137694.4292254,36.12996554374695,2.132434727367873,1739137694.429227,36.12996554374695,0.6108,1739137694.4292283,36.12996554374695,1.0653643367860293,1739137694.429231,36.12996554374695,0.0,1739137694.4292321,36.12996554374695,0.041207084217342205,1739137694.429234,36.12996554374695,3.80514508377827,1739137694.4292355,36.12996554374695,1.024157252568687 +1739137694.4494123,36.14996552467346,44.612169515587766,1739137694.4494157,36.14996552467346,7.91123166371365,1739137694.4494195,36.14996552467346,63.11632254595047,1739137694.4494228,36.14996552467346,43.07317935458663,1739137694.4494243,36.14996552467346,3.9196802855479516,1739137694.4494264,36.14996552467346,-1.938794446812702,1739137694.4494283,36.14996552467346,2.0945268645030835,1739137694.4494302,36.14996552467346,0.6108,1739137694.4494321,36.14996552467346,1.0816417070473958,1739137694.4494338,36.14996552467346,0.0,1739137694.4494357,36.14996552467346,0.0632220076401164,1739137694.4494374,36.14996552467346,3.8327502979791848,1739137694.449439,36.14996552467346,1.0289030015121345 +1739137694.4718475,36.169965505599976,44.612169515587766,1739137694.4718518,36.169965505599976,7.91123166371365,1739137694.471857,36.169965505599976,63.11632254595047,1739137694.4718635,36.169965505599976,43.07317935458663,1739137694.4718673,36.169965505599976,3.9196802855479516,1739137694.471872,36.169965505599976,-1.938794446812702,1739137694.4718764,36.169965505599976,2.0945268645030835,1739137694.4718804,36.169965505599976,0.6108,1739137694.4718845,36.169965505599976,1.0816417070473958,1739137694.4718888,36.169965505599976,0.0,1739137694.471893,36.169965505599976,0.05273870553526128,1739137694.4718974,36.169965505599976,3.8327502979791848,1739137694.4719017,36.169965505599976,1.0289030015121345 +1739137694.4891787,36.18996548652649,44.612169515587766,1739137694.4891815,36.18996548652649,7.91123166371365,1739137694.489185,36.18996548652649,63.11632254595047,1739137694.4891882,36.18996548652649,43.07317935458663,1739137694.4891896,36.18996548652649,3.9196802855479516,1739137694.4891918,36.18996548652649,-1.938794446812702,1739137694.4891932,36.18996548652649,2.0945268645030835,1739137694.489195,36.18996548652649,0.6108,1739137694.4891963,36.18996548652649,1.0816417070473958,1739137694.489198,36.18996548652649,0.0,1739137694.4891996,36.18996548652649,0.05273870553526128,1739137694.4892013,36.18996548652649,3.8327502979791848,1739137694.489203,36.18996548652649,1.0289030015121345 +1739137694.5091019,36.209965467453,44.612169515587766,1739137694.509105,36.209965467453,7.91123166371365,1739137694.5091083,36.209965467453,63.11632254595047,1739137694.5091114,36.209965467453,43.07317935458663,1739137694.509113,36.209965467453,3.9196802855479516,1739137694.5091152,36.209965467453,-1.938794446812702,1739137694.5091166,36.209965467453,2.0945268645030835,1739137694.5091183,36.209965467453,0.6108,1739137694.5091197,36.209965467453,1.0816417070473958,1739137694.509122,36.209965467453,0.0,1739137694.5091233,36.209965467453,0.05273870553526128,1739137694.5091252,36.209965467453,3.8327502979791848,1739137694.5091267,36.209965467453,1.0289030015121345 +1739137694.5287557,36.22996544837952,44.612169515587766,1739137694.5287585,36.22996544837952,7.91123166371365,1739137694.5287619,36.22996544837952,63.11632254595047,1739137694.528765,36.22996544837952,43.07317935458663,1739137694.5287666,36.22996544837952,3.9196802855479516,1739137694.5287685,36.22996544837952,-1.938794446812702,1739137694.5287702,36.22996544837952,2.0945268645030835,1739137694.5287719,36.22996544837952,0.6108,1739137694.5287733,36.22996544837952,1.0816417070473958,1739137694.5287752,36.22996544837952,0.0,1739137694.528777,36.22996544837952,0.05273870553526128,1739137694.5287788,36.22996544837952,3.8327502979791848,1739137694.5287805,36.22996544837952,1.0289030015121345 +1739137694.5498621,36.24996542930603,44.52565442201144,1739137694.5498657,36.24996542930603,7.837809317565512,1739137694.5498707,36.24996542930603,63.204524967939946,1739137694.5498745,36.24996542930603,43.05075934948282,1739137694.549876,36.24996542930603,3.816269770376435,1739137694.5498784,36.24996542930603,-1.9223135775415436,1739137694.5498803,36.24996542930603,2.055544061718121,1739137694.5498822,36.24996542930603,0.6108,1739137694.5498838,36.24996542930603,1.0986400614656326,1739137694.5498867,36.24996542930603,0.0,1739137694.5498884,36.24996542930603,0.07398108140275235,1739137694.5498903,36.24996542930603,3.8603555121800994,1739137694.5498924,36.24996542930603,1.0347744021957332 +1739137694.5719943,36.269965410232544,44.52565442201144,1739137694.5719988,36.269965410232544,7.837809317565512,1739137694.572004,36.269965410232544,63.204524967939946,1739137694.5720108,36.269965410232544,43.05075934948282,1739137694.5720143,36.269965410232544,3.816269770376435,1739137694.5720189,36.269965410232544,-1.9223135775415436,1739137694.5720234,36.269965410232544,2.055544061718121,1739137694.5720274,36.269965410232544,0.6108,1739137694.5720317,36.269965410232544,1.0986400614656326,1739137694.5720358,36.269965410232544,0.0,1739137694.57204,36.269965410232544,0.0638656592698994,1739137694.5720446,36.269965410232544,3.8603555121800994,1739137694.5720487,36.269965410232544,1.0347744021957332 +1739137694.5891716,36.28996539115906,44.52565442201144,1739137694.5891745,36.28996539115906,7.837809317565512,1739137694.5891786,36.28996539115906,63.204524967939946,1739137694.589182,36.28996539115906,43.05075934948282,1739137694.5891838,36.28996539115906,3.816269770376435,1739137694.5891855,36.28996539115906,-1.9223135775415436,1739137694.5891874,36.28996539115906,2.055544061718121,1739137694.5891888,36.28996539115906,0.6108,1739137694.5891905,36.28996539115906,1.0986400614656326,1739137694.5891922,36.28996539115906,0.0,1739137694.5891938,36.28996539115906,0.0638656592698994,1739137694.5891955,36.28996539115906,3.8603555121800994,1739137694.5891972,36.28996539115906,1.0347744021957332 +1739137694.6090736,36.30996537208557,44.52565442201144,1739137694.6090765,36.30996537208557,7.837809317565512,1739137694.6090798,36.30996537208557,63.204524967939946,1739137694.6090832,36.30996537208557,43.05075934948282,1739137694.6090848,36.30996537208557,3.816269770376435,1739137694.6090868,36.30996537208557,-1.9223135775415436,1739137694.6090884,36.30996537208557,2.055544061718121,1739137694.60909,36.30996537208557,0.6108,1739137694.6090915,36.30996537208557,1.0986400614656326,1739137694.6090934,36.30996537208557,0.0,1739137694.6090949,36.30996537208557,0.0638656592698994,1739137694.6090968,36.30996537208557,3.8603555121800994,1739137694.6090982,36.30996537208557,1.0347744021957332 +1739137694.6292193,36.329965353012085,44.52565442201144,1739137694.6292222,36.329965353012085,7.837809317565512,1739137694.6292257,36.329965353012085,63.204524967939946,1739137694.629229,36.329965353012085,43.05075934948282,1739137694.6292305,36.329965353012085,3.816269770376435,1739137694.6292326,36.329965353012085,-1.9223135775415436,1739137694.629234,36.329965353012085,2.055544061718121,1739137694.629236,36.329965353012085,0.6108,1739137694.6292374,36.329965353012085,1.0986400614656326,1739137694.6292396,36.329965353012085,0.0,1739137694.629241,36.329965353012085,0.0638656592698994,1739137694.629243,36.329965353012085,3.8603555121800994,1739137694.6292443,36.329965353012085,1.0347744021957332 +1739137694.6488006,36.3499653339386,44.52565442201144,1739137694.648804,36.3499653339386,7.837809317565512,1739137694.6488075,36.3499653339386,63.204524967939946,1739137694.648811,36.3499653339386,43.05075934948282,1739137694.6488128,36.3499653339386,3.816269770376435,1739137694.648815,36.3499653339386,-1.9223135775415436,1739137694.648817,36.3499653339386,2.055544061718121,1739137694.6488187,36.3499653339386,0.6108,1739137694.6488204,36.3499653339386,1.0986400614656326,1739137694.6488223,36.3499653339386,0.0,1739137694.648824,36.3499653339386,0.0638656592698994,1739137694.648826,36.3499653339386,3.8603555121800994,1739137694.6488276,36.3499653339386,1.0347744021957332 +1739137694.6725879,36.36996531486511,44.44066309270728,1739137694.6725929,36.36996531486511,7.761545831225931,1739137694.672599,36.36996531486511,63.37650214708873,1739137694.6726065,36.36996531486511,43.00919115429199,1739137694.6726105,36.36996531486511,3.627204147330161,1739137694.672616,36.36996531486511,-1.9041170155062044,1739137694.6726205,36.36996531486511,2.0633307720762692,1739137694.6726253,36.36996531486511,0.6108,1739137694.67263,36.36996531486511,1.095223468253491,1739137694.6726348,36.36996531486511,0.0,1739137694.6726394,36.36996531486511,0.04359497525075852,1739137694.6726444,36.36996531486511,3.887960726381014,1739137694.672649,36.36996531486511,1.041975781505 +1739137694.689388,36.389965295791626,44.44066309270728,1739137694.6893914,36.389965295791626,7.761545831225931,1739137694.689395,36.389965295791626,63.37650214708873,1739137694.6893985,36.389965295791626,43.00919115429199,1739137694.6894004,36.389965295791626,3.627204147330161,1739137694.6894026,36.389965295791626,-1.9041170155062044,1739137694.689405,36.389965295791626,2.0633307720762692,1739137694.6894064,36.389965295791626,0.6108,1739137694.6894083,36.389965295791626,1.095223468253491,1739137694.6894102,36.389965295791626,0.0,1739137694.6894119,36.389965295791626,0.05324768674849101,1739137694.6894138,36.389965295791626,3.887960726381014,1739137694.6894157,36.389965295791626,1.041975781505 +1739137694.7125952,36.40996527671814,44.44066309270728,1739137694.7125998,36.40996527671814,7.761545831225931,1739137694.712606,36.40996527671814,63.37650214708873,1739137694.7126133,36.40996527671814,43.00919115429199,1739137694.7126174,36.40996527671814,3.627204147330161,1739137694.7126226,36.40996527671814,-1.9041170155062044,1739137694.7126274,36.40996527671814,2.0633307720762692,1739137694.7126327,36.40996527671814,0.6108,1739137694.7126372,36.40996527671814,1.095223468253491,1739137694.712642,36.40996527671814,0.0,1739137694.7126467,36.40996527671814,0.05324768674849101,1739137694.7126517,36.40996527671814,3.887960726381014,1739137694.7126565,36.40996527671814,1.041975781505 +1739137694.7290893,36.4199652671814,44.44066309270728,1739137694.7290926,36.4199652671814,7.761545831225931,1739137694.7290962,36.4199652671814,63.37650214708873,1739137694.7291,36.4199652671814,43.00919115429199,1739137694.7291021,36.4199652671814,3.627204147330161,1739137694.7291043,36.4199652671814,-1.9041170155062044,1739137694.7291062,36.4199652671814,2.0633307720762692,1739137694.7291079,36.4199652671814,0.6108,1739137694.7291098,36.4199652671814,1.095223468253491,1739137694.729112,36.4199652671814,0.0,1739137694.7291136,36.4199652671814,0.05324768674849101,1739137694.7291157,36.4199652671814,3.887960726381014,1739137694.7291174,36.4199652671814,1.041975781505 +1739137694.748597,36.44996523857117,44.44066309270728,1739137694.7485993,36.44996523857117,7.761545831225931,1739137694.7486022,36.44996523857117,63.37650214708873,1739137694.748605,36.44996523857117,43.00919115429199,1739137694.7486062,36.44996523857117,3.627204147330161,1739137694.748608,36.44996523857117,-1.9041170155062044,1739137694.7486095,36.44996523857117,2.0633307720762692,1739137694.7486107,36.44996523857117,0.6108,1739137694.7486124,36.44996523857117,1.095223468253491,1739137694.7486138,36.44996523857117,0.0,1739137694.7486155,36.44996523857117,0.05324768674849101,1739137694.748617,36.44996523857117,3.887960726381014,1739137694.7486181,36.44996523857117,1.041975781505 +1739137694.7687247,36.46996521949768,44.35729489224389,1739137694.7687273,36.46996521949768,7.6824782843211175,1739137694.7687302,36.46996521949768,63.44251781384363,1739137694.768733,36.46996521949768,42.98957896741395,1739137694.7687342,36.46996521949768,3.546307557296419,1739137694.7687364,36.46996521949768,-1.8901497889664063,1739137694.7687378,36.46996521949768,2.001928178406051,1739137694.768739,36.46996521949768,0.6108,1739137694.7687402,36.46996521949768,1.1224563579108617,1739137694.7687416,36.46996521949768,0.0,1739137694.7687428,36.46996521949768,0.09427002527215114,1739137694.7687445,36.46996521949768,3.9155659405819287,1739137694.7687457,36.46996521949768,1.0477207893130538 +1739137694.7884145,36.489965200424194,44.35729489224389,1739137694.788417,36.489965200424194,7.6824782843211175,1739137694.7884197,36.489965200424194,63.44251781384363,1739137694.7884223,36.489965200424194,42.98957896741395,1739137694.7884238,36.489965200424194,3.546307557296419,1739137694.7884252,36.489965200424194,-1.8901497889664063,1739137694.7884264,36.489965200424194,2.001928178406051,1739137694.7884278,36.489965200424194,0.6108,1739137694.7884288,36.489965200424194,1.1224563579108617,1739137694.7884305,36.489965200424194,0.0,1739137694.7884316,36.489965200424194,0.07473556859780794,1739137694.7884328,36.489965200424194,3.9155659405819287,1739137694.7884343,36.489965200424194,1.0477207893130538 +1739137694.8086872,36.50996518135071,44.35729489224389,1739137694.8086896,36.50996518135071,7.6824782843211175,1739137694.8086925,36.50996518135071,63.44251781384363,1739137694.808695,36.50996518135071,42.98957896741395,1739137694.8086963,36.50996518135071,3.546307557296419,1739137694.808698,36.50996518135071,-1.8901497889664063,1739137694.8086991,36.50996518135071,2.001928178406051,1739137694.8087003,36.50996518135071,0.6108,1739137694.808702,36.50996518135071,1.1224563579108617,1739137694.8087034,36.50996518135071,0.0,1739137694.8087049,36.50996518135071,0.07473556859780794,1739137694.808706,36.50996518135071,3.9155659405819287,1739137694.8087072,36.50996518135071,1.0477207893130538 +1739137694.831091,36.52996516227722,44.35729489224389,1739137694.8310945,36.52996516227722,7.6824782843211175,1739137694.831099,36.52996516227722,63.44251781384363,1739137694.8311045,36.52996516227722,42.98957896741395,1739137694.8311074,36.52996516227722,3.546307557296419,1739137694.831111,36.52996516227722,-1.8901497889664063,1739137694.831114,36.52996516227722,2.001928178406051,1739137694.8311174,36.52996516227722,0.6108,1739137694.8311205,36.52996516227722,1.1224563579108617,1739137694.8311238,36.52996516227722,0.0,1739137694.8311267,36.52996516227722,0.07473556859780794,1739137694.83113,36.52996516227722,3.9155659405819287,1739137694.8311334,36.52996516227722,1.0477207893130538 +1739137694.8484633,36.549965143203735,44.35729489224389,1739137694.848466,36.549965143203735,7.6824782843211175,1739137694.8484688,36.549965143203735,63.44251781384363,1739137694.8484714,36.549965143203735,42.98957896741395,1739137694.8484726,36.549965143203735,3.546307557296419,1739137694.848474,36.549965143203735,-1.8901497889664063,1739137694.8484755,36.549965143203735,2.001928178406051,1739137694.8484766,36.549965143203735,0.6108,1739137694.8484778,36.549965143203735,1.1224563579108617,1739137694.8484793,36.549965143203735,0.0,1739137694.8484805,36.549965143203735,0.07473556859780794,1739137694.848482,36.549965143203735,3.9155659405819287,1739137694.848483,36.549965143203735,1.0477207893130538 +1739137694.8705404,36.56996512413025,44.35729489224389,1739137694.870544,36.56996512413025,7.6824782843211175,1739137694.8705485,36.56996512413025,63.44251781384363,1739137694.8705692,36.56996512413025,42.98957896741395,1739137694.8705723,36.56996512413025,3.546307557296419,1739137694.8705888,36.56996512413025,-1.8901497889664063,1739137694.8705916,36.56996512413025,2.001928178406051,1739137694.870595,36.56996512413025,0.6108,1739137694.870598,36.56996512413025,1.1224563579108617,1739137694.8706014,36.56996512413025,0.0,1739137694.8706045,36.56996512413025,0.07473556859780794,1739137694.8706079,36.56996512413025,3.9155659405819287,1739137694.8706112,36.56996512413025,1.0477207893130538 +1739137694.8905892,36.58996510505676,44.275581136331674,1739137694.8905926,36.58996510505676,7.60057779363833,1739137694.8905969,36.58996510505676,63.54609343756429,1739137694.8906016,36.58996510505676,42.95718247802658,1739137694.8906045,36.58996510505676,3.4211181019148578,1739137694.890608,36.58996510505676,-1.876363888048443,1739137694.8906112,36.58996510505676,1.9599113414847964,1739137694.8906143,36.58996510505676,0.6108,1739137694.8906176,36.58996510505676,1.1414806041307002,1739137694.890621,36.58996510505676,0.0,1739137694.890624,36.58996510505676,0.09467488343383255,1739137694.8906274,36.58996510505676,3.9431711547828434,1739137694.8906307,36.58996510505676,1.0563006372666717 +1739137694.9085197,36.609965085983276,44.275581136331674,1739137694.9085221,36.609965085983276,7.60057779363833,1739137694.9085255,36.609965085983276,63.54609343756429,1739137694.908528,36.609965085983276,42.95718247802658,1739137694.9085295,36.609965085983276,3.4211181019148578,1739137694.908531,36.609965085983276,-1.876363888048443,1739137694.9085324,36.609965085983276,1.9599113414847964,1739137694.908534,36.609965085983276,0.6108,1739137694.9085352,36.609965085983276,1.1414806041307002,1739137694.908537,36.609965085983276,0.0,1739137694.908538,36.609965085983276,0.08517996686402851,1739137694.9085395,36.609965085983276,3.9431711547828434,1739137694.908541,36.609965085983276,1.0563006372666717 +1739137694.9306753,36.62996506690979,44.275581136331674,1739137694.9306786,36.62996506690979,7.60057779363833,1739137694.930683,36.62996506690979,63.54609343756429,1739137694.930688,36.62996506690979,42.95718247802658,1739137694.9306908,36.62996506690979,3.4211181019148578,1739137694.9306943,36.62996506690979,-1.876363888048443,1739137694.9306977,36.62996506690979,1.9599113414847964,1739137694.930701,36.62996506690979,0.6108,1739137694.930704,36.62996506690979,1.1414806041307002,1739137694.9307075,36.62996506690979,0.0,1739137694.9307106,36.62996506690979,0.08517996686402851,1739137694.9307141,36.62996506690979,3.9431711547828434,1739137694.9307175,36.62996506690979,1.0563006372666717 +1739137694.9486754,36.649965047836304,44.275581136331674,1739137694.9486775,36.649965047836304,7.60057779363833,1739137694.9486804,36.649965047836304,63.54609343756429,1739137694.9486833,36.649965047836304,42.95718247802658,1739137694.9486842,36.649965047836304,3.4211181019148578,1739137694.948686,36.649965047836304,-1.876363888048443,1739137694.9486873,36.649965047836304,1.9599113414847964,1739137694.9486883,36.649965047836304,0.6108,1739137694.9486897,36.649965047836304,1.1414806041307002,1739137694.9486911,36.649965047836304,0.0,1739137694.9486923,36.649965047836304,0.08517996686402851,1739137694.9486938,36.649965047836304,3.9431711547828434,1739137694.948695,36.649965047836304,1.0563006372666717 +1739137694.9704013,36.66996502876282,44.275581136331674,1739137694.9704044,36.66996502876282,7.60057779363833,1739137694.9704087,36.66996502876282,63.54609343756429,1739137694.970414,36.66996502876282,42.95718247802658,1739137694.9704165,36.66996502876282,3.4211181019148578,1739137694.9704201,36.66996502876282,-1.876363888048443,1739137694.9704235,36.66996502876282,1.9599113414847964,1739137694.9704266,36.66996502876282,0.6108,1739137694.97043,36.66996502876282,1.1414806041307002,1739137694.970433,36.66996502876282,0.0,1739137694.9704363,36.66996502876282,0.08517996686402851,1739137694.9704397,36.66996502876282,3.9431711547828434,1739137694.9704428,36.66996502876282,1.0563006372666717 +1739137694.9888031,36.68996500968933,44.19549396836992,1739137694.9888055,36.68996500968933,7.515748199237823,1739137694.9888084,36.68996500968933,63.63185698756749,1739137694.988811,36.68996500968933,42.92695196219059,1739137694.9888122,36.68996500968933,3.31118895342034,1739137694.9888139,36.68996500968933,-1.8638177965022888,1739137694.988815,36.68996500968933,1.9046890357865647,1739137694.9888165,36.68996500968933,0.6108,1739137694.9888177,36.68996500968933,1.166975218148845,1739137694.9888191,36.68996500968933,0.0,1739137694.9888203,36.68996500968933,0.11587644252765053,1739137694.9888217,36.68996500968933,3.970776368983758,1739137694.988823,36.68996500968933,1.0657161522868424 +1739137695.0085123,36.709964990615845,44.19549396836992,1739137695.008515,36.709964990615845,7.515748199237823,1739137695.0085177,36.709964990615845,63.63185698756749,1739137695.0085201,36.709964990615845,42.92695196219059,1739137695.0085216,36.709964990615845,3.31118895342034,1739137695.0085232,36.709964990615845,-1.8638177965022888,1739137695.0085247,36.709964990615845,1.9046890357865647,1739137695.0085258,36.709964990615845,0.6108,1739137695.008527,36.709964990615845,1.166975218148845,1739137695.0085287,36.709964990615845,0.0,1739137695.00853,36.709964990615845,0.10125906586200273,1739137695.008531,36.709964990615845,3.970776368983758,1739137695.0085325,36.709964990615845,1.0657161522868424 +1739137695.0306256,36.72996497154236,44.19549396836992,1739137695.030629,36.72996497154236,7.515748199237823,1739137695.0306332,36.72996497154236,63.63185698756749,1739137695.0306387,36.72996497154236,42.92695196219059,1739137695.0306413,36.72996497154236,3.31118895342034,1739137695.0306451,36.72996497154236,-1.8638177965022888,1739137695.0306485,36.72996497154236,1.9046890357865647,1739137695.0306518,36.72996497154236,0.6108,1739137695.0306551,36.72996497154236,1.166975218148845,1739137695.0306585,36.72996497154236,0.0,1739137695.0306618,36.72996497154236,0.10125906586200273,1739137695.0306656,36.72996497154236,3.970776368983758,1739137695.030669,36.72996497154236,1.0657161522868424 +1739137695.0485485,36.74996495246887,44.19549396836992,1739137695.0485508,36.74996495246887,7.515748199237823,1739137695.048554,36.74996495246887,63.63185698756749,1739137695.0485566,36.74996495246887,42.92695196219059,1739137695.0485578,36.74996495246887,3.31118895342034,1739137695.0485597,36.74996495246887,-1.8638177965022888,1739137695.0485609,36.74996495246887,1.9046890357865647,1739137695.0485623,36.74996495246887,0.6108,1739137695.0485635,36.74996495246887,1.166975218148845,1739137695.048565,36.74996495246887,0.0,1739137695.0485663,36.74996495246887,0.10125906586200273,1739137695.0485678,36.74996495246887,3.970776368983758,1739137695.0485692,36.74996495246887,1.0657161522868424 +1739137695.0715446,36.769964933395386,44.19549396836992,1739137695.0715477,36.769964933395386,7.515748199237823,1739137695.0715516,36.769964933395386,63.63185698756749,1739137695.0715563,36.769964933395386,42.92695196219059,1739137695.071559,36.769964933395386,3.31118895342034,1739137695.0715623,36.769964933395386,-1.8638177965022888,1739137695.0715654,36.769964933395386,1.9046890357865647,1739137695.071568,36.769964933395386,0.6108,1739137695.071571,36.769964933395386,1.166975218148845,1739137695.0715742,36.769964933395386,0.0,1739137695.0715773,36.769964933395386,0.10125906586200273,1739137695.0715806,36.769964933395386,3.970776368983758,1739137695.0715837,36.769964933395386,1.0657161522868424 +1739137695.0884857,36.7899649143219,44.19549396836992,1739137695.088488,36.7899649143219,7.515748199237823,1739137695.0885074,36.7899649143219,63.63185698756749,1739137695.08851,36.7899649143219,42.92695196219059,1739137695.0885112,36.7899649143219,3.31118895342034,1739137695.0885127,36.7899649143219,-1.8638177965022888,1739137695.088514,36.7899649143219,1.9046890357865647,1739137695.0885153,36.7899649143219,0.6108,1739137695.0885162,36.7899649143219,1.166975218148845,1739137695.088518,36.7899649143219,0.0,1739137695.0885189,36.7899649143219,0.10125906586200273,1739137695.0885205,36.7899649143219,3.970776368983758,1739137695.0885215,36.7899649143219,1.0657161522868424 +1739137695.1083732,36.80996489524841,44.1170153142955,1739137695.1083755,36.80996489524841,7.427885003484494,1739137695.1083784,36.80996489524841,63.79385442682712,1739137695.108381,36.80996489524841,42.87154577916894,1739137695.1083822,36.80996489524841,3.123023782299054,1739137695.108384,36.80996489524841,-1.8524236183073632,1739137695.1083856,36.80996489524841,1.8778584007400605,1739137695.1083865,36.80996489524841,0.6108,1739137695.108388,36.80996489524841,1.179566940544416,1739137695.1083894,36.80996489524841,0.0,1739137695.1083906,36.80996489524841,0.10355479948830056,1739137695.1083922,36.80996489524841,3.9983815831846727,1739137695.1083932,36.80996489524841,1.0771053480909334 +1739137695.1310003,36.82996487617493,44.1170153142955,1739137695.1310039,36.82996487617493,7.427885003484494,1739137695.1310086,36.82996487617493,63.79385442682712,1739137695.1310136,36.82996487617493,42.87154577916894,1739137695.1310165,36.82996487617493,3.123023782299054,1739137695.13102,36.82996487617493,-1.8524236183073632,1739137695.1310234,36.82996487617493,1.8778584007400605,1739137695.1310267,36.82996487617493,0.6108,1739137695.1310298,36.82996487617493,1.179566940544416,1739137695.1310337,36.82996487617493,0.0,1739137695.1310368,36.82996487617493,0.10246159245348263,1739137695.1310403,36.82996487617493,3.9983815831846727,1739137695.1310437,36.82996487617493,1.0771053480909334 +1739137695.148377,36.84996485710144,44.1170153142955,1739137695.1483793,36.84996485710144,7.427885003484494,1739137695.1483824,36.84996485710144,63.79385442682712,1739137695.148385,36.84996485710144,42.87154577916894,1739137695.1483862,36.84996485710144,3.123023782299054,1739137695.1483884,36.84996485710144,-1.8524236183073632,1739137695.1483898,36.84996485710144,1.8778584007400605,1739137695.1483912,36.84996485710144,0.6108,1739137695.1483924,36.84996485710144,1.179566940544416,1739137695.1483939,36.84996485710144,0.0,1739137695.148395,36.84996485710144,0.10246159245348263,1739137695.1483965,36.84996485710144,3.9983815831846727,1739137695.148398,36.84996485710144,1.0771053480909334 +1739137695.1708772,36.869964838027954,44.1170153142955,1739137695.170881,36.869964838027954,7.427885003484494,1739137695.1708853,36.869964838027954,63.79385442682712,1739137695.1708906,36.869964838027954,42.87154577916894,1739137695.1708937,36.869964838027954,3.123023782299054,1739137695.1708972,36.869964838027954,-1.8524236183073632,1739137695.1709006,36.869964838027954,1.8778584007400605,1739137695.170904,36.869964838027954,0.6108,1739137695.170907,36.869964838027954,1.179566940544416,1739137695.1709104,36.869964838027954,0.0,1739137695.1709137,36.869964838027954,0.10246159245348263,1739137695.170917,36.869964838027954,3.9983815831846727,1739137695.1709204,36.869964838027954,1.0771053480909334 +1739137695.18849,36.88996481895447,44.1170153142955,1739137695.1884925,36.88996481895447,7.427885003484494,1739137695.1884954,36.88996481895447,63.79385442682712,1739137695.188498,36.88996481895447,42.87154577916894,1739137695.1884992,36.88996481895447,3.123023782299054,1739137695.1885006,36.88996481895447,-1.8524236183073632,1739137695.188502,36.88996481895447,1.8778584007400605,1739137695.1885033,36.88996481895447,0.6108,1739137695.1885045,36.88996481895447,1.179566940544416,1739137695.1885061,36.88996481895447,0.0,1739137695.1885073,36.88996481895447,0.10246159245348263,1739137695.1885087,36.88996481895447,3.9983815831846727,1739137695.18851,36.88996481895447,1.0771053480909334 +1739137695.2085018,36.90996479988098,44.040196980409064,1739137695.2085044,36.90996479988098,7.336948385703899,1739137695.2085068,36.90996479988098,64.06018814231503,1739137695.2085094,36.90996479988098,42.77644870373552,1739137695.2085106,36.90996479988098,2.8384743186088706,1739137695.2085125,36.90996479988098,-1.8446655530481906,1739137695.2085137,36.90996479988098,1.873396452464215,1739137695.2085152,36.90996479988098,0.6108,1739137695.2085164,36.90996479988098,1.1816740870514548,1739137695.2085178,36.90996479988098,0.0,1739137695.208519,36.90996479988098,0.08504099045511632,1739137695.2085204,36.90996479988098,4.025986797385592,1739137695.2085218,36.90996479988098,1.0883375676912326 +1739137695.2310517,36.929964780807495,44.040196980409064,1739137695.2310553,36.929964780807495,7.336948385703899,1739137695.23106,36.929964780807495,64.06018814231503,1739137695.231065,36.929964780807495,42.77644870373552,1739137695.231068,36.929964780807495,2.8384743186088706,1739137695.2310717,36.929964780807495,-1.8446655530481906,1739137695.231075,36.929964780807495,1.873396452464215,1739137695.2310784,36.929964780807495,0.6108,1739137695.2310815,36.929964780807495,1.1816740870514548,1739137695.231085,36.929964780807495,0.0,1739137695.2310882,36.929964780807495,0.09333651936022225,1739137695.2310917,36.929964780807495,4.025986797385592,1739137695.231095,36.929964780807495,1.0883375676912326 +1739137695.248396,36.94996476173401,44.040196980409064,1739137695.2483985,36.94996476173401,7.336948385703899,1739137695.2484016,36.94996476173401,64.06018814231503,1739137695.2484043,36.94996476173401,42.77644870373552,1739137695.2484055,36.94996476173401,2.8384743186088706,1739137695.2484074,36.94996476173401,-1.8446655530481906,1739137695.2484086,36.94996476173401,1.873396452464215,1739137695.2484097,36.94996476173401,0.6108,1739137695.2484114,36.94996476173401,1.1816740870514548,1739137695.2484128,36.94996476173401,0.0,1739137695.2484143,36.94996476173401,0.09333651936022225,1739137695.2484157,36.94996476173401,4.025986797385592,1739137695.2484171,36.94996476173401,1.0883375676912326 +1739137695.2710977,36.96996474266052,44.040196980409064,1739137695.271105,36.96996474266052,7.336948385703899,1739137695.2711122,36.96996474266052,64.06018814231503,1739137695.2711194,36.96996474266052,42.77644870373552,1739137695.2711236,36.96996474266052,2.8384743186088706,1739137695.271129,36.96996474266052,-1.8446655530481906,1739137695.271133,36.96996474266052,1.873396452464215,1739137695.2711482,36.96996474266052,0.6108,1739137695.2711585,36.96996474266052,1.1816740870514548,1739137695.2711635,36.96996474266052,0.0,1739137695.271168,36.96996474266052,0.09333651936022225,1739137695.2711737,36.96996474266052,4.025986797385592,1739137695.2711785,36.96996474266052,1.0883375676912326 +1739137695.2885308,36.989964723587036,44.040196980409064,1739137695.2885337,36.989964723587036,7.336948385703899,1739137695.2885365,36.989964723587036,64.06018814231503,1739137695.2885394,36.989964723587036,42.77644870373552,1739137695.2885406,36.989964723587036,2.8384743186088706,1739137695.2885425,36.989964723587036,-1.8446655530481906,1739137695.288544,36.989964723587036,1.873396452464215,1739137695.2885454,36.989964723587036,0.6108,1739137695.2885466,36.989964723587036,1.1816740870514548,1739137695.288548,36.989964723587036,0.0,1739137695.2885494,36.989964723587036,0.09333651936022225,1739137695.2885509,36.989964723587036,4.025986797385592,1739137695.2885523,36.989964723587036,1.0883375676912326 +1739137695.3085592,37.00996470451355,44.040196980409064,1739137695.3085616,37.00996470451355,7.336948385703899,1739137695.3085644,37.00996470451355,64.06018814231503,1739137695.3085673,37.00996470451355,42.77644870373552,1739137695.3085685,37.00996470451355,2.8384743186088706,1739137695.3085704,37.00996470451355,-1.8446655530481906,1739137695.308572,37.00996470451355,1.873396452464215,1739137695.3085735,37.00996470451355,0.6108,1739137695.3085747,37.00996470451355,1.1816740870514548,1739137695.3085763,37.00996470451355,0.0,1739137695.3085775,37.00996470451355,0.09333651936022225,1739137695.3085787,37.00996470451355,4.025986797385592,1739137695.3085804,37.00996470451355,1.0883375676912326 +1739137695.3307528,37.02996468544006,43.96518769946258,1739137695.3307562,37.02996468544006,7.243012114505504,1739137695.3307607,37.02996468544006,64.06210262567932,1739137695.3307657,37.02996468544006,42.76597074922136,1739137695.3307686,37.02996468544006,2.80812179977985,1739137695.3307724,37.02996468544006,-1.8348856956991753,1739137695.3307757,37.02996468544006,1.766633237724556,1739137695.330779,37.02996468544006,0.6108,1739137695.3307824,37.02996468544006,1.2332308547472053,1739137695.3307858,37.02996468544006,0.0,1739137695.330789,37.02996468544006,0.17254727135246278,1739137695.3307927,37.02996468544006,4.053592011586511,1739137695.3307962,37.02996468544006,1.0984030079478337 +1739137695.3484795,37.04996466636658,43.96518769946258,1739137695.3484821,37.04996466636658,7.243012114505504,1739137695.3484848,37.04996466636658,64.06210262567932,1739137695.3484879,37.04996466636658,42.76597074922136,1739137695.3484893,37.04996466636658,2.80812179977985,1739137695.3484907,37.04996466636658,-1.8348856956991753,1739137695.3484924,37.04996466636658,1.766633237724556,1739137695.3484936,37.04996466636658,0.6108,1739137695.3484948,37.04996466636658,1.2332308547472053,1739137695.3484964,37.04996466636658,0.0,1739137695.3484976,37.04996466636658,0.13482784679937154,1739137695.3484993,37.04996466636658,4.053592011586511,1739137695.3485005,37.04996466636658,1.0984030079478337 +1739137695.3707085,37.06996464729309,43.96518769946258,1739137695.3707123,37.06996464729309,7.243012114505504,1739137695.3707166,37.06996464729309,64.06210262567932,1739137695.3707218,37.06996464729309,42.76597074922136,1739137695.3707252,37.06996464729309,2.80812179977985,1739137695.3707287,37.06996464729309,-1.8348856956991753,1739137695.3707323,37.06996464729309,1.766633237724556,1739137695.370736,37.06996464729309,0.6108,1739137695.3707392,37.06996464729309,1.2332308547472053,1739137695.3707426,37.06996464729309,0.0,1739137695.370746,37.06996464729309,0.13482784679937154,1739137695.3707495,37.06996464729309,4.053592011586511,1739137695.370753,37.06996464729309,1.0984030079478337 +1739137695.3884995,37.089964628219604,43.96518769946258,1739137695.3885024,37.089964628219604,7.243012114505504,1739137695.3885047,37.089964628219604,64.06210262567932,1739137695.3885076,37.089964628219604,42.76597074922136,1739137695.3885093,37.089964628219604,2.80812179977985,1739137695.3885107,37.089964628219604,-1.8348856956991753,1739137695.3885124,37.089964628219604,1.766633237724556,1739137695.3885136,37.089964628219604,0.6108,1739137695.3885148,37.089964628219604,1.2332308547472053,1739137695.3885164,37.089964628219604,0.0,1739137695.3885176,37.089964628219604,0.13482784679937154,1739137695.3885193,37.089964628219604,4.053592011586511,1739137695.388521,37.089964628219604,1.0984030079478337 +1739137695.4084294,37.10996460914612,43.96518769946258,1739137695.4084322,37.10996460914612,7.243012114505504,1739137695.408435,37.10996460914612,64.06210262567932,1739137695.408438,37.10996460914612,42.76597074922136,1739137695.4084394,37.10996460914612,2.80812179977985,1739137695.4084408,37.10996460914612,-1.8348856956991753,1739137695.4084423,37.10996460914612,1.766633237724556,1739137695.4084437,37.10996460914612,0.6108,1739137695.408445,37.10996460914612,1.2332308547472053,1739137695.4084463,37.10996460914612,0.0,1739137695.4084475,37.10996460914612,0.13482784679937154,1739137695.408449,37.10996460914612,4.053592011586511,1739137695.4084504,37.10996460914612,1.0984030079478337 +1739137695.4308305,37.12996459007263,43.89197436704963,1739137695.4308338,37.12996459007263,7.145944766131791,1739137695.4308386,37.12996459007263,64.06402507248443,1739137695.4308438,37.12996459007263,42.750840736087866,1739137695.4308467,37.12996459007263,2.763362177593275,1739137695.4308505,37.12996459007263,-1.8255196021377853,1739137695.4308538,37.12996459007263,1.664928519741532,1739137695.4308572,37.12996459007263,0.6108,1739137695.4308605,37.12996459007263,1.2844355022626575,1739137695.4308639,37.12996459007263,0.0,1739137695.4308672,37.12996459007263,0.20373888970006276,1739137695.4308708,37.12996459007263,4.081197225787431,1739137695.430874,37.12996459007263,1.1135114112886828 +1739137695.4484775,37.149964570999146,43.89197436704963,1739137695.4484804,37.149964570999146,7.145944766131791,1739137695.448483,37.149964570999146,64.06402507248443,1739137695.4484859,37.149964570999146,42.750840736087866,1739137695.4484875,37.149964570999146,2.763362177593275,1739137695.448489,37.149964570999146,-1.8255196021377853,1739137695.4484901,37.149964570999146,1.664928519741532,1739137695.4484918,37.149964570999146,0.6108,1739137695.448493,37.149964570999146,1.2844355022626575,1739137695.4484944,37.149964570999146,0.0,1739137695.448496,37.149964570999146,0.17092409097397465,1739137695.4484973,37.149964570999146,4.081197225787431,1739137695.448499,37.149964570999146,1.1135114112886828 +1739137695.470772,37.16996455192566,43.89197436704963,1739137695.4707758,37.16996455192566,7.145944766131791,1739137695.4707801,37.16996455192566,64.06402507248443,1739137695.4707856,37.16996455192566,42.750840736087866,1739137695.4707882,37.16996455192566,2.763362177593275,1739137695.4707923,37.16996455192566,-1.8255196021377853,1739137695.4707956,37.16996455192566,1.664928519741532,1739137695.4707987,37.16996455192566,0.6108,1739137695.4708025,37.16996455192566,1.2844355022626575,1739137695.470819,37.16996455192566,0.0,1739137695.4708226,37.16996455192566,0.17092409097397465,1739137695.470826,37.16996455192566,4.081197225787431,1739137695.4708295,37.16996455192566,1.1135114112886828 +1739137695.4909348,37.18996453285217,43.89197436704963,1739137695.4909382,37.18996453285217,7.145944766131791,1739137695.4909425,37.18996453285217,64.06402507248443,1739137695.4909475,37.18996453285217,42.750840736087866,1739137695.49095,37.18996453285217,2.763362177593275,1739137695.4909542,37.18996453285217,-1.8255196021377853,1739137695.4909573,37.18996453285217,1.664928519741532,1739137695.4909606,37.18996453285217,0.6108,1739137695.4909637,37.18996453285217,1.2844355022626575,1739137695.490967,37.18996453285217,0.0,1739137695.4909701,37.18996453285217,0.17092409097397465,1739137695.4909735,37.18996453285217,4.081197225787431,1739137695.4909768,37.18996453285217,1.1135114112886828 +1739137695.5084598,37.20996451377869,43.89197436704963,1739137695.5084624,37.20996451377869,7.145944766131791,1739137695.5084648,37.20996451377869,64.06402507248443,1739137695.508468,37.20996451377869,42.750840736087866,1739137695.508469,37.20996451377869,2.763362177593275,1739137695.5084705,37.20996451377869,-1.8255196021377853,1739137695.508472,37.20996451377869,1.664928519741532,1739137695.5084732,37.20996451377869,0.6108,1739137695.5084743,37.20996451377869,1.2844355022626575,1739137695.5084755,37.20996451377869,0.0,1739137695.508477,37.20996451377869,0.17092409097397465,1739137695.5084782,37.20996451377869,4.081197225787431,1739137695.5084796,37.20996451377869,1.1135114112886828 +1739137695.5306985,37.2299644947052,43.89197436704963,1739137695.5307019,37.2299644947052,7.145944766131791,1739137695.530706,37.2299644947052,64.06402507248443,1739137695.5307107,37.2299644947052,42.750840736087866,1739137695.5307136,37.2299644947052,2.763362177593275,1739137695.5307171,37.2299644947052,-1.8255196021377853,1739137695.5307205,37.2299644947052,1.664928519741532,1739137695.5307236,37.2299644947052,0.6108,1739137695.530727,37.2299644947052,1.2844355022626575,1739137695.5307302,37.2299644947052,0.0,1739137695.5307333,37.2299644947052,0.17092409097397465,1739137695.5307367,37.2299644947052,4.081197225787431,1739137695.5307398,37.2299644947052,1.1135114112886828 +1739137695.548528,37.249964475631714,43.82036692833563,1739137695.5485303,37.249964475631714,7.0453449682324045,1739137695.5485337,37.249964475631714,64.25222989831681,1739137695.5485363,37.249964475631714,42.66201772294193,1739137695.5485375,37.249964475631714,2.533598221897242,1739137695.5485392,37.249964475631714,-1.822109086192125,1739137695.5485406,37.249964475631714,1.6071877263642131,1739137695.548542,37.249964475631714,0.6108,1739137695.5485432,37.249964475631714,1.314446469576902,1739137695.548545,37.249964475631714,0.0,1739137695.5485463,37.249964475631714,0.1912090130439718,1739137695.5485477,37.249964475631714,4.1088024399883505,1739137695.5485492,37.249964475631714,1.132896948058267 +1739137695.5713522,37.26996445655823,43.82036692833563,1739137695.5713558,37.26996445655823,7.0453449682324045,1739137695.57136,37.26996445655823,64.25222989831681,1739137695.5713649,37.26996445655823,42.66201772294193,1739137695.5713677,37.26996445655823,2.533598221897242,1739137695.5713716,37.26996445655823,-1.822109086192125,1739137695.5713747,37.26996445655823,1.6071877263642131,1739137695.571378,37.26996445655823,0.6108,1739137695.571381,37.26996445655823,1.314446469576902,1739137695.5713844,37.26996445655823,0.0,1739137695.5713873,37.26996445655823,0.18154952151863513,1739137695.5713906,37.26996445655823,4.1088024399883505,1739137695.571394,37.26996445655823,1.132896948058267 +1739137695.59114,37.28996443748474,43.82036692833563,1739137695.5911438,37.28996443748474,7.0453449682324045,1739137695.5911481,37.28996443748474,64.25222989831681,1739137695.5911531,37.28996443748474,42.66201772294193,1739137695.5911558,37.28996443748474,2.533598221897242,1739137695.5911593,37.28996443748474,-1.822109086192125,1739137695.5911624,37.28996443748474,1.6071877263642131,1739137695.5911658,37.28996443748474,0.6108,1739137695.5911689,37.28996443748474,1.314446469576902,1739137695.591172,37.28996443748474,0.0,1739137695.591175,37.28996443748474,0.18154952151863513,1739137695.5911784,37.28996443748474,4.1088024399883505,1739137695.5911818,37.28996443748474,1.132896948058267 +1739137695.6084876,37.309964418411255,43.82036692833563,1739137695.6084907,37.309964418411255,7.0453449682324045,1739137695.6084936,37.309964418411255,64.25222989831681,1739137695.608497,37.309964418411255,42.66201772294193,1739137695.608498,37.309964418411255,2.533598221897242,1739137695.6084998,37.309964418411255,-1.822109086192125,1739137695.6085012,37.309964418411255,1.6071877263642131,1739137695.6085026,37.309964418411255,0.6108,1739137695.608504,37.309964418411255,1.314446469576902,1739137695.6085055,37.309964418411255,0.0,1739137695.608507,37.309964418411255,0.18154952151863513,1739137695.6085083,37.309964418411255,4.1088024399883505,1739137695.6085098,37.309964418411255,1.132896948058267 +1739137695.6310842,37.32996439933777,43.82036692833563,1739137695.6310873,37.32996439933777,7.0453449682324045,1739137695.631091,37.32996439933777,64.25222989831681,1739137695.631096,37.32996439933777,42.66201772294193,1739137695.6310985,37.32996439933777,2.533598221897242,1739137695.6311018,37.32996439933777,-1.822109086192125,1739137695.631105,37.32996439933777,1.6071877263642131,1739137695.6311078,37.32996439933777,0.6108,1739137695.631111,37.32996439933777,1.314446469576902,1739137695.631114,37.32996439933777,0.0,1739137695.631117,37.32996439933777,0.18154952151863513,1739137695.6311204,37.32996439933777,4.1088024399883505,1739137695.6311235,37.32996439933777,1.132896948058267 +1739137695.6485393,37.34996438026428,43.75037518860606,1739137695.6485417,37.34996438026428,6.941035835137775,1739137695.6485445,37.34996438026428,64.36313234274549,1739137695.6485472,37.34996438026428,42.59407907627963,1739137695.6485484,37.34996438026428,2.3768959243316004,1739137695.6485498,37.34996438026428,-1.8189195214664078,1739137695.6485512,37.34996438026428,1.5161583058046877,1739137695.6485524,37.34996438026428,0.6108,1739137695.6485534,37.34996438026428,1.3631898202866162,1739137695.6485548,37.34996438026428,0.0,1739137695.648556,37.34996438026428,0.23647954055649528,1739137695.6485574,37.34996438026428,4.13640765418927,1739137695.6485586,37.34996438026428,1.1528674447195582 +1739137695.671743,37.369964361190796,43.75037518860606,1739137695.671746,37.369964361190796,6.941035835137775,1739137695.6717498,37.369964361190796,64.36313234274549,1739137695.6717548,37.369964361190796,42.59407907627963,1739137695.6717572,37.369964361190796,2.3768959243316004,1739137695.6717606,37.369964361190796,-1.8189195214664078,1739137695.671764,37.369964361190796,1.5161583058046877,1739137695.671767,37.369964361190796,0.6108,1739137695.67177,37.369964361190796,1.3631898202866162,1739137695.6717732,37.369964361190796,0.0,1739137695.6717763,37.369964361190796,0.21032237556705802,1739137695.6717796,37.369964361190796,4.13640765418927,1739137695.6717825,37.369964361190796,1.1528674447195582 +1739137695.6883829,37.38996434211731,43.75037518860606,1739137695.6883857,37.38996434211731,6.941035835137775,1739137695.6883888,37.38996434211731,64.36313234274549,1739137695.6883917,37.38996434211731,42.59407907627963,1739137695.6883929,37.38996434211731,2.3768959243316004,1739137695.6883948,37.38996434211731,-1.8189195214664078,1739137695.6883962,37.38996434211731,1.5161583058046877,1739137695.688398,37.38996434211731,0.6108,1739137695.688399,37.38996434211731,1.3631898202866162,1739137695.6884007,37.38996434211731,0.0,1739137695.688402,37.38996434211731,0.21032237556705802,1739137695.6884031,37.38996434211731,4.13640765418927,1739137695.6884046,37.38996434211731,1.1528674447195582 +1739137695.7084959,37.40996432304382,43.75037518860606,1739137695.7084987,37.40996432304382,6.941035835137775,1739137695.7085016,37.40996432304382,64.36313234274549,1739137695.7085044,37.40996432304382,42.59407907627963,1739137695.7085056,37.40996432304382,2.3768959243316004,1739137695.7085073,37.40996432304382,-1.8189195214664078,1739137695.708509,37.40996432304382,1.5161583058046877,1739137695.7085102,37.40996432304382,0.6108,1739137695.7085116,37.40996432304382,1.3631898202866162,1739137695.7085133,37.40996432304382,0.0,1739137695.7085142,37.40996432304382,0.21032237556705802,1739137695.708516,37.40996432304382,4.13640765418927,1739137695.708517,37.40996432304382,1.1528674447195582 +1739137695.7286584,37.42996430397034,43.75037518860606,1739137695.7286608,37.42996430397034,6.941035835137775,1739137695.728664,37.42996430397034,64.36313234274549,1739137695.7286665,37.42996430397034,42.59407907627963,1739137695.728668,37.42996430397034,2.3768959243316004,1739137695.7286694,37.42996430397034,-1.8189195214664078,1739137695.728671,37.42996430397034,1.5161583058046877,1739137695.7286723,37.42996430397034,0.6108,1739137695.7286735,37.42996430397034,1.3631898202866162,1739137695.7286751,37.42996430397034,0.0,1739137695.7286763,37.42996430397034,0.21032237556705802,1739137695.728678,37.42996430397034,4.13640765418927,1739137695.7286792,37.42996430397034,1.1528674447195582 +1739137695.7486916,37.44996428489685,43.75037518860606,1739137695.748694,37.44996428489685,6.941035835137775,1739137695.7486973,37.44996428489685,64.36313234274549,1739137695.7487001,37.44996428489685,42.59407907627963,1739137695.7487013,37.44996428489685,2.3768959243316004,1739137695.7487032,37.44996428489685,-1.8189195214664078,1739137695.7487047,37.44996428489685,1.5161583058046877,1739137695.748706,37.44996428489685,0.6108,1739137695.7487073,37.44996428489685,1.3631898202866162,1739137695.7487092,37.44996428489685,0.0,1739137695.7487106,37.44996428489685,0.21032237556705802,1739137695.7487123,37.44996428489685,4.13640765418927,1739137695.7487135,37.44996428489685,1.1528674447195582 +1739137695.7697077,37.469964265823364,43.68200826540329,1739137695.7697113,37.469964265823364,6.832805305783586,1739137695.7697163,37.469964265823364,64.44375971170118,1739137695.7697215,37.469964265823364,42.527912795915455,1739137695.7697246,37.469964265823364,2.240825591830914,1739137695.7697287,37.469964265823364,-1.8170249711420883,1739137695.7697322,37.469964265823364,1.4089358631171096,1739137695.769736,37.469964265823364,0.6108,1739137695.7697396,37.469964265823364,1.422927524926068,1739137695.7697432,37.469964265823364,0.0,1739137695.7697468,37.469964265823364,0.27936893070118646,1739137695.7697504,37.469964265823364,4.16401286839019,1739137695.769754,37.469964265823364,1.1764379226181751 +1739137695.7886817,37.48996424674988,43.68200826540329,1739137695.7886844,37.48996424674988,6.832805305783586,1739137695.7886875,37.48996424674988,64.44375971170118,1739137695.7886903,37.48996424674988,42.527912795915455,1739137695.7886922,37.48996424674988,2.240825591830914,1739137695.788694,37.48996424674988,-1.8170249711420883,1739137695.7886953,37.48996424674988,1.4089358631171096,1739137695.7886968,37.48996424674988,0.6108,1739137695.7886982,37.48996424674988,1.422927524926068,1739137695.7886996,37.48996424674988,0.0,1739137695.7887008,37.48996424674988,0.24648960230789285,1739137695.7887025,37.48996424674988,4.16401286839019,1739137695.788704,37.48996424674988,1.1764379226181751 +1739137695.8087711,37.50996422767639,43.68200826540329,1739137695.808774,37.50996422767639,6.832805305783586,1739137695.8087769,37.50996422767639,64.44375971170118,1739137695.8087797,37.50996422767639,42.527912795915455,1739137695.8087814,37.50996422767639,2.240825591830914,1739137695.808783,37.50996422767639,-1.8170249711420883,1739137695.8087847,37.50996422767639,1.4089358631171096,1739137695.8087857,37.50996422767639,0.6108,1739137695.808787,37.50996422767639,1.422927524926068,1739137695.8087888,37.50996422767639,0.0,1739137695.80879,37.50996422767639,0.24648960230789285,1739137695.8087916,37.50996422767639,4.16401286839019,1739137695.808793,37.50996422767639,1.1764379226181751 +1739137695.8293679,37.529964208602905,43.68200826540329,1739137695.8293703,37.529964208602905,6.832805305783586,1739137695.8293731,37.529964208602905,64.44375971170118,1739137695.8293762,37.529964208602905,42.527912795915455,1739137695.8293777,37.529964208602905,2.240825591830914,1739137695.8293793,37.529964208602905,-1.8170249711420883,1739137695.8293808,37.529964208602905,1.4089358631171096,1739137695.8293822,37.529964208602905,0.6108,1739137695.8293834,37.529964208602905,1.422927524926068,1739137695.829385,37.529964208602905,0.0,1739137695.8293865,37.529964208602905,0.24648960230789285,1739137695.8293884,37.529964208602905,4.16401286839019,1739137695.8293896,37.529964208602905,1.1764379226181751 +1739137695.848661,37.54996418952942,43.68200826540329,1739137695.8486636,37.54996418952942,6.832805305783586,1739137695.848667,37.54996418952942,64.44375971170118,1739137695.8486698,37.54996418952942,42.527912795915455,1739137695.8486712,37.54996418952942,2.240825591830914,1739137695.848673,37.54996418952942,-1.8170249711420883,1739137695.8486743,37.54996418952942,1.4089358631171096,1739137695.8486757,37.54996418952942,0.6108,1739137695.8486772,37.54996418952942,1.422927524926068,1739137695.8486788,37.54996418952942,0.0,1739137695.8486803,37.54996418952942,0.24648960230789285,1739137695.848682,37.54996418952942,4.16401286839019,1739137695.8486834,37.54996418952942,1.1764379226181751 +1739137695.8690453,37.56996417045593,43.61524672165738,1739137695.869048,37.56996417045593,6.720355649185233,1739137695.869051,37.56996417045593,64.59427661232252,1739137695.8690536,37.56996417045593,42.416408575249136,1739137695.869055,37.56996417045593,2.0369784481576043,1739137695.8690567,37.56996417045593,-1.8213927030264088,1739137695.8690584,37.56996417045593,1.2902943761075727,1739137695.8690596,37.56996417045593,0.6108,1739137695.8690608,37.56996417045593,1.492082777933363,1739137695.8690627,37.56996417045593,0.0,1739137695.8690639,37.56996417045593,0.3264114032822531,1739137695.8690655,37.56996417045593,4.191618082591109,1739137695.8690667,37.56996417045593,1.2037293941267344 +1739137695.8884988,37.589964151382446,43.61524672165738,1739137695.8885007,37.589964151382446,6.720355649185233,1739137695.8885036,37.589964151382446,64.59427661232252,1739137695.888506,37.589964151382446,42.416408575249136,1739137695.8885071,37.589964151382446,2.0369784481576043,1739137695.8885083,37.589964151382446,-1.8213927030264088,1739137695.8885098,37.589964151382446,1.2902943761075727,1739137695.888511,37.589964151382446,0.6108,1739137695.888512,37.589964151382446,1.492082777933363,1739137695.8885136,37.589964151382446,0.0,1739137695.8885148,37.589964151382446,0.28835338380662856,1739137695.888516,37.589964151382446,4.191618082591109,1739137695.8885171,37.589964151382446,1.2037293941267344 +1739137695.9091043,37.60996413230896,43.61524672165738,1739137695.9091077,37.60996413230896,6.720355649185233,1739137695.9091117,37.60996413230896,64.59427661232252,1739137695.909115,37.60996413230896,42.416408575249136,1739137695.909117,37.60996413230896,2.0369784481576043,1739137695.9091191,37.60996413230896,-1.8213927030264088,1739137695.909121,37.60996413230896,1.2902943761075727,1739137695.9091225,37.60996413230896,0.6108,1739137695.9091241,37.60996413230896,1.492082777933363,1739137695.9091258,37.60996413230896,0.0,1739137695.9091277,37.60996413230896,0.28835338380662856,1739137695.9091294,37.60996413230896,4.191618082591109,1739137695.909131,37.60996413230896,1.2037293941267344 +1739137695.9293904,37.629964113235474,43.61524672165738,1739137695.9293933,37.629964113235474,6.720355649185233,1739137695.9293964,37.629964113235474,64.59427661232252,1739137695.9294,37.629964113235474,42.416408575249136,1739137695.9294016,37.629964113235474,2.0369784481576043,1739137695.9294033,37.629964113235474,-1.8213927030264088,1739137695.9294052,37.629964113235474,1.2902943761075727,1739137695.9294066,37.629964113235474,0.6108,1739137695.9294083,37.629964113235474,1.492082777933363,1739137695.92941,37.629964113235474,0.0,1739137695.9294116,37.629964113235474,0.28835338380662856,1739137695.9294133,37.629964113235474,4.191618082591109,1739137695.929415,37.629964113235474,1.2037293941267344 +1739137695.9490278,37.64996409416199,43.61524672165738,1739137695.9490309,37.64996409416199,6.720355649185233,1739137695.949035,37.64996409416199,64.59427661232252,1739137695.9490383,37.64996409416199,42.416408575249136,1739137695.9490402,37.64996409416199,2.0369784481576043,1739137695.949042,37.64996409416199,-1.8213927030264088,1739137695.9490442,37.64996409416199,1.2902943761075727,1739137695.9490461,37.64996409416199,0.6108,1739137695.9490476,37.64996409416199,1.492082777933363,1739137695.9490497,37.64996409416199,0.0,1739137695.9490511,37.64996409416199,0.28835338380662856,1739137695.9490528,37.64996409416199,4.191618082591109,1739137695.949055,37.64996409416199,1.2037293941267344 +1739137695.9691272,37.6699640750885,43.61524672165738,1739137695.96913,37.6699640750885,6.720355649185233,1739137695.9691334,37.6699640750885,64.59427661232252,1739137695.9691367,37.6699640750885,42.416408575249136,1739137695.9691381,37.6699640750885,2.0369784481576043,1739137695.9691403,37.6699640750885,-1.8213927030264088,1739137695.9691417,37.6699640750885,1.2902943761075727,1739137695.9691434,37.6699640750885,0.6108,1739137695.9691448,37.6699640750885,1.492082777933363,1739137695.9691467,37.6699640750885,0.0,1739137695.9691482,37.6699640750885,0.28835338380662856,1739137695.96915,37.6699640750885,4.191618082591109,1739137695.9691515,37.6699640750885,1.2037293941267344 +1739137695.989359,37.689964056015015,43.55001648116723,1739137695.9893618,37.689964056015015,6.603235042445094,1739137695.9893653,37.689964056015015,64.74359315192883,1739137695.9893687,37.689964056015015,42.285789124992064,1739137695.9893706,37.689964056015015,1.828109246416562,1739137695.9893725,37.689964056015015,-1.8296109523917552,1739137695.9893742,37.689964056015015,1.1470441151430786,1739137695.9893758,37.689964056015015,0.6108,1739137695.9893773,37.689964056015015,1.5800762191076596,1739137695.9893794,37.689964056015015,0.0,1739137695.9893808,37.689964056015015,0.3945682013141659,1739137695.9893827,37.689964056015015,4.219223296792029,1739137695.9893842,37.689964056015015,1.2360865275870678 +1739137696.0093288,37.70996403694153,43.55001648116723,1739137696.0093322,37.70996403694153,6.603235042445094,1739137696.0093355,37.70996403694153,64.74359315192883,1739137696.0093393,37.70996403694153,42.285789124992064,1739137696.009341,37.70996403694153,1.828109246416562,1739137696.0093431,37.70996403694153,-1.8296109523917552,1739137696.0093453,37.70996403694153,1.1470441151430786,1739137696.0093467,37.70996403694153,0.6108,1739137696.0093486,37.70996403694153,1.5800762191076596,1739137696.0093505,37.70996403694153,0.0,1739137696.0093524,37.70996403694153,0.3439896915205918,1739137696.0093546,37.70996403694153,4.219223296792029,1739137696.0093563,37.70996403694153,1.2360865275870678 +1739137696.0290742,37.72996401786804,43.55001648116723,1739137696.029077,37.72996401786804,6.603235042445094,1739137696.0290804,37.72996401786804,64.74359315192883,1739137696.0290837,37.72996401786804,42.285789124992064,1739137696.0290852,37.72996401786804,1.828109246416562,1739137696.0290873,37.72996401786804,-1.8296109523917552,1739137696.029089,37.72996401786804,1.1470441151430786,1739137696.0290906,37.72996401786804,0.6108,1739137696.029092,37.72996401786804,1.5800762191076596,1739137696.029094,37.72996401786804,0.0,1739137696.0290954,37.72996401786804,0.3439896915205918,1739137696.0290973,37.72996401786804,4.219223296792029,1739137696.0290987,37.72996401786804,1.2360865275870678 +1739137696.049057,37.749963998794556,43.55001648116723,1739137696.0490603,37.749963998794556,6.603235042445094,1739137696.0490642,37.749963998794556,64.74359315192883,1739137696.0490675,37.749963998794556,42.285789124992064,1739137696.0490692,37.749963998794556,1.828109246416562,1739137696.0490713,37.749963998794556,-1.8296109523917552,1739137696.049073,37.749963998794556,1.1470441151430786,1739137696.0490746,37.749963998794556,0.6108,1739137696.0490763,37.749963998794556,1.5800762191076596,1739137696.049078,37.749963998794556,0.0,1739137696.0490797,37.749963998794556,0.3439896915205918,1739137696.0490813,37.749963998794556,4.219223296792029,1739137696.0490832,37.749963998794556,1.2360865275870678 +1739137696.0689108,37.76996397972107,43.55001648116723,1739137696.0689137,37.76996397972107,6.603235042445094,1739137696.068917,37.76996397972107,64.74359315192883,1739137696.0689204,37.76996397972107,42.285789124992064,1739137696.068922,37.76996397972107,1.828109246416562,1739137696.068924,37.76996397972107,-1.8296109523917552,1739137696.0689256,37.76996397972107,1.1470441151430786,1739137696.0689273,37.76996397972107,0.6108,1739137696.0689287,37.76996397972107,1.5800762191076596,1739137696.0689306,37.76996397972107,0.0,1739137696.068932,37.76996397972107,0.3439896915205918,1739137696.068934,37.76996397972107,4.219223296792029,1739137696.0689354,37.76996397972107,1.2360865275870678 +1739137696.0889845,37.78996396064758,43.4862790249021,1739137696.088987,37.78996396064758,6.480970399191964,1739137696.0889907,37.78996396064758,64.82099169091784,1739137696.088994,37.78996396064758,42.17717339385063,1739137696.088996,37.78996396064758,1.6700862128130598,1739137696.0889978,37.78996396064758,-1.8364768314581856,1739137696.0889997,37.78996396064758,0.9899422370816398,1739137696.0890012,37.78996396064758,0.6034147311075049,1739137696.0890028,37.78996396064758,1.6825556151234076,1739137696.0890045,37.78996396064758,0.0,1739137696.0890062,37.78996396064758,0.46684547560036654,1739137696.0890079,37.78996396064758,4.246828510992948,1739137696.0890095,37.78996396064758,1.2742129230714396 +1739137696.1089785,37.8099639415741,43.4862790249021,1739137696.1089816,37.8099639415741,6.480970399191964,1739137696.1089852,37.8099639415741,64.82099169091784,1739137696.1089885,37.8099639415741,42.17717339385063,1739137696.10899,37.8099639415741,1.6700862128130598,1739137696.1089923,37.8099639415741,-1.8364768314581856,1739137696.108994,37.8099639415741,0.9899422370816398,1739137696.1089957,37.8099639415741,0.6034147311075049,1739137696.1089973,37.8099639415741,1.6825556151234076,1739137696.1089993,37.8099639415741,0.0,1739137696.1090007,37.8099639415741,0.40834269205196794,1739137696.1090026,37.8099639415741,4.246828510992948,1739137696.1090043,37.8099639415741,1.2742129230714396 +1739137696.1311412,37.82996392250061,43.4862790249021,1739137696.131144,37.82996392250061,6.480970399191964,1739137696.131147,37.82996392250061,64.82099169091784,1739137696.1311502,37.82996392250061,42.17717339385063,1739137696.131152,37.82996392250061,1.6700862128130598,1739137696.1311536,37.82996392250061,-1.8364768314581856,1739137696.1311555,37.82996392250061,0.9899422370816398,1739137696.131157,37.82996392250061,0.6034147311075049,1739137696.1311586,37.82996392250061,1.6825556151234076,1739137696.1311605,37.82996392250061,0.0,1739137696.1311622,37.82996392250061,0.40834269205196794,1739137696.1311638,37.82996392250061,4.246828510992948,1739137696.1311655,37.82996392250061,1.2742129230714396 +1739137696.1492772,37.849963903427124,43.4862790249021,1739137696.1492808,37.849963903427124,6.480970399191964,1739137696.1492844,37.849963903427124,64.82099169091784,1739137696.149288,37.849963903427124,42.17717339385063,1739137696.1492898,37.849963903427124,1.6700862128130598,1739137696.149292,37.849963903427124,-1.8364768314581856,1739137696.149294,37.849963903427124,0.9899422370816398,1739137696.1492953,37.849963903427124,0.6034147311075049,1739137696.1492972,37.849963903427124,1.6825556151234076,1739137696.1492991,37.849963903427124,0.0,1739137696.1493008,37.849963903427124,0.40834269205196794,1739137696.1493025,37.849963903427124,4.246828510992948,1739137696.1493042,37.849963903427124,1.2742129230714396 +1739137696.17118,37.86996388435364,43.4862790249021,1739137696.1711829,37.86996388435364,6.480970399191964,1739137696.1711862,37.86996388435364,64.82099169091784,1739137696.1711898,37.86996388435364,42.17717339385063,1739137696.1711912,37.86996388435364,1.6700862128130598,1739137696.1711934,37.86996388435364,-1.8364768314581856,1739137696.171195,37.86996388435364,0.9899422370816398,1739137696.1711972,37.86996388435364,0.6034147311075049,1739137696.1711986,37.86996388435364,1.6825556151234076,1739137696.1712005,37.86996388435364,0.0,1739137696.171202,37.86996388435364,0.40834269205196794,1739137696.1712039,37.86996388435364,4.246828510992948,1739137696.1712053,37.86996388435364,1.2742129230714396 +1739137696.189005,37.88996386528015,43.4862790249021,1739137696.1890085,37.88996386528015,6.480970399191964,1739137696.1890123,37.88996386528015,64.82099169091784,1739137696.1890156,37.88996386528015,42.17717339385063,1739137696.1890173,37.88996386528015,1.6700862128130598,1739137696.1890194,37.88996386528015,-1.8364768314581856,1739137696.189021,37.88996386528015,0.9899422370816398,1739137696.1890228,37.88996386528015,0.6034147311075049,1739137696.1890242,37.88996386528015,1.6825556151234076,1739137696.189026,37.88996386528015,0.0,1739137696.1890278,37.88996386528015,0.40834269205196794,1739137696.1890297,37.88996386528015,4.246828510992948,1739137696.1890311,37.88996386528015,1.2742129230714396 +1739137696.2092094,37.909963846206665,43.423915831855034,1739137696.2092123,37.909963846206665,6.352829532254258,1739137696.2092164,37.909963846206665,65.03327074399219,1739137696.2092197,37.909963846206665,41.958998308647836,1739137696.2092214,37.909963846206665,1.3967054194585442,1739137696.2092235,37.909963846206665,-1.858190627276703,1739137696.2092252,37.909963846206665,0.7751760395793792,1739137696.209227,37.909963846206665,0.4425528170177303,1739137696.2092285,37.909963846206665,1.8334882794128402,1739137696.2092307,37.909963846206665,0.0,1739137696.209232,37.909963846206665,0.6088414517176155,1739137696.2092342,37.909963846206665,4.274433725193868,1739137696.209236,37.909963846206665,1.3201224752302665 +1739137696.2293825,37.92996382713318,43.423915831855034,1739137696.229385,37.92996382713318,6.352829532254258,1739137696.2293882,37.92996382713318,65.03327074399219,1739137696.2293916,37.92996382713318,41.958998308647836,1739137696.2293932,37.92996382713318,1.3967054194585442,1739137696.229395,37.92996382713318,-1.858190627276703,1739137696.229397,37.92996382713318,0.7751760395793792,1739137696.2293985,37.92996382713318,0.4425528170177303,1739137696.2294002,37.92996382713318,1.8334882794128402,1739137696.2294018,37.92996382713318,0.0,1739137696.2294035,37.92996382713318,0.5133658041825737,1739137696.2294052,37.92996382713318,4.274433725193868,1739137696.2294068,37.92996382713318,1.3201224752302665 +1739137696.2492576,37.94996380805969,43.423915831855034,1739137696.249261,37.94996380805969,6.352829532254258,1739137696.2492647,37.94996380805969,65.03327074399219,1739137696.249268,37.94996380805969,41.958998308647836,1739137696.2492695,37.94996380805969,1.3967054194585442,1739137696.2492719,37.94996380805969,-1.858190627276703,1739137696.2492738,37.94996380805969,0.7751760395793792,1739137696.2492754,37.94996380805969,0.4425528170177303,1739137696.2492769,37.94996380805969,1.8334882794128402,1739137696.249279,37.94996380805969,0.0,1739137696.2492805,37.94996380805969,0.5133658041825737,1739137696.2492824,37.94996380805969,4.274433725193868,1739137696.249284,37.94996380805969,1.3201224752302665 +1739137696.271193,37.969963788986206,43.423915831855034,1739137696.2711961,37.969963788986206,6.352829532254258,1739137696.2711995,37.969963788986206,65.03327074399219,1739137696.2712028,37.969963788986206,41.958998308647836,1739137696.2712047,37.969963788986206,1.3967054194585442,1739137696.2712064,37.969963788986206,-1.858190627276703,1739137696.271208,37.969963788986206,0.7751760395793792,1739137696.2712097,37.969963788986206,0.4425528170177303,1739137696.271211,37.969963788986206,1.8334882794128402,1739137696.271213,37.969963788986206,0.0,1739137696.2712145,37.969963788986206,0.5133658041825737,1739137696.2712164,37.969963788986206,4.274433725193868,1739137696.2712178,37.969963788986206,1.3201224752302665 +1739137696.2920954,37.98996376991272,43.423915831855034,1739137696.2921,37.98996376991272,6.352829532254258,1739137696.2921054,37.98996376991272,65.03327074399219,1739137696.2921119,37.98996376991272,41.958998308647836,1739137696.2921154,37.98996376991272,1.3967054194585442,1739137696.29212,37.98996376991272,-1.858190627276703,1739137696.2921245,37.98996376991272,0.7751760395793792,1739137696.2921288,37.98996376991272,0.4425528170177303,1739137696.2921329,37.98996376991272,1.8334882794128402,1739137696.2921374,37.98996376991272,0.0,1739137696.2921417,37.98996376991272,0.5133658041825737,1739137696.2921462,37.98996376991272,4.274433725193868,1739137696.2921503,37.98996376991272,1.3201224752302665 +1739137696.3092325,38.00996375083923,43.36279764121877,1739137696.309236,38.00996375083923,6.217951179359467,1739137696.3092396,38.00996375083923,65.1109729030537,1739137696.3092434,38.00996375083923,41.786426844156566,1739137696.309245,38.00996375083923,1.2174268441565663,1739137696.3092475,38.00996375083923,-1.8761764735244513,1739137696.3092492,38.00996375083923,0.5525119923290986,1739137696.3092508,38.00996375083923,0.3076303892382903,1739137696.309253,38.00996375083923,2.004282086298274,1739137696.309255,38.00996375083923,0.0,1739137696.3092566,38.00996375083923,0.7304668337515235,1739137696.3092585,38.00996375083923,4.3014341167196015,1739137696.3092604,38.00996375083923,1.3771967468422046 +1739137696.3290854,38.02996373176575,43.36279764121877,1739137696.329088,38.02996373176575,6.217951179359467,1739137696.3290915,38.02996373176575,65.1109729030537,1739137696.329095,38.02996373176575,41.786426844156566,1739137696.3290966,38.02996373176575,1.2174268441565663,1739137696.3290985,38.02996373176575,-1.8761764735244513,1739137696.3291004,38.02996373176575,0.5525119923290986,1739137696.3291018,38.02996373176575,0.3076303892382903,1739137696.3291035,38.02996373176575,2.004282086298274,1739137696.3291051,38.02996373176575,0.0,1739137696.3291066,38.02996373176575,0.6270853394560696,1739137696.3291082,38.02996373176575,4.3014341167196015,1739137696.32911,38.02996373176575,1.3771967468422046 +1739137696.349093,38.04996371269226,43.36279764121877,1739137696.3490958,38.04996371269226,6.217951179359467,1739137696.3490999,38.04996371269226,65.1109729030537,1739137696.3491032,38.04996371269226,41.786426844156566,1739137696.349105,38.04996371269226,1.2174268441565663,1739137696.3491068,38.04996371269226,-1.8761764735244513,1739137696.3491085,38.04996371269226,0.5525119923290986,1739137696.3491104,38.04996371269226,0.3076303892382903,1739137696.3491118,38.04996371269226,2.004282086298274,1739137696.349114,38.04996371269226,0.0,1739137696.3491154,38.04996371269226,0.6270853394560696,1739137696.3491173,38.04996371269226,4.3014341167196015,1739137696.349119,38.04996371269226,1.3771967468422046 +1739137696.369249,38.069963693618774,43.36279764121877,1739137696.3692522,38.069963693618774,6.217951179359467,1739137696.3692555,38.069963693618774,65.1109729030537,1739137696.3692586,38.069963693618774,41.786426844156566,1739137696.3692605,38.069963693618774,1.2174268441565663,1739137696.3692622,38.069963693618774,-1.8761764735244513,1739137696.3692641,38.069963693618774,0.5525119923290986,1739137696.369266,38.069963693618774,0.3076303892382903,1739137696.3692675,38.069963693618774,2.004282086298274,1739137696.3692691,38.069963693618774,0.0,1739137696.3692708,38.069963693618774,0.6270853394560696,1739137696.3692725,38.069963693618774,4.3014341167196015,1739137696.3692741,38.069963693618774,1.3771967468422046 +1739137696.3890858,38.08996367454529,43.36279764121877,1739137696.3890886,38.08996367454529,6.217951179359467,1739137696.3890915,38.08996367454529,65.1109729030537,1739137696.3890946,38.08996367454529,41.786426844156566,1739137696.3890965,38.08996367454529,1.2174268441565663,1739137696.3890984,38.08996367454529,-1.8761764735244513,1739137696.3891003,38.08996367454529,0.5525119923290986,1739137696.3891017,38.08996367454529,0.3076303892382903,1739137696.3891034,38.08996367454529,2.004282086298274,1739137696.389105,38.08996367454529,0.0,1739137696.3891068,38.08996367454529,0.6270853394560696,1739137696.3891082,38.08996367454529,4.3014341167196015,1739137696.3891098,38.08996367454529,1.3771967468422046 +1739137696.4087787,38.1099636554718,43.36279764121877,1739137696.4087815,38.1099636554718,6.217951179359467,1739137696.4087849,38.1099636554718,65.1109729030537,1739137696.4087882,38.1099636554718,41.786426844156566,1739137696.4087899,38.1099636554718,1.2174268441565663,1739137696.4087918,38.1099636554718,-1.8761764735244513,1739137696.4087934,38.1099636554718,0.5525119923290986,1739137696.4087949,38.1099636554718,0.3076303892382903,1739137696.4087968,38.1099636554718,2.004282086298274,1739137696.4087982,38.1099636554718,0.0,1739137696.4087996,38.1099636554718,0.6270853394560696,1739137696.4088018,38.1099636554718,4.3014341167196015,1739137696.4088032,38.1099636554718,1.3771967468422046 +1739137696.4290042,38.129963636398315,43.30251120300159,1739137696.4290068,38.129963636398315,6.075020951453027,1739137696.4290104,38.129963636398315,65.1991693736,1739137696.4290135,38.129963636398315,41.56261254736442,1739137696.429015,38.129963636398315,1.0171375387527035,1739137696.429017,38.129963636398315,-1.9021136266862149,1739137696.429019,38.129963636398315,0.28950902398750233,1739137696.4290204,38.129963636398315,0.15529444898633166,1739137696.4290216,38.129963636398315,2.226625303151991,1739137696.4290237,38.129963636398315,0.0,1739137696.4290252,38.129963636398315,0.9164651916802472,1739137696.4290268,38.129963636398315,4.326919023418368,1739137696.4290283,38.129963636398315,1.4479601099394241 +1739137696.4494054,38.14996361732483,43.30251120300159,1739137696.4494083,38.14996361732483,6.075020951453027,1739137696.4494114,38.14996361732483,65.1991693736,1739137696.4494145,38.14996361732483,41.56261254736442,1739137696.4494162,38.14996361732483,1.0171375387527035,1739137696.4494185,38.14996361732483,-1.9021136266862149,1739137696.4494202,38.14996361732483,0.28950902398750233,1739137696.449422,38.14996361732483,0.15529444898633166,1739137696.4494233,38.14996361732483,2.226625303151991,1739137696.4494252,38.14996361732483,0.0,1739137696.4494267,38.14996361732483,0.7786651932125668,1739137696.4494286,38.14996361732483,4.326919023418368,1739137696.4494302,38.14996361732483,1.4479601099394241 +1739137696.4695058,38.16996359825134,43.30251120300159,1739137696.469509,38.16996359825134,6.075020951453027,1739137696.4695122,38.16996359825134,65.1991693736,1739137696.4695156,38.16996359825134,41.56261254736442,1739137696.4695172,38.16996359825134,1.0171375387527035,1739137696.4695194,38.16996359825134,-1.9021136266862149,1739137696.4695208,38.16996359825134,0.28950902398750233,1739137696.4695225,38.16996359825134,0.15529444898633166,1739137696.469524,38.16996359825134,2.226625303151991,1739137696.4695265,38.16996359825134,0.0,1739137696.469528,38.16996359825134,0.7786651932125668,1739137696.4695299,38.16996359825134,4.326919023418368,1739137696.4695313,38.16996359825134,1.4479601099394241 +1739137696.488952,38.189963579177856,43.30251120300159,1739137696.4889543,38.189963579177856,6.075020951453027,1739137696.4889576,38.189963579177856,65.1991693736,1739137696.4889607,38.189963579177856,41.56261254736442,1739137696.4889624,38.189963579177856,1.0171375387527035,1739137696.4889643,38.189963579177856,-1.9021136266862149,1739137696.4889662,38.189963579177856,0.28950902398750233,1739137696.4889677,38.189963579177856,0.15529444898633166,1739137696.4889693,38.189963579177856,2.226625303151991,1739137696.4889708,38.189963579177856,0.0,1739137696.4889724,38.189963579177856,0.7786651932125668,1739137696.4889743,38.189963579177856,4.326919023418368,1739137696.4889758,38.189963579177856,1.4479601099394241 +1739137696.5096405,38.20996356010437,43.30251120300159,1739137696.5096438,38.20996356010437,6.075020951453027,1739137696.5096476,38.20996356010437,65.1991693736,1739137696.509651,38.20996356010437,41.56261254736442,1739137696.509653,38.20996356010437,1.0171375387527035,1739137696.509655,38.20996356010437,-1.9021136266862149,1739137696.509657,38.20996356010437,0.28950902398750233,1739137696.5096583,38.20996356010437,0.15529444898633166,1739137696.50966,38.20996356010437,2.226625303151991,1739137696.5096626,38.20996356010437,0.0,1739137696.5096645,38.20996356010437,0.7786651932125668,1739137696.5096662,38.20996356010437,4.326919023418368,1739137696.5096684,38.20996356010437,1.4479601099394241 +1739137696.5296965,38.229963541030884,43.24269084143972,1739137696.5296993,38.229963541030884,5.92272714803379,1739137696.5297027,38.229963541030884,65.3937015644763,1739137696.529706,38.229963541030884,41.194889608174286,1739137696.5297077,38.229963541030884,0.7514053474991282,1739137696.5297098,38.229963541030884,-1.9478426247988845,1739137696.5297112,38.229963541030884,-0.08735148064255081,1739137696.529713,38.229963541030884,-0.04336768552192055,1739137696.5297143,38.229963541030884,2.4141569559998373,1739137696.5297163,38.229963541030884,0.0,1739137696.5297177,38.229963541030884,0.9715588731663853,1739137696.5297196,38.229963541030884,4.351048322121599,1739137696.529721,38.229963541030884,1.5344522620299696 +1739137696.5516858,38.2499635219574,43.24269084143972,1739137696.5516903,38.2499635219574,5.92272714803379,1739137696.5516958,38.2499635219574,65.3937015644763,1739137696.5517023,38.2499635219574,41.194889608174286,1739137696.551706,38.2499635219574,0.7514053474991282,1739137696.5517106,38.2499635219574,-1.9478426247988845,1739137696.5517151,38.2499635219574,-0.08735148064255081,1739137696.5517194,38.2499635219574,-0.04336768552192055,1739137696.5517237,38.2499635219574,2.4141569559998373,1739137696.551728,38.2499635219574,0.0,1739137696.5517323,38.2499635219574,0.8797046939698676,1739137696.5517366,38.2499635219574,4.351048322121599,1739137696.551741,38.2499635219574,1.5344522620299696 +1739137696.571384,38.26996350288391,43.24269084143972,1739137696.5713873,38.26996350288391,5.92272714803379,1739137696.5713916,38.26996350288391,65.3937015644763,1739137696.571396,38.26996350288391,41.194889608174286,1739137696.571399,38.26996350288391,0.7514053474991282,1739137696.5714023,38.26996350288391,-1.9478426247988845,1739137696.5714054,38.26996350288391,-0.08735148064255081,1739137696.5714083,38.26996350288391,-0.04336768552192055,1739137696.5714111,38.26996350288391,2.4141569559998373,1739137696.5714145,38.26996350288391,0.0,1739137696.5714173,38.26996350288391,0.8797046939698676,1739137696.5714207,38.26996350288391,4.351048322121599,1739137696.5714238,38.26996350288391,1.5344522620299696 +1739137696.588418,38.289963483810425,43.24269084143972,1739137696.5884206,38.289963483810425,5.92272714803379,1739137696.5884235,38.289963483810425,65.3937015644763,1739137696.5884259,38.289963483810425,41.194889608174286,1739137696.5884273,38.289963483810425,0.7514053474991282,1739137696.5884287,38.289963483810425,-1.9478426247988845,1739137696.5884302,38.289963483810425,-0.08735148064255081,1739137696.5884314,38.289963483810425,-0.04336768552192055,1739137696.5884328,38.289963483810425,2.4141569559998373,1739137696.5884345,38.289963483810425,0.0,1739137696.5884356,38.289963483810425,0.8797046939698676,1739137696.5884373,38.289963483810425,4.351048322121599,1739137696.5884385,38.289963483810425,1.5344522620299696 +1739137696.6084416,38.30996346473694,43.24269084143972,1739137696.6084442,38.30996346473694,5.92272714803379,1739137696.608447,38.30996346473694,65.3937015644763,1739137696.6084495,38.30996346473694,41.194889608174286,1739137696.608451,38.30996346473694,0.7514053474991282,1739137696.6084523,38.30996346473694,-1.9478426247988845,1739137696.608454,38.30996346473694,-0.08735148064255081,1739137696.6084552,38.30996346473694,-0.04336768552192055,1739137696.6084561,38.30996346473694,2.4141569559998373,1739137696.608458,38.30996346473694,0.0,1739137696.6084592,38.30996346473694,0.8797046939698676,1739137696.608461,38.30996346473694,4.351048322121599,1739137696.608462,38.30996346473694,1.5344522620299696 +1739137696.6310682,38.32996344566345,43.24269084143972,1739137696.6310706,38.32996344566345,5.92272714803379,1739137696.631074,38.32996344566345,65.3937015644763,1739137696.6310773,38.32996344566345,41.194889608174286,1739137696.631079,38.32996344566345,0.7514053474991282,1739137696.6310806,38.32996344566345,-1.9478426247988845,1739137696.6310825,38.32996344566345,-0.08735148064255081,1739137696.631084,38.32996344566345,-0.04336768552192055,1739137696.6310854,38.32996344566345,2.4141569559998373,1739137696.6310868,38.32996344566345,0.0,1739137696.6310885,38.32996344566345,0.8797046939698676,1739137696.6310902,38.32996344566345,4.351048322121599,1739137696.6310916,38.32996344566345,1.5344522620299696 +1739137696.64903,38.349963426589966,43.18298432213589,1739137696.6490333,38.349963426589966,5.7595190654755815,1739137696.649037,38.349963426589966,65.54585226812333,1739137696.64904,38.349963426589966,40.80331420576446,1739137696.6490417,38.349963426589966,0.5371084285946558,1739137696.6490438,38.349963426589966,-1.998351330197225,1739137696.6490455,38.349963426589966,-0.5109038078628436,1739137696.6490471,38.349963426589966,-0.23776260752300496,1739137696.6490488,38.349963426589966,2.037919039874376,1739137696.6490507,38.349963426589966,0.0,1739137696.6490521,38.349963426589966,-0.026036955219810698,1739137696.6490538,38.349963426589966,4.373974743868513,1739137696.6490552,38.349963426589966,1.6326502324049343 +1739137696.6691225,38.36996340751648,43.18298432213589,1739137696.6691253,38.36996340751648,5.7595190654755815,1739137696.6691282,38.36996340751648,65.54585226812333,1739137696.6691315,38.36996340751648,40.80331420576446,1739137696.669133,38.36996340751648,0.5371084285946558,1739137696.6691349,38.36996340751648,-1.998351330197225,1739137696.6691365,38.36996340751648,-0.5109038078628436,1739137696.6691382,38.36996340751648,-0.23776260752300496,1739137696.6691394,38.36996340751648,2.037919039874376,1739137696.6691413,38.36996340751648,0.0,1739137696.6691425,38.36996340751648,0.4052688074694415,1739137696.6691444,38.36996340751648,4.373974743868513,1739137696.6691456,38.36996340751648,1.6326502324049343 +1739137696.689065,38.38996338844299,43.18298432213589,1739137696.6890678,38.38996338844299,5.7595190654755815,1739137696.6890712,38.38996338844299,65.54585226812333,1739137696.6890743,38.38996338844299,40.80331420576446,1739137696.6890757,38.38996338844299,0.5371084285946558,1739137696.6890779,38.38996338844299,-1.998351330197225,1739137696.6890793,38.38996338844299,-0.5109038078628436,1739137696.6890807,38.38996338844299,-0.23776260752300496,1739137696.6890824,38.38996338844299,2.037919039874376,1739137696.689084,38.38996338844299,0.0,1739137696.6890855,38.38996338844299,0.4052688074694415,1739137696.6890872,38.38996338844299,4.373974743868513,1739137696.6890886,38.38996338844299,1.6326502324049343 +1739137696.7087722,38.40996336936951,43.18298432213589,1739137696.7087755,38.40996336936951,5.7595190654755815,1739137696.7087789,38.40996336936951,65.54585226812333,1739137696.7087822,38.40996336936951,40.80331420576446,1739137696.7087836,38.40996336936951,0.5371084285946558,1739137696.7087858,38.40996336936951,-1.998351330197225,1739137696.7087872,38.40996336936951,-0.5109038078628436,1739137696.7087886,38.40996336936951,-0.23776260752300496,1739137696.7087903,38.40996336936951,2.037919039874376,1739137696.708792,38.40996336936951,0.0,1739137696.7087936,38.40996336936951,0.4052688074694415,1739137696.7087953,38.40996336936951,4.373974743868513,1739137696.7087967,38.40996336936951,1.6326502324049343 +1739137696.7292173,38.42996335029602,43.18298432213589,1739137696.7292202,38.42996335029602,5.7595190654755815,1739137696.7292233,38.42996335029602,65.54585226812333,1739137696.7292264,38.42996335029602,40.80331420576446,1739137696.7292278,38.42996335029602,0.5371084285946558,1739137696.7292295,38.42996335029602,-1.998351330197225,1739137696.729231,38.42996335029602,-0.5109038078628436,1739137696.7292323,38.42996335029602,-0.23776260752300496,1739137696.729234,38.42996335029602,2.037919039874376,1739137696.7292356,38.42996335029602,0.0,1739137696.729237,38.42996335029602,0.4052688074694415,1739137696.7292387,38.42996335029602,4.373974743868513,1739137696.7292402,38.42996335029602,1.6326502324049343 +1739137696.749019,38.449963331222534,43.12443308377723,1739137696.749022,38.449963331222534,5.587674965790381,1739137696.7490256,38.449963331222534,65.72856955261307,1739137696.7490294,38.449963331222534,40.52316260378416,1739137696.7490306,38.449963331222534,0.4190978470745866,1739137696.749033,38.449963331222534,-2.037068966585737,1739137696.7490344,38.449963331222534,-0.8624047799048192,1739137696.749036,38.449963331222534,-0.3933756565048795,1739137696.7490377,38.449963331222534,1.77061832176325,1739137696.7490396,38.449963331222534,0.0,1739137696.749041,38.449963331222534,-0.18226579712758118,1739137696.749043,38.449963331222534,4.395717313837462,1739137696.7490444,38.449963331222534,1.6731055959877963 +1739137696.76874,38.46996331214905,43.12443308377723,1739137696.7687423,38.46996331214905,5.587674965790381,1739137696.7687457,38.46996331214905,65.72856955261307,1739137696.768749,38.46996331214905,40.52316260378416,1739137696.7687504,38.46996331214905,0.4190978470745866,1739137696.768752,38.46996331214905,-2.037068966585737,1739137696.768754,38.46996331214905,-0.8624047799048192,1739137696.7687554,38.46996331214905,-0.3933756565048795,1739137696.768757,38.46996331214905,1.77061832176325,1739137696.7687585,38.46996331214905,0.0,1739137696.76876,38.46996331214905,0.09751272577545378,1739137696.7687619,38.46996331214905,4.395717313837462,1739137696.7687633,38.46996331214905,1.6731055959877963 +1739137696.789039,38.48996329307556,43.12443308377723,1739137696.789042,38.48996329307556,5.587674965790381,1739137696.7890458,38.48996329307556,65.72856955261307,1739137696.789049,38.48996329307556,40.52316260378416,1739137696.7890506,38.48996329307556,0.4190978470745866,1739137696.7890527,38.48996329307556,-2.037068966585737,1739137696.7890542,38.48996329307556,-0.8624047799048192,1739137696.7890558,38.48996329307556,-0.3933756565048795,1739137696.7890573,38.48996329307556,1.77061832176325,1739137696.7890594,38.48996329307556,0.0,1739137696.7890608,38.48996329307556,0.09751272577545378,1739137696.7890627,38.48996329307556,4.395717313837462,1739137696.7890642,38.48996329307556,1.6731055959877963 +1739137696.8112938,38.509963274002075,43.12443308377723,1739137696.8112967,38.509963274002075,5.587674965790381,1739137696.8113003,38.509963274002075,65.72856955261307,1739137696.8113039,38.509963274002075,40.52316260378416,1739137696.8113058,38.509963274002075,0.4190978470745866,1739137696.8113081,38.509963274002075,-2.037068966585737,1739137696.8113098,38.509963274002075,-0.8624047799048192,1739137696.8113112,38.509963274002075,-0.3933756565048795,1739137696.811313,38.509963274002075,1.77061832176325,1739137696.8113146,38.509963274002075,0.0,1739137696.8113165,38.509963274002075,0.09751272577545378,1739137696.8113182,38.509963274002075,4.395717313837462,1739137696.81132,38.509963274002075,1.6731055959877963 +1739137696.8293478,38.52996325492859,43.12443308377723,1739137696.829351,38.52996325492859,5.587674965790381,1739137696.8293545,38.52996325492859,65.72856955261307,1739137696.8293579,38.52996325492859,40.52316260378416,1739137696.8293595,38.52996325492859,0.4190978470745866,1739137696.8293617,38.52996325492859,-2.037068966585737,1739137696.8293633,38.52996325492859,-0.8624047799048192,1739137696.8293653,38.52996325492859,-0.3933756565048795,1739137696.8293667,38.52996325492859,1.77061832176325,1739137696.8293688,38.52996325492859,0.0,1739137696.8293703,38.52996325492859,0.09751272577545378,1739137696.8293724,38.52996325492859,4.395717313837462,1739137696.8293738,38.52996325492859,1.6731055959877963 +1739137696.849043,38.5499632358551,43.12443308377723,1739137696.8490458,38.5499632358551,5.587674965790381,1739137696.8490493,38.5499632358551,65.72856955261307,1739137696.8490527,38.5499632358551,40.52316260378416,1739137696.8490546,38.5499632358551,0.4190978470745866,1739137696.8490565,38.5499632358551,-2.037068966585737,1739137696.8490584,38.5499632358551,-0.8624047799048192,1739137696.8490598,38.5499632358551,-0.3933756565048795,1739137696.8490615,38.5499632358551,1.77061832176325,1739137696.8490632,38.5499632358551,0.0,1739137696.849065,38.5499632358551,0.09751272577545378,1739137696.849067,38.5499632358551,4.395717313837462,1739137696.8490686,38.5499632358551,1.6731055959877963 +1739137696.8694446,38.569963216781616,43.06876881456238,1739137696.8694477,38.569963216781616,5.412250979470711,1739137696.8694513,38.569963216781616,65.91848804229532,1739137696.8694546,38.569963216781616,40.330386559186685,1739137696.8694565,38.569963216781616,0.3485384334779268,1739137696.8694587,38.569963216781616,-2.0665375409177145,1739137696.8694606,38.569963216781616,-1.1408824071823598,1739137696.869462,38.569963216781616,-0.5234104972437218,1739137696.8694634,38.569963216781616,1.5839754095554959,1739137696.8694656,38.569963216781616,0.0,1739137696.869467,38.569963216781616,-0.26860009302704935,1739137696.869469,38.569963216781616,4.4161509838541955,1739137696.8694708,38.569963216781616,1.6782359779673344 +1739137696.8894062,38.58996319770813,43.06876881456238,1739137696.8894093,38.58996319770813,5.412250979470711,1739137696.8894129,38.58996319770813,65.91848804229532,1739137696.8894162,38.58996319770813,40.330386559186685,1739137696.889418,38.58996319770813,0.3485384334779268,1739137696.88942,38.58996319770813,-2.0665375409177145,1739137696.889422,38.58996319770813,-1.1408824071823598,1739137696.8894234,38.58996319770813,-0.5234104972437218,1739137696.8894248,38.58996319770813,1.5839754095554959,1739137696.8894267,38.58996319770813,0.0,1739137696.8894284,38.58996319770813,-0.0942605684118385,1739137696.8894305,38.58996319770813,4.4161509838541955,1739137696.889432,38.58996319770813,1.6782359779673344 +1739137696.9091895,38.609963178634644,43.06876881456238,1739137696.9091926,38.609963178634644,5.412250979470711,1739137696.9091957,38.609963178634644,65.91848804229532,1739137696.9091995,38.609963178634644,40.330386559186685,1739137696.9092011,38.609963178634644,0.3485384334779268,1739137696.9092033,38.609963178634644,-2.0665375409177145,1739137696.9092052,38.609963178634644,-1.1408824071823598,1739137696.9092069,38.609963178634644,-0.5234104972437218,1739137696.9092085,38.609963178634644,1.5839754095554959,1739137696.9092104,38.609963178634644,0.0,1739137696.9092119,38.609963178634644,-0.0942605684118385,1739137696.9092138,38.609963178634644,4.4161509838541955,1739137696.9092152,38.609963178634644,1.6782359779673344 +1739137696.9294353,38.62996315956116,43.06876881456238,1739137696.9294379,38.62996315956116,5.412250979470711,1739137696.9294412,38.62996315956116,65.91848804229532,1739137696.9294448,38.62996315956116,40.330386559186685,1739137696.929447,38.62996315956116,0.3485384334779268,1739137696.9294488,38.62996315956116,-2.0665375409177145,1739137696.9294508,38.62996315956116,-1.1408824071823598,1739137696.9294522,38.62996315956116,-0.5234104972437218,1739137696.9294538,38.62996315956116,1.5839754095554959,1739137696.9294558,38.62996315956116,0.0,1739137696.9294574,38.62996315956116,-0.0942605684118385,1739137696.929459,38.62996315956116,4.4161509838541955,1739137696.9294608,38.62996315956116,1.6782359779673344 +1739137696.9494343,38.64996314048767,43.06876881456238,1739137696.9494371,38.64996314048767,5.412250979470711,1739137696.9494407,38.64996314048767,65.91848804229532,1739137696.949444,38.64996314048767,40.330386559186685,1739137696.949446,38.64996314048767,0.3485384334779268,1739137696.9494479,38.64996314048767,-2.0665375409177145,1739137696.9494498,38.64996314048767,-1.1408824071823598,1739137696.9494512,38.64996314048767,-0.5234104972437218,1739137696.9494529,38.64996314048767,1.5839754095554959,1739137696.9494545,38.64996314048767,0.0,1739137696.9494562,38.64996314048767,-0.0942605684118385,1739137696.9494581,38.64996314048767,4.4161509838541955,1739137696.9494598,38.64996314048767,1.6782359779673344 +1739137696.9692364,38.669963121414185,43.016624104128695,1739137696.9692395,38.669963121414185,5.23589078972233,1739137696.9692428,38.669963121414185,66.17823460207745,1739137696.9692461,38.669963121414185,40.119862041877525,1739137696.969248,38.669963121414185,0.27980279368238914,1739137696.96925,38.669963121414185,-2.0997300657844007,1739137696.9692519,38.669963121414185,-1.4298137677453817,1739137696.9692533,38.669963121414185,-0.6108,1739137696.969255,38.669963121414185,1.4110939078632532,1739137696.9692566,38.669963121414185,0.0,1739137696.9692583,38.669963121414185,-0.39995968423275485,1739137696.9692602,38.669963121414185,4.435177324587149,1739137696.969262,38.669963121414185,1.6654825118431238 +1739137696.9910297,38.6899631023407,43.016624104128695,1739137696.9910336,38.6899631023407,5.23589078972233,1739137696.9910383,38.6899631023407,66.17823460207745,1739137696.9910426,38.6899631023407,40.119862041877525,1739137696.9910448,38.6899631023407,0.27980279368238914,1739137696.9910476,38.6899631023407,-2.0997300657844007,1739137696.9910502,38.6899631023407,-1.4298137677453817,1739137696.9910526,38.6899631023407,-0.6108,1739137696.9910548,38.6899631023407,1.4110939078632532,1739137696.9910572,38.6899631023407,0.0,1739137696.9910595,38.6899631023407,-0.2543886039798706,1739137696.991062,38.6899631023407,4.435177324587149,1739137696.9910643,38.6899631023407,1.6654825118431238 +1739137697.0099158,38.70996308326721,43.016624104128695,1739137697.00992,38.70996308326721,5.23589078972233,1739137697.0099244,38.70996308326721,66.17823460207745,1739137697.0099287,38.70996308326721,40.119862041877525,1739137697.0099308,38.70996308326721,0.27980279368238914,1739137697.0099332,38.70996308326721,-2.0997300657844007,1739137697.0099359,38.70996308326721,-1.4298137677453817,1739137697.0099382,38.70996308326721,-0.6108,1739137697.0099401,38.70996308326721,1.4110939078632532,1739137697.0099428,38.70996308326721,0.0,1739137697.0099452,38.70996308326721,-0.2543886039798706,1739137697.0099473,38.70996308326721,4.435177324587149,1739137697.0099497,38.70996308326721,1.6654825118431238 +1739137697.030447,38.729963064193726,43.016624104128695,1739137697.0304506,38.729963064193726,5.23589078972233,1739137697.0304549,38.729963064193726,66.17823460207745,1739137697.0304594,38.729963064193726,40.119862041877525,1739137697.030462,38.729963064193726,0.27980279368238914,1739137697.0304644,38.729963064193726,-2.0997300657844007,1739137697.0304754,38.729963064193726,-1.4298137677453817,1739137697.0304782,38.729963064193726,-0.6108,1739137697.0304806,38.729963064193726,1.4110939078632532,1739137697.0304832,38.729963064193726,0.0,1739137697.0304854,38.729963064193726,-0.2543886039798706,1739137697.030488,38.729963064193726,4.435177324587149,1739137697.0304906,38.729963064193726,1.6654825118431238 +1739137697.0494359,38.74996304512024,43.016624104128695,1739137697.0494392,38.74996304512024,5.23589078972233,1739137697.0494428,38.74996304512024,66.17823460207745,1739137697.0494463,38.74996304512024,40.119862041877525,1739137697.0494485,38.74996304512024,0.27980279368238914,1739137697.049451,38.74996304512024,-2.0997300657844007,1739137697.049453,38.74996304512024,-1.4298137677453817,1739137697.0494552,38.74996304512024,-0.6108,1739137697.0494568,38.74996304512024,1.4110939078632532,1739137697.0494592,38.74996304512024,0.0,1739137697.0494614,38.74996304512024,-0.2543886039798706,1739137697.0494637,38.74996304512024,4.435177324587149,1739137697.049466,38.74996304512024,1.6654825118431238 +1739137697.0710983,38.76996302604675,43.016624104128695,1739137697.0711024,38.76996302604675,5.23589078972233,1739137697.0711071,38.76996302604675,66.17823460207745,1739137697.0711114,38.76996302604675,40.119862041877525,1739137697.0711138,38.76996302604675,0.27980279368238914,1739137697.0711164,38.76996302604675,-2.0997300657844007,1739137697.071119,38.76996302604675,-1.4298137677453817,1739137697.0711217,38.76996302604675,-0.6108,1739137697.0711243,38.76996302604675,1.4110939078632532,1739137697.0711265,38.76996302604675,0.0,1739137697.0711288,38.76996302604675,-0.2543886039798706,1739137697.0711315,38.76996302604675,4.435177324587149,1739137697.0711339,38.76996302604675,1.6654825118431238 +1739137697.0900881,38.78996300697327,42.9683623118163,1739137697.090092,38.78996300697327,5.060930697097101,1739137697.0900965,38.78996300697327,66.18057543215052,1739137697.0901008,38.78996300697327,40.215162776644796,1739137697.0901034,38.78996300697327,0.30965208852633463,1739137697.090106,38.78996300697327,-2.0959796786532587,1739137697.0901086,38.78996300697327,-1.440819919499892,1739137697.090111,38.78996300697327,-0.6108,1739137697.0901132,38.78996300697327,1.4048952770133338,1739137697.0901158,38.78996300697327,0.0,1739137697.0901182,38.78996300697327,-0.20118039012641356,1739137697.0901208,38.78996300697327,4.4526940866737945,1739137697.090123,38.78996300697327,1.6314129244889368 +1739137697.111346,38.80996298789978,42.9683623118163,1739137697.11135,38.80996298789978,5.060930697097101,1739137697.1113546,38.80996298789978,66.18057543215052,1739137697.111359,38.80996298789978,40.215162776644796,1739137697.1113613,38.80996298789978,0.30965208852633463,1739137697.1113641,38.80996298789978,-2.0959796786532587,1739137697.1113667,38.80996298789978,-1.440819919499892,1739137697.1113691,38.80996298789978,-0.6108,1739137697.111372,38.80996298789978,1.4048952770133338,1739137697.1113744,38.80996298789978,0.0,1739137697.1113765,38.80996298789978,-0.226517647475603,1739137697.1113791,38.80996298789978,4.4526940866737945,1739137697.1113818,38.80996298789978,1.6314129244889368 +1739137697.1300972,38.829962968826294,42.9683623118163,1739137697.1301005,38.829962968826294,5.060930697097101,1739137697.1301048,38.829962968826294,66.18057543215052,1739137697.1301095,38.829962968826294,40.215162776644796,1739137697.1301117,38.829962968826294,0.30965208852633463,1739137697.1301146,38.829962968826294,-2.0959796786532587,1739137697.1301172,38.829962968826294,-1.440819919499892,1739137697.13012,38.829962968826294,-0.6108,1739137697.1301222,38.829962968826294,1.4048952770133338,1739137697.1301248,38.829962968826294,0.0,1739137697.1301274,38.829962968826294,-0.226517647475603,1739137697.1301298,38.829962968826294,4.4526940866737945,1739137697.1301324,38.829962968826294,1.6314129244889368 +1739137697.148414,38.84996294975281,42.9683623118163,1739137697.1484165,38.84996294975281,5.060930697097101,1739137697.1484196,38.84996294975281,66.18057543215052,1739137697.1484222,38.84996294975281,40.215162776644796,1739137697.1484234,38.84996294975281,0.30965208852633463,1739137697.1484246,38.84996294975281,-2.0959796786532587,1739137697.1484263,38.84996294975281,-1.440819919499892,1739137697.1484275,38.84996294975281,-0.6108,1739137697.1484284,38.84996294975281,1.4048952770133338,1739137697.14843,38.84996294975281,0.0,1739137697.148431,38.84996294975281,-0.226517647475603,1739137697.1484327,38.84996294975281,4.4526940866737945,1739137697.148434,38.84996294975281,1.6314129244889368 +1739137697.1686404,38.86996293067932,42.9683623118163,1739137697.1686425,38.86996293067932,5.060930697097101,1739137697.168645,38.86996293067932,66.18057543215052,1739137697.1686478,38.86996293067932,40.215162776644796,1739137697.168649,38.86996293067932,0.30965208852633463,1739137697.1686504,38.86996293067932,-2.0959796786532587,1739137697.1686518,38.86996293067932,-1.440819919499892,1739137697.168653,38.86996293067932,-0.6108,1739137697.1686547,38.86996293067932,1.4048952770133338,1739137697.1686559,38.86996293067932,0.0,1739137697.168657,38.86996293067932,-0.226517647475603,1739137697.1686585,38.86996293067932,4.4526940866737945,1739137697.1686597,38.86996293067932,1.6314129244889368 +1739137697.188687,38.889962911605835,42.923936590572545,1739137697.18869,38.889962911605835,4.888621567393878,1739137697.1886928,38.889962911605835,66.40804097595561,1739137697.1886952,38.889962911605835,40.08852394531905,1739137697.1886966,38.889962911605835,0.27049929626659147,1739137697.188698,38.889962911605835,-2.1214284020950123,1739137697.1886997,38.889962911605835,-1.6372423562667966,1739137697.188701,38.889962911605835,-0.6108,1739137697.188702,38.889962911605835,1.2987389943561882,1739137697.1887035,38.889962911605835,0.0,1739137697.1887047,38.889962911605835,-0.36878390713796955,1739137697.1887064,38.889962911605835,4.468677465246748,1739137697.1887076,38.889962911605835,1.5997770297176748 +1739137697.2085762,38.90996289253235,42.923936590572545,1739137697.2085788,38.90996289253235,4.888621567393878,1739137697.208582,38.90996289253235,66.40804097595561,1739137697.2085845,38.90996289253235,40.08852394531905,1739137697.2085857,38.90996289253235,0.27049929626659147,1739137697.2085874,38.90996289253235,-2.1214284020950123,1739137697.2085888,38.90996289253235,-1.6372423562667966,1739137697.20859,38.90996289253235,-0.6108,1739137697.208592,38.90996289253235,1.2987389943561882,1739137697.2085931,38.90996289253235,0.0,1739137697.2085943,38.90996289253235,-0.30103803536148654,1739137697.208596,38.90996289253235,4.468677465246748,1739137697.208597,38.90996289253235,1.5997770297176748 +1739137697.2287495,38.92996287345886,42.923936590572545,1739137697.2287521,38.92996287345886,4.888621567393878,1739137697.2287545,38.92996287345886,66.40804097595561,1739137697.228757,38.92996287345886,40.08852394531905,1739137697.2287583,38.92996287345886,0.27049929626659147,1739137697.2287598,38.92996287345886,-2.1214284020950123,1739137697.2287614,38.92996287345886,-1.6372423562667966,1739137697.2287624,38.92996287345886,-0.6108,1739137697.2287636,38.92996287345886,1.2987389943561882,1739137697.2287652,38.92996287345886,0.0,1739137697.2287662,38.92996287345886,-0.30103803536148654,1739137697.2287676,38.92996287345886,4.468677465246748,1739137697.2287688,38.92996287345886,1.5997770297176748 +1739137697.2565312,38.93996286392212,42.923936590572545,1739137697.2565393,38.93996286392212,4.888621567393878,1739137697.2565496,38.93996286392212,66.40804097595561,1739137697.2565596,38.93996286392212,40.08852394531905,1739137697.2565646,38.93996286392212,0.27049929626659147,1739137697.2565703,38.93996286392212,-2.1214284020950123,1739137697.2565756,38.93996286392212,-1.6372423562667966,1739137697.25658,38.93996286392212,-0.6108,1739137697.2565846,38.93996286392212,1.2987389943561882,1739137697.2565901,38.93996286392212,0.0,1739137697.2565947,38.93996286392212,-0.30103803536148654,1739137697.2566,38.93996286392212,4.468677465246748,1739137697.2566044,38.93996286392212,1.5997770297176748 +1739137697.27653,38.95996284484863,42.923936590572545,1739137697.276538,38.95996284484863,4.888621567393878,1739137697.276547,38.95996284484863,66.40804097595561,1739137697.2765565,38.95996284484863,40.08852394531905,1739137697.2765613,38.95996284484863,0.27049929626659147,1739137697.2765667,38.95996284484863,-2.1214284020950123,1739137697.276572,38.95996284484863,-1.6372423562667966,1739137697.2765763,38.95996284484863,-0.6108,1739137697.2765808,38.95996284484863,1.2987389943561882,1739137697.2765863,38.95996284484863,0.0,1739137697.2765908,38.95996284484863,-0.30103803536148654,1739137697.276596,38.95996284484863,4.468677465246748,1739137697.2766006,38.95996284484863,1.5997770297176748 +1739137697.305409,38.97996282577515,42.923936590572545,1739137697.305418,38.97996282577515,4.888621567393878,1739137697.3054278,38.97996282577515,66.40804097595561,1739137697.3054383,38.97996282577515,40.08852394531905,1739137697.3054428,38.97996282577515,0.27049929626659147,1739137697.3054488,38.97996282577515,-2.1214284020950123,1739137697.3054538,38.97996282577515,-1.6372423562667966,1739137697.3054585,38.97996282577515,-0.6108,1739137697.3054628,38.97996282577515,1.2987389943561882,1739137697.305468,38.97996282577515,0.0,1739137697.3054729,38.97996282577515,-0.30103803536148654,1739137697.3054779,38.97996282577515,4.468677465246748,1739137697.3054829,38.97996282577515,1.5997770297176748 +1739137697.32179,39.00996279716492,42.883008593805556,1739137697.321798,39.00996279716492,4.719197626899792,1739137697.3218076,39.00996279716492,66.58488946111012,1739137697.3218179,39.00996279716492,40.01491695456392,1739137697.3218224,39.00996279716492,0.24997735124470635,1739137697.3218284,39.00996279716492,-2.141345189159653,1739137697.3218331,39.00996279716492,-1.7775534604362744,1739137697.3218381,39.00996279716492,-0.6108,1739137697.3218427,39.00996279716492,1.2278557405470372,1739137697.3218482,39.00996279716492,0.0,1739137697.3218527,39.00996279716492,-0.3724502468235068,1739137697.321858,39.00996279716492,4.483162409619532,1739137697.3218625,39.00996279716492,1.5663001554012308 +1739137697.3587754,39.03996276855469,42.883008593805556,1739137697.358782,39.03996276855469,4.719197626899792,1739137697.3587906,39.03996276855469,66.58488946111012,1739137697.3588011,39.03996276855469,40.01491695456392,1739137697.3588068,39.03996276855469,0.24997735124470635,1739137697.3588142,39.03996276855469,-2.141345189159653,1739137697.3588207,39.03996276855469,-1.7775534604362744,1739137697.3588276,39.03996276855469,-0.6108,1739137697.358834,39.03996276855469,1.2278557405470372,1739137697.358841,39.03996276855469,0.0,1739137697.3588474,39.03996276855469,-0.33844441485419363,1739137697.3588543,39.03996276855469,4.483162409619532,1739137697.358861,39.03996276855469,1.5663001554012308 +1739137697.3727226,39.06996273994446,42.883008593805556,1739137697.3727262,39.06996273994446,4.719197626899792,1739137697.3727303,39.06996273994446,66.58488946111012,1739137697.372735,39.06996273994446,40.01491695456392,1739137697.372737,39.06996273994446,0.24997735124470635,1739137697.3727396,39.06996273994446,-2.141345189159653,1739137697.372742,39.06996273994446,-1.7775534604362744,1739137697.3727438,39.06996273994446,-0.6108,1739137697.372746,39.06996273994446,1.2278557405470372,1739137697.3727486,39.06996273994446,0.0,1739137697.3727505,39.06996273994446,-0.33844441485419363,1739137697.372753,39.06996273994446,4.483162409619532,1739137697.3727546,39.06996273994446,1.5663001554012308 +1739137697.4122233,39.109962701797485,42.84523727433375,1739137697.412226,39.109962701797485,4.552800538235392,1739137697.4122293,39.109962701797485,66.7680215999969,1739137697.4122324,39.109962701797485,39.93450694593507,1739137697.412234,39.109962701797485,0.2271267364837676,1739137697.4122355,39.109962701797485,-2.163099430938448,1739137697.4122372,39.109962701797485,-1.9149815479176977,1739137697.4122384,39.109962701797485,-0.6108,1739137697.4122396,39.109962701797485,1.1621806519114806,1739137697.4122412,39.109962701797485,0.0,1739137697.4122424,39.109962701797485,-0.4004833938149799,1739137697.4122443,39.109962701797485,4.496179903710137,1739137697.4122455,39.109962701797485,1.5331216600350404 +1739137697.4330432,39.129962682724,42.84523727433375,1739137697.4330463,39.129962682724,4.552800538235392,1739137697.4330492,39.129962682724,66.7680215999969,1739137697.4330516,39.129962682724,39.93450694593507,1739137697.4330533,39.129962682724,0.2271267364837676,1739137697.433055,39.129962682724,-2.163099430938448,1739137697.4330566,39.129962682724,-1.9149815479176977,1739137697.4330578,39.129962682724,-0.6108,1739137697.4330587,39.129962682724,1.1621806519114806,1739137697.433061,39.129962682724,0.0,1739137697.4330623,39.129962682724,-0.3709410081235598,1739137697.433064,39.129962682724,4.496179903710137,1739137697.4330652,39.129962682724,1.5331216600350404 +1739137697.4519975,39.14996266365051,42.84523727433375,1739137697.4519997,39.14996266365051,4.552800538235392,1739137697.4520023,39.14996266365051,66.7680215999969,1739137697.452005,39.14996266365051,39.93450694593507,1739137697.4520059,39.14996266365051,0.2271267364837676,1739137697.4520075,39.14996266365051,-2.163099430938448,1739137697.452009,39.14996266365051,-1.9149815479176977,1739137697.45201,39.14996266365051,-0.6108,1739137697.4520113,39.14996266365051,1.1621806519114806,1739137697.4520125,39.14996266365051,0.0,1739137697.4520137,39.14996266365051,-0.3709410081235598,1739137697.4520152,39.14996266365051,4.496179903710137,1739137697.4520164,39.14996266365051,1.5331216600350404 +1739137697.4723313,39.169962644577026,42.84523727433375,1739137697.472334,39.169962644577026,4.552800538235392,1739137697.472337,39.169962644577026,66.7680215999969,1739137697.4723396,39.169962644577026,39.93450694593507,1739137697.472341,39.169962644577026,0.2271267364837676,1739137697.4723425,39.169962644577026,-2.163099430938448,1739137697.4723442,39.169962644577026,-1.9149815479176977,1739137697.4723456,39.169962644577026,-0.6108,1739137697.4723465,39.169962644577026,1.1621806519114806,1739137697.4723485,39.169962644577026,0.0,1739137697.4723496,39.169962644577026,-0.3709410081235598,1739137697.4723513,39.169962644577026,4.496179903710137,1739137697.4723525,39.169962644577026,1.5331216600350404 +1739137697.4922302,39.18996262550354,42.84523727433375,1739137697.4922328,39.18996262550354,4.552800538235392,1739137697.492235,39.18996262550354,66.7680215999969,1739137697.4922376,39.18996262550354,39.93450694593507,1739137697.4922388,39.18996262550354,0.2271267364837676,1739137697.4922404,39.18996262550354,-2.163099430938448,1739137697.4922419,39.18996262550354,-1.9149815479176977,1739137697.4922433,39.18996262550354,-0.6108,1739137697.4922445,39.18996262550354,1.1621806519114806,1739137697.4922457,39.18996262550354,0.0,1739137697.492247,39.18996262550354,-0.3709410081235598,1739137697.4922485,39.18996262550354,4.496179903710137,1739137697.4922495,39.18996262550354,1.5331216600350404 +1739137697.511931,39.209962606430054,42.84523727433375,1739137697.511933,39.209962606430054,4.552800538235392,1739137697.5119362,39.209962606430054,66.7680215999969,1739137697.5119388,39.209962606430054,39.93450694593507,1739137697.51194,39.209962606430054,0.2271267364837676,1739137697.511942,39.209962606430054,-2.163099430938448,1739137697.511943,39.209962606430054,-1.9149815479176977,1739137697.5119443,39.209962606430054,-0.6108,1739137697.5119455,39.209962606430054,1.1621806519114806,1739137697.511947,39.209962606430054,0.0,1739137697.511948,39.209962606430054,-0.3709410081235598,1739137697.5119495,39.209962606430054,4.496179903710137,1739137697.5119507,39.209962606430054,1.5331216600350404 +1739137697.5325716,39.22996258735657,42.81032627138867,1739137697.5325744,39.22996258735657,4.389689150728572,1739137697.532577,39.22996258735657,66.95674704976392,1739137697.53258,39.22996258735657,39.852907066646836,1739137697.532581,39.22996258735657,0.20678869757965515,1739137697.5325828,39.22996258735657,-2.186222152026833,1739137697.5325842,39.22996258735657,-2.045722322336236,1739137697.5325854,39.22996258735657,-0.6108,1739137697.5325868,39.22996258735657,1.1029647736856498,1739137697.5325882,39.22996258735657,0.0,1739137697.5325897,39.22996258735657,-0.4174073457021951,1739137697.532591,39.22996258735657,4.507757245229959,1739137697.5325923,39.22996258735657,1.4982452809161246 +1739137697.5546422,39.24996256828308,42.81032627138867,1739137697.554644,39.24996256828308,4.389689150728572,1739137697.5546467,39.24996256828308,66.95674704976392,1739137697.5546494,39.24996256828308,39.852907066646836,1739137697.5546503,39.24996256828308,0.20678869757965515,1739137697.554652,39.24996256828308,-2.186222152026833,1739137697.5546534,39.24996256828308,-2.045722322336236,1739137697.5546548,39.24996256828308,-0.6108,1739137697.5546558,39.24996256828308,1.1029647736856498,1739137697.5546572,39.24996256828308,0.0,1739137697.5546584,39.24996256828308,-0.3952805072304748,1739137697.5546596,39.24996256828308,4.507757245229959,1739137697.5546608,39.24996256828308,1.4982452809161246 +1739137697.572652,39.269962549209595,42.81032627138867,1739137697.572655,39.269962549209595,4.389689150728572,1739137697.5726578,39.269962549209595,66.95674704976392,1739137697.572661,39.269962549209595,39.852907066646836,1739137697.5726624,39.269962549209595,0.20678869757965515,1739137697.572664,39.269962549209595,-2.186222152026833,1739137697.5726655,39.269962549209595,-2.045722322336236,1739137697.572667,39.269962549209595,-0.6108,1739137697.5726678,39.269962549209595,1.1029647736856498,1739137697.5726695,39.269962549209595,0.0,1739137697.5726707,39.269962549209595,-0.3952805072304748,1739137697.5726724,39.269962549209595,4.507757245229959,1739137697.5726736,39.269962549209595,1.4982452809161246 +1739137697.5920138,39.28996253013611,42.81032627138867,1739137697.5920165,39.28996253013611,4.389689150728572,1739137697.592019,39.28996253013611,66.95674704976392,1739137697.592022,39.28996253013611,39.852907066646836,1739137697.5920234,39.28996253013611,0.20678869757965515,1739137697.592025,39.28996253013611,-2.186222152026833,1739137697.5920265,39.28996253013611,-2.045722322336236,1739137697.592028,39.28996253013611,-0.6108,1739137697.592029,39.28996253013611,1.1029647736856498,1739137697.5920308,39.28996253013611,0.0,1739137697.592032,39.28996253013611,-0.3952805072304748,1739137697.5920339,39.28996253013611,4.507757245229959,1739137697.592035,39.28996253013611,1.4982452809161246 +1739137697.6125786,39.30996251106262,42.81032627138867,1739137697.6125815,39.30996251106262,4.389689150728572,1739137697.6125846,39.30996251106262,66.95674704976392,1739137697.6125875,39.30996251106262,39.852907066646836,1739137697.6125891,39.30996251106262,0.20678869757965515,1739137697.6125906,39.30996251106262,-2.186222152026833,1739137697.6125922,39.30996251106262,-2.045722322336236,1739137697.6125937,39.30996251106262,-0.6108,1739137697.6125948,39.30996251106262,1.1029647736856498,1739137697.6125965,39.30996251106262,0.0,1739137697.6125977,39.30996251106262,-0.3952805072304748,1739137697.6125994,39.30996251106262,4.507757245229959,1739137697.6126008,39.30996251106262,1.4982452809161246 +1739137697.6400173,39.329962491989136,42.77796214722567,1739137697.6400259,39.329962491989136,4.2299637992354935,1739137697.6400354,39.329962491989136,67.02923384106793,1739137697.6400452,39.329962491989136,39.88435977848595,1739137697.6400497,39.329962491989136,0.21458994462148748,1739137697.6400552,39.329962491989136,-2.195234741276579,1739137697.6400602,39.329962491989136,-2.063098339846835,1739137697.6400647,39.329962491989136,-0.6108,1739137697.6400695,39.329962491989136,1.0953252990801525,1739137697.6400747,39.329962491989136,0.0,1739137697.6400793,39.329962491989136,-0.34311510718577554,1739137697.6400847,39.329962491989136,4.5179182847403965,1739137697.6400893,39.329962491989136,1.4632810853628846 +1739137697.6619637,39.34996247291565,42.77796214722567,1739137697.6619794,39.34996247291565,4.2299637992354935,1739137697.6619966,39.34996247291565,67.02923384106793,1739137697.6620135,39.34996247291565,39.88435977848595,1739137697.6620243,39.34996247291565,0.21458994462148748,1739137697.662043,39.34996247291565,-2.195234741276579,1739137697.6620593,39.34996247291565,-2.063098339846835,1739137697.662071,39.34996247291565,-0.6108,1739137697.662082,39.34996247291565,1.0953252990801525,1739137697.662098,39.34996247291565,0.0,1739137697.6621141,39.34996247291565,-0.36795578628273207,1739137697.6621263,39.34996247291565,4.5179182847403965,1739137697.6621375,39.34996247291565,1.4632810853628846 +1739137697.685155,39.36996245384216,42.77796214722567,1739137697.6851597,39.36996245384216,4.2299637992354935,1739137697.6851656,39.36996245384216,67.02923384106793,1739137697.6851707,39.36996245384216,39.88435977848595,1739137697.6851733,39.36996245384216,0.21458994462148748,1739137697.6851766,39.36996245384216,-2.195234741276579,1739137697.6851795,39.36996245384216,-2.063098339846835,1739137697.6851816,39.36996245384216,-0.6108,1739137697.6851847,39.36996245384216,1.0953252990801525,1739137697.6851876,39.36996245384216,0.0,1739137697.6851904,39.36996245384216,-0.36795578628273207,1739137697.6851933,39.36996245384216,4.5179182847403965,1739137697.6851957,39.36996245384216,1.4632810853628846 +1739137697.702526,39.38996243476868,42.77796214722567,1739137697.7025306,39.38996243476868,4.2299637992354935,1739137697.702536,39.38996243476868,67.02923384106793,1739137697.7025416,39.38996243476868,39.88435977848595,1739137697.7025442,39.38996243476868,0.21458994462148748,1739137697.7025473,39.38996243476868,-2.195234741276579,1739137697.70255,39.38996243476868,-2.063098339846835,1739137697.7025526,39.38996243476868,-0.6108,1739137697.702555,39.38996243476868,1.0953252990801525,1739137697.7025578,39.38996243476868,0.0,1739137697.7025602,39.38996243476868,-0.36795578628273207,1739137697.7025633,39.38996243476868,4.5179182847403965,1739137697.7025657,39.38996243476868,1.4632810853628846 +1739137697.725043,39.41996240615845,42.77796214722567,1739137697.7250476,39.41996240615845,4.2299637992354935,1739137697.7250528,39.41996240615845,67.02923384106793,1739137697.7250583,39.41996240615845,39.88435977848595,1739137697.725061,39.41996240615845,0.21458994462148748,1739137697.7250645,39.41996240615845,-2.195234741276579,1739137697.725067,39.41996240615845,-2.063098339846835,1739137697.7250695,39.41996240615845,-0.6108,1739137697.725072,39.41996240615845,1.0953252990801525,1739137697.7250752,39.41996240615845,0.0,1739137697.7250779,39.41996240615845,-0.36795578628273207,1739137697.7250805,39.41996240615845,4.5179182847403965,1739137697.725083,39.41996240615845,1.4632810853628846 +1739137697.7614405,39.44996237754822,42.74780786921732,1739137697.7614436,39.44996237754822,4.073498932325611,1739137697.7614467,39.44996237754822,67.4690760654616,1739137697.7614496,39.44996237754822,39.549952729107304,1739137697.761451,39.44996237754822,0.1384775123238108,1739137697.761453,39.44996237754822,-2.253212408474506,1739137697.761454,39.44996237754822,-2.4163104682264778,1739137697.7614555,39.44996237754822,-0.6108,1739137697.761457,39.44996237754822,0.9510073807589564,1739137697.7614584,39.44996237754822,0.0,1739137697.7614598,39.44996237754822,-0.5818549126763728,1739137697.7614613,39.44996237754822,4.5266836292184855,1739137697.7614627,39.44996237754822,1.431005515699304 +1739137697.7803113,39.46996235847473,42.74780786921732,1739137697.7803142,39.46996235847473,4.073498932325611,1739137697.7803168,39.46996235847473,67.4690760654616,1739137697.7803197,39.46996235847473,39.549952729107304,1739137697.7803211,39.46996235847473,0.1384775123238108,1739137697.7803228,39.46996235847473,-2.253212408474506,1739137697.780324,39.46996235847473,-2.4163104682264778,1739137697.7803254,39.46996235847473,-0.6108,1739137697.7803266,39.46996235847473,0.9510073807589564,1739137697.7803283,39.46996235847473,0.0,1739137697.7803292,39.46996235847473,-0.4799981349403476,1739137697.780331,39.46996235847473,4.5266836292184855,1739137697.7803323,39.46996235847473,1.431005515699304 +1739137697.8015382,39.489962339401245,42.74780786921732,1739137697.8015416,39.489962339401245,4.073498932325611,1739137697.8015466,39.489962339401245,67.4690760654616,1739137697.8015516,39.489962339401245,39.549952729107304,1739137697.8015544,39.489962339401245,0.1384775123238108,1739137697.8015583,39.489962339401245,-2.253212408474506,1739137697.8015618,39.489962339401245,-2.4163104682264778,1739137697.801565,39.489962339401245,-0.6108,1739137697.8015683,39.489962339401245,0.9510073807589564,1739137697.8015716,39.489962339401245,0.0,1739137697.801575,39.489962339401245,-0.4799981349403476,1739137697.8015785,39.489962339401245,4.5266836292184855,1739137697.8015816,39.489962339401245,1.431005515699304 +1739137697.8200185,39.50996232032776,42.74780786921732,1739137697.820021,39.50996232032776,4.073498932325611,1739137697.8200238,39.50996232032776,67.4690760654616,1739137697.8200266,39.50996232032776,39.549952729107304,1739137697.8200278,39.50996232032776,0.1384775123238108,1739137697.8200297,39.50996232032776,-2.253212408474506,1739137697.820031,39.50996232032776,-2.4163104682264778,1739137697.8200324,39.50996232032776,-0.6108,1739137697.8200338,39.50996232032776,0.9510073807589564,1739137697.8200352,39.50996232032776,0.0,1739137697.8200366,39.50996232032776,-0.4799981349403476,1739137697.820038,39.50996232032776,4.5266836292184855,1739137697.8200395,39.50996232032776,1.431005515699304 +1739137697.8469014,39.52996230125427,42.74780786921732,1739137697.8469102,39.52996230125427,4.073498932325611,1739137697.84692,39.52996230125427,67.4690760654616,1739137697.84693,39.52996230125427,39.549952729107304,1739137697.846935,39.52996230125427,0.1384775123238108,1739137697.8469412,39.52996230125427,-2.253212408474506,1739137697.8469462,39.52996230125427,-2.4163104682264778,1739137697.846951,39.52996230125427,-0.6108,1739137697.8469558,39.52996230125427,0.9510073807589564,1739137697.8469615,39.52996230125427,0.0,1739137697.8469663,39.52996230125427,-0.4799981349403476,1739137697.8469718,39.52996230125427,4.5266836292184855,1739137697.8469765,39.52996230125427,1.431005515699304 +1739137697.869417,39.549962282180786,42.71970495624484,1739137697.8694308,39.549962282180786,3.921015866137788,1739137697.8694527,39.549962282180786,67.47144762019333,1739137697.8694787,39.549962282180786,39.69395927864518,1739137697.8694928,39.549962282180786,0.16919412842639314,1739137697.8695104,39.549962282180786,-2.2494722197899,1739137697.8695168,39.549962282180786,-2.3122895323340162,1739137697.8695214,39.549962282180786,-0.6108,1739137697.8695257,39.549962282180786,0.9914120082428445,1739137697.8695312,39.549962282180786,0.0,1739137697.869536,39.549962282180786,-0.3076475044264431,1739137697.8695414,39.549962282180786,4.534070813956478,1739137697.869546,39.549962282180786,1.3811312824838673 +1739137697.8942552,39.57996225357056,42.71970495624484,1739137697.8942606,39.57996225357056,3.921015866137788,1739137697.8942676,39.57996225357056,67.47144762019333,1739137697.8942742,39.57996225357056,39.69395927864518,1739137697.8942776,39.57996225357056,0.16919412842639314,1739137697.8942814,39.57996225357056,-2.2494722197899,1739137697.894285,39.57996225357056,-2.3122895323340162,1739137697.894288,39.57996225357056,-0.6108,1739137697.8942914,39.57996225357056,0.9914120082428445,1739137697.894295,39.57996225357056,0.0,1739137697.8942983,39.57996225357056,-0.3897192742410228,1739137697.894302,39.57996225357056,4.534070813956478,1739137697.8943052,39.57996225357056,1.3811312824838673 +1739137697.9135206,39.59996223449707,42.71970495624484,1739137697.9135253,39.59996223449707,3.921015866137788,1739137697.9135303,39.59996223449707,67.47144762019333,1739137697.9135358,39.59996223449707,39.69395927864518,1739137697.9135382,39.59996223449707,0.16919412842639314,1739137697.9135413,39.59996223449707,-2.2494722197899,1739137697.9135442,39.59996223449707,-2.3122895323340162,1739137697.9135468,39.59996223449707,-0.6108,1739137697.9135494,39.59996223449707,0.9914120082428445,1739137697.913552,39.59996223449707,0.0,1739137697.9135547,39.59996223449707,-0.3897192742410228,1739137697.9135578,39.59996223449707,4.534070813956478,1739137697.9135604,39.59996223449707,1.3811312824838673 +1739137697.9323094,39.619962215423584,42.71970495624484,1739137697.9323144,39.619962215423584,3.921015866137788,1739137697.9323196,39.619962215423584,67.47144762019333,1739137697.9323251,39.619962215423584,39.69395927864518,1739137697.9323277,39.619962215423584,0.16919412842639314,1739137697.9323308,39.619962215423584,-2.2494722197899,1739137697.9323332,39.619962215423584,-2.3122895323340162,1739137697.9323359,39.619962215423584,-0.6108,1739137697.9323382,39.619962215423584,0.9914120082428445,1739137697.932341,39.619962215423584,0.0,1739137697.9323432,39.619962215423584,-0.3897192742410228,1739137697.932346,39.619962215423584,4.534070813956478,1739137697.9323487,39.619962215423584,1.3811312824838673 +1739137697.9528308,39.6399621963501,42.71970495624484,1739137697.9528358,39.6399621963501,3.921015866137788,1739137697.9528408,39.6399621963501,67.47144762019333,1739137697.9528456,39.6399621963501,39.69395927864518,1739137697.9528482,39.6399621963501,0.16919412842639314,1739137697.9528515,39.6399621963501,-2.2494722197899,1739137697.9528542,39.6399621963501,-2.3122895323340162,1739137697.9528565,39.6399621963501,-0.6108,1739137697.9528592,39.6399621963501,0.9914120082428445,1739137697.952862,39.6399621963501,0.0,1739137697.9528642,39.6399621963501,-0.3897192742410228,1739137697.952867,39.6399621963501,4.534070813956478,1739137697.9528697,39.6399621963501,1.3811312824838673 +1739137697.973553,39.65996217727661,42.6935274442852,1739137697.9735625,39.65996217727661,3.7733758393150296,1739137697.973572,39.65996217727661,68.27902793708277,1739137697.9735835,39.65996217727661,39.01985736554824,1739137697.9735913,39.65996217727661,0.04290003117675322,1739137697.9736013,39.65996217727661,-2.348522489161571,1739137697.9736102,39.65996217727661,-2.9797123321612893,1739137697.9736176,39.65996217727661,-0.6108,1739137697.9736269,39.65996217727661,0.7591209187834365,1739137697.9736326,39.65996217727661,0.0,1739137697.973635,39.65996217727661,-0.7558049390904749,1739137697.9736378,39.65996217727661,4.54009444593122,1739137697.9736404,39.65996217727661,1.3405992637189936 +1739137697.9932778,39.679962158203125,42.6935274442852,1739137697.9932823,39.679962158203125,3.7733758393150296,1739137697.9932876,39.679962158203125,68.27902793708277,1739137697.993293,39.679962158203125,39.01985736554824,1739137697.9932957,39.679962158203125,0.04290003117675322,1739137697.9932988,39.679962158203125,-2.348522489161571,1739137697.9933014,39.679962158203125,-2.9797123321612893,1739137697.993304,39.679962158203125,-0.6108,1739137697.9933064,39.679962158203125,0.7591209187834365,1739137697.9933097,39.679962158203125,0.0,1739137697.9933124,39.679962158203125,-0.5814783449355572,1739137697.993315,39.679962158203125,4.54009444593122,1739137697.9933174,39.679962158203125,1.3405992637189936 +1739137698.0122218,39.69996213912964,42.6935274442852,1739137698.0122263,39.69996213912964,3.7733758393150296,1739137698.0122316,39.69996213912964,68.27902793708277,1739137698.0122368,39.69996213912964,39.01985736554824,1739137698.0122395,39.69996213912964,0.04290003117675322,1739137698.0122423,39.69996213912964,-2.348522489161571,1739137698.0122452,39.69996213912964,-2.9797123321612893,1739137698.0122478,39.69996213912964,-0.6108,1739137698.0122504,39.69996213912964,0.7591209187834365,1739137698.0122533,39.69996213912964,0.0,1739137698.0122554,39.69996213912964,-0.5814783449355572,1739137698.0122585,39.69996213912964,4.54009444593122,1739137698.0122612,39.69996213912964,1.3405992637189936 +1739137698.0321417,39.72996211051941,42.6935274442852,1739137698.032144,39.72996211051941,3.7733758393150296,1739137698.0321476,39.72996211051941,68.27902793708277,1739137698.0321505,39.72996211051941,39.01985736554824,1739137698.0321524,39.72996211051941,0.04290003117675322,1739137698.0321543,39.72996211051941,-2.348522489161571,1739137698.032156,39.72996211051941,-2.9797123321612893,1739137698.0321574,39.72996211051941,-0.6108,1739137698.032159,39.72996211051941,0.7591209187834365,1739137698.032161,39.72996211051941,0.0,1739137698.0321627,39.72996211051941,-0.5814783449355572,1739137698.0321643,39.72996211051941,4.54009444593122,1739137698.0321655,39.72996211051941,1.3405992637189936 +1739137698.0534418,39.74996209144592,42.6935274442852,1739137698.0534449,39.74996209144592,3.7733758393150296,1739137698.0534482,39.74996209144592,68.27902793708277,1739137698.0534513,39.74996209144592,39.01985736554824,1739137698.0534527,39.74996209144592,0.04290003117675322,1739137698.0534546,39.74996209144592,-2.348522489161571,1739137698.0534563,39.74996209144592,-2.9797123321612893,1739137698.053458,39.74996209144592,-0.6108,1739137698.0534594,39.74996209144592,0.7591209187834365,1739137698.0534616,39.74996209144592,0.0,1739137698.053463,39.74996209144592,-0.5814783449355572,1739137698.0534647,39.74996209144592,4.54009444593122,1739137698.0534663,39.74996209144592,1.3405992637189936 +1739137698.0726967,39.76996207237244,42.669124503389234,1739137698.0726995,39.76996207237244,3.6312823767642755,1739137698.0727026,39.76996207237244,68.28154113770971,1739137698.0727055,39.76996207237244,39.21063413094435,1739137698.0727074,39.76996207237244,0.07356639300272695,1739137698.0727093,39.76996207237244,-2.342053087868004,1739137698.072711,39.76996207237244,-2.816451739258328,1739137698.0727124,39.76996207237244,-0.6108,1739137698.0727136,39.76996207237244,0.8103492399316277,1739137698.0727155,39.76996207237244,0.0,1739137698.072717,39.76996207237244,-0.3591128751935951,1739137698.0727186,39.76996207237244,4.544766321191235,1739137698.07272,39.76996207237244,1.2753504869458345 +1739137698.0927994,39.78996205329895,42.669124503389234,1739137698.0928028,39.78996205329895,3.6312823767642755,1739137698.0928059,39.78996205329895,68.28154113770971,1739137698.092809,39.78996205329895,39.21063413094435,1739137698.0928104,39.78996205329895,0.07356639300272695,1739137698.0928123,39.78996205329895,-2.342053087868004,1739137698.092814,39.78996205329895,-2.816451739258328,1739137698.0928154,39.78996205329895,-0.6108,1739137698.0928168,39.78996205329895,0.8103492399316277,1739137698.0928187,39.78996205329895,0.0,1739137698.0928202,39.78996205329895,-0.46500124701420686,1739137698.0928218,39.78996205329895,4.544766321191235,1739137698.0928233,39.78996205329895,1.2753504869458345 +1739137698.1117299,39.809962034225464,42.669124503389234,1739137698.1117322,39.809962034225464,3.6312823767642755,1739137698.111735,39.809962034225464,68.28154113770971,1739137698.1117375,39.809962034225464,39.21063413094435,1739137698.111739,39.809962034225464,0.07356639300272695,1739137698.1117404,39.809962034225464,-2.342053087868004,1739137698.1117418,39.809962034225464,-2.816451739258328,1739137698.111743,39.809962034225464,-0.6108,1739137698.1117442,39.809962034225464,0.8103492399316277,1739137698.1117456,39.809962034225464,0.0,1739137698.1117465,39.809962034225464,-0.46500124701420686,1739137698.111748,39.809962034225464,4.544766321191235,1739137698.1117492,39.809962034225464,1.2753504869458345 +1739137698.1318772,39.82996201515198,42.669124503389234,1739137698.1318796,39.82996201515198,3.6312823767642755,1739137698.1318824,39.82996201515198,68.28154113770971,1739137698.1318853,39.82996201515198,39.21063413094435,1739137698.1318862,39.82996201515198,0.07356639300272695,1739137698.1318882,39.82996201515198,-2.342053087868004,1739137698.1318893,39.82996201515198,-2.816451739258328,1739137698.1318908,39.82996201515198,-0.6108,1739137698.131892,39.82996201515198,0.8103492399316277,1739137698.1318932,39.82996201515198,0.0,1739137698.1318946,39.82996201515198,-0.46500124701420686,1739137698.1318958,39.82996201515198,4.544766321191235,1739137698.1318974,39.82996201515198,1.2753504869458345 +1739137698.151601,39.84996199607849,42.669124503389234,1739137698.1516035,39.84996199607849,3.6312823767642755,1739137698.1516063,39.84996199607849,68.28154113770971,1739137698.1516092,39.84996199607849,39.21063413094435,1739137698.1516106,39.84996199607849,0.07356639300272695,1739137698.151612,39.84996199607849,-2.342053087868004,1739137698.1516137,39.84996199607849,-2.816451739258328,1739137698.1516151,39.84996199607849,-0.6108,1739137698.151617,39.84996199607849,0.8103492399316277,1739137698.1516185,39.84996199607849,0.0,1739137698.15162,39.84996199607849,-0.46500124701420686,1739137698.1516213,39.84996199607849,4.544766321191235,1739137698.1516228,39.84996199607849,1.2753504869458345 +1739137698.1751354,39.869961977005005,42.669124503389234,1739137698.1751385,39.869961977005005,3.6312823767642755,1739137698.1751418,39.869961977005005,68.28154113770971,1739137698.1751451,39.869961977005005,39.21063413094435,1739137698.175147,39.869961977005005,0.07356639300272695,1739137698.175149,39.869961977005005,-2.342053087868004,1739137698.1751509,39.869961977005005,-2.816451739258328,1739137698.1751523,39.869961977005005,-0.6108,1739137698.175154,39.869961977005005,0.8103492399316277,1739137698.1751559,39.869961977005005,0.0,1739137698.1751575,39.869961977005005,-0.46500124701420686,1739137698.1751592,39.869961977005005,4.544766321191235,1739137698.1751611,39.869961977005005,1.2753504869458345 +1739137698.192585,39.88996195793152,42.64630588625796,1739137698.1925883,39.88996195793152,3.495093728558123,1739137698.1925921,39.88996195793152,68.7027138798856,1739137698.1925957,39.88996195793152,38.93464627331604,1739137698.1925974,39.88996195793152,0.03070228352635985,1739137698.1925995,39.88996195793152,-2.39063827744578,1739137698.1926017,39.88996195793152,-3.0950592483950214,1739137698.192603,39.88996195793152,-0.6108,1739137698.1926048,39.88996195793152,0.7248917341512101,1739137698.1926067,39.88996195793152,0.0,1739137698.1926086,39.88996195793152,-0.5378756858447954,1739137698.1926103,39.88996195793152,4.548095518300795,1739137698.192612,39.88996195793152,1.2280652889319232 +1739137698.2193007,39.90996193885803,42.64630588625796,1739137698.2193096,39.90996193885803,3.495093728558123,1739137698.2193196,39.90996193885803,68.7027138798856,1739137698.2193294,39.90996193885803,38.93464627331604,1739137698.2193336,39.90996193885803,0.03070228352635985,1739137698.2193396,39.90996193885803,-2.39063827744578,1739137698.2193444,39.90996193885803,-3.0950592483950214,1739137698.2193491,39.90996193885803,-0.6108,1739137698.2193542,39.90996193885803,0.7248917341512101,1739137698.21936,39.90996193885803,0.0,1739137698.2193646,39.90996193885803,-0.5031735547807131,1739137698.21937,39.90996193885803,4.548095518300795,1739137698.2193747,39.90996193885803,1.2280652889319232 +1739137698.24198,39.929961919784546,42.64630588625796,1739137698.2419887,39.929961919784546,3.495093728558123,1739137698.2419987,39.929961919784546,68.7027138798856,1739137698.242011,39.929961919784546,38.93464627331604,1739137698.242018,39.929961919784546,0.03070228352635985,1739137698.242023,39.929961919784546,-2.39063827744578,1739137698.2420256,39.929961919784546,-3.0950592483950214,1739137698.2420285,39.929961919784546,-0.6108,1739137698.242031,39.929961919784546,0.7248917341512101,1739137698.2420342,39.929961919784546,0.0,1739137698.242037,39.929961919784546,-0.5031735547807131,1739137698.24204,39.929961919784546,4.548095518300795,1739137698.2420423,39.929961919784546,1.2280652889319232 +1739137698.2599823,39.94996190071106,42.64630588625796,1739137698.2599862,39.94996190071106,3.495093728558123,1739137698.2599905,39.94996190071106,68.7027138798856,1739137698.259995,39.94996190071106,38.93464627331604,1739137698.2599967,39.94996190071106,0.03070228352635985,1739137698.2599995,39.94996190071106,-2.39063827744578,1739137698.260002,39.94996190071106,-3.0950592483950214,1739137698.2600036,39.94996190071106,-0.6108,1739137698.2600057,39.94996190071106,0.7248917341512101,1739137698.2600079,39.94996190071106,0.0,1739137698.26001,39.94996190071106,-0.5031735547807131,1739137698.2600124,39.94996190071106,4.548095518300795,1739137698.2600148,39.94996190071106,1.2280652889319232 +1739137698.27964,39.96996188163757,42.64630588625796,1739137698.2796445,39.96996188163757,3.495093728558123,1739137698.279649,39.96996188163757,68.7027138798856,1739137698.279653,39.96996188163757,38.93464627331604,1739137698.2796555,39.96996188163757,0.03070228352635985,1739137698.279658,39.96996188163757,-2.39063827744578,1739137698.27966,39.96996188163757,-3.0950592483950214,1739137698.2796624,39.96996188163757,-0.6108,1739137698.2796643,39.96996188163757,0.7248917341512101,1739137698.279667,39.96996188163757,0.0,1739137698.2796688,39.96996188163757,-0.5031735547807131,1739137698.279671,39.96996188163757,4.548095518300795,1739137698.279673,39.96996188163757,1.2280652889319232 +1739137698.2997115,39.98996186256409,42.62479772084397,1739137698.2997143,39.98996186256409,3.364545006755497,1739137698.2997177,39.98996186256409,68.71363095726892,1739137698.2997205,39.98996186256409,39.088261433613695,1739137698.2997222,39.98996186256409,0.05371023893561619,1739137698.299724,39.98996186256409,-2.38914433778663,1739137698.299726,39.98996186256409,-2.9550655042768246,1739137698.2997277,39.98996186256409,-0.6108,1739137698.299729,39.98996186256409,0.7666419005872888,1739137698.299731,39.98996186256409,0.0,1739137698.2997324,39.98996186256409,-0.31766728068810207,1739137698.299734,39.98996186256409,4.550088469433626,1739137698.2997355,39.98996186256409,1.172645546399746 +1739137698.3188732,40.0099618434906,42.62479772084397,1739137698.3188753,40.0099618434906,3.364545006755497,1739137698.3188784,40.0099618434906,68.71363095726892,1739137698.3188813,40.0099618434906,39.088261433613695,1739137698.3188825,40.0099618434906,0.05371023893561619,1739137698.3188844,40.0099618434906,-2.38914433778663,1739137698.3188856,40.0099618434906,-2.9550655042768246,1739137698.318887,40.0099618434906,-0.6108,1739137698.3188882,40.0099618434906,0.7666419005872888,1739137698.31889,40.0099618434906,0.0,1739137698.3188913,40.0099618434906,-0.4060036458124573,1739137698.3188927,40.0099618434906,4.550088469433626,1739137698.3188944,40.0099618434906,1.172645546399746 +1739137698.338155,40.029961824417114,42.62479772084397,1739137698.338158,40.029961824417114,3.364545006755497,1739137698.3381612,40.029961824417114,68.71363095726892,1739137698.3381639,40.029961824417114,39.088261433613695,1739137698.3381655,40.029961824417114,0.05371023893561619,1739137698.338167,40.029961824417114,-2.38914433778663,1739137698.3381686,40.029961824417114,-2.9550655042768246,1739137698.3381698,40.029961824417114,-0.6108,1739137698.3381715,40.029961824417114,0.7666419005872888,1739137698.338173,40.029961824417114,0.0,1739137698.338174,40.029961824417114,-0.4060036458124573,1739137698.3381758,40.029961824417114,4.550088469433626,1739137698.338177,40.029961824417114,1.172645546399746 +1739137698.3577375,40.04996180534363,42.62479772084397,1739137698.3577397,40.04996180534363,3.364545006755497,1739137698.3577425,40.04996180534363,68.71363095726892,1739137698.3577452,40.04996180534363,39.088261433613695,1739137698.3577464,40.04996180534363,0.05371023893561619,1739137698.3577483,40.04996180534363,-2.38914433778663,1739137698.3577497,40.04996180534363,-2.9550655042768246,1739137698.3577511,40.04996180534363,-0.6108,1739137698.3577523,40.04996180534363,0.7666419005872888,1739137698.3577538,40.04996180534363,0.0,1739137698.3577552,40.04996180534363,-0.4060036458124573,1739137698.3577569,40.04996180534363,4.550088469433626,1739137698.357758,40.04996180534363,1.172645546399746 +1739137698.378544,40.06996178627014,42.62479772084397,1739137698.3785465,40.06996178627014,3.364545006755497,1739137698.3785493,40.06996178627014,68.71363095726892,1739137698.3785517,40.06996178627014,39.088261433613695,1739137698.3785534,40.06996178627014,0.05371023893561619,1739137698.3785548,40.06996178627014,-2.38914433778663,1739137698.3785565,40.06996178627014,-2.9550655042768246,1739137698.3785577,40.06996178627014,-0.6108,1739137698.3785589,40.06996178627014,0.7666419005872888,1739137698.3785605,40.06996178627014,0.0,1739137698.3785617,40.06996178627014,-0.4060036458124573,1739137698.3785634,40.06996178627014,4.550088469433626,1739137698.3785648,40.06996178627014,1.172645546399746 +1739137698.398096,40.089961767196655,42.62479772084397,1739137698.3980987,40.089961767196655,3.364545006755497,1739137698.3981016,40.089961767196655,68.71363095726892,1739137698.3981044,40.089961767196655,39.088261433613695,1739137698.3981056,40.089961767196655,0.05371023893561619,1739137698.3981073,40.089961767196655,-2.38914433778663,1739137698.3981087,40.089961767196655,-2.9550655042768246,1739137698.3981102,40.089961767196655,-0.6108,1739137698.3981113,40.089961767196655,0.7666419005872888,1739137698.398113,40.089961767196655,0.0,1739137698.3981142,40.089961767196655,-0.4060036458124573,1739137698.3981159,40.089961767196655,4.550088469433626,1739137698.398117,40.089961767196655,1.172645546399746 +1739137698.418542,40.10996174812317,42.60432450223199,1739137698.4185445,40.10996174812317,3.2391898898113958,1739137698.4185474,40.10996174812317,68.95240126603349,1739137698.4185505,40.10996174812317,38.97630030195345,1739137698.418552,40.10996174812317,0.0368020422734827,1739137698.4185534,40.10996174812317,-2.418428905031082,1739137698.4185548,40.10996174812317,-3.0653489990376155,1739137698.4185562,40.10996174812317,-0.6108,1739137698.4185574,40.10996174812317,0.7335578120964581,1739137698.4185593,40.10996174812317,0.0,1739137698.4185605,40.10996174812317,-0.3892812363602953,1739137698.418562,40.10996174812317,4.550749010309403,1739137698.4185634,40.10996174812317,1.130802104554725 +1739137698.4377897,40.12996172904968,42.60432450223199,1739137698.4377928,40.12996172904968,3.2391898898113958,1739137698.4377964,40.12996172904968,68.95240126603349,1739137698.4377995,40.12996172904968,38.97630030195345,1739137698.437801,40.12996172904968,0.0368020422734827,1739137698.4378026,40.12996172904968,-2.418428905031082,1739137698.437804,40.12996172904968,-3.0653489990376155,1739137698.437806,40.12996172904968,-0.6108,1739137698.437807,40.12996172904968,0.7335578120964581,1739137698.437809,40.12996172904968,0.0,1739137698.4378104,40.12996172904968,-0.39724429245826687,1739137698.4378119,40.12996172904968,4.550749010309403,1739137698.4378135,40.12996172904968,1.130802104554725 +1739137698.4575603,40.149961709976196,42.60432450223199,1739137698.457563,40.149961709976196,3.2391898898113958,1739137698.4575658,40.149961709976196,68.95240126603349,1739137698.4575682,40.149961709976196,38.97630030195345,1739137698.4575698,40.149961709976196,0.0368020422734827,1739137698.4575715,40.149961709976196,-2.418428905031082,1739137698.4575732,40.149961709976196,-3.0653489990376155,1739137698.4575746,40.149961709976196,-0.6108,1739137698.457576,40.149961709976196,0.7335578120964581,1739137698.4575775,40.149961709976196,0.0,1739137698.4575787,40.149961709976196,-0.39724429245826687,1739137698.4575803,40.149961709976196,4.550749010309403,1739137698.4575818,40.149961709976196,1.130802104554725 +1739137698.4777248,40.16996169090271,42.60432450223199,1739137698.477727,40.16996169090271,3.2391898898113958,1739137698.4777298,40.16996169090271,68.95240126603349,1739137698.4777327,40.16996169090271,38.97630030195345,1739137698.4777339,40.16996169090271,0.0368020422734827,1739137698.4777355,40.16996169090271,-2.418428905031082,1739137698.477737,40.16996169090271,-3.0653489990376155,1739137698.4777384,40.16996169090271,-0.6108,1739137698.4777398,40.16996169090271,0.7335578120964581,1739137698.4777412,40.16996169090271,0.0,1739137698.4777427,40.16996169090271,-0.39724429245826687,1739137698.477744,40.16996169090271,4.550749010309403,1739137698.4777453,40.16996169090271,1.130802104554725 +1739137698.497511,40.189961671829224,42.60432450223199,1739137698.4975135,40.189961671829224,3.2391898898113958,1739137698.4975164,40.189961671829224,68.95240126603349,1739137698.4975188,40.189961671829224,38.97630030195345,1739137698.4975204,40.189961671829224,0.0368020422734827,1739137698.4975219,40.189961671829224,-2.418428905031082,1739137698.4975235,40.189961671829224,-3.0653489990376155,1739137698.4975247,40.189961671829224,-0.6108,1739137698.497526,40.189961671829224,0.7335578120964581,1739137698.4975276,40.189961671829224,0.0,1739137698.4975288,40.189961671829224,-0.39724429245826687,1739137698.4975305,40.189961671829224,4.550749010309403,1739137698.4975317,40.189961671829224,1.130802104554725 +1739137698.5176048,40.20996165275574,42.5846321751648,1739137698.5176075,40.20996165275574,3.1185708674445554,1739137698.51761,40.20996165275574,69.11058621441316,1739137698.5176132,40.20996165275574,38.94869705815252,1739137698.5176146,40.20996165275574,0.03293758814135275,1739137698.517616,40.20996165275574,-2.4378833450927355,1739137698.5176177,40.20996165275574,-3.089511570584558,1739137698.517619,40.20996165275574,-0.6108,1739137698.5176203,40.20996165275574,0.7265021065712675,1739137698.5176218,40.20996165275574,0.0,1739137698.517623,40.20996165275574,-0.3277881043505309,1739137698.5176246,40.20996165275574,4.550078409801442,1739137698.517626,40.20996165275574,1.0873646027333002 +1739137698.537676,40.22996163368225,42.5846321751648,1739137698.5376785,40.22996163368225,3.1185708674445554,1739137698.5376818,40.22996163368225,69.11058621441316,1739137698.537685,40.22996163368225,38.94869705815252,1739137698.5376863,40.22996163368225,0.03293758814135275,1739137698.537688,40.22996163368225,-2.4378833450927355,1739137698.5376897,40.22996163368225,-3.089511570584558,1739137698.537691,40.22996163368225,-0.6108,1739137698.5376923,40.22996163368225,0.7265021065712675,1739137698.537694,40.22996163368225,0.0,1739137698.5376952,40.22996163368225,-0.3608624961620327,1739137698.5376968,40.22996163368225,4.550078409801442,1739137698.5376983,40.22996163368225,1.0873646027333002 +1739137698.5577848,40.249961614608765,42.5846321751648,1739137698.5577888,40.249961614608765,3.1185708674445554,1739137698.5577958,40.249961614608765,69.11058621441316,1739137698.557802,40.249961614608765,38.94869705815252,1739137698.5578046,40.249961614608765,0.03293758814135275,1739137698.5578084,40.249961614608765,-2.4378833450927355,1739137698.5578113,40.249961614608765,-3.089511570584558,1739137698.5578141,40.249961614608765,-0.6108,1739137698.557817,40.249961614608765,0.7265021065712675,1739137698.5578203,40.249961614608765,0.0,1739137698.5578227,40.249961614608765,-0.3608624961620327,1739137698.557825,40.249961614608765,4.550078409801442,1739137698.5578275,40.249961614608765,1.0873646027333002 +1739137698.578181,40.26996159553528,42.5846321751648,1739137698.5781841,40.26996159553528,3.1185708674445554,1739137698.5781875,40.26996159553528,69.11058621441316,1739137698.5781906,40.26996159553528,38.94869705815252,1739137698.5781922,40.26996159553528,0.03293758814135275,1739137698.578194,40.26996159553528,-2.4378833450927355,1739137698.5781958,40.26996159553528,-3.089511570584558,1739137698.5781972,40.26996159553528,-0.6108,1739137698.5781987,40.26996159553528,0.7265021065712675,1739137698.5782006,40.26996159553528,0.0,1739137698.578202,40.26996159553528,-0.3608624961620327,1739137698.5782037,40.26996159553528,4.550078409801442,1739137698.5782053,40.26996159553528,1.0873646027333002 +1739137698.597812,40.28996157646179,42.5846321751648,1739137698.5978148,40.28996157646179,3.1185708674445554,1739137698.597818,40.28996157646179,69.11058621441316,1739137698.597821,40.28996157646179,38.94869705815252,1739137698.5978224,40.28996157646179,0.03293758814135275,1739137698.5978246,40.28996157646179,-2.4378833450927355,1739137698.597826,40.28996157646179,-3.089511570584558,1739137698.5978277,40.28996157646179,-0.6108,1739137698.597829,40.28996157646179,0.7265021065712675,1739137698.597831,40.28996157646179,0.0,1739137698.5978324,40.28996157646179,-0.3608624961620327,1739137698.5978343,40.28996157646179,4.550078409801442,1739137698.5978355,40.28996157646179,1.0873646027333002 +1739137698.6179557,40.309961557388306,42.5846321751648,1739137698.6179583,40.309961557388306,3.1185708674445554,1739137698.617962,40.309961557388306,69.11058621441316,1739137698.6179652,40.309961557388306,38.94869705815252,1739137698.617967,40.309961557388306,0.03293758814135275,1739137698.617969,40.309961557388306,-2.4378833450927355,1739137698.617971,40.309961557388306,-3.089511570584558,1739137698.6179724,40.309961557388306,-0.6108,1739137698.6179743,40.309961557388306,0.7265021065712675,1739137698.617976,40.309961557388306,0.0,1739137698.6179776,40.309961557388306,-0.3608624961620327,1739137698.6179798,40.309961557388306,4.550078409801442,1739137698.6179817,40.309961557388306,1.0873646027333002 +1739137698.6386178,40.32996153831482,42.56544661683969,1739137698.6386213,40.32996153831482,3.0019898159979004,1739137698.6386256,40.32996153831482,69.11243085797648,1739137698.638629,40.32996153831482,39.03355452115501,1739137698.638631,40.32996153831482,0.04481763296170114,1739137698.6386333,40.32996153831482,-2.4445314495904813,1739137698.638635,40.32996153831482,-3.000600489544916,1739137698.638637,40.32996153831482,-0.6108,1739137698.6386387,40.32996153831482,0.7528046875249089,1739137698.6386406,40.32996153831482,0.0,1739137698.6386425,40.32996153831482,-0.2549477280520973,1739137698.6386442,40.32996153831482,4.5480753797029125,1739137698.6386461,40.32996153831482,1.0581880446336804 +1739137698.6581166,40.34996151924133,42.56544661683969,1739137698.6581194,40.34996151924133,3.0019898159979004,1739137698.6581233,40.34996151924133,69.11243085797648,1739137698.6581268,40.34996151924133,39.03355452115501,1739137698.6581285,40.34996151924133,0.04481763296170114,1739137698.6581304,40.34996151924133,-2.4445314495904813,1739137698.6581323,40.34996151924133,-3.000600489544916,1739137698.658134,40.34996151924133,-0.6108,1739137698.6581357,40.34996151924133,0.7528046875249089,1739137698.6581373,40.34996151924133,0.0,1739137698.6581392,40.34996151924133,-0.3053833571087715,1739137698.658141,40.34996151924133,4.5480753797029125,1739137698.6581428,40.34996151924133,1.0581880446336804 +1739137698.6786332,40.36996150016785,42.56544661683969,1739137698.6786375,40.36996150016785,3.0019898159979004,1739137698.678642,40.36996150016785,69.11243085797648,1739137698.678646,40.36996150016785,39.03355452115501,1739137698.678648,40.36996150016785,0.04481763296170114,1739137698.6786501,40.36996150016785,-2.4445314495904813,1739137698.678652,40.36996150016785,-3.000600489544916,1739137698.678654,40.36996150016785,-0.6108,1739137698.6786559,40.36996150016785,0.7528046875249089,1739137698.6786578,40.36996150016785,0.0,1739137698.6786597,40.36996150016785,-0.3053833571087715,1739137698.6786625,40.36996150016785,4.5480753797029125,1739137698.6786644,40.36996150016785,1.0581880446336804 +1739137698.698056,40.38996148109436,42.56544661683969,1739137698.698059,40.38996148109436,3.0019898159979004,1739137698.6980627,40.38996148109436,69.11243085797648,1739137698.698066,40.38996148109436,39.03355452115501,1739137698.6980677,40.38996148109436,0.04481763296170114,1739137698.6980698,40.38996148109436,-2.4445314495904813,1739137698.6980715,40.38996148109436,-3.000600489544916,1739137698.6980734,40.38996148109436,-0.6108,1739137698.6980748,40.38996148109436,0.7528046875249089,1739137698.6980767,40.38996148109436,0.0,1739137698.6980782,40.38996148109436,-0.3053833571087715,1739137698.6980805,40.38996148109436,4.5480753797029125,1739137698.698082,40.38996148109436,1.0581880446336804 +1739137698.718053,40.409961462020874,42.56544661683969,1739137698.7180567,40.409961462020874,3.0019898159979004,1739137698.7180638,40.409961462020874,69.11243085797648,1739137698.7180724,40.409961462020874,39.03355452115501,1739137698.7180765,40.409961462020874,0.04481763296170114,1739137698.718081,40.409961462020874,-2.4445314495904813,1739137698.718085,40.409961462020874,-3.000600489544916,1739137698.7180908,40.409961462020874,-0.6108,1739137698.718098,40.409961462020874,0.7528046875249089,1739137698.718102,40.409961462020874,0.0,1739137698.7181058,40.409961462020874,-0.3053833571087715,1739137698.7181103,40.409961462020874,4.5480753797029125,1739137698.7181146,40.409961462020874,1.0581880446336804 +1739137698.7384646,40.42996144294739,42.54648474860735,1739137698.7384808,40.42996144294739,2.8886134019760767,1739137698.738489,40.42996144294739,69.27295391360722,1739137698.7384934,40.42996144294739,38.960589714538195,1739137698.7384953,40.42996144294739,0.034602560035347354,1739137698.7384973,40.42996144294739,-2.4693572309951155,1739137698.7384992,40.42996144294739,-3.0593727992953053,1739137698.7385008,40.42996144294739,-0.6108,1739137698.7385025,40.42996144294739,0.7353134648898195,1739137698.7385044,40.42996144294739,0.0,1739137698.7385063,40.42996144294739,-0.2835096225422481,1739137698.738508,40.42996144294739,4.544736064811713,1739137698.7385101,40.42996144294739,1.0292391567146462 +1739137698.7579799,40.4499614238739,42.54648474860735,1739137698.757984,40.4499614238739,2.8886134019760767,1739137698.7579892,40.4499614238739,69.27295391360722,1739137698.7579966,40.4499614238739,38.960589714538195,1739137698.7580016,40.4499614238739,0.034602560035347354,1739137698.7580047,40.4499614238739,-2.4693572309951155,1739137698.7580066,40.4499614238739,-3.0593727992953053,1739137698.7580082,40.4499614238739,-0.6108,1739137698.7580104,40.4499614238739,0.7353134648898195,1739137698.758012,40.4499614238739,0.0,1739137698.7580137,40.4499614238739,-0.29392569182482664,1739137698.7580154,40.4499614238739,4.544736064811713,1739137698.7580173,40.4499614238739,1.0292391567146462 +1739137698.7785366,40.469961404800415,42.54648474860735,1739137698.7785392,40.469961404800415,2.8886134019760767,1739137698.7785428,40.469961404800415,69.27295391360722,1739137698.7785463,40.469961404800415,38.960589714538195,1739137698.7785485,40.469961404800415,0.034602560035347354,1739137698.7785506,40.469961404800415,-2.4693572309951155,1739137698.7785523,40.469961404800415,-3.0593727992953053,1739137698.778554,40.469961404800415,-0.6108,1739137698.7785556,40.469961404800415,0.7353134648898195,1739137698.778558,40.469961404800415,0.0,1739137698.7785594,40.469961404800415,-0.29392569182482664,1739137698.7785614,40.469961404800415,4.544736064811713,1739137698.7785628,40.469961404800415,1.0292391567146462 +1739137698.798267,40.48996138572693,42.54648474860735,1739137698.7982702,40.48996138572693,2.8886134019760767,1739137698.7982743,40.48996138572693,69.27295391360722,1739137698.7982776,40.48996138572693,38.960589714538195,1739137698.7982795,40.48996138572693,0.034602560035347354,1739137698.7982817,40.48996138572693,-2.4693572309951155,1739137698.7982836,40.48996138572693,-3.0593727992953053,1739137698.7982852,40.48996138572693,-0.6108,1739137698.798287,40.48996138572693,0.7353134648898195,1739137698.7982886,40.48996138572693,0.0,1739137698.7982903,40.48996138572693,-0.29392569182482664,1739137698.7982922,40.48996138572693,4.544736064811713,1739137698.7982938,40.48996138572693,1.0292391567146462 +1739137698.8182294,40.50996136665344,42.54648474860735,1739137698.8182325,40.50996136665344,2.8886134019760767,1739137698.8182359,40.50996136665344,69.27295391360722,1739137698.8182395,40.50996136665344,38.960589714538195,1739137698.8182414,40.50996136665344,0.034602560035347354,1739137698.8182435,40.50996136665344,-2.4693572309951155,1739137698.8182454,40.50996136665344,-3.0593727992953053,1739137698.818247,40.50996136665344,-0.6108,1739137698.8182487,40.50996136665344,0.7353134648898195,1739137698.8182504,40.50996136665344,0.0,1739137698.8182523,40.50996136665344,-0.29392569182482664,1739137698.8182542,40.50996136665344,4.544736064811713,1739137698.818256,40.50996136665344,1.0292391567146462 +1739137698.8387759,40.529961347579956,42.54648474860735,1739137698.8387806,40.529961347579956,2.8886134019760767,1739137698.8387883,40.529961347579956,69.27295391360722,1739137698.8387976,40.529961347579956,38.960589714538195,1739137698.838802,40.529961347579956,0.034602560035347354,1739137698.838805,40.529961347579956,-2.4693572309951155,1739137698.8388069,40.529961347579956,-3.0593727992953053,1739137698.8388085,40.529961347579956,-0.6108,1739137698.8388102,40.529961347579956,0.7353134648898195,1739137698.8388119,40.529961347579956,0.0,1739137698.8388138,40.529961347579956,-0.29392569182482664,1739137698.8388155,40.529961347579956,4.544736064811713,1739137698.8388174,40.529961347579956,1.0292391567146462 +1739137698.858571,40.54996132850647,42.52761145905976,1739137698.8585758,40.54996132850647,2.778440318731171,1739137698.8585808,40.54996132850647,69.42043278869116,1739137698.858586,40.54996132850647,38.89991945252132,1739137698.8585894,40.54996132850647,0.02590564673964342,1739137698.8585932,40.54996132850647,-2.492510937229674,1739137698.858599,40.54996132850647,-3.101941732290121,1739137698.8586016,40.54996132850647,-0.6108,1739137698.8586056,40.54996132850647,0.7228988563253878,1739137698.8586085,40.54996132850647,0.0,1739137698.8586109,40.54996132850647,-0.2627879905539035,1739137698.8586137,40.54996132850647,4.540054013171417,1739137698.8586164,40.54996132850647,1.000514331081945 +1739137698.8785892,40.56996130943298,42.52761145905976,1739137698.8785944,40.56996130943298,2.778440318731171,1739137698.8786006,40.56996130943298,69.42043278869116,1739137698.8786101,40.56996130943298,38.89991945252132,1739137698.8786151,40.56996130943298,0.02590564673964342,1739137698.8786209,40.56996130943298,-2.492510937229674,1739137698.8786235,40.56996130943298,-3.101941732290121,1739137698.8786266,40.56996130943298,-0.6108,1739137698.8786294,40.56996130943298,0.7228988563253878,1739137698.8786325,40.56996130943298,0.0,1739137698.878635,40.56996130943298,-0.27761547475655735,1739137698.8786378,40.56996130943298,4.540054013171417,1739137698.878642,40.56996130943298,1.000514331081945 +1739137698.8977892,40.5899612903595,42.52761145905976,1739137698.8977919,40.5899612903595,2.778440318731171,1739137698.8977954,40.5899612903595,69.42043278869116,1739137698.8978028,40.5899612903595,38.89991945252132,1739137698.897805,40.5899612903595,0.02590564673964342,1739137698.897808,40.5899612903595,-2.492510937229674,1739137698.897812,40.5899612903595,-3.101941732290121,1739137698.8978155,40.5899612903595,-0.6108,1739137698.8978176,40.5899612903595,0.7228988563253878,1739137698.8978212,40.5899612903595,0.0,1739137698.8978238,40.5899612903595,-0.27761547475655735,1739137698.8978288,40.5899612903595,4.540054013171417,1739137698.8978314,40.5899612903595,1.000514331081945 +1739137698.9175627,40.60996127128601,42.52761145905976,1739137698.9175649,40.60996127128601,2.778440318731171,1739137698.9175675,40.60996127128601,69.42043278869116,1739137698.91757,40.60996127128601,38.89991945252132,1739137698.9175713,40.60996127128601,0.02590564673964342,1739137698.917573,40.60996127128601,-2.492510937229674,1739137698.9175744,40.60996127128601,-3.101941732290121,1739137698.9175756,40.60996127128601,-0.6108,1739137698.917577,40.60996127128601,0.7228988563253878,1739137698.9175782,40.60996127128601,0.0,1739137698.9175794,40.60996127128601,-0.27761547475655735,1739137698.917581,40.60996127128601,4.540054013171417,1739137698.9175823,40.60996127128601,1.000514331081945 +1739137698.9374938,40.629961252212524,42.52761145905976,1739137698.9374957,40.629961252212524,2.778440318731171,1739137698.9374986,40.629961252212524,69.42043278869116,1739137698.9375012,40.629961252212524,38.89991945252132,1739137698.9375024,40.629961252212524,0.02590564673964342,1739137698.9375043,40.629961252212524,-2.492510937229674,1739137698.9375057,40.629961252212524,-3.101941732290121,1739137698.9375074,40.629961252212524,-0.6108,1739137698.9375086,40.629961252212524,0.7228988563253878,1739137698.9375098,40.629961252212524,0.0,1739137698.9375112,40.629961252212524,-0.27761547475655735,1739137698.9375129,40.629961252212524,4.540054013171417,1739137698.9375143,40.629961252212524,1.000514331081945 +1739137698.9576774,40.64996123313904,42.50870344677576,1739137698.9576795,40.64996123313904,2.6714693280598576,1739137698.9576821,40.64996123313904,69.56433674509233,1739137698.957685,40.64996123313904,38.841967796648014,1739137698.9576864,40.64996123313904,0.018755767118910853,1739137698.9576883,40.64996123313904,-2.515298742377901,1739137698.9576895,40.64996123313904,-3.137904222126268,1739137698.957691,40.64996123313904,-0.6108,1739137698.9576921,40.64996123313904,0.7125743959111386,1739137698.9576936,40.64996123313904,0.0,1739137698.957695,40.64996123313904,-0.2429084910386336,1739137698.9576964,40.64996123313904,4.53402012597847,1739137698.9576979,40.64996123313904,0.9720100303095756 +1739137698.97816,40.66996121406555,42.50870344677576,1739137698.9781623,40.66996121406555,2.6714693280598576,1739137698.978165,40.66996121406555,69.56433674509233,1739137698.9781678,40.66996121406555,38.841967796648014,1739137698.9781692,40.66996121406555,0.018755767118910853,1739137698.9781709,40.66996121406555,-2.515298742377901,1739137698.978172,40.66996121406555,-3.137904222126268,1739137698.9781735,40.66996121406555,-0.6108,1739137698.978175,40.66996121406555,0.7125743959111386,1739137698.9781764,40.66996121406555,0.0,1739137698.9781775,40.66996121406555,-0.259435634398437,1739137698.978179,40.66996121406555,4.53402012597847,1739137698.9781804,40.66996121406555,0.9720100303095756 +1739137698.9974687,40.689961194992065,42.50870344677576,1739137698.997471,40.689961194992065,2.6714693280598576,1739137698.9974735,40.689961194992065,69.56433674509233,1739137698.997476,40.689961194992065,38.841967796648014,1739137698.9974773,40.689961194992065,0.018755767118910853,1739137698.997479,40.689961194992065,-2.515298742377901,1739137698.9974802,40.689961194992065,-3.137904222126268,1739137698.9974816,40.689961194992065,-0.6108,1739137698.9974828,40.689961194992065,0.7125743959111386,1739137698.9974842,40.689961194992065,0.0,1739137698.9974856,40.689961194992065,-0.259435634398437,1739137698.9974868,40.689961194992065,4.53402012597847,1739137698.9974885,40.689961194992065,0.9720100303095756 +1739137699.0174816,40.70996117591858,42.50870344677576,1739137699.0174837,40.70996117591858,2.6714693280598576,1739137699.0174863,40.70996117591858,69.56433674509233,1739137699.017489,40.70996117591858,38.841967796648014,1739137699.0174901,40.70996117591858,0.018755767118910853,1739137699.017492,40.70996117591858,-2.515298742377901,1739137699.0174932,40.70996117591858,-3.137904222126268,1739137699.0174944,40.70996117591858,-0.6108,1739137699.0174959,40.70996117591858,0.7125743959111386,1739137699.0174973,40.70996117591858,0.0,1739137699.0174987,40.70996117591858,-0.259435634398437,1739137699.0175002,40.70996117591858,4.53402012597847,1739137699.0175014,40.70996117591858,0.9720100303095756 +1739137699.0375588,40.72996115684509,42.50870344677576,1739137699.0375612,40.72996115684509,2.6714693280598576,1739137699.0375638,40.72996115684509,69.56433674509233,1739137699.0375667,40.72996115684509,38.841967796648014,1739137699.037568,40.72996115684509,0.018755767118910853,1739137699.0375695,40.72996115684509,-2.515298742377901,1739137699.037571,40.72996115684509,-3.137904222126268,1739137699.0375724,40.72996115684509,-0.6108,1739137699.0375736,40.72996115684509,0.7125743959111386,1739137699.037575,40.72996115684509,0.0,1739137699.0375764,40.72996115684509,-0.259435634398437,1739137699.0375779,40.72996115684509,4.53402012597847,1739137699.0375793,40.72996115684509,0.9720100303095756 +1739137699.057408,40.749961137771606,42.50870344677576,1739137699.0574102,40.749961137771606,2.6714693280598576,1739137699.0574129,40.749961137771606,69.56433674509233,1739137699.0574157,40.749961137771606,38.841967796648014,1739137699.057417,40.749961137771606,0.018755767118910853,1739137699.0574188,40.749961137771606,-2.515298742377901,1739137699.05742,40.749961137771606,-3.137904222126268,1739137699.0574217,40.749961137771606,-0.6108,1739137699.0574226,40.749961137771606,0.7125743959111386,1739137699.057424,40.749961137771606,0.0,1739137699.0574255,40.749961137771606,-0.259435634398437,1739137699.057427,40.749961137771606,4.53402012597847,1739137699.0574281,40.749961137771606,0.9720100303095756 +1739137699.0782132,40.76996111869812,42.489648932945585,1739137699.0782156,40.76996111869812,2.5676997018243792,1739137699.0782185,40.76996111869812,69.6388609065606,1739137699.078221,40.76996111869812,38.852227577860795,1739137699.0782223,40.76996111869812,0.020021584281526995,1739137699.0782242,40.76996111869812,-2.5305930819782754,1739137699.0782256,40.76996111869812,-3.104283842941293,1739137699.078227,40.76996111869812,-0.6108,1739137699.0782282,40.76996111869812,0.7222219298178066,1739137699.0782297,40.76996111869812,0.0,1739137699.0782313,40.76996111869812,-0.1870146606656161,1739137699.0782325,40.76996111869812,4.526622586324551,1739137699.078234,40.76996111869812,0.9437227856787939 +1739137699.0974872,40.789961099624634,42.489648932945585,1739137699.097489,40.789961099624634,2.5676997018243792,1739137699.097492,40.789961099624634,69.6388609065606,1739137699.0974948,40.789961099624634,38.852227577860795,1739137699.0974963,40.789961099624634,0.020021584281526995,1739137699.097498,40.789961099624634,-2.5305930819782754,1739137699.0974994,40.789961099624634,-3.104283842941293,1739137699.0975006,40.789961099624634,-0.6108,1739137699.097502,40.789961099624634,0.7222219298178066,1739137699.0975034,40.789961099624634,0.0,1739137699.0975046,40.789961099624634,-0.22150085586098722,1739137699.097506,40.789961099624634,4.526622586324551,1739137699.0975072,40.789961099624634,0.9437227856787939 +1739137699.1175063,40.80996108055115,42.489648932945585,1739137699.1175086,40.80996108055115,2.5676997018243792,1739137699.1175115,40.80996108055115,69.6388609065606,1739137699.117514,40.80996108055115,38.852227577860795,1739137699.1175153,40.80996108055115,0.020021584281526995,1739137699.117517,40.80996108055115,-2.5305930819782754,1739137699.1175184,40.80996108055115,-3.104283842941293,1739137699.1175199,40.80996108055115,-0.6108,1739137699.1175208,40.80996108055115,0.7222219298178066,1739137699.1175225,40.80996108055115,0.0,1739137699.1175237,40.80996108055115,-0.22150085586098722,1739137699.1175256,40.80996108055115,4.526622586324551,1739137699.117527,40.80996108055115,0.9437227856787939 +1739137699.1375778,40.82996106147766,42.489648932945585,1739137699.13758,40.82996106147766,2.5676997018243792,1739137699.1375825,40.82996106147766,69.6388609065606,1739137699.1375854,40.82996106147766,38.852227577860795,1739137699.1375866,40.82996106147766,0.020021584281526995,1739137699.1375887,40.82996106147766,-2.5305930819782754,1739137699.13759,40.82996106147766,-3.104283842941293,1739137699.1375914,40.82996106147766,-0.6108,1739137699.1375926,40.82996106147766,0.7222219298178066,1739137699.1375942,40.82996106147766,0.0,1739137699.1375954,40.82996106147766,-0.22150085586098722,1739137699.1375966,40.82996106147766,4.526622586324551,1739137699.1375983,40.82996106147766,0.9437227856787939 +1739137699.15749,40.849961042404175,42.489648932945585,1739137699.1574924,40.849961042404175,2.5676997018243792,1739137699.1574953,40.849961042404175,69.6388609065606,1739137699.157498,40.849961042404175,38.852227577860795,1739137699.157499,40.849961042404175,0.020021584281526995,1739137699.157501,40.849961042404175,-2.5305930819782754,1739137699.1575022,40.849961042404175,-3.104283842941293,1739137699.1575038,40.849961042404175,-0.6108,1739137699.157505,40.849961042404175,0.7222219298178066,1739137699.1575065,40.849961042404175,0.0,1739137699.157508,40.849961042404175,-0.22150085586098722,1739137699.1575093,40.849961042404175,4.526622586324551,1739137699.1575105,40.849961042404175,0.9437227856787939 +1739137699.1775227,40.86996102333069,42.470347411726195,1739137699.177525,40.86996102333069,2.4671315945534875,1739137699.177528,40.86996102333069,69.77752648950774,1739137699.1775303,40.86996102333069,38.798192467910255,1739137699.1775317,40.86996102333069,0.013354914872044661,1739137699.1775334,40.86996102333069,-2.552521215233876,1739137699.1775348,40.86996102333069,-3.128526663587563,1739137699.1775362,40.86996102333069,-0.6108,1739137699.1775374,40.86996102333069,0.7152522984531645,1739137699.1775389,40.86996102333069,0.0,1739137699.17754,40.86996102333069,-0.18121146158760074,1739137699.177542,40.86996102333069,4.517846765578092,1739137699.1775432,40.86996102333069,0.9156491954691982 +1739137699.197462,40.8899610042572,42.470347411726195,1739137699.1974642,40.8899610042572,2.4671315945534875,1739137699.197467,40.8899610042572,69.77752648950774,1739137699.1974697,40.8899610042572,38.798192467910255,1739137699.197471,40.8899610042572,0.013354914872044661,1739137699.1974728,40.8899610042572,-2.552521215233876,1739137699.1974742,40.8899610042572,-3.128526663587563,1739137699.1974757,40.8899610042572,-0.6108,1739137699.1974769,40.8899610042572,0.7152522984531645,1739137699.197478,40.8899610042572,0.0,1739137699.1974795,40.8899610042572,-0.2003968970160337,1739137699.1974812,40.8899610042572,4.517846765578092,1739137699.1974826,40.8899610042572,0.9156491954691982 +1739137699.2174704,40.909960985183716,42.470347411726195,1739137699.2174728,40.909960985183716,2.4671315945534875,1739137699.2174757,40.909960985183716,69.77752648950774,1739137699.217478,40.909960985183716,38.798192467910255,1739137699.2174797,40.909960985183716,0.013354914872044661,1739137699.2174811,40.909960985183716,-2.552521215233876,1739137699.2174828,40.909960985183716,-3.128526663587563,1739137699.217484,40.909960985183716,-0.6108,1739137699.2174854,40.909960985183716,0.7152522984531645,1739137699.2174866,40.909960985183716,0.0,1739137699.217488,40.909960985183716,-0.2003968970160337,1739137699.2174897,40.909960985183716,4.517846765578092,1739137699.217491,40.909960985183716,0.9156491954691982 +1739137699.2375176,40.92996096611023,42.470347411726195,1739137699.2375202,40.92996096611023,2.4671315945534875,1739137699.2375224,40.92996096611023,69.77752648950774,1739137699.2375252,40.92996096611023,38.798192467910255,1739137699.2375264,40.92996096611023,0.013354914872044661,1739137699.2375283,40.92996096611023,-2.552521215233876,1739137699.2375298,40.92996096611023,-3.128526663587563,1739137699.2375312,40.92996096611023,-0.6108,1739137699.2375324,40.92996096611023,0.7152522984531645,1739137699.237534,40.92996096611023,0.0,1739137699.2375352,40.92996096611023,-0.2003968970160337,1739137699.2375364,40.92996096611023,4.517846765578092,1739137699.2375379,40.92996096611023,0.9156491954691982 +1739137699.2575855,40.94996094703674,42.470347411726195,1739137699.257588,40.94996094703674,2.4671315945534875,1739137699.257591,40.94996094703674,69.77752648950774,1739137699.257594,40.94996094703674,38.798192467910255,1739137699.257596,40.94996094703674,0.013354914872044661,1739137699.257598,40.94996094703674,-2.552521215233876,1739137699.2575998,40.94996094703674,-3.128526663587563,1739137699.2576013,40.94996094703674,-0.6108,1739137699.257603,40.94996094703674,0.7152522984531645,1739137699.2576044,40.94996094703674,0.0,1739137699.2576058,40.94996094703674,-0.2003968970160337,1739137699.2576075,40.94996094703674,4.517846765578092,1739137699.257609,40.94996094703674,0.9156491954691982 +1739137699.2775707,40.96996092796326,42.470347411726195,1739137699.277573,40.96996092796326,2.4671315945534875,1739137699.2775764,40.96996092796326,69.77752648950774,1739137699.277579,40.96996092796326,38.798192467910255,1739137699.2775803,40.96996092796326,0.013354914872044661,1739137699.277582,40.96996092796326,-2.552521215233876,1739137699.2775834,40.96996092796326,-3.128526663587563,1739137699.2775846,40.96996092796326,-0.6108,1739137699.277586,40.96996092796326,0.7152522984531645,1739137699.2775872,40.96996092796326,0.0,1739137699.2775888,40.96996092796326,-0.2003968970160337,1739137699.27759,40.96996092796326,4.517846765578092,1739137699.2775912,40.96996092796326,0.9156491954691982 +1739137699.2977755,40.98996090888977,42.45070943894125,1739137699.297778,40.98996090888977,2.369766350686043,1739137699.297781,40.98996090888977,69.86295070072504,1739137699.2977839,40.98996090888977,38.79637187719417,1739137699.2977853,40.98996090888977,0.013130296536942556,1739137699.297787,40.98996090888977,-2.568819966008486,1739137699.2977884,40.98996090888977,-3.0989585197147824,1739137699.29779,40.98996090888977,-0.6108,1739137699.2977912,40.98996090888977,0.7237619955921049,1739137699.2977927,40.98996090888977,0.0,1739137699.2977943,40.98996090888977,-0.13095756043884862,1739137699.2977962,40.98996090888977,4.507675105809126,1739137699.2977977,40.98996090888977,0.8877859233000891 +1739137699.3185954,41.009960889816284,42.45070943894125,1739137699.318598,41.009960889816284,2.369766350686043,1739137699.3186018,41.009960889816284,69.86295070072504,1739137699.3186054,41.009960889816284,38.79637187719417,1739137699.3186069,41.009960889816284,0.013130296536942556,1739137699.3186092,41.009960889816284,-2.568819966008486,1739137699.318611,41.009960889816284,-3.0989585197147824,1739137699.318613,41.009960889816284,-0.6108,1739137699.3186147,41.009960889816284,0.7237619955921049,1739137699.3186166,41.009960889816284,0.0,1739137699.3186183,41.009960889816284,-0.16402392770798424,1739137699.3186202,41.009960889816284,4.507675105809126,1739137699.3186219,41.009960889816284,0.8877859233000891 +1739137699.3383453,41.0299608707428,42.45070943894125,1739137699.3383482,41.0299608707428,2.369766350686043,1739137699.3383517,41.0299608707428,69.86295070072504,1739137699.3383553,41.0299608707428,38.79637187719417,1739137699.338357,41.0299608707428,0.013130296536942556,1739137699.338359,41.0299608707428,-2.568819966008486,1739137699.338361,41.0299608707428,-3.0989585197147824,1739137699.338363,41.0299608707428,-0.6108,1739137699.3383646,41.0299608707428,0.7237619955921049,1739137699.3383667,41.0299608707428,0.0,1739137699.3383682,41.0299608707428,-0.16402392770798424,1739137699.3383703,41.0299608707428,4.507675105809126,1739137699.3383718,41.0299608707428,0.8877859233000891 +1739137699.3576453,41.04996085166931,42.45070943894125,1739137699.3576477,41.04996085166931,2.369766350686043,1739137699.3576508,41.04996085166931,69.86295070072504,1739137699.3576531,41.04996085166931,38.79637187719417,1739137699.3576548,41.04996085166931,0.013130296536942556,1739137699.3576565,41.04996085166931,-2.568819966008486,1739137699.3576581,41.04996085166931,-3.0989585197147824,1739137699.3576593,41.04996085166931,-0.6108,1739137699.3576605,41.04996085166931,0.7237619955921049,1739137699.357662,41.04996085166931,0.0,1739137699.3576632,41.04996085166931,-0.16402392770798424,1739137699.3576646,41.04996085166931,4.507675105809126,1739137699.3576658,41.04996085166931,0.8877859233000891 +1739137699.3773878,41.069960832595825,42.45070943894125,1739137699.37739,41.069960832595825,2.369766350686043,1739137699.3773923,41.069960832595825,69.86295070072504,1739137699.377395,41.069960832595825,38.79637187719417,1739137699.377396,41.069960832595825,0.013130296536942556,1739137699.377398,41.069960832595825,-2.568819966008486,1739137699.3773994,41.069960832595825,-3.0989585197147824,1739137699.3774009,41.069960832595825,-0.6108,1739137699.3774018,41.069960832595825,0.7237619955921049,1739137699.3774035,41.069960832595825,0.0,1739137699.3774047,41.069960832595825,-0.16402392770798424,1739137699.377406,41.069960832595825,4.507675105809126,1739137699.3774073,41.069960832595825,0.8877859233000891 +1739137699.3974068,41.08996081352234,42.43061334851039,1739137699.3974087,41.08996081352234,2.2754056090726467,1739137699.3974113,41.08996081352234,69.98217340685657,1739137699.397414,41.08996081352234,38.753168217044916,1739137699.3974152,41.08996081352234,0.008155332797749958,1739137699.3974166,41.08996081352234,-2.5891083026121837,1739137699.3974183,41.08996081352234,-3.105156912257113,1739137699.3974195,41.08996081352234,-0.6108,1739137699.397421,41.08996081352234,0.7219697539313209,1739137699.3974223,41.08996081352234,0.0,1739137699.3974233,41.08996081352234,-0.11925267884927969,1739137699.3974247,41.08996081352234,4.496086976214561,1739137699.397426,41.08996081352234,0.8625420857443675 +1739137699.4173658,41.10996079444885,42.43061334851039,1739137699.4173682,41.10996079444885,2.2754056090726467,1739137699.4173706,41.10996079444885,69.98217340685657,1739137699.4173732,41.10996079444885,38.753168217044916,1739137699.4173744,41.10996079444885,0.008155332797749958,1739137699.417376,41.10996079444885,-2.5891083026121837,1739137699.4173775,41.10996079444885,-3.105156912257113,1739137699.4173787,41.10996079444885,-0.6108,1739137699.4173799,41.10996079444885,0.7219697539313209,1739137699.417381,41.10996079444885,0.0,1739137699.4173825,41.10996079444885,-0.14057233181304662,1739137699.4173837,41.10996079444885,4.496086976214561,1739137699.4173849,41.10996079444885,0.8625420857443675 +1739137699.4376125,41.129960775375366,42.43061334851039,1739137699.4376152,41.129960775375366,2.2754056090726467,1739137699.4376185,41.129960775375366,69.98217340685657,1739137699.4376214,41.129960775375366,38.753168217044916,1739137699.4376228,41.129960775375366,0.008155332797749958,1739137699.4376247,41.129960775375366,-2.5891083026121837,1739137699.4376264,41.129960775375366,-3.105156912257113,1739137699.4376276,41.129960775375366,-0.6108,1739137699.437629,41.129960775375366,0.7219697539313209,1739137699.4376307,41.129960775375366,0.0,1739137699.437632,41.129960775375366,-0.14057233181304662,1739137699.4376335,41.129960775375366,4.496086976214561,1739137699.4376347,41.129960775375366,0.8625420857443675 +1739137699.4575799,41.14996075630188,42.43061334851039,1739137699.4575822,41.14996075630188,2.2754056090726467,1739137699.457585,41.14996075630188,69.98217340685657,1739137699.457588,41.14996075630188,38.753168217044916,1739137699.4575894,41.14996075630188,0.008155332797749958,1739137699.4575913,41.14996075630188,-2.5891083026121837,1739137699.4575925,41.14996075630188,-3.105156912257113,1739137699.4575942,41.14996075630188,-0.6108,1739137699.4575953,41.14996075630188,0.7219697539313209,1739137699.457597,41.14996075630188,0.0,1739137699.4575982,41.14996075630188,-0.14057233181304662,1739137699.4576,41.14996075630188,4.496086976214561,1739137699.4576013,41.14996075630188,0.8625420857443675 +1739137699.4775977,41.169960737228394,42.43061334851039,1739137699.4776003,41.169960737228394,2.2754056090726467,1739137699.477603,41.169960737228394,69.98217340685657,1739137699.477606,41.169960737228394,38.753168217044916,1739137699.4776077,41.169960737228394,0.008155332797749958,1739137699.4776094,41.169960737228394,-2.5891083026121837,1739137699.477611,41.169960737228394,-3.105156912257113,1739137699.4776125,41.169960737228394,-0.6108,1739137699.4776142,41.169960737228394,0.7219697539313209,1739137699.4776158,41.169960737228394,0.0,1739137699.4776173,41.169960737228394,-0.14057233181304662,1739137699.4776187,41.169960737228394,4.496086976214561,1739137699.4776201,41.169960737228394,0.8625420857443675 +1739137699.4975662,41.18996071815491,42.43061334851039,1739137699.4975688,41.18996071815491,2.2754056090726467,1739137699.4975715,41.18996071815491,69.98217340685657,1739137699.4975743,41.18996071815491,38.753168217044916,1739137699.497576,41.18996071815491,0.008155332797749958,1739137699.4975777,41.18996071815491,-2.5891083026121837,1739137699.4975793,41.18996071815491,-3.105156912257113,1739137699.4975805,41.18996071815491,-0.6108,1739137699.4975817,41.18996071815491,0.7219697539313209,1739137699.4975839,41.18996071815491,0.0,1739137699.497585,41.18996071815491,-0.14057233181304662,1739137699.4975867,41.18996071815491,4.496086976214561,1739137699.497588,41.18996071815491,0.8625420857443675 +1739137699.5175598,41.20996069908142,42.40987599321172,1739137699.5175622,41.20996069908142,2.1835700725749074,1739137699.5175653,41.20996069908142,70.05065046082001,1739137699.517568,41.20996069908142,38.72977836088642,1739137699.5175695,41.20996069908142,0.0057356925054919015,1739137699.5175717,41.20996069908142,-2.607233921706566,1739137699.5175729,41.20996069908142,-3.0886708362611035,1739137699.5175743,41.20996069908142,-0.6108,1739137699.5175757,41.20996069908142,0.7267464657600186,1739137699.5175772,41.20996069908142,0.0,1739137699.5175786,41.20996069908142,-0.10284071579020715,1739137699.51758,41.20996069908142,4.483058500991902,1739137699.5175812,41.20996069908142,0.8475546267271017 +1739137699.5396545,41.229960680007935,42.40987599321172,1739137699.5396569,41.229960680007935,2.1835700725749074,1739137699.53966,41.229960680007935,70.05065046082001,1739137699.539663,41.229960680007935,38.72977836088642,1739137699.5396643,41.229960680007935,0.0057356925054919015,1739137699.5396662,41.229960680007935,-2.607233921706566,1739137699.539668,41.229960680007935,-3.0886708362611035,1739137699.5396693,41.229960680007935,-0.6108,1739137699.5396705,41.229960680007935,0.7267464657600186,1739137699.5396724,41.229960680007935,0.0,1739137699.5396736,41.229960680007935,-0.12080816096708313,1739137699.5396752,41.229960680007935,4.483058500991902,1739137699.5396764,41.229960680007935,0.8475546267271017 +1739137699.5574467,41.24996066093445,42.40987599321172,1739137699.5574489,41.24996066093445,2.1835700725749074,1739137699.5574517,41.24996066093445,70.05065046082001,1739137699.5574548,41.24996066093445,38.72977836088642,1739137699.557456,41.24996066093445,0.0057356925054919015,1739137699.557458,41.24996066093445,-2.607233921706566,1739137699.5574594,41.24996066093445,-3.0886708362611035,1739137699.557461,41.24996066093445,-0.6108,1739137699.5574622,41.24996066093445,0.7267464657600186,1739137699.557464,41.24996066093445,0.0,1739137699.557465,41.24996066093445,-0.12080816096708313,1739137699.557467,41.24996066093445,4.483058500991902,1739137699.5574682,41.24996066093445,0.8475546267271017 +1739137699.577541,41.26996064186096,42.40987599321172,1739137699.5775437,41.26996064186096,2.1835700725749074,1739137699.5775466,41.26996064186096,70.05065046082001,1739137699.5775495,41.26996064186096,38.72977836088642,1739137699.577551,41.26996064186096,0.0057356925054919015,1739137699.5775526,41.26996064186096,-2.607233921706566,1739137699.5775542,41.26996064186096,-3.0886708362611035,1739137699.577556,41.26996064186096,-0.6108,1739137699.5775573,41.26996064186096,0.7267464657600186,1739137699.577559,41.26996064186096,0.0,1739137699.5775604,41.26996064186096,-0.12080816096708313,1739137699.577562,41.26996064186096,4.483058500991902,1739137699.577564,41.26996064186096,0.8475546267271017 +1739137699.5974119,41.289960622787476,42.40987599321172,1739137699.5974143,41.289960622787476,2.1835700725749074,1739137699.597417,41.289960622787476,70.05065046082001,1739137699.59742,41.289960622787476,38.72977836088642,1739137699.5974216,41.289960622787476,0.0057356925054919015,1739137699.5974233,41.289960622787476,-2.607233921706566,1739137699.5974247,41.289960622787476,-3.0886708362611035,1739137699.597426,41.289960622787476,-0.6108,1739137699.5974271,41.289960622787476,0.7267464657600186,1739137699.5974288,41.289960622787476,0.0,1739137699.5974302,41.289960622787476,-0.12080816096708313,1739137699.597432,41.289960622787476,4.483058500991902,1739137699.597433,41.289960622787476,0.8475546267271017 +1739137699.6174598,41.30996060371399,42.38824658260408,1739137699.6174622,41.30996060371399,2.0935404158776256,1739137699.6174653,41.30996060371399,70.05423408701657,1739137699.6174684,41.30996060371399,38.76469264268701,1739137699.61747,41.30996060371399,0.00934751476072511,1739137699.6174717,41.30996060371399,-2.619623701358687,1739137699.6174734,41.30996060371399,-3.013212491024807,1739137699.6174748,41.30996060371399,-0.6108,1739137699.617476,41.30996060371399,0.7490165013477025,1739137699.617478,41.30996060371399,0.0,1739137699.6174793,41.30996060371399,-0.05367537120859373,1739137699.617481,41.30996060371399,4.4685623555207235,1739137699.6174822,41.30996060371399,0.8346598836488046 +1739137699.6374907,41.3299605846405,42.38824658260408,1739137699.637493,41.3299605846405,2.0935404158776256,1739137699.637496,41.3299605846405,70.05423408701657,1739137699.6374989,41.3299605846405,38.76469264268701,1739137699.6375005,41.3299605846405,0.00934751476072511,1739137699.637502,41.3299605846405,-2.619623701358687,1739137699.6375039,41.3299605846405,-3.013212491024807,1739137699.637505,41.3299605846405,-0.6108,1739137699.6375062,41.3299605846405,0.7490165013477025,1739137699.6375082,41.3299605846405,0.0,1739137699.6375093,41.3299605846405,-0.08564338230110213,1739137699.637511,41.3299605846405,4.4685623555207235,1739137699.6375122,41.3299605846405,0.8346598836488046 +1739137699.657446,41.34996056556702,42.38824658260408,1739137699.6574483,41.34996056556702,2.0935404158776256,1739137699.657451,41.34996056556702,70.05423408701657,1739137699.6574538,41.34996056556702,38.76469264268701,1739137699.6574552,41.34996056556702,0.00934751476072511,1739137699.6574569,41.34996056556702,-2.619623701358687,1739137699.6574585,41.34996056556702,-3.013212491024807,1739137699.6574597,41.34996056556702,-0.6108,1739137699.6574612,41.34996056556702,0.7490165013477025,1739137699.6574628,41.34996056556702,0.0,1739137699.657464,41.34996056556702,-0.08564338230110213,1739137699.6574657,41.34996056556702,4.4685623555207235,1739137699.657467,41.34996056556702,0.8346598836488046 +1739137699.6776514,41.36996054649353,42.38824658260408,1739137699.677654,41.36996054649353,2.0935404158776256,1739137699.6776574,41.36996054649353,70.05423408701657,1739137699.6776605,41.36996054649353,38.76469264268701,1739137699.677662,41.36996054649353,0.00934751476072511,1739137699.677664,41.36996054649353,-2.619623701358687,1739137699.6776657,41.36996054649353,-3.013212491024807,1739137699.6776676,41.36996054649353,-0.6108,1739137699.677669,41.36996054649353,0.7490165013477025,1739137699.677671,41.36996054649353,0.0,1739137699.6776724,41.36996054649353,-0.08564338230110213,1739137699.677674,41.36996054649353,4.4685623555207235,1739137699.6776755,41.36996054649353,0.8346598836488046 +1739137699.6977746,41.389960527420044,42.38824658260408,1739137699.6977775,41.389960527420044,2.0935404158776256,1739137699.6977813,41.389960527420044,70.05423408701657,1739137699.697785,41.389960527420044,38.76469264268701,1739137699.6977866,41.389960527420044,0.00934751476072511,1739137699.697789,41.389960527420044,-2.619623701358687,1739137699.6977906,41.389960527420044,-3.013212491024807,1739137699.6977925,41.389960527420044,-0.6108,1739137699.697794,41.389960527420044,0.7490165013477025,1739137699.697796,41.389960527420044,0.0,1739137699.6977975,41.389960527420044,-0.08564338230110213,1739137699.6977994,41.389960527420044,4.4685623555207235,1739137699.6978009,41.389960527420044,0.8346598836488046 +1739137699.7178204,41.40996050834656,42.38824658260408,1739137699.7178233,41.40996050834656,2.0935404158776256,1739137699.7178268,41.40996050834656,70.05423408701657,1739137699.7178302,41.40996050834656,38.76469264268701,1739137699.7178319,41.40996050834656,0.00934751476072511,1739137699.7178342,41.40996050834656,-2.619623701358687,1739137699.7178361,41.40996050834656,-3.013212491024807,1739137699.7178378,41.40996050834656,-0.6108,1739137699.7178392,41.40996050834656,0.7490165013477025,1739137699.7178414,41.40996050834656,0.0,1739137699.7178433,41.40996050834656,-0.08564338230110213,1739137699.717845,41.40996050834656,4.4685623555207235,1739137699.7178469,41.40996050834656,0.8346598836488046 +1739137699.7381248,41.42996048927307,42.365548548356436,1739137699.7381282,41.42996048927307,2.005001481976307,1739137699.738132,41.42996048927307,70.05778691038807,1739137699.7381353,41.42996048927307,38.78724534954266,1739137699.738137,41.42996048927307,0.012004296372146415,1739137699.7381394,41.42996048927307,-2.6334161561622995,1739137699.7381413,41.42996048927307,-2.946183616988196,1739137699.7381427,41.42996048927307,-0.6108,1739137699.7381444,41.42996048927307,0.7693704354057569,1739137699.7381463,41.42996048927307,0.0,1739137699.7381482,41.42996048927307,-0.03007343291581807,1739137699.73815,41.42996048927307,4.452567527021365,1739137699.7381513,41.42996048927307,0.8259057622001061 +1739137699.757853,41.449960470199585,42.365548548356436,1739137699.757856,41.449960470199585,2.005001481976307,1739137699.7578592,41.449960470199585,70.05778691038807,1739137699.7578628,41.449960470199585,38.78724534954266,1739137699.7578647,41.449960470199585,0.012004296372146415,1739137699.7578669,41.449960470199585,-2.6334161561622995,1739137699.7578685,41.449960470199585,-2.946183616988196,1739137699.7578702,41.449960470199585,-0.6108,1739137699.7578716,41.449960470199585,0.7693704354057569,1739137699.7578738,41.449960470199585,0.0,1739137699.7578752,41.449960470199585,-0.05653532679434925,1739137699.7578769,41.449960470199585,4.452567527021365,1739137699.7578788,41.449960470199585,0.8259057622001061 +1739137699.7780554,41.4699604511261,42.365548548356436,1739137699.7780588,41.4699604511261,2.005001481976307,1739137699.7780628,41.4699604511261,70.05778691038807,1739137699.7780662,41.4699604511261,38.78724534954266,1739137699.778068,41.4699604511261,0.012004296372146415,1739137699.7780702,41.4699604511261,-2.6334161561622995,1739137699.778072,41.4699604511261,-2.946183616988196,1739137699.7780735,41.4699604511261,-0.6108,1739137699.7780752,41.4699604511261,0.7693704354057569,1739137699.7780771,41.4699604511261,0.0,1739137699.7780788,41.4699604511261,-0.05653532679434925,1739137699.7780805,41.4699604511261,4.452567527021365,1739137699.7780824,41.4699604511261,0.8259057622001061 +1739137699.797822,41.48996043205261,42.365548548356436,1739137699.7978249,41.48996043205261,2.005001481976307,1739137699.7978284,41.48996043205261,70.05778691038807,1739137699.7978323,41.48996043205261,38.78724534954266,1739137699.797834,41.48996043205261,0.012004296372146415,1739137699.797836,41.48996043205261,-2.6334161561622995,1739137699.7978377,41.48996043205261,-2.946183616988196,1739137699.7978396,41.48996043205261,-0.6108,1739137699.7978415,41.48996043205261,0.7693704354057569,1739137699.7978435,41.48996043205261,0.0,1739137699.7978454,41.48996043205261,-0.05653532679434925,1739137699.797847,41.48996043205261,4.452567527021365,1739137699.7978485,41.48996043205261,0.8259057622001061 +1739137699.817939,41.509960412979126,42.365548548356436,1739137699.817942,41.509960412979126,2.005001481976307,1739137699.8179457,41.509960412979126,70.05778691038807,1739137699.8179488,41.509960412979126,38.78724534954266,1739137699.8179507,41.509960412979126,0.012004296372146415,1739137699.8179529,41.509960412979126,-2.6334161561622995,1739137699.8179545,41.509960412979126,-2.946183616988196,1739137699.8179564,41.509960412979126,-0.6108,1739137699.8179579,41.509960412979126,0.7693704354057569,1739137699.81796,41.509960412979126,0.0,1739137699.8179615,41.509960412979126,-0.05653532679434925,1739137699.8179634,41.509960412979126,4.452567527021365,1739137699.8179648,41.509960412979126,0.8259057622001061 +1739137699.8382525,41.52996039390564,42.34159990621618,1739137699.8382561,41.52996039390564,1.9176710840280213,1739137699.8382597,41.52996039390564,70.31503613473726,1739137699.8382633,41.52996039390564,38.54909778614044,1739137699.838265,41.52996039390564,-0.0122159293356902,1739137699.838267,41.52996039390564,-2.6708749915553867,1739137699.838269,41.52996039390564,-3.1191512747865624,1739137699.8382707,41.52996039390564,-0.6108,1739137699.8382723,41.52996039390564,0.7179396416366344,1739137699.8382742,41.52996039390564,0.0,1739137699.8382761,41.52996039390564,-0.14335210405525517,1739137699.838278,41.52996039390564,4.4350390350427125,1739137699.83828,41.52996039390564,0.8199504025348892 +1739137699.8579473,41.54996037483215,42.34159990621618,1739137699.8579507,41.54996037483215,1.9176710840280213,1739137699.8579545,41.54996037483215,70.31503613473726,1739137699.857958,41.54996037483215,38.54909778614044,1739137699.85796,41.54996037483215,-0.0122159293356902,1739137699.8579626,41.54996037483215,-2.6708749915553867,1739137699.8579643,41.54996037483215,-3.1191512747865624,1739137699.8579657,41.54996037483215,-0.6108,1739137699.8579676,41.54996037483215,0.7179396416366344,1739137699.85797,41.54996037483215,0.0,1739137699.8579714,41.54996037483215,-0.10201076089825478,1739137699.8579736,41.54996037483215,4.4350390350427125,1739137699.857975,41.54996037483215,0.8199504025348892 +1739137699.8780549,41.56996035575867,42.34159990621618,1739137699.8780582,41.56996035575867,1.9176710840280213,1739137699.878062,41.56996035575867,70.31503613473726,1739137699.8780656,41.56996035575867,38.54909778614044,1739137699.8780675,41.56996035575867,-0.0122159293356902,1739137699.8780694,41.56996035575867,-2.6708749915553867,1739137699.8780713,41.56996035575867,-3.1191512747865624,1739137699.878073,41.56996035575867,-0.6108,1739137699.878075,41.56996035575867,0.7179396416366344,1739137699.8780766,41.56996035575867,0.0,1739137699.8780785,41.56996035575867,-0.10201076089825478,1739137699.8780806,41.56996035575867,4.4350390350427125,1739137699.878082,41.56996035575867,0.8199504025348892 +1739137699.8979106,41.58996033668518,42.34159990621618,1739137699.8979137,41.58996033668518,1.9176710840280213,1739137699.8979175,41.58996033668518,70.31503613473726,1739137699.897921,41.58996033668518,38.54909778614044,1739137699.8979228,41.58996033668518,-0.0122159293356902,1739137699.8979251,41.58996033668518,-2.6708749915553867,1739137699.8979268,41.58996033668518,-3.1191512747865624,1739137699.8979285,41.58996033668518,-0.6108,1739137699.89793,41.58996033668518,0.7179396416366344,1739137699.897932,41.58996033668518,0.0,1739137699.8979335,41.58996033668518,-0.10201076089825478,1739137699.8979354,41.58996033668518,4.4350390350427125,1739137699.897937,41.58996033668518,0.8199504025348892 +1739137699.9179294,41.609960317611694,42.34159990621618,1739137699.9179323,41.609960317611694,1.9176710840280213,1739137699.9179358,41.609960317611694,70.31503613473726,1739137699.9179392,41.609960317611694,38.54909778614044,1739137699.917941,41.609960317611694,-0.0122159293356902,1739137699.917943,41.609960317611694,-2.6708749915553867,1739137699.917945,41.609960317611694,-3.1191512747865624,1739137699.9179466,41.609960317611694,-0.6108,1739137699.9179482,41.609960317611694,0.7179396416366344,1739137699.91795,41.609960317611694,0.0,1739137699.9179518,41.609960317611694,-0.10201076089825478,1739137699.9179537,41.609960317611694,4.4350390350427125,1739137699.9179556,41.609960317611694,0.8199504025348892 +1739137699.9380562,41.62996029853821,42.34159990621618,1739137699.9380596,41.62996029853821,1.9176710840280213,1739137699.9380631,41.62996029853821,70.31503613473726,1739137699.938067,41.62996029853821,38.54909778614044,1739137699.9380686,41.62996029853821,-0.0122159293356902,1739137699.9380708,41.62996029853821,-2.6708749915553867,1739137699.9380727,41.62996029853821,-3.1191512747865624,1739137699.9380744,41.62996029853821,-0.6108,1739137699.938076,41.62996029853821,0.7179396416366344,1739137699.938078,41.62996029853821,0.0,1739137699.9380798,41.62996029853821,-0.10201076089825478,1739137699.9380817,41.62996029853821,4.4350390350427125,1739137699.9380836,41.62996029853821,0.8199504025348892 +1739137699.9580934,41.64996027946472,42.3163454243036,1739137699.9580963,41.64996027946472,1.831750788241922,1739137699.9580996,41.64996027946472,70.01233500175684,1739137699.9581032,41.64996027946472,38.88583287069088,1739137699.9581048,41.64996027946472,0.024167691838484703,1739137699.9581072,41.64996027946472,-2.6566468484342387,1739137699.958109,41.64996027946472,-2.752824687646844,1739137699.9581108,41.64996027946472,-0.6108,1739137699.9581125,41.64996027946472,0.831237983393459,1739137699.9581144,41.64996027946472,0.0,1739137699.958116,41.64996027946472,0.1372061159110866,1739137699.958118,41.64996027946472,4.415937606152277,1739137699.9581196,41.64996027946472,0.8079447228674592 +1739137699.9830005,41.669960260391235,42.3163454243036,1739137699.9830089,41.669960260391235,1.831750788241922,1739137699.9830186,41.669960260391235,70.01233500175684,1739137699.9830282,41.669960260391235,38.88583287069088,1739137699.983033,41.669960260391235,0.024167691838484703,1739137699.983039,41.669960260391235,-2.6566468484342387,1739137699.983044,41.669960260391235,-2.752824687646844,1739137699.9830484,41.669960260391235,-0.6108,1739137699.9830527,41.669960260391235,0.831237983393459,1739137699.983058,41.669960260391235,0.0,1739137699.9830623,41.669960260391235,0.02329326052599978,1739137699.983068,41.669960260391235,4.415937606152277,1739137699.9830728,41.669960260391235,0.8079447228674592 +1739137700.005369,41.68996024131775,42.3163454243036,1739137700.005378,41.68996024131775,1.831750788241922,1739137700.0053892,41.68996024131775,70.01233500175684,1739137700.005403,41.68996024131775,38.88583287069088,1739137700.0054107,41.68996024131775,0.024167691838484703,1739137700.0054207,41.68996024131775,-2.6566468484342387,1739137700.0054295,41.68996024131775,-2.752824687646844,1739137700.0054379,41.68996024131775,-0.6108,1739137700.0054467,41.68996024131775,0.831237983393459,1739137700.0054553,41.68996024131775,0.0,1739137700.005464,41.68996024131775,0.02329326052599978,1739137700.0054731,41.68996024131775,4.415937606152277,1739137700.0054817,41.68996024131775,0.8079447228674592 +1739137700.0239303,41.70996022224426,42.3163454243036,1739137700.0239365,41.70996022224426,1.831750788241922,1739137700.0239434,41.70996022224426,70.01233500175684,1739137700.0239503,41.70996022224426,38.88583287069088,1739137700.0239537,41.70996022224426,0.024167691838484703,1739137700.0239575,41.70996022224426,-2.6566468484342387,1739137700.0239608,41.70996022224426,-2.752824687646844,1739137700.023964,41.70996022224426,-0.6108,1739137700.023967,41.70996022224426,0.831237983393459,1739137700.023971,41.70996022224426,0.0,1739137700.0239742,41.70996022224426,0.02329326052599978,1739137700.023978,41.70996022224426,4.415937606152277,1739137700.023981,41.70996022224426,0.8079447228674592 +1739137700.0482042,41.729960203170776,42.3163454243036,1739137700.0482109,41.729960203170776,1.831750788241922,1739137700.04822,41.729960203170776,70.01233500175684,1739137700.0482304,41.729960203170776,38.88583287069088,1739137700.0482361,41.729960203170776,0.024167691838484703,1739137700.0482435,41.729960203170776,-2.6566468484342387,1739137700.04825,41.729960203170776,-2.752824687646844,1739137700.0482564,41.729960203170776,-0.6108,1739137700.048263,41.729960203170776,0.831237983393459,1739137700.0482697,41.729960203170776,0.0,1739137700.0482764,41.729960203170776,0.02329326052599978,1739137700.0482833,41.729960203170776,4.415937606152277,1739137700.0482898,41.729960203170776,0.8079447228674592 +1739137700.066008,41.74996018409729,42.289535482027006,1739137700.0660157,41.74996018409729,1.7468122404523667,1739137700.0660233,41.74996018409729,69.94034022048102,1739137700.0660357,41.74996018409729,38.94647713773289,1739137700.0660594,41.74996018409729,0.03262679928260523,1739137700.066068,41.74996018409729,-2.667789504489981,1739137700.0660758,41.74996018409729,-2.6416951985788435,1739137700.0660923,41.74996018409729,-0.6108,1739137700.0661,41.74996018409729,0.869021556819856,1739137700.0661063,41.74996018409729,0.0,1739137700.066114,41.74996018409729,0.08858643715474918,1739137700.06612,41.74996018409729,4.395219296019919,1739137700.0661256,41.74996018409729,0.8115271240677545 +1739137700.0836744,41.769960165023804,42.289535482027006,1739137700.0836787,41.769960165023804,1.7468122404523667,1739137700.0836833,41.769960165023804,69.94034022048102,1739137700.083688,41.769960165023804,38.94647713773289,1739137700.08369,41.769960165023804,0.03262679928260523,1739137700.0836928,41.769960165023804,-2.667789504489981,1739137700.083695,41.769960165023804,-2.6416951985788435,1739137700.0836968,41.769960165023804,-0.6108,1739137700.083699,41.769960165023804,0.869021556819856,1739137700.0837011,41.769960165023804,0.0,1739137700.0837035,41.769960165023804,0.05749443275210153,1739137700.083706,41.769960165023804,4.395219296019919,1739137700.0837076,41.769960165023804,0.8115271240677545 +1739137700.1069796,41.78996014595032,42.289535482027006,1739137700.1069858,41.78996014595032,1.7468122404523667,1739137700.1069937,41.78996014595032,69.94034022048102,1739137700.107003,41.78996014595032,38.94647713773289,1739137700.107008,41.78996014595032,0.03262679928260523,1739137700.1070147,41.78996014595032,-2.667789504489981,1739137700.1070209,41.78996014595032,-2.6416951985788435,1739137700.107027,41.78996014595032,-0.6108,1739137700.1070328,41.78996014595032,0.869021556819856,1739137700.1070392,41.78996014595032,0.0,1739137700.1070452,41.78996014595032,0.05749443275210153,1739137700.1070514,41.78996014595032,4.395219296019919,1739137700.1070573,41.78996014595032,0.8115271240677545 +1739137700.1246333,41.81996011734009,42.289535482027006,1739137700.1246405,41.81996011734009,1.7468122404523667,1739137700.1246495,41.81996011734009,69.94034022048102,1739137700.1246605,41.81996011734009,38.94647713773289,1739137700.1246665,41.81996011734009,0.03262679928260523,1739137700.1246743,41.81996011734009,-2.667789504489981,1739137700.12468,41.81996011734009,-2.6416951985788435,1739137700.124686,41.81996011734009,-0.6108,1739137700.1246905,41.81996011734009,0.869021556819856,1739137700.124696,41.81996011734009,0.0,1739137700.124701,41.81996011734009,0.05749443275210153,1739137700.1247058,41.81996011734009,4.395219296019919,1739137700.1247127,41.81996011734009,0.8115271240677545 +1739137700.1433606,41.829960107803345,42.289535482027006,1739137700.1433647,41.829960107803345,1.7468122404523667,1739137700.143369,41.829960107803345,69.94034022048102,1739137700.1433733,41.829960107803345,38.94647713773289,1739137700.1433754,41.829960107803345,0.03262679928260523,1739137700.143378,41.829960107803345,-2.667789504489981,1739137700.1433802,41.829960107803345,-2.6416951985788435,1739137700.1433825,41.829960107803345,-0.6108,1739137700.1433842,41.829960107803345,0.869021556819856,1739137700.1433868,41.829960107803345,0.0,1739137700.143389,41.829960107803345,0.05749443275210153,1739137700.1433911,41.829960107803345,4.395219296019919,1739137700.1433933,41.829960107803345,0.8115271240677545 +1739137700.1653585,41.84996008872986,42.289535482027006,1739137700.1653647,41.84996008872986,1.7468122404523667,1739137700.165372,41.84996008872986,69.94034022048102,1739137700.1653807,41.84996008872986,38.94647713773289,1739137700.1653852,41.84996008872986,0.03262679928260523,1739137700.1653912,41.84996008872986,-2.667789504489981,1739137700.1653965,41.84996008872986,-2.6416951985788435,1739137700.165402,41.84996008872986,-0.6108,1739137700.1654072,41.84996008872986,0.869021556819856,1739137700.165413,41.84996008872986,0.0,1739137700.1654181,41.84996008872986,0.05749443275210153,1739137700.165424,41.84996008872986,4.395219296019919,1739137700.1654296,41.84996008872986,0.8115271240677545 +1739137700.182875,41.86996006965637,42.26071590125308,1739137700.1828785,41.86996006965637,1.661904492028798,1739137700.1828825,41.86996006965637,69.83433511077051,1739137700.1828868,41.86996006965637,39.029975885401605,1739137700.182889,41.86996006965637,0.04431662395622414,1739137700.1828916,41.86996006965637,-2.677396006023772,1739137700.1828938,41.86996006965637,-2.5075111518826225,1739137700.182896,41.86996006965637,-0.6108,1739137700.1828978,41.86996006965637,0.9169395513779692,1739137700.1829004,41.86996006965637,0.0,1739137700.1829023,41.86996006965637,0.13517024711654377,1739137700.1829047,41.86996006965637,4.37283505064759,1739137700.1829069,41.86996006965637,0.8187578057694848 +1739137700.2025568,41.889960050582886,42.26071590125308,1739137700.2025604,41.889960050582886,1.661904492028798,1739137700.202565,41.889960050582886,69.83433511077051,1739137700.202569,41.889960050582886,39.029975885401605,1739137700.202571,41.889960050582886,0.04431662395622414,1739137700.2025735,41.889960050582886,-2.677396006023772,1739137700.202576,41.889960050582886,-2.5075111518826225,1739137700.2025778,41.889960050582886,-0.6108,1739137700.20258,41.889960050582886,0.9169395513779692,1739137700.2025824,41.889960050582886,0.0,1739137700.2025845,41.889960050582886,0.09818174560848447,1739137700.2025871,41.889960050582886,4.37283505064759,1739137700.2025893,41.889960050582886,0.8187578057694848 +1739137700.2216814,41.9099600315094,42.26071590125308,1739137700.2216845,41.9099600315094,1.661904492028798,1739137700.221688,41.9099600315094,69.83433511077051,1739137700.2216916,41.9099600315094,39.029975885401605,1739137700.2216935,41.9099600315094,0.04431662395622414,1739137700.2216957,41.9099600315094,-2.677396006023772,1739137700.2216976,41.9099600315094,-2.5075111518826225,1739137700.2216992,41.9099600315094,-0.6108,1739137700.2217011,41.9099600315094,0.9169395513779692,1739137700.2217028,41.9099600315094,0.0,1739137700.2217047,41.9099600315094,0.09818174560848447,1739137700.2217069,41.9099600315094,4.37283505064759,1739137700.2217083,41.9099600315094,0.8187578057694848 +1739137700.2420926,41.92996001243591,42.26071590125308,1739137700.242096,41.92996001243591,1.661904492028798,1739137700.2420995,41.92996001243591,69.83433511077051,1739137700.2421029,41.92996001243591,39.029975885401605,1739137700.2421045,41.92996001243591,0.04431662395622414,1739137700.2421064,41.92996001243591,-2.677396006023772,1739137700.242108,41.92996001243591,-2.5075111518826225,1739137700.2421098,41.92996001243591,-0.6108,1739137700.2421114,41.92996001243591,0.9169395513779692,1739137700.2421134,41.92996001243591,0.0,1739137700.2421148,41.92996001243591,0.09818174560848447,1739137700.2421167,41.92996001243591,4.37283505064759,1739137700.2421181,41.92996001243591,0.8187578057694848 +1739137700.2612936,41.94995999336243,42.26071590125308,1739137700.261297,41.94995999336243,1.661904492028798,1739137700.2613006,41.94995999336243,69.83433511077051,1739137700.261304,41.94995999336243,39.029975885401605,1739137700.2613053,41.94995999336243,0.04431662395622414,1739137700.2613077,41.94995999336243,-2.677396006023772,1739137700.2613091,41.94995999336243,-2.5075111518826225,1739137700.261311,41.94995999336243,-0.6108,1739137700.2613125,41.94995999336243,0.9169395513779692,1739137700.2613146,41.94995999336243,0.0,1739137700.261316,41.94995999336243,0.09818174560848447,1739137700.261318,41.94995999336243,4.37283505064759,1739137700.2613194,41.94995999336243,0.8187578057694848 +1739137700.2840953,41.96995997428894,42.229608399090054,1739137700.2840993,41.96995997428894,1.5767890748426518,1739137700.2841046,41.96995997428894,69.84059949961596,1739137700.2841108,41.96995997428894,38.99082082133154,1739137700.2841141,41.96995997428894,0.03883491498641505,1739137700.2841184,41.96995997428894,-2.698262710263501,1739137700.2841227,41.96995997428894,-2.4799319547623653,1739137700.2841265,41.96995997428894,-0.6108,1739137700.2841303,41.96995997428894,0.9271109345956221,1739137700.2841344,41.96995997428894,0.0,1739137700.2841384,41.96995997428894,0.09642641006239289,1739137700.2841425,41.96995997428894,4.348730196732282,1739137700.2841465,41.96995997428894,0.829848650046106 +1739137700.302401,41.989959955215454,42.229608399090054,1739137700.3024049,41.989959955215454,1.5767890748426518,1739137700.3024094,41.989959955215454,69.84059949961596,1739137700.302415,41.989959955215454,38.99082082133154,1739137700.302418,41.989959955215454,0.03883491498641505,1739137700.3024218,41.989959955215454,-2.698262710263501,1739137700.3024254,41.989959955215454,-2.4799319547623653,1739137700.3024287,41.989959955215454,-0.6108,1739137700.3024323,41.989959955215454,0.9271109345956221,1739137700.3024356,41.989959955215454,0.0,1739137700.3024392,41.989959955215454,0.09726228454951613,1739137700.3024428,41.989959955215454,4.348730196732282,1739137700.3024464,41.989959955215454,0.829848650046106 +1739137700.324012,42.00995993614197,42.229608399090054,1739137700.3240156,42.00995993614197,1.5767890748426518,1739137700.3240204,42.00995993614197,69.84059949961596,1739137700.3240259,42.00995993614197,38.99082082133154,1739137700.3240292,42.00995993614197,0.03883491498641505,1739137700.324033,42.00995993614197,-2.698262710263501,1739137700.3240366,42.00995993614197,-2.4799319547623653,1739137700.32404,42.00995993614197,-0.6108,1739137700.3240435,42.00995993614197,0.9271109345956221,1739137700.324047,42.00995993614197,0.0,1739137700.3240504,42.00995993614197,0.09726228454951613,1739137700.3240542,42.00995993614197,4.348730196732282,1739137700.3240578,42.00995993614197,0.829848650046106 +1739137700.3440912,42.02995991706848,42.229608399090054,1739137700.3440948,42.02995991706848,1.5767890748426518,1739137700.3440998,42.02995991706848,69.84059949961596,1739137700.3441055,42.02995991706848,38.99082082133154,1739137700.3441086,42.02995991706848,0.03883491498641505,1739137700.3441124,42.02995991706848,-2.698262710263501,1739137700.344116,42.02995991706848,-2.4799319547623653,1739137700.3441193,42.02995991706848,-0.6108,1739137700.3441231,42.02995991706848,0.9271109345956221,1739137700.3441267,42.02995991706848,0.0,1739137700.3441303,42.02995991706848,0.09726228454951613,1739137700.3441339,42.02995991706848,4.348730196732282,1739137700.3441374,42.02995991706848,0.829848650046106 +1739137700.3614461,42.049959897994995,42.229608399090054,1739137700.3614495,42.049959897994995,1.5767890748426518,1739137700.361453,42.049959897994995,69.84059949961596,1739137700.3614562,42.049959897994995,38.99082082133154,1739137700.3614576,42.049959897994995,0.03883491498641505,1739137700.3614595,42.049959897994995,-2.698262710263501,1739137700.361461,42.049959897994995,-2.4799319547623653,1739137700.3614626,42.049959897994995,-0.6108,1739137700.3614638,42.049959897994995,0.9271109345956221,1739137700.361466,42.049959897994995,0.0,1739137700.3614671,42.049959897994995,0.09726228454951613,1739137700.3614686,42.049959897994995,4.348730196732282,1739137700.3614702,42.049959897994995,0.829848650046106 +1739137700.3808975,42.06995987892151,42.229608399090054,1739137700.3809004,42.06995987892151,1.5767890748426518,1739137700.3809035,42.06995987892151,69.84059949961596,1739137700.3809063,42.06995987892151,38.99082082133154,1739137700.380908,42.06995987892151,0.03883491498641505,1739137700.38091,42.06995987892151,-2.698262710263501,1739137700.3809114,42.06995987892151,-2.4799319547623653,1739137700.3809125,42.06995987892151,-0.6108,1739137700.380914,42.06995987892151,0.9271109345956221,1739137700.3809154,42.06995987892151,0.0,1739137700.380917,42.06995987892151,0.09726228454951613,1739137700.3809185,42.06995987892151,4.348730196732282,1739137700.3809197,42.06995987892151,0.829848650046106 +1739137700.403547,42.08995985984802,42.19595392608917,1739137700.4035509,42.08995985984802,1.4913664507014683,1739137700.4035559,42.08995985984802,69.8581428514034,1739137700.403561,42.08995985984802,38.941816481235804,1739137700.4035645,42.08995985984802,0.03196761433573049,1739137700.4035683,42.08995985984802,-2.7200077584042206,1739137700.403572,42.08995985984802,-2.456111163586659,1739137700.4035752,42.08995985984802,-0.6108,1739137700.403579,42.08995985984802,0.9359869606224446,1739137700.4035826,42.08995985984802,0.0,1739137700.4035861,42.08995985984802,0.0938820032194303,1739137700.4035897,42.08995985984802,4.3228438489678895,1739137700.4035933,42.08995985984802,0.8404952988226881 +1739137700.4234622,42.109959840774536,42.19595392608917,1739137700.423466,42.109959840774536,1.4913664507014683,1739137700.4234707,42.109959840774536,69.8581428514034,1739137700.4234767,42.109959840774536,38.941816481235804,1739137700.4234807,42.109959840774536,0.03196761433573049,1739137700.4234855,42.109959840774536,-2.7200077584042206,1739137700.4234893,42.109959840774536,-2.456111163586659,1739137700.4234927,42.109959840774536,-0.6108,1739137700.4234962,42.109959840774536,0.9359869606224446,1739137700.4234998,42.109959840774536,0.0,1739137700.4235032,42.109959840774536,0.09549166179975643,1739137700.423507,42.109959840774536,4.3228438489678895,1739137700.4235106,42.109959840774536,0.8404952988226881 +1739137700.4478629,42.12995982170105,42.19595392608917,1739137700.4478674,42.12995982170105,1.4913664507014683,1739137700.4478729,42.12995982170105,69.8581428514034,1739137700.447878,42.12995982170105,38.941816481235804,1739137700.4478805,42.12995982170105,0.03196761433573049,1739137700.4478838,42.12995982170105,-2.7200077584042206,1739137700.4478867,42.12995982170105,-2.456111163586659,1739137700.4478889,42.12995982170105,-0.6108,1739137700.4478915,42.12995982170105,0.9359869606224446,1739137700.4478943,42.12995982170105,0.0,1739137700.4478967,42.12995982170105,0.09549166179975643,1739137700.4478998,42.12995982170105,4.3228438489678895,1739137700.4479022,42.12995982170105,0.8404952988226881 +1739137700.4624517,42.14995980262756,42.19595392608917,1739137700.4624546,42.14995980262756,1.4913664507014683,1739137700.4624577,42.14995980262756,69.8581428514034,1739137700.462461,42.14995980262756,38.941816481235804,1739137700.4624627,42.14995980262756,0.03196761433573049,1739137700.4624646,42.14995980262756,-2.7200077584042206,1739137700.4624662,42.14995980262756,-2.456111163586659,1739137700.4624808,42.14995980262756,-0.6108,1739137700.4624865,42.14995980262756,0.9359869606224446,1739137700.462491,42.14995980262756,0.0,1739137700.4624932,42.14995980262756,0.09549166179975643,1739137700.462495,42.14995980262756,4.3228438489678895,1739137700.4624963,42.14995980262756,0.8404952988226881 +1739137700.483855,42.16995978355408,42.19595392608917,1739137700.4838583,42.16995978355408,1.4913664507014683,1739137700.4838629,42.16995978355408,69.8581428514034,1739137700.4838865,42.16995978355408,38.941816481235804,1739137700.4838896,42.16995978355408,0.03196761433573049,1739137700.4838932,42.16995978355408,-2.7200077584042206,1739137700.4838967,42.16995978355408,-2.456111163586659,1739137700.483916,42.16995978355408,-0.6108,1739137700.4839194,42.16995978355408,0.9359869606224446,1739137700.4839232,42.16995978355408,0.0,1739137700.483945,42.16995978355408,0.09549166179975643,1739137700.4839485,42.16995978355408,4.3228438489678895,1739137700.4839518,42.16995978355408,0.8404952988226881 +1739137700.5012,42.18995976448059,42.159577265579216,1739137700.501202,42.18995976448059,1.4058041152584835,1739137700.5012047,42.18995976448059,70.04275161505629,1739137700.5012074,42.18995976448059,38.72752456001969,1739137700.5012085,42.18995976448059,0.005502540691691971,1739137700.5012102,42.18995976448059,-2.7542027932208266,1739137700.5012114,42.18995976448059,-2.5706829792064116,1739137700.5012126,42.18995976448059,-0.6108,1739137700.501214,42.18995976448059,0.894059939345455,1739137700.5012152,42.18995976448059,0.0,1739137700.5012164,42.18995976448059,-0.004496206481544536,1739137700.501218,42.18995976448059,4.295343517188419,1739137700.5012193,42.18995976448059,0.8509428514319355 +1739137700.5210745,42.209959745407104,42.159577265579216,1739137700.521077,42.209959745407104,1.4058041152584835,1739137700.52108,42.209959745407104,70.04275161505629,1739137700.5210829,42.209959745407104,38.72752456001969,1739137700.521084,42.209959745407104,0.005502540691691971,1739137700.5210857,42.209959745407104,-2.7542027932208266,1739137700.5210872,42.209959745407104,-2.5706829792064116,1739137700.5210886,42.209959745407104,-0.6108,1739137700.5210898,42.209959745407104,0.894059939345455,1739137700.5210912,42.209959745407104,0.0,1739137700.5210927,42.209959745407104,0.043117087913519536,1739137700.521094,42.209959745407104,4.295343517188419,1739137700.5210955,42.209959745407104,0.8509428514319355 +1739137700.5411909,42.22995972633362,42.159577265579216,1739137700.5411942,42.22995972633362,1.4058041152584835,1739137700.541197,42.22995972633362,70.04275161505629,1739137700.5412,42.22995972633362,38.72752456001969,1739137700.5412014,42.22995972633362,0.005502540691691971,1739137700.5412033,42.22995972633362,-2.7542027932208266,1739137700.5412045,42.22995972633362,-2.5706829792064116,1739137700.5412056,42.22995972633362,-0.6108,1739137700.541207,42.22995972633362,0.894059939345455,1739137700.5412087,42.22995972633362,0.0,1739137700.5412102,42.22995972633362,0.043117087913519536,1739137700.5412116,42.22995972633362,4.295343517188419,1739137700.5412133,42.22995972633362,0.8509428514319355 +1739137700.5610015,42.24995970726013,42.159577265579216,1739137700.561004,42.24995970726013,1.4058041152584835,1739137700.561007,42.24995970726013,70.04275161505629,1739137700.56101,42.24995970726013,38.72752456001969,1739137700.5610116,42.24995970726013,0.005502540691691971,1739137700.561013,42.24995970726013,-2.7542027932208266,1739137700.5610142,42.24995970726013,-2.5706829792064116,1739137700.5610156,42.24995970726013,-0.6108,1739137700.5610168,42.24995970726013,0.894059939345455,1739137700.5610185,42.24995970726013,0.0,1739137700.5610197,42.24995970726013,0.043117087913519536,1739137700.5610209,42.24995970726013,4.295343517188419,1739137700.5610223,42.24995970726013,0.8509428514319355 +1739137700.5810091,42.269959688186646,42.159577265579216,1739137700.581012,42.269959688186646,1.4058041152584835,1739137700.5810149,42.269959688186646,70.04275161505629,1739137700.5810175,42.269959688186646,38.72752456001969,1739137700.5810192,42.269959688186646,0.005502540691691971,1739137700.5810206,42.269959688186646,-2.7542027932208266,1739137700.5810223,42.269959688186646,-2.5706829792064116,1739137700.5810235,42.269959688186646,-0.6108,1739137700.5810251,42.269959688186646,0.894059939345455,1739137700.5810268,42.269959688186646,0.0,1739137700.581028,42.269959688186646,0.043117087913519536,1739137700.5810294,42.269959688186646,4.295343517188419,1739137700.5810306,42.269959688186646,0.8509428514319355 +1739137700.6009166,42.28995966911316,42.159577265579216,1739137700.6009195,42.28995966911316,1.4058041152584835,1739137700.6009223,42.28995966911316,70.04275161505629,1739137700.600925,42.28995966911316,38.72752456001969,1739137700.6009264,42.28995966911316,0.005502540691691971,1739137700.6009283,42.28995966911316,-2.7542027932208266,1739137700.6009297,42.28995966911316,-2.5706829792064116,1739137700.6009312,42.28995966911316,-0.6108,1739137700.6009324,42.28995966911316,0.894059939345455,1739137700.6009338,42.28995966911316,0.0,1739137700.6009352,42.28995966911316,0.043117087913519536,1739137700.6009364,42.28995966911316,4.295343517188419,1739137700.6009378,42.28995966911316,0.8509428514319355 +1739137700.6213374,42.30995965003967,42.12052559382945,1739137700.6213408,42.30995965003967,1.3205779258333967,1739137700.6213446,42.30995965003967,70.04907578824604,1739137700.6213477,42.30995965003967,38.709951780591794,1739137700.621349,42.30995965003967,0.003684666957772192,1739137700.6213512,42.30995965003967,-2.773108121877905,1739137700.6213527,42.30995965003967,-2.51214301477881,1739137700.6213543,42.30995965003967,-0.6108,1739137700.6213558,42.30995965003967,0.9152422688650352,1739137700.6213577,42.30995965003967,0.0,1739137700.6213589,42.30995965003967,0.07633821501388652,1739137700.6213608,42.30995965003967,4.267611002958886,1739137700.6213622,42.30995965003967,0.8547236460872343 +1739137700.6416438,42.32995963096619,42.12052559382945,1739137700.6416466,42.32995963096619,1.3205779258333967,1739137700.64165,42.32995963096619,70.04907578824604,1739137700.6416535,42.32995963096619,38.709951780591794,1739137700.641655,42.32995963096619,0.003684666957772192,1739137700.6416569,42.32995963096619,-2.773108121877905,1739137700.6416583,42.32995963096619,-2.51214301477881,1739137700.64166,42.32995963096619,-0.6108,1739137700.6416614,42.32995963096619,0.9152422688650352,1739137700.641663,42.32995963096619,0.0,1739137700.6416645,42.32995963096619,0.06051862277780096,1739137700.641666,42.32995963096619,4.267611002958886,1739137700.6416676,42.32995963096619,0.8547236460872343 +1739137700.661615,42.3499596118927,42.12052559382945,1739137700.661618,42.3499596118927,1.3205779258333967,1739137700.6616216,42.3499596118927,70.04907578824604,1739137700.6616244,42.3499596118927,38.709951780591794,1739137700.6616259,42.3499596118927,0.003684666957772192,1739137700.661628,42.3499596118927,-2.773108121877905,1739137700.6616294,42.3499596118927,-2.51214301477881,1739137700.6616316,42.3499596118927,-0.6108,1739137700.661633,42.3499596118927,0.9152422688650352,1739137700.661635,42.3499596118927,0.0,1739137700.6616364,42.3499596118927,0.06051862277780096,1739137700.6616385,42.3499596118927,4.267611002958886,1739137700.66164,42.3499596118927,0.8547236460872343 +1739137700.6812775,42.369959592819214,42.12052559382945,1739137700.6812804,42.369959592819214,1.3205779258333967,1739137700.681283,42.369959592819214,70.04907578824604,1739137700.6812859,42.369959592819214,38.709951780591794,1739137700.681287,42.369959592819214,0.003684666957772192,1739137700.6812887,42.369959592819214,-2.773108121877905,1739137700.68129,42.369959592819214,-2.51214301477881,1739137700.6812916,42.369959592819214,-0.6108,1739137700.681293,42.369959592819214,0.9152422688650352,1739137700.6812947,42.369959592819214,0.0,1739137700.6812959,42.369959592819214,0.06051862277780096,1739137700.6812973,42.369959592819214,4.267611002958886,1739137700.6812987,42.369959592819214,0.8547236460872343 +1739137700.701608,42.38995957374573,42.12052559382945,1739137700.701611,42.38995957374573,1.3205779258333967,1739137700.7016149,42.38995957374573,70.04907578824604,1739137700.7016182,42.38995957374573,38.709951780591794,1739137700.7016199,42.38995957374573,0.003684666957772192,1739137700.7016222,42.38995957374573,-2.773108121877905,1739137700.7016242,42.38995957374573,-2.51214301477881,1739137700.7016258,42.38995957374573,-0.6108,1739137700.7016275,42.38995957374573,0.9152422688650352,1739137700.7016296,42.38995957374573,0.0,1739137700.7016313,42.38995957374573,0.06051862277780096,1739137700.701633,42.38995957374573,4.267611002958886,1739137700.701635,42.38995957374573,0.8547236460872343 +1739137700.721872,42.40995955467224,42.078855331551054,1739137700.7218754,42.40995955467224,1.235919653288823,1739137700.721879,42.40995955467224,70.18047424012968,1739137700.7218826,42.40995955467224,38.55897820956503,1739137700.7218845,42.40995955467224,-0.0113278013874126,1739137700.7218864,42.40995955467224,-2.801053125683125,1739137700.7218883,42.40995955467224,-2.566547783935601,1739137700.7218897,42.40995955467224,-0.6108,1739137700.7218914,42.40995955467224,0.8955400080558298,1739137700.7218933,42.40995955467224,0.0,1739137700.721895,42.40995955467224,0.009973071481515921,1739137700.7218966,42.40995955467224,4.239878488729353,1739137700.7218986,42.40995955467224,0.8614976144095478 +1739137700.7418396,42.429959535598755,42.078855331551054,1739137700.7418432,42.429959535598755,1.235919653288823,1739137700.7418473,42.429959535598755,70.18047424012968,1739137700.7418509,42.429959535598755,38.55897820956503,1739137700.741853,42.429959535598755,-0.0113278013874126,1739137700.741855,42.429959535598755,-2.801053125683125,1739137700.7418568,42.429959535598755,-2.566547783935601,1739137700.7418585,42.429959535598755,-0.6108,1739137700.7418602,42.429959535598755,0.8955400080558298,1739137700.741862,42.429959535598755,0.0,1739137700.741864,42.429959535598755,0.03404239364628203,1739137700.7418656,42.429959535598755,4.239878488729353,1739137700.7418675,42.429959535598755,0.8614976144095478 +1739137700.7633102,42.44995951652527,42.078855331551054,1739137700.7633162,42.44995951652527,1.235919653288823,1739137700.7633233,42.44995951652527,70.18047424012968,1739137700.7633312,42.44995951652527,38.55897820956503,1739137700.763335,42.44995951652527,-0.0113278013874126,1739137700.7633395,42.44995951652527,-2.801053125683125,1739137700.7633436,42.44995951652527,-2.566547783935601,1739137700.7633474,42.44995951652527,-0.6108,1739137700.7633514,42.44995951652527,0.8955400080558298,1739137700.7633562,42.44995951652527,0.0,1739137700.76336,42.44995951652527,0.03404239364628203,1739137700.7633643,42.44995951652527,4.239878488729353,1739137700.7633684,42.44995951652527,0.8614976144095478 +1739137700.7824311,42.46995949745178,42.078855331551054,1739137700.7824368,42.46995949745178,1.235919653288823,1739137700.7824435,42.46995949745178,70.18047424012968,1739137700.7824497,42.46995949745178,38.55897820956503,1739137700.7824528,42.46995949745178,-0.0113278013874126,1739137700.7824566,42.46995949745178,-2.801053125683125,1739137700.7824602,42.46995949745178,-2.566547783935601,1739137700.7824655,42.46995949745178,-0.6108,1739137700.7824848,42.46995949745178,0.8955400080558298,1739137700.7824903,42.46995949745178,0.0,1739137700.7824972,42.46995949745178,0.03404239364628203,1739137700.782501,42.46995949745178,4.239878488729353,1739137700.782503,42.46995949745178,0.8614976144095478 +1739137700.8034909,42.489959478378296,42.078855331551054,1739137700.8034964,42.489959478378296,1.235919653288823,1739137700.8035033,42.489959478378296,70.18047424012968,1739137700.8035111,42.489959478378296,38.55897820956503,1739137700.8035152,42.489959478378296,-0.0113278013874126,1739137700.80352,42.489959478378296,-2.801053125683125,1739137700.803524,42.489959478378296,-2.566547783935601,1739137700.8035283,42.489959478378296,-0.6108,1739137700.803532,42.489959478378296,0.8955400080558298,1739137700.8035364,42.489959478378296,0.0,1739137700.8035405,42.489959478378296,0.03404239364628203,1739137700.8035448,42.489959478378296,4.239878488729353,1739137700.8035486,42.489959478378296,0.8614976144095478 +1739137700.8239794,42.50995945930481,42.078855331551054,1739137700.8239856,42.50995945930481,1.235919653288823,1739137700.8239925,42.50995945930481,70.18047424012968,1739137700.824,42.50995945930481,38.55897820956503,1739137700.8240037,42.50995945930481,-0.0113278013874126,1739137700.8240087,42.50995945930481,-2.801053125683125,1739137700.8240128,42.50995945930481,-2.566547783935601,1739137700.8240166,42.50995945930481,-0.6108,1739137700.8240206,42.50995945930481,0.8955400080558298,1739137700.824025,42.50995945930481,0.0,1739137700.8240292,42.50995945930481,0.03404239364628203,1739137700.8240333,42.50995945930481,4.239878488729353,1739137700.8240373,42.50995945930481,0.8614976144095478 +1739137700.8431015,42.52995944023132,42.034600258508604,1739137700.8431072,42.52995944023132,1.1519669081275872,1739137700.843114,42.52995944023132,70.24689897094069,1739137700.8431208,42.52995944023132,38.4831208094862,1739137700.8431246,42.52995944023132,-0.018387919051379528,1739137700.8431292,42.52995944023132,-2.823259901899919,1739137700.8431332,42.52995944023132,-2.5549550185177976,1739137700.8431373,42.52995944023132,-0.6108,1739137700.843141,42.52995944023132,0.8997023653378913,1739137700.8431454,42.52995944023132,0.0,1739137700.8431497,42.52995944023132,0.03577695601961021,1739137700.843154,42.52995944023132,4.21214597449982,1739137700.8431582,42.52995944023132,0.8647513918134326 +1739137700.8625016,42.54995942115784,42.034600258508604,1739137700.8625076,42.54995942115784,1.1519669081275872,1739137700.862515,42.54995942115784,70.24689897094069,1739137700.862523,42.54995942115784,38.4831208094862,1739137700.8625274,42.54995942115784,-0.018387919051379528,1739137700.8625317,42.54995942115784,-2.823259901899919,1739137700.8625333,42.54995942115784,-2.5549550185177976,1739137700.8625352,42.54995942115784,-0.6108,1739137700.862537,42.54995942115784,0.8997023653378913,1739137700.8625393,42.54995942115784,0.0,1739137700.8625407,42.54995942115784,0.03495097352445864,1739137700.8625429,42.54995942115784,4.21214597449982,1739137700.8625443,42.54995942115784,0.8647513918134326 +1739137700.8815918,42.56995940208435,42.034600258508604,1739137700.8815942,42.56995940208435,1.1519669081275872,1739137700.881597,42.56995940208435,70.24689897094069,1739137700.8815994,42.56995940208435,38.4831208094862,1739137700.881601,42.56995940208435,-0.018387919051379528,1739137700.8816025,42.56995940208435,-2.823259901899919,1739137700.8816042,42.56995940208435,-2.5549550185177976,1739137700.8816054,42.56995940208435,-0.6108,1739137700.8816066,42.56995940208435,0.8997023653378913,1739137700.8816082,42.56995940208435,0.0,1739137700.8816094,42.56995940208435,0.03495097352445864,1739137700.881611,42.56995940208435,4.21214597449982,1739137700.8816123,42.56995940208435,0.8647513918134326 +1739137700.9012814,42.589959383010864,42.034600258508604,1739137700.9012835,42.589959383010864,1.1519669081275872,1739137700.9012861,42.589959383010864,70.24689897094069,1739137700.9012887,42.589959383010864,38.4831208094862,1739137700.9012902,42.589959383010864,-0.018387919051379528,1739137700.9012918,42.589959383010864,-2.823259901899919,1739137700.901293,42.589959383010864,-2.5549550185177976,1739137700.9012942,42.589959383010864,-0.6108,1739137700.9012957,42.589959383010864,0.8997023653378913,1739137700.901297,42.589959383010864,0.0,1739137700.9012983,42.589959383010864,0.03495097352445864,1739137700.9012997,42.589959383010864,4.21214597449982,1739137700.901301,42.589959383010864,0.8647513918134326 +1739137700.9212918,42.60995936393738,42.034600258508604,1739137700.9212945,42.60995936393738,1.1519669081275872,1739137700.9212973,42.60995936393738,70.24689897094069,1739137700.9212997,42.60995936393738,38.4831208094862,1739137700.9213014,42.60995936393738,-0.018387919051379528,1739137700.9213028,42.60995936393738,-2.823259901899919,1739137700.921304,42.60995936393738,-2.5549550185177976,1739137700.9213057,42.60995936393738,-0.6108,1739137700.9213066,42.60995936393738,0.8997023653378913,1739137700.9213083,42.60995936393738,0.0,1739137700.9213092,42.60995936393738,0.03495097352445864,1739137700.9213107,42.60995936393738,4.21214597449982,1739137700.921312,42.60995936393738,0.8647513918134326 +1739137700.9415634,42.62995934486389,41.98783361626981,1739137700.9415658,42.62995934486389,1.0689174675767985,1739137700.941598,42.62995934486389,70.3740994037902,1739137700.941601,42.62995934486389,38.345017027384735,1739137700.9416025,42.62995934486389,-0.03132817341672649,1739137700.9416041,42.62995934486389,-2.848273070249371,1739137700.9416056,42.62995934486389,-2.5924817994579548,1739137700.9416075,42.62995934486389,-0.6108,1739137700.9416087,42.62995934486389,0.8862980477746283,1739137700.9416103,42.62995934486389,0.0,1739137700.9416113,42.62995934486389,0.002035870600732407,1739137700.9416127,42.62995934486389,4.184413460270287,1739137700.9416144,42.62995934486389,0.8685883108090071 +1739137700.9715838,42.649959325790405,41.98783361626981,1739137700.9715924,42.649959325790405,1.0689174675767985,1739137700.9716024,42.649959325790405,70.3740994037902,1739137700.9716127,42.649959325790405,38.345017027384735,1739137700.9716177,42.649959325790405,-0.03132817341672649,1739137700.971624,42.649959325790405,-2.848273070249371,1739137700.971629,42.649959325790405,-2.5924817994579548,1739137700.9716337,42.649959325790405,-0.6108,1739137700.971638,42.649959325790405,0.8862980477746283,1739137700.9716434,42.649959325790405,0.0,1739137700.971648,42.649959325790405,0.01770973696562117,1739137700.9716532,42.649959325790405,4.184413460270287,1739137700.971658,42.649959325790405,0.8685883108090071 +1739137700.992418,42.66995930671692,41.98783361626981,1739137700.9924242,42.66995930671692,1.0689174675767985,1739137700.9924312,42.66995930671692,70.3740994037902,1739137700.992438,42.66995930671692,38.345017027384735,1739137700.9924412,42.66995930671692,-0.03132817341672649,1739137700.9924452,42.66995930671692,-2.848273070249371,1739137700.9924486,42.66995930671692,-2.5924817994579548,1739137700.992452,42.66995930671692,-0.6108,1739137700.9924552,42.66995930671692,0.8862980477746283,1739137700.992459,42.66995930671692,0.0,1739137700.9924624,42.66995930671692,0.01770973696562117,1739137700.9924662,42.66995930671692,4.184413460270287,1739137700.9924695,42.66995930671692,0.8685883108090071 +1739137701.009165,42.69995927810669,41.98783361626981,1739137701.0091686,42.69995927810669,1.0689174675767985,1739137701.0091727,42.69995927810669,70.3740994037902,1739137701.009177,42.69995927810669,38.345017027384735,1739137701.009179,42.69995927810669,-0.03132817341672649,1739137701.0091817,42.69995927810669,-2.848273070249371,1739137701.009184,42.69995927810669,-2.5924817994579548,1739137701.009186,42.69995927810669,-0.6108,1739137701.0091882,42.69995927810669,0.8862980477746283,1739137701.0091903,42.69995927810669,0.0,1739137701.0091927,42.69995927810669,0.01770973696562117,1739137701.0091953,42.69995927810669,4.184413460270287,1739137701.0091975,42.69995927810669,0.8685883108090071 +1739137701.0281968,42.7199592590332,41.98783361626981,1739137701.0282001,42.7199592590332,1.0689174675767985,1739137701.0282037,42.7199592590332,70.3740994037902,1739137701.0282075,42.7199592590332,38.345017027384735,1739137701.0282094,42.7199592590332,-0.03132817341672649,1739137701.0282114,42.7199592590332,-2.848273070249371,1739137701.0282133,42.7199592590332,-2.5924817994579548,1739137701.028215,42.7199592590332,-0.6108,1739137701.0282168,42.7199592590332,0.8862980477746283,1739137701.0282185,42.7199592590332,0.0,1739137701.0282202,42.7199592590332,0.01770973696562117,1739137701.0282223,42.7199592590332,4.184413460270287,1739137701.028224,42.7199592590332,0.8685883108090071 +1739137701.0478773,42.73995923995972,41.93863594361971,1739137701.0478804,42.73995923995972,0.9869521463925723,1739137701.0478842,42.73995923995972,70.51688852011831,1739137701.0478878,42.73995923995972,38.198270136839014,1739137701.0478897,42.73995923995972,-0.04298751511062225,1739137701.0478916,42.73995923995972,-2.872893640006992,1739137701.0478935,42.73995923995972,-2.6342027980737592,1739137701.047895,42.73995923995972,-0.6108,1739137701.0478969,42.73995923995972,0.8716298864180698,1739137701.0478985,42.73995923995972,0.0,1739137701.0479004,42.73995923995972,-0.013107414913882318,1739137701.047902,42.73995923995972,4.156680946040754,1739137701.0479043,42.73995923995972,0.8700624597728926 +1739137701.068019,42.75995922088623,41.93863594361971,1739137701.068022,42.75995922088623,0.9869521463925723,1739137701.0680256,42.75995922088623,70.51688852011831,1739137701.0680292,42.75995922088623,38.198270136839014,1739137701.068031,42.75995922088623,-0.04298751511062225,1739137701.068033,42.75995922088623,-2.872893640006992,1739137701.068035,42.75995922088623,-2.6342027980737592,1739137701.0680366,42.75995922088623,-0.6108,1739137701.0680387,42.75995922088623,0.8716298864180698,1739137701.0680406,42.75995922088623,0.0,1739137701.0680423,42.75995922088623,0.0015674266451771723,1739137701.0680442,42.75995922088623,4.156680946040754,1739137701.0680459,42.75995922088623,0.8700624597728926 +1739137701.0880983,42.76995921134949,41.93863594361971,1739137701.0881014,42.76995921134949,0.9869521463925723,1739137701.088105,42.76995921134949,70.51688852011831,1739137701.0881085,42.76995921134949,38.198270136839014,1739137701.0881104,42.76995921134949,-0.04298751511062225,1739137701.0881126,42.76995921134949,-2.872893640006992,1739137701.0881145,42.76995921134949,-2.6342027980737592,1739137701.088116,42.76995921134949,-0.6108,1739137701.0881178,42.76995921134949,0.8716298864180698,1739137701.0881195,42.76995921134949,0.0,1739137701.0881214,42.76995921134949,0.0015674266451771723,1739137701.088123,42.76995921134949,4.156680946040754,1739137701.088125,42.76995921134949,0.8700624597728926 +1739137701.1076653,42.79995918273926,41.93863594361971,1739137701.1076684,42.79995918273926,0.9869521463925723,1739137701.107672,42.79995918273926,70.51688852011831,1739137701.1076753,42.79995918273926,38.198270136839014,1739137701.1076772,42.79995918273926,-0.04298751511062225,1739137701.1076791,42.79995918273926,-2.872893640006992,1739137701.107681,42.79995918273926,-2.6342027980737592,1739137701.1076827,42.79995918273926,-0.6108,1739137701.1076846,42.79995918273926,0.8716298864180698,1739137701.1076868,42.79995918273926,0.0,1739137701.1076884,42.79995918273926,0.0015674266451771723,1739137701.1076903,42.79995918273926,4.156680946040754,1739137701.1076922,42.79995918273926,0.8700624597728926 +1739137701.1281574,42.81995916366577,41.93863594361971,1739137701.1281602,42.81995916366577,0.9869521463925723,1739137701.1281638,42.81995916366577,70.51688852011831,1739137701.1281676,42.81995916366577,38.198270136839014,1739137701.1281695,42.81995916366577,-0.04298751511062225,1739137701.1281714,42.81995916366577,-2.872893640006992,1739137701.1281734,42.81995916366577,-2.6342027980737592,1739137701.128175,42.81995916366577,-0.6108,1739137701.1281767,42.81995916366577,0.8716298864180698,1739137701.1281786,42.81995916366577,0.0,1739137701.1281805,42.81995916366577,0.0015674266451771723,1739137701.1281824,42.81995916366577,4.156680946040754,1739137701.128184,42.81995916366577,0.8700624597728926 +1739137701.1471684,42.82995915412903,41.93863594361971,1739137701.1471713,42.82995915412903,0.9869521463925723,1739137701.1471746,42.82995915412903,70.51688852011831,1739137701.147178,42.82995915412903,38.198270136839014,1739137701.1471796,42.82995915412903,-0.04298751511062225,1739137701.1471813,42.82995915412903,-2.872893640006992,1739137701.1471834,42.82995915412903,-2.6342027980737592,1739137701.1471848,42.82995915412903,-0.6108,1739137701.1471863,42.82995915412903,0.8716298864180698,1739137701.147188,42.82995915412903,0.0,1739137701.1471896,42.82995915412903,0.0015674266451771723,1739137701.1471913,42.82995915412903,4.156680946040754,1739137701.1471927,42.82995915412903,0.8700624597728926 +1739137701.1671176,42.8599591255188,41.88713737183162,1739137701.1671205,42.8599591255188,0.9063082027657012,1739137701.1671236,42.8599591255188,70.51813609350071,1739137701.167127,42.8599591255188,38.19738518934611,1739137701.1671283,42.8599591255188,-0.043063639626141154,1739137701.16713,42.8599591255188,-2.8897556451736706,1739137701.167132,42.8599591255188,-2.5563569981586336,1739137701.167133,42.8599591255188,-0.6108,1739137701.1671348,42.8599591255188,0.8991979610244198,1739137701.1671364,42.8599591255188,0.0,1739137701.1671379,42.8599591255188,0.054426093467520906,1739137701.1671395,42.8599591255188,4.128948431811221,1739137701.167141,42.8599591255188,0.869942673855742 +1739137701.1871705,42.869959115982056,41.88713737183162,1739137701.1871731,42.869959115982056,0.9063082027657012,1739137701.1871762,42.869959115982056,70.51813609350071,1739137701.1871793,42.869959115982056,38.19738518934611,1739137701.1871808,42.869959115982056,-0.043063639626141154,1739137701.1871827,42.869959115982056,-2.8897556451736706,1739137701.187184,42.869959115982056,-2.5563569981586336,1739137701.1871858,42.869959115982056,-0.6108,1739137701.1871872,42.869959115982056,0.8991979610244198,1739137701.187189,42.869959115982056,0.0,1739137701.1871903,42.869959115982056,0.029255287168677868,1739137701.187192,42.869959115982056,4.128948431811221,1739137701.1871936,42.869959115982056,0.869942673855742 +1739137701.207546,42.899959087371826,41.88713737183162,1739137701.2075486,42.899959087371826,0.9063082027657012,1739137701.2075515,42.899959087371826,70.51813609350071,1739137701.2075546,42.899959087371826,38.19738518934611,1739137701.207556,42.899959087371826,-0.043063639626141154,1739137701.207558,42.899959087371826,-2.8897556451736706,1739137701.2075593,42.899959087371826,-2.5563569981586336,1739137701.207561,42.899959087371826,-0.6108,1739137701.2075624,42.899959087371826,0.8991979610244198,1739137701.2075644,42.899959087371826,0.0,1739137701.2075655,42.899959087371826,0.029255287168677868,1739137701.2075675,42.899959087371826,4.128948431811221,1739137701.207569,42.899959087371826,0.869942673855742 +1739137701.2275853,42.91995906829834,41.88713737183162,1739137701.227588,42.91995906829834,0.9063082027657012,1739137701.2275913,42.91995906829834,70.51813609350071,1739137701.2275941,42.91995906829834,38.19738518934611,1739137701.227596,42.91995906829834,-0.043063639626141154,1739137701.2275977,42.91995906829834,-2.8897556451736706,1739137701.2275996,42.91995906829834,-2.5563569981586336,1739137701.227601,42.91995906829834,-0.6108,1739137701.2276027,42.91995906829834,0.8991979610244198,1739137701.2276044,42.91995906829834,0.0,1739137701.227606,42.91995906829834,0.029255287168677868,1739137701.2276075,42.91995906829834,4.128948431811221,1739137701.2276092,42.91995906829834,0.869942673855742 +1739137701.2469428,42.93995904922485,41.88713737183162,1739137701.2469456,42.93995904922485,0.9063082027657012,1739137701.2469487,42.93995904922485,70.51813609350071,1739137701.2469516,42.93995904922485,38.19738518934611,1739137701.2469532,42.93995904922485,-0.043063639626141154,1739137701.246955,42.93995904922485,-2.8897556451736706,1739137701.2469568,42.93995904922485,-2.5563569981586336,1739137701.246958,42.93995904922485,-0.6108,1739137701.2469597,42.93995904922485,0.8991979610244198,1739137701.2469614,42.93995904922485,0.0,1739137701.246963,42.93995904922485,0.029255287168677868,1739137701.2469645,42.93995904922485,4.128948431811221,1739137701.2469661,42.93995904922485,0.869942673855742 +1739137701.2670596,42.95995903015137,41.83331968086326,1739137701.2670622,42.95995903015137,0.8269734308564116,1739137701.2670653,42.95995903015137,70.69315116129951,1739137701.2670681,42.95995903015137,38.01267173640209,1739137701.26707,42.95995903015137,-0.057828310167102014,1739137701.267072,42.95995903015137,-2.914020170145656,1739137701.2670736,42.95995903015137,-2.6212923359885427,1739137701.267075,42.95995903015137,-0.6108,1739137701.2670765,42.95995903015137,0.8761427869552351,1739137701.2670784,42.95995903015137,0.0,1739137701.2670798,42.95995903015137,-0.02131279363134493,1739137701.2670815,42.95995903015137,4.101215917581688,1739137701.267083,42.95995903015137,0.8733755300813414 +1739137701.2884889,42.97995901107788,41.83331968086326,1739137701.288492,42.97995901107788,0.8269734308564116,1739137701.288495,42.97995901107788,70.69315116129951,1739137701.2884982,42.97995901107788,38.01267173640209,1739137701.2884996,42.97995901107788,-0.057828310167102014,1739137701.2885017,42.97995901107788,-2.914020170145656,1739137701.2885034,42.97995901107788,-2.6212923359885427,1739137701.2885048,42.97995901107788,-0.6108,1739137701.2885065,42.97995901107788,0.8761427869552351,1739137701.2885084,42.97995901107788,0.0,1739137701.2885098,42.97995901107788,0.0027672568738936754,1739137701.2885115,42.97995901107788,4.101215917581688,1739137701.2885132,42.97995901107788,0.8733755300813414 +1739137701.3076522,42.999958992004395,41.83331968086326,1739137701.3076549,42.999958992004395,0.8269734308564116,1739137701.3076582,42.999958992004395,70.69315116129951,1739137701.3076613,42.999958992004395,38.01267173640209,1739137701.307663,42.999958992004395,-0.057828310167102014,1739137701.3076649,42.999958992004395,-2.914020170145656,1739137701.3076665,42.999958992004395,-2.6212923359885427,1739137701.307668,42.999958992004395,-0.6108,1739137701.3076694,42.999958992004395,0.8761427869552351,1739137701.3076713,42.999958992004395,0.0,1739137701.3076727,42.999958992004395,0.0027672568738936754,1739137701.3076746,42.999958992004395,4.101215917581688,1739137701.307676,42.999958992004395,0.8733755300813414 +1739137701.3270888,43.00995898246765,41.83331968086326,1739137701.3270917,43.00995898246765,0.8269734308564116,1739137701.3270948,43.00995898246765,70.69315116129951,1739137701.3270981,43.00995898246765,38.01267173640209,1739137701.3270996,43.00995898246765,-0.057828310167102014,1739137701.3271017,43.00995898246765,-2.914020170145656,1739137701.3271031,43.00995898246765,-2.6212923359885427,1739137701.3271048,43.00995898246765,-0.6108,1739137701.3271062,43.00995898246765,0.8761427869552351,1739137701.3271081,43.00995898246765,0.0,1739137701.3271096,43.00995898246765,0.0027672568738936754,1739137701.3271112,43.00995898246765,4.101215917581688,1739137701.3271127,43.00995898246765,0.8733755300813414 +1739137701.3475242,43.029958963394165,41.83331968086326,1739137701.347527,43.029958963394165,0.8269734308564116,1739137701.34753,43.029958963394165,70.69315116129951,1739137701.347533,43.029958963394165,38.01267173640209,1739137701.3475347,43.029958963394165,-0.057828310167102014,1739137701.3475363,43.029958963394165,-2.914020170145656,1739137701.347538,43.029958963394165,-2.6212923359885427,1739137701.3475394,43.029958963394165,-0.6108,1739137701.347541,43.029958963394165,0.8761427869552351,1739137701.3475425,43.029958963394165,0.0,1739137701.3475437,43.029958963394165,0.0027672568738936754,1739137701.3475454,43.029958963394165,4.101215917581688,1739137701.3475468,43.029958963394165,0.8733755300813414 +1739137701.367198,43.059958934783936,41.83331968086326,1739137701.3672006,43.059958934783936,0.8269734308564116,1739137701.367204,43.059958934783936,70.69315116129951,1739137701.3672068,43.059958934783936,38.01267173640209,1739137701.3672085,43.059958934783936,-0.057828310167102014,1739137701.36721,43.059958934783936,-2.914020170145656,1739137701.3672116,43.059958934783936,-2.6212923359885427,1739137701.367213,43.059958934783936,-0.6108,1739137701.3672147,43.059958934783936,0.8761427869552351,1739137701.367216,43.059958934783936,0.0,1739137701.3672178,43.059958934783936,0.0027672568738936754,1739137701.3672194,43.059958934783936,4.101215917581688,1739137701.3672206,43.059958934783936,0.8733755300813414 +1739137701.3874648,43.07995891571045,41.77722337459264,1739137701.3874671,43.07995891571045,0.7490217271742221,1739137701.3874702,43.07995891571045,70.69935816492668,1739137701.3874733,43.07995891571045,38.007001121975584,1739137701.387475,43.07995891571045,-0.05818072123315602,1739137701.3874767,43.07995891571045,-2.9306774297794855,1739137701.3874786,43.07995891571045,-2.5451928762894815,1739137701.38748,43.07995891571045,-0.6108,1739137701.3874817,43.07995891571045,0.9032224425453782,1739137701.3874834,43.07995891571045,0.0,1739137701.3874848,43.07995891571045,0.05479918152909853,1739137701.3874865,43.07995891571045,4.073483403352155,1739137701.3874876,43.07995891571045,0.8732003803722023 +1739137701.4077559,43.09995889663696,41.77722337459264,1739137701.4077585,43.09995889663696,0.7490217271742221,1739137701.4077616,43.09995889663696,70.69935816492668,1739137701.4077647,43.09995889663696,38.007001121975584,1739137701.4077663,43.09995889663696,-0.05818072123315602,1739137701.407768,43.09995889663696,-2.9306774297794855,1739137701.4077697,43.09995889663696,-2.5451928762894815,1739137701.407771,43.09995889663696,-0.6108,1739137701.4077728,43.09995889663696,0.9032224425453782,1739137701.4077744,43.09995889663696,0.0,1739137701.407776,43.09995889663696,0.030022062173175934,1739137701.4077775,43.09995889663696,4.073483403352155,1739137701.4077792,43.09995889663696,0.8732003803722023 +1739137701.4271798,43.11995887756348,41.77722337459264,1739137701.4271827,43.11995887756348,0.7490217271742221,1739137701.427186,43.11995887756348,70.69935816492668,1739137701.4271889,43.11995887756348,38.007001121975584,1739137701.4271905,43.11995887756348,-0.05818072123315602,1739137701.4271922,43.11995887756348,-2.9306774297794855,1739137701.427194,43.11995887756348,-2.5451928762894815,1739137701.4271953,43.11995887756348,-0.6108,1739137701.427197,43.11995887756348,0.9032224425453782,1739137701.4271986,43.11995887756348,0.0,1739137701.4272003,43.11995887756348,0.030022062173175934,1739137701.4272017,43.11995887756348,4.073483403352155,1739137701.4272034,43.11995887756348,0.8732003803722023 +1739137701.4474578,43.12995886802673,41.77722337459264,1739137701.4474607,43.12995886802673,0.7490217271742221,1739137701.447464,43.12995886802673,70.69935816492668,1739137701.447467,43.12995886802673,38.007001121975584,1739137701.4474688,43.12995886802673,-0.05818072123315602,1739137701.4474707,43.12995886802673,-2.9306774297794855,1739137701.447472,43.12995886802673,-2.5451928762894815,1739137701.4474738,43.12995886802673,-0.6108,1739137701.4474752,43.12995886802673,0.9032224425453782,1739137701.4474766,43.12995886802673,0.0,1739137701.4474783,43.12995886802673,0.030022062173175934,1739137701.4474797,43.12995886802673,4.073483403352155,1739137701.4474814,43.12995886802673,0.8732003803722023 +1739137701.4673977,43.14995884895325,41.77722337459264,1739137701.4674006,43.14995884895325,0.7490217271742221,1739137701.4674034,43.14995884895325,70.69935816492668,1739137701.467407,43.14995884895325,38.007001121975584,1739137701.4674084,43.14995884895325,-0.05818072123315602,1739137701.4674103,43.14995884895325,-2.9306774297794855,1739137701.467412,43.14995884895325,-2.5451928762894815,1739137701.4674134,43.14995884895325,-0.6108,1739137701.467415,43.14995884895325,0.9032224425453782,1739137701.4674165,43.14995884895325,0.0,1739137701.4674182,43.14995884895325,0.030022062173175934,1739137701.4674199,43.14995884895325,4.073483403352155,1739137701.4674215,43.14995884895325,0.8732003803722023 +1739137701.4893458,43.17995882034302,41.71887067650024,1739137701.4893491,43.17995882034302,0.6725043375320299,1739137701.4893525,43.17995882034302,70.82416166218862,1739137701.489356,43.17995882034302,37.87191798729954,1739137701.4893577,43.17995882034302,-0.06657571830341841,1739137701.48936,43.17995882034302,-2.9517844918176954,1739137701.4893622,43.17995882034302,-2.5663308954797723,1739137701.489364,43.17995882034302,-0.6108,1739137701.489366,43.17995882034302,0.8956177043418585,1739137701.489368,43.17995882034302,0.0,1739137701.4893699,43.17995882034302,0.008796485728059762,1739137701.489372,43.17995882034302,4.045750889122622,1739137701.4893737,43.17995882034302,0.8767137962098824 +1739137701.5082376,43.19995880126953,41.71887067650024,1739137701.50824,43.19995880126953,0.6725043375320299,1739137701.508243,43.19995880126953,70.82416166218862,1739137701.5082462,43.19995880126953,37.87191798729954,1739137701.5082479,43.19995880126953,-0.06657571830341841,1739137701.5082495,43.19995880126953,-2.9517844918176954,1739137701.5082514,43.19995880126953,-2.5663308954797723,1739137701.5082529,43.19995880126953,-0.6108,1739137701.5082543,43.19995880126953,0.8956177043418585,1739137701.508256,43.19995880126953,0.0,1739137701.5082576,43.19995880126953,0.018903908131976066,1739137701.508259,43.19995880126953,4.045750889122622,1739137701.508261,43.19995880126953,0.8767137962098824 +1739137701.530352,43.20995879173279,41.71887067650024,1739137701.5303562,43.20995879173279,0.6725043375320299,1739137701.5303614,43.20995879173279,70.82416166218862,1739137701.5303674,43.20995879173279,37.87191798729954,1739137701.5303712,43.20995879173279,-0.06657571830341841,1739137701.5303755,43.20995879173279,-2.9517844918176954,1739137701.5303793,43.20995879173279,-2.5663308954797723,1739137701.530383,43.20995879173279,-0.6108,1739137701.5303872,43.20995879173279,0.8956177043418585,1739137701.530391,43.20995879173279,0.0,1739137701.5303948,43.20995879173279,0.018903908131976066,1739137701.5303993,43.20995879173279,4.045750889122622,1739137701.5304031,43.20995879173279,0.8767137962098824 +1739137701.5508428,43.2299587726593,41.71887067650024,1739137701.550847,43.2299587726593,0.6725043375320299,1739137701.550852,43.2299587726593,70.82416166218862,1739137701.5508583,43.2299587726593,37.87191798729954,1739137701.5508616,43.2299587726593,-0.06657571830341841,1739137701.550866,43.2299587726593,-2.9517844918176954,1739137701.55087,43.2299587726593,-2.5663308954797723,1739137701.550874,43.2299587726593,-0.6108,1739137701.550878,43.2299587726593,0.8956177043418585,1739137701.550882,43.2299587726593,0.0,1739137701.550886,43.2299587726593,0.018903908131976066,1739137701.55089,43.2299587726593,4.045750889122622,1739137701.550894,43.2299587726593,0.8767137962098824 +1739137701.5676825,43.25995874404907,41.71887067650024,1739137701.5676851,43.25995874404907,0.6725043375320299,1739137701.5676882,43.25995874404907,70.82416166218862,1739137701.567691,43.25995874404907,37.87191798729954,1739137701.5676925,43.25995874404907,-0.06657571830341841,1739137701.5676944,43.25995874404907,-2.9517844918176954,1739137701.5676959,43.25995874404907,-2.5663308954797723,1739137701.5676975,43.25995874404907,-0.6108,1739137701.5676987,43.25995874404907,0.8956177043418585,1739137701.5677004,43.25995874404907,0.0,1739137701.5677018,43.25995874404907,0.018903908131976066,1739137701.5677035,43.25995874404907,4.045750889122622,1739137701.5677052,43.25995874404907,0.8767137962098824 +1739137701.5872662,43.279958724975586,41.71887067650024,1739137701.5872688,43.279958724975586,0.6725043375320299,1739137701.5872724,43.279958724975586,70.82416166218862,1739137701.5872755,43.279958724975586,37.87191798729954,1739137701.5872772,43.279958724975586,-0.06657571830341841,1739137701.5872793,43.279958724975586,-2.9517844918176954,1739137701.587281,43.279958724975586,-2.5663308954797723,1739137701.5872824,43.279958724975586,-0.6108,1739137701.5872836,43.279958724975586,0.8956177043418585,1739137701.5872858,43.279958724975586,0.0,1739137701.5872872,43.279958724975586,0.018903908131976066,1739137701.5872889,43.279958724975586,4.045750889122622,1739137701.5872903,43.279958724975586,0.8767137962098824 +1739137701.6079166,43.2999587059021,41.65823592831964,1739137701.6079197,43.2999587059021,0.5974074021257403,1739137701.607923,43.2999587059021,70.85157667540517,1739137701.6079264,43.2999587059021,37.838950207655806,1739137701.607928,43.2999587059021,-0.06859701736698168,1739137701.6079302,43.2999587059021,-2.968949294001638,1739137701.6079316,43.2999587059021,-2.508777841278946,1739137701.6079335,43.2999587059021,-0.6108,1739137701.607935,43.2999587059021,0.916475078013883,1739137701.6079373,43.2999587059021,0.0,1739137701.6079388,43.2999587059021,0.05514955698248479,1739137701.607941,43.2999587059021,4.018018374893089,1739137701.6079423,43.2999587059021,0.8785853624393996 +1739137701.6276355,43.31995868682861,41.65823592831964,1739137701.6276386,43.31995868682861,0.5974074021257403,1739137701.627642,43.31995868682861,70.85157667540517,1739137701.6276457,43.31995868682861,37.838950207655806,1739137701.6276474,43.31995868682861,-0.06859701736698168,1739137701.6276493,43.31995868682861,-2.968949294001638,1739137701.6276512,43.31995868682861,-2.508777841278946,1739137701.627653,43.31995868682861,-0.6108,1739137701.6276546,43.31995868682861,0.916475078013883,1739137701.6276565,43.31995868682861,0.0,1739137701.6276581,43.31995868682861,0.037889715574483396,1739137701.6276603,43.31995868682861,4.018018374893089,1739137701.6276617,43.31995868682861,0.8785853624393996 +1739137701.647775,43.33995866775513,41.65823592831964,1739137701.647778,43.33995866775513,0.5974074021257403,1739137701.6477818,43.33995866775513,70.85157667540517,1739137701.6477854,43.33995866775513,37.838950207655806,1739137701.647787,43.33995866775513,-0.06859701736698168,1739137701.647789,43.33995866775513,-2.968949294001638,1739137701.647791,43.33995866775513,-2.508777841278946,1739137701.6477923,43.33995866775513,-0.6108,1739137701.647794,43.33995866775513,0.916475078013883,1739137701.647796,43.33995866775513,0.0,1739137701.6477976,43.33995866775513,0.037889715574483396,1739137701.6477993,43.33995866775513,4.018018374893089,1739137701.6478012,43.33995866775513,0.8785853624393996 +1739137701.6704624,43.349958658218384,41.65823592831964,1739137701.6704655,43.349958658218384,0.5974074021257403,1739137701.6704879,43.349958658218384,70.85157667540517,1739137701.6704922,43.349958658218384,37.838950207655806,1739137701.6704936,43.349958658218384,-0.06859701736698168,1739137701.6704962,43.349958658218384,-2.968949294001638,1739137701.670498,43.349958658218384,-2.508777841278946,1739137701.6704996,43.349958658218384,-0.6108,1739137701.6705012,43.349958658218384,0.916475078013883,1739137701.6705031,43.349958658218384,0.0,1739137701.670505,43.349958658218384,0.037889715574483396,1739137701.6705067,43.349958658218384,4.018018374893089,1739137701.6705084,43.349958658218384,0.8785853624393996 +1739137701.687708,43.379958629608154,41.65823592831964,1739137701.687711,43.379958629608154,0.5974074021257403,1739137701.6877143,43.379958629608154,70.85157667540517,1739137701.687718,43.379958629608154,37.838950207655806,1739137701.6877196,43.379958629608154,-0.06859701736698168,1739137701.6877217,43.379958629608154,-2.968949294001638,1739137701.6877236,43.379958629608154,-2.508777841278946,1739137701.687725,43.379958629608154,-0.6108,1739137701.6877267,43.379958629608154,0.916475078013883,1739137701.6877286,43.379958629608154,0.0,1739137701.6877306,43.379958629608154,0.037889715574483396,1739137701.6877322,43.379958629608154,4.018018374893089,1739137701.6877337,43.379958629608154,0.8785853624393996 +1739137701.7146468,43.39995861053467,41.595321183479776,1739137701.7146523,43.39995861053467,0.5237630074773652,1739137701.7146585,43.39995861053467,71.01062346683807,1739137701.7146657,43.39995861053467,37.66724107663279,1739137701.7146692,43.39995861053467,-0.07799796650332692,1739137701.7146742,43.39995861053467,-2.9895797985415817,1739137701.7146783,43.39995861053467,-2.5499567271400876,1739137701.714682,43.39995861053467,-0.6108,1739137701.7146862,43.39995861053467,0.9015029545420736,1739137701.7146904,43.39995861053467,0.0,1739137701.7146947,43.39995861053467,0.00108372920962449,1739137701.714699,43.39995861053467,3.9902858606635556,1739137701.714703,43.39995861053467,0.8828925564033699 +1739137701.7443435,43.41995859146118,41.595321183479776,1739137701.7443485,43.41995859146118,0.5237630074773652,1739137701.7443535,43.41995859146118,71.01062346683807,1739137701.744359,43.41995859146118,37.66724107663279,1739137701.7443616,43.41995859146118,-0.07799796650332692,1739137701.7443652,43.41995859146118,-2.9895797985415817,1739137701.7443686,43.41995859146118,-2.5499567271400876,1739137701.744372,43.41995859146118,-0.6108,1739137701.744375,43.41995859146118,0.9015029545420736,1739137701.744378,43.41995859146118,0.0,1739137701.7443812,43.41995859146118,0.018610398138703688,1739137701.7443845,43.41995859146118,3.9902858606635556,1739137701.7443876,43.41995859146118,0.8828925564033699 +1739137701.7610815,43.44995856285095,41.595321183479776,1739137701.7610838,43.44995856285095,0.5237630074773652,1739137701.7610865,43.44995856285095,71.01062346683807,1739137701.761089,43.44995856285095,37.66724107663279,1739137701.7610903,43.44995856285095,-0.07799796650332692,1739137701.761092,43.44995856285095,-2.9895797985415817,1739137701.7610934,43.44995856285095,-2.5499567271400876,1739137701.7610946,43.44995856285095,-0.6108,1739137701.7610958,43.44995856285095,0.9015029545420736,1739137701.7610974,43.44995856285095,0.0,1739137701.7610984,43.44995856285095,0.018610398138703688,1739137701.7611,43.44995856285095,3.9902858606635556,1739137701.761101,43.44995856285095,0.8828925564033699 +1739137701.7787275,43.45995855331421,41.595321183479776,1739137701.778732,43.45995855331421,0.5237630074773652,1739137701.7787375,43.45995855331421,71.01062346683807,1739137701.778743,43.45995855331421,37.66724107663279,1739137701.7787457,43.45995855331421,-0.07799796650332692,1739137701.778749,43.45995855331421,-2.9895797985415817,1739137701.778752,43.45995855331421,-2.5499567271400876,1739137701.7787545,43.45995855331421,-0.6108,1739137701.778757,43.45995855331421,0.9015029545420736,1739137701.7787602,43.45995855331421,0.0,1739137701.7787628,43.45995855331421,0.018610398138703688,1739137701.7787657,43.45995855331421,3.9902858606635556,1739137701.778768,43.45995855331421,0.8828925564033699 +1739137701.7973602,43.47995853424072,41.595321183479776,1739137701.7973628,43.47995853424072,0.5237630074773652,1739137701.7973657,43.47995853424072,71.01062346683807,1739137701.7973685,43.47995853424072,37.66724107663279,1739137701.7973702,43.47995853424072,-0.07799796650332692,1739137701.7973716,43.47995853424072,-2.9895797985415817,1739137701.7973735,43.47995853424072,-2.5499567271400876,1739137701.7973747,43.47995853424072,-0.6108,1739137701.7973762,43.47995853424072,0.9015029545420736,1739137701.7973778,43.47995853424072,0.0,1739137701.797379,43.47995853424072,0.018610398138703688,1739137701.7973807,43.47995853424072,3.9902858606635556,1739137701.7973819,43.47995853424072,0.8828925564033699 +1739137701.8172646,43.499958515167236,41.595321183479776,1739137701.8172672,43.499958515167236,0.5237630074773652,1739137701.8172703,43.499958515167236,71.01062346683807,1739137701.817273,43.499958515167236,37.66724107663279,1739137701.817274,43.499958515167236,-0.07799796650332692,1739137701.8172758,43.499958515167236,-2.9895797985415817,1739137701.817277,43.499958515167236,-2.5499567271400876,1739137701.8172781,43.499958515167236,-0.6108,1739137701.8172796,43.499958515167236,0.9015029545420736,1739137701.8172808,43.499958515167236,0.0,1739137701.817282,43.499958515167236,0.018610398138703688,1739137701.8172834,43.499958515167236,3.9902858606635556,1739137701.8172846,43.499958515167236,0.8828925564033699 +1739137701.8361166,43.51995849609375,41.53018089219855,1739137701.8361187,43.51995849609375,0.45166057367621804,1739137701.8361213,43.51995849609375,71.13042790748086,1739137701.836124,43.51995849609375,37.54303046967641,1739137701.8361251,43.51995849609375,-0.08403504326470791,1739137701.8361266,43.51995849609375,-3.008036936887595,1739137701.8361278,43.51995849609375,-2.552713790892448,1739137701.8361292,43.51995849609375,-0.6108,1739137701.8361304,43.51995849609375,0.9005093021079581,1739137701.8361318,43.51995849609375,0.0,1739137701.836133,43.51995849609375,0.013816139129325094,1739137701.8361344,43.51995849609375,3.9625533464340226,1739137701.8361356,43.51995849609375,0.8844101813575275 +1739137701.8555338,43.539958477020264,41.53018089219855,1739137701.8555362,43.539958477020264,0.45166057367621804,1739137701.8555388,43.539958477020264,71.13042790748086,1739137701.8555415,43.539958477020264,37.54303046967641,1739137701.855543,43.539958477020264,-0.08403504326470791,1739137701.8555443,43.539958477020264,-3.008036936887595,1739137701.8555458,43.539958477020264,-2.552713790892448,1739137701.8555472,43.539958477020264,-0.6108,1739137701.8555481,43.539958477020264,0.9005093021079581,1739137701.85555,43.539958477020264,0.0,1739137701.855551,43.539958477020264,0.01609912075043063,1739137701.8555524,43.539958477020264,3.9625533464340226,1739137701.8555539,43.539958477020264,0.8844101813575275 +1739137701.8752353,43.55995845794678,41.53018089219855,1739137701.8752377,43.55995845794678,0.45166057367621804,1739137701.87524,43.55995845794678,71.13042790748086,1739137701.8752427,43.55995845794678,37.54303046967641,1739137701.8752446,43.55995845794678,-0.08403504326470791,1739137701.875246,43.55995845794678,-3.008036936887595,1739137701.8752477,43.55995845794678,-2.552713790892448,1739137701.875249,43.55995845794678,-0.6108,1739137701.87525,43.55995845794678,0.9005093021079581,1739137701.8752518,43.55995845794678,0.0,1739137701.8752527,43.55995845794678,0.01609912075043063,1739137701.8752542,43.55995845794678,3.9625533464340226,1739137701.8752556,43.55995845794678,0.8844101813575275 +1739137701.895239,43.57995843887329,41.53018089219855,1739137701.8952415,43.57995843887329,0.45166057367621804,1739137701.8952441,43.57995843887329,71.13042790748086,1739137701.8952465,43.57995843887329,37.54303046967641,1739137701.895248,43.57995843887329,-0.08403504326470791,1739137701.8952496,43.57995843887329,-3.008036936887595,1739137701.895251,43.57995843887329,-2.552713790892448,1739137701.8952522,43.57995843887329,-0.6108,1739137701.8952534,43.57995843887329,0.9005093021079581,1739137701.895255,43.57995843887329,0.0,1739137701.8952563,43.57995843887329,0.01609912075043063,1739137701.895258,43.57995843887329,3.9625533464340226,1739137701.8952591,43.57995843887329,0.8844101813575275 +1739137701.915138,43.599958419799805,41.53018089219855,1739137701.9151404,43.599958419799805,0.45166057367621804,1739137701.9151433,43.599958419799805,71.13042790748086,1739137701.9151459,43.599958419799805,37.54303046967641,1739137701.9151473,43.599958419799805,-0.08403504326470791,1739137701.915149,43.599958419799805,-3.008036936887595,1739137701.9151504,43.599958419799805,-2.552713790892448,1739137701.9151516,43.599958419799805,-0.6108,1739137701.9151528,43.599958419799805,0.9005093021079581,1739137701.9151545,43.599958419799805,0.0,1739137701.9151556,43.599958419799805,0.01609912075043063,1739137701.9151578,43.599958419799805,3.9625533464340226,1739137701.915159,43.599958419799805,0.8844101813575275 +1739137701.9354873,43.61995840072632,41.4629289391355,1739137701.9354897,43.61995840072632,0.3812483474881372,1739137701.9354923,43.61995840072632,71.13628337550873,1739137701.935495,43.61995840072632,37.53195189608148,1739137701.935496,43.61995840072632,-0.084435473635609,1739137701.935498,43.61995840072632,-3.023677054048054,1739137701.9354992,43.61995840072632,-2.474599776310948,1739137701.9355006,43.61995840072632,-0.6108,1739137701.9355018,43.61995840072632,0.9290904532535527,1739137701.9355032,43.61995840072632,0.0,1739137701.9355044,43.61995840072632,0.06733476172429295,1739137701.9355059,43.61995840072632,3.9348208322044895,1739137701.9355073,43.61995840072632,0.8861536279903627 +1739137701.9552748,43.63995838165283,41.4629289391355,1739137701.955277,43.63995838165283,0.3812483474881372,1739137701.9552798,43.63995838165283,71.13628337550873,1739137701.9552824,43.63995838165283,37.53195189608148,1739137701.9552836,43.63995838165283,-0.084435473635609,1739137701.9552853,43.63995838165283,-3.023677054048054,1739137701.9552867,43.63995838165283,-2.474599776310948,1739137701.9552877,43.63995838165283,-0.6108,1739137701.9552894,43.63995838165283,0.9290904532535527,1739137701.9552908,43.63995838165283,0.0,1739137701.9552922,43.63995838165283,0.04293682526318998,1739137701.955294,43.63995838165283,3.9348208322044895,1739137701.9552953,43.63995838165283,0.8861536279903627 +1739137701.9752367,43.659958362579346,41.4629289391355,1739137701.9752388,43.659958362579346,0.3812483474881372,1739137701.9752414,43.659958362579346,71.13628337550873,1739137701.9752443,43.659958362579346,37.53195189608148,1739137701.9752455,43.659958362579346,-0.084435473635609,1739137701.9752471,43.659958362579346,-3.023677054048054,1739137701.9752486,43.659958362579346,-2.474599776310948,1739137701.97525,43.659958362579346,-0.6108,1739137701.9752512,43.659958362579346,0.9290904532535527,1739137701.9752526,43.659958362579346,0.0,1739137701.975254,43.659958362579346,0.04293682526318998,1739137701.9752555,43.659958362579346,3.9348208322044895,1739137701.9752572,43.659958362579346,0.8861536279903627 +1739137701.9958143,43.67995834350586,41.4629289391355,1739137701.995817,43.67995834350586,0.3812483474881372,1739137701.99582,43.67995834350586,71.13628337550873,1739137701.9958231,43.67995834350586,37.53195189608148,1739137701.9958246,43.67995834350586,-0.084435473635609,1739137701.9958267,43.67995834350586,-3.023677054048054,1739137701.995828,43.67995834350586,-2.474599776310948,1739137701.9958296,43.67995834350586,-0.6108,1739137701.9958308,43.67995834350586,0.9290904532535527,1739137701.9958322,43.67995834350586,0.0,1739137701.995834,43.67995834350586,0.04293682526318998,1739137701.995836,43.67995834350586,3.9348208322044895,1739137701.9958372,43.67995834350586,0.8861536279903627 +1739137702.0227041,43.69995832443237,41.4629289391355,1739137702.0227125,43.69995832443237,0.3812483474881372,1739137702.022723,43.69995832443237,71.13628337550873,1739137702.0227327,43.69995832443237,37.53195189608148,1739137702.0227377,43.69995832443237,-0.084435473635609,1739137702.0227432,43.69995832443237,-3.023677054048054,1739137702.0227482,43.69995832443237,-2.474599776310948,1739137702.0227528,43.69995832443237,-0.6108,1739137702.022757,43.69995832443237,0.9290904532535527,1739137702.0227628,43.69995832443237,0.0,1739137702.0227673,43.69995832443237,0.04293682526318998,1739137702.022773,43.69995832443237,3.9348208322044895,1739137702.0227776,43.69995832443237,0.8861536279903627 +1739137702.0473013,43.70995831489563,41.4629289391355,1739137702.0473099,43.70995831489563,0.3812483474881372,1739137702.0473197,43.70995831489563,71.13628337550873,1739137702.0473292,43.70995831489563,37.53195189608148,1739137702.0473342,43.70995831489563,-0.084435473635609,1739137702.0473406,43.70995831489563,-3.023677054048054,1739137702.0473452,43.70995831489563,-2.474599776310948,1739137702.0473497,43.70995831489563,-0.6108,1739137702.0473545,43.70995831489563,0.9290904532535527,1739137702.0473595,43.70995831489563,0.0,1739137702.0473642,43.70995831489563,0.04293682526318998,1739137702.0473695,43.70995831489563,3.9348208322044895,1739137702.047374,43.70995831489563,0.8861536279903627 +1739137702.0641062,43.7399582862854,41.393511429399084,1739137702.064115,43.7399582862854,0.31249242310083414,1739137702.0641253,43.7399582862854,71.30871704505503,1739137702.0641344,43.7399582862854,37.3456113058525,1739137702.064139,43.7399582862854,-0.09161554776589982,1739137702.0641448,43.7399582862854,-3.042090828303029,1739137702.0641496,43.7399582862854,-2.51339003074883,1739137702.0641541,43.7399582862854,-0.6108,1739137702.0641587,43.7399582862854,0.9147858540155351,1739137702.064164,43.7399582862854,0.0,1739137702.0641687,43.7399582862854,0.006689966134846393,1739137702.064174,43.7399582862854,3.9070883179749565,1739137702.0641785,43.7399582862854,0.890835470149621 +1739137702.0815258,43.759958267211914,41.393511429399084,1739137702.0815318,43.759958267211914,0.31249242310083414,1739137702.0815382,43.759958267211914,71.30871704505503,1739137702.0815449,43.759958267211914,37.3456113058525,1739137702.0815482,43.759958267211914,-0.09161554776589982,1739137702.0815523,43.759958267211914,-3.042090828303029,1739137702.081556,43.759958267211914,-2.51339003074883,1739137702.081559,43.759958267211914,-0.6108,1739137702.081562,43.759958267211914,0.9147858540155351,1739137702.0815659,43.759958267211914,0.0,1739137702.081569,43.759958267211914,0.023950383865914193,1739137702.0815725,43.759958267211914,3.9070883179749565,1739137702.0815756,43.759958267211914,0.890835470149621 +1739137702.1009953,43.76995825767517,41.393511429399084,1739137702.1009996,43.76995825767517,0.31249242310083414,1739137702.101005,43.76995825767517,71.30871704505503,1739137702.10101,43.76995825767517,37.3456113058525,1739137702.1010127,43.76995825767517,-0.09161554776589982,1739137702.1010158,43.76995825767517,-3.042090828303029,1739137702.1010187,43.76995825767517,-2.51339003074883,1739137702.1010208,43.76995825767517,-0.6108,1739137702.1010234,43.76995825767517,0.9147858540155351,1739137702.1010263,43.76995825767517,0.0,1739137702.101029,43.76995825767517,0.023950383865914193,1739137702.101032,43.76995825767517,3.9070883179749565,1739137702.1010344,43.76995825767517,0.890835470149621 +1739137702.119942,43.79995822906494,41.393511429399084,1739137702.1199467,43.79995822906494,0.31249242310083414,1739137702.1199522,43.79995822906494,71.30871704505503,1739137702.119958,43.79995822906494,37.3456113058525,1739137702.119961,43.79995822906494,-0.09161554776589982,1739137702.1199641,43.79995822906494,-3.042090828303029,1739137702.119967,43.79995822906494,-2.51339003074883,1739137702.1199696,43.79995822906494,-0.6108,1739137702.1199718,43.79995822906494,0.9147858540155351,1739137702.1199749,43.79995822906494,0.0,1739137702.1199775,43.79995822906494,0.023950383865914193,1739137702.1199806,43.79995822906494,3.9070883179749565,1739137702.119983,43.79995822906494,0.890835470149621 +1739137702.1403584,43.819958209991455,41.393511429399084,1739137702.1403627,43.819958209991455,0.31249242310083414,1739137702.140368,43.819958209991455,71.30871704505503,1739137702.140373,43.819958209991455,37.3456113058525,1739137702.1403759,43.819958209991455,-0.09161554776589982,1739137702.1403792,43.819958209991455,-3.042090828303029,1739137702.1403818,43.819958209991455,-2.51339003074883,1739137702.1403842,43.819958209991455,-0.6108,1739137702.1403868,43.819958209991455,0.9147858540155351,1739137702.14039,43.819958209991455,0.0,1739137702.1403925,43.819958209991455,0.023950383865914193,1739137702.1403952,43.819958209991455,3.9070883179749565,1739137702.1403975,43.819958209991455,0.890835470149621 +1739137702.1601756,43.83995819091797,41.321904150059815,1739137702.1601791,43.83995819091797,0.24539658937687037,1739137702.160183,43.83995819091797,71.31447547996996,1739137702.1601868,43.83995819091797,37.33190401392644,1739137702.1601887,43.83995819091797,-0.09215456551220966,1739137702.160191,43.83995819091797,-3.0571943340413292,1739137702.1601932,43.83995819091797,-2.434031866306703,1739137702.1601954,43.83995819091797,-0.6108,1739137702.160197,43.83995819091797,0.9442899452081215,1739137702.1601992,43.83995819091797,0.0,1739137702.160201,43.83995819091797,0.07521128961007542,1739137702.160203,43.83995819091797,3.8793558037454234,1739137702.1602046,43.83995819091797,0.8934886229081584 +1739137702.1779628,43.85995817184448,41.321904150059815,1739137702.1779652,43.85995817184448,0.24539658937687037,1739137702.1779675,43.85995817184448,71.31447547996996,1739137702.1779706,43.85995817184448,37.33190401392644,1739137702.1779723,43.85995817184448,-0.09215456551220966,1739137702.177974,43.85995817184448,-3.0571943340413292,1739137702.1779752,43.85995817184448,-2.434031866306703,1739137702.1779768,43.85995817184448,-0.6108,1739137702.1779778,43.85995817184448,0.9442899452081215,1739137702.1779797,43.85995817184448,0.0,1739137702.1779811,43.85995817184448,0.050801322299963036,1739137702.1779828,43.85995817184448,3.8793558037454234,1739137702.177984,43.85995817184448,0.8934886229081584 +1739137702.1979816,43.879958152770996,41.321904150059815,1739137702.197984,43.879958152770996,0.24539658937687037,1739137702.1979868,43.879958152770996,71.31447547996996,1739137702.1979897,43.879958152770996,37.33190401392644,1739137702.197991,43.879958152770996,-0.09215456551220966,1739137702.1979926,43.879958152770996,-3.0571943340413292,1739137702.197994,43.879958152770996,-2.434031866306703,1739137702.1979952,43.879958152770996,-0.6108,1739137702.1979969,43.879958152770996,0.9442899452081215,1739137702.1979983,43.879958152770996,0.0,1739137702.1979997,43.879958152770996,0.050801322299963036,1739137702.198001,43.879958152770996,3.8793558037454234,1739137702.1980026,43.879958152770996,0.8934886229081584 +1739137702.2178164,43.89995813369751,41.321904150059815,1739137702.2178187,43.89995813369751,0.24539658937687037,1739137702.2178214,43.89995813369751,71.31447547996996,1739137702.2178242,43.89995813369751,37.33190401392644,1739137702.217826,43.89995813369751,-0.09215456551220966,1739137702.2178273,43.89995813369751,-3.0571943340413292,1739137702.2178288,43.89995813369751,-2.434031866306703,1739137702.2178302,43.89995813369751,-0.6108,1739137702.2178316,43.89995813369751,0.9442899452081215,1739137702.2178333,43.89995813369751,0.0,1739137702.2178345,43.89995813369751,0.050801322299963036,1739137702.2178357,43.89995813369751,3.8793558037454234,1739137702.2178373,43.89995813369751,0.8934886229081584 +1739137702.238419,43.91995811462402,41.321904150059815,1739137702.2384212,43.91995811462402,0.24539658937687037,1739137702.2384243,43.91995811462402,71.31447547996996,1739137702.2384272,43.91995811462402,37.33190401392644,1739137702.2384284,43.91995811462402,-0.09215456551220966,1739137702.23843,43.91995811462402,-3.0571943340413292,1739137702.2384315,43.91995811462402,-2.434031866306703,1739137702.2384331,43.91995811462402,-0.6108,1739137702.2384343,43.91995811462402,0.9442899452081215,1739137702.238436,43.91995811462402,0.0,1739137702.2384372,43.91995811462402,0.050801322299963036,1739137702.2384388,43.91995811462402,3.8793558037454234,1739137702.23844,43.91995811462402,0.8934886229081584 +1739137702.2583625,43.93995809555054,41.321904150059815,1739137702.258365,43.93995809555054,0.24539658937687037,1739137702.2583678,43.93995809555054,71.31447547996996,1739137702.2583704,43.93995809555054,37.33190401392644,1739137702.2583716,43.93995809555054,-0.09215456551220966,1739137702.258373,43.93995809555054,-3.0571943340413292,1739137702.2583747,43.93995809555054,-2.434031866306703,1739137702.258376,43.93995809555054,-0.6108,1739137702.2583773,43.93995809555054,0.9442899452081215,1739137702.2583787,43.93995809555054,0.0,1739137702.2583797,43.93995809555054,0.050801322299963036,1739137702.2583814,43.93995809555054,3.8793558037454234,1739137702.2583826,43.93995809555054,0.8934886229081584 +1739137702.278482,43.95995807647705,41.248107150543994,1739137702.2784846,43.95995807647705,0.17999714977675385,1739137702.2784872,43.95995807647705,71.41752155417771,1739137702.27849,43.95995807647705,37.21077536125772,1739137702.2784915,43.95995807647705,-0.09654409354930989,1739137702.2784932,43.95995807647705,-3.073203433290178,1739137702.2784944,43.95995807647705,-2.4220501900679428,1739137702.2784958,43.95995807647705,-0.6108,1739137702.2784967,43.95995807647705,0.948826478137924,1739137702.2784984,43.95995807647705,0.0,1739137702.2784996,43.95995807647705,0.04790382554167397,1739137702.278501,43.95995807647705,3.8516232895158904,1739137702.2785027,43.95995807647705,0.899542891545909 +1739137702.2982178,43.979958057403564,41.248107150543994,1739137702.2982206,43.979958057403564,0.17999714977675385,1739137702.298224,43.979958057403564,71.41752155417771,1739137702.2982268,43.979958057403564,37.21077536125772,1739137702.2982285,43.979958057403564,-0.09654409354930989,1739137702.2982302,43.979958057403564,-3.073203433290178,1739137702.2982318,43.979958057403564,-2.4220501900679428,1739137702.298233,43.979958057403564,-0.6108,1739137702.2982347,43.979958057403564,0.948826478137924,1739137702.2982364,43.979958057403564,0.0,1739137702.2982378,43.979958057403564,0.04928358659201493,1739137702.2982392,43.979958057403564,3.8516232895158904,1739137702.2982407,43.979958057403564,0.899542891545909 +1739137702.3191059,43.99995803833008,41.248107150543994,1739137702.319108,43.99995803833008,0.17999714977675385,1739137702.319111,43.99995803833008,71.41752155417771,1739137702.3191137,43.99995803833008,37.21077536125772,1739137702.3191152,43.99995803833008,-0.09654409354930989,1739137702.3191168,43.99995803833008,-3.073203433290178,1739137702.319118,43.99995803833008,-2.4220501900679428,1739137702.3191195,43.99995803833008,-0.6108,1739137702.3191206,43.99995803833008,0.948826478137924,1739137702.319122,43.99995803833008,0.0,1739137702.3191235,43.99995803833008,0.04928358659201493,1739137702.319125,43.99995803833008,3.8516232895158904,1739137702.3191264,43.99995803833008,0.899542891545909 +1739137702.3382912,44.01995801925659,41.248107150543994,1739137702.338294,44.01995801925659,0.17999714977675385,1739137702.338297,44.01995801925659,71.41752155417771,1739137702.3383,44.01995801925659,37.21077536125772,1739137702.3383014,44.01995801925659,-0.09654409354930989,1739137702.3383033,44.01995801925659,-3.073203433290178,1739137702.338305,44.01995801925659,-2.4220501900679428,1739137702.3383062,44.01995801925659,-0.6108,1739137702.3383083,44.01995801925659,0.948826478137924,1739137702.33831,44.01995801925659,0.0,1739137702.3383114,44.01995801925659,0.04928358659201493,1739137702.3383129,44.01995801925659,3.8516232895158904,1739137702.3383143,44.01995801925659,0.899542891545909 +1739137702.357971,44.039958000183105,41.248107150543994,1739137702.3579736,44.039958000183105,0.17999714977675385,1739137702.3579767,44.039958000183105,71.41752155417771,1739137702.3579795,44.039958000183105,37.21077536125772,1739137702.3579812,44.039958000183105,-0.09654409354930989,1739137702.3579829,44.039958000183105,-3.073203433290178,1739137702.3579845,44.039958000183105,-2.4220501900679428,1739137702.357986,44.039958000183105,-0.6108,1739137702.3579876,44.039958000183105,0.948826478137924,1739137702.357989,44.039958000183105,0.0,1739137702.3579907,44.039958000183105,0.04928358659201493,1739137702.3579922,44.039958000183105,3.8516232895158904,1739137702.3579938,44.039958000183105,0.899542891545909 +1739137702.3780143,44.05995798110962,41.172057485609336,1739137702.3780167,44.05995798110962,0.11627721157699078,1739137702.3780198,44.05995798110962,71.54223008323905,1739137702.378023,44.05995798110962,37.06995197895025,1739137702.3780243,44.05995798110962,-0.10001024338410756,1739137702.3780262,44.05995798110962,-3.088915471116869,1739137702.3780277,44.05995798110962,-2.4188325577777716,1739137702.3780293,44.05995798110962,-0.6108,1739137702.3780308,44.05995798110962,0.9500484542287158,1739137702.3780327,44.05995798110962,0.0,1739137702.3780339,44.05995798110962,0.041333420727989977,1739137702.3780358,44.05995798110962,3.8238907752863573,1739137702.3780372,44.05995798110962,0.9049292383409724 +1739137702.398006,44.07995796203613,41.172057485609336,1739137702.3980083,44.07995796203613,0.11627721157699078,1739137702.3980114,44.07995796203613,71.54223008323905,1739137702.3980143,44.07995796203613,37.06995197895025,1739137702.3980157,44.07995796203613,-0.10001024338410756,1739137702.3980181,44.07995796203613,-3.088915471116869,1739137702.3980196,44.07995796203613,-2.4188325577777716,1739137702.3980212,44.07995796203613,-0.6108,1739137702.3980224,44.07995796203613,0.9500484542287158,1739137702.398024,44.07995796203613,0.0,1739137702.3980255,44.07995796203613,0.04511921588774337,1739137702.3980272,44.07995796203613,3.8238907752863573,1739137702.3980286,44.07995796203613,0.9049292383409724 +1739137702.417936,44.09995794296265,41.172057485609336,1739137702.4179387,44.09995794296265,0.11627721157699078,1739137702.417942,44.09995794296265,71.54223008323905,1739137702.417945,44.09995794296265,37.06995197895025,1739137702.4179463,44.09995794296265,-0.10001024338410756,1739137702.4179482,44.09995794296265,-3.088915471116869,1739137702.41795,44.09995794296265,-2.4188325577777716,1739137702.4179518,44.09995794296265,-0.6108,1739137702.417953,44.09995794296265,0.9500484542287158,1739137702.417955,44.09995794296265,0.0,1739137702.417956,44.09995794296265,0.04511921588774337,1739137702.4179578,44.09995794296265,3.8238907752863573,1739137702.4179592,44.09995794296265,0.9049292383409724 +1739137702.438004,44.11995792388916,41.172057485609336,1739137702.4380066,44.11995792388916,0.11627721157699078,1739137702.4380093,44.11995792388916,71.54223008323905,1739137702.4380124,44.11995792388916,37.06995197895025,1739137702.438014,44.11995792388916,-0.10001024338410756,1739137702.4380157,44.11995792388916,-3.088915471116869,1739137702.4380176,44.11995792388916,-2.4188325577777716,1739137702.438019,44.11995792388916,-0.6108,1739137702.4380207,44.11995792388916,0.9500484542287158,1739137702.4380221,44.11995792388916,0.0,1739137702.4380236,44.11995792388916,0.04511921588774337,1739137702.4380252,44.11995792388916,3.8238907752863573,1739137702.4380267,44.11995792388916,0.9049292383409724 +1739137702.4581864,44.139957904815674,41.172057485609336,1739137702.4581892,44.139957904815674,0.11627721157699078,1739137702.4581926,44.139957904815674,71.54223008323905,1739137702.4581957,44.139957904815674,37.06995197895025,1739137702.4581976,44.139957904815674,-0.10001024338410756,1739137702.4581995,44.139957904815674,-3.088915471116869,1739137702.4582012,44.139957904815674,-2.4188325577777716,1739137702.4582026,44.139957904815674,-0.6108,1739137702.4582045,44.139957904815674,0.9500484542287158,1739137702.4582062,44.139957904815674,0.0,1739137702.4582078,44.139957904815674,0.04511921588774337,1739137702.4582093,44.139957904815674,3.8238907752863573,1739137702.4582107,44.139957904815674,0.9049292383409724 +1739137702.4787927,44.15995788574219,41.172057485609336,1739137702.4787962,44.15995788574219,0.11627721157699078,1739137702.4788005,44.15995788574219,71.54223008323905,1739137702.4788048,44.15995788574219,37.06995197895025,1739137702.478807,44.15995788574219,-0.10001024338410756,1739137702.4788096,44.15995788574219,-3.088915471116869,1739137702.4788117,44.15995788574219,-2.4188325577777716,1739137702.4788136,44.15995788574219,-0.6108,1739137702.4788158,44.15995788574219,0.9500484542287158,1739137702.478818,44.15995788574219,0.0,1739137702.47882,44.15995788574219,0.04511921588774337,1739137702.4788225,44.15995788574219,3.8238907752863573,1739137702.4788244,44.15995788574219,0.9049292383409724 +1739137702.5005555,44.1799578666687,41.093828314592784,1739137702.5005596,44.1799578666687,0.05434055166996732,1739137702.5005646,44.1799578666687,71.60152056813463,1739137702.5005693,44.1799578666687,36.99608140433005,1739137702.500572,44.1799578666687,-0.10199612360333096,1739137702.5005748,44.1799578666687,-3.1034592861168244,1739137702.5005774,44.1799578666687,-2.3707446884966847,1739137702.5005798,44.1799578666687,-0.6108,1739137702.5005822,44.1799578666687,0.9684996635533932,1739137702.500585,44.1799578666687,0.0,1739137702.500587,44.1799578666687,0.07104505460478847,1739137702.5005898,44.1799578666687,3.7961582610568243,1739137702.5005922,44.1799578666687,0.9098002526001003 +1739137702.5202873,44.199957847595215,41.093828314592784,1739137702.5202916,44.199957847595215,0.05434055166996732,1739137702.5202963,44.199957847595215,71.60152056813463,1739137702.5203018,44.199957847595215,36.99608140433005,1739137702.5203044,44.199957847595215,-0.10199612360333096,1739137702.5203075,44.199957847595215,-3.1034592861168244,1739137702.52031,44.199957847595215,-2.3707446884966847,1739137702.5203123,44.199957847595215,-0.6108,1739137702.5203154,44.199957847595215,0.9684996635533932,1739137702.520318,44.199957847595215,0.0,1739137702.5203204,44.199957847595215,0.058699410953292896,1739137702.5203233,44.199957847595215,3.7961582610568243,1739137702.5203257,44.199957847595215,0.9098002526001003 +1739137702.5407016,44.21995782852173,41.093828314592784,1739137702.5407062,44.21995782852173,0.05434055166996732,1739137702.540711,44.21995782852173,71.60152056813463,1739137702.5407157,44.21995782852173,36.99608140433005,1739137702.5407183,44.21995782852173,-0.10199612360333096,1739137702.540721,44.21995782852173,-3.1034592861168244,1739137702.5407236,44.21995782852173,-2.3707446884966847,1739137702.5407257,44.21995782852173,-0.6108,1739137702.540728,44.21995782852173,0.9684996635533932,1739137702.540731,44.21995782852173,0.0,1739137702.540733,44.21995782852173,0.058699410953292896,1739137702.5407357,44.21995782852173,3.7961582610568243,1739137702.540738,44.21995782852173,0.9098002526001003 +1739137702.5607727,44.23995780944824,41.093828314592784,1739137702.5607774,44.23995780944824,0.05434055166996732,1739137702.560783,44.23995780944824,71.60152056813463,1739137702.560788,44.23995780944824,36.99608140433005,1739137702.5607905,44.23995780944824,-0.10199612360333096,1739137702.5607936,44.23995780944824,-3.1034592861168244,1739137702.5607963,44.23995780944824,-2.3707446884966847,1739137702.5607984,44.23995780944824,-0.6108,1739137702.560801,44.23995780944824,0.9684996635533932,1739137702.5608037,44.23995780944824,0.0,1739137702.560806,44.23995780944824,0.058699410953292896,1739137702.560809,44.23995780944824,3.7961582610568243,1739137702.5608113,44.23995780944824,0.9098002526001003 +1739137702.5796304,44.259957790374756,41.093828314592784,1739137702.5796351,44.259957790374756,0.05434055166996732,1739137702.5796418,44.259957790374756,71.60152056813463,1739137702.579648,44.259957790374756,36.99608140433005,1739137702.579652,44.259957790374756,-0.10199612360333096,1739137702.5796576,44.259957790374756,-3.1034592861168244,1739137702.5796626,44.259957790374756,-2.3707446884966847,1739137702.5796664,44.259957790374756,-0.6108,1739137702.5796692,44.259957790374756,0.9684996635533932,1739137702.5796719,44.259957790374756,0.0,1739137702.5796745,44.259957790374756,0.058699410953292896,1739137702.5796773,44.259957790374756,3.7961582610568243,1739137702.57968,44.259957790374756,0.9098002526001003 +1739137702.598191,44.27995777130127,41.01341129428817,1739137702.598194,44.27995777130127,-0.005776698271598768,1739137702.598197,44.27995777130127,71.72680881655413,1739137702.5982,44.27995777130127,36.8511740102319,1739137702.5982015,44.27995777130127,-0.1034778162221234,1739137702.5982034,44.27995777130127,-3.118123741792702,1739137702.5982049,44.27995777130127,-2.3623699682597703,1739137702.5982065,44.27995777130127,-0.6108,1739137702.598208,44.27995777130127,0.9717494692497799,1739137702.5982096,44.27995777130127,0.0,1739137702.598211,44.27995777130127,0.052413815043924394,1739137702.598213,44.27995777130127,3.7684257468272913,1739137702.5982144,44.27995777130127,0.916342511801427 +1739137702.6195135,44.29995775222778,41.01341129428817,1739137702.619533,44.29995775222778,-0.005776698271598768,1739137702.6195362,44.29995775222778,71.72680881655413,1739137702.6195393,44.29995775222778,36.8511740102319,1739137702.6195405,44.29995775222778,-0.1034778162221234,1739137702.6195426,44.29995775222778,-3.118123741792702,1739137702.619544,44.29995775222778,-2.3623699682597703,1739137702.6195455,44.29995775222778,-0.6108,1739137702.6195467,44.29995775222778,0.9717494692497799,1739137702.619548,44.29995775222778,0.0,1739137702.6195495,44.29995775222778,0.05540695744835289,1739137702.619551,44.29995775222778,3.7684257468272913,1739137702.6195526,44.29995775222778,0.916342511801427 +1739137702.6376805,44.3199577331543,41.01341129428817,1739137702.6376827,44.3199577331543,-0.005776698271598768,1739137702.6376853,44.3199577331543,71.72680881655413,1739137702.637688,44.3199577331543,36.8511740102319,1739137702.637689,44.3199577331543,-0.1034778162221234,1739137702.6376905,44.3199577331543,-3.118123741792702,1739137702.637692,44.3199577331543,-2.3623699682597703,1739137702.6376932,44.3199577331543,-0.6108,1739137702.6376944,44.3199577331543,0.9717494692497799,1739137702.637696,44.3199577331543,0.0,1739137702.6376972,44.3199577331543,0.05540695744835289,1739137702.6376987,44.3199577331543,3.7684257468272913,1739137702.6377,44.3199577331543,0.916342511801427 +1739137702.6576483,44.33995771408081,41.01341129428817,1739137702.6576507,44.33995771408081,-0.005776698271598768,1739137702.6576536,44.33995771408081,71.72680881655413,1739137702.6576557,44.33995771408081,36.8511740102319,1739137702.6576571,44.33995771408081,-0.1034778162221234,1739137702.6576586,44.33995771408081,-3.118123741792702,1739137702.6576602,44.33995771408081,-2.3623699682597703,1739137702.6576612,44.33995771408081,-0.6108,1739137702.6576624,44.33995771408081,0.9717494692497799,1739137702.657664,44.33995771408081,0.0,1739137702.657665,44.33995771408081,0.05540695744835289,1739137702.6576664,44.33995771408081,3.7684257468272913,1739137702.6576676,44.33995771408081,0.916342511801427 +1739137702.677695,44.359957695007324,41.01341129428817,1739137702.677697,44.359957695007324,-0.005776698271598768,1739137702.6776996,44.359957695007324,71.72680881655413,1739137702.6777022,44.359957695007324,36.8511740102319,1739137702.6777034,44.359957695007324,-0.1034778162221234,1739137702.6777053,44.359957695007324,-3.118123741792702,1739137702.6777065,44.359957695007324,-2.3623699682597703,1739137702.6777074,44.359957695007324,-0.6108,1739137702.6777089,44.359957695007324,0.9717494692497799,1739137702.6777103,44.359957695007324,0.0,1739137702.6777112,44.359957695007324,0.05540695744835289,1739137702.677713,44.359957695007324,3.7684257468272913,1739137702.677714,44.359957695007324,0.916342511801427 +1739137702.6977916,44.37995767593384,41.01341129428817,1739137702.6977935,44.37995767593384,-0.005776698271598768,1739137702.697796,44.37995767593384,71.72680881655413,1739137702.6977987,44.37995767593384,36.8511740102319,1739137702.6978,44.37995767593384,-0.1034778162221234,1739137702.6978018,44.37995767593384,-3.118123741792702,1739137702.6978033,44.37995767593384,-2.3623699682597703,1739137702.6978045,44.37995767593384,-0.6108,1739137702.697806,44.37995767593384,0.9717494692497799,1739137702.6978073,44.37995767593384,0.0,1739137702.6978083,44.37995767593384,0.05540695744835289,1739137702.69781,44.37995767593384,3.7684257468272913,1739137702.6978111,44.37995767593384,0.916342511801427 +1739137702.7179668,44.39995765686035,40.930795377173105,1739137702.7179692,44.39995765686035,-0.06403805875006086,1739137702.7179718,44.39995765686035,71.72796018933151,1739137702.7179742,44.39995765686035,36.83198013867514,1739137702.7179756,44.39995765686035,-0.10367367205433528,1739137702.717977,44.39995765686035,-3.1319229379194145,1739137702.7179785,44.39995765686035,-2.278588789860067,1739137702.7179797,44.39995765686035,-0.6108,1739137702.7179809,44.39995765686035,1.0048670215896012,1739137702.7179823,44.39995765686035,0.0,1739137702.7179835,44.39995765686035,0.10714917303804988,1739137702.7179847,44.39995765686035,3.740693232597758,1739137702.7179863,44.39995765686035,0.9223570111406976 +1739137702.7407572,44.419957637786865,40.930795377173105,1739137702.7407608,44.419957637786865,-0.06403805875006086,1739137702.740766,44.419957637786865,71.72796018933151,1739137702.7407715,44.419957637786865,36.83198013867514,1739137702.7407749,44.419957637786865,-0.10367367205433528,1739137702.740779,44.419957637786865,-3.1319229379194145,1739137702.7407832,44.419957637786865,-2.278588789860067,1739137702.740787,44.419957637786865,-0.6108,1739137702.7407906,44.419957637786865,1.0048670215896012,1739137702.7407944,44.419957637786865,0.0,1739137702.740798,44.419957637786865,0.0825100104489036,1739137702.740802,44.419957637786865,3.740693232597758,1739137702.7408056,44.419957637786865,0.9223570111406976 +1739137702.7576282,44.43995761871338,40.930795377173105,1739137702.7576303,44.43995761871338,-0.06403805875006086,1739137702.757633,44.43995761871338,71.72796018933151,1739137702.7576356,44.43995761871338,36.83198013867514,1739137702.757637,44.43995761871338,-0.10367367205433528,1739137702.7576387,44.43995761871338,-3.1319229379194145,1739137702.75764,44.43995761871338,-2.278588789860067,1739137702.7576413,44.43995761871338,-0.6108,1739137702.7576427,44.43995761871338,1.0048670215896012,1739137702.7576442,44.43995761871338,0.0,1739137702.7576456,44.43995761871338,0.0825100104489036,1739137702.7576468,44.43995761871338,3.740693232597758,1739137702.7576482,44.43995761871338,0.9223570111406976 +1739137702.7777798,44.45995759963989,40.930795377173105,1739137702.777782,44.45995759963989,-0.06403805875006086,1739137702.7777848,44.45995759963989,71.72796018933151,1739137702.7777874,44.45995759963989,36.83198013867514,1739137702.7777886,44.45995759963989,-0.10367367205433528,1739137702.7777905,44.45995759963989,-3.1319229379194145,1739137702.7777915,44.45995759963989,-2.278588789860067,1739137702.7777932,44.45995759963989,-0.6108,1739137702.7777946,44.45995759963989,1.0048670215896012,1739137702.777796,44.45995759963989,0.0,1739137702.7777975,44.45995759963989,0.0825100104489036,1739137702.7777987,44.45995759963989,3.740693232597758,1739137702.7777998,44.45995759963989,0.9223570111406976 +1739137702.7979307,44.479957580566406,40.930795377173105,1739137702.7979333,44.479957580566406,-0.06403805875006086,1739137702.7979364,44.479957580566406,71.72796018933151,1739137702.7979393,44.479957580566406,36.83198013867514,1739137702.7979407,44.479957580566406,-0.10367367205433528,1739137702.7979422,44.479957580566406,-3.1319229379194145,1739137702.7979438,44.479957580566406,-2.278588789860067,1739137702.797945,44.479957580566406,-0.6108,1739137702.7979465,44.479957580566406,1.0048670215896012,1739137702.7979481,44.479957580566406,0.0,1739137702.7979498,44.479957580566406,0.0825100104489036,1739137702.7979512,44.479957580566406,3.740693232597758,1739137702.7979527,44.479957580566406,0.9223570111406976 +1739137702.8178163,44.49995756149292,40.84590364255372,1739137702.8178186,44.49995756149292,-0.12044500266936886,1739137702.817822,44.49995756149292,71.88648904901582,1739137702.8178248,44.49995756149292,36.6456677457081,1739137702.8178263,44.49995756149292,-0.104,1739137702.817828,44.49995756149292,3.137677416673526,1739137702.8178296,44.49995756149292,-2.2852504168837386,1739137702.8178308,44.49995756149292,-0.6108,1739137702.8178322,44.49995756149292,1.0021929661613254,1739137702.8178337,44.49995756149292,0.0,1739137702.817835,44.49995756149292,0.05972349544275376,1739137702.8178365,44.49995756149292,3.712960718368225,1739137702.8178382,44.49995756149292,0.9316187438666595 +1739137702.8380663,44.519957542419434,40.84590364255372,1739137702.838069,44.519957542419434,-0.12044500266936886,1739137702.838072,44.519957542419434,71.88648904901582,1739137702.8380752,44.519957542419434,36.6456677457081,1739137702.8380766,44.519957542419434,-0.104,1739137702.8380785,44.519957542419434,3.137677416673526,1739137702.83808,44.519957542419434,-2.2852504168837386,1739137702.8380816,44.519957542419434,-0.6108,1739137702.8380828,44.519957542419434,1.0021929661613254,1739137702.8380845,44.519957542419434,0.0,1739137702.838086,44.519957542419434,0.07057422229466581,1739137702.8380873,44.519957542419434,3.712960718368225,1739137702.838089,44.519957542419434,0.9316187438666595 +1739137702.8577628,44.53995752334595,40.84590364255372,1739137702.8577652,44.53995752334595,-0.12044500266936886,1739137702.8577683,44.53995752334595,71.88648904901582,1739137702.857771,44.53995752334595,36.6456677457081,1739137702.8577726,44.53995752334595,-0.104,1739137702.8577743,44.53995752334595,3.137677416673526,1739137702.857776,44.53995752334595,-2.2852504168837386,1739137702.8577774,44.53995752334595,-0.6108,1739137702.8577788,44.53995752334595,1.0021929661613254,1739137702.8577802,44.53995752334595,0.0,1739137702.8577816,44.53995752334595,0.07057422229466581,1739137702.8577833,44.53995752334595,3.712960718368225,1739137702.8577847,44.53995752334595,0.9316187438666595 +1739137702.8777745,44.55995750427246,40.84590364255372,1739137702.8777769,44.55995750427246,-0.12044500266936886,1739137702.87778,44.55995750427246,71.88648904901582,1739137702.8777828,44.55995750427246,36.6456677457081,1739137702.8777843,44.55995750427246,-0.104,1739137702.8777862,44.55995750427246,3.137677416673526,1739137702.8777874,44.55995750427246,-2.2852504168837386,1739137702.877789,44.55995750427246,-0.6108,1739137702.8777902,44.55995750427246,1.0021929661613254,1739137702.8777916,44.55995750427246,0.0,1739137702.877793,44.55995750427246,0.07057422229466581,1739137702.8777947,44.55995750427246,3.712960718368225,1739137702.8777964,44.55995750427246,0.9316187438666595 +1739137702.897956,44.579957485198975,40.84590364255372,1739137702.8979588,44.579957485198975,-0.12044500266936886,1739137702.8979614,44.579957485198975,71.88648904901582,1739137702.8979642,44.579957485198975,36.6456677457081,1739137702.897966,44.579957485198975,-0.104,1739137702.8979676,44.579957485198975,3.137677416673526,1739137702.897969,44.579957485198975,-2.2852504168837386,1739137702.8979704,44.579957485198975,-0.6108,1739137702.8979716,44.579957485198975,1.0021929661613254,1739137702.8979733,44.579957485198975,0.0,1739137702.8979747,44.579957485198975,0.07057422229466581,1739137702.8979764,44.579957485198975,3.712960718368225,1739137702.8979778,44.579957485198975,0.9316187438666595 +1739137702.9178915,44.59995746612549,40.84590364255372,1739137702.917894,44.59995746612549,-0.12044500266936886,1739137702.9178967,44.59995746612549,71.88648904901582,1739137702.9178996,44.59995746612549,36.6456677457081,1739137702.9179008,44.59995746612549,-0.104,1739137702.9179027,44.59995746612549,3.137677416673526,1739137702.9179041,44.59995746612549,-2.2852504168837386,1739137702.9179053,44.59995746612549,-0.6108,1739137702.917907,44.59995746612549,1.0021929661613254,1739137702.9179087,44.59995746612549,0.0,1739137702.91791,44.59995746612549,0.07057422229466581,1739137702.9179115,44.59995746612549,3.712960718368225,1739137702.9179132,44.59995746612549,0.9316187438666595 +1739137702.9379354,44.619957447052,40.758702017546625,1739137702.9379377,44.619957447052,-0.1749635375134222,1739137702.9379408,44.619957447052,71.94634533864534,1739137702.9379435,44.619957447052,36.56324858254453,1739137702.9379451,44.619957447052,-0.104,1739137702.9379468,44.619957447052,3.124679875913085,1739137702.9379482,44.619957447052,-2.2308347703688693,1739137702.9379494,44.619957447052,-0.6108,1739137702.9379506,44.619957447052,1.0242460938065452,1739137702.9379525,44.619957447052,0.0,1739137702.9379537,44.619957447052,0.09831746814929944,1739137702.9379556,44.619957447052,3.685228204138692,1739137702.9379568,44.619957447052,0.9391397017113429 +1739137702.9578927,44.639957427978516,40.758702017546625,1739137702.9578953,44.639957427978516,-0.1749635375134222,1739137702.9578981,44.639957427978516,71.94634533864534,1739137702.9579012,44.639957427978516,36.56324858254453,1739137702.957903,44.639957427978516,-0.104,1739137702.9579046,44.639957427978516,3.124679875913085,1739137702.957906,44.639957427978516,-2.2308347703688693,1739137702.9579077,44.639957427978516,-0.6108,1739137702.957909,44.639957427978516,1.0242460938065452,1739137702.9579108,44.639957427978516,0.0,1739137702.957912,44.639957427978516,0.08510639209520232,1739137702.9579136,44.639957427978516,3.685228204138692,1739137702.957915,44.639957427978516,0.9391397017113429 +1739137702.977859,44.65995740890503,40.758702017546625,1739137702.9778616,44.65995740890503,-0.1749635375134222,1739137702.9778647,44.65995740890503,71.94634533864534,1739137702.9778678,44.65995740890503,36.56324858254453,1739137702.9778693,44.65995740890503,-0.104,1739137702.9778712,44.65995740890503,3.124679875913085,1739137702.9778724,44.65995740890503,-2.2308347703688693,1739137702.9778738,44.65995740890503,-0.6108,1739137702.9778752,44.65995740890503,1.0242460938065452,1739137702.9778767,44.65995740890503,0.0,1739137702.977878,44.65995740890503,0.08510639209520232,1739137702.9778795,44.65995740890503,3.685228204138692,1739137702.9778807,44.65995740890503,0.9391397017113429 +1739137702.9980037,44.67995738983154,40.758702017546625,1739137702.998006,44.67995738983154,-0.1749635375134222,1739137702.9980092,44.67995738983154,71.94634533864534,1739137702.9980118,44.67995738983154,36.56324858254453,1739137702.9980133,44.67995738983154,-0.104,1739137702.998015,44.67995738983154,3.124679875913085,1739137702.9980166,44.67995738983154,-2.2308347703688693,1739137702.9980178,44.67995738983154,-0.6108,1739137702.998019,44.67995738983154,1.0242460938065452,1739137702.998021,44.67995738983154,0.0,1739137702.998022,44.67995738983154,0.08510639209520232,1739137702.9980237,44.67995738983154,3.685228204138692,1739137702.9980252,44.67995738983154,0.9391397017113429 +1739137703.017894,44.69995737075806,40.758702017546625,1739137703.0178967,44.69995737075806,-0.1749635375134222,1739137703.0178993,44.69995737075806,71.94634533864534,1739137703.0179021,44.69995737075806,36.56324858254453,1739137703.0179033,44.69995737075806,-0.104,1739137703.0179052,44.69995737075806,3.124679875913085,1739137703.0179067,44.69995737075806,-2.2308347703688693,1739137703.0179079,44.69995737075806,-0.6108,1739137703.0179095,44.69995737075806,1.0242460938065452,1739137703.017911,44.69995737075806,0.0,1739137703.0179124,44.69995737075806,0.08510639209520232,1739137703.0179138,44.69995737075806,3.685228204138692,1739137703.0179155,44.69995737075806,0.9391397017113429 +1739137703.0378256,44.71995735168457,40.669215703501095,1739137703.0378277,44.71995735168457,-0.2275161750013952,1739137703.0378306,44.71995735168457,72.05099395647221,1739137703.0378332,44.71995735168457,36.43027166056315,1739137703.0378346,44.71995735168457,-0.104,1739137703.0378366,44.71995735168457,3.1124624658615496,1739137703.0378377,44.71995735168457,-2.1985984710430966,1739137703.0378394,44.71995735168457,-0.6108,1739137703.0378406,44.71995735168457,1.0375387724461977,1739137703.0378423,44.71995735168457,0.0,1739137703.0378435,44.71995735168457,0.092456224737651,1739137703.037845,44.71995735168457,3.657495689909159,1739137703.0378466,44.71995735168457,0.9485824697628387 +1739137703.0578477,44.739957332611084,40.669215703501095,1739137703.0578501,44.739957332611084,-0.2275161750013952,1739137703.057853,44.739957332611084,72.05099395647221,1739137703.0578558,44.739957332611084,36.43027166056315,1739137703.057857,44.739957332611084,-0.104,1739137703.0578592,44.739957332611084,3.1124624658615496,1739137703.0578606,44.739957332611084,-2.1985984710430966,1739137703.0578618,44.739957332611084,-0.6108,1739137703.0578632,44.739957332611084,1.0375387724461977,1739137703.0578647,44.739957332611084,0.0,1739137703.057866,44.739957332611084,0.08895630268335908,1739137703.0578675,44.739957332611084,3.657495689909159,1739137703.057869,44.739957332611084,0.9485824697628387 +1739137703.077871,44.7599573135376,40.669215703501095,1739137703.0778737,44.7599573135376,-0.2275161750013952,1739137703.0778766,44.7599573135376,72.05099395647221,1739137703.0778797,44.7599573135376,36.43027166056315,1739137703.077881,44.7599573135376,-0.104,1739137703.0778828,44.7599573135376,3.1124624658615496,1739137703.0778844,44.7599573135376,-2.1985984710430966,1739137703.0778856,44.7599573135376,-0.6108,1739137703.0778873,44.7599573135376,1.0375387724461977,1739137703.0778887,44.7599573135376,0.0,1739137703.0778904,44.7599573135376,0.08895630268335908,1739137703.0778918,44.7599573135376,3.657495689909159,1739137703.077893,44.7599573135376,0.9485824697628387 +1739137703.0978925,44.77995729446411,40.669215703501095,1739137703.097895,44.77995729446411,-0.2275161750013952,1739137703.0978978,44.77995729446411,72.05099395647221,1739137703.0979006,44.77995729446411,36.43027166056315,1739137703.0979018,44.77995729446411,-0.104,1739137703.0979037,44.77995729446411,3.1124624658615496,1739137703.0979052,44.77995729446411,-2.1985984710430966,1739137703.0979066,44.77995729446411,-0.6108,1739137703.097908,44.77995729446411,1.0375387724461977,1739137703.0979095,44.77995729446411,0.0,1739137703.097911,44.77995729446411,0.08895630268335908,1739137703.0979123,44.77995729446411,3.657495689909159,1739137703.0979135,44.77995729446411,0.9485824697628387 +1739137703.1177988,44.799957275390625,40.669215703501095,1739137703.1178014,44.799957275390625,-0.2275161750013952,1739137703.1178043,44.799957275390625,72.05099395647221,1739137703.1178074,44.799957275390625,36.43027166056315,1739137703.1178088,44.799957275390625,-0.104,1739137703.1178107,44.799957275390625,3.1124624658615496,1739137703.117812,44.799957275390625,-2.1985984710430966,1739137703.1178136,44.799957275390625,-0.6108,1739137703.1178148,44.799957275390625,1.0375387724461977,1739137703.1178162,44.799957275390625,0.0,1739137703.1178179,44.799957275390625,0.08895630268335908,1739137703.117819,44.799957275390625,3.657495689909159,1739137703.1178207,44.799957275390625,0.9485824697628387 +1739137703.1380293,44.81995725631714,40.669215703501095,1739137703.1380317,44.81995725631714,-0.2275161750013952,1739137703.1380343,44.81995725631714,72.05099395647221,1739137703.1380372,44.81995725631714,36.43027166056315,1739137703.1380386,44.81995725631714,-0.104,1739137703.1380403,44.81995725631714,3.1124624658615496,1739137703.1380422,44.81995725631714,-2.1985984710430966,1739137703.1380434,44.81995725631714,-0.6108,1739137703.1380448,44.81995725631714,1.0375387724461977,1739137703.1380467,44.81995725631714,0.0,1739137703.138048,44.81995725631714,0.08895630268335908,1739137703.1380498,44.81995725631714,3.657495689909159,1739137703.138051,44.81995725631714,0.9485824697628387 +1739137703.157964,44.83995723724365,40.57737882842146,1739137703.1579666,44.83995723724365,-0.2780779712538797,1739137703.1579695,44.83995723724365,72.23160345012016,1739137703.1579726,44.83995723724365,36.220199082443024,1739137703.1579738,44.83995723724365,-0.104,1739137703.1579754,44.83995723724365,3.101661906827664,1739137703.1579769,44.83995723724365,-2.197309101605402,1739137703.157978,44.83995723724365,-0.6108,1739137703.1579795,44.83995723724365,1.0380740187738307,1739137703.1579812,44.83995723724365,0.0,1739137703.1579823,44.83995723724365,0.07122889295779217,1739137703.157984,44.83995723724365,3.629763175679626,1739137703.1579852,44.83995723724365,0.9584034979202352 +1739137703.1832,44.859957218170166,40.57737882842146,1739137703.1832094,44.859957218170166,-0.2780779712538797,1739137703.1832192,44.859957218170166,72.23160345012016,1739137703.1832292,44.859957218170166,36.220199082443024,1739137703.1832337,44.859957218170166,-0.104,1739137703.1832397,44.859957218170166,3.101661906827664,1739137703.1832445,44.859957218170166,-2.197309101605402,1739137703.1832492,44.859957218170166,-0.6108,1739137703.1832535,44.859957218170166,1.0380740187738307,1739137703.183265,44.859957218170166,0.0,1739137703.1832814,44.859957218170166,0.0796705208535955,1739137703.1832974,44.859957218170166,3.629763175679626,1739137703.1833084,44.859957218170166,0.9584034979202352 +1739137703.2044187,44.87995719909668,40.57737882842146,1739137703.2044272,44.87995719909668,-0.2780779712538797,1739137703.2044373,44.87995719909668,72.23160345012016,1739137703.2044466,44.87995719909668,36.220199082443024,1739137703.2044513,44.87995719909668,-0.104,1739137703.2044573,44.87995719909668,3.101661906827664,1739137703.204462,44.87995719909668,-2.197309101605402,1739137703.2044666,44.87995719909668,-0.6108,1739137703.2044716,44.87995719909668,1.0380740187738307,1739137703.2044768,44.87995719909668,0.0,1739137703.204482,44.87995719909668,0.0796705208535955,1739137703.2044868,44.87995719909668,3.629763175679626,1739137703.2044919,44.87995719909668,0.9584034979202352 +1739137703.229656,44.89995718002319,40.57737882842146,1739137703.2296648,44.89995718002319,-0.2780779712538797,1739137703.229675,44.89995718002319,72.23160345012016,1739137703.229685,44.89995718002319,36.220199082443024,1739137703.2296898,44.89995718002319,-0.104,1739137703.2296956,44.89995718002319,3.101661906827664,1739137703.2297003,44.89995718002319,-2.197309101605402,1739137703.2297049,44.89995718002319,-0.6108,1739137703.2297096,44.89995718002319,1.0380740187738307,1739137703.2297146,44.89995718002319,0.0,1739137703.2297194,44.89995718002319,0.0796705208535955,1739137703.2297244,44.89995718002319,3.629763175679626,1739137703.229729,44.89995718002319,0.9584034979202352 +1739137703.2756286,44.93995714187622,40.48327127676746,1739137703.2756348,44.93995714187622,-0.32653965409639873,1739137703.275642,44.93995714187622,72.23780832405694,1739137703.275649,44.93995714187622,36.188040829670804,1739137703.2756524,44.93995714187622,-0.104,1739137703.2756567,44.93995714187622,3.0898280623975376,1739137703.2756605,44.93995714187622,-2.1079089468886663,1739137703.2756639,44.93995714187622,-0.6108,1739137703.2756672,44.93995714187622,1.0758673281038695,1739137703.2756708,44.93995714187622,0.0,1739137703.275674,44.93995714187622,0.13530562285400446,1739137703.275678,44.93995714187622,3.602030661450093,1739137703.275681,44.93995714187622,0.967054624198716 +1739137703.2906585,44.959957122802734,40.48327127676746,1739137703.2906666,44.959957122802734,-0.32653965409639873,1739137703.2906756,44.959957122802734,72.23780832405694,1739137703.2906866,44.959957122802734,36.188040829670804,1739137703.2906928,44.959957122802734,-0.104,1739137703.290697,44.959957122802734,3.0898280623975376,1739137703.2906995,44.959957122802734,-2.1079089468886663,1739137703.2907016,44.959957122802734,-0.6108,1739137703.2907033,44.959957122802734,1.0758673281038695,1739137703.290706,44.959957122802734,0.0,1739137703.290708,44.959957122802734,0.10881270390515352,1739137703.2907102,44.959957122802734,3.602030661450093,1739137703.2907126,44.959957122802734,0.967054624198716 +1739137703.3067281,44.97995710372925,40.48327127676746,1739137703.306731,44.97995710372925,-0.32653965409639873,1739137703.306734,44.97995710372925,72.23780832405694,1739137703.306737,44.97995710372925,36.188040829670804,1739137703.3067384,44.97995710372925,-0.104,1739137703.3067403,44.97995710372925,3.0898280623975376,1739137703.3067415,44.97995710372925,-2.1079089468886663,1739137703.3067431,44.97995710372925,-0.6108,1739137703.3067443,44.97995710372925,1.0758673281038695,1739137703.306746,44.97995710372925,0.0,1739137703.3067474,44.97995710372925,0.10881270390515352,1739137703.306749,44.97995710372925,3.602030661450093,1739137703.3067505,44.97995710372925,0.967054624198716 +1739137703.3273451,45.00995707511902,40.48327127676746,1739137703.327348,45.00995707511902,-0.32653965409639873,1739137703.3273513,45.00995707511902,72.23780832405694,1739137703.3273542,45.00995707511902,36.188040829670804,1739137703.3273556,45.00995707511902,-0.104,1739137703.3273573,45.00995707511902,3.0898280623975376,1739137703.3273585,45.00995707511902,-2.1079089468886663,1739137703.32736,45.00995707511902,-0.6108,1739137703.3273616,45.00995707511902,1.0758673281038695,1739137703.327363,45.00995707511902,0.0,1739137703.3273644,45.00995707511902,0.10881270390515352,1739137703.3273659,45.00995707511902,3.602030661450093,1739137703.327367,45.00995707511902,0.967054624198716 +1739137703.3484006,45.02995705604553,40.48327127676746,1739137703.3484042,45.02995705604553,-0.32653965409639873,1739137703.3484092,45.02995705604553,72.23780832405694,1739137703.3484147,45.02995705604553,36.188040829670804,1739137703.3484175,45.02995705604553,-0.104,1739137703.348421,45.02995705604553,3.0898280623975376,1739137703.3484247,45.02995705604553,-2.1079089468886663,1739137703.348428,45.02995705604553,-0.6108,1739137703.3484313,45.02995705604553,1.0758673281038695,1739137703.3484347,45.02995705604553,0.0,1739137703.348438,45.02995705604553,0.10881270390515352,1739137703.3484414,45.02995705604553,3.602030661450093,1739137703.3484447,45.02995705604553,0.967054624198716 +1739137703.3674195,45.049957036972046,40.38689949390877,1739137703.3674235,45.049957036972046,-0.372831929942814,1739137703.3674283,45.049957036972046,72.29788975820398,1739137703.3674338,45.049957036972046,36.09394831455523,1739137703.3674366,45.049957036972046,-0.104,1739137703.3674402,45.049957036972046,3.0790526113075667,1739137703.3674438,45.049957036972046,-2.0442115934346514,1739137703.3674471,45.049957036972046,-0.6108,1739137703.3674505,45.049957036972046,1.1036314874145157,1739137703.367454,45.049957036972046,0.0,1739137703.3674574,45.049957036972046,0.14017360712381788,1739137703.367461,45.049957036972046,3.57429814722056,1739137703.3674643,45.049957036972046,0.978391651188228 +1739137703.388819,45.06995701789856,40.38689949390877,1739137703.3888233,45.06995701789856,-0.372831929942814,1739137703.3888285,45.06995701789856,72.29788975820398,1739137703.3888335,45.06995701789856,36.09394831455523,1739137703.3888364,45.06995701789856,-0.104,1739137703.38884,45.06995701789856,3.0790526113075667,1739137703.3888433,45.06995701789856,-2.0442115934346514,1739137703.3888469,45.06995701789856,-0.6108,1739137703.3888502,45.06995701789856,1.1036314874145157,1739137703.3888538,45.06995701789856,0.0,1739137703.388857,45.06995701789856,0.12523983622628765,1739137703.3888605,45.06995701789856,3.57429814722056,1739137703.3888636,45.06995701789856,0.978391651188228 +1739137703.4079502,45.08995699882507,40.38689949390877,1739137703.4079535,45.08995699882507,-0.372831929942814,1739137703.4079576,45.08995699882507,72.29788975820398,1739137703.407962,45.08995699882507,36.09394831455523,1739137703.407965,45.08995699882507,-0.104,1739137703.4079683,45.08995699882507,3.0790526113075667,1739137703.4079714,45.08995699882507,-2.0442115934346514,1739137703.4079742,45.08995699882507,-0.6108,1739137703.407977,45.08995699882507,1.1036314874145157,1739137703.4079804,45.08995699882507,0.0,1739137703.4079833,45.08995699882507,0.12523983622628765,1739137703.4079866,45.08995699882507,3.57429814722056,1739137703.4079897,45.08995699882507,0.978391651188228 +1739137703.4277225,45.10995697975159,40.38689949390877,1739137703.427726,45.10995697975159,-0.372831929942814,1739137703.4277308,45.10995697975159,72.29788975820398,1739137703.4277356,45.10995697975159,36.09394831455523,1739137703.4277384,45.10995697975159,-0.104,1739137703.427742,45.10995697975159,3.0790526113075667,1739137703.4277453,45.10995697975159,-2.0442115934346514,1739137703.4277484,45.10995697975159,-0.6108,1739137703.4277518,45.10995697975159,1.1036314874145157,1739137703.427755,45.10995697975159,0.0,1739137703.4277587,45.10995697975159,0.12523983622628765,1739137703.427762,45.10995697975159,3.57429814722056,1739137703.427765,45.10995697975159,0.978391651188228 +1739137703.4480026,45.1299569606781,40.38689949390877,1739137703.4480064,45.1299569606781,-0.372831929942814,1739137703.448011,45.1299569606781,72.29788975820398,1739137703.448016,45.1299569606781,36.09394831455523,1739137703.4480188,45.1299569606781,-0.104,1739137703.4480224,45.1299569606781,3.0790526113075667,1739137703.4480257,45.1299569606781,-2.0442115934346514,1739137703.4480293,45.1299569606781,-0.6108,1739137703.4480326,45.1299569606781,1.1036314874145157,1739137703.448036,45.1299569606781,0.0,1739137703.4480388,45.1299569606781,0.12523983622628765,1739137703.4480422,45.1299569606781,3.57429814722056,1739137703.4480453,45.1299569606781,0.978391651188228 +1739137703.4682589,45.149956941604614,40.38689949390877,1739137703.4682624,45.149956941604614,-0.372831929942814,1739137703.4682667,45.149956941604614,72.29788975820398,1739137703.4682717,45.149956941604614,36.09394831455523,1739137703.4682744,45.149956941604614,-0.104,1739137703.468278,45.149956941604614,3.0790526113075667,1739137703.4682813,45.149956941604614,-2.0442115934346514,1739137703.4682844,45.149956941604614,-0.6108,1739137703.4682877,45.149956941604614,1.1036314874145157,1739137703.468291,45.149956941604614,0.0,1739137703.4682941,45.149956941604614,0.12523983622628765,1739137703.4682975,45.149956941604614,3.57429814722056,1739137703.4683008,45.149956941604614,0.978391651188228 +1739137703.4885345,45.16995692253113,40.287982695565574,1739137703.4885383,45.16995692253113,-0.41701344907297067,1739137703.4885428,45.16995692253113,72.41315593974295,1739137703.4885478,45.16995692253113,35.93660651681622,1739137703.4885507,45.16995692253113,-0.104,1739137703.488554,45.16995692253113,3.0697819884386837,1739137703.4885573,45.16995692253113,-2.0021105259417196,1739137703.4885607,45.16995692253113,-0.6108,1739137703.4885638,45.16995692253113,1.1223744900362749,1739137703.488567,45.16995692253113,0.0,1739137703.4885705,45.16995692253113,0.1342465441034798,1739137703.4885738,45.16995692253113,3.546565632991027,1739137703.4885774,45.16995692253113,0.992416856588242 +1739137703.507469,45.18995690345764,40.287982695565574,1739137703.5074723,45.18995690345764,-0.41701344907297067,1739137703.5074768,45.18995690345764,72.41315593974295,1739137703.5074818,45.18995690345764,35.93660651681622,1739137703.5074847,45.18995690345764,-0.104,1739137703.5074885,45.18995690345764,3.0697819884386837,1739137703.5074916,45.18995690345764,-2.0021105259417196,1739137703.507495,45.18995690345764,-0.6108,1739137703.5074983,45.18995690345764,1.1223744900362749,1739137703.5075018,45.18995690345764,0.0,1739137703.5075052,45.18995690345764,0.1299576334480329,1739137703.5075085,45.18995690345764,3.546565632991027,1739137703.5075119,45.18995690345764,0.992416856588242 +1739137703.5275402,45.209956884384155,40.287982695565574,1739137703.5275435,45.209956884384155,-0.41701344907297067,1739137703.5275476,45.209956884384155,72.41315593974295,1739137703.5275528,45.209956884384155,35.93660651681622,1739137703.5275552,45.209956884384155,-0.104,1739137703.5275588,45.209956884384155,3.0697819884386837,1739137703.5275621,45.209956884384155,-2.0021105259417196,1739137703.5275652,45.209956884384155,-0.6108,1739137703.5275686,45.209956884384155,1.1223744900362749,1739137703.5275717,45.209956884384155,0.0,1739137703.527575,45.209956884384155,0.1299576334480329,1739137703.5275784,45.209956884384155,3.546565632991027,1739137703.5275817,45.209956884384155,0.992416856588242 +1739137703.54776,45.22995686531067,40.287982695565574,1739137703.5477633,45.22995686531067,-0.41701344907297067,1739137703.547768,45.22995686531067,72.41315593974295,1739137703.5477731,45.22995686531067,35.93660651681622,1739137703.547776,45.22995686531067,-0.104,1739137703.5477796,45.22995686531067,3.0697819884386837,1739137703.547783,45.22995686531067,-2.0021105259417196,1739137703.5477865,45.22995686531067,-0.6108,1739137703.5477896,45.22995686531067,1.1223744900362749,1739137703.5477931,45.22995686531067,0.0,1739137703.5477962,45.22995686531067,0.1299576334480329,1739137703.5477996,45.22995686531067,3.546565632991027,1739137703.547803,45.22995686531067,0.992416856588242 +1739137703.5676067,45.24995684623718,40.287982695565574,1739137703.56761,45.24995684623718,-0.41701344907297067,1739137703.5676143,45.24995684623718,72.41315593974295,1739137703.567619,45.24995684623718,35.93660651681622,1739137703.567622,45.24995684623718,-0.104,1739137703.5676255,45.24995684623718,3.0697819884386837,1739137703.567629,45.24995684623718,-2.0021105259417196,1739137703.5676324,45.24995684623718,-0.6108,1739137703.5676355,45.24995684623718,1.1223744900362749,1739137703.5676389,45.24995684623718,0.0,1739137703.567642,45.24995684623718,0.1299576334480329,1739137703.567645,45.24995684623718,3.546565632991027,1739137703.5676484,45.24995684623718,0.992416856588242 +1739137703.5882068,45.269956827163696,40.18645404959124,1739137703.5882103,45.269956827163696,-0.45902462582415726,1739137703.5882146,45.269956827163696,72.53136142683195,1739137703.5882194,45.269956827163696,35.77558335832452,1739137703.5882223,45.269956827163696,-0.10300566367305357,1739137703.5882256,45.269956827163696,3.0610532611502372,1739137703.5882287,45.269956827163696,-1.9557577215848088,1739137703.5882316,45.269956827163696,-0.6108,1739137703.5882347,45.269956827163696,1.1433786911015453,1739137703.588238,45.269956827163696,0.0,1739137703.5882409,45.269956827163696,0.14280588793922538,1739137703.5882442,45.269956827163696,3.518833118761494,1739137703.588247,45.269956827163696,1.0066910226430152 +1739137703.6069937,45.28995680809021,40.18645404959124,1739137703.606997,45.28995680809021,-0.45902462582415726,1739137703.607001,45.28995680809021,72.53136142683195,1739137703.6070063,45.28995680809021,35.77558335832452,1739137703.607009,45.28995680809021,-0.10300566367305357,1739137703.6070125,45.28995680809021,3.0610532611502372,1739137703.6070156,45.28995680809021,-1.9557577215848088,1739137703.607019,45.28995680809021,-0.6108,1739137703.607022,45.28995680809021,1.1433786911015453,1739137703.6070254,45.28995680809021,0.0,1739137703.6070287,45.28995680809021,0.1366876684585301,1739137703.607032,45.28995680809021,3.518833118761494,1739137703.6070354,45.28995680809021,1.0066910226430152 +1739137703.6274922,45.309956789016724,40.18645404959124,1739137703.6274955,45.309956789016724,-0.45902462582415726,1739137703.6274996,45.309956789016724,72.53136142683195,1739137703.6275048,45.309956789016724,35.77558335832452,1739137703.6275074,45.309956789016724,-0.10300566367305357,1739137703.6275113,45.309956789016724,3.0610532611502372,1739137703.6275146,45.309956789016724,-1.9557577215848088,1739137703.627518,45.309956789016724,-0.6108,1739137703.6275213,45.309956789016724,1.1433786911015453,1739137703.6275246,45.309956789016724,0.0,1739137703.627528,45.309956789016724,0.1366876684585301,1739137703.6275315,45.309956789016724,3.518833118761494,1739137703.6275349,45.309956789016724,1.0066910226430152 +1739137703.648332,45.32995676994324,40.18645404959124,1739137703.6483357,45.32995676994324,-0.45902462582415726,1739137703.64834,45.32995676994324,72.53136142683195,1739137703.648345,45.32995676994324,35.77558335832452,1739137703.648348,45.32995676994324,-0.10300566367305357,1739137703.6483517,45.32995676994324,3.0610532611502372,1739137703.6483548,45.32995676994324,-1.9557577215848088,1739137703.648358,45.32995676994324,-0.6108,1739137703.6483612,45.32995676994324,1.1433786911015453,1739137703.6483645,45.32995676994324,0.0,1739137703.6483676,45.32995676994324,0.1366876684585301,1739137703.648371,45.32995676994324,3.518833118761494,1739137703.6483743,45.32995676994324,1.0066910226430152 +1739137703.668336,45.34995675086975,40.18645404959124,1739137703.668339,45.34995675086975,-0.45902462582415726,1739137703.668343,45.34995675086975,72.53136142683195,1739137703.6683476,45.34995675086975,35.77558335832452,1739137703.6683505,45.34995675086975,-0.10300566367305357,1739137703.6683538,45.34995675086975,3.0610532611502372,1739137703.668357,45.34995675086975,-1.9557577215848088,1739137703.66836,45.34995675086975,-0.6108,1739137703.668363,45.34995675086975,1.1433786911015453,1739137703.6683662,45.34995675086975,0.0,1739137703.668369,45.34995675086975,0.1366876684585301,1739137703.6683724,45.34995675086975,3.518833118761494,1739137703.6683753,45.34995675086975,1.0066910226430152 +1739137703.6885178,45.369956731796265,40.18645404959124,1739137703.6885211,45.369956731796265,-0.45902462582415726,1739137703.6885252,45.369956731796265,72.53136142683195,1739137703.68853,45.369956731796265,35.77558335832452,1739137703.6885328,45.369956731796265,-0.10300566367305357,1739137703.6885362,45.369956731796265,3.0610532611502372,1739137703.688539,45.369956731796265,-1.9557577215848088,1739137703.6885421,45.369956731796265,-0.6108,1739137703.688545,45.369956731796265,1.1433786911015453,1739137703.6885483,45.369956731796265,0.0,1739137703.6885514,45.369956731796265,0.1366876684585301,1739137703.6885548,45.369956731796265,3.518833118761494,1739137703.6885576,45.369956731796265,1.0066910226430152 +1739137703.7068563,45.38995671272278,40.08228872874602,1739137703.7068594,45.38995671272278,-0.49878083266448225,1739137703.7068634,45.38995671272278,72.59258871112178,1739137703.7068684,45.38995671272278,35.669047434190844,1739137703.706871,45.38995671272278,-0.102,1739137703.7068746,45.38995671272278,3.0519268346071082,1739137703.706878,45.38995671272278,-1.8840426913235877,1739137703.706881,45.38995671272278,-0.6108,1739137703.7068844,45.38995671272278,1.1766526327265956,1739137703.7068877,45.38995671272278,0.0,1739137703.7068908,45.38995671272278,0.1713747863007427,1739137703.7068942,45.38995671272278,3.491100604531961,1739137703.7068975,45.38995671272278,1.0217955298401158 +1739137703.7275813,45.40995669364929,40.08228872874602,1739137703.7275844,45.40995669364929,-0.49878083266448225,1739137703.7275882,45.40995669364929,72.59258871112178,1739137703.727593,45.40995669364929,35.669047434190844,1739137703.7275956,45.40995669364929,-0.102,1739137703.727599,45.40995669364929,3.0519268346071082,1739137703.727602,45.40995669364929,-1.8840426913235877,1739137703.727605,45.40995669364929,-0.6108,1739137703.727608,45.40995669364929,1.1766526327265956,1739137703.727611,45.40995669364929,0.0,1739137703.7276142,45.40995669364929,0.1548571028864798,1739137703.7276173,45.40995669364929,3.491100604531961,1739137703.7276206,45.40995669364929,1.0217955298401158 +1739137703.7481685,45.429956674575806,40.08228872874602,1739137703.7481716,45.429956674575806,-0.49878083266448225,1739137703.7481759,45.429956674575806,72.59258871112178,1739137703.7481806,45.429956674575806,35.669047434190844,1739137703.7481835,45.429956674575806,-0.102,1739137703.748187,45.429956674575806,3.0519268346071082,1739137703.7481902,45.429956674575806,-1.8840426913235877,1739137703.7481933,45.429956674575806,-0.6108,1739137703.7481961,45.429956674575806,1.1766526327265956,1739137703.7481995,45.429956674575806,0.0,1739137703.7482026,45.429956674575806,0.1548571028864798,1739137703.748206,45.429956674575806,3.491100604531961,1739137703.7482085,45.429956674575806,1.0217955298401158 +1739137703.7676435,45.44995665550232,40.08228872874602,1739137703.7676468,45.44995665550232,-0.49878083266448225,1739137703.767651,45.44995665550232,72.59258871112178,1739137703.7676558,45.44995665550232,35.669047434190844,1739137703.7676585,45.44995665550232,-0.102,1739137703.767662,45.44995665550232,3.0519268346071082,1739137703.7676654,45.44995665550232,-1.8840426913235877,1739137703.7676685,45.44995665550232,-0.6108,1739137703.7676716,45.44995665550232,1.1766526327265956,1739137703.767675,45.44995665550232,0.0,1739137703.7676783,45.44995665550232,0.1548571028864798,1739137703.7676816,45.44995665550232,3.491100604531961,1739137703.767685,45.44995665550232,1.0217955298401158 +1739137703.7879243,45.46995663642883,40.08228872874602,1739137703.7879276,45.46995663642883,-0.49878083266448225,1739137703.7879317,45.46995663642883,72.59258871112178,1739137703.7879367,45.46995663642883,35.669047434190844,1739137703.7879393,45.46995663642883,-0.102,1739137703.7879426,45.46995663642883,3.0519268346071082,1739137703.7879457,45.46995663642883,-1.8840426913235877,1739137703.7879488,45.46995663642883,-0.6108,1739137703.787952,45.46995663642883,1.1766526327265956,1739137703.787955,45.46995663642883,0.0,1739137703.787958,45.46995663642883,0.1548571028864798,1739137703.787961,45.46995663642883,3.491100604531961,1739137703.787964,45.46995663642883,1.0217955298401158 +1739137703.8078585,45.48995661735535,39.97540133591943,1739137703.8078628,45.48995661735535,-0.5362141085446455,1739137703.8078673,45.48995661735535,72.71196554534183,1739137703.8078728,45.48995661735535,35.4983373881502,1739137703.8078759,45.48995661735535,-0.10134992166552918,1739137703.8078797,45.48995661735535,3.044764843984904,1739137703.807883,45.48995661735535,-1.828422582297965,1739137703.8078864,45.48995661735535,-0.6108,1739137703.8078897,45.48995661735535,1.203124230554835,1739137703.807893,45.48995661735535,0.0,1739137703.8078964,45.48995661735535,0.17272592369648404,1739137703.8079,45.48995661735535,3.4633680903024278,1739137703.8079033,45.48995661735535,1.0389072733994298 +1739137703.8281348,45.50995659828186,39.97540133591943,1739137703.8281386,45.50995659828186,-0.5362141085446455,1739137703.8281434,45.50995659828186,72.71196554534183,1739137703.8281488,45.50995659828186,35.4983373881502,1739137703.8281515,45.50995659828186,-0.10134992166552918,1739137703.828155,45.50995659828186,3.044764843984904,1739137703.828159,45.50995659828186,-1.828422582297965,1739137703.828162,45.50995659828186,-0.6108,1739137703.8281653,45.50995659828186,1.203124230554835,1739137703.8281689,45.50995659828186,0.0,1739137703.8281722,45.50995659828186,0.1642169571554053,1739137703.8281755,45.50995659828186,3.4633680903024278,1739137703.828179,45.50995659828186,1.0389072733994298 +1739137703.8457785,45.529956579208374,39.97540133591943,1739137703.845781,45.529956579208374,-0.5362141085446455,1739137703.845784,45.529956579208374,72.71196554534183,1739137703.845787,45.529956579208374,35.4983373881502,1739137703.8457885,45.529956579208374,-0.10134992166552918,1739137703.8457901,45.529956579208374,3.044764843984904,1739137703.8457916,45.529956579208374,-1.828422582297965,1739137703.8457928,45.529956579208374,-0.6108,1739137703.845794,45.529956579208374,1.203124230554835,1739137703.8457956,45.529956579208374,0.0,1739137703.8457968,45.529956579208374,0.1642169571554053,1739137703.8457983,45.529956579208374,3.4633680903024278,1739137703.8457994,45.529956579208374,1.0389072733994298 +1739137703.8719,45.54995656013489,39.97540133591943,1739137703.8719099,45.54995656013489,-0.5362141085446455,1739137703.8719199,45.54995656013489,72.71196554534183,1739137703.8719304,45.54995656013489,35.4983373881502,1739137703.8719356,45.54995656013489,-0.10134992166552918,1739137703.8719413,45.54995656013489,3.044764843984904,1739137703.8719466,45.54995656013489,-1.828422582297965,1739137703.8719513,45.54995656013489,-0.6108,1739137703.871956,45.54995656013489,1.203124230554835,1739137703.8719616,45.54995656013489,0.0,1739137703.8719661,45.54995656013489,0.1642169571554053,1739137703.8719716,45.54995656013489,3.4633680903024278,1739137703.8719764,45.54995656013489,1.0389072733994298 +1739137703.8895679,45.559956550598145,39.97540133591943,1739137703.8895743,45.559956550598145,-0.5362141085446455,1739137703.8895822,45.559956550598145,72.71196554534183,1739137703.8895888,45.559956550598145,35.4983373881502,1739137703.8895922,45.559956550598145,-0.10134992166552918,1739137703.889597,45.559956550598145,3.044764843984904,1739137703.8896008,45.559956550598145,-1.828422582297965,1739137703.8896043,45.559956550598145,-0.6108,1739137703.8896077,45.559956550598145,1.203124230554835,1739137703.8896117,45.559956550598145,0.0,1739137703.889615,45.559956550598145,0.1642169571554053,1739137703.889619,45.559956550598145,3.4633680903024278,1739137703.8896227,45.559956550598145,1.0389072733994298 +1739137703.9092708,45.589956521987915,39.97540133591943,1739137703.9092762,45.589956521987915,-0.5362141085446455,1739137703.909282,45.589956521987915,72.71196554534183,1739137703.9092877,45.589956521987915,35.4983373881502,1739137703.9092903,45.589956521987915,-0.10134992166552918,1739137703.9092934,45.589956521987915,3.044764843984904,1739137703.9092958,45.589956521987915,-1.828422582297965,1739137703.9092984,45.589956521987915,-0.6108,1739137703.909301,45.589956521987915,1.203124230554835,1739137703.9093046,45.589956521987915,0.0,1739137703.9093072,45.589956521987915,0.1642169571554053,1739137703.9093099,45.589956521987915,3.4633680903024278,1739137703.909313,45.589956521987915,1.0389072733994298 +1739137703.928208,45.60995650291443,39.86566813886469,1739137703.9282124,45.60995650291443,-0.5712594452109991,1739137703.9282172,45.60995650291443,72.83348165095222,1739137703.9282215,45.60995650291443,35.32231556011817,1739137703.9282238,45.60995650291443,-0.10095099620791526,1739137703.9282262,45.60995650291443,3.038444307751692,1739137703.9282284,45.60995650291443,-1.7668953355880248,1739137703.928231,45.60995650291443,-0.6108,1739137703.928233,45.60995650291443,1.2331015706554633,1739137703.9282353,45.60995650291443,0.0,1739137703.9282372,45.60995650291443,0.18676014918453368,1739137703.9282396,45.60995650291443,3.4356355760728947,1739137703.9282417,45.60995650291443,1.0570762801806646 +1739137703.946684,45.62995648384094,39.86566813886469,1739137703.9466867,45.62995648384094,-0.5712594452109991,1739137703.9466898,45.62995648384094,72.83348165095222,1739137703.9466927,45.62995648384094,35.32231556011817,1739137703.9466941,45.62995648384094,-0.10095099620791526,1739137703.9466956,45.62995648384094,3.038444307751692,1739137703.946697,45.62995648384094,-1.7668953355880248,1739137703.9466987,45.62995648384094,-0.6108,1739137703.9467003,45.62995648384094,1.2331015706554633,1739137703.9467018,45.62995648384094,0.0,1739137703.9467032,45.62995648384094,0.17602529047479876,1739137703.9467046,45.62995648384094,3.4356355760728947,1739137703.9467063,45.62995648384094,1.0570762801806646 +1739137703.9678984,45.649956464767456,39.86566813886469,1739137703.9679012,45.649956464767456,-0.5712594452109991,1739137703.9679039,45.649956464767456,72.83348165095222,1739137703.9679065,45.649956464767456,35.32231556011817,1739137703.9679081,45.649956464767456,-0.10095099620791526,1739137703.9679096,45.649956464767456,3.038444307751692,1739137703.9679112,45.649956464767456,-1.7668953355880248,1739137703.9679124,45.649956464767456,-0.6108,1739137703.9679136,45.649956464767456,1.2331015706554633,1739137703.9679153,45.649956464767456,0.0,1739137703.9679167,45.649956464767456,0.17602529047479876,1739137703.9679184,45.649956464767456,3.4356355760728947,1739137703.9679198,45.649956464767456,1.0570762801806646 +1739137703.989047,45.66995644569397,39.86566813886469,1739137703.989051,45.66995644569397,-0.5712594452109991,1739137703.989056,45.66995644569397,72.83348165095222,1739137703.9890614,45.66995644569397,35.32231556011817,1739137703.9890645,45.66995644569397,-0.10095099620791526,1739137703.989068,45.66995644569397,3.038444307751692,1739137703.9890714,45.66995644569397,-1.7668953355880248,1739137703.9890747,45.66995644569397,-0.6108,1739137703.989078,45.66995644569397,1.2331015706554633,1739137703.9890816,45.66995644569397,0.0,1739137703.989085,45.66995644569397,0.17602529047479876,1739137703.9890885,45.66995644569397,3.4356355760728947,1739137703.9890916,45.66995644569397,1.0570762801806646 +1739137704.008838,45.68995642662048,39.86566813886469,1739137704.0088415,45.68995642662048,-0.5712594452109991,1739137704.0088463,45.68995642662048,72.83348165095222,1739137704.0088513,45.68995642662048,35.32231556011817,1739137704.008854,45.68995642662048,-0.10095099620791526,1739137704.0088582,45.68995642662048,3.038444307751692,1739137704.008861,45.68995642662048,-1.7668953355880248,1739137704.0088644,45.68995642662048,-0.6108,1739137704.008868,45.68995642662048,1.2331015706554633,1739137704.0088713,45.68995642662048,0.0,1739137704.0088747,45.68995642662048,0.17602529047479876,1739137704.008878,45.68995642662048,3.4356355760728947,1739137704.0088816,45.68995642662048,1.0570762801806646 +1739137704.0294554,45.709956407547,39.753033668162125,1739137704.0294595,45.709956407547,-0.6038182077563725,1739137704.0294638,45.709956407547,72.89836650449574,1739137704.029469,45.709956407547,35.19930293865093,1739137704.0294716,45.709956407547,-0.1,1739137704.0294752,45.709956407547,3.031402245490155,1739137704.0294785,45.709956407547,-1.684480043970009,1739137704.029482,45.709956407547,-0.6108,1739137704.0294855,45.709956407547,1.2744296106105648,1739137704.0294888,45.709956407547,0.0,1739137704.0294921,45.709956407547,0.21793128862134115,1739137704.0294957,45.709956407547,3.4079030618433617,1739137704.029499,45.709956407547,1.0764535691703807 +1739137704.0472288,45.72995638847351,39.753033668162125,1739137704.0472317,45.72995638847351,-0.6038182077563725,1739137704.0472343,45.72995638847351,72.89836650449574,1739137704.0472372,45.72995638847351,35.19930293865093,1739137704.0472383,45.72995638847351,-0.1,1739137704.04724,45.72995638847351,3.031402245490155,1739137704.0472414,45.72995638847351,-1.684480043970009,1739137704.0472436,45.72995638847351,-0.6108,1739137704.0472448,45.72995638847351,1.2744296106105648,1739137704.0472462,45.72995638847351,0.0,1739137704.0472476,45.72995638847351,0.1979760414401841,1739137704.0472488,45.72995638847351,3.4079030618433617,1739137704.0472503,45.72995638847351,1.0764535691703807 +1739137704.066689,45.749956369400024,39.753033668162125,1739137704.066692,45.749956369400024,-0.6038182077563725,1739137704.066695,45.749956369400024,72.89836650449574,1739137704.0666974,45.749956369400024,35.19930293865093,1739137704.0666993,45.749956369400024,-0.1,1739137704.0667007,45.749956369400024,3.031402245490155,1739137704.0667021,45.749956369400024,-1.684480043970009,1739137704.0667033,45.749956369400024,-0.6108,1739137704.0667048,45.749956369400024,1.2744296106105648,1739137704.0667064,45.749956369400024,0.0,1739137704.0667074,45.749956369400024,0.1979760414401841,1739137704.066709,45.749956369400024,3.4079030618433617,1739137704.0667102,45.749956369400024,1.0764535691703807 +1739137704.0867271,45.76995635032654,39.753033668162125,1739137704.0867295,45.76995635032654,-0.6038182077563725,1739137704.0867324,45.76995635032654,72.89836650449574,1739137704.0867348,45.76995635032654,35.19930293865093,1739137704.0867362,45.76995635032654,-0.1,1739137704.086738,45.76995635032654,3.031402245490155,1739137704.0867395,45.76995635032654,-1.684480043970009,1739137704.086741,45.76995635032654,-0.6108,1739137704.0867422,45.76995635032654,1.2744296106105648,1739137704.0867438,45.76995635032654,0.0,1739137704.0867455,45.76995635032654,0.1979760414401841,1739137704.0867472,45.76995635032654,3.4079030618433617,1739137704.0867484,45.76995635032654,1.0764535691703807 +1739137704.106534,45.78995633125305,39.753033668162125,1739137704.1065366,45.78995633125305,-0.6038182077563725,1739137704.1065395,45.78995633125305,72.89836650449574,1739137704.106542,45.78995633125305,35.19930293865093,1739137704.1065433,45.78995633125305,-0.1,1739137704.1065452,45.78995633125305,3.031402245490155,1739137704.1065469,45.78995633125305,-1.684480043970009,1739137704.1065483,45.78995633125305,-0.6108,1739137704.1065495,45.78995633125305,1.2744296106105648,1739137704.106551,45.78995633125305,0.0,1739137704.1065524,45.78995633125305,0.1979760414401841,1739137704.1065538,45.78995633125305,3.4079030618433617,1739137704.1065552,45.78995633125305,1.0764535691703807 +1739137704.126277,45.809956312179565,39.753033668162125,1739137704.1262794,45.809956312179565,-0.6038182077563725,1739137704.1262822,45.809956312179565,72.89836650449574,1739137704.126285,45.809956312179565,35.19930293865093,1739137704.1262865,45.809956312179565,-0.1,1739137704.1262882,45.809956312179565,3.031402245490155,1739137704.1262896,45.809956312179565,-1.684480043970009,1739137704.126291,45.809956312179565,-0.6108,1739137704.1262922,45.809956312179565,1.2744296106105648,1739137704.1262937,45.809956312179565,0.0,1739137704.1262953,45.809956312179565,0.1979760414401841,1739137704.1262968,45.809956312179565,3.4079030618433617,1739137704.126298,45.809956312179565,1.0764535691703807 +1739137704.147035,45.82995629310608,39.63732811505842,1739137704.1470377,45.82995629310608,-0.6338139997015322,1739137704.1470408,45.82995629310608,73.07419587449095,1739137704.1470432,45.82995629310608,34.95718590382089,1739137704.147045,45.82995629310608,-0.1,1739137704.1470463,45.82995629310608,3.0280240934909726,1739137704.147048,45.82995629310608,-1.6247098139753378,1739137704.1470492,45.82995629310608,-0.6108,1739137704.1470504,45.82995629310608,1.305265941083609,1739137704.147052,45.82995629310608,0.0,1739137704.1470532,45.82995629310608,0.2146623477534132,1739137704.147055,45.82995629310608,3.3801705476138286,1739137704.147056,45.82995629310608,1.0985494574486587 +1739137704.1667807,45.84995627403259,39.63732811505842,1739137704.166784,45.84995627403259,-0.6338139997015322,1739137704.1667871,45.84995627403259,73.07419587449095,1739137704.1667898,45.84995627403259,34.95718590382089,1739137704.1667912,45.84995627403259,-0.1,1739137704.1667929,45.84995627403259,3.0280240934909726,1739137704.1667945,45.84995627403259,-1.6247098139753378,1739137704.1667957,45.84995627403259,-0.6108,1739137704.1667972,45.84995627403259,1.305265941083609,1739137704.1667986,45.84995627403259,0.0,1739137704.1668,45.84995627403259,0.2067164836349502,1739137704.1668017,45.84995627403259,3.3801705476138286,1739137704.166803,45.84995627403259,1.0985494574486587 +1739137704.186785,45.869956254959106,39.63732811505842,1739137704.1867878,45.869956254959106,-0.6338139997015322,1739137704.1867907,45.869956254959106,73.07419587449095,1739137704.1867938,45.869956254959106,34.95718590382089,1739137704.186795,45.869956254959106,-0.1,1739137704.1867964,45.869956254959106,3.0280240934909726,1739137704.1867983,45.869956254959106,-1.6247098139753378,1739137704.1867995,45.869956254959106,-0.6108,1739137704.186801,45.869956254959106,1.305265941083609,1739137704.1868024,45.869956254959106,0.0,1739137704.1868038,45.869956254959106,0.2067164836349502,1739137704.1868055,45.869956254959106,3.3801705476138286,1739137704.1868072,45.869956254959106,1.0985494574486587 +1739137704.2066598,45.88995623588562,39.63732811505842,1739137704.2066624,45.88995623588562,-0.6338139997015322,1739137704.2066653,45.88995623588562,73.07419587449095,1739137704.2066677,45.88995623588562,34.95718590382089,1739137704.2066693,45.88995623588562,-0.1,1739137704.206671,45.88995623588562,3.0280240934909726,1739137704.2066724,45.88995623588562,-1.6247098139753378,1739137704.2066736,45.88995623588562,-0.6108,1739137704.206675,45.88995623588562,1.305265941083609,1739137704.2066765,45.88995623588562,0.0,1739137704.2066777,45.88995623588562,0.2067164836349502,1739137704.2066793,45.88995623588562,3.3801705476138286,1739137704.2066805,45.88995623588562,1.0985494574486587 +1739137704.2263858,45.909956216812134,39.63732811505842,1739137704.2263882,45.909956216812134,-0.6338139997015322,1739137704.2263913,45.909956216812134,73.07419587449095,1739137704.2263942,45.909956216812134,34.95718590382089,1739137704.2263956,45.909956216812134,-0.1,1739137704.2263973,45.909956216812134,3.0280240934909726,1739137704.2263987,45.909956216812134,-1.6247098139753378,1739137704.2264001,45.909956216812134,-0.6108,1739137704.2264016,45.909956216812134,1.305265941083609,1739137704.226403,45.909956216812134,0.0,1739137704.2264044,45.909956216812134,0.2067164836349502,1739137704.2264059,45.909956216812134,3.3801705476138286,1739137704.226407,45.909956216812134,1.0985494574486587 +1739137704.2491567,45.92995619773865,39.5184535819713,1739137704.2491608,45.92995619773865,-0.6611372112186258,1739137704.2491658,45.92995619773865,73.15605169608172,1739137704.2491713,45.92995619773865,34.807194907909754,1739137704.2491744,45.92995619773865,-0.09950593938384404,1739137704.2491782,45.92995619773865,3.0229421409006405,1739137704.2491815,45.92995619773865,-1.5351970395181656,1739137704.2491848,45.92995619773865,-0.6108,1739137704.2491884,45.92995619773865,1.3528478865377116,1739137704.2491918,45.92995619773865,0.0,1739137704.2491953,45.92995619773865,0.2541946738301124,1739137704.249199,45.92995619773865,3.3524380333842956,1739137704.2492023,45.92995619773865,1.1212618859993155 +1739137704.2689106,45.94995617866516,39.5184535819713,1739137704.2689145,45.94995617866516,-0.6611372112186258,1739137704.268919,45.94995617866516,73.15605169608172,1739137704.2689245,45.94995617866516,34.807194907909754,1739137704.2689276,45.94995617866516,-0.09950593938384404,1739137704.2689314,45.94995617866516,3.0229421409006405,1739137704.2689347,45.94995617866516,-1.5351970395181656,1739137704.2689383,45.94995617866516,-0.6108,1739137704.2689416,45.94995617866516,1.3528478865377116,1739137704.2689452,45.94995617866516,0.0,1739137704.268949,45.94995617866516,0.23158600053839606,1739137704.2689524,45.94995617866516,3.3524380333842956,1739137704.2689562,45.94995617866516,1.1212618859993155 +1739137704.2868605,45.969956159591675,39.5184535819713,1739137704.286863,45.969956159591675,-0.6611372112186258,1739137704.2868662,45.969956159591675,73.15605169608172,1739137704.286869,45.969956159591675,34.807194907909754,1739137704.2868702,45.969956159591675,-0.09950593938384404,1739137704.2868721,45.969956159591675,3.0229421409006405,1739137704.2868736,45.969956159591675,-1.5351970395181656,1739137704.2868748,45.969956159591675,-0.6108,1739137704.2868762,45.969956159591675,1.3528478865377116,1739137704.2868776,45.969956159591675,0.0,1739137704.2868793,45.969956159591675,0.23158600053839606,1739137704.286881,45.969956159591675,3.3524380333842956,1739137704.2868824,45.969956159591675,1.1212618859993155 +1739137704.307498,45.98995614051819,39.5184535819713,1739137704.307501,45.98995614051819,-0.6611372112186258,1739137704.3075037,45.98995614051819,73.15605169608172,1739137704.307506,45.98995614051819,34.807194907909754,1739137704.3075075,45.98995614051819,-0.09950593938384404,1739137704.307509,45.98995614051819,3.0229421409006405,1739137704.3075106,45.98995614051819,-1.5351970395181656,1739137704.3075118,45.98995614051819,-0.6108,1739137704.307513,45.98995614051819,1.3528478865377116,1739137704.3075147,45.98995614051819,0.0,1739137704.3075159,45.98995614051819,0.23158600053839606,1739137704.3075173,45.98995614051819,3.3524380333842956,1739137704.3075185,45.98995614051819,1.1212618859993155 +1739137704.3268976,46.0099561214447,39.5184535819713,1739137704.3269002,46.0099561214447,-0.6611372112186258,1739137704.326903,46.0099561214447,73.15605169608172,1739137704.326906,46.0099561214447,34.807194907909754,1739137704.3269072,46.0099561214447,-0.09950593938384404,1739137704.3269088,46.0099561214447,3.0229421409006405,1739137704.3269103,46.0099561214447,-1.5351970395181656,1739137704.3269114,46.0099561214447,-0.6108,1739137704.3269129,46.0099561214447,1.3528478865377116,1739137704.3269145,46.0099561214447,0.0,1739137704.3269157,46.0099561214447,0.23158600053839606,1739137704.3269172,46.0099561214447,3.3524380333842956,1739137704.3269184,46.0099561214447,1.1212618859993155 +1739137704.3467343,46.029956102371216,39.5184535819713,1739137704.3467371,46.029956102371216,-0.6611372112186258,1739137704.34674,46.029956102371216,73.15605169608172,1739137704.346743,46.029956102371216,34.807194907909754,1739137704.3467443,46.029956102371216,-0.09950593938384404,1739137704.346746,46.029956102371216,3.0229421409006405,1739137704.3467474,46.029956102371216,-1.5351970395181656,1739137704.3467488,46.029956102371216,-0.6108,1739137704.3467503,46.029956102371216,1.3528478865377116,1739137704.3467517,46.029956102371216,0.0,1739137704.3467531,46.029956102371216,0.23158600053839606,1739137704.3467548,46.029956102371216,3.3524380333842956,1739137704.346756,46.029956102371216,1.1212618859993155 +1739137704.3665664,46.04995608329773,39.3962449515374,1739137704.366569,46.04995608329773,-0.685679632198049,1739137704.3665724,46.04995608329773,73.22557454673635,1739137704.366575,46.04995608329773,34.66018042198454,1739137704.3665764,46.04995608329773,-0.099,1739137704.3665779,46.04995608329773,3.0183455794464122,1739137704.3665793,46.04995608329773,-1.4392673312872608,1739137704.3665805,46.04995608329773,-0.6108,1739137704.3665817,46.04995608329773,1.4057680375316506,1739137704.3665833,46.04995608329773,0.0,1739137704.3665843,46.04995608329773,0.28330116850714626,1739137704.3665862,46.04995608329773,3.3247055191547625,1739137704.3665879,46.04995608329773,1.147093151787718 +1739137704.3868194,46.06995606422424,39.3962449515374,1739137704.3868222,46.06995606422424,-0.685679632198049,1739137704.3868248,46.06995606422424,73.22557454673635,1739137704.3868275,46.06995606422424,34.66018042198454,1739137704.386829,46.06995606422424,-0.099,1739137704.3868306,46.06995606422424,3.0183455794464122,1739137704.3868318,46.06995606422424,-1.4392673312872608,1739137704.3868332,46.06995606422424,-0.6108,1739137704.3868344,46.06995606422424,1.4057680375316506,1739137704.386836,46.06995606422424,0.0,1739137704.3868375,46.06995606422424,0.2586748857439325,1739137704.3868392,46.06995606422424,3.3247055191547625,1739137704.3868403,46.06995606422424,1.147093151787718 +1739137704.4068887,46.08995604515076,39.3962449515374,1739137704.4068918,46.08995604515076,-0.685679632198049,1739137704.4068947,46.08995604515076,73.22557454673635,1739137704.406897,46.08995604515076,34.66018042198454,1739137704.4068987,46.08995604515076,-0.099,1739137704.4069004,46.08995604515076,3.0183455794464122,1739137704.406902,46.08995604515076,-1.4392673312872608,1739137704.4069033,46.08995604515076,-0.6108,1739137704.406905,46.08995604515076,1.4057680375316506,1739137704.4069064,46.08995604515076,0.0,1739137704.4069076,46.08995604515076,0.2586748857439325,1739137704.4069092,46.08995604515076,3.3247055191547625,1739137704.4069104,46.08995604515076,1.147093151787718 +1739137704.4269369,46.10995602607727,39.3962449515374,1739137704.4269402,46.10995602607727,-0.685679632198049,1739137704.4269435,46.10995602607727,73.22557454673635,1739137704.4269466,46.10995602607727,34.66018042198454,1739137704.426948,46.10995602607727,-0.099,1739137704.42695,46.10995602607727,3.0183455794464122,1739137704.4269514,46.10995602607727,-1.4392673312872608,1739137704.426953,46.10995602607727,-0.6108,1739137704.4269543,46.10995602607727,1.4057680375316506,1739137704.426956,46.10995602607727,0.0,1739137704.4269574,46.10995602607727,0.2586748857439325,1739137704.426959,46.10995602607727,3.3247055191547625,1739137704.4269605,46.10995602607727,1.147093151787718 +1739137704.4465606,46.129956007003784,39.3962449515374,1739137704.4465635,46.129956007003784,-0.685679632198049,1739137704.4465668,46.129956007003784,73.22557454673635,1739137704.44657,46.129956007003784,34.66018042198454,1739137704.4465716,46.129956007003784,-0.099,1739137704.4465733,46.129956007003784,3.0183455794464122,1739137704.446575,46.129956007003784,-1.4392673312872608,1739137704.446576,46.129956007003784,-0.6108,1739137704.4465775,46.129956007003784,1.4057680375316506,1739137704.4465792,46.129956007003784,0.0,1739137704.4465806,46.129956007003784,0.2586748857439325,1739137704.4465826,46.129956007003784,3.3247055191547625,1739137704.446584,46.129956007003784,1.147093151787718 +1739137704.4668508,46.1499559879303,39.27048552954639,1739137704.4668539,46.1499559879303,-0.7073254121817651,1739137704.4668574,46.1499559879303,73.36164974093221,1739137704.4668605,46.1499559879303,34.43845081858556,1739137704.466862,46.1499559879303,-0.09837670185241999,1739137704.4668636,46.1499559879303,3.016230280201186,1739137704.466865,46.1499559879303,-1.3493983293253289,1739137704.4668667,46.1499559879303,-0.6108,1739137704.4668682,46.1499559879303,1.4572212956643877,1739137704.4668698,46.1499559879303,0.0,1739137704.466871,46.1499559879303,0.3023948209658266,1739137704.4668727,46.1499559879303,3.2969730049252295,1739137704.4668741,46.1499559879303,1.1756455018709053 +1739137704.4868155,46.16995596885681,39.27048552954639,1739137704.4868186,46.16995596885681,-0.7073254121817651,1739137704.4868217,46.16995596885681,73.36164974093221,1739137704.4868248,46.16995596885681,34.43845081858556,1739137704.4868262,46.16995596885681,-0.09837670185241999,1739137704.486828,46.16995596885681,3.016230280201186,1739137704.4868295,46.16995596885681,-1.3493983293253289,1739137704.4868312,46.16995596885681,-0.6108,1739137704.4868324,46.16995596885681,1.4572212956643877,1739137704.4868338,46.16995596885681,0.0,1739137704.4868355,46.16995596885681,0.2815757937934824,1739137704.486837,46.16995596885681,3.2969730049252295,1739137704.4868383,46.16995596885681,1.1756455018709053 +1739137704.5067112,46.189955949783325,39.27048552954639,1739137704.506714,46.189955949783325,-0.7073254121817651,1739137704.506718,46.189955949783325,73.36164974093221,1739137704.506721,46.189955949783325,34.43845081858556,1739137704.5067225,46.189955949783325,-0.09837670185241999,1739137704.5067244,46.189955949783325,3.016230280201186,1739137704.5067258,46.189955949783325,-1.3493983293253289,1739137704.5067272,46.189955949783325,-0.6108,1739137704.5067286,46.189955949783325,1.4572212956643877,1739137704.5067303,46.189955949783325,0.0,1739137704.5067317,46.189955949783325,0.2815757937934824,1739137704.5067334,46.189955949783325,3.2969730049252295,1739137704.5067346,46.189955949783325,1.1756455018709053 +1739137704.5272021,46.20995593070984,39.27048552954639,1739137704.5272048,46.20995593070984,-0.7073254121817651,1739137704.527208,46.20995593070984,73.36164974093221,1739137704.5272112,46.20995593070984,34.43845081858556,1739137704.5272126,46.20995593070984,-0.09837670185241999,1739137704.5272145,46.20995593070984,3.016230280201186,1739137704.5272162,46.20995593070984,-1.3493983293253289,1739137704.5272174,46.20995593070984,-0.6108,1739137704.5272186,46.20995593070984,1.4572212956643877,1739137704.5272205,46.20995593070984,0.0,1739137704.527222,46.20995593070984,0.2815757937934824,1739137704.527224,46.20995593070984,3.2969730049252295,1739137704.5272253,46.20995593070984,1.1756455018709053 +1739137704.5567281,46.22995591163635,39.27048552954639,1739137704.556737,46.22995591163635,-0.7073254121817651,1739137704.556747,46.22995591163635,73.36164974093221,1739137704.5567567,46.22995591163635,34.43845081858556,1739137704.5567622,46.22995591163635,-0.09837670185241999,1739137704.5567682,46.22995591163635,3.016230280201186,1739137704.5567734,46.22995591163635,-1.3493983293253289,1739137704.556778,46.22995591163635,-0.6108,1739137704.5567822,46.22995591163635,1.4572212956643877,1739137704.5567877,46.22995591163635,0.0,1739137704.5567925,46.22995591163635,0.2815757937934824,1739137704.5567977,46.22995591163635,3.2969730049252295,1739137704.5568023,46.22995591163635,1.1756455018709053 +1739137704.5727549,46.249955892562866,39.27048552954639,1739137704.572761,46.249955892562866,-0.7073254121817651,1739137704.5727684,46.249955892562866,73.36164974093221,1739137704.572777,46.249955892562866,34.43845081858556,1739137704.5727816,46.249955892562866,-0.09837670185241999,1739137704.5727878,46.249955892562866,3.016230280201186,1739137704.572793,46.249955892562866,-1.3493983293253289,1739137704.5727987,46.249955892562866,-0.6108,1739137704.5728042,46.249955892562866,1.4572212956643877,1739137704.5728097,46.249955892562866,0.0,1739137704.5728152,46.249955892562866,0.2815757937934824,1739137704.5728207,46.249955892562866,3.2969730049252295,1739137704.572826,46.249955892562866,1.1756455018709053 +1739137704.5899928,46.26995587348938,39.1409148076054,1739137704.5899966,46.26995587348938,-0.7259436266452113,1739137704.5900009,46.26995587348938,73.58958562913068,1739137704.5900059,46.26995587348938,34.11669931722894,1739137704.5900085,46.26995587348938,-0.09748934507236062,1739137704.590012,46.26995587348938,3.017153911375741,1739137704.5900154,46.26995587348938,-1.2629312450721426,1739137704.5900187,46.26995587348938,-0.6108,1739137704.5900218,46.26995587348938,1.5085037022079626,1739137704.5900254,46.26995587348938,0.0,1739137704.5900285,46.26995587348938,0.31977576537285407,1739137704.5900319,46.26995587348938,3.2692404906956964,1739137704.590035,46.26995587348938,1.2069184085788875 +1739137704.610256,46.289955854415894,39.1409148076054,1739137704.6102598,46.289955854415894,-0.7259436266452113,1739137704.6102645,46.289955854415894,73.58958562913068,1739137704.6102698,46.289955854415894,34.11669931722894,1739137704.6102724,46.289955854415894,-0.09748934507236062,1739137704.610276,46.289955854415894,3.017153911375741,1739137704.6102793,46.289955854415894,-1.2629312450721426,1739137704.6102824,46.289955854415894,-0.6108,1739137704.6102858,46.289955854415894,1.5085037022079626,1739137704.610289,46.289955854415894,0.0,1739137704.6102924,46.289955854415894,0.30158529362907505,1739137704.610296,46.289955854415894,3.2692404906956964,1739137704.6102993,46.289955854415894,1.2069184085788875 +1739137704.6296723,46.30995583534241,39.1409148076054,1739137704.6296756,46.30995583534241,-0.7259436266452113,1739137704.6296797,46.30995583534241,73.58958562913068,1739137704.6296844,46.30995583534241,34.11669931722894,1739137704.629687,46.30995583534241,-0.09748934507236062,1739137704.6296904,46.30995583534241,3.017153911375741,1739137704.6296937,46.30995583534241,-1.2629312450721426,1739137704.6296966,46.30995583534241,-0.6108,1739137704.6297002,46.30995583534241,1.5085037022079626,1739137704.6297033,46.30995583534241,0.0,1739137704.6297061,46.30995583534241,0.30158529362907505,1739137704.6297092,46.30995583534241,3.2692404906956964,1739137704.6297123,46.30995583534241,1.2069184085788875 +1739137704.64981,46.32995581626892,39.1409148076054,1739137704.6498137,46.32995581626892,-0.7259436266452113,1739137704.6498184,46.32995581626892,73.58958562913068,1739137704.6498232,46.32995581626892,34.11669931722894,1739137704.649826,46.32995581626892,-0.09748934507236062,1739137704.6498296,46.32995581626892,3.017153911375741,1739137704.6498327,46.32995581626892,-1.2629312450721426,1739137704.6498358,46.32995581626892,-0.6108,1739137704.649839,46.32995581626892,1.5085037022079626,1739137704.6498423,46.32995581626892,0.0,1739137704.6498454,46.32995581626892,0.30158529362907505,1739137704.6498485,46.32995581626892,3.2692404906956964,1739137704.6498516,46.32995581626892,1.2069184085788875 +1739137704.6694224,46.349955797195435,39.1409148076054,1739137704.6694255,46.349955797195435,-0.7259436266452113,1739137704.6694295,46.349955797195435,73.58958562913068,1739137704.669434,46.349955797195435,34.11669931722894,1739137704.669437,46.349955797195435,-0.09748934507236062,1739137704.6694403,46.349955797195435,3.017153911375741,1739137704.6694434,46.349955797195435,-1.2629312450721426,1739137704.6694465,46.349955797195435,-0.6108,1739137704.6694496,46.349955797195435,1.5085037022079626,1739137704.6694524,46.349955797195435,0.0,1739137704.6694553,46.349955797195435,0.30158529362907505,1739137704.6694589,46.349955797195435,3.2692404906956964,1739137704.669462,46.349955797195435,1.2069184085788875 +1739137704.6898074,46.36995577812195,39.00738199425798,1739137704.6898105,46.36995577812195,-0.7413651996046928,1739137704.6898146,46.36995577812195,73.59151677480939,1739137704.6898375,46.36995577812195,34.01519566377562,1739137704.6898403,46.36995577812195,-0.097,1739137704.689844,46.36995577812195,3.013227630652434,1739137704.689847,46.36995577812195,-1.1391179064815926,1739137704.6898503,46.36995577812195,-0.6108,1739137704.6898534,46.36995577812195,1.5850937744682674,1739137704.6898568,46.36995577812195,0.0,1739137704.6898603,46.36995577812195,0.3844374975064017,1739137704.6898637,46.36995577812195,3.2415079764661634,1739137704.6898668,46.36995577812195,1.2401097270883623 +1739137704.7094302,46.38995575904846,39.00738199425798,1739137704.7094333,46.38995575904846,-0.7413651996046928,1739137704.7094371,46.38995575904846,73.59151677480939,1739137704.7094421,46.38995575904846,34.01519566377562,1739137704.7094445,46.38995575904846,-0.097,1739137704.709448,46.38995575904846,3.013227630652434,1739137704.709451,46.38995575904846,-1.1391179064815926,1739137704.709454,46.38995575904846,-0.6108,1739137704.7094572,46.38995575904846,1.5850937744682674,1739137704.7094603,46.38995575904846,0.0,1739137704.7094634,46.38995575904846,0.34498404737990507,1739137704.7094667,46.38995575904846,3.2415079764661634,1739137704.7094696,46.38995575904846,1.2401097270883623 +1739137704.7293348,46.409955739974976,39.00738199425798,1739137704.7293382,46.409955739974976,-0.7413651996046928,1739137704.7293422,46.409955739974976,73.59151677480939,1739137704.729347,46.409955739974976,34.01519566377562,1739137704.7293499,46.409955739974976,-0.097,1739137704.7293534,46.409955739974976,3.013227630652434,1739137704.7293565,46.409955739974976,-1.1391179064815926,1739137704.7293599,46.409955739974976,-0.6108,1739137704.729363,46.409955739974976,1.5850937744682674,1739137704.7293665,46.409955739974976,0.0,1739137704.7293696,46.409955739974976,0.34498404737990507,1739137704.729373,46.409955739974976,3.2415079764661634,1739137704.7293766,46.409955739974976,1.2401097270883623 +1739137704.7477028,46.42995572090149,39.00738199425798,1739137704.7477057,46.42995572090149,-0.7413651996046928,1739137704.7477086,46.42995572090149,73.59151677480939,1739137704.7477114,46.42995572090149,34.01519566377562,1739137704.7477129,46.42995572090149,-0.097,1739137704.7477145,46.42995572090149,3.013227630652434,1739137704.747716,46.42995572090149,-1.1391179064815926,1739137704.7477174,46.42995572090149,-0.6108,1739137704.7477183,46.42995572090149,1.5850937744682674,1739137704.74772,46.42995572090149,0.0,1739137704.7477212,46.42995572090149,0.34498404737990507,1739137704.747723,46.42995572090149,3.2415079764661634,1739137704.7477243,46.42995572090149,1.2401097270883623 +1739137704.7682745,46.449955701828,39.00738199425798,1739137704.7682772,46.449955701828,-0.7413651996046928,1739137704.7682798,46.449955701828,73.59151677480939,1739137704.768283,46.449955701828,34.01519566377562,1739137704.768284,46.449955701828,-0.097,1739137704.768286,46.449955701828,3.013227630652434,1739137704.7682872,46.449955701828,-1.1391179064815926,1739137704.7682886,46.449955701828,-0.6108,1739137704.7682898,46.449955701828,1.5850937744682674,1739137704.768291,46.449955701828,0.0,1739137704.7682924,46.449955701828,0.34498404737990507,1739137704.7682936,46.449955701828,3.2415079764661634,1739137704.7682948,46.449955701828,1.2401097270883623 +1739137704.787562,46.46995568275452,39.00738199425798,1739137704.7875645,46.46995568275452,-0.7413651996046928,1739137704.7875679,46.46995568275452,73.59151677480939,1739137704.7875702,46.46995568275452,34.01519566377562,1739137704.787572,46.46995568275452,-0.097,1739137704.7875736,46.46995568275452,3.013227630652434,1739137704.787575,46.46995568275452,-1.1391179064815926,1739137704.7875764,46.46995568275452,-0.6108,1739137704.7875779,46.46995568275452,1.5850937744682674,1739137704.7875793,46.46995568275452,0.0,1739137704.7875807,46.46995568275452,0.34498404737990507,1739137704.7875822,46.46995568275452,3.2415079764661634,1739137704.7875836,46.46995568275452,1.2401097270883623 +1739137704.8071826,46.48995566368103,38.86953268663845,1739137704.807185,46.48995566368103,-0.7534217385000872,1739137704.8071876,46.48995566368103,73.83181938482818,1739137704.80719,46.48995566368103,33.65912866311762,1739137704.8071914,46.48995566368103,-0.09590348506599691,1739137704.8071928,46.48995566368103,3.016062857450024,1739137704.8071945,46.48995566368103,-1.0315811220545523,1739137704.8071957,46.48995566368103,-0.5676281376006671,1739137704.8071969,46.48995566368103,1.6547638056954832,1739137704.8071988,46.48995566368103,0.0,1739137704.8072,46.48995566368103,0.40431939132042893,1739137704.8072016,46.48995566368103,3.2137754622366304,1739137704.8072026,46.48995566368103,1.2786993541755949 +1739137704.82728,46.509955644607544,38.86953268663845,1739137704.8272824,46.509955644607544,-0.7534217385000872,1739137704.827285,46.509955644607544,73.83181938482818,1739137704.8272874,46.509955644607544,33.65912866311762,1739137704.8272889,46.509955644607544,-0.09590348506599691,1739137704.8272905,46.509955644607544,3.016062857450024,1739137704.827292,46.509955644607544,-1.0315811220545523,1739137704.8272936,46.509955644607544,-0.5676281376006671,1739137704.8272948,46.509955644607544,1.6547638056954832,1739137704.8272963,46.509955644607544,0.0,1739137704.8272972,46.509955644607544,0.3760644515198883,1739137704.8272989,46.509955644607544,3.2137754622366304,1739137704.8272998,46.509955644607544,1.2786993541755949 +1739137704.848975,46.52995562553406,38.86953268663845,1739137704.8489788,46.52995562553406,-0.7534217385000872,1739137704.848983,46.52995562553406,73.83181938482818,1739137704.8489873,46.52995562553406,33.65912866311762,1739137704.8489902,46.52995562553406,-0.09590348506599691,1739137704.848993,46.52995562553406,3.016062857450024,1739137704.8489957,46.52995562553406,-1.0315811220545523,1739137704.848998,46.52995562553406,-0.5676281376006671,1739137704.8490005,46.52995562553406,1.6547638056954832,1739137704.8490033,46.52995562553406,0.0,1739137704.8490055,46.52995562553406,0.3760644515198883,1739137704.8490078,46.52995562553406,3.2137754622366304,1739137704.8490102,46.52995562553406,1.2786993541755949 +1739137704.8696575,46.54995560646057,38.86953268663845,1739137704.869661,46.54995560646057,-0.7534217385000872,1739137704.8696659,46.54995560646057,73.83181938482818,1739137704.869671,46.54995560646057,33.65912866311762,1739137704.869674,46.54995560646057,-0.09590348506599691,1739137704.8696778,46.54995560646057,3.016062857450024,1739137704.8696814,46.54995560646057,-1.0315811220545523,1739137704.8696847,46.54995560646057,-0.5676281376006671,1739137704.8696883,46.54995560646057,1.6547638056954832,1739137704.8696918,46.54995560646057,0.0,1739137704.8696952,46.54995560646057,0.3760644515198883,1739137704.8696988,46.54995560646057,3.2137754622366304,1739137704.869702,46.54995560646057,1.2786993541755949 +1739137704.8894339,46.569955587387085,38.86953268663845,1739137704.8894367,46.569955587387085,-0.7534217385000872,1739137704.8894396,46.569955587387085,73.83181938482818,1739137704.8894422,46.569955587387085,33.65912866311762,1739137704.8894439,46.569955587387085,-0.09590348506599691,1739137704.8894453,46.569955587387085,3.016062857450024,1739137704.889447,46.569955587387085,-1.0315811220545523,1739137704.8894482,46.569955587387085,-0.5676281376006671,1739137704.8894498,46.569955587387085,1.6547638056954832,1739137704.8894515,46.569955587387085,0.0,1739137704.8894527,46.569955587387085,0.3760644515198883,1739137704.8894546,46.569955587387085,3.2137754622366304,1739137704.8894558,46.569955587387085,1.2786993541755949 +1739137704.9097402,46.5899555683136,38.727055208202295,1739137704.909745,46.5899555683136,-0.7619096750248833,1739137704.9097512,46.5899555683136,73.83629560221537,1739137704.9097552,46.5899555683136,33.53035171808203,1739137704.9097564,46.5899555683136,-0.095,1739137704.9097579,46.5899555683136,3.013957080223607,1739137704.9097595,46.5899555683136,-0.8971698737618401,1739137704.9097607,46.5899555683136,-0.49740524884796056,1739137704.9097621,46.5899555683136,1.7461664452992758,1739137704.9097636,46.5899555683136,0.0,1739137704.9097648,46.5899555683136,0.4714576429900717,1739137704.9097664,46.5899555683136,3.1860429480070973,1739137704.9097676,46.5899555683136,1.320134154272668 +1739137704.9299984,46.60995554924011,38.727055208202295,1739137704.930002,46.60995554924011,-0.7619096750248833,1739137704.9300065,46.60995554924011,73.83629560221537,1739137704.9300117,46.60995554924011,33.53035171808203,1739137704.930015,46.60995554924011,-0.095,1739137704.9300187,46.60995554924011,3.013957080223607,1739137704.9300222,46.60995554924011,-0.8971698737618401,1739137704.9300256,46.60995554924011,-0.49740524884796056,1739137704.930029,46.60995554924011,1.7461664452992758,1739137704.9300325,46.60995554924011,0.0,1739137704.9300358,46.60995554924011,0.4260322910266079,1739137704.9300396,46.60995554924011,3.1860429480070973,1739137704.930043,46.60995554924011,1.320134154272668 +1739137704.9504027,46.629955530166626,38.727055208202295,1739137704.950407,46.629955530166626,-0.7619096750248833,1739137704.9504118,46.629955530166626,73.83629560221537,1739137704.9504182,46.629955530166626,33.53035171808203,1739137704.9504206,46.629955530166626,-0.095,1739137704.9504251,46.629955530166626,3.013957080223607,1739137704.9504292,46.629955530166626,-0.8971698737618401,1739137704.9504328,46.629955530166626,-0.49740524884796056,1739137704.950436,46.629955530166626,1.7461664452992758,1739137704.9504395,46.629955530166626,0.0,1739137704.950443,46.629955530166626,0.4260322910266079,1739137704.950447,46.629955530166626,3.1860429480070973,1739137704.9504502,46.629955530166626,1.320134154272668 +1739137704.9704123,46.64995551109314,38.727055208202295,1739137704.9704163,46.64995551109314,-0.7619096750248833,1739137704.9704213,46.64995551109314,73.83629560221537,1739137704.9704273,46.64995551109314,33.53035171808203,1739137704.9704313,46.64995551109314,-0.095,1739137704.9704351,46.64995551109314,3.013957080223607,1739137704.9704385,46.64995551109314,-0.8971698737618401,1739137704.9704428,46.64995551109314,-0.49740524884796056,1739137704.9704454,46.64995551109314,1.7461664452992758,1739137704.97045,46.64995551109314,0.0,1739137704.9704535,46.64995551109314,0.4260322910266079,1739137704.970457,46.64995551109314,3.1860429480070973,1739137704.9704611,46.64995551109314,1.320134154272668 +1739137704.988296,46.66995549201965,38.727055208202295,1739137704.9882987,46.66995549201965,-0.7619096750248833,1739137704.9883015,46.66995549201965,73.83629560221537,1739137704.988304,46.66995549201965,33.53035171808203,1739137704.988305,46.66995549201965,-0.095,1739137704.9883068,46.66995549201965,3.013957080223607,1739137704.9883082,46.66995549201965,-0.8971698737618401,1739137704.9883091,46.66995549201965,-0.49740524884796056,1739137704.9883106,46.66995549201965,1.7461664452992758,1739137704.9883118,46.66995549201965,0.0,1739137704.988334,46.66995549201965,0.4260322910266079,1739137704.9883354,46.66995549201965,3.1860429480070973,1739137704.9883366,46.66995549201965,1.320134154272668 +1739137705.0093205,46.68995547294617,38.727055208202295,1739137705.0093236,46.68995547294617,-0.7619096750248833,1739137705.0093274,46.68995547294617,73.83629560221537,1739137705.009332,46.68995547294617,33.53035171808203,1739137705.0093346,46.68995547294617,-0.095,1739137705.009338,46.68995547294617,3.013957080223607,1739137705.009341,46.68995547294617,-0.8971698737618401,1739137705.009344,46.68995547294617,-0.49740524884796056,1739137705.009347,46.68995547294617,1.7461664452992758,1739137705.00935,46.68995547294617,0.0,1739137705.0093532,46.68995547294617,0.4260322910266079,1739137705.0093565,46.68995547294617,3.1860429480070973,1739137705.0093594,46.68995547294617,1.320134154272668 +1739137705.0274904,46.70995545387268,38.57949655546732,1739137705.0274932,46.70995545387268,-0.7666297264171744,1739137705.027496,46.70995545387268,74.03964231349146,1739137705.0274987,46.70995545387268,33.18427117471069,1739137705.0275,46.70995545387268,-0.09108571015789729,1739137705.0275018,46.70995545387268,3.0170294632967716,1739137705.027503,46.70995545387268,-0.769791387973305,1739137705.0275044,46.70995545387268,-0.39759042571899117,1739137705.0275056,46.70995545387268,1.8374416135933413,1739137705.0275073,46.70995545387268,0.0,1739137705.0275085,46.70995545387268,0.5094386663222508,1739137705.02751,46.70995545387268,3.1590813554227397,1739137705.0275111,46.70995545387268,1.3677202886809916 +1739137705.047987,46.729955434799194,38.57949655546732,1739137705.0479896,46.729955434799194,-0.7666297264171744,1739137705.0479925,46.729955434799194,74.03964231349146,1739137705.047995,46.729955434799194,33.18427117471069,1739137705.0479968,46.729955434799194,-0.09108571015789729,1739137705.0479984,46.729955434799194,3.0170294632967716,1739137705.048,46.729955434799194,-0.769791387973305,1739137705.0480013,46.729955434799194,-0.39759042571899117,1739137705.0480025,46.729955434799194,1.8374416135933413,1739137705.0480042,46.729955434799194,0.0,1739137705.048005,46.729955434799194,0.46972132491234975,1739137705.048007,46.729955434799194,3.1590813554227397,1739137705.0480082,46.729955434799194,1.3677202886809916 +1739137705.0679257,46.74995541572571,38.57949655546732,1739137705.067928,46.74995541572571,-0.7666297264171744,1739137705.0679307,46.74995541572571,74.03964231349146,1739137705.067933,46.74995541572571,33.18427117471069,1739137705.0679348,46.74995541572571,-0.09108571015789729,1739137705.0679362,46.74995541572571,3.0170294632967716,1739137705.0679379,46.74995541572571,-0.769791387973305,1739137705.0679393,46.74995541572571,-0.39759042571899117,1739137705.0679407,46.74995541572571,1.8374416135933413,1739137705.0679421,46.74995541572571,0.0,1739137705.0679433,46.74995541572571,0.46972132491234975,1739137705.067945,46.74995541572571,3.1590813554227397,1739137705.0679464,46.74995541572571,1.3677202886809916 +1739137705.0874116,46.76995539665222,38.57949655546732,1739137705.0874138,46.76995539665222,-0.7666297264171744,1739137705.0874166,46.76995539665222,74.03964231349146,1739137705.087419,46.76995539665222,33.18427117471069,1739137705.0874205,46.76995539665222,-0.09108571015789729,1739137705.087422,46.76995539665222,3.0170294632967716,1739137705.0874236,46.76995539665222,-0.769791387973305,1739137705.0874248,46.76995539665222,-0.39759042571899117,1739137705.0874257,46.76995539665222,1.8374416135933413,1739137705.0874274,46.76995539665222,0.0,1739137705.0874283,46.76995539665222,0.46972132491234975,1739137705.08743,46.76995539665222,3.1590813554227397,1739137705.0874312,46.76995539665222,1.3677202886809916 +1739137705.1074278,46.789955377578735,38.57949655546732,1739137705.10743,46.789955377578735,-0.7666297264171744,1739137705.1074324,46.789955377578735,74.03964231349146,1739137705.1074347,46.789955377578735,33.18427117471069,1739137705.107436,46.789955377578735,-0.09108571015789729,1739137705.1074378,46.789955377578735,3.0170294632967716,1739137705.107439,46.789955377578735,-0.769791387973305,1739137705.1074402,46.789955377578735,-0.39759042571899117,1739137705.1074414,46.789955377578735,1.8374416135933413,1739137705.1074429,46.789955377578735,0.0,1739137705.107444,46.789955377578735,0.46972132491234975,1739137705.1074455,46.789955377578735,3.1590813554227397,1739137705.1074467,46.789955377578735,1.3677202886809916 +1739137705.127466,46.80995535850525,38.42645634598359,1739137705.1274683,46.80995535850525,-0.7675117547306609,1739137705.1274705,46.80995535850525,74.12666089555465,1739137705.127473,46.80995535850525,32.94189579179336,1739137705.1274745,46.80995535850525,-0.0890804535918159,1739137705.127476,46.80995535850525,3.018519450577381,1739137705.1274772,46.80995535850525,-0.6353121674946615,1739137705.1274784,46.80995535850525,-0.31832123982755955,1739137705.1274796,46.80995535850525,1.938987374467094,1739137705.1274807,46.80995535850525,0.0,1739137705.1274822,46.80995535850525,0.5647126502334456,1739137705.1274834,46.80995535850525,3.133734479718361,1739137705.1274846,46.80995535850525,1.4195087112686182 +1739137705.1472452,46.82995533943176,38.42645634598359,1739137705.1472473,46.82995533943176,-0.7675117547306609,1739137705.14725,46.82995533943176,74.12666089555465,1739137705.1472526,46.82995533943176,32.94189579179336,1739137705.1472538,46.82995533943176,-0.0890804535918159,1739137705.147256,46.82995533943176,3.018519450577381,1739137705.147257,46.82995533943176,-0.6353121674946615,1739137705.1472585,46.82995533943176,-0.31832123982755955,1739137705.14726,46.82995533943176,1.938987374467094,1739137705.1472611,46.82995533943176,0.0,1739137705.1472626,46.82995533943176,0.5194786631984758,1739137705.147264,46.82995533943176,3.133734479718361,1739137705.1472652,46.82995533943176,1.4195087112686182 +1739137705.1674953,46.849955320358276,38.42645634598359,1739137705.1674974,46.849955320358276,-0.7675117547306609,1739137705.1675,46.849955320358276,74.12666089555465,1739137705.1675026,46.849955320358276,32.94189579179336,1739137705.1675038,46.849955320358276,-0.0890804535918159,1739137705.1675055,46.849955320358276,3.018519450577381,1739137705.1675067,46.849955320358276,-0.6353121674946615,1739137705.167508,46.849955320358276,-0.31832123982755955,1739137705.1675093,46.849955320358276,1.938987374467094,1739137705.1675105,46.849955320358276,0.0,1739137705.1675117,46.849955320358276,0.5194786631984758,1739137705.1675131,46.849955320358276,3.133734479718361,1739137705.1675143,46.849955320358276,1.4195087112686182 +1739137705.1873374,46.86995530128479,38.42645634598359,1739137705.1873395,46.86995530128479,-0.7675117547306609,1739137705.1873424,46.86995530128479,74.12666089555465,1739137705.1873455,46.86995530128479,32.94189579179336,1739137705.1873467,46.86995530128479,-0.0890804535918159,1739137705.1873484,46.86995530128479,3.018519450577381,1739137705.1873498,46.86995530128479,-0.6353121674946615,1739137705.1873507,46.86995530128479,-0.31832123982755955,1739137705.1873522,46.86995530128479,1.938987374467094,1739137705.1873536,46.86995530128479,0.0,1739137705.1873546,46.86995530128479,0.5194786631984758,1739137705.1873562,46.86995530128479,3.133734479718361,1739137705.1873574,46.86995530128479,1.4195087112686182 +1739137705.207409,46.889955282211304,38.42645634598359,1739137705.2074113,46.889955282211304,-0.7675117547306609,1739137705.2074137,46.889955282211304,74.12666089555465,1739137705.207416,46.889955282211304,32.94189579179336,1739137705.2074175,46.889955282211304,-0.0890804535918159,1739137705.2074192,46.889955282211304,3.018519450577381,1739137705.2074203,46.889955282211304,-0.6353121674946615,1739137705.2074218,46.889955282211304,-0.31832123982755955,1739137705.207423,46.889955282211304,1.938987374467094,1739137705.2074249,46.889955282211304,0.0,1739137705.2074258,46.889955282211304,0.5194786631984758,1739137705.2074273,46.889955282211304,3.133734479718361,1739137705.2074287,46.889955282211304,1.4195087112686182 +1739137705.2273796,46.90995526313782,38.42645634598359,1739137705.2273815,46.90995526313782,-0.7675117547306609,1739137705.2273843,46.90995526313782,74.12666089555465,1739137705.227387,46.90995526313782,32.94189579179336,1739137705.2273881,46.90995526313782,-0.0890804535918159,1739137705.22739,46.90995526313782,3.018519450577381,1739137705.2273915,46.90995526313782,-0.6353121674946615,1739137705.2273927,46.90995526313782,-0.31832123982755955,1739137705.227394,46.90995526313782,1.938987374467094,1739137705.2273953,46.90995526313782,0.0,1739137705.2273967,46.90995526313782,0.5194786631984758,1739137705.2273982,46.90995526313782,3.133734479718361,1739137705.2273993,46.90995526313782,1.4195087112686182 +1739137705.2475889,46.92995524406433,38.267406547785605,1739137705.2475913,46.92995524406433,-0.7645034489125777,1739137705.2475936,46.92995524406433,74.39329999249065,1739137705.2475963,46.92995524406433,32.50183458154931,1739137705.2475975,46.92995524406433,-0.08455067665239452,1739137705.2475994,46.92995524406433,3.0242016116649824,1739137705.2476006,46.92995524406433,-0.49657916283985765,1739137705.247602,46.92995524406433,-0.22587829139881377,1739137705.2476034,46.92995524406433,2.049629544331755,1739137705.247605,46.92995524406433,0.0,1739137705.2476063,46.92995524406433,0.6203284986452059,1739137705.2476077,46.92995524406433,3.109841829843897,1739137705.2476091,46.92995524406433,1.4773248008416227 +1739137705.2671611,46.949955224990845,38.267406547785605,1739137705.2671633,46.949955224990845,-0.7645034489125777,1739137705.267166,46.949955224990845,74.39329999249065,1739137705.2671685,46.949955224990845,32.50183458154931,1739137705.2671697,46.949955224990845,-0.08455067665239452,1739137705.2671716,46.949955224990845,3.0242016116649824,1739137705.2671728,46.949955224990845,-0.49657916283985765,1739137705.2671742,46.949955224990845,-0.22587829139881377,1739137705.2671754,46.949955224990845,2.049629544331755,1739137705.2671766,46.949955224990845,0.0,1739137705.267178,46.949955224990845,0.5723047434901325,1739137705.2671795,46.949955224990845,3.109841829843897,1739137705.2671807,46.949955224990845,1.4773248008416227 +1739137705.28723,46.96995520591736,38.267406547785605,1739137705.287232,46.96995520591736,-0.7645034489125777,1739137705.2872345,46.96995520591736,74.39329999249065,1739137705.2872374,46.96995520591736,32.50183458154931,1739137705.2872386,46.96995520591736,-0.08455067665239452,1739137705.2872403,46.96995520591736,3.0242016116649824,1739137705.2872415,46.96995520591736,-0.49657916283985765,1739137705.2872427,46.96995520591736,-0.22587829139881377,1739137705.2872438,46.96995520591736,2.049629544331755,1739137705.2872455,46.96995520591736,0.0,1739137705.287247,46.96995520591736,0.5723047434901325,1739137705.2872484,46.96995520591736,3.109841829843897,1739137705.2872498,46.96995520591736,1.4773248008416227 +1739137705.3074958,46.98995518684387,38.267406547785605,1739137705.307498,46.98995518684387,-0.7645034489125777,1739137705.3075008,46.98995518684387,74.39329999249065,1739137705.3075035,46.98995518684387,32.50183458154931,1739137705.3075047,46.98995518684387,-0.08455067665239452,1739137705.3075063,46.98995518684387,3.0242016116649824,1739137705.3075078,46.98995518684387,-0.49657916283985765,1739137705.307509,46.98995518684387,-0.22587829139881377,1739137705.3075104,46.98995518684387,2.049629544331755,1739137705.3075118,46.98995518684387,0.0,1739137705.307513,46.98995518684387,0.5723047434901325,1739137705.3075147,46.98995518684387,3.109841829843897,1739137705.3075156,46.98995518684387,1.4773248008416227 +1739137705.3275533,47.009955167770386,38.267406547785605,1739137705.3275554,47.009955167770386,-0.7645034489125777,1739137705.327558,47.009955167770386,74.39329999249065,1739137705.3275607,47.009955167770386,32.50183458154931,1739137705.327562,47.009955167770386,-0.08455067665239452,1739137705.3275635,47.009955167770386,3.0242016116649824,1739137705.327565,47.009955167770386,-0.49657916283985765,1739137705.3275661,47.009955167770386,-0.22587829139881377,1739137705.3275673,47.009955167770386,2.049629544331755,1739137705.327569,47.009955167770386,0.0,1739137705.3275702,47.009955167770386,0.5723047434901325,1739137705.3275714,47.009955167770386,3.109841829843897,1739137705.3275728,47.009955167770386,1.4773248008416227 +1739137705.3476565,47.0299551486969,38.10188735581583,1739137705.347659,47.0299551486969,-0.7575166407815459,1739137705.3476617,47.0299551486969,74.39609285832975,1739137705.3476644,47.0299551486969,32.30978652960099,1739137705.347666,47.0299551486969,-0.0830221153142936,1739137705.3476677,47.0299551486969,3.0256640424215884,1739137705.347669,47.0299551486969,-0.3591189260407451,1739137705.3476706,47.0299551486969,-0.16206332094067152,1739137705.3476717,47.0299551486969,2.1654824157464887,1739137705.3476732,47.0299551486969,0.0,1739137705.3476744,47.0299551486969,0.6730394633468332,1739137705.3476758,47.0299551486969,3.0872883699777796,1739137705.3476772,47.0299551486969,1.5404118905797124 +1739137705.3674955,47.04995512962341,38.10188735581583,1739137705.3674977,47.04995512962341,-0.7575166407815459,1739137705.3675005,47.04995512962341,74.39609285832975,1739137705.3675032,47.04995512962341,32.30978652960099,1739137705.3675044,47.04995512962341,-0.0830221153142936,1739137705.3675063,47.04995512962341,3.0256640424215884,1739137705.3675075,47.04995512962341,-0.3591189260407451,1739137705.3675086,47.04995512962341,-0.16206332094067152,1739137705.36751,47.04995512962341,2.1654824157464887,1739137705.3675113,47.04995512962341,0.0,1739137705.367513,47.04995512962341,0.6250705251667763,1739137705.3675144,47.04995512962341,3.0872883699777796,1739137705.3675156,47.04995512962341,1.5404118905797124 +1739137705.387652,47.06995511054993,38.10188735581583,1739137705.3876576,47.06995511054993,-0.7575166407815459,1739137705.387661,47.06995511054993,74.39609285832975,1739137705.387664,47.06995511054993,32.30978652960099,1739137705.3876674,47.06995511054993,-0.0830221153142936,1739137705.3876834,47.06995511054993,3.0256640424215884,1739137705.3876848,47.06995511054993,-0.3591189260407451,1739137705.3876948,47.06995511054993,-0.16206332094067152,1739137705.3876975,47.06995511054993,2.1654824157464887,1739137705.387701,47.06995511054993,0.0,1739137705.387704,47.06995511054993,0.6250705251667763,1739137705.387707,47.06995511054993,3.0872883699777796,1739137705.3877087,47.06995511054993,1.5404118905797124 +1739137705.4079492,47.08995509147644,38.10188735581583,1739137705.407952,47.08995509147644,-0.7575166407815459,1739137705.4079552,47.08995509147644,74.39609285832975,1739137705.407958,47.08995509147644,32.30978652960099,1739137705.4079595,47.08995509147644,-0.0830221153142936,1739137705.4079616,47.08995509147644,3.0256640424215884,1739137705.407963,47.08995509147644,-0.3591189260407451,1739137705.407965,47.08995509147644,-0.16206332094067152,1739137705.4079661,47.08995509147644,2.1654824157464887,1739137705.407968,47.08995509147644,0.0,1739137705.4079695,47.08995509147644,0.6250705251667763,1739137705.4079714,47.08995509147644,3.0872883699777796,1739137705.407973,47.08995509147644,1.5404118905797124 +1739137705.427755,47.109955072402954,38.10188735581583,1739137705.4277577,47.109955072402954,-0.7575166407815459,1739137705.427761,47.109955072402954,74.39609285832975,1739137705.4277642,47.109955072402954,32.30978652960099,1739137705.4277658,47.109955072402954,-0.0830221153142936,1739137705.4277678,47.109955072402954,3.0256640424215884,1739137705.42777,47.109955072402954,-0.3591189260407451,1739137705.4277713,47.109955072402954,-0.16206332094067152,1739137705.427773,47.109955072402954,2.1654824157464887,1739137705.4277744,47.109955072402954,0.0,1739137705.4277763,47.109955072402954,0.6250705251667763,1739137705.427778,47.109955072402954,3.0872883699777796,1739137705.4277797,47.109955072402954,1.5404118905797124 +1739137705.4477377,47.12995505332947,38.10188735581583,1739137705.4477403,47.12995505332947,-0.7575166407815459,1739137705.4477434,47.12995505332947,74.39609285832975,1739137705.4477465,47.12995505332947,32.30978652960099,1739137705.4477482,47.12995505332947,-0.0830221153142936,1739137705.44775,47.12995505332947,3.0256640424215884,1739137705.447752,47.12995505332947,-0.3591189260407451,1739137705.4477534,47.12995505332947,-0.16206332094067152,1739137705.447755,47.12995505332947,2.1654824157464887,1739137705.4477568,47.12995505332947,0.0,1739137705.4477584,47.12995505332947,0.6250705251667763,1739137705.4477603,47.12995505332947,3.0872883699777796,1739137705.447762,47.12995505332947,1.5404118905797124 +1739137705.4681268,47.14995503425598,37.929280954874905,1739137705.4681296,47.14995503425598,-0.7464250304229516,1739137705.468133,47.14995503425598,74.63191010342551,1739137705.4681358,47.14995503425598,31.865691871369528,1739137705.4681375,47.14995503425598,-0.07938308783534183,1739137705.4681394,47.14995503425598,3.032025444938565,1739137705.468141,47.14995503425598,-0.20701850267959065,1739137705.4681425,47.14995503425598,-0.08542781257309744,1739137705.468144,47.14995503425598,2.301321057339055,1739137705.4681456,47.14995503425598,0.0,1739137705.4681473,47.14995503425598,0.7518486152977879,1739137705.468149,47.14995503425598,3.0659684835699803,1739137705.4681504,47.14995503425598,1.6098429913089995 +1739137705.4881136,47.169955015182495,37.929280954874905,1739137705.4881163,47.169955015182495,-0.7464250304229516,1739137705.4881194,47.169955015182495,74.63191010342551,1739137705.4881222,47.169955015182495,31.865691871369528,1739137705.4881234,47.169955015182495,-0.07938308783534183,1739137705.488125,47.169955015182495,3.032025444938565,1739137705.4881268,47.169955015182495,-0.20701850267959065,1739137705.4881282,47.169955015182495,-0.08542781257309744,1739137705.4881296,47.169955015182495,2.301321057339055,1739137705.488131,47.169955015182495,0.0,1739137705.4881327,47.169955015182495,0.6914780660300555,1739137705.4881341,47.169955015182495,3.0659684835699803,1739137705.4881356,47.169955015182495,1.6098429913089995 +1739137705.5077415,47.18995499610901,37.929280954874905,1739137705.5077438,47.18995499610901,-0.7464250304229516,1739137705.5077462,47.18995499610901,74.63191010342551,1739137705.507749,47.18995499610901,31.865691871369528,1739137705.5077507,47.18995499610901,-0.07938308783534183,1739137705.5077522,47.18995499610901,3.032025444938565,1739137705.5077536,47.18995499610901,-0.20701850267959065,1739137705.507755,47.18995499610901,-0.08542781257309744,1739137705.5077562,47.18995499610901,2.301321057339055,1739137705.507758,47.18995499610901,0.0,1739137705.507759,47.18995499610901,0.6914780660300555,1739137705.507761,47.18995499610901,3.0659684835699803,1739137705.5077622,47.18995499610901,1.6098429913089995 +1739137705.5275936,47.20995497703552,37.929280954874905,1739137705.527596,47.20995497703552,-0.7464250304229516,1739137705.5275989,47.20995497703552,74.63191010342551,1739137705.527602,47.20995497703552,31.865691871369528,1739137705.5276031,47.20995497703552,-0.07938308783534183,1739137705.527605,47.20995497703552,3.032025444938565,1739137705.5276065,47.20995497703552,-0.20701850267959065,1739137705.527608,47.20995497703552,-0.08542781257309744,1739137705.527609,47.20995497703552,2.301321057339055,1739137705.5276105,47.20995497703552,0.0,1739137705.527612,47.20995497703552,0.6914780660300555,1739137705.5276136,47.20995497703552,3.0659684835699803,1739137705.527615,47.20995497703552,1.6098429913089995 +1739137705.5480516,47.229954957962036,37.929280954874905,1739137705.5480542,47.229954957962036,-0.7464250304229516,1739137705.5480573,47.229954957962036,74.63191010342551,1739137705.5480602,47.229954957962036,31.865691871369528,1739137705.5480616,47.229954957962036,-0.07938308783534183,1739137705.5480635,47.229954957962036,3.032025444938565,1739137705.548065,47.229954957962036,-0.20701850267959065,1739137705.5480664,47.229954957962036,-0.08542781257309744,1739137705.5480678,47.229954957962036,2.301321057339055,1739137705.5480695,47.229954957962036,0.0,1739137705.548071,47.229954957962036,0.6914780660300555,1739137705.5480723,47.229954957962036,3.0659684835699803,1739137705.5480738,47.229954957962036,1.6098429913089995 +1739137705.5704553,47.24995493888855,37.749029521542404,1739137705.570459,47.24995493888855,-0.7310742162935773,1739137705.5704634,47.24995493888855,74.89180786792915,1739137705.5704777,47.24995493888855,31.37710905459935,1739137705.570481,47.24995493888855,-0.07566491448905743,1739137705.5704856,47.24995493888855,3.039094126811656,1739137705.5704892,47.24995493888855,-0.04300234801013261,1739137705.5704927,47.24995493888855,-0.01609784855242291,1739137705.5704963,47.24995493888855,2.4573653809302547,1739137705.5705,47.24995493888855,0.0,1739137705.5705035,47.24995493888855,0.8438449592401726,1739137705.5705073,47.24995493888855,3.045807483802307,1739137705.5705109,47.24995493888855,1.6860761213682132 +1739137705.5899396,47.26995491981506,37.749029521542404,1739137705.5899436,47.26995491981506,-0.7310742162935773,1739137705.5899484,47.26995491981506,74.89180786792915,1739137705.589954,47.26995491981506,31.37710905459935,1739137705.5899568,47.26995491981506,-0.07566491448905743,1739137705.589961,47.26995491981506,3.039094126811656,1739137705.5899646,47.26995491981506,-0.04300234801013261,1739137705.5899682,47.26995491981506,-0.01609784855242291,1739137705.5899718,47.26995491981506,2.4573653809302547,1739137705.5899754,47.26995491981506,0.0,1739137705.589979,47.26995491981506,0.7712892595620415,1739137705.5899827,47.26995491981506,3.045807483802307,1739137705.5899863,47.26995491981506,1.6860761213682132 +1739137705.609422,47.28995490074158,37.749029521542404,1739137705.609425,47.28995490074158,-0.7310742162935773,1739137705.6094296,47.28995490074158,74.89180786792915,1739137705.6094346,47.28995490074158,31.37710905459935,1739137705.6094375,47.28995490074158,-0.07566491448905743,1739137705.609441,47.28995490074158,3.039094126811656,1739137705.6094444,47.28995490074158,-0.04300234801013261,1739137705.6094475,47.28995490074158,-0.01609784855242291,1739137705.6094506,47.28995490074158,2.4573653809302547,1739137705.609454,47.28995490074158,0.0,1739137705.6094568,47.28995490074158,0.7712892595620415,1739137705.6094606,47.28995490074158,3.045807483802307,1739137705.6094635,47.28995490074158,1.6860761213682132 +1739137705.6294491,47.30995488166809,37.749029521542404,1739137705.6294525,47.30995488166809,-0.7310742162935773,1739137705.629457,47.30995488166809,74.89180786792915,1739137705.629462,47.30995488166809,31.37710905459935,1739137705.6294649,47.30995488166809,-0.07566491448905743,1739137705.6294684,47.30995488166809,3.039094126811656,1739137705.6294718,47.30995488166809,-0.04300234801013261,1739137705.629475,47.30995488166809,-0.01609784855242291,1739137705.6294782,47.30995488166809,2.4573653809302547,1739137705.6294816,47.30995488166809,0.0,1739137705.629485,47.30995488166809,0.7712892595620415,1739137705.6294885,47.30995488166809,3.045807483802307,1739137705.6294916,47.30995488166809,1.6860761213682132 +1739137705.6500514,47.329954862594604,37.749029521542404,1739137705.6500545,47.329954862594604,-0.7310742162935773,1739137705.6500583,47.329954862594604,74.89180786792915,1739137705.6500628,47.329954862594604,31.37710905459935,1739137705.6500657,47.329954862594604,-0.07566491448905743,1739137705.650069,47.329954862594604,3.039094126811656,1739137705.650072,47.329954862594604,-0.04300234801013261,1739137705.6500752,47.329954862594604,-0.01609784855242291,1739137705.650078,47.329954862594604,2.4573653809302547,1739137705.650081,47.329954862594604,0.0,1739137705.650084,47.329954862594604,0.7712892595620415,1739137705.6500874,47.329954862594604,3.045807483802307,1739137705.6500902,47.329954862594604,1.6860761213682132 +1739137705.6693819,47.34995484352112,37.749029521542404,1739137705.669387,47.34995484352112,-0.7310742162935773,1739137705.6693914,47.34995484352112,74.89180786792915,1739137705.6693964,47.34995484352112,31.37710905459935,1739137705.669399,47.34995484352112,-0.07566491448905743,1739137705.6694026,47.34995484352112,3.039094126811656,1739137705.6694057,47.34995484352112,-0.04300234801013261,1739137705.6694088,47.34995484352112,-0.01609784855242291,1739137705.669412,47.34995484352112,2.4573653809302547,1739137705.669415,47.34995484352112,0.0,1739137705.669418,47.34995484352112,0.7712892595620415,1739137705.6694212,47.34995484352112,3.045807483802307,1739137705.669424,47.34995484352112,1.6860761213682132 +1739137705.6910274,47.36995482444763,37.560233242573666,1739137705.6910305,47.36995482444763,-0.7112495895353748,1739137705.6910346,47.36995482444763,74.99105950915349,1739137705.6910393,47.36995482444763,31.020094453403157,1739137705.6910417,47.36995482444763,-0.073,1739137705.6910453,47.36995482444763,3.044311091646099,1739137705.6910484,47.36995482444763,0.11552658254066174,1739137705.6910515,47.36995482444763,0.04109183340624993,1739137705.6910543,47.36995482444763,2.387102050014738,1739137705.6910577,47.36995482444763,0.0,1739137705.6910605,47.36995482444763,0.47311183568487125,1739137705.6910641,47.36995482444763,3.0267294643269493,1739137705.6910672,47.36995482444763,1.7720008939346787 +1739137705.7093587,47.389954805374146,37.560233242573666,1739137705.709362,47.389954805374146,-0.7112495895353748,1739137705.7093658,47.389954805374146,74.99105950915349,1739137705.7093706,47.389954805374146,31.020094453403157,1739137705.7093732,47.389954805374146,-0.073,1739137705.7093766,47.389954805374146,3.044311091646099,1739137705.70938,47.389954805374146,0.11552658254066174,1739137705.7093828,47.389954805374146,0.04109183340624993,1739137705.7093856,47.389954805374146,2.387102050014738,1739137705.7093887,47.389954805374146,0.0,1739137705.7093918,47.389954805374146,0.6151011560800594,1739137705.7093954,47.389954805374146,3.0267294643269493,1739137705.7093985,47.389954805374146,1.7720008939346787 +1739137705.7295117,47.40995478630066,37.560233242573666,1739137705.729515,47.40995478630066,-0.7112495895353748,1739137705.7295191,47.40995478630066,74.99105950915349,1739137705.729537,47.40995478630066,31.020094453403157,1739137705.72954,47.40995478630066,-0.073,1739137705.7295434,47.40995478630066,3.044311091646099,1739137705.7295592,47.40995478630066,0.11552658254066174,1739137705.7295623,47.40995478630066,0.04109183340624993,1739137705.7295654,47.40995478630066,2.387102050014738,1739137705.7295685,47.40995478630066,0.0,1739137705.7295716,47.40995478630066,0.6151011560800594,1739137705.7295747,47.40995478630066,3.0267294643269493,1739137705.7295778,47.40995478630066,1.7720008939346787 +1739137705.749313,47.42995476722717,37.560233242573666,1739137705.7493165,47.42995476722717,-0.7112495895353748,1739137705.7493205,47.42995476722717,74.99105950915349,1739137705.7493253,47.42995476722717,31.020094453403157,1739137705.7493281,47.42995476722717,-0.073,1739137705.749332,47.42995476722717,3.044311091646099,1739137705.749335,47.42995476722717,0.11552658254066174,1739137705.7493384,47.42995476722717,0.04109183340624993,1739137705.7493415,47.42995476722717,2.387102050014738,1739137705.7493448,47.42995476722717,0.0,1739137705.749348,47.42995476722717,0.6151011560800594,1739137705.7493515,47.42995476722717,3.0267294643269493,1739137705.7493546,47.42995476722717,1.7720008939346787 +1739137705.7694647,47.44995474815369,37.560233242573666,1739137705.769468,47.44995474815369,-0.7112495895353748,1739137705.7694724,47.44995474815369,74.99105950915349,1739137705.7694771,47.44995474815369,31.020094453403157,1739137705.76948,47.44995474815369,-0.073,1739137705.7694836,47.44995474815369,3.044311091646099,1739137705.7694867,47.44995474815369,0.11552658254066174,1739137705.76949,47.44995474815369,0.04109183340624993,1739137705.769493,47.44995474815369,2.387102050014738,1739137705.7694962,47.44995474815369,0.0,1739137705.7694993,47.44995474815369,0.6151011560800594,1739137705.7695026,47.44995474815369,3.0267294643269493,1739137705.7695057,47.44995474815369,1.7720008939346787 +1739137705.7900114,47.4699547290802,37.36353597517628,1739137705.7900145,47.4699547290802,-0.68689306340457,1739137705.7900183,47.4699547290802,75.17825307664944,1739137705.790023,47.4699547290802,30.634838898883615,1739137705.7900257,47.4699547290802,-0.069,1739137705.7900293,47.4699547290802,3.0500199518132467,1739137705.7900324,47.4699547290802,0.27914201060072313,1739137705.7900355,47.4699547290802,0.09387841936454512,1739137705.7900383,47.4699547290802,2.235877855890759,1739137705.7900417,47.4699547290802,0.0,1739137705.7900448,47.4699547290802,0.200345335088586,1739137705.7900476,47.4699547290802,3.00869671028852,1739137705.7900507,47.4699547290802,1.8380296502401587 +1739137705.8094618,47.489954710006714,37.36353597517628,1739137705.809465,47.489954710006714,-0.68689306340457,1739137705.8094687,47.489954710006714,75.17825307664944,1739137705.8094735,47.489954710006714,30.634838898883615,1739137705.8094761,47.489954710006714,-0.069,1739137705.8094797,47.489954710006714,3.0500199518132467,1739137705.8094828,47.489954710006714,0.27914201060072313,1739137705.8094857,47.489954710006714,0.09387841936454512,1739137705.8094885,47.489954710006714,2.235877855890759,1739137705.8094916,47.489954710006714,0.0,1739137705.8094947,47.489954710006714,0.3978482056506003,1739137705.809498,47.489954710006714,3.00869671028852,1739137705.809501,47.489954710006714,1.8380296502401587 +1739137705.8302348,47.50995469093323,37.36353597517628,1739137705.830238,47.50995469093323,-0.68689306340457,1739137705.8302429,47.50995469093323,75.17825307664944,1739137705.8302479,47.50995469093323,30.634838898883615,1739137705.830251,47.50995469093323,-0.069,1739137705.8302546,47.50995469093323,3.0500199518132467,1739137705.830258,47.50995469093323,0.27914201060072313,1739137705.8302612,47.50995469093323,0.09387841936454512,1739137705.8302648,47.50995469093323,2.235877855890759,1739137705.8302681,47.50995469093323,0.0,1739137705.8302715,47.50995469093323,0.3978482056506003,1739137705.8302748,47.50995469093323,3.00869671028852,1739137705.8302782,47.50995469093323,1.8380296502401587 +1739137705.8502092,47.52995467185974,37.36353597517628,1739137705.8502128,47.52995467185974,-0.68689306340457,1739137705.850217,47.52995467185974,75.17825307664944,1739137705.850222,47.52995467185974,30.634838898883615,1739137705.850225,47.52995467185974,-0.069,1739137705.8502285,47.52995467185974,3.0500199518132467,1739137705.8502316,47.52995467185974,0.27914201060072313,1739137705.850235,47.52995467185974,0.09387841936454512,1739137705.8502378,47.52995467185974,2.235877855890759,1739137705.8502414,47.52995467185974,0.0,1739137705.8502445,47.52995467185974,0.3978482056506003,1739137705.850248,47.52995467185974,3.00869671028852,1739137705.8502514,47.52995467185974,1.8380296502401587 +1739137705.8700058,47.549954652786255,37.36353597517628,1739137705.8700094,47.549954652786255,-0.68689306340457,1739137705.8700135,47.549954652786255,75.17825307664944,1739137705.8700187,47.549954652786255,30.634838898883615,1739137705.8700216,47.549954652786255,-0.069,1739137705.8700252,47.549954652786255,3.0500199518132467,1739137705.8700285,47.549954652786255,0.27914201060072313,1739137705.8700316,47.549954652786255,0.09387841936454512,1739137705.8700347,47.549954652786255,2.235877855890759,1739137705.870038,47.549954652786255,0.0,1739137705.8700414,47.549954652786255,0.3978482056506003,1739137705.8700447,47.549954652786255,3.00869671028852,1739137705.870048,47.549954652786255,1.8380296502401587 +1739137705.890229,47.56995463371277,37.36353597517628,1739137705.8902323,47.56995463371277,-0.68689306340457,1739137705.8902364,47.56995463371277,75.17825307664944,1739137705.8902416,47.56995463371277,30.634838898883615,1739137705.8902442,47.56995463371277,-0.069,1739137705.8902478,47.56995463371277,3.0500199518132467,1739137705.890251,47.56995463371277,0.27914201060072313,1739137705.890254,47.56995463371277,0.09387841936454512,1739137705.8902574,47.56995463371277,2.235877855890759,1739137705.8902605,47.56995463371277,0.0,1739137705.8902638,47.56995463371277,0.3978482056506003,1739137705.8902671,47.56995463371277,3.00869671028852,1739137705.8902702,47.56995463371277,1.8380296502401587 +1739137705.9083188,47.58995461463928,37.16156331356984,1739137705.9083207,47.58995461463928,-0.6582796705741485,1739137705.908323,47.58995461463928,75.45954314417268,1739137705.9083254,47.58995461463928,30.234606242708608,1739137705.9083266,47.58995461463928,-0.06476254877116099,1739137705.9083283,47.58995461463928,3.0561191829425853,1739137705.9083292,47.58995461463928,0.4474424176013889,1739137705.9083304,47.58995461463928,0.14208289180850095,1739137705.9083316,47.58995461463928,2.090312894030234,1739137705.9083328,47.58995461463928,0.0,1739137705.908334,47.58995461463928,0.044244619917510136,1739137705.9083354,47.58995461463928,2.991716112694061,1739137705.9083366,47.58995461463928,1.8776855301252864 +1739137705.9272192,47.609954595565796,37.16156331356984,1739137705.9272215,47.609954595565796,-0.6582796705741485,1739137705.9272242,47.609954595565796,75.45954314417268,1739137705.9272263,47.609954595565796,30.234606242708608,1739137705.9272277,47.609954595565796,-0.06476254877116099,1739137705.9272292,47.609954595565796,3.0561191829425853,1739137705.9272308,47.609954595565796,0.4474424176013889,1739137705.9272318,47.609954595565796,0.14208289180850095,1739137705.927233,47.609954595565796,2.090312894030234,1739137705.9272346,47.609954595565796,0.0,1739137705.9272358,47.609954595565796,0.2126273639049474,1739137705.927237,47.609954595565796,2.991716112694061,1739137705.9272385,47.609954595565796,1.8776855301252864 +1739137705.9478326,47.62995457649231,37.16156331356984,1739137705.9478352,47.62995457649231,-0.6582796705741485,1739137705.947838,47.62995457649231,75.45954314417268,1739137705.9478407,47.62995457649231,30.234606242708608,1739137705.9478421,47.62995457649231,-0.06476254877116099,1739137705.947844,47.62995457649231,3.0561191829425853,1739137705.9478455,47.62995457649231,0.4474424176013889,1739137705.9478467,47.62995457649231,0.14208289180850095,1739137705.9478478,47.62995457649231,2.090312894030234,1739137705.9478495,47.62995457649231,0.0,1739137705.9478507,47.62995457649231,0.2126273639049474,1739137705.9478524,47.62995457649231,2.991716112694061,1739137705.9478536,47.62995457649231,1.8776855301252864 +1739137705.9673445,47.64995455741882,37.16156331356984,1739137705.967347,47.64995455741882,-0.6582796705741485,1739137705.9673495,47.64995455741882,75.45954314417268,1739137705.9673522,47.64995455741882,30.234606242708608,1739137705.9673533,47.64995455741882,-0.06476254877116099,1739137705.9673553,47.64995455741882,3.0561191829425853,1739137705.9673564,47.64995455741882,0.4474424176013889,1739137705.9673576,47.64995455741882,0.14208289180850095,1739137705.967359,47.64995455741882,2.090312894030234,1739137705.9673605,47.64995455741882,0.0,1739137705.9673617,47.64995455741882,0.2126273639049474,1739137705.9673634,47.64995455741882,2.991716112694061,1739137705.9673645,47.64995455741882,1.8776855301252864 +1739137705.996739,47.66995453834534,37.16156331356984,1739137705.9967465,47.66995453834534,-0.6582796705741485,1739137705.9967568,47.66995453834534,75.45954314417268,1739137705.9967668,47.66995453834534,30.234606242708608,1739137705.9967716,47.66995453834534,-0.06476254877116099,1739137705.9967775,47.66995453834534,3.0561191829425853,1739137705.9967825,47.66995453834534,0.4474424176013889,1739137705.9967873,47.66995453834534,0.14208289180850095,1739137705.9967918,47.66995453834534,2.090312894030234,1739137705.996797,47.66995453834534,0.0,1739137705.9968019,47.66995453834534,0.2126273639049474,1739137705.9968069,47.66995453834534,2.991716112694061,1739137705.9968116,47.66995453834534,1.8776855301252864 +1739137706.0124767,47.68995451927185,36.95651831688222,1739137706.0124843,47.68995451927185,-0.6257753936346457,1739137706.012494,47.68995451927185,75.57075255516462,1739137706.0125036,47.68995451927185,30.05816458159377,1739137706.012508,47.68995451927185,-0.0633888727255331,1739137706.0125139,47.68995451927185,3.06024780514786,1739137706.0125186,47.68995451927185,0.5837911277950892,1739137706.012523,47.68995451927185,0.18694688130557097,1739137706.0125277,47.68995451927185,1.97936142637431,1739137706.0125327,47.68995451927185,0.0,1739137706.0125377,47.68995451927185,-0.04070402413910959,1739137706.012543,47.68995451927185,2.975799701928147,1739137706.0125475,47.68995451927185,1.899431395944745 +1739137706.0336587,47.709954500198364,36.95651831688222,1739137706.0336666,47.709954500198364,-0.6257753936346457,1739137706.0336757,47.709954500198364,75.57075255516462,1739137706.0336852,47.709954500198364,30.05816458159377,1739137706.0336897,47.709954500198364,-0.0633888727255331,1739137706.0336957,47.709954500198364,3.06024780514786,1739137706.0337007,47.709954500198364,0.5837911277950892,1739137706.033705,47.709954500198364,0.18694688130557097,1739137706.0337093,47.709954500198364,1.97936142637431,1739137706.0337148,47.709954500198364,0.0,1739137706.0337195,47.709954500198364,0.07993003042956492,1739137706.0337248,47.709954500198364,2.975799701928147,1739137706.0337293,47.709954500198364,1.899431395944745 +1739137706.0681713,47.72995448112488,36.95651831688222,1739137706.0681796,47.72995448112488,-0.6257753936346457,1739137706.0681891,47.72995448112488,75.57075255516462,1739137706.0681987,47.72995448112488,30.05816458159377,1739137706.0682034,47.72995448112488,-0.0633888727255331,1739137706.0682096,47.72995448112488,3.06024780514786,1739137706.0682151,47.72995448112488,0.5837911277950892,1739137706.0682197,47.72995448112488,0.18694688130557097,1739137706.0682242,47.72995448112488,1.97936142637431,1739137706.0682297,47.72995448112488,0.0,1739137706.0682344,47.72995448112488,0.07993003042956492,1739137706.0682397,47.72995448112488,2.975799701928147,1739137706.068244,47.72995448112488,1.899431395944745 +1739137706.0835273,47.75995445251465,36.95651831688222,1739137706.0835354,47.75995445251465,-0.6257753936346457,1739137706.0835447,47.75995445251465,75.57075255516462,1739137706.083554,47.75995445251465,30.05816458159377,1739137706.0835593,47.75995445251465,-0.0633888727255331,1739137706.0835648,47.75995445251465,3.06024780514786,1739137706.08357,47.75995445251465,0.5837911277950892,1739137706.0835748,47.75995445251465,0.18694688130557097,1739137706.0835793,47.75995445251465,1.97936142637431,1739137706.0835848,47.75995445251465,0.0,1739137706.0835896,47.75995445251465,0.07993003042956492,1739137706.083595,47.75995445251465,2.975799701928147,1739137706.0835998,47.75995445251465,1.899431395944745 +1739137706.1172245,47.78995442390442,36.95651831688222,1739137706.1172283,47.78995442390442,-0.6257753936346457,1739137706.1172328,47.78995442390442,75.57075255516462,1739137706.1172373,47.78995442390442,30.05816458159377,1739137706.1172392,47.78995442390442,-0.0633888727255331,1739137706.1172419,47.78995442390442,3.06024780514786,1739137706.117244,47.78995442390442,0.5837911277950892,1739137706.117246,47.78995442390442,0.18694688130557097,1739137706.117248,47.78995442390442,1.97936142637431,1739137706.1172502,47.78995442390442,0.0,1739137706.1172526,47.78995442390442,0.07993003042956492,1739137706.117255,47.78995442390442,2.975799701928147,1739137706.1172566,47.78995442390442,1.899431395944745 +1739137706.136086,47.81995439529419,36.75048136864282,1739137706.136089,47.81995439529419,-0.5898493865783552,1739137706.136093,47.81995439529419,75.77446266627527,1739137706.1360958,47.81995439529419,29.835377950773548,1739137706.1360972,47.81995439529419,-0.06164077126593345,1739137706.1360996,47.81995439529419,3.065355920223009,1739137706.136101,47.81995439529419,0.7226732603658109,1739137706.1361024,47.81995439529419,0.23033223703506528,1739137706.1361036,47.81995439529419,1.8724007438748071,1739137706.1361058,47.81995439529419,0.0,1739137706.1361072,47.81995439529419,-0.13641170232584,1739137706.1361089,47.81995439529419,2.9609634659316173,1739137706.13611,47.81995439529419,1.905792521997025 +1739137706.155381,47.8399543762207,36.75048136864282,1739137706.1553836,47.8399543762207,-0.5898493865783552,1739137706.1553862,47.8399543762207,75.77446266627527,1739137706.1553886,47.8399543762207,29.835377950773548,1739137706.1553898,47.8399543762207,-0.06164077126593345,1739137706.1553915,47.8399543762207,3.065355920223009,1739137706.155393,47.8399543762207,0.7226732603658109,1739137706.155394,47.8399543762207,0.23033223703506528,1739137706.1553953,47.8399543762207,1.8724007438748071,1739137706.1553967,47.8399543762207,0.0,1739137706.155398,47.8399543762207,-0.03339177812221794,1739137706.1553993,47.8399543762207,2.9609634659316173,1739137706.1554008,47.8399543762207,1.905792521997025 +1739137706.175272,47.85995435714722,36.75048136864282,1739137706.1752741,47.85995435714722,-0.5898493865783552,1739137706.1752768,47.85995435714722,75.77446266627527,1739137706.1752796,47.85995435714722,29.835377950773548,1739137706.1752806,47.85995435714722,-0.06164077126593345,1739137706.1752822,47.85995435714722,3.065355920223009,1739137706.1752927,47.85995435714722,0.7226732603658109,1739137706.175294,47.85995435714722,0.23033223703506528,1739137706.175295,47.85995435714722,1.8724007438748071,1739137706.1752968,47.85995435714722,0.0,1739137706.175298,47.85995435714722,-0.03339177812221794,1739137706.1752996,47.85995435714722,2.9609634659316173,1739137706.1753008,47.85995435714722,1.905792521997025 +1739137706.195348,47.87995433807373,36.75048136864282,1739137706.1953506,47.87995433807373,-0.5898493865783552,1739137706.195353,47.87995433807373,75.77446266627527,1739137706.1953557,47.87995433807373,29.835377950773548,1739137706.1953568,47.87995433807373,-0.06164077126593345,1739137706.1953588,47.87995433807373,3.065355920223009,1739137706.19536,47.87995433807373,0.7226732603658109,1739137706.1953614,47.87995433807373,0.23033223703506528,1739137706.195363,47.87995433807373,1.8724007438748071,1739137706.1953647,47.87995433807373,0.0,1739137706.195366,47.87995433807373,-0.03339177812221794,1739137706.1953673,47.87995433807373,2.9609634659316173,1739137706.1953688,47.87995433807373,1.905792521997025 +1739137706.2161467,47.899954319000244,36.75048136864282,1739137706.216149,47.899954319000244,-0.5898493865783552,1739137706.2161515,47.899954319000244,75.77446266627527,1739137706.216154,47.899954319000244,29.835377950773548,1739137706.2161553,47.899954319000244,-0.06164077126593345,1739137706.216157,47.899954319000244,3.065355920223009,1739137706.2161582,47.899954319000244,0.7226732603658109,1739137706.2161596,47.899954319000244,0.23033223703506528,1739137706.2161605,47.899954319000244,1.8724007438748071,1739137706.216162,47.899954319000244,0.0,1739137706.2161634,47.899954319000244,-0.03339177812221794,1739137706.2161648,47.899954319000244,2.9609634659316173,1739137706.2161658,47.899954319000244,1.905792521997025 +1739137706.2355301,47.91995429992676,36.544620861741905,1739137706.2355328,47.91995429992676,-0.5509056910771699,1739137706.2355356,47.91995429992676,75.9826094080336,1739137706.2355382,47.91995429992676,29.63764917805933,1739137706.2355394,47.91995429992676,-0.05932978967736696,1739137706.235541,47.91995429992676,3.0705414834216094,1739137706.2355425,47.91995429992676,0.8517932137669234,1739137706.2355437,47.91995429992676,0.27212119781795757,1739137706.235545,47.91995429992676,1.7781499082113839,1739137706.2355464,47.91995429992676,0.0,1739137706.2355475,47.91995429992676,-0.20670577602048062,1739137706.2355492,47.91995429992676,2.947216579995698,1739137706.2355502,47.91995429992676,1.902325167814617 +1739137706.2561398,47.93995428085327,36.544620861741905,1739137706.2561421,47.93995428085327,-0.5509056910771699,1739137706.2561445,47.93995428085327,75.9826094080336,1739137706.2561471,47.93995428085327,29.63764917805933,1739137706.2561486,47.93995428085327,-0.05932978967736696,1739137706.25615,47.93995428085327,3.0705414834216094,1739137706.2561514,47.93995428085327,0.8517932137669234,1739137706.2561529,47.93995428085327,0.27212119781795757,1739137706.2561538,47.93995428085327,1.7781499082113839,1739137706.2561557,47.93995428085327,0.0,1739137706.2561567,47.93995428085327,-0.12417525960323306,1739137706.256158,47.93995428085327,2.947216579995698,1739137706.2561595,47.93995428085327,1.902325167814617 +1739137706.2753987,47.959954261779785,36.544620861741905,1739137706.2754018,47.959954261779785,-0.5509056910771699,1739137706.2754042,47.959954261779785,75.9826094080336,1739137706.275407,47.959954261779785,29.63764917805933,1739137706.2754083,47.959954261779785,-0.05932978967736696,1739137706.27541,47.959954261779785,3.0705414834216094,1739137706.2754111,47.959954261779785,0.8517932137669234,1739137706.2754128,47.959954261779785,0.27212119781795757,1739137706.2754138,47.959954261779785,1.7781499082113839,1739137706.275415,47.959954261779785,0.0,1739137706.2754164,47.959954261779785,-0.12417525960323306,1739137706.2754178,47.959954261779785,2.947216579995698,1739137706.2754192,47.959954261779785,1.902325167814617 +1739137706.2952526,47.9799542427063,36.544620861741905,1739137706.2952547,47.9799542427063,-0.5509056910771699,1739137706.2952573,47.9799542427063,75.9826094080336,1739137706.2952602,47.9799542427063,29.63764917805933,1739137706.2952614,47.9799542427063,-0.05932978967736696,1739137706.2952633,47.9799542427063,3.0705414834216094,1739137706.2952645,47.9799542427063,0.8517932137669234,1739137706.2952657,47.9799542427063,0.27212119781795757,1739137706.295267,47.9799542427063,1.7781499082113839,1739137706.2952685,47.9799542427063,0.0,1739137706.29527,47.9799542427063,-0.12417525960323306,1739137706.2952714,47.9799542427063,2.947216579995698,1739137706.2952726,47.9799542427063,1.902325167814617 +1739137706.3151994,47.99995422363281,36.544620861741905,1739137706.3152015,47.99995422363281,-0.5509056910771699,1739137706.3152044,47.99995422363281,75.9826094080336,1739137706.315207,47.99995422363281,29.63764917805933,1739137706.3152082,47.99995422363281,-0.05932978967736696,1739137706.3152096,47.99995422363281,3.0705414834216094,1739137706.3152113,47.99995422363281,0.8517932137669234,1739137706.3152125,47.99995422363281,0.27212119781795757,1739137706.315214,47.99995422363281,1.7781499082113839,1739137706.3152153,47.99995422363281,0.0,1739137706.3152165,47.99995422363281,-0.12417525960323306,1739137706.3152182,47.99995422363281,2.947216579995698,1739137706.3152194,47.99995422363281,1.902325167814617 +1739137706.3354058,48.019954204559326,36.34026190139196,1739137706.335408,48.019954204559326,-0.5094362045404557,1739137706.3354106,48.019954204559326,76.32459896274156,1739137706.335413,48.019954204559326,29.33867230275624,1739137706.3354142,48.019954204559326,-0.057441847945303215,1739137706.3354158,48.019954204559326,3.077126145765038,1739137706.335417,48.019954204559326,0.996777553509138,1739137706.3354185,48.019954204559326,0.309914036277275,1739137706.3354197,48.019954204559326,1.6779615783098478,1739137706.3354208,48.019954204559326,0.0,1739137706.3354223,48.019954204559326,-0.2880775833932793,1739137706.3354237,48.019954204559326,2.934575105754685,1739137706.3354247,48.019954204559326,1.8879903971000516 +1739137706.355148,48.03995418548584,36.34026190139196,1739137706.35515,48.03995418548584,-0.5094362045404557,1739137706.3551528,48.03995418548584,76.32459896274156,1739137706.3551555,48.03995418548584,29.33867230275624,1739137706.3551567,48.03995418548584,-0.057441847945303215,1739137706.3551583,48.03995418548584,3.077126145765038,1739137706.3551598,48.03995418548584,0.996777553509138,1739137706.3551612,48.03995418548584,0.309914036277275,1739137706.3551624,48.03995418548584,1.6779615783098478,1739137706.3551636,48.03995418548584,0.0,1739137706.3551655,48.03995418548584,-0.21002881879020374,1739137706.3551667,48.03995418548584,2.934575105754685,1739137706.355168,48.03995418548584,1.8879903971000516 +1739137706.3752308,48.05995416641235,36.34026190139196,1739137706.3752332,48.05995416641235,-0.5094362045404557,1739137706.375236,48.05995416641235,76.32459896274156,1739137706.375239,48.05995416641235,29.33867230275624,1739137706.3752406,48.05995416641235,-0.057441847945303215,1739137706.3752425,48.05995416641235,3.077126145765038,1739137706.3752437,48.05995416641235,0.996777553509138,1739137706.3752453,48.05995416641235,0.309914036277275,1739137706.3752465,48.05995416641235,1.6779615783098478,1739137706.3752482,48.05995416641235,0.0,1739137706.3752494,48.05995416641235,-0.21002881879020374,1739137706.375251,48.05995416641235,2.934575105754685,1739137706.3752522,48.05995416641235,1.8879903971000516 +1739137706.3955953,48.07995414733887,36.34026190139196,1739137706.3955986,48.07995414733887,-0.5094362045404557,1739137706.3956022,48.07995414733887,76.32459896274156,1739137706.3956053,48.07995414733887,29.33867230275624,1739137706.3956065,48.07995414733887,-0.057441847945303215,1739137706.3956087,48.07995414733887,3.077126145765038,1739137706.39561,48.07995414733887,0.996777553509138,1739137706.395612,48.07995414733887,0.309914036277275,1739137706.3956134,48.07995414733887,1.6779615783098478,1739137706.3956153,48.07995414733887,0.0,1739137706.3956168,48.07995414733887,-0.21002881879020374,1739137706.3956187,48.07995414733887,2.934575105754685,1739137706.39562,48.07995414733887,1.8879903971000516 +1739137706.4154313,48.09995412826538,36.34026190139196,1739137706.4154336,48.09995412826538,-0.5094362045404557,1739137706.4154367,48.09995412826538,76.32459896274156,1739137706.41544,48.09995412826538,29.33867230275624,1739137706.4154418,48.09995412826538,-0.057441847945303215,1739137706.4154434,48.09995412826538,3.077126145765038,1739137706.4154453,48.09995412826538,0.996777553509138,1739137706.4154468,48.09995412826538,0.309914036277275,1739137706.4154484,48.09995412826538,1.6779615783098478,1739137706.4154499,48.09995412826538,0.0,1739137706.4154513,48.09995412826538,-0.21002881879020374,1739137706.4154532,48.09995412826538,2.934575105754685,1739137706.4154546,48.09995412826538,1.8879903971000516 +1739137706.4355989,48.119954109191895,36.34026190139196,1739137706.435602,48.119954109191895,-0.5094362045404557,1739137706.4356055,48.119954109191895,76.32459896274156,1739137706.4356089,48.119954109191895,29.33867230275624,1739137706.4356105,48.119954109191895,-0.057441847945303215,1739137706.4356124,48.119954109191895,3.077126145765038,1739137706.4356139,48.119954109191895,0.996777553509138,1739137706.4356155,48.119954109191895,0.309914036277275,1739137706.435617,48.119954109191895,1.6779615783098478,1739137706.4356189,48.119954109191895,0.0,1739137706.4356203,48.119954109191895,-0.21002881879020374,1739137706.4356222,48.119954109191895,2.934575105754685,1739137706.435624,48.119954109191895,1.8879903971000516 +1739137706.4554534,48.13995409011841,36.138596526190945,1739137706.455456,48.13995409011841,-0.4659603994460362,1739137706.4554594,48.13995409011841,76.32879045981569,1739137706.4554625,48.13995409011841,29.41062754577627,1739137706.455464,48.13995409011841,-0.05786761861406077,1739137706.4554663,48.13995409011841,3.0810107152632034,1739137706.4554677,48.13995409011841,1.0602423679620685,1739137706.4554694,48.13995409011841,0.3567626866196879,1739137706.4554706,48.13995409011841,1.6359011010777742,1739137706.4554725,48.13995409011841,0.0,1739137706.4554741,48.13995409011841,-0.24186828993637882,1739137706.4554758,48.13995409011841,2.923056532845705,1739137706.4554772,48.13995409011841,1.8626077305134912 +1739137706.4755318,48.15995407104492,36.138596526190945,1739137706.4755344,48.15995407104492,-0.4659603994460362,1739137706.4755378,48.15995407104492,76.32879045981569,1739137706.4755406,48.15995407104492,29.41062754577627,1739137706.4755423,48.15995407104492,-0.05786761861406077,1739137706.4755442,48.15995407104492,3.0810107152632034,1739137706.475546,48.15995407104492,1.0602423679620685,1739137706.4755473,48.15995407104492,0.3567626866196879,1739137706.4755492,48.15995407104492,1.6359011010777742,1739137706.475551,48.15995407104492,0.0,1739137706.4755526,48.15995407104492,-0.22670662943571696,1739137706.475554,48.15995407104492,2.923056532845705,1739137706.4755557,48.15995407104492,1.8626077305134912 +1739137706.4957254,48.179954051971436,36.138596526190945,1739137706.4957287,48.179954051971436,-0.4659603994460362,1739137706.4957318,48.179954051971436,76.32879045981569,1739137706.4957347,48.179954051971436,29.41062754577627,1739137706.4957361,48.179954051971436,-0.05786761861406077,1739137706.495738,48.179954051971436,3.0810107152632034,1739137706.4957397,48.179954051971436,1.0602423679620685,1739137706.4957411,48.179954051971436,0.3567626866196879,1739137706.4957428,48.179954051971436,1.6359011010777742,1739137706.4957445,48.179954051971436,0.0,1739137706.4957461,48.179954051971436,-0.22670662943571696,1739137706.4957478,48.179954051971436,2.923056532845705,1739137706.4957495,48.179954051971436,1.8626077305134912 +1739137706.515618,48.19995403289795,36.138596526190945,1739137706.515621,48.19995403289795,-0.4659603994460362,1739137706.5156243,48.19995403289795,76.32879045981569,1739137706.5156276,48.19995403289795,29.41062754577627,1739137706.5156293,48.19995403289795,-0.05786761861406077,1739137706.5156317,48.19995403289795,3.0810107152632034,1739137706.5156333,48.19995403289795,1.0602423679620685,1739137706.515635,48.19995403289795,0.3567626866196879,1739137706.5156367,48.19995403289795,1.6359011010777742,1739137706.5156386,48.19995403289795,0.0,1739137706.5156403,48.19995403289795,-0.22670662943571696,1739137706.5156422,48.19995403289795,2.923056532845705,1739137706.5156436,48.19995403289795,1.8626077305134912 +1739137706.5364957,48.21995401382446,36.138596526190945,1739137706.536499,48.21995401382446,-0.4659603994460362,1739137706.5365028,48.21995401382446,76.32879045981569,1739137706.5365067,48.21995401382446,29.41062754577627,1739137706.5365086,48.21995401382446,-0.05786761861406077,1739137706.536511,48.21995401382446,3.0810107152632034,1739137706.5365133,48.21995401382446,1.0602423679620685,1739137706.536515,48.21995401382446,0.3567626866196879,1739137706.536517,48.21995401382446,1.6359011010777742,1739137706.5365188,48.21995401382446,0.0,1739137706.5365207,48.21995401382446,-0.22670662943571696,1739137706.536523,48.21995401382446,2.923056532845705,1739137706.5365248,48.21995401382446,1.8626077305134912 +1739137706.556094,48.23995399475098,35.94016066231619,1739137706.5560973,48.23995399475098,-0.4208904222414027,1739137706.5561013,48.23995399475098,76.6224551928068,1739137706.5561051,48.23995399475098,29.196916217617023,1739137706.5561073,48.23995399475098,-0.05644096848014187,1739137706.55611,48.23995399475098,3.087598582810924,1739137706.5561118,48.23995399475098,1.1752513026115219,1739137706.556114,48.23995399475098,0.39356448884439477,1739137706.5561156,48.23995399475098,1.5623486138984148,1739137706.556118,48.23995399475098,0.0,1739137706.55612,48.23995399475098,-0.3162487310106452,1739137706.556122,48.23995399475098,2.912676162614875,1739137706.5561242,48.23995399475098,1.835958227620897 +1739137706.5761623,48.25995397567749,35.94016066231619,1739137706.576166,48.25995397567749,-0.4208904222414027,1739137706.5761697,48.25995397567749,76.6224551928068,1739137706.5761733,48.25995397567749,29.196916217617023,1739137706.5761755,48.25995397567749,-0.05644096848014187,1739137706.5761778,48.25995397567749,3.087598582810924,1739137706.5761797,48.25995397567749,1.1752513026115219,1739137706.5761814,48.25995397567749,0.39356448884439477,1739137706.5761833,48.25995397567749,1.5623486138984148,1739137706.5761857,48.25995397567749,0.0,1739137706.5761876,48.25995397567749,-0.27360961372248216,1739137706.5761898,48.25995397567749,2.912676162614875,1739137706.5761914,48.25995397567749,1.835958227620897 +1739137706.5960057,48.279953956604004,35.94016066231619,1739137706.596009,48.279953956604004,-0.4208904222414027,1739137706.5960126,48.279953956604004,76.6224551928068,1739137706.5960166,48.279953956604004,29.196916217617023,1739137706.5960183,48.279953956604004,-0.05644096848014187,1739137706.596021,48.279953956604004,3.087598582810924,1739137706.596023,48.279953956604004,1.1752513026115219,1739137706.596025,48.279953956604004,0.39356448884439477,1739137706.596027,48.279953956604004,1.5623486138984148,1739137706.596029,48.279953956604004,0.0,1739137706.5960307,48.279953956604004,-0.27360961372248216,1739137706.5960329,48.279953956604004,2.912676162614875,1739137706.5960348,48.279953956604004,1.835958227620897 +1739137706.6160927,48.29995393753052,35.94016066231619,1739137706.6160963,48.29995393753052,-0.4208904222414027,1739137706.6161003,48.29995393753052,76.6224551928068,1739137706.6161044,48.29995393753052,29.196916217617023,1739137706.6161063,48.29995393753052,-0.05644096848014187,1739137706.6161091,48.29995393753052,3.087598582810924,1739137706.616111,48.29995393753052,1.1752513026115219,1739137706.6161132,48.29995393753052,0.39356448884439477,1739137706.616115,48.29995393753052,1.5623486138984148,1739137706.6161172,48.29995393753052,0.0,1739137706.6161191,48.29995393753052,-0.27360961372248216,1739137706.616121,48.29995393753052,2.912676162614875,1739137706.616123,48.29995393753052,1.835958227620897 +1739137706.6361322,48.31995391845703,35.94016066231619,1739137706.6361356,48.31995391845703,-0.4208904222414027,1739137706.6361396,48.31995391845703,76.6224551928068,1739137706.6361434,48.31995391845703,29.196916217617023,1739137706.6361454,48.31995391845703,-0.05644096848014187,1739137706.6361477,48.31995391845703,3.087598582810924,1739137706.6361496,48.31995391845703,1.1752513026115219,1739137706.6361516,48.31995391845703,0.39356448884439477,1739137706.6361535,48.31995391845703,1.5623486138984148,1739137706.6361554,48.31995391845703,0.0,1739137706.6361575,48.31995391845703,-0.27360961372248216,1739137706.6361594,48.31995391845703,2.912676162614875,1739137706.6361613,48.31995391845703,1.835958227620897 +1739137706.6562216,48.339953899383545,35.94016066231619,1739137706.6562254,48.339953899383545,-0.4208904222414027,1739137706.6562302,48.339953899383545,76.6224551928068,1739137706.6562343,48.339953899383545,29.196916217617023,1739137706.6562362,48.339953899383545,-0.05644096848014187,1739137706.6562388,48.339953899383545,3.087598582810924,1739137706.656241,48.339953899383545,1.1752513026115219,1739137706.6562428,48.339953899383545,0.39356448884439477,1739137706.6562448,48.339953899383545,1.5623486138984148,1739137706.656247,48.339953899383545,0.0,1739137706.6562488,48.339953899383545,-0.27360961372248216,1739137706.6562512,48.339953899383545,2.912676162614875,1739137706.6562529,48.339953899383545,1.835958227620897 +1739137706.6766355,48.35995388031006,35.745409282020645,1739137706.6766396,48.35995388031006,-0.3746351468227678,1739137706.6766443,48.35995388031006,76.7427515960196,1739137706.6766484,48.35995388031006,29.183573708331153,1739137706.6766508,48.35995388031006,-0.05632978090275962,1739137706.6766534,48.35995388031006,3.0931220621004245,1739137706.6766553,48.35995388031006,1.2385542320818175,1739137706.6766572,48.35995388031006,0.4376615487080969,1739137706.6766589,48.35995388031006,1.5232847745111802,1739137706.6766613,48.35995388031006,0.0,1739137706.6766634,48.35995388031006,-0.28012476327740654,1739137706.6766655,48.35995388031006,2.9034574812803062,1739137706.676668,48.35995388031006,1.800307084069764 +1739137706.696952,48.37995386123657,35.745409282020645,1739137706.6969554,48.37995386123657,-0.3746351468227678,1739137706.6969595,48.37995386123657,76.7427515960196,1739137706.6969633,48.37995386123657,29.183573708331153,1739137706.6969655,48.37995386123657,-0.05632978090275962,1739137706.6969676,48.37995386123657,3.0931220621004245,1739137706.6969697,48.37995386123657,1.2385542320818175,1739137706.6969714,48.37995386123657,0.4376615487080969,1739137706.6969733,48.37995386123657,1.5232847745111802,1739137706.6969757,48.37995386123657,0.0,1739137706.6969774,48.37995386123657,-0.27702230955858376,1739137706.6969795,48.37995386123657,2.9034574812803062,1739137706.6969812,48.37995386123657,1.800307084069764 +1739137706.7158484,48.399953842163086,35.745409282020645,1739137706.715851,48.399953842163086,-0.3746351468227678,1739137706.715854,48.399953842163086,76.7427515960196,1739137706.7158568,48.399953842163086,29.183573708331153,1739137706.7158585,48.399953842163086,-0.05632978090275962,1739137706.7158601,48.399953842163086,3.0931220621004245,1739137706.7158618,48.399953842163086,1.2385542320818175,1739137706.7158632,48.399953842163086,0.4376615487080969,1739137706.7158647,48.399953842163086,1.5232847745111802,1739137706.715866,48.399953842163086,0.0,1739137706.7158678,48.399953842163086,-0.27702230955858376,1739137706.7158694,48.399953842163086,2.9034574812803062,1739137706.7158706,48.399953842163086,1.800307084069764 +1739137706.7354572,48.4199538230896,35.745409282020645,1739137706.7354608,48.4199538230896,-0.3746351468227678,1739137706.7354643,48.4199538230896,76.7427515960196,1739137706.7354672,48.4199538230896,29.183573708331153,1739137706.7354689,48.4199538230896,-0.05632978090275962,1739137706.7354703,48.4199538230896,3.0931220621004245,1739137706.7354722,48.4199538230896,1.2385542320818175,1739137706.7354734,48.4199538230896,0.4376615487080969,1739137706.7354746,48.4199538230896,1.5232847745111802,1739137706.7354765,48.4199538230896,0.0,1739137706.7354777,48.4199538230896,-0.27702230955858376,1739137706.7354796,48.4199538230896,2.9034574812803062,1739137706.735481,48.4199538230896,1.800307084069764 +1739137706.755393,48.43995380401611,35.745409282020645,1739137706.755396,48.43995380401611,-0.3746351468227678,1739137706.7553988,48.43995380401611,76.7427515960196,1739137706.7554014,48.43995380401611,29.183573708331153,1739137706.7554028,48.43995380401611,-0.05632978090275962,1739137706.7554042,48.43995380401611,3.0931220621004245,1739137706.755406,48.43995380401611,1.2385542320818175,1739137706.755407,48.43995380401611,0.4376615487080969,1739137706.755408,48.43995380401611,1.5232847745111802,1739137706.7554097,48.43995380401611,0.0,1739137706.755411,48.43995380401611,-0.27702230955858376,1739137706.7554126,48.43995380401611,2.9034574812803062,1739137706.7554135,48.43995380401611,1.800307084069764 +1739137706.7754412,48.45995378494263,35.55485794703115,1739137706.7754438,48.45995378494263,-0.3276252789657912,1739137706.7754464,48.45995378494263,76.88196929354217,1739137706.7754493,48.45995378494263,29.150302695669318,1739137706.7754507,48.45995378494263,-0.05605252246391101,1739137706.7754521,48.45995378494263,3.0992149775721383,1739137706.7754533,48.45995378494263,1.2973696348909396,1739137706.7754548,48.45995378494263,0.4807908298855627,1739137706.775456,48.45995378494263,1.4878659989962908,1739137706.7754576,48.45995378494263,0.0,1739137706.7754588,48.45995378494263,-0.27722008949854887,1739137706.77546,48.45995378494263,2.8954192487018013,1739137706.7754614,48.45995378494263,1.7649919075239993 +1739137706.7953207,48.47995376586914,35.55485794703115,1739137706.7953238,48.47995376586914,-0.3276252789657912,1739137706.7953265,48.47995376586914,76.88196929354217,1739137706.7953293,48.47995376586914,29.150302695669318,1739137706.7953308,48.47995376586914,-0.05605252246391101,1739137706.7953324,48.47995376586914,3.0992149775721383,1739137706.7953339,48.47995376586914,1.2973696348909396,1739137706.795335,48.47995376586914,0.4807908298855627,1739137706.7953365,48.47995376586914,1.4878659989962908,1739137706.7953382,48.47995376586914,0.0,1739137706.7953393,48.47995376586914,-0.27712590852770846,1739137706.7953408,48.47995376586914,2.8954192487018013,1739137706.7953424,48.47995376586914,1.7649919075239993 +1739137706.8153965,48.499953746795654,35.55485794703115,1739137706.8153994,48.499953746795654,-0.3276252789657912,1739137706.8154023,48.499953746795654,76.88196929354217,1739137706.815405,48.499953746795654,29.150302695669318,1739137706.815406,48.499953746795654,-0.05605252246391101,1739137706.8154075,48.499953746795654,3.0992149775721383,1739137706.815409,48.499953746795654,1.2973696348909396,1739137706.8154101,48.499953746795654,0.4807908298855627,1739137706.8154116,48.499953746795654,1.4878659989962908,1739137706.815413,48.499953746795654,0.0,1739137706.8154142,48.499953746795654,-0.27712590852770846,1739137706.8154159,48.499953746795654,2.8954192487018013,1739137706.815417,48.499953746795654,1.7649919075239993 +1739137706.8354716,48.51995372772217,35.55485794703115,1739137706.8354745,48.51995372772217,-0.3276252789657912,1739137706.8354778,48.51995372772217,76.88196929354217,1739137706.8354802,48.51995372772217,29.150302695669318,1739137706.835482,48.51995372772217,-0.05605252246391101,1739137706.8354836,48.51995372772217,3.0992149775721383,1739137706.835485,48.51995372772217,1.2973696348909396,1739137706.8354862,48.51995372772217,0.4807908298855627,1739137706.8354876,48.51995372772217,1.4878659989962908,1739137706.835489,48.51995372772217,0.0,1739137706.8354902,48.51995372772217,-0.27712590852770846,1739137706.8354924,48.51995372772217,2.8954192487018013,1739137706.8354933,48.51995372772217,1.7649919075239993 +1739137706.8553152,48.53995370864868,35.55485794703115,1739137706.855318,48.53995370864868,-0.3276252789657912,1739137706.8553212,48.53995370864868,76.88196929354217,1739137706.8553238,48.53995370864868,29.150302695669318,1739137706.8553252,48.53995370864868,-0.05605252246391101,1739137706.855327,48.53995370864868,3.0992149775721383,1739137706.8553286,48.53995370864868,1.2973696348909396,1739137706.8553298,48.53995370864868,0.4807908298855627,1739137706.8553312,48.53995370864868,1.4878659989962908,1739137706.8553326,48.53995370864868,0.0,1739137706.8553338,48.53995370864868,-0.27712590852770846,1739137706.8553355,48.53995370864868,2.8954192487018013,1739137706.8553367,48.53995370864868,1.7649919075239993 +1739137706.87522,48.559953689575195,35.55485794703115,1739137706.8752222,48.559953689575195,-0.3276252789657912,1739137706.875225,48.559953689575195,76.88196929354217,1739137706.8752277,48.559953689575195,29.150302695669318,1739137706.875229,48.559953689575195,-0.05605252246391101,1739137706.8752306,48.559953689575195,3.0992149775721383,1739137706.8752317,48.559953689575195,1.2973696348909396,1739137706.875233,48.559953689575195,0.4807908298855627,1739137706.8752344,48.559953689575195,1.4878659989962908,1739137706.8752356,48.559953689575195,0.0,1739137706.8752367,48.559953689575195,-0.27712590852770846,1739137706.8752384,48.559953689575195,2.8954192487018013,1739137706.8752396,48.559953689575195,1.7649919075239993 +1739137706.8953872,48.57995367050171,35.36841247896322,1739137706.8953898,48.57995367050171,-0.2801436816252929,1739137706.8953924,48.57995367050171,77.18550241620105,1739137706.8953953,48.57995367050171,28.951731961121826,1739137706.8953967,48.57995367050171,-0.05437377744548569,1739137706.8953984,48.57995367050171,3.1064223179323234,1739137706.8953996,48.57995367050171,1.3875772138270615,1739137706.895401,48.57995367050171,0.5119708576295612,1739137706.8954022,48.57995367050171,1.4351363273593072,1739137706.8954039,48.57995367050171,0.0,1739137706.895405,48.57995367050171,-0.3110019296875211,1739137706.8954065,48.57995367050171,2.888592122842486,1739137706.895408,48.57995367050171,1.730006810340936 +1739137706.9153247,48.59995365142822,35.36841247896322,1739137706.9153275,48.59995365142822,-0.2801436816252929,1739137706.9153304,48.59995365142822,77.18550241620105,1739137706.9153328,48.59995365142822,28.951731961121826,1739137706.9153342,48.59995365142822,-0.05437377744548569,1739137706.915336,48.59995365142822,3.1064223179323234,1739137706.9153376,48.59995365142822,1.3875772138270615,1739137706.9153388,48.59995365142822,0.5119708576295612,1739137706.91534,48.59995365142822,1.4351363273593072,1739137706.9153416,48.59995365142822,0.0,1739137706.9153428,48.59995365142822,-0.2948704829816289,1739137706.9153442,48.59995365142822,2.888592122842486,1739137706.9153454,48.59995365142822,1.730006810340936 +1739137706.9353445,48.619953632354736,35.36841247896322,1739137706.9353476,48.619953632354736,-0.2801436816252929,1739137706.9353504,48.619953632354736,77.18550241620105,1739137706.9353533,48.619953632354736,28.951731961121826,1739137706.9353547,48.619953632354736,-0.05437377744548569,1739137706.9353564,48.619953632354736,3.1064223179323234,1739137706.935358,48.619953632354736,1.3875772138270615,1739137706.9353597,48.619953632354736,0.5119708576295612,1739137706.935361,48.619953632354736,1.4351363273593072,1739137706.9353623,48.619953632354736,0.0,1739137706.9353638,48.619953632354736,-0.2948704829816289,1739137706.9353654,48.619953632354736,2.888592122842486,1739137706.9353666,48.619953632354736,1.730006810340936 +1739137706.9553306,48.63995361328125,35.36841247896322,1739137706.9553332,48.63995361328125,-0.2801436816252929,1739137706.955336,48.63995361328125,77.18550241620105,1739137706.9553387,48.63995361328125,28.951731961121826,1739137706.9553404,48.63995361328125,-0.05437377744548569,1739137706.9553423,48.63995361328125,3.1064223179323234,1739137706.9553437,48.63995361328125,1.3875772138270615,1739137706.955345,48.63995361328125,0.5119708576295612,1739137706.9553463,48.63995361328125,1.4351363273593072,1739137706.9553478,48.63995361328125,0.0,1739137706.9553492,48.63995361328125,-0.2948704829816289,1739137706.9553509,48.63995361328125,2.888592122842486,1739137706.955352,48.63995361328125,1.730006810340936 +1739137706.9752445,48.659953594207764,35.36841247896322,1739137706.975247,48.659953594207764,-0.2801436816252929,1739137706.9752498,48.659953594207764,77.18550241620105,1739137706.9752522,48.659953594207764,28.951731961121826,1739137706.9752538,48.659953594207764,-0.05437377744548569,1739137706.9752553,48.659953594207764,3.1064223179323234,1739137706.9752567,48.659953594207764,1.3875772138270615,1739137706.9752579,48.659953594207764,0.5119708576295612,1739137706.975259,48.659953594207764,1.4351363273593072,1739137706.975261,48.659953594207764,0.0,1739137706.9752622,48.659953594207764,-0.2948704829816289,1739137706.9752636,48.659953594207764,2.888592122842486,1739137706.9752648,48.659953594207764,1.730006810340936 +1739137706.9959307,48.67995357513428,35.18597580311682,1739137706.9959335,48.67995357513428,-0.23246302911234729,1739137706.995936,48.67995357513428,77.30634876057168,1739137706.9959388,48.67995357513428,28.934868554932525,1739137706.9959397,48.67995357513428,-0.05422964576865406,1739137706.9959416,48.67995357513428,3.1130880860792747,1739137706.9959428,48.67995357513428,1.4262324410520777,1739137706.9959443,48.67995357513428,0.5537862636343878,1739137706.9959455,48.67995357513428,1.413116791750524,1739137706.9959466,48.67995357513428,0.0,1739137706.9959483,48.67995357513428,-0.2707371985735682,1739137706.9959497,48.67995357513428,2.8829991807288646,1739137706.9959512,48.67995357513428,1.695346036259186 +1739137707.0153697,48.69995355606079,35.18597580311682,1739137707.0153723,48.69995355606079,-0.23246302911234729,1739137707.0153751,48.69995355606079,77.30634876057168,1739137707.015378,48.69995355606079,28.934868554932525,1739137707.0153792,48.69995355606079,-0.05422964576865406,1739137707.0153806,48.69995355606079,3.1130880860792747,1739137707.0153823,48.69995355606079,1.4262324410520777,1739137707.0153835,48.69995355606079,0.5537862636343878,1739137707.015385,48.69995355606079,1.413116791750524,1739137707.0153866,48.69995355606079,0.0,1739137707.015388,48.69995355606079,-0.2822292445086618,1739137707.0153894,48.69995355606079,2.8829991807288646,1739137707.0153906,48.69995355606079,1.695346036259186 +1739137707.0353782,48.719953536987305,35.18597580311682,1739137707.035381,48.719953536987305,-0.23246302911234729,1739137707.0353842,48.719953536987305,77.30634876057168,1739137707.0353868,48.719953536987305,28.934868554932525,1739137707.0353882,48.719953536987305,-0.05422964576865406,1739137707.03539,48.719953536987305,3.1130880860792747,1739137707.0353916,48.719953536987305,1.4262324410520777,1739137707.0353928,48.719953536987305,0.5537862636343878,1739137707.0353942,48.719953536987305,1.413116791750524,1739137707.0353959,48.719953536987305,0.0,1739137707.035397,48.719953536987305,-0.2822292445086618,1739137707.0353987,48.719953536987305,2.8829991807288646,1739137707.0354,48.719953536987305,1.695346036259186 +1739137707.055386,48.73995351791382,35.18597580311682,1739137707.0553887,48.73995351791382,-0.23246302911234729,1739137707.055392,48.73995351791382,77.30634876057168,1739137707.0553946,48.73995351791382,28.934868554932525,1739137707.055396,48.73995351791382,-0.05422964576865406,1739137707.055398,48.73995351791382,3.1130880860792747,1739137707.0553992,48.73995351791382,1.4262324410520777,1739137707.0554004,48.73995351791382,0.5537862636343878,1739137707.055402,48.73995351791382,1.413116791750524,1739137707.0554032,48.73995351791382,0.0,1739137707.055405,48.73995351791382,-0.2822292445086618,1739137707.0554063,48.73995351791382,2.8829991807288646,1739137707.0554075,48.73995351791382,1.695346036259186 +1739137707.075475,48.75995349884033,35.18597580311682,1739137707.0754776,48.75995349884033,-0.23246302911234729,1739137707.0754802,48.75995349884033,77.30634876057168,1739137707.075483,48.75995349884033,28.934868554932525,1739137707.0754845,48.75995349884033,-0.05422964576865406,1739137707.0754864,48.75995349884033,3.1130880860792747,1739137707.0754879,48.75995349884033,1.4262324410520777,1739137707.075489,48.75995349884033,0.5537862636343878,1739137707.0754902,48.75995349884033,1.413116791750524,1739137707.075492,48.75995349884033,0.0,1739137707.075493,48.75995349884033,-0.2822292445086618,1739137707.0754943,48.75995349884033,2.8829991807288646,1739137707.075496,48.75995349884033,1.695346036259186 +1739137707.0953684,48.779953479766846,35.18597580311682,1739137707.095371,48.779953479766846,-0.23246302911234729,1739137707.0953739,48.779953479766846,77.30634876057168,1739137707.0953765,48.779953479766846,28.934868554932525,1739137707.0953777,48.779953479766846,-0.05422964576865406,1739137707.0953798,48.779953479766846,3.1130880860792747,1739137707.0953813,48.779953479766846,1.4262324410520777,1739137707.0953825,48.779953479766846,0.5537862636343878,1739137707.095384,48.779953479766846,1.413116791750524,1739137707.0953856,48.779953479766846,0.0,1739137707.095387,48.779953479766846,-0.2822292445086618,1739137707.0953882,48.779953479766846,2.8829991807288646,1739137707.0953894,48.779953479766846,1.695346036259186 +1739137707.115294,48.79995346069336,35.0074493034494,1739137707.1152968,48.79995346069336,-0.1848449562899761,1739137707.1152997,48.79995346069336,77.44656469234455,1739137707.115302,48.79995346069336,28.89768021377041,1739137707.1153035,48.79995346069336,-0.05391254418449498,1739137707.1153052,48.79995346069336,3.1201659233256853,1739137707.1153064,48.79995346069336,1.4615198067322481,1739137707.115308,48.79995346069336,0.5932445596134346,1739137707.115309,48.79995346069336,1.3933108330107054,1739137707.1153107,48.79995346069336,0.0,1739137707.1153119,48.79995346069336,-0.25447845580276585,1739137707.1153133,48.79995346069336,2.8786699982206843,1739137707.115315,48.79995346069336,1.661003956703297 +1739137707.1352985,48.81995344161987,35.0074493034494,1739137707.135301,48.81995344161987,-0.1848449562899761,1739137707.1353045,48.81995344161987,77.44656469234455,1739137707.1353073,48.81995344161987,28.89768021377041,1739137707.1353085,48.81995344161987,-0.05391254418449498,1739137707.1353102,48.81995344161987,3.1201659233256853,1739137707.1353116,48.81995344161987,1.4615198067322481,1739137707.1353128,48.81995344161987,0.5932445596134346,1739137707.1353142,48.81995344161987,1.3933108330107054,1739137707.1353157,48.81995344161987,0.0,1739137707.135317,48.81995344161987,-0.2676931236925917,1739137707.1353188,48.81995344161987,2.8786699982206843,1739137707.13532,48.81995344161987,1.661003956703297 +1739137707.155184,48.83995342254639,35.0074493034494,1739137707.155187,48.83995342254639,-0.1848449562899761,1739137707.1551898,48.83995342254639,77.44656469234455,1739137707.1551924,48.83995342254639,28.89768021377041,1739137707.1551938,48.83995342254639,-0.05391254418449498,1739137707.1551955,48.83995342254639,3.1201659233256853,1739137707.155197,48.83995342254639,1.4615198067322481,1739137707.155198,48.83995342254639,0.5932445596134346,1739137707.1551995,48.83995342254639,1.3933108330107054,1739137707.155201,48.83995342254639,0.0,1739137707.1552024,48.83995342254639,-0.2676931236925917,1739137707.1552038,48.83995342254639,2.8786699982206843,1739137707.1552055,48.83995342254639,1.661003956703297 +1739137707.1752167,48.8599534034729,35.0074493034494,1739137707.1752195,48.8599534034729,-0.1848449562899761,1739137707.1752226,48.8599534034729,77.44656469234455,1739137707.1752253,48.8599534034729,28.89768021377041,1739137707.1752267,48.8599534034729,-0.05391254418449498,1739137707.1752286,48.8599534034729,3.1201659233256853,1739137707.17523,48.8599534034729,1.4615198067322481,1739137707.1752312,48.8599534034729,0.5932445596134346,1739137707.1752324,48.8599534034729,1.3933108330107054,1739137707.175234,48.8599534034729,0.0,1739137707.1752353,48.8599534034729,-0.2676931236925917,1739137707.175237,48.8599534034729,2.8786699982206843,1739137707.1752381,48.8599534034729,1.661003956703297 +1739137707.19522,48.879953384399414,35.0074493034494,1739137707.1952229,48.879953384399414,-0.1848449562899761,1739137707.1952257,48.879953384399414,77.44656469234455,1739137707.1952286,48.879953384399414,28.89768021377041,1739137707.19523,48.879953384399414,-0.05391254418449498,1739137707.1952317,48.879953384399414,3.1201659233256853,1739137707.1952333,48.879953384399414,1.4615198067322481,1739137707.1952345,48.879953384399414,0.5932445596134346,1739137707.1952357,48.879953384399414,1.3933108330107054,1739137707.1952372,48.879953384399414,0.0,1739137707.1952384,48.879953384399414,-0.2676931236925917,1739137707.1952403,48.879953384399414,2.8786699982206843,1739137707.1952415,48.879953384399414,1.661003956703297 +1739137707.215325,48.89995336532593,34.832733495679456,1739137707.2153277,48.89995336532593,-0.13754174849440393,1739137707.2153308,48.89995336532593,77.71293212363109,1739137707.2153337,48.89995336532593,28.7334053847199,1739137707.215335,48.89995336532593,-0.05251628533948633,1739137707.215337,48.89995336532593,3.1276534205040876,1739137707.2153385,48.89995336532593,1.521057973784795,1739137707.2153397,48.89995336532593,0.6108,1739137707.215341,48.89995336532593,1.3605207656319727,1739137707.2153425,48.89995336532593,0.0,1739137707.215344,48.89995336532593,-0.26532809858548223,1739137707.2153454,48.89995336532593,2.875637188590957,1739137707.2153466,48.89995336532593,1.6269750672119994 +1739137707.2352097,48.91995334625244,34.832733495679456,1739137707.235213,48.91995334625244,-0.13754174849440393,1739137707.235216,48.91995334625244,77.71293212363109,1739137707.2352188,48.91995334625244,28.7334053847199,1739137707.2352197,48.91995334625244,-0.05251628533948633,1739137707.2352214,48.91995334625244,3.1276534205040876,1739137707.235223,48.91995334625244,1.521057973784795,1739137707.2352242,48.91995334625244,0.6108,1739137707.2352257,48.91995334625244,1.3605207656319727,1739137707.235227,48.91995334625244,0.0,1739137707.2352283,48.91995334625244,-0.2664543015800267,1739137707.23523,48.91995334625244,2.875637188590957,1739137707.2352312,48.91995334625244,1.6269750672119994 +1739137707.2552478,48.939953327178955,34.832733495679456,1739137707.2552507,48.939953327178955,-0.13754174849440393,1739137707.2552536,48.939953327178955,77.71293212363109,1739137707.2552562,48.939953327178955,28.7334053847199,1739137707.2552576,48.939953327178955,-0.05251628533948633,1739137707.2552593,48.939953327178955,3.1276534205040876,1739137707.255261,48.939953327178955,1.521057973784795,1739137707.2552624,48.939953327178955,0.6108,1739137707.2552638,48.939953327178955,1.3605207656319727,1739137707.2552652,48.939953327178955,0.0,1739137707.2552667,48.939953327178955,-0.2664543015800267,1739137707.2552679,48.939953327178955,2.875637188590957,1739137707.255269,48.939953327178955,1.6269750672119994 +1739137707.2756145,48.95995330810547,34.832733495679456,1739137707.2756174,48.95995330810547,-0.13754174849440393,1739137707.27562,48.95995330810547,77.71293212363109,1739137707.2756226,48.95995330810547,28.7334053847199,1739137707.2756243,48.95995330810547,-0.05251628533948633,1739137707.2756257,48.95995330810547,3.1276534205040876,1739137707.2756274,48.95995330810547,1.521057973784795,1739137707.2756286,48.95995330810547,0.6108,1739137707.2756298,48.95995330810547,1.3605207656319727,1739137707.2756314,48.95995330810547,0.0,1739137707.2756329,48.95995330810547,-0.2664543015800267,1739137707.2756343,48.95995330810547,2.875637188590957,1739137707.2756355,48.95995330810547,1.6269750672119994 +1739137707.2952032,48.97995328903198,34.832733495679456,1739137707.2952063,48.97995328903198,-0.13754174849440393,1739137707.2952094,48.97995328903198,77.71293212363109,1739137707.295212,48.97995328903198,28.7334053847199,1739137707.2952132,48.97995328903198,-0.05251628533948633,1739137707.2952151,48.97995328903198,3.1276534205040876,1739137707.2952163,48.97995328903198,1.521057973784795,1739137707.2952178,48.97995328903198,0.6108,1739137707.295219,48.97995328903198,1.3605207656319727,1739137707.2952209,48.97995328903198,0.0,1739137707.295222,48.97995328903198,-0.2664543015800267,1739137707.2952235,48.97995328903198,2.875637188590957,1739137707.295225,48.97995328903198,1.6269750672119994 +1739137707.315214,48.999953269958496,34.832733495679456,1739137707.3152165,48.999953269958496,-0.13754174849440393,1739137707.3152194,48.999953269958496,77.71293212363109,1739137707.3152223,48.999953269958496,28.7334053847199,1739137707.3152237,48.999953269958496,-0.05251628533948633,1739137707.3152258,48.999953269958496,3.1276534205040876,1739137707.315227,48.999953269958496,1.521057973784795,1739137707.3152285,48.999953269958496,0.6108,1739137707.3152297,48.999953269958496,1.3605207656319727,1739137707.3152313,48.999953269958496,0.0,1739137707.3152325,48.999953269958496,-0.2664543015800267,1739137707.315234,48.999953269958496,2.875637188590957,1739137707.3152354,48.999953269958496,1.6269750672119994 +1739137707.3353784,49.01995325088501,34.66172907380108,1739137707.3353813,49.01995325088501,-0.09079647126214141,1739137707.3353844,49.01995325088501,78.07632347136088,1739137707.3353877,49.01995325088501,28.47118273742538,1739137707.3353887,49.01995325088501,-0.05125376293413372,1739137707.3353906,49.01995325088501,3.1352051445730553,1739137707.335392,49.01995325088501,1.5991204307030162,1739137707.335394,49.01995325088501,0.6108,1739137707.335395,49.01995325088501,1.3186949319310395,1739137707.3353968,49.01995325088501,0.0,1739137707.3353982,49.01995325088501,-0.2819270140573523,1739137707.3353999,49.01995325088501,2.873931420224553,1739137707.3354013,49.01995325088501,1.5932539839852369 +1739137707.3552473,49.03995323181152,34.66172907380108,1739137707.3552501,49.03995323181152,-0.09079647126214141,1739137707.355253,49.03995323181152,78.07632347136088,1739137707.3552558,49.03995323181152,28.47118273742538,1739137707.3552573,49.03995323181152,-0.05125376293413372,1739137707.355259,49.03995323181152,3.1352051445730553,1739137707.3552604,49.03995323181152,1.5991204307030162,1739137707.3552618,49.03995323181152,0.6108,1739137707.3552628,49.03995323181152,1.3186949319310395,1739137707.3552642,49.03995323181152,0.0,1739137707.3552656,49.03995323181152,-0.2745590520541974,1739137707.355267,49.03995323181152,2.873931420224553,1739137707.3552682,49.03995323181152,1.5932539839852369 +1739137707.375207,49.05995321273804,34.66172907380108,1739137707.3752093,49.05995321273804,-0.09079647126214141,1739137707.375212,49.05995321273804,78.07632347136088,1739137707.3752148,49.05995321273804,28.47118273742538,1739137707.3752162,49.05995321273804,-0.05125376293413372,1739137707.3752177,49.05995321273804,3.1352051445730553,1739137707.375219,49.05995321273804,1.5991204307030162,1739137707.3752205,49.05995321273804,0.6108,1739137707.3752215,49.05995321273804,1.3186949319310395,1739137707.375223,49.05995321273804,0.0,1739137707.3752244,49.05995321273804,-0.2745590520541974,1739137707.3752258,49.05995321273804,2.873931420224553,1739137707.3752272,49.05995321273804,1.5932539839852369 +1739137707.3951435,49.07995319366455,34.66172907380108,1739137707.3951466,49.07995319366455,-0.09079647126214141,1739137707.3951492,49.07995319366455,78.07632347136088,1739137707.3951519,49.07995319366455,28.47118273742538,1739137707.3951535,49.07995319366455,-0.05125376293413372,1739137707.3951552,49.07995319366455,3.1352051445730553,1739137707.3951566,49.07995319366455,1.5991204307030162,1739137707.395158,49.07995319366455,0.6108,1739137707.395159,49.07995319366455,1.3186949319310395,1739137707.395161,49.07995319366455,0.0,1739137707.395162,49.07995319366455,-0.2745590520541974,1739137707.3951635,49.07995319366455,2.873931420224553,1739137707.395165,49.07995319366455,1.5932539839852369 +1739137707.4151995,49.099953174591064,34.66172907380108,1739137707.4152024,49.099953174591064,-0.09079647126214141,1739137707.415206,49.099953174591064,78.07632347136088,1739137707.415209,49.099953174591064,28.47118273742538,1739137707.4152105,49.099953174591064,-0.05125376293413372,1739137707.4152126,49.099953174591064,3.1352051445730553,1739137707.415214,49.099953174591064,1.5991204307030162,1739137707.4152153,49.099953174591064,0.6108,1739137707.415217,49.099953174591064,1.3186949319310395,1739137707.4152186,49.099953174591064,0.0,1739137707.4152203,49.099953174591064,-0.2745590520541974,1739137707.4152217,49.099953174591064,2.873931420224553,1739137707.4152231,49.099953174591064,1.5932539839852369 +1739137707.4351947,49.11995315551758,34.49433853313986,1739137707.435197,49.11995315551758,-0.044840947971252376,1739137707.4352,49.11995315551758,78.09578672960087,1739137707.4352028,49.11995315551758,28.551972055146106,1739137707.4352043,49.11995315551758,-0.05195627874040092,1739137707.435206,49.11995315551758,-3.140395264065774,1739137707.4352074,49.11995315551758,1.5806020638663323,1739137707.4352088,49.11995315551758,0.6108,1739137707.43521,49.11995315551758,1.3284992296162135,1739137707.4352114,49.11995315551758,0.0,1739137707.4352129,49.11995315551758,-0.19204268152410753,1739137707.4352143,49.11995315551758,2.8735608629536715,1739137707.4352157,49.11995315551758,1.559835440545389 +1739137707.4549289,49.13995313644409,34.49433853313986,1739137707.4549313,49.13995313644409,-0.044840947971252376,1739137707.4549336,49.13995313644409,78.09578672960087,1739137707.4549365,49.13995313644409,28.551972055146106,1739137707.454938,49.13995313644409,-0.05195627874040092,1739137707.4549394,49.13995313644409,-3.140395264065774,1739137707.454941,49.13995313644409,1.5806020638663323,1739137707.4549422,49.13995313644409,0.6108,1739137707.4549434,49.13995313644409,1.3284992296162135,1739137707.454945,49.13995313644409,0.0,1739137707.4549463,49.13995313644409,-0.23133621092917545,1739137707.454948,49.13995313644409,2.8735608629536715,1739137707.4549494,49.13995313644409,1.559835440545389 +1739137707.474904,49.159953117370605,34.49433853313986,1739137707.4749064,49.159953117370605,-0.044840947971252376,1739137707.474909,49.159953117370605,78.09578672960087,1739137707.4749117,49.159953117370605,28.551972055146106,1739137707.4749131,49.159953117370605,-0.05195627874040092,1739137707.4749148,49.159953117370605,-3.140395264065774,1739137707.4749165,49.159953117370605,1.5806020638663323,1739137707.474918,49.159953117370605,0.6108,1739137707.4749188,49.159953117370605,1.3284992296162135,1739137707.4749205,49.159953117370605,0.0,1739137707.4749217,49.159953117370605,-0.23133621092917545,1739137707.4749234,49.159953117370605,2.8735608629536715,1739137707.4749246,49.159953117370605,1.559835440545389 +1739137707.4950776,49.17995309829712,34.49433853313986,1739137707.49508,49.17995309829712,-0.044840947971252376,1739137707.495083,49.17995309829712,78.09578672960087,1739137707.4950855,49.17995309829712,28.551972055146106,1739137707.495087,49.17995309829712,-0.05195627874040092,1739137707.4950886,49.17995309829712,-3.140395264065774,1739137707.49509,49.17995309829712,1.5806020638663323,1739137707.4950912,49.17995309829712,0.6108,1739137707.4950922,49.17995309829712,1.3284992296162135,1739137707.4950945,49.17995309829712,0.0,1739137707.4950957,49.17995309829712,-0.23133621092917545,1739137707.4950972,49.17995309829712,2.8735608629536715,1739137707.4950986,49.17995309829712,1.559835440545389 +1739137707.5149233,49.19995307922363,34.49433853313986,1739137707.5149255,49.19995307922363,-0.044840947971252376,1739137707.514928,49.19995307922363,78.09578672960087,1739137707.5149312,49.19995307922363,28.551972055146106,1739137707.5149324,49.19995307922363,-0.05195627874040092,1739137707.5149343,49.19995307922363,-3.140395264065774,1739137707.5149355,49.19995307922363,1.5806020638663323,1739137707.5149372,49.19995307922363,0.6108,1739137707.5149384,49.19995307922363,1.3284992296162135,1739137707.5149398,49.19995307922363,0.0,1739137707.514941,49.19995307922363,-0.23133621092917545,1739137707.5149424,49.19995307922363,2.8735608629536715,1739137707.5149438,49.19995307922363,1.559835440545389 +1739137707.5351377,49.21995306015015,34.49433853313986,1739137707.53514,49.21995306015015,-0.044840947971252376,1739137707.535143,49.21995306015015,78.09578672960087,1739137707.5351458,49.21995306015015,28.551972055146106,1739137707.535147,49.21995306015015,-0.05195627874040092,1739137707.5351489,49.21995306015015,-3.140395264065774,1739137707.53515,49.21995306015015,1.5806020638663323,1739137707.5351517,49.21995306015015,0.6108,1739137707.535153,49.21995306015015,1.3284992296162135,1739137707.5351543,49.21995306015015,0.0,1739137707.5351558,49.21995306015015,-0.23133621092917545,1739137707.5351572,49.21995306015015,2.8735608629536715,1739137707.5351586,49.21995306015015,1.559835440545389 +1739137707.5617547,49.23995304107666,34.330266605783414,1739137707.561763,49.23995304107666,0.00016225131420366523,1739137707.561773,49.23995304107666,78.11486407637351,1739137707.561783,49.23995304107666,28.625691849938317,1739137707.5617876,49.23995304107666,-0.052,1739137707.5617936,49.23995304107666,-3.132448975080652,1739137707.5617983,49.23995304107666,1.5557752765389794,1739137707.561803,49.23995304107666,0.6108,1739137707.5618074,49.23995304107666,1.3417579018355805,1739137707.5618641,49.23995304107666,0.0,1739137707.5618703,49.23995304107666,-0.14697131459987833,1739137707.5618753,49.23995304107666,2.8745248015422513,1739137707.56188,49.23995304107666,1.5289029966608254 +1739137707.581304,49.259953022003174,34.330266605783414,1739137707.5813131,49.259953022003174,0.00016225131420366523,1739137707.5813236,49.259953022003174,78.11486407637351,1739137707.5813334,49.259953022003174,28.625691849938317,1739137707.581339,49.259953022003174,-0.052,1739137707.5813453,49.259953022003174,-3.132448975080652,1739137707.5813503,49.259953022003174,1.5557752765389794,1739137707.5813553,49.259953022003174,0.6108,1739137707.5813599,49.259953022003174,1.3417579018355805,1739137707.5813668,49.259953022003174,0.0,1739137707.5813713,49.259953022003174,-0.18714509482524488,1739137707.5813768,49.259953022003174,2.8745248015422513,1739137707.581381,49.259953022003174,1.5289029966608254 +1739137707.5997036,49.27995300292969,34.330266605783414,1739137707.5997112,49.27995300292969,0.00016225131420366523,1739137707.5997214,49.27995300292969,78.11486407637351,1739137707.599731,49.27995300292969,28.625691849938317,1739137707.5997357,49.27995300292969,-0.052,1739137707.5997417,49.27995300292969,-3.132448975080652,1739137707.5997462,49.27995300292969,1.5557752765389794,1739137707.5997512,49.27995300292969,0.6108,1739137707.5997558,49.27995300292969,1.3417579018355805,1739137707.599761,49.27995300292969,0.0,1739137707.5997655,49.27995300292969,-0.18714509482524488,1739137707.5997705,49.27995300292969,2.8745248015422513,1739137707.5997753,49.27995300292969,1.5289029966608254 +1739137707.6194117,49.2999529838562,34.330266605783414,1739137707.61942,49.2999529838562,0.00016225131420366523,1739137707.6194303,49.2999529838562,78.11486407637351,1739137707.6194398,49.2999529838562,28.625691849938317,1739137707.6194444,49.2999529838562,-0.052,1739137707.6194503,49.2999529838562,-3.132448975080652,1739137707.6194553,49.2999529838562,1.5557752765389794,1739137707.6194599,49.2999529838562,0.6108,1739137707.6194644,49.2999529838562,1.3417579018355805,1739137707.61947,49.2999529838562,0.0,1739137707.6194744,49.2999529838562,-0.18714509482524488,1739137707.6194797,49.2999529838562,2.8745248015422513,1739137707.619484,49.2999529838562,1.5289029966608254 +1739137707.650035,49.319952964782715,34.330266605783414,1739137707.6500413,49.319952964782715,0.00016225131420366523,1739137707.6500487,49.319952964782715,78.11486407637351,1739137707.650056,49.319952964782715,28.625691849938317,1739137707.6500592,49.319952964782715,-0.052,1739137707.6500633,49.319952964782715,-3.132448975080652,1739137707.6500669,49.319952964782715,1.5557752765389794,1739137707.6500702,49.319952964782715,0.6108,1739137707.6500733,49.319952964782715,1.3417579018355805,1739137707.650077,49.319952964782715,0.0,1739137707.6500807,49.319952964782715,-0.18714509482524488,1739137707.6500843,49.319952964782715,2.8745248015422513,1739137707.6500876,49.319952964782715,1.5289029966608254 +1739137707.6710727,49.349952936172485,34.16904143341238,1739137707.6710787,49.349952936172485,0.04411253302091023,1739137707.6710854,49.349952936172485,78.5436014154816,1739137707.671092,49.349952936172485,28.25943663182902,1739137707.6710954,49.349952936172485,-0.049246556393725514,1739137707.6710994,49.349952936172485,-3.1257961109954397,1739137707.671103,49.349952936172485,1.636560365069747,1739137707.6711063,49.349952936172485,0.6108,1739137707.6711094,49.349952936172485,1.2990933341098758,1739137707.6711135,49.349952936172485,0.0,1739137707.6711166,49.349952936172485,-0.22884249451994154,1739137707.6711202,49.349952936172485,2.876825097348096,1739137707.6711235,49.349952936172485,1.5080799140943983 +1739137707.691841,49.35995292663574,34.16904143341238,1739137707.6918468,49.35995292663574,0.04411253302091023,1739137707.6918542,49.35995292663574,78.5436014154816,1739137707.6918614,49.35995292663574,28.25943663182902,1739137707.6918652,49.35995292663574,-0.049246556393725514,1739137707.6918695,49.35995292663574,-3.1257961109954397,1739137707.691873,49.35995292663574,1.636560365069747,1739137707.6918764,49.35995292663574,0.6108,1739137707.6918797,49.35995292663574,1.2990933341098758,1739137707.6918836,49.35995292663574,0.0,1739137707.6918867,49.35995292663574,-0.20898657998452252,1739137707.6918902,49.35995292663574,2.876825097348096,1739137707.6918936,49.35995292663574,1.5080799140943983 +1739137707.711554,49.38995289802551,34.16904143341238,1739137707.7115602,49.38995289802551,0.04411253302091023,1739137707.7115676,49.38995289802551,78.5436014154816,1739137707.711575,49.38995289802551,28.25943663182902,1739137707.7115784,49.38995289802551,-0.049246556393725514,1739137707.7115827,49.38995289802551,-3.1257961109954397,1739137707.711586,49.38995289802551,1.636560365069747,1739137707.7115893,49.38995289802551,0.6108,1739137707.711593,49.38995289802551,1.2990933341098758,1739137707.7115965,49.38995289802551,0.0,1739137707.7116,49.38995289802551,-0.20898657998452252,1739137707.7116036,49.38995289802551,2.876825097348096,1739137707.711607,49.38995289802551,1.5080799140943983 +1739137707.7291133,49.409952878952026,34.16904143341238,1739137707.729117,49.409952878952026,0.04411253302091023,1739137707.7291212,49.409952878952026,78.5436014154816,1739137707.7291253,49.409952878952026,28.25943663182902,1739137707.7291276,49.409952878952026,-0.049246556393725514,1739137707.7291303,49.409952878952026,-3.1257961109954397,1739137707.7291327,49.409952878952026,1.636560365069747,1739137707.7291346,49.409952878952026,0.6108,1739137707.7291365,49.409952878952026,1.2990933341098758,1739137707.7291386,49.409952878952026,0.0,1739137707.7291408,49.409952878952026,-0.20898657998452252,1739137707.7291431,49.409952878952026,2.876825097348096,1739137707.729145,49.409952878952026,1.5080799140943983 +1739137707.7504811,49.42995285987854,34.16904143341238,1739137707.7504835,49.42995285987854,0.04411253302091023,1739137707.7504866,49.42995285987854,78.5436014154816,1739137707.7504892,49.42995285987854,28.25943663182902,1739137707.7504904,49.42995285987854,-0.049246556393725514,1739137707.750492,49.42995285987854,-3.1257961109954397,1739137707.7504938,49.42995285987854,1.636560365069747,1739137707.7504947,49.42995285987854,0.6108,1739137707.7504961,49.42995285987854,1.2990933341098758,1739137707.7504978,49.42995285987854,0.0,1739137707.7504988,49.42995285987854,-0.20898657998452252,1739137707.7505004,49.42995285987854,2.876825097348096,1739137707.7505016,49.42995285987854,1.5080799140943983 +1739137707.7688043,49.449952840805054,34.01033796195807,1739137707.7688074,49.449952840805054,0.08688042695294218,1739137707.7688105,49.449952840805054,78.5622124895357,1739137707.7688131,49.449952840805054,28.33546390141852,1739137707.7688146,49.449952840805054,-0.05006547281946073,1739137707.7688162,49.449952840805054,-3.1174653647687314,1739137707.7688177,49.449952840805054,1.5973798474986574,1739137707.7688186,49.449952840805054,0.6108,1739137707.76882,49.449952840805054,1.319613370917911,1739137707.7688215,49.449952840805054,0.0,1739137707.7688227,49.449952840805054,-0.10958470154387226,1739137707.7688243,49.449952840805054,2.880466202726162,1739137707.7688255,49.449952840805054,1.476532323936191 +1739137707.7886739,49.46995282173157,34.01033796195807,1739137707.788676,49.46995282173157,0.08688042695294218,1739137707.788679,49.46995282173157,78.5622124895357,1739137707.7886817,49.46995282173157,28.33546390141852,1739137707.788683,49.46995282173157,-0.05006547281946073,1739137707.7886848,49.46995282173157,-3.1174653647687314,1739137707.788686,49.46995282173157,1.5973798474986574,1739137707.7886877,49.46995282173157,0.6108,1739137707.788689,49.46995282173157,1.319613370917911,1739137707.7886903,49.46995282173157,0.0,1739137707.788692,49.46995282173157,-0.15691895301827996,1739137707.7886934,49.46995282173157,2.880466202726162,1739137707.7886949,49.46995282173157,1.476532323936191 +1739137707.8154178,49.48995280265808,34.01033796195807,1739137707.8154268,49.48995280265808,0.08688042695294218,1739137707.8154368,49.48995280265808,78.5622124895357,1739137707.8154469,49.48995280265808,28.33546390141852,1739137707.8154514,49.48995280265808,-0.05006547281946073,1739137707.815457,49.48995280265808,-3.1174653647687314,1739137707.8154624,49.48995280265808,1.5973798474986574,1739137707.8154666,49.48995280265808,0.6108,1739137707.8154714,49.48995280265808,1.319613370917911,1739137707.8154764,49.48995280265808,0.0,1739137707.8154814,49.48995280265808,-0.15691895301827996,1739137707.815487,49.48995280265808,2.880466202726162,1739137707.8154914,49.48995280265808,1.476532323936191 +1739137707.8338912,49.509952783584595,34.01033796195807,1739137707.833899,49.509952783584595,0.08688042695294218,1739137707.8339093,49.509952783584595,78.5622124895357,1739137707.8339186,49.509952783584595,28.33546390141852,1739137707.8339233,49.509952783584595,-0.05006547281946073,1739137707.8339295,49.509952783584595,-3.1174653647687314,1739137707.833934,49.509952783584595,1.5973798474986574,1739137707.8339388,49.509952783584595,0.6108,1739137707.8339436,49.509952783584595,1.319613370917911,1739137707.8339486,49.509952783584595,0.0,1739137707.8339534,49.509952783584595,-0.15691895301827996,1739137707.8339586,49.509952783584595,2.880466202726162,1739137707.8339632,49.509952783584595,1.476532323936191 +1739137707.8678691,49.539952754974365,34.01033796195807,1739137707.8678784,49.539952754974365,0.08688042695294218,1739137707.8678887,49.539952754974365,78.5622124895357,1739137707.8678987,49.539952754974365,28.33546390141852,1739137707.8679035,49.539952754974365,-0.05006547281946073,1739137707.8679097,49.539952754974365,-3.1174653647687314,1739137707.8679147,49.539952754974365,1.5973798474986574,1739137707.8679197,49.539952754974365,0.6108,1739137707.8679242,49.539952754974365,1.319613370917911,1739137707.86793,49.539952754974365,0.0,1739137707.8679347,49.539952754974365,-0.15691895301827996,1739137707.86794,49.539952754974365,2.880466202726162,1739137707.8679447,49.539952754974365,1.476532323936191 +1739137707.8845148,49.55995273590088,33.85408138777619,1739137707.8845196,49.55995273590088,0.12827660363054694,1739137707.8845253,49.55995273590088,78.89289609693009,1739137707.8845308,49.55995273590088,28.0535491459661,1739137707.8845334,49.55995273590088,-0.048,1739137707.8845367,49.55995273590088,-3.1112122746131927,1739137707.8845394,49.55995273590088,1.6400668982082083,1739137707.884542,49.55995273590088,0.6108,1739137707.8845444,49.55995273590088,1.2972724858509401,1739137707.884547,49.55995273590088,0.0,1739137707.8845499,49.55995273590088,-0.16854103358968126,1739137707.8845527,49.55995273590088,2.8854551956035497,1739137707.8845558,49.55995273590088,1.4602791925943637 +1739137707.9041798,49.57995271682739,33.85408138777619,1739137707.9041839,49.57995271682739,0.12827660363054694,1739137707.9041884,49.57995271682739,78.89289609693009,1739137707.9041932,49.57995271682739,28.0535491459661,1739137707.9041955,49.57995271682739,-0.048,1739137707.9041984,49.57995271682739,-3.1112122746131927,1739137707.904201,49.57995271682739,1.6400668982082083,1739137707.9042032,49.57995271682739,0.6108,1739137707.9042053,49.57995271682739,1.2972724858509401,1739137707.9042077,49.57995271682739,0.0,1739137707.9042099,49.57995271682739,-0.16300670674342355,1739137707.9042122,49.57995271682739,2.8854551956035497,1739137707.9042144,49.57995271682739,1.4602791925943637 +1739137707.9248633,49.599952697753906,33.85408138777619,1739137707.9248686,49.599952697753906,0.12827660363054694,1739137707.9248753,49.599952697753906,78.89289609693009,1739137707.9248824,49.599952697753906,28.0535491459661,1739137707.9248865,49.599952697753906,-0.048,1739137707.9248917,49.599952697753906,-3.1112122746131927,1739137707.9248967,49.599952697753906,1.6400668982082083,1739137707.9249015,49.599952697753906,0.6108,1739137707.9249058,49.599952697753906,1.2972724858509401,1739137707.9249105,49.599952697753906,0.0,1739137707.9249153,49.599952697753906,-0.16300670674342355,1739137707.92492,49.599952697753906,2.8854551956035497,1739137707.9249246,49.599952697753906,1.4602791925943637 +1739137707.9449453,49.61995267868042,33.85408138777619,1739137707.9449492,49.61995267868042,0.12827660363054694,1739137707.9449534,49.61995267868042,78.89289609693009,1739137707.944957,49.61995267868042,28.0535491459661,1739137707.944959,49.61995267868042,-0.048,1739137707.944961,49.61995267868042,-3.1112122746131927,1739137707.9449625,49.61995267868042,1.6400668982082083,1739137707.9449642,49.61995267868042,0.6108,1739137707.9449656,49.61995267868042,1.2972724858509401,1739137707.9449677,49.61995267868042,0.0,1739137707.9449694,49.61995267868042,-0.16300670674342355,1739137707.9449716,49.61995267868042,2.8854551956035497,1739137707.9449735,49.61995267868042,1.4602791925943637 +1739137707.9642973,49.639952659606934,33.85408138777619,1739137707.9643006,49.639952659606934,0.12827660363054694,1739137707.9643044,49.639952659606934,78.89289609693009,1739137707.9643075,49.639952659606934,28.0535491459661,1739137707.9643092,49.639952659606934,-0.048,1739137707.9643111,49.639952659606934,-3.1112122746131927,1739137707.9643126,49.639952659606934,1.6400668982082083,1739137707.9643142,49.639952659606934,0.6108,1739137707.9643157,49.639952659606934,1.2972724858509401,1739137707.964317,49.639952659606934,0.0,1739137707.9643185,49.639952659606934,-0.16300670674342355,1739137707.96432,49.639952659606934,2.8854551956035497,1739137707.9643219,49.639952659606934,1.4602791925943637 +1739137707.982907,49.65995264053345,33.85408138777619,1739137707.9829102,49.65995264053345,0.12827660363054694,1739137707.9829135,49.65995264053345,78.89289609693009,1739137707.9829164,49.65995264053345,28.0535491459661,1739137707.9829178,49.65995264053345,-0.048,1739137707.9829197,49.65995264053345,-3.1112122746131927,1739137707.982921,49.65995264053345,1.6400668982082083,1739137707.9829226,49.65995264053345,0.6108,1739137707.9829237,49.65995264053345,1.2972724858509401,1739137707.9829254,49.65995264053345,0.0,1739137707.982927,49.65995264053345,-0.16300670674342355,1739137707.9829288,49.65995264053345,2.8854551956035497,1739137707.9829302,49.65995264053345,1.4602791925943637 +1739137708.0052202,49.67995262145996,33.699455428837,1739137708.0052242,49.67995262145996,0.16831492062605058,1739137708.0052285,49.67995262145996,78.9111819984019,1739137708.005234,49.67995262145996,28.08917281097348,1739137708.005237,49.67995262145996,-0.048,1739137708.005241,49.67995262145996,-3.103054876207557,1739137708.0052443,49.67995262145996,1.5964704232472038,1739137708.0052478,49.67995262145996,0.6108,1739137708.0052512,49.67995262145996,1.320093493600481,1739137708.0052547,49.67995262145996,0.0,1739137708.0052583,49.67995262145996,-0.08513320518824402,1739137708.005262,49.67995262145996,2.8918018347989785,1739137708.0052655,49.67995262145996,1.4423093371013036 +1739137708.024417,49.699952602386475,33.699455428837,1739137708.0244203,49.699952602386475,0.16831492062605058,1739137708.0244248,49.699952602386475,78.9111819984019,1739137708.02443,49.699952602386475,28.08917281097348,1739137708.024433,49.699952602386475,-0.048,1739137708.0244367,49.699952602386475,-3.103054876207557,1739137708.0244398,49.699952602386475,1.5964704232472038,1739137708.0244431,49.699952602386475,0.6108,1739137708.0244467,49.699952602386475,1.320093493600481,1739137708.02445,49.699952602386475,0.0,1739137708.0244534,49.699952602386475,-0.12221584350082271,1739137708.024457,49.699952602386475,2.8918018347989785,1739137708.02446,49.699952602386475,1.4423093371013036 +1739137708.0447526,49.71995258331299,33.699455428837,1739137708.0447564,49.71995258331299,0.16831492062605058,1739137708.044761,49.71995258331299,78.9111819984019,1739137708.0447657,49.71995258331299,28.08917281097348,1739137708.0447686,49.71995258331299,-0.048,1739137708.0447724,49.71995258331299,-3.103054876207557,1739137708.0447757,49.71995258331299,1.5964704232472038,1739137708.0447788,49.71995258331299,0.6108,1739137708.0447824,49.71995258331299,1.320093493600481,1739137708.044786,49.71995258331299,0.0,1739137708.0447893,49.71995258331299,-0.12221584350082271,1739137708.044793,49.71995258331299,2.8918018347989785,1739137708.044796,49.71995258331299,1.4423093371013036 +1739137708.0633888,49.7399525642395,33.699455428837,1739137708.063392,49.7399525642395,0.16831492062605058,1739137708.0633953,49.7399525642395,78.9111819984019,1739137708.0633981,49.7399525642395,28.08917281097348,1739137708.0633993,49.7399525642395,-0.048,1739137708.0634012,49.7399525642395,-3.103054876207557,1739137708.0634024,49.7399525642395,1.5964704232472038,1739137708.063404,49.7399525642395,0.6108,1739137708.0634055,49.7399525642395,1.320093493600481,1739137708.063407,49.7399525642395,0.0,1739137708.0634084,49.7399525642395,-0.12221584350082271,1739137708.0634103,49.7399525642395,2.8918018347989785,1739137708.0634115,49.7399525642395,1.4423093371013036 +1739137708.083423,49.759952545166016,33.699455428837,1739137708.0834253,49.759952545166016,0.16831492062605058,1739137708.0834281,49.759952545166016,78.9111819984019,1739137708.083431,49.759952545166016,28.08917281097348,1739137708.0834322,49.759952545166016,-0.048,1739137708.0834336,49.759952545166016,-3.103054876207557,1739137708.083435,49.759952545166016,1.5964704232472038,1739137708.0834363,49.759952545166016,0.6108,1739137708.0834377,49.759952545166016,1.320093493600481,1739137708.0834389,49.759952545166016,0.0,1739137708.08344,49.759952545166016,-0.12221584350082271,1739137708.0834415,49.759952545166016,2.8918018347989785,1739137708.0834427,49.759952545166016,1.4423093371013036 +1739137708.1027737,49.77995252609253,33.5462211728974,1739137708.1027768,49.77995252609253,0.20685540966062899,1739137708.1027794,49.77995252609253,78.92930218109181,1739137708.102782,49.77995252609253,28.11018689706703,1739137708.1027832,49.77995252609253,-0.04806755071372817,1739137708.102785,49.77995252609253,-3.094731960127075,1739137708.1027865,49.77995252609253,1.5505982578572084,1739137708.1027877,49.77995252609253,0.6108,1739137708.102789,49.77995252609253,1.3445393030044859,1739137708.1027904,49.77995252609253,0.0,1739137708.1027918,49.77995252609253,-0.05064275487160763,1739137708.1027935,49.77995252609253,2.899518637011167,1739137708.1027946,49.77995252609253,1.4292644980585305 +1739137708.122657,49.79995250701904,33.5462211728974,1739137708.12266,49.79995250701904,0.20685540966062899,1739137708.122663,49.79995250701904,78.92930218109181,1739137708.1226654,49.79995250701904,28.11018689706703,1739137708.122667,49.79995250701904,-0.04806755071372817,1739137708.1226687,49.79995250701904,-3.094731960127075,1739137708.1226707,49.79995250701904,1.5505982578572084,1739137708.1226718,49.79995250701904,0.6108,1739137708.1226735,49.79995250701904,1.3445393030044859,1739137708.1226752,49.79995250701904,0.0,1739137708.1226764,49.79995250701904,-0.08472519505404463,1739137708.122678,49.79995250701904,2.899518637011167,1739137708.1226795,49.79995250701904,1.4292644980585305 +1739137708.1430712,49.81995248794556,33.5462211728974,1739137708.143074,49.81995248794556,0.20685540966062899,1739137708.1430774,49.81995248794556,78.92930218109181,1739137708.1430807,49.81995248794556,28.11018689706703,1739137708.143082,49.81995248794556,-0.04806755071372817,1739137708.1430838,49.81995248794556,-3.094731960127075,1739137708.1430852,49.81995248794556,1.5505982578572084,1739137708.143087,49.81995248794556,0.6108,1739137708.143088,49.81995248794556,1.3445393030044859,1739137708.14309,49.81995248794556,0.0,1739137708.1430917,49.81995248794556,-0.08472519505404463,1739137708.1430933,49.81995248794556,2.899518637011167,1739137708.1430948,49.81995248794556,1.4292644980585305 +1739137708.162786,49.83995246887207,33.5462211728974,1739137708.1627889,49.83995246887207,0.20685540966062899,1739137708.1627936,49.83995246887207,78.92930218109181,1739137708.162797,49.83995246887207,28.11018689706703,1739137708.1627984,49.83995246887207,-0.04806755071372817,1739137708.1628,49.83995246887207,-3.094731960127075,1739137708.1628017,49.83995246887207,1.5505982578572084,1739137708.1628032,49.83995246887207,0.6108,1739137708.1628048,49.83995246887207,1.3445393030044859,1739137708.1628063,49.83995246887207,0.0,1739137708.1628077,49.83995246887207,-0.08472519505404463,1739137708.1628094,49.83995246887207,2.899518637011167,1739137708.162811,49.83995246887207,1.4292644980585305 +1739137708.1828828,49.859952449798584,33.5462211728974,1739137708.182886,49.859952449798584,0.20685540966062899,1739137708.182889,49.859952449798584,78.92930218109181,1739137708.182892,49.859952449798584,28.11018689706703,1739137708.1828935,49.859952449798584,-0.04806755071372817,1739137708.1828957,49.859952449798584,-3.094731960127075,1739137708.182897,49.859952449798584,1.5505982578572084,1739137708.1828988,49.859952449798584,0.6108,1739137708.1829,49.859952449798584,1.3445393030044859,1739137708.1829019,49.859952449798584,0.0,1739137708.182903,49.859952449798584,-0.08472519505404463,1739137708.1829045,49.859952449798584,2.899518637011167,1739137708.1829066,49.859952449798584,1.4292644980585305 +1739137708.20278,49.8799524307251,33.5462211728974,1739137708.2027826,49.8799524307251,0.20685540966062899,1739137708.202786,49.8799524307251,78.92930218109181,1739137708.202789,49.8799524307251,28.11018689706703,1739137708.2027907,49.8799524307251,-0.04806755071372817,1739137708.2027924,49.8799524307251,-3.094731960127075,1739137708.202794,49.8799524307251,1.5505982578572084,1739137708.2027953,49.8799524307251,0.6108,1739137708.2027967,49.8799524307251,1.3445393030044859,1739137708.2027984,49.8799524307251,0.0,1739137708.2027998,49.8799524307251,-0.08472519505404463,1739137708.2028015,49.8799524307251,2.899518637011167,1739137708.202803,49.8799524307251,1.4292644980585305 +1739137708.222907,49.89995241165161,33.39382552635008,1739137708.2229102,49.89995241165161,0.24383538961154194,1739137708.2229137,49.89995241165161,79.47684374102501,1739137708.2229166,49.89995241165161,27.588480037855174,1739137708.222918,49.89995241165161,-0.045,1739137708.22292,49.89995241165161,-3.091880295174858,1739137708.2229214,49.89995241165161,1.621312124899583,1739137708.222923,49.89995241165161,0.6108,1739137708.2229242,49.89995241165161,1.3070411022310868,1739137708.222926,49.89995241165161,0.0,1739137708.2229273,49.89995241165161,-0.13988175491912377,1739137708.222929,49.89995241165161,2.9086209767789284,1739137708.2229304,49.89995241165161,1.4206578155224943 +1739137708.251224,49.919952392578125,33.39382552635008,1739137708.2512412,49.919952392578125,0.24383538961154194,1739137708.2512615,49.919952392578125,79.47684374102501,1739137708.2512865,49.919952392578125,27.588480037855174,1739137708.251294,49.919952392578125,-0.045,1739137708.2513044,49.919952392578125,-3.091880295174858,1739137708.2513213,49.919952392578125,1.621312124899583,1739137708.2513285,49.919952392578125,0.6108,1739137708.2513328,49.919952392578125,1.3070411022310868,1739137708.2513387,49.919952392578125,0.0,1739137708.2513433,49.919952392578125,-0.11361671329140743,1739137708.2513487,49.919952392578125,2.9086209767789284,1739137708.2513535,49.919952392578125,1.4206578155224943 +1739137708.2757716,49.93995237350464,33.39382552635008,1739137708.2757804,49.93995237350464,0.24383538961154194,1739137708.275791,49.93995237350464,79.47684374102501,1739137708.2758012,49.93995237350464,27.588480037855174,1739137708.2758057,49.93995237350464,-0.045,1739137708.2758117,49.93995237350464,-3.091880295174858,1739137708.2758164,49.93995237350464,1.621312124899583,1739137708.275821,49.93995237350464,0.6108,1739137708.2758255,49.93995237350464,1.3070411022310868,1739137708.2758317,49.93995237350464,0.0,1739137708.2758367,49.93995237350464,-0.11361671329140743,1739137708.2758417,49.93995237350464,2.9086209767789284,1739137708.2758467,49.93995237350464,1.4206578155224943 +1739137708.2899947,49.95995235443115,33.39382552635008,1739137708.290001,49.95995235443115,0.24383538961154194,1739137708.2900078,49.95995235443115,79.47684374102501,1739137708.2900145,49.95995235443115,27.588480037855174,1739137708.2900178,49.95995235443115,-0.045,1739137708.290022,49.95995235443115,-3.091880295174858,1739137708.2900255,49.95995235443115,1.621312124899583,1739137708.2900286,49.95995235443115,0.6108,1739137708.290032,49.95995235443115,1.3070411022310868,1739137708.2900357,49.95995235443115,0.0,1739137708.290039,49.95995235443115,-0.11361671329140743,1739137708.2900429,49.95995235443115,2.9086209767789284,1739137708.2900462,49.95995235443115,1.4206578155224943 +1739137708.3053024,49.979952335357666,33.39382552635008,1739137708.3053062,49.979952335357666,0.24383538961154194,1739137708.3053105,49.979952335357666,79.47684374102501,1739137708.3053145,49.979952335357666,27.588480037855174,1739137708.305317,49.979952335357666,-0.045,1739137708.3053193,49.979952335357666,-3.091880295174858,1739137708.3053215,49.979952335357666,1.621312124899583,1739137708.3053236,49.979952335357666,0.6108,1739137708.3053255,49.979952335357666,1.3070411022310868,1739137708.3053277,49.979952335357666,0.0,1739137708.30533,49.979952335357666,-0.11361671329140743,1739137708.305332,49.979952335357666,2.9086209767789284,1739137708.305334,49.979952335357666,1.4206578155224943 +1739137708.326009,49.99995231628418,33.24224924093999,1739137708.3260133,49.99995231628418,0.2790576336899253,1739137708.3260188,49.99995231628418,79.49537127008912,1739137708.3260238,49.99995231628418,27.608768518401856,1739137708.3260264,49.99995231628418,-0.045,1739137708.3260298,49.99995231628418,-3.0841324568016493,1739137708.3260326,49.99995231628418,1.5590145899246155,1739137708.3260353,49.99995231628418,0.6108,1739137708.3260376,49.99995231628418,1.3400204779580662,1739137708.3260407,49.99995231628418,0.0,1739137708.3260467,49.99995231628418,-0.025954950068569987,1739137708.3260498,49.99995231628418,2.9191272111323796,1739137708.3260524,49.99995231628418,1.4077191456522267 +1739137708.347297,50.02995228767395,33.24224924093999,1739137708.3473005,50.02995228767395,0.2790576336899253,1739137708.3473043,50.02995228767395,79.49537127008912,1739137708.3473084,50.02995228767395,27.608768518401856,1739137708.34731,50.02995228767395,-0.045,1739137708.3473125,50.02995228767395,-3.0841324568016493,1739137708.3473141,50.02995228767395,1.5590145899246155,1739137708.347316,50.02995228767395,0.6108,1739137708.3473177,50.02995228767395,1.3400204779580662,1739137708.3473196,50.02995228767395,0.0,1739137708.3473213,50.02995228767395,-0.06769866769416044,1739137708.3473234,50.02995228767395,2.9191272111323796,1739137708.347325,50.02995228767395,1.4077191456522267 +1739137708.3658605,50.03995227813721,33.24224924093999,1739137708.3658633,50.03995227813721,0.2790576336899253,1739137708.3658674,50.03995227813721,79.49537127008912,1739137708.3658712,50.03995227813721,27.608768518401856,1739137708.3658729,50.03995227813721,-0.045,1739137708.3658752,50.03995227813721,-3.0841324568016493,1739137708.3658772,50.03995227813721,1.5590145899246155,1739137708.365879,50.03995227813721,0.6108,1739137708.3658807,50.03995227813721,1.3400204779580662,1739137708.3658829,50.03995227813721,0.0,1739137708.3658893,50.03995227813721,-0.06769866769416044,1739137708.3658943,50.03995227813721,2.9191272111323796,1739137708.3658993,50.03995227813721,1.4077191456522267 +1739137708.3855124,50.05995225906372,33.24224924093999,1739137708.3855176,50.05995225906372,0.2790576336899253,1739137708.3855238,50.05995225906372,79.49537127008912,1739137708.3855295,50.05995225906372,27.608768518401856,1739137708.3855326,50.05995225906372,-0.045,1739137708.3855362,50.05995225906372,-3.0841324568016493,1739137708.3855398,50.05995225906372,1.5590145899246155,1739137708.3855429,50.05995225906372,0.6108,1739137708.3855462,50.05995225906372,1.3400204779580662,1739137708.38555,50.05995225906372,0.0,1739137708.3855531,50.05995225906372,-0.06769866769416044,1739137708.385557,50.05995225906372,2.9191272111323796,1739137708.3855603,50.05995225906372,1.4077191456522267 +1739137708.4050453,50.079952239990234,33.24224924093999,1739137708.40505,50.079952239990234,0.2790576336899253,1739137708.4050558,50.079952239990234,79.49537127008912,1739137708.4050615,50.079952239990234,27.608768518401856,1739137708.4050653,50.079952239990234,-0.045,1739137708.4050686,50.079952239990234,-3.0841324568016493,1739137708.4050713,50.079952239990234,1.5590145899246155,1739137708.4050741,50.079952239990234,0.6108,1739137708.4050767,50.079952239990234,1.3400204779580662,1739137708.40508,50.079952239990234,0.0,1739137708.405083,50.079952239990234,-0.06769866769416044,1739137708.405086,50.079952239990234,2.9191272111323796,1739137708.4050887,50.079952239990234,1.4077191456522267 +1739137708.4250064,50.09995222091675,33.24224924093999,1739137708.4250104,50.09995222091675,0.2790576336899253,1739137708.4250154,50.09995222091675,79.49537127008912,1739137708.4250202,50.09995222091675,27.608768518401856,1739137708.4250226,50.09995222091675,-0.045,1739137708.4250257,50.09995222091675,-3.0841324568016493,1739137708.4250283,50.09995222091675,1.5590145899246155,1739137708.425031,50.09995222091675,0.6108,1739137708.4250336,50.09995222091675,1.3400204779580662,1739137708.4250362,50.09995222091675,0.0,1739137708.4250388,50.09995222091675,-0.06769866769416044,1739137708.4250417,50.09995222091675,2.9191272111323796,1739137708.4250443,50.09995222091675,1.4077191456522267 +1739137708.4452672,50.11995220184326,33.091375441450765,1739137708.44527,50.11995220184326,0.312347189377161,1739137708.4452739,50.11995220184326,80.05177630702195,1739137708.4452767,50.11995220184326,27.07348661310775,1739137708.4452782,50.11995220184326,-0.04084078739188864,1739137708.4452803,50.11995220184326,-3.0829702185965893,1739137708.4452817,50.11995220184326,1.6030196402796886,1739137708.4452834,50.11995220184326,0.6108,1739137708.4452846,50.11995220184326,1.316639787872215,1739137708.445286,50.11995220184326,0.0,1739137708.4452877,50.11995220184326,-0.09890591095478349,1739137708.4452896,50.11995220184326,2.9310588311227193,1739137708.445291,50.11995220184326,1.4006850993746116 +1739137708.465064,50.139952182769775,33.091375441450765,1739137708.4650686,50.139952182769775,0.312347189377161,1739137708.465073,50.139952182769775,80.05177630702195,1739137708.4650774,50.139952182769775,27.07348661310775,1739137708.4650798,50.139952182769775,-0.04084078739188864,1739137708.4650831,50.139952182769775,-3.0829702185965893,1739137708.4650857,50.139952182769775,1.6030196402796886,1739137708.465088,50.139952182769775,0.6108,1739137708.4650903,50.139952182769775,1.316639787872215,1739137708.4650931,50.139952182769775,0.0,1739137708.4650958,50.139952182769775,-0.08404531150239669,1739137708.4650984,50.139952182769775,2.9310588311227193,1739137708.4651008,50.139952182769775,1.4006850993746116 +1739137708.485213,50.15995216369629,33.091375441450765,1739137708.4852176,50.15995216369629,0.312347189377161,1739137708.485222,50.15995216369629,80.05177630702195,1739137708.485227,50.15995216369629,27.07348661310775,1739137708.4852293,50.15995216369629,-0.04084078739188864,1739137708.4852324,50.15995216369629,-3.0829702185965893,1739137708.485235,50.15995216369629,1.6030196402796886,1739137708.4852376,50.15995216369629,0.6108,1739137708.4852397,50.15995216369629,1.316639787872215,1739137708.4852426,50.15995216369629,0.0,1739137708.4852452,50.15995216369629,-0.08404531150239669,1739137708.485248,50.15995216369629,2.9310588311227193,1739137708.4852507,50.15995216369629,1.4006850993746116 +1739137708.5074375,50.1799521446228,33.091375441450765,1739137708.5074418,50.1799521446228,0.312347189377161,1739137708.507447,50.1799521446228,80.05177630702195,1739137708.5074525,50.1799521446228,27.07348661310775,1739137708.5074556,50.1799521446228,-0.04084078739188864,1739137708.5074594,50.1799521446228,-3.0829702185965893,1739137708.5074632,50.1799521446228,1.6030196402796886,1739137708.5074666,50.1799521446228,0.6108,1739137708.5074701,50.1799521446228,1.316639787872215,1739137708.5074737,50.1799521446228,0.0,1739137708.5074775,50.1799521446228,-0.08404531150239669,1739137708.5074813,50.1799521446228,2.9310588311227193,1739137708.507485,50.1799521446228,1.4006850993746116 +1739137708.5269012,50.199952125549316,33.091375441450765,1739137708.526904,50.199952125549316,0.312347189377161,1739137708.5269072,50.199952125549316,80.05177630702195,1739137708.52691,50.199952125549316,27.07348661310775,1739137708.5269115,50.199952125549316,-0.04084078739188864,1739137708.5269132,50.199952125549316,-3.0829702185965893,1739137708.5269146,50.199952125549316,1.6030196402796886,1739137708.526916,50.199952125549316,0.6108,1739137708.5269172,50.199952125549316,1.316639787872215,1739137708.5269186,50.199952125549316,0.0,1739137708.5269198,50.199952125549316,-0.08404531150239669,1739137708.5269217,50.199952125549316,2.9310588311227193,1739137708.526923,50.199952125549316,1.4006850993746116 +1739137708.5469954,50.21995210647583,32.940946022220956,1739137708.5469995,50.21995210647583,0.34355859110000964,1739137708.5470045,50.21995210647583,80.07034154839066,1739137708.5470097,50.21995210647583,27.08198489469898,1739137708.5470128,50.21995210647583,-0.040918044497263446,1739137708.5470166,50.21995210647583,-3.076064624755763,1739137708.54702,50.21995210647583,1.524666255186415,1739137708.5470235,50.21995210647583,0.6108,1739137708.5470269,50.21995210647583,1.358558525325591,1739137708.5470307,50.21995210647583,0.0,1739137708.5470343,50.21995210647583,0.0132038786042104,1739137708.5470378,50.21995210647583,2.9444406429532584,1739137708.5470412,50.21995210647583,1.3916638080008332 +1739137708.567166,50.239952087402344,32.940946022220956,1739137708.5671713,50.239952087402344,0.34355859110000964,1739137708.5671763,50.239952087402344,80.07034154839066,1739137708.5671818,50.239952087402344,27.08198489469898,1739137708.567185,50.239952087402344,-0.040918044497263446,1739137708.5671887,50.239952087402344,-3.076064624755763,1739137708.5671926,50.239952087402344,1.524666255186415,1739137708.567196,50.239952087402344,0.6108,1739137708.5671995,50.239952087402344,1.358558525325591,1739137708.567203,50.239952087402344,0.0,1739137708.5672064,50.239952087402344,-0.033105282675242265,1739137708.5672102,50.239952087402344,2.9444406429532584,1739137708.5672135,50.239952087402344,1.3916638080008332 +1739137708.5869393,50.25995206832886,32.940946022220956,1739137708.5869443,50.25995206832886,0.34355859110000964,1739137708.5869493,50.25995206832886,80.07034154839066,1739137708.5869553,50.25995206832886,27.08198489469898,1739137708.5869582,50.25995206832886,-0.040918044497263446,1739137708.5869622,50.25995206832886,-3.076064624755763,1739137708.5869663,50.25995206832886,1.524666255186415,1739137708.5869699,50.25995206832886,0.6108,1739137708.5869734,50.25995206832886,1.358558525325591,1739137708.586977,50.25995206832886,0.0,1739137708.5869806,50.25995206832886,-0.033105282675242265,1739137708.5869842,50.25995206832886,2.9444406429532584,1739137708.5869877,50.25995206832886,1.3916638080008332 +1739137708.6050382,50.27995204925537,32.940946022220956,1739137708.6050417,50.27995204925537,0.34355859110000964,1739137708.605045,50.27995204925537,80.07034154839066,1739137708.6050482,50.27995204925537,27.08198489469898,1739137708.6050496,50.27995204925537,-0.040918044497263446,1739137708.6050513,50.27995204925537,-3.076064624755763,1739137708.605053,50.27995204925537,1.524666255186415,1739137708.6050544,50.27995204925537,0.6108,1739137708.6050558,50.27995204925537,1.358558525325591,1739137708.6050575,50.27995204925537,0.0,1739137708.605059,50.27995204925537,-0.033105282675242265,1739137708.6050603,50.27995204925537,2.9444406429532584,1739137708.6050613,50.27995204925537,1.3916638080008332 +1739137708.6268065,50.299952030181885,32.940946022220956,1739137708.6268108,50.299952030181885,0.34355859110000964,1739137708.6268368,50.299952030181885,80.07034154839066,1739137708.6268423,50.299952030181885,27.08198489469898,1739137708.6268451,50.299952030181885,-0.040918044497263446,1739137708.626849,50.299952030181885,-3.076064624755763,1739137708.6268523,50.299952030181885,1.524666255186415,1739137708.6268556,50.299952030181885,0.6108,1739137708.626859,50.299952030181885,1.358558525325591,1739137708.6268625,50.299952030181885,0.0,1739137708.6268659,50.299952030181885,-0.033105282675242265,1739137708.6268694,50.299952030181885,2.9444406429532584,1739137708.6268733,50.299952030181885,1.3916638080008332 +1739137708.6464648,50.3199520111084,32.940946022220956,1739137708.646487,50.3199520111084,0.34355859110000964,1739137708.6464946,50.3199520111084,80.07034154839066,1739137708.6465008,50.3199520111084,27.08198489469898,1739137708.6465225,50.3199520111084,-0.040918044497263446,1739137708.6465266,50.3199520111084,-3.076064624755763,1739137708.6465302,50.3199520111084,1.524666255186415,1739137708.6465337,50.3199520111084,0.6108,1739137708.646537,50.3199520111084,1.358558525325591,1739137708.6465406,50.3199520111084,0.0,1739137708.646544,50.3199520111084,-0.033105282675242265,1739137708.6465473,50.3199520111084,2.9444406429532584,1739137708.646551,50.3199520111084,1.3916638080008332 +1739137708.665688,50.34995198249817,32.79069032702662,1739137708.665691,50.34995198249817,0.3725372282999899,1739137708.665694,50.34995198249817,80.08888095617397,1739137708.6656969,50.34995198249817,27.070189583590597,1739137708.6656983,50.34995198249817,-0.04081081439627816,1739137708.6657002,50.34995198249817,-3.0694606975780103,1739137708.6657016,50.34995198249817,1.443533024622218,1739137708.6657028,50.34995198249817,0.6108,1739137708.6657043,50.34995198249817,1.4033714525931005,1739137708.6657064,50.34995198249817,0.0,1739137708.6657078,50.34995198249817,0.05673809790230305,1739137708.6657095,50.34995198249817,2.95930098205555,1739137708.665711,50.34995198249817,1.3894159382423505 +1739137708.68533,50.36995196342468,32.79069032702662,1739137708.685333,50.36995196342468,0.3725372282999899,1739137708.685336,50.36995196342468,80.08888095617397,1739137708.685339,50.36995196342468,27.070189583590597,1739137708.6853402,50.36995196342468,-0.04081081439627816,1739137708.6853418,50.36995196342468,-3.0694606975780103,1739137708.6853435,50.36995196342468,1.443533024622218,1739137708.685345,50.36995196342468,0.6108,1739137708.6853464,50.36995196342468,1.4033714525931005,1739137708.685348,50.36995196342468,0.0,1739137708.6853495,50.36995196342468,0.013955514350749931,1739137708.6853514,50.36995196342468,2.95930098205555,1739137708.685353,50.36995196342468,1.3894159382423505 +1739137708.7048476,50.37995195388794,32.79069032702662,1739137708.704851,50.37995195388794,0.3725372282999899,1739137708.704854,50.37995195388794,80.08888095617397,1739137708.7048573,50.37995195388794,27.070189583590597,1739137708.7048588,50.37995195388794,-0.04081081439627816,1739137708.704861,50.37995195388794,-3.0694606975780103,1739137708.704863,50.37995195388794,1.443533024622218,1739137708.704865,50.37995195388794,0.6108,1739137708.7048666,50.37995195388794,1.4033714525931005,1739137708.7048683,50.37995195388794,0.0,1739137708.7048702,50.37995195388794,0.013955514350749931,1739137708.704872,50.37995195388794,2.95930098205555,1739137708.7048736,50.37995195388794,1.3894159382423505 +1739137708.72604,50.39995193481445,32.79069032702662,1739137708.7260442,50.39995193481445,0.3725372282999899,1739137708.7260492,50.39995193481445,80.08888095617397,1739137708.7260547,50.39995193481445,27.070189583590597,1739137708.7260575,50.39995193481445,-0.04081081439627816,1739137708.7260613,50.39995193481445,-3.0694606975780103,1739137708.726065,50.39995193481445,1.443533024622218,1739137708.7260683,50.39995193481445,0.6108,1739137708.726072,50.39995193481445,1.4033714525931005,1739137708.7260756,50.39995193481445,0.0,1739137708.7260792,50.39995193481445,0.013955514350749931,1739137708.726083,50.39995193481445,2.95930098205555,1739137708.7260866,50.39995193481445,1.3894159382423505 +1739137708.7462556,50.41995191574097,32.79069032702662,1739137708.7462595,50.41995191574097,0.3725372282999899,1739137708.7462645,50.41995191574097,80.08888095617397,1739137708.74627,50.41995191574097,27.070189583590597,1739137708.746273,50.41995191574097,-0.04081081439627816,1739137708.7462769,50.41995191574097,-3.0694606975780103,1739137708.7462802,50.41995191574097,1.443533024622218,1739137708.7462838,50.41995191574097,0.6108,1739137708.746287,50.41995191574097,1.4033714525931005,1739137708.7462907,50.41995191574097,0.0,1739137708.746294,50.41995191574097,0.013955514350749931,1739137708.7462976,50.41995191574097,2.95930098205555,1739137708.7463012,50.41995191574097,1.3894159382423505 +1739137708.7662334,50.43995189666748,32.6401388758025,1739137708.7662377,50.43995189666748,0.3991520890022553,1739137708.7662427,50.43995189666748,80.10745201439593,1739137708.7662482,50.43995189666748,27.047272441014414,1739137708.766251,50.43995189666748,-0.04060247673649467,1739137708.766255,50.43995189666748,-3.0631263282307337,1739137708.7662585,50.43995189666748,1.3574356053653125,1739137708.7662618,50.43995189666748,0.6108,1739137708.7662654,50.43995189666748,1.4525439823427955,1739137708.766269,50.43995189666748,0.0,1739137708.7662723,50.43995189666748,0.10506409258736871,1739137708.766276,50.43995189666748,2.97567196418474,1739137708.7662792,50.43995189666748,1.390864948683692 +1739137708.78608,50.459951877593994,32.6401388758025,1739137708.786084,50.459951877593994,0.3991520890022553,1739137708.7860885,50.459951877593994,80.10745201439593,1739137708.7860937,50.459951877593994,27.047272441014414,1739137708.7860968,50.459951877593994,-0.04060247673649467,1739137708.7861004,50.459951877593994,-3.0631263282307337,1739137708.786104,50.459951877593994,1.3574356053653125,1739137708.7861075,50.459951877593994,0.6108,1739137708.7861109,50.459951877593994,1.4525439823427955,1739137708.7861145,50.459951877593994,0.0,1739137708.7861178,50.459951877593994,0.061679033659103544,1739137708.7861218,50.459951877593994,2.97567196418474,1739137708.786125,50.459951877593994,1.390864948683692 +1739137708.80631,50.47995185852051,32.6401388758025,1739137708.8063138,50.47995185852051,0.3991520890022553,1739137708.8063185,50.47995185852051,80.10745201439593,1739137708.806324,50.47995185852051,27.047272441014414,1739137708.8063269,50.47995185852051,-0.04060247673649467,1739137708.8063312,50.47995185852051,-3.0631263282307337,1739137708.8063347,50.47995185852051,1.3574356053653125,1739137708.8063383,50.47995185852051,0.6108,1739137708.8063416,50.47995185852051,1.4525439823427955,1739137708.806345,50.47995185852051,0.0,1739137708.8063483,50.47995185852051,0.061679033659103544,1739137708.806352,50.47995185852051,2.97567196418474,1739137708.8063552,50.47995185852051,1.390864948683692 +1739137708.8262503,50.49995183944702,32.6401388758025,1739137708.826254,50.49995183944702,0.3991520890022553,1739137708.826258,50.49995183944702,80.10745201439593,1739137708.826263,50.49995183944702,27.047272441014414,1739137708.8262656,50.49995183944702,-0.04060247673649467,1739137708.8262694,50.49995183944702,-3.0631263282307337,1739137708.8262725,50.49995183944702,1.3574356053653125,1739137708.8262968,50.49995183944702,0.6108,1739137708.8263001,50.49995183944702,1.4525439823427955,1739137708.8263037,50.49995183944702,0.0,1739137708.826307,50.49995183944702,0.061679033659103544,1739137708.8263106,50.49995183944702,2.97567196418474,1739137708.826314,50.49995183944702,1.390864948683692 +1739137708.8466113,50.519951820373535,32.6401388758025,1739137708.8466153,50.519951820373535,0.3991520890022553,1739137708.846619,50.519951820373535,80.10745201439593,1739137708.8466218,50.519951820373535,27.047272441014414,1739137708.846623,50.519951820373535,-0.04060247673649467,1739137708.846625,50.519951820373535,-3.0631263282307337,1739137708.8466263,50.519951820373535,1.3574356053653125,1739137708.846628,50.519951820373535,0.6108,1739137708.8466291,50.519951820373535,1.4525439823427955,1739137708.8466308,50.519951820373535,0.0,1739137708.8466325,50.519951820373535,0.061679033659103544,1739137708.846634,50.519951820373535,2.97567196418474,1739137708.8466353,50.519951820373535,1.390864948683692 +1739137708.8660395,50.549951791763306,32.48863361434647,1739137708.8660429,50.549951791763306,0.42327526268131166,1739137708.8660464,50.549951791763306,80.12613540790238,1739137708.8660495,50.549951791763306,27.00573183291527,1739137708.8660507,50.549951791763306,-0.04022483484468425,1739137708.8660526,50.549951791763306,-3.0572576191789866,1739137708.866054,50.549951791763306,1.2669588005326515,1739137708.8660555,50.549951791763306,0.6108,1739137708.866057,50.549951791763306,1.5060754258075217,1739137708.8660586,50.549951791763306,0.0,1739137708.8660598,50.549951791763306,0.149328873007263,1739137708.8660614,50.549951791763306,2.9935897784763044,1739137708.866063,50.549951791763306,1.3984845923874518 +1739137708.886983,50.55995178222656,32.48863361434647,1739137708.886987,50.55995178222656,0.42327526268131166,1739137708.8869915,50.55995178222656,80.12613540790238,1739137708.8869967,50.55995178222656,27.00573183291527,1739137708.8869996,50.55995178222656,-0.04022483484468425,1739137708.8870034,50.55995178222656,-3.0572576191789866,1739137708.8870068,50.55995178222656,1.2669588005326515,1739137708.8870103,50.55995178222656,0.6108,1739137708.8870137,50.55995178222656,1.5060754258075217,1739137708.887017,50.55995178222656,0.0,1739137708.8870203,50.55995178222656,0.10759083342006992,1739137708.887024,50.55995178222656,2.9935897784763044,1739137708.8870273,50.55995178222656,1.3984845923874518 +1739137708.906328,50.579951763153076,32.48863361434647,1739137708.9063325,50.579951763153076,0.42327526268131166,1739137708.906337,50.579951763153076,80.12613540790238,1739137708.9063425,50.579951763153076,27.00573183291527,1739137708.9063451,50.579951763153076,-0.04022483484468425,1739137708.9063494,50.579951763153076,-3.0572576191789866,1739137708.9063528,50.579951763153076,1.2669588005326515,1739137708.9063563,50.579951763153076,0.6108,1739137708.9063594,50.579951763153076,1.5060754258075217,1739137708.9063632,50.579951763153076,0.0,1739137708.9063663,50.579951763153076,0.10759083342006992,1739137708.9063704,50.579951763153076,2.9935897784763044,1739137708.906374,50.579951763153076,1.3984845923874518 +1739137708.926295,50.59995174407959,32.48863361434647,1739137708.926299,50.59995174407959,0.42327526268131166,1739137708.9263046,50.59995174407959,80.12613540790238,1739137708.9263098,50.59995174407959,27.00573183291527,1739137708.926313,50.59995174407959,-0.04022483484468425,1739137708.926317,50.59995174407959,-3.0572576191789866,1739137708.9263203,50.59995174407959,1.2669588005326515,1739137708.9263237,50.59995174407959,0.6108,1739137708.926327,50.59995174407959,1.5060754258075217,1739137708.926331,50.59995174407959,0.0,1739137708.9263344,50.59995174407959,0.10759083342006992,1739137708.926338,50.59995174407959,2.9935897784763044,1739137708.9263415,50.59995174407959,1.3984845923874518 +1739137708.946449,50.6199517250061,32.48863361434647,1739137708.9464533,50.6199517250061,0.42327526268131166,1739137708.946458,50.6199517250061,80.12613540790238,1739137708.9464636,50.6199517250061,27.00573183291527,1739137708.9464664,50.6199517250061,-0.04022483484468425,1739137708.9464881,50.6199517250061,-3.0572576191789866,1739137708.946492,50.6199517250061,1.2669588005326515,1739137708.9464955,50.6199517250061,0.6108,1739137708.9464989,50.6199517250061,1.5060754258075217,1739137708.9465032,50.6199517250061,0.0,1739137708.9465065,50.6199517250061,0.10759083342006992,1739137708.946511,50.6199517250061,2.9935897784763044,1739137708.9465146,50.6199517250061,1.3984845923874518 +1739137708.9661508,50.63995170593262,32.48863361434647,1739137708.9661546,50.63995170593262,0.42327526268131166,1739137708.9661593,50.63995170593262,80.12613540790238,1739137708.9661646,50.63995170593262,27.00573183291527,1739137708.9661672,50.63995170593262,-0.04022483484468425,1739137708.9661708,50.63995170593262,-3.0572576191789866,1739137708.9661741,50.63995170593262,1.2669588005326515,1739137708.9661775,50.63995170593262,0.6108,1739137708.966181,50.63995170593262,1.5060754258075217,1739137708.9661844,50.63995170593262,0.0,1739137708.9661877,50.63995170593262,0.10759083342006992,1739137708.9661915,50.63995170593262,2.9935897784763044,1739137708.9661946,50.63995170593262,1.3984845923874518 +1739137708.9864469,50.65995168685913,32.335628941779476,1739137708.9864504,50.65995168685913,0.4447208416334707,1739137708.986455,50.65995168685913,80.14499787378601,1739137708.9864602,50.65995168685913,26.949019173480128,1739137708.9864633,50.65995168685913,-0.039711884445766905,1739137708.986467,50.65995168685913,-3.0519011716922138,1739137708.9865036,50.65995168685913,1.1707021707127765,1739137708.9865072,50.65995168685913,0.6063690059450051,1739137708.9865105,50.65995168685913,1.5651941340090956,1739137708.986514,50.65995168685913,0.0,1739137708.9865177,50.65995168685913,0.19636589911228228,1739137708.9865246,50.65995168685913,3.0130950284481797,1739137708.9865282,50.65995168685913,1.4111020968202697 +1739137709.0067153,50.679951667785645,32.335628941779476,1739137709.0067225,50.679951667785645,0.4447208416334707,1739137709.00673,50.679951667785645,80.14499787378601,1739137709.0067353,50.679951667785645,26.949019173480128,1739137709.0067384,50.679951667785645,-0.039711884445766905,1739137709.006744,50.679951667785645,-3.0519011716922138,1739137709.0067482,50.679951667785645,1.1707021707127765,1739137709.0067518,50.679951667785645,0.6063690059450051,1739137709.0067554,50.679951667785645,1.5651941340090956,1739137709.0067604,50.679951667785645,0.0,1739137709.0067642,50.679951667785645,0.15409203718882591,1739137709.0067687,50.679951667785645,3.0130950284481797,1739137709.0067728,50.679951667785645,1.4111020968202697 +1739137709.0263257,50.69995164871216,32.335628941779476,1739137709.0263295,50.69995164871216,0.4447208416334707,1739137709.0263343,50.69995164871216,80.14499787378601,1739137709.0263393,50.69995164871216,26.949019173480128,1739137709.0263422,50.69995164871216,-0.039711884445766905,1739137709.026346,50.69995164871216,-3.0519011716922138,1739137709.0263493,50.69995164871216,1.1707021707127765,1739137709.0263526,50.69995164871216,0.6063690059450051,1739137709.0263557,50.69995164871216,1.5651941340090956,1739137709.0263593,50.69995164871216,0.0,1739137709.0263627,50.69995164871216,0.15409203718882591,1739137709.0263877,50.69995164871216,3.0130950284481797,1739137709.026391,50.69995164871216,1.4111020968202697 +1739137709.0451317,50.71995162963867,32.335628941779476,1739137709.0451348,50.71995162963867,0.4447208416334707,1739137709.0451381,50.71995162963867,80.14499787378601,1739137709.0451407,50.71995162963867,26.949019173480128,1739137709.0451422,50.71995162963867,-0.039711884445766905,1739137709.045144,50.71995162963867,-3.0519011716922138,1739137709.0451453,50.71995162963867,1.1707021707127765,1739137709.0451467,50.71995162963867,0.6063690059450051,1739137709.045148,50.71995162963867,1.5651941340090956,1739137709.0451498,50.71995162963867,0.0,1739137709.0451512,50.71995162963867,0.15409203718882591,1739137709.0451524,50.71995162963867,3.0130950284481797,1739137709.045154,50.71995162963867,1.4111020968202697 +1739137709.066652,50.739951610565186,32.335628941779476,1739137709.066655,50.739951610565186,0.4447208416334707,1739137709.066658,50.739951610565186,80.14499787378601,1739137709.066661,50.739951610565186,26.949019173480128,1739137709.066662,50.739951610565186,-0.039711884445766905,1739137709.0666637,50.739951610565186,-3.0519011716922138,1739137709.0666652,50.739951610565186,1.1707021707127765,1739137709.0666666,50.739951610565186,0.6063690059450051,1739137709.0666678,50.739951610565186,1.5651941340090956,1739137709.0666692,50.739951610565186,0.0,1739137709.0666707,50.739951610565186,0.15409203718882591,1739137709.066672,50.739951610565186,3.0130950284481797,1739137709.0666735,50.739951610565186,1.4111020968202697 +1739137709.0904462,50.7599515914917,32.335628941779476,1739137709.0904553,50.7599515914917,0.4447208416334707,1739137709.0904655,50.7599515914917,80.14499787378601,1739137709.0905144,50.7599515914917,26.949019173480128,1739137709.0905287,50.7599515914917,-0.039711884445766905,1739137709.090547,50.7599515914917,-3.0519011716922138,1739137709.0905561,50.7599515914917,1.1707021707127765,1739137709.0905666,50.7599515914917,0.6063690059450051,1739137709.0905807,50.7599515914917,1.5651941340090956,1739137709.090593,50.7599515914917,0.0,1739137709.0906017,50.7599515914917,0.15409203718882591,1739137709.0906186,50.7599515914917,3.0130950284481797,1739137709.0906315,50.7599515914917,1.4111020968202697 +1739137709.113597,50.77995157241821,32.18058938107474,1739137709.1136045,50.77995157241821,0.4632590356430999,1739137709.1136138,50.77995157241821,80.70799302576101,1739137709.1136243,50.77995157241821,26.33288042793796,1739137709.1136303,50.77995157241821,-0.03419363210564565,1739137709.1136374,50.77995157241821,-3.056729007548376,1739137709.1136441,50.77995157241821,1.1212074157456962,1739137709.1136513,50.77995157241821,0.49545073076346596,1739137709.1136577,50.77995157241821,1.5964904727600993,1739137709.1136646,50.77995157241821,0.0,1739137709.113671,50.77995157241821,0.18000460410701305,1739137709.113678,50.77995157241821,3.0342301938252714,1739137709.1136844,50.77995157241821,1.4288251923972066 +1739137709.1306515,50.79995155334473,32.18058938107474,1739137709.1306558,50.79995155334473,0.4632590356430999,1739137709.1306615,50.79995155334473,80.70799302576101,1739137709.1306674,50.79995155334473,26.33288042793796,1739137709.1306708,50.79995155334473,-0.03419363210564565,1739137709.1306756,50.79995155334473,-3.056729007548376,1739137709.1306796,50.79995155334473,1.1212074157456962,1739137709.1306837,50.79995155334473,0.49545073076346596,1739137709.1306877,50.79995155334473,1.5964904727600993,1739137709.1306918,50.79995155334473,0.0,1739137709.1306956,50.79995155334473,0.16766528036289263,1739137709.1307,50.79995155334473,3.0342301938252714,1739137709.130704,50.79995155334473,1.4288251923972066 +1739137709.1496172,50.81995153427124,32.18058938107474,1739137709.149621,50.81995153427124,0.4632590356430999,1739137709.1496267,50.81995153427124,80.70799302576101,1739137709.149632,50.81995153427124,26.33288042793796,1739137709.1496348,50.81995153427124,-0.03419363210564565,1739137709.149639,50.81995153427124,-3.056729007548376,1739137709.1496425,50.81995153427124,1.1212074157456962,1739137709.1496458,50.81995153427124,0.49545073076346596,1739137709.1496491,50.81995153427124,1.5964904727600993,1739137709.1496527,50.81995153427124,0.0,1739137709.149656,50.81995153427124,0.16766528036289263,1739137709.1496596,50.81995153427124,3.0342301938252714,1739137709.149663,50.81995153427124,1.4288251923972066 +1739137709.1707757,50.839951515197754,32.18058938107474,1739137709.1707802,50.839951515197754,0.4632590356430999,1739137709.1707854,50.839951515197754,80.70799302576101,1739137709.170789,50.839951515197754,26.33288042793796,1739137709.1707911,50.839951515197754,-0.03419363210564565,1739137709.1707938,50.839951515197754,-3.056729007548376,1739137709.170797,50.839951515197754,1.1212074157456962,1739137709.170799,50.839951515197754,0.49545073076346596,1739137709.1708012,50.839951515197754,1.5964904727600993,1739137709.1708033,50.839951515197754,0.0,1739137709.1708057,50.839951515197754,0.16766528036289263,1739137709.1708083,50.839951515197754,3.0342301938252714,1739137709.1708105,50.839951515197754,1.4288251923972066 +1739137709.1902444,50.85995149612427,32.18058938107474,1739137709.1902487,50.85995149612427,0.4632590356430999,1739137709.190254,50.85995149612427,80.70799302576101,1739137709.19026,50.85995149612427,26.33288042793796,1739137709.190263,50.85995149612427,-0.03419363210564565,1739137709.190267,50.85995149612427,-3.056729007548376,1739137709.1902707,50.85995149612427,1.1212074157456962,1739137709.1902745,50.85995149612427,0.49545073076346596,1739137709.1902778,50.85995149612427,1.5964904727600993,1739137709.1902816,50.85995149612427,0.0,1739137709.1902852,50.85995149612427,0.16766528036289263,1739137709.1902895,50.85995149612427,3.0342301938252714,1739137709.1902928,50.85995149612427,1.4288251923972066 +1739137709.210315,50.87995147705078,32.02324303937578,1739137709.2103188,50.87995147705078,0.4786115031543954,1739137709.2103236,50.87995147705078,80.72769202340841,1739137709.210329,50.87995147705078,26.257779999437098,1739137709.210332,50.87995147705078,-0.03395532608389728,1739137709.2103357,50.87995147705078,-3.0529227938622245,1739137709.210339,50.87995147705078,1.0012312860873895,1739137709.2103424,50.87995147705078,0.4554942372178137,1739137709.210346,50.87995147705078,1.674974962558762,1739137709.2103493,50.87995147705078,0.0,1739137709.210353,50.87995147705078,0.2822432799136726,1739137709.2103567,50.87995147705078,3.0564101364661527,1739137709.21036,50.87995147705078,1.4472926620677204 +1739137709.229493,50.899951457977295,32.02324303937578,1739137709.2294974,50.899951457977295,0.4786115031543954,1739137709.229502,50.899951457977295,80.72769202340841,1739137709.2295074,50.899951457977295,26.257779999437098,1739137709.2295103,50.899951457977295,-0.03395532608389728,1739137709.2295141,50.899951457977295,-3.0529227938622245,1739137709.2295175,50.899951457977295,1.0012312860873895,1739137709.229521,50.899951457977295,0.4554942372178137,1739137709.2295244,50.899951457977295,1.674974962558762,1739137709.2295284,50.899951457977295,0.0,1739137709.2295318,50.899951457977295,0.22768230049104154,1739137709.2295353,50.899951457977295,3.0564101364661527,1739137709.2295394,50.899951457977295,1.4472926620677204 +1739137709.249157,50.91995143890381,32.02324303937578,1739137709.2491622,50.91995143890381,0.4786115031543954,1739137709.2491682,50.91995143890381,80.72769202340841,1739137709.2491736,50.91995143890381,26.257779999437098,1739137709.2491765,50.91995143890381,-0.03395532608389728,1739137709.249181,50.91995143890381,-3.0529227938622245,1739137709.2491844,50.91995143890381,1.0012312860873895,1739137709.249189,50.91995143890381,0.4554942372178137,1739137709.2491922,50.91995143890381,1.674974962558762,1739137709.249196,50.91995143890381,0.0,1739137709.2491987,50.91995143890381,0.22768230049104154,1739137709.2492018,50.91995143890381,3.0564101364661527,1739137709.2492042,50.91995143890381,1.4472926620677204 +1739137709.2697752,50.93995141983032,32.02324303937578,1739137709.26978,50.93995141983032,0.4786115031543954,1739137709.2697856,50.93995141983032,80.72769202340841,1739137709.2697918,50.93995141983032,26.257779999437098,1739137709.2697954,50.93995141983032,-0.03395532608389728,1739137709.2697992,50.93995141983032,-3.0529227938622245,1739137709.2698016,50.93995141983032,1.0012312860873895,1739137709.2698045,50.93995141983032,0.4554942372178137,1739137709.2698073,50.93995141983032,1.674974962558762,1739137709.2698107,50.93995141983032,0.0,1739137709.269815,50.93995141983032,0.22768230049104154,1739137709.2698174,50.93995141983032,3.0564101364661527,1739137709.2698207,50.93995141983032,1.4472926620677204 +1739137709.2899375,50.959951400756836,32.02324303937578,1739137709.2899408,50.959951400756836,0.4786115031543954,1739137709.2899454,50.959951400756836,80.72769202340841,1739137709.2899504,50.959951400756836,26.257779999437098,1739137709.2899532,50.959951400756836,-0.03395532608389728,1739137709.289957,50.959951400756836,-3.0529227938622245,1739137709.2899604,50.959951400756836,1.0012312860873895,1739137709.2899637,50.959951400756836,0.4554942372178137,1739137709.2899668,50.959951400756836,1.674974962558762,1739137709.2899704,50.959951400756836,0.0,1739137709.2899735,50.959951400756836,0.22768230049104154,1739137709.289977,50.959951400756836,3.0564101364661527,1739137709.2899806,50.959951400756836,1.4472926620677204 +1739137709.3077254,50.97995138168335,32.02324303937578,1739137709.3077278,50.97995138168335,0.4786115031543954,1739137709.3077304,50.97995138168335,80.72769202340841,1739137709.3077333,50.97995138168335,26.257779999437098,1739137709.3077345,50.97995138168335,-0.03395532608389728,1739137709.3077526,50.97995138168335,-3.0529227938622245,1739137709.3077543,50.97995138168335,1.0012312860873895,1739137709.3077552,50.97995138168335,0.4554942372178137,1739137709.3077567,50.97995138168335,1.674974962558762,1739137709.307758,50.97995138168335,0.0,1739137709.3077593,50.97995138168335,0.22768230049104154,1739137709.3077607,50.97995138168335,3.0564101364661527,1739137709.307762,50.97995138168335,1.4472926620677204 +1739137709.327813,50.99995136260986,31.863143596784987,1739137709.3278148,50.99995136260986,0.4906515243035372,1739137709.3278174,50.99995136260986,80.74772853377456,1739137709.3278198,50.99995136260986,26.159657147187854,1739137709.327821,50.99995136260986,-0.033422049712977464,1739137709.3278227,50.99995136260986,-3.049963425649368,1739137709.327824,50.99995136260986,0.8820518379322575,1739137709.327825,50.99995136260986,0.4104230280472999,1739137709.3278263,50.99995136260986,1.756757880114942,1739137709.327828,50.99995136260986,0.0,1739137709.327829,50.99995136260986,0.33412114262175246,1739137709.3278306,50.99995136260986,3.078603973170045,1739137709.3278315,50.99995136260986,1.4733219257320416 +1739137709.3482249,51.01995134353638,31.863143596784987,1739137709.3482273,51.01995134353638,0.4906515243035372,1739137709.34823,51.01995134353638,80.74772853377456,1739137709.3482325,51.01995134353638,26.159657147187854,1739137709.3482337,51.01995134353638,-0.033422049712977464,1739137709.3482356,51.01995134353638,-3.049963425649368,1739137709.3482368,51.01995134353638,0.8820518379322575,1739137709.348238,51.01995134353638,0.4104230280472999,1739137709.3482394,51.01995134353638,1.756757880114942,1739137709.3482409,51.01995134353638,0.0,1739137709.3482423,51.01995134353638,0.28343595438290037,1739137709.3482435,51.01995134353638,3.078603973170045,1739137709.3482447,51.01995134353638,1.4733219257320416 +1739137709.3679574,51.03995132446289,31.863143596784987,1739137709.3679593,51.03995132446289,0.4906515243035372,1739137709.3679621,51.03995132446289,80.74772853377456,1739137709.3679647,51.03995132446289,26.159657147187854,1739137709.367966,51.03995132446289,-0.033422049712977464,1739137709.3679678,51.03995132446289,-3.049963425649368,1739137709.367969,51.03995132446289,0.8820518379322575,1739137709.3679702,51.03995132446289,0.4104230280472999,1739137709.3679714,51.03995132446289,1.756757880114942,1739137709.3679729,51.03995132446289,0.0,1739137709.367974,51.03995132446289,0.28343595438290037,1739137709.3679757,51.03995132446289,3.078603973170045,1739137709.367977,51.03995132446289,1.4733219257320416 +1739137709.3878205,51.059951305389404,31.863143596784987,1739137709.3878229,51.059951305389404,0.4906515243035372,1739137709.3878253,51.059951305389404,80.74772853377456,1739137709.3878276,51.059951305389404,26.159657147187854,1739137709.387829,51.059951305389404,-0.033422049712977464,1739137709.3878305,51.059951305389404,-3.049963425649368,1739137709.387832,51.059951305389404,0.8820518379322575,1739137709.387833,51.059951305389404,0.4104230280472999,1739137709.387834,51.059951305389404,1.756757880114942,1739137709.3878357,51.059951305389404,0.0,1739137709.387837,51.059951305389404,0.28343595438290037,1739137709.3878381,51.059951305389404,3.078603973170045,1739137709.3878396,51.059951305389404,1.4733219257320416 +1739137709.407722,51.07995128631592,31.863143596784987,1739137709.4077241,51.07995128631592,0.4906515243035372,1739137709.4077268,51.07995128631592,80.74772853377456,1739137709.4077291,51.07995128631592,26.159657147187854,1739137709.4077303,51.07995128631592,-0.033422049712977464,1739137709.4077322,51.07995128631592,-3.049963425649368,1739137709.4077334,51.07995128631592,0.8820518379322575,1739137709.4077349,51.07995128631592,0.4104230280472999,1739137709.4077358,51.07995128631592,1.756757880114942,1739137709.4077373,51.07995128631592,0.0,1739137709.4077384,51.07995128631592,0.28343595438290037,1739137709.4077399,51.07995128631592,3.078603973170045,1739137709.407741,51.07995128631592,1.4733219257320416 +1739137709.4278028,51.09995126724243,31.69972760846231,1739137709.4278052,51.09995126724243,0.4993192169416858,1739137709.4278078,51.09995126724243,80.76817286770017,1739137709.4278102,51.09995126724243,26.044753265030295,1739137709.4278116,51.09995126724243,-0.032681651837865755,1739137709.427813,51.09995126724243,-3.0477921085803636,1739137709.4278145,51.09995126724243,0.7651736861603022,1739137709.4278157,51.09995126724243,0.3625283372547309,1739137709.4278166,51.09995126724243,1.8408386529186138,1739137709.427818,51.09995126724243,0.0,1739137709.4278193,51.09995126724243,0.383841621810348,1739137709.4278207,51.09995126724243,3.100267349617838,1739137709.4278219,51.09995126724243,1.5048092775770707 +1739137709.4479036,51.119951248168945,31.69972760846231,1739137709.447906,51.119951248168945,0.4993192169416858,1739137709.4479086,51.119951248168945,80.76817286770017,1739137709.4479113,51.119951248168945,26.044753265030295,1739137709.4479125,51.119951248168945,-0.032681651837865755,1739137709.447914,51.119951248168945,-3.0477921085803636,1739137709.4479153,51.119951248168945,0.7651736861603022,1739137709.4479165,51.119951248168945,0.3625283372547309,1739137709.447918,51.119951248168945,1.8408386529186138,1739137709.4479191,51.119951248168945,0.0,1739137709.4479203,51.119951248168945,0.3360293753415431,1739137709.4479218,51.119951248168945,3.100267349617838,1739137709.4479232,51.119951248168945,1.5048092775770707 +1739137709.468592,51.13995122909546,31.69972760846231,1739137709.4685946,51.13995122909546,0.4993192169416858,1739137709.4685972,51.13995122909546,80.76817286770017,1739137709.4686,51.13995122909546,26.044753265030295,1739137709.4686012,51.13995122909546,-0.032681651837865755,1739137709.468603,51.13995122909546,-3.0477921085803636,1739137709.4686043,51.13995122909546,0.7651736861603022,1739137709.4686055,51.13995122909546,0.3625283372547309,1739137709.4686067,51.13995122909546,1.8408386529186138,1739137709.4686081,51.13995122909546,0.0,1739137709.4686093,51.13995122909546,0.3360293753415431,1739137709.4686105,51.13995122909546,3.100267349617838,1739137709.468612,51.13995122909546,1.5048092775770707 +1739137709.487787,51.15995121002197,31.69972760846231,1739137709.4877896,51.15995121002197,0.4993192169416858,1739137709.487792,51.15995121002197,80.76817286770017,1739137709.4877946,51.15995121002197,26.044753265030295,1739137709.4877963,51.15995121002197,-0.032681651837865755,1739137709.4877977,51.15995121002197,-3.0477921085803636,1739137709.4877994,51.15995121002197,0.7651736861603022,1739137709.4878006,51.15995121002197,0.3625283372547309,1739137709.4878018,51.15995121002197,1.8408386529186138,1739137709.4878035,51.15995121002197,0.0,1739137709.487805,51.15995121002197,0.3360293753415431,1739137709.4878063,51.15995121002197,3.100267349617838,1739137709.4878075,51.15995121002197,1.5048092775770707 +1739137709.5075603,51.179951190948486,31.69972760846231,1739137709.5075626,51.179951190948486,0.4993192169416858,1739137709.5075655,51.179951190948486,80.76817286770017,1739137709.5075686,51.179951190948486,26.044753265030295,1739137709.5075703,51.179951190948486,-0.032681651837865755,1739137709.5075717,51.179951190948486,-3.0477921085803636,1739137709.5075734,51.179951190948486,0.7651736861603022,1739137709.5075748,51.179951190948486,0.3625283372547309,1739137709.507576,51.179951190948486,1.8408386529186138,1739137709.5075777,51.179951190948486,0.0,1739137709.507579,51.179951190948486,0.3360293753415431,1739137709.5075808,51.179951190948486,3.100267349617838,1739137709.507582,51.179951190948486,1.5048092775770707 +1739137709.5299904,51.199951171875,31.69972760846231,1739137709.529995,51.199951171875,0.4993192169416858,1739137709.5300007,51.199951171875,80.76817286770017,1739137709.5300076,51.199951171875,26.044753265030295,1739137709.5300114,51.199951171875,-0.032681651837865755,1739137709.5300162,51.199951171875,-3.0477921085803636,1739137709.5300207,51.199951171875,0.7651736861603022,1739137709.530025,51.199951171875,0.3625283372547309,1739137709.5300293,51.199951171875,1.8408386529186138,1739137709.5300338,51.199951171875,0.0,1739137709.5300384,51.199951171875,0.3360293753415431,1739137709.530043,51.199951171875,3.100267349617838,1739137709.5300472,51.199951171875,1.5048092775770707 +1739137709.548478,51.219951152801514,31.532352665134773,1739137709.5484807,51.219951152801514,0.5046685991912243,1739137709.5484843,51.219951152801514,81.43967294419683,1739137709.5484881,51.219951152801514,25.25998540831542,1739137709.5484898,51.219951152801514,-0.026965391450994986,1739137709.548492,51.219951152801514,-3.0570366393632598,1739137709.5484939,51.219951152801514,0.6634365818953059,1739137709.5484953,51.219951152801514,0.2565419892477343,1739137709.5484972,51.219951152801514,1.917296458316524,1739137709.5484989,51.219951152801514,0.0,1739137709.5485008,51.219951152801514,0.40989924424403323,1739137709.5485024,51.219951152801514,3.1205591412237306,1739137709.548504,51.219951152801514,1.542573359693317 +1739137709.579343,51.23995113372803,31.532352665134773,1739137709.5793512,51.23995113372803,0.5046685991912243,1739137709.579361,51.23995113372803,81.43967294419683,1739137709.5793707,51.23995113372803,25.25998540831542,1739137709.579375,51.23995113372803,-0.026965391450994986,1739137709.579381,51.23995113372803,-3.0570366393632598,1739137709.5793858,51.23995113372803,0.6634365818953059,1739137709.5793905,51.23995113372803,0.2565419892477343,1739137709.579395,51.23995113372803,1.917296458316524,1739137709.5794005,51.23995113372803,0.0,1739137709.5794053,51.23995113372803,0.37472309862320685,1739137709.5794103,51.23995113372803,3.1205591412237306,1739137709.579415,51.23995113372803,1.542573359693317 +1739137709.5972178,51.25995111465454,31.532352665134773,1739137709.5972261,51.25995111465454,0.5046685991912243,1739137709.5972357,51.25995111465454,81.43967294419683,1739137709.597245,51.25995111465454,25.25998540831542,1739137709.5972497,51.25995111465454,-0.026965391450994986,1739137709.5972557,51.25995111465454,-3.0570366393632598,1739137709.5972605,51.25995111465454,0.6634365818953059,1739137709.5972652,51.25995111465454,0.2565419892477343,1739137709.5972695,51.25995111465454,1.917296458316524,1739137709.5972757,51.25995111465454,0.0,1739137709.5972803,51.25995111465454,0.37472309862320685,1739137709.5972857,51.25995111465454,3.1205591412237306,1739137709.5972903,51.25995111465454,1.542573359693317 +1739137709.619126,51.279951095581055,31.532352665134773,1739137709.6191344,51.279951095581055,0.5046685991912243,1739137709.6191442,51.279951095581055,81.43967294419683,1739137709.6191545,51.279951095581055,25.25998540831542,1739137709.619159,51.279951095581055,-0.026965391450994986,1739137709.6191652,51.279951095581055,-3.0570366393632598,1739137709.6191702,51.279951095581055,0.6634365818953059,1739137709.619175,51.279951095581055,0.2565419892477343,1739137709.6191792,51.279951095581055,1.917296458316524,1739137709.6191847,51.279951095581055,0.0,1739137709.6191895,51.279951095581055,0.37472309862320685,1739137709.6191945,51.279951095581055,3.1205591412237306,1739137709.6191993,51.279951095581055,1.542573359693317 +1739137709.6415198,51.309951066970825,31.532352665134773,1739137709.6415281,51.309951066970825,0.5046685991912243,1739137709.6415381,51.309951066970825,81.43967294419683,1739137709.6415474,51.309951066970825,25.25998540831542,1739137709.6415522,51.309951066970825,-0.026965391450994986,1739137709.6415582,51.309951066970825,-3.0570366393632598,1739137709.6415634,51.309951066970825,0.6634365818953059,1739137709.6415682,51.309951066970825,0.2565419892477343,1739137709.6415732,51.309951066970825,1.917296458316524,1739137709.6415787,51.309951066970825,0.0,1739137709.6415837,51.309951066970825,0.37472309862320685,1739137709.6415896,51.309951066970825,3.1205591412237306,1739137709.6415946,51.309951066970825,1.542573359693317 +1739137709.665413,51.32995104789734,31.36061105566415,1739137709.6654193,51.32995104789734,0.5067731251058625,1739137709.665427,51.32995104789734,81.45702095127929,1739137709.665435,51.32995104789734,25.118649948822735,1739137709.6654391,51.32995104789734,-0.02497351459813235,1739137709.6654444,51.32995104789734,-3.056608803599592,1739137709.6654487,51.32995104789734,0.5444269142379424,1739137709.6654527,51.32995104789734,0.21272551448193672,1739137709.6654563,51.32995104789734,2.0107744898313107,1739137709.66546,51.32995104789734,0.0,1739137709.6654642,51.32995104789734,0.47426415640011205,1739137709.6654682,51.32995104789734,3.1395610195500656,1739137709.665472,51.32995104789734,1.5839108608131212 +1739137709.68394,51.34995102882385,31.36061105566415,1739137709.6839445,51.34995102882385,0.5067731251058625,1739137709.6839495,51.34995102882385,81.45702095127929,1739137709.6839545,51.34995102882385,25.118649948822735,1739137709.683957,51.34995102882385,-0.02497351459813235,1739137709.68396,51.34995102882385,-3.056608803599592,1739137709.6839626,51.34995102882385,0.5444269142379424,1739137709.6839652,51.34995102882385,0.21272551448193672,1739137709.6839678,51.34995102882385,2.0107744898313107,1739137709.6839705,51.34995102882385,0.0,1739137709.683973,51.34995102882385,0.4268636290181895,1739137709.683976,51.34995102882385,3.1395610195500656,1739137709.6839786,51.34995102882385,1.5839108608131212 +1739137709.7024543,51.369951009750366,31.36061105566415,1739137709.7024589,51.369951009750366,0.5067731251058625,1739137709.702464,51.369951009750366,81.45702095127929,1739137709.702488,51.369951009750366,25.118649948822735,1739137709.7024918,51.369951009750366,-0.02497351459813235,1739137709.7024958,51.369951009750366,-3.056608803599592,1739137709.7024987,51.369951009750366,0.5444269142379424,1739137709.702501,51.369951009750366,0.21272551448193672,1739137709.7025037,51.369951009750366,2.0107744898313107,1739137709.7025065,51.369951009750366,0.0,1739137709.7025092,51.369951009750366,0.4268636290181895,1739137709.7025118,51.369951009750366,3.1395610195500656,1739137709.7025144,51.369951009750366,1.5839108608131212 +1739137709.7217703,51.38995099067688,31.36061105566415,1739137709.7217746,51.38995099067688,0.5067731251058625,1739137709.7217793,51.38995099067688,81.45702095127929,1739137709.721784,51.38995099067688,25.118649948822735,1739137709.721786,51.38995099067688,-0.02497351459813235,1739137709.721789,51.38995099067688,-3.056608803599592,1739137709.7217913,51.38995099067688,0.5444269142379424,1739137709.721794,51.38995099067688,0.21272551448193672,1739137709.7217956,51.38995099067688,2.0107744898313107,1739137709.7217984,51.38995099067688,0.0,1739137709.7218008,51.38995099067688,0.4268636290181895,1739137709.721803,51.38995099067688,3.1395610195500656,1739137709.7218053,51.38995099067688,1.5839108608131212 +1739137709.7411852,51.409950971603394,31.36061105566415,1739137709.7411878,51.409950971603394,0.5067731251058625,1739137709.7411911,51.409950971603394,81.45702095127929,1739137709.7411942,51.409950971603394,25.118649948822735,1739137709.7411957,51.409950971603394,-0.02497351459813235,1739137709.7411978,51.409950971603394,-3.056608803599592,1739137709.7411993,51.409950971603394,0.5444269142379424,1739137709.741201,51.409950971603394,0.21272551448193672,1739137709.7412024,51.409950971603394,2.0107744898313107,1739137709.741204,51.409950971603394,0.0,1739137709.7412055,51.409950971603394,0.4268636290181895,1739137709.7412071,51.409950971603394,3.1395610195500656,1739137709.7412086,51.409950971603394,1.5839108608131212 +1739137709.7609475,51.42995095252991,31.184078762118673,1739137709.7609503,51.42995095252991,0.5056782850167565,1739137709.7609532,51.42995095252991,81.47484961808729,1739137709.7609558,51.42995095252991,24.961011730762305,1739137709.7609572,51.42995095252991,-0.024193127380011406,1739137709.760959,51.42995095252991,-3.0566511856222336,1739137709.7609606,51.42995095252991,0.43164077815172314,1739137709.7609618,51.42995095252991,0.16978661695694794,1739137709.7609627,51.42995095252991,2.103566885137888,1739137709.7609644,51.42995095252991,0.0,1739137709.7609658,51.42995095252991,0.515041843716566,1739137709.7609675,51.42995095252991,3.1573676367842447,1739137709.7609687,51.42995095252991,1.6305146884438313 +1739137709.7803748,51.44995093345642,31.184078762118673,1739137709.7803776,51.44995093345642,0.5056782850167565,1739137709.7803805,51.44995093345642,81.47484961808729,1739137709.7803826,51.44995093345642,24.961011730762305,1739137709.780384,51.44995093345642,-0.024193127380011406,1739137709.7803855,51.44995093345642,-3.0566511856222336,1739137709.780387,51.44995093345642,0.43164077815172314,1739137709.780388,51.44995093345642,0.16978661695694794,1739137709.780389,51.44995093345642,2.103566885137888,1739137709.7803905,51.44995093345642,0.0,1739137709.7803917,51.44995093345642,0.47305219669405685,1739137709.780393,51.44995093345642,3.1573676367842447,1739137709.780394,51.44995093345642,1.6305146884438313 +1739137709.800298,51.469950914382935,31.184078762118673,1739137709.8003001,51.469950914382935,0.5056782850167565,1739137709.8003025,51.469950914382935,81.47484961808729,1739137709.8003051,51.469950914382935,24.961011730762305,1739137709.8003063,51.469950914382935,-0.024193127380011406,1739137709.800308,51.469950914382935,-3.0566511856222336,1739137709.8003092,51.469950914382935,0.43164077815172314,1739137709.8003106,51.469950914382935,0.16978661695694794,1739137709.8003116,51.469950914382935,2.103566885137888,1739137709.8003128,51.469950914382935,0.0,1739137709.8003142,51.469950914382935,0.47305219669405685,1739137709.8003156,51.469950914382935,3.1573676367842447,1739137709.8003166,51.469950914382935,1.6305146884438313 +1739137709.82017,51.48995089530945,31.184078762118673,1739137709.820172,51.48995089530945,0.5056782850167565,1739137709.8201742,51.48995089530945,81.47484961808729,1739137709.8201768,51.48995089530945,24.961011730762305,1739137709.8201783,51.48995089530945,-0.024193127380011406,1739137709.8201797,51.48995089530945,-3.0566511856222336,1739137709.8201811,51.48995089530945,0.43164077815172314,1739137709.8201823,51.48995089530945,0.16978661695694794,1739137709.8201835,51.48995089530945,2.103566885137888,1739137709.820185,51.48995089530945,0.0,1739137709.8201861,51.48995089530945,0.47305219669405685,1739137709.8201873,51.48995089530945,3.1573676367842447,1739137709.8201888,51.48995089530945,1.6305146884438313 +1739137709.8403432,51.50995087623596,31.184078762118673,1739137709.8403454,51.50995087623596,0.5056782850167565,1739137709.840348,51.50995087623596,81.47484961808729,1739137709.8403502,51.50995087623596,24.961011730762305,1739137709.8403516,51.50995087623596,-0.024193127380011406,1739137709.840353,51.50995087623596,-3.0566511856222336,1739137709.8403542,51.50995087623596,0.43164077815172314,1739137709.8403556,51.50995087623596,0.16978661695694794,1739137709.8403566,51.50995087623596,2.103566885137888,1739137709.8403587,51.50995087623596,0.0,1739137709.84036,51.50995087623596,0.47305219669405685,1739137709.840361,51.50995087623596,3.1573676367842447,1739137709.8403625,51.50995087623596,1.6305146884438313 +1739137709.8604414,51.529950857162476,31.184078762118673,1739137709.860444,51.529950857162476,0.5056782850167565,1739137709.860447,51.529950857162476,81.47484961808729,1739137709.8604496,51.529950857162476,24.961011730762305,1739137709.8604512,51.529950857162476,-0.024193127380011406,1739137709.8604534,51.529950857162476,-3.0566511856222336,1739137709.8604548,51.529950857162476,0.43164077815172314,1739137709.8604562,51.529950857162476,0.16978661695694794,1739137709.8604574,51.529950857162476,2.103566885137888,1739137709.860459,51.529950857162476,0.0,1739137709.8604603,51.529950857162476,0.47305219669405685,1739137709.8604615,51.529950857162476,3.1573676367842447,1739137709.860463,51.529950857162476,1.6305146884438313 +1739137709.880296,51.54995083808899,31.002099629842,1739137709.8802981,51.54995083808899,0.5014031118401459,1739137709.8803008,51.54995083808899,81.49322523527405,1739137709.8803034,51.54995083808899,24.784684573244682,1739137709.8803048,51.54995083808899,-0.022507830148552805,1739137709.8803067,51.54995083808899,-3.0575261780972522,1739137709.8803082,51.54995083808899,0.32193540511063995,1739137709.8803096,51.54995083808899,0.12694279915380066,1739137709.8803105,51.54995083808899,2.1979312341146513,1739137709.880312,51.54995083808899,0.0,1739137709.8803132,51.54995083808899,0.5526817189659057,1739137709.8803146,51.54995083808899,3.1740394453438925,1739137709.880316,51.54995083808899,1.6831683542203142 +1739137709.9002028,51.5699508190155,31.002099629842,1739137709.900205,51.5699508190155,0.5014031118401459,1739137709.9002073,51.5699508190155,81.49322523527405,1739137709.90021,51.5699508190155,24.784684573244682,1739137709.900211,51.5699508190155,-0.022507830148552805,1739137709.9002128,51.5699508190155,-3.0575261780972522,1739137709.9002142,51.5699508190155,0.32193540511063995,1739137709.9002156,51.5699508190155,0.12694279915380066,1739137709.9002168,51.5699508190155,2.1979312341146513,1739137709.900218,51.5699508190155,0.0,1739137709.9002194,51.5699508190155,0.5147628798943371,1739137709.9002206,51.5699508190155,3.1740394453438925,1739137709.9002223,51.5699508190155,1.6831683542203142 +1739137709.9202187,51.58995079994202,31.002099629842,1739137709.9202209,51.58995079994202,0.5014031118401459,1739137709.9202237,51.58995079994202,81.49322523527405,1739137709.9202266,51.58995079994202,24.784684573244682,1739137709.9202278,51.58995079994202,-0.022507830148552805,1739137709.9202297,51.58995079994202,-3.0575261780972522,1739137709.9202309,51.58995079994202,0.32193540511063995,1739137709.9202318,51.58995079994202,0.12694279915380066,1739137709.9202335,51.58995079994202,2.1979312341146513,1739137709.9202347,51.58995079994202,0.0,1739137709.9202363,51.58995079994202,0.5147628798943371,1739137709.9202375,51.58995079994202,3.1740394453438925,1739137709.9202387,51.58995079994202,1.6831683542203142 +1739137709.9403703,51.60995078086853,31.002099629842,1739137709.940373,51.60995078086853,0.5014031118401459,1739137709.940376,51.60995078086853,81.49322523527405,1739137709.940379,51.60995078086853,24.784684573244682,1739137709.94038,51.60995078086853,-0.022507830148552805,1739137709.940382,51.60995078086853,-3.0575261780972522,1739137709.9403834,51.60995078086853,0.32193540511063995,1739137709.9403849,51.60995078086853,0.12694279915380066,1739137709.940386,51.60995078086853,2.1979312341146513,1739137709.9403875,51.60995078086853,0.0,1739137709.940389,51.60995078086853,0.5147628798943371,1739137709.9403906,51.60995078086853,3.1740394453438925,1739137709.940392,51.60995078086853,1.6831683542203142 +1739137709.9606838,51.629950761795044,31.002099629842,1739137709.960687,51.629950761795044,0.5014031118401459,1739137709.9606905,51.629950761795044,81.49322523527405,1739137709.9606938,51.629950761795044,24.784684573244682,1739137709.9606953,51.629950761795044,-0.022507830148552805,1739137709.9606974,51.629950761795044,-3.0575261780972522,1739137709.9606988,51.629950761795044,0.32193540511063995,1739137709.9607005,51.629950761795044,0.12694279915380066,1739137709.960702,51.629950761795044,2.1979312341146513,1739137709.9607038,51.629950761795044,0.0,1739137709.960705,51.629950761795044,0.5147628798943371,1739137709.9607067,51.629950761795044,3.1740394453438925,1739137709.9607084,51.629950761795044,1.6831683542203142 +1739137709.9804897,51.64995074272156,30.814258423163587,1739137709.9804924,51.64995074272156,0.49394911459505497,1739137709.9804955,51.64995074272156,82.19974312163488,1739137709.9804988,51.64995074272156,23.908162170646488,1739137709.9805,51.64995074272156,-0.015,1739137709.9805021,51.64995074272156,-3.068030005241505,1739137709.9805036,51.64995074272156,0.1767778969833382,1739137709.9805048,51.64995074272156,0.056617419112903855,1739137709.9805064,51.64995074272156,2.3293274389094947,1739137709.980508,51.64995074272156,0.0,1739137709.9805095,51.64995074272156,0.6573980546321743,1739137709.9805112,51.64995074272156,3.189624387373186,1739137709.9805126,51.64995074272156,1.7398509299870224 +1739137710.0005422,51.66995072364807,30.814258423163587,1739137710.0005448,51.66995072364807,0.49394911459505497,1739137710.0005481,51.66995072364807,82.19974312163488,1739137710.0005515,51.66995072364807,23.908162170646488,1739137710.000553,51.66995072364807,-0.015,1739137710.0005548,51.66995072364807,-3.068030005241505,1739137710.0005565,51.66995072364807,0.1767778969833382,1739137710.0005581,51.66995072364807,0.056617419112903855,1739137710.0005593,51.66995072364807,2.3293274389094947,1739137710.0005612,51.66995072364807,0.0,1739137710.0005627,51.66995072364807,0.5894765089224723,1739137710.0005646,51.66995072364807,3.189624387373186,1739137710.000566,51.66995072364807,1.7398509299870224 +1739137710.0205145,51.689950704574585,30.814258423163587,1739137710.0205173,51.689950704574585,0.49394911459505497,1739137710.0205202,51.689950704574585,82.19974312163488,1739137710.0205235,51.689950704574585,23.908162170646488,1739137710.0205247,51.689950704574585,-0.015,1739137710.020527,51.689950704574585,-3.068030005241505,1739137710.0205283,51.689950704574585,0.1767778969833382,1739137710.02053,51.689950704574585,0.056617419112903855,1739137710.0205314,51.689950704574585,2.3293274389094947,1739137710.020533,51.689950704574585,0.0,1739137710.0205348,51.689950704574585,0.5894765089224723,1739137710.0205364,51.689950704574585,3.189624387373186,1739137710.0205379,51.689950704574585,1.7398509299870224 +1739137710.0404503,51.7099506855011,30.814258423163587,1739137710.0404532,51.7099506855011,0.49394911459505497,1739137710.0404563,51.7099506855011,82.19974312163488,1739137710.0404592,51.7099506855011,23.908162170646488,1739137710.0404608,51.7099506855011,-0.015,1739137710.0404627,51.7099506855011,-3.068030005241505,1739137710.0404644,51.7099506855011,0.1767778969833382,1739137710.0404658,51.7099506855011,0.056617419112903855,1739137710.0404673,51.7099506855011,2.3293274389094947,1739137710.0404692,51.7099506855011,0.0,1739137710.0404708,51.7099506855011,0.5894765089224723,1739137710.0404725,51.7099506855011,3.189624387373186,1739137710.0404742,51.7099506855011,1.7398509299870224 +1739137710.0607166,51.72995066642761,30.814258423163587,1739137710.06072,51.72995066642761,0.49394911459505497,1739137710.0607233,51.72995066642761,82.19974312163488,1739137710.0607266,51.72995066642761,23.908162170646488,1739137710.060728,51.72995066642761,-0.015,1739137710.0607302,51.72995066642761,-3.068030005241505,1739137710.0607316,51.72995066642761,0.1767778969833382,1739137710.060733,51.72995066642761,0.056617419112903855,1739137710.0607345,51.72995066642761,2.3293274389094947,1739137710.0607362,51.72995066642761,0.0,1739137710.0607378,51.72995066642761,0.5894765089224723,1739137710.0607393,51.72995066642761,3.189624387373186,1739137710.060741,51.72995066642761,1.7398509299870224 +1739137710.080453,51.749950647354126,30.814258423163587,1739137710.0804555,51.749950647354126,0.49394911459505497,1739137710.0804586,51.749950647354126,82.19974312163488,1739137710.0804617,51.749950647354126,23.908162170646488,1739137710.0804634,51.749950647354126,-0.015,1739137710.0804653,51.749950647354126,-3.068030005241505,1739137710.080467,51.749950647354126,0.1767778969833382,1739137710.0804684,51.749950647354126,0.056617419112903855,1739137710.08047,51.749950647354126,2.3293274389094947,1739137710.0804715,51.749950647354126,0.0,1739137710.0804732,51.749950647354126,0.5894765089224723,1739137710.0804749,51.749950647354126,3.189624387373186,1739137710.080476,51.749950647354126,1.7398509299870224 +1739137710.100717,51.76995062828064,30.619806155129034,1739137710.10072,51.76995062828064,0.4832875347704375,1739137710.1007233,51.76995062828064,82.56965068942011,1739137710.1007264,51.76995062828064,23.340530045575292,1739137710.1007278,51.76995062828064,-0.018467314392821378,1739137710.10073,51.76995062828064,-3.0727722864125333,1739137710.1007314,51.76995062828064,0.04550102744219012,1739137710.100733,51.76995062828064,0.013127278878646067,1739137710.1007347,51.76995062828064,2.454910540572678,1739137710.1007366,51.76995062828064,0.0,1739137710.100738,51.76995062828064,0.703389720739176,1739137710.1007395,51.76995062828064,3.2041770143936867,1739137710.1007414,51.76995062828064,1.8057652335103394 +1739137710.1204588,51.78995060920715,30.619806155129034,1739137710.1204615,51.78995060920715,0.4832875347704375,1739137710.1204648,51.78995060920715,82.56965068942011,1739137710.120468,51.78995060920715,23.340530045575292,1739137710.1204693,51.78995060920715,-0.018467314392821378,1739137710.1204712,51.78995060920715,-3.0727722864125333,1739137710.1204731,51.78995060920715,0.04550102744219012,1739137710.1204743,51.78995060920715,0.013127278878646067,1739137710.120476,51.78995060920715,2.454910540572678,1739137710.1204774,51.78995060920715,0.0,1739137710.1204789,51.78995060920715,0.6491453070623388,1739137710.1204808,51.78995060920715,3.2041770143936867,1739137710.1204822,51.78995060920715,1.8057652335103394 +1739137710.1404853,51.80995059013367,30.619806155129034,1739137710.140488,51.80995059013367,0.4832875347704375,1739137710.140491,51.80995059013367,82.56965068942011,1739137710.140494,51.80995059013367,23.340530045575292,1739137710.1404955,51.80995059013367,-0.018467314392821378,1739137710.1404977,51.80995059013367,-3.0727722864125333,1739137710.1404994,51.80995059013367,0.04550102744219012,1739137710.1405008,51.80995059013367,0.013127278878646067,1739137710.1405022,51.80995059013367,2.454910540572678,1739137710.1405041,51.80995059013367,0.0,1739137710.1405056,51.80995059013367,0.6491453070623388,1739137710.1405072,51.80995059013367,3.2041770143936867,1739137710.1405087,51.80995059013367,1.8057652335103394 +1739137710.1605904,51.82995057106018,30.619806155129034,1739137710.160593,51.82995057106018,0.4832875347704375,1739137710.1605961,51.82995057106018,82.56965068942011,1739137710.1605995,51.82995057106018,23.340530045575292,1739137710.1606011,51.82995057106018,-0.018467314392821378,1739137710.160603,51.82995057106018,-3.0727722864125333,1739137710.1606047,51.82995057106018,0.04550102744219012,1739137710.1606061,51.82995057106018,0.013127278878646067,1739137710.160608,51.82995057106018,2.454910540572678,1739137710.1606097,51.82995057106018,0.0,1739137710.1606114,51.82995057106018,0.6491453070623388,1739137710.1606128,51.82995057106018,3.2041770143936867,1739137710.1606145,51.82995057106018,1.8057652335103394 +1739137710.180457,51.849950551986694,30.619806155129034,1739137710.1804597,51.849950551986694,0.4832875347704375,1739137710.180463,51.849950551986694,82.56965068942011,1739137710.1804662,51.849950551986694,23.340530045575292,1739137710.1804674,51.849950551986694,-0.018467314392821378,1739137710.1804695,51.849950551986694,-3.0727722864125333,1739137710.180471,51.849950551986694,0.04550102744219012,1739137710.1804729,51.849950551986694,0.013127278878646067,1739137710.1804743,51.849950551986694,2.454910540572678,1739137710.180476,51.849950551986694,0.0,1739137710.1804774,51.849950551986694,0.6491453070623388,1739137710.1804793,51.849950551986694,3.2041770143936867,1739137710.180481,51.849950551986694,1.8057652335103394 +1739137710.2005863,51.86995053291321,30.41806506065913,1739137710.2005887,51.86995053291321,0.4693705496351521,1739137710.2005918,51.86995053291321,82.595445715542,1739137710.200595,51.86995053291321,23.100163517001565,1739137710.2005966,51.86995053291321,-0.020683671138874375,1739137710.2005985,51.86995053291321,-3.0747259936084252,1739137710.2006001,51.86995053291321,-0.06810252789224104,1739137710.2006016,51.86995053291321,-0.01944607681819705,1739137710.2006032,51.86995053291321,2.432816697181706,1739137710.200605,51.86995053291321,0.0,1739137710.2006063,51.86995053291321,0.4704140662665065,1739137710.2006083,51.86995053291321,3.217744941749977,1739137710.2006097,51.86995053291321,1.8772924737342755 +1739137710.2205133,51.88995051383972,30.41806506065913,1739137710.2205157,51.88995051383972,0.4693705496351521,1739137710.220519,51.88995051383972,82.595445715542,1739137710.2205222,51.88995051383972,23.100163517001565,1739137710.2205238,51.88995051383972,-0.020683671138874375,1739137710.2205255,51.88995051383972,-3.0747259936084252,1739137710.2205272,51.88995051383972,-0.06810252789224104,1739137710.2205286,51.88995051383972,-0.01944607681819705,1739137710.22053,51.88995051383972,2.432816697181706,1739137710.2205317,51.88995051383972,0.0,1739137710.220533,51.88995051383972,0.5555242234474305,1739137710.2205348,51.88995051383972,3.217744941749977,1739137710.2205362,51.88995051383972,1.8772924737342755 +1739137710.2404528,51.909950494766235,30.41806506065913,1739137710.2404554,51.909950494766235,0.4693705496351521,1739137710.2404585,51.909950494766235,82.595445715542,1739137710.2404616,51.909950494766235,23.100163517001565,1739137710.240463,51.909950494766235,-0.020683671138874375,1739137710.2404654,51.909950494766235,-3.0747259936084252,1739137710.2404668,51.909950494766235,-0.06810252789224104,1739137710.2404685,51.909950494766235,-0.01944607681819705,1739137710.24047,51.909950494766235,2.432816697181706,1739137710.2404716,51.909950494766235,0.0,1739137710.240473,51.909950494766235,0.5555242234474305,1739137710.240475,51.909950494766235,3.217744941749977,1739137710.2404761,51.909950494766235,1.8772924737342755 +1739137710.2607293,51.92995047569275,30.41806506065913,1739137710.2607324,51.92995047569275,0.4693705496351521,1739137710.2607358,51.92995047569275,82.595445715542,1739137710.260739,51.92995047569275,23.100163517001565,1739137710.2607405,51.92995047569275,-0.020683671138874375,1739137710.2607427,51.92995047569275,-3.0747259936084252,1739137710.260744,51.92995047569275,-0.06810252789224104,1739137710.2607458,51.92995047569275,-0.01944607681819705,1739137710.2607472,51.92995047569275,2.432816697181706,1739137710.260749,51.92995047569275,0.0,1739137710.2607505,51.92995047569275,0.5555242234474305,1739137710.2607524,51.92995047569275,3.217744941749977,1739137710.2607539,51.92995047569275,1.8772924737342755 +1739137710.280599,51.94995045661926,30.41806506065913,1739137710.2806017,51.94995045661926,0.4693705496351521,1739137710.2806048,51.94995045661926,82.595445715542,1739137710.2806082,51.94995045661926,23.100163517001565,1739137710.28061,51.94995045661926,-0.020683671138874375,1739137710.280612,51.94995045661926,-3.0747259936084252,1739137710.280614,51.94995045661926,-0.06810252789224104,1739137710.280615,51.94995045661926,-0.01944607681819705,1739137710.2806168,51.94995045661926,2.432816697181706,1739137710.2806184,51.94995045661926,0.0,1739137710.28062,51.94995045661926,0.5555242234474305,1739137710.2806218,51.94995045661926,3.217744941749977,1739137710.2806232,51.94995045661926,1.8772924737342755 +1739137710.3004608,51.969950437545776,30.41806506065913,1739137710.3004634,51.969950437545776,0.4693705496351521,1739137710.3004665,51.969950437545776,82.595445715542,1739137710.3004694,51.969950437545776,23.100163517001565,1739137710.300471,51.969950437545776,-0.020683671138874375,1739137710.3004727,51.969950437545776,-3.0747259936084252,1739137710.3004746,51.969950437545776,-0.06810252789224104,1739137710.300476,51.969950437545776,-0.01944607681819705,1739137710.3004775,51.969950437545776,2.432816697181706,1739137710.3004792,51.969950437545776,0.0,1739137710.3004808,51.969950437545776,0.5555242234474305,1739137710.3004825,51.969950437545776,3.217744941749977,1739137710.3004842,51.969950437545776,1.8772924737342755 +1739137710.3205829,51.98995041847229,30.209381521540763,1739137710.3205857,51.98995041847229,0.4522209479345731,1739137710.3205886,51.98995041847229,82.62212290934575,1739137710.320592,51.98995041847229,22.89603731281374,1739137710.3205934,51.98995041847229,-0.022,1739137710.3205953,51.98995041847229,-3.076840064020205,1739137710.3205967,51.98995041847229,-0.1759434679379907,1739137710.3205984,51.98995041847229,-0.05031174614519941,1739137710.3205998,51.98995041847229,2.330105032059998,1739137710.3206012,51.98995041847229,0.0,1739137710.320603,51.98995041847229,0.2465122014668382,1739137710.3206046,51.98995041847229,3.230354999204081,1739137710.3206062,51.98995041847229,1.9364441751904573 +1739137710.3406944,52.009950399398804,30.209381521540763,1739137710.340697,52.009950399398804,0.4522209479345731,1739137710.3407004,52.009950399398804,82.62212290934575,1739137710.340704,52.009950399398804,22.89603731281374,1739137710.3407059,52.009950399398804,-0.022,1739137710.340708,52.009950399398804,-3.076840064020205,1739137710.34071,52.009950399398804,-0.1759434679379907,1739137710.3407116,52.009950399398804,-0.05031174614519941,1739137710.3407135,52.009950399398804,2.330105032059998,1739137710.3407154,52.009950399398804,0.0,1739137710.3407173,52.009950399398804,0.39366085686954055,1739137710.3407195,52.009950399398804,3.230354999204081,1739137710.3407214,52.009950399398804,1.9364441751904573 +1739137710.361133,52.02995038032532,30.209381521540763,1739137710.361136,52.02995038032532,0.4522209479345731,1739137710.361139,52.02995038032532,82.62212290934575,1739137710.361142,52.02995038032532,22.89603731281374,1739137710.3611436,52.02995038032532,-0.022,1739137710.3611453,52.02995038032532,-3.076840064020205,1739137710.3611472,52.02995038032532,-0.1759434679379907,1739137710.3611484,52.02995038032532,-0.05031174614519941,1739137710.36115,52.02995038032532,2.330105032059998,1739137710.3611515,52.02995038032532,0.0,1739137710.3611531,52.02995038032532,0.39366085686954055,1739137710.3611548,52.02995038032532,3.230354999204081,1739137710.3611565,52.02995038032532,1.9364441751904573 +1739137710.3804743,52.04995036125183,30.209381521540763,1739137710.380477,52.04995036125183,0.4522209479345731,1739137710.38048,52.04995036125183,82.62212290934575,1739137710.3804834,52.04995036125183,22.89603731281374,1739137710.3804848,52.04995036125183,-0.022,1739137710.380487,52.04995036125183,-3.076840064020205,1739137710.3804884,52.04995036125183,-0.1759434679379907,1739137710.38049,52.04995036125183,-0.05031174614519941,1739137710.3804915,52.04995036125183,2.330105032059998,1739137710.3804934,52.04995036125183,0.0,1739137710.3804948,52.04995036125183,0.39366085686954055,1739137710.3804967,52.04995036125183,3.230354999204081,1739137710.3804984,52.04995036125183,1.9364441751904573 +1739137710.4004776,52.069950342178345,30.209381521540763,1739137710.4004805,52.069950342178345,0.4522209479345731,1739137710.4004836,52.069950342178345,82.62212290934575,1739137710.400487,52.069950342178345,22.89603731281374,1739137710.4004881,52.069950342178345,-0.022,1739137710.4004903,52.069950342178345,-3.076840064020205,1739137710.400492,52.069950342178345,-0.1759434679379907,1739137710.4004936,52.069950342178345,-0.05031174614519941,1739137710.4004948,52.069950342178345,2.330105032059998,1739137710.4004967,52.069950342178345,0.0,1739137710.4004982,52.069950342178345,0.39366085686954055,1739137710.4005005,52.069950342178345,3.230354999204081,1739137710.400502,52.069950342178345,1.9364441751904573 +1739137710.420557,52.08995032310486,29.9952605301297,1739137710.4205596,52.08995032310486,0.43199952189932755,1739137710.4205627,52.08995032310486,82.64948995339428,1739137710.4205658,52.08995032310486,22.74344319110365,1739137710.4205675,52.08995032310486,-0.022,1739137710.4205694,52.08995032310486,-3.0790693218758487,1739137710.4205709,52.08995032310486,-0.2752808383837166,1739137710.4205725,52.08995032310486,-0.08007030930546133,1739137710.420574,52.08995032310486,2.23933376776108,1739137710.4205759,52.08995032310486,0.0,1739137710.4205773,52.08995032310486,0.14068018799155022,1739137710.420579,52.08995032310486,3.242011137583876,1739137710.4205804,52.08995032310486,1.978186534410982 +1739137710.4405272,52.10995030403137,29.9952605301297,1739137710.4405296,52.10995030403137,0.43199952189932755,1739137710.4405327,52.10995030403137,82.64948995339428,1739137710.4405358,52.10995030403137,22.74344319110365,1739137710.4405375,52.10995030403137,-0.022,1739137710.4405394,52.10995030403137,-3.0790693218758487,1739137710.440541,52.10995030403137,-0.2752808383837166,1739137710.4405425,52.10995030403137,-0.08007030930546133,1739137710.440544,52.10995030403137,2.23933376776108,1739137710.4405458,52.10995030403137,0.0,1739137710.440547,52.10995030403137,0.26114723335009793,1739137710.440549,52.10995030403137,3.242011137583876,1739137710.4405503,52.10995030403137,1.978186534410982 +1739137710.4607635,52.129950284957886,29.9952605301297,1739137710.4607666,52.129950284957886,0.43199952189932755,1739137710.46077,52.129950284957886,82.64948995339428,1739137710.4607737,52.129950284957886,22.74344319110365,1739137710.4607751,52.129950284957886,-0.022,1739137710.4607775,52.129950284957886,-3.0790693218758487,1739137710.4607792,52.129950284957886,-0.2752808383837166,1739137710.4607809,52.129950284957886,-0.08007030930546133,1739137710.4607823,52.129950284957886,2.23933376776108,1739137710.4607844,52.129950284957886,0.0,1739137710.4607859,52.129950284957886,0.26114723335009793,1739137710.4607878,52.129950284957886,3.242011137583876,1739137710.4607894,52.129950284957886,1.978186534410982 +1739137710.4810066,52.1499502658844,29.9952605301297,1739137710.48101,52.1499502658844,0.43199952189932755,1739137710.4810138,52.1499502658844,82.64948995339428,1739137710.4810174,52.1499502658844,22.74344319110365,1739137710.4810195,52.1499502658844,-0.022,1739137710.481022,52.1499502658844,-3.0790693218758487,1739137710.481024,52.1499502658844,-0.2752808383837166,1739137710.481026,52.1499502658844,-0.08007030930546133,1739137710.4810276,52.1499502658844,2.23933376776108,1739137710.4810297,52.1499502658844,0.0,1739137710.4810314,52.1499502658844,0.26114723335009793,1739137710.4810336,52.1499502658844,3.242011137583876,1739137710.4810355,52.1499502658844,1.978186534410982 +1739137710.5042331,52.16995024681091,29.9952605301297,1739137710.5042386,52.16995024681091,0.43199952189932755,1739137710.5042453,52.16995024681091,82.64948995339428,1739137710.5042531,52.16995024681091,22.74344319110365,1739137710.5042577,52.16995024681091,-0.022,1739137710.5042632,52.16995024681091,-3.0790693218758487,1739137710.5042682,52.16995024681091,-0.2752808383837166,1739137710.5042734,52.16995024681091,-0.08007030930546133,1739137710.5042782,52.16995024681091,2.23933376776108,1739137710.5042834,52.16995024681091,0.0,1739137710.5042882,52.16995024681091,0.26114723335009793,1739137710.5042937,52.16995024681091,3.242011137583876,1739137710.5042984,52.16995024681091,1.978186534410982 +1739137710.5211594,52.18995022773743,29.9952605301297,1739137710.521164,52.18995022773743,0.43199952189932755,1739137710.5211692,52.18995022773743,82.64948995339428,1739137710.521173,52.18995022773743,22.74344319110365,1739137710.5211751,52.18995022773743,-0.022,1739137710.521178,52.18995022773743,-3.0790693218758487,1739137710.5211804,52.18995022773743,-0.2752808383837166,1739137710.5211823,52.18995022773743,-0.08007030930546133,1739137710.521184,52.18995022773743,2.23933376776108,1739137710.5211864,52.18995022773743,0.0,1739137710.5211883,52.18995022773743,0.26114723335009793,1739137710.5211906,52.18995022773743,3.242011137583876,1739137710.521193,52.18995022773743,1.978186534410982 +1739137710.5413244,52.20995020866394,29.77767019959277,1739137710.5413282,52.20995020866394,0.4089864622929813,1739137710.5413322,52.20995020866394,83.01364806396013,1739137710.5413365,52.20995020866394,22.300673478860766,1739137710.5413384,52.20995020866394,-0.019086370346971117,1739137710.541341,52.20995020866394,-3.0844031087051453,1739137710.5413432,52.20995020866394,-0.4036512584107398,1739137710.5413451,52.20995020866394,-0.11049064731708308,1739137710.5413468,52.20995020866394,2.1272503462361936,1739137710.541349,52.20995020866394,0.0,1739137710.5413508,52.20995020866394,-0.002865276153709906,1739137710.541353,52.20995020866394,3.25270581512881,1739137710.541355,52.20995020866394,2.0043953169662574 +1739137710.5612354,52.229950189590454,29.77767019959277,1739137710.561239,52.229950189590454,0.4089864622929813,1739137710.561243,52.229950189590454,83.01364806396013,1739137710.5612473,52.229950189590454,22.300673478860766,1739137710.5612493,52.229950189590454,-0.019086370346971117,1739137710.5612516,52.229950189590454,-3.0844031087051453,1739137710.5612538,52.229950189590454,-0.4036512584107398,1739137710.561256,52.229950189590454,-0.11049064731708308,1739137710.5612578,52.229950189590454,2.1272503462361936,1739137710.5612597,52.229950189590454,0.0,1739137710.5612617,52.229950189590454,0.12285502926993619,1739137710.5612638,52.229950189590454,3.25270581512881,1739137710.5612657,52.229950189590454,2.0043953169662574 +1739137710.5809565,52.24995017051697,29.77767019959277,1739137710.5809598,52.24995017051697,0.4089864622929813,1739137710.5809636,52.24995017051697,83.01364806396013,1739137710.5809677,52.24995017051697,22.300673478860766,1739137710.5809696,52.24995017051697,-0.019086370346971117,1739137710.5809717,52.24995017051697,-3.0844031087051453,1739137710.580974,52.24995017051697,-0.4036512584107398,1739137710.5809758,52.24995017051697,-0.11049064731708308,1739137710.5809777,52.24995017051697,2.1272503462361936,1739137710.5809798,52.24995017051697,0.0,1739137710.5809817,52.24995017051697,0.12285502926993619,1739137710.5809839,52.24995017051697,3.25270581512881,1739137710.5809855,52.24995017051697,2.0043953169662574 +1739137710.601159,52.26995015144348,29.77767019959277,1739137710.6011624,52.26995015144348,0.4089864622929813,1739137710.6011662,52.26995015144348,83.01364806396013,1739137710.60117,52.26995015144348,22.300673478860766,1739137710.601172,52.26995015144348,-0.019086370346971117,1739137710.6011746,52.26995015144348,-3.0844031087051453,1739137710.6011765,52.26995015144348,-0.4036512584107398,1739137710.6011784,52.26995015144348,-0.11049064731708308,1739137710.6011803,52.26995015144348,2.1272503462361936,1739137710.6011825,52.26995015144348,0.0,1739137710.6011844,52.26995015144348,0.12285502926993619,1739137710.6011865,52.26995015144348,3.25270581512881,1739137710.6011884,52.26995015144348,2.0043953169662574 +1739137710.6210825,52.289950132369995,29.77767019959277,1739137710.6210864,52.289950132369995,0.4089864622929813,1739137710.6210907,52.289950132369995,83.01364806396013,1739137710.6210945,52.289950132369995,22.300673478860766,1739137710.6210964,52.289950132369995,-0.019086370346971117,1739137710.621099,52.289950132369995,-3.0844031087051453,1739137710.6211011,52.289950132369995,-0.4036512584107398,1739137710.621103,52.289950132369995,-0.11049064731708308,1739137710.6211054,52.289950132369995,2.1272503462361936,1739137710.6211073,52.289950132369995,0.0,1739137710.6211095,52.289950132369995,0.12285502926993619,1739137710.6211119,52.289950132369995,3.25270581512881,1739137710.6211138,52.289950132369995,2.0043953169662574 +1739137710.6410246,52.30995011329651,29.558067357953604,1739137710.6410277,52.30995011329651,0.38348229830729696,1739137710.641032,52.30995011329651,83.04192582220362,1739137710.6410358,52.30995011329651,22.235480308677502,1739137710.6410375,52.30995011329651,-0.019,1739137710.64104,52.30995011329651,-3.0866834096027254,1739137710.6410422,52.30995011329651,-0.48316612750532145,1739137710.641044,52.30995011329651,-0.13789310266663243,1739137710.6410458,52.30995011329651,2.06065579838945,1739137710.6410477,52.30995011329651,0.0,1739137710.6410499,52.30995011329651,-0.027771956168939696,1739137710.641052,52.30995011329651,3.2624331902568375,1739137710.6410537,52.30995011329651,2.0167005828042592 +1739137710.6612995,52.32995009422302,29.558067357953604,1739137710.6613033,52.32995009422302,0.38348229830729696,1739137710.6613073,52.32995009422302,83.04192582220362,1739137710.6613114,52.32995009422302,22.235480308677502,1739137710.6613133,52.32995009422302,-0.019,1739137710.661316,52.32995009422302,-3.0866834096027254,1739137710.6613178,52.32995009422302,-0.48316612750532145,1739137710.66132,52.32995009422302,-0.13789310266663243,1739137710.6613219,52.32995009422302,2.06065579838945,1739137710.6613243,52.32995009422302,0.0,1739137710.6613262,52.32995009422302,0.043955215585190555,1739137710.6613286,52.32995009422302,3.2624331902568375,1739137710.6613305,52.32995009422302,2.0167005828042592 +1739137710.6885133,52.349950075149536,29.558067357953604,1739137710.6885214,52.349950075149536,0.38348229830729696,1739137710.6885316,52.349950075149536,83.04192582220362,1739137710.6885412,52.349950075149536,22.235480308677502,1739137710.688546,52.349950075149536,-0.019,1739137710.6885521,52.349950075149536,-3.0866834096027254,1739137710.6885571,52.349950075149536,-0.48316612750532145,1739137710.6885617,52.349950075149536,-0.13789310266663243,1739137710.688566,52.349950075149536,2.06065579838945,1739137710.6885717,52.349950075149536,0.0,1739137710.6885765,52.349950075149536,0.043955215585190555,1739137710.6885817,52.349950075149536,3.2624331902568375,1739137710.6885862,52.349950075149536,2.0167005828042592 +1739137710.7068043,52.36995005607605,29.558067357953604,1739137710.7068129,52.36995005607605,0.38348229830729696,1739137710.7068226,52.36995005607605,83.04192582220362,1739137710.7068322,52.36995005607605,22.235480308677502,1739137710.7068367,52.36995005607605,-0.019,1739137710.7068427,52.36995005607605,-3.0866834096027254,1739137710.7068474,52.36995005607605,-0.48316612750532145,1739137710.7068522,52.36995005607605,-0.13789310266663243,1739137710.7068567,52.36995005607605,2.06065579838945,1739137710.706862,52.36995005607605,0.0,1739137710.7068667,52.36995005607605,0.043955215585190555,1739137710.7068717,52.36995005607605,3.2624331902568375,1739137710.7068765,52.36995005607605,2.0167005828042592 +1739137710.7273765,52.38995003700256,29.558067357953604,1739137710.7273848,52.38995003700256,0.38348229830729696,1739137710.7273948,52.38995003700256,83.04192582220362,1739137710.7274046,52.38995003700256,22.235480308677502,1739137710.7274094,52.38995003700256,-0.019,1739137710.7274153,52.38995003700256,-3.0866834096027254,1739137710.7274203,52.38995003700256,-0.48316612750532145,1739137710.727425,52.38995003700256,-0.13789310266663243,1739137710.7274296,52.38995003700256,2.06065579838945,1739137710.727435,52.38995003700256,0.0,1739137710.7274399,52.38995003700256,0.043955215585190555,1739137710.7274454,52.38995003700256,3.2624331902568375,1739137710.7274501,52.38995003700256,2.0167005828042592 +1739137710.7524073,52.40995001792908,29.558067357953604,1739137710.7524164,52.40995001792908,0.38348229830729696,1739137710.7524269,52.40995001792908,83.04192582220362,1739137710.7524369,52.40995001792908,22.235480308677502,1739137710.752442,52.40995001792908,-0.019,1739137710.7524478,52.40995001792908,-3.0866834096027254,1739137710.7524526,52.40995001792908,-0.48316612750532145,1739137710.7524574,52.40995001792908,-0.13789310266663243,1739137710.7524621,52.40995001792908,2.06065579838945,1739137710.7524676,52.40995001792908,0.0,1739137710.7524724,52.40995001792908,0.043955215585190555,1739137710.7524774,52.40995001792908,3.2624331902568375,1739137710.752483,52.40995001792908,2.0167005828042592 +1739137710.783016,52.43994998931885,29.3378545791737,1739137710.783024,52.43994998931885,0.35583363604323104,1739137710.783034,52.43994998931885,83.59444481039966,1739137710.7830436,52.43994998931885,21.67280159841979,1739137710.7830484,52.43994998931885,-0.016,1739137710.7830546,52.43994998931885,-3.0931204021508285,1739137710.7830591,52.43994998931885,-0.6218328209464532,1739137710.783064,52.43994998931885,-0.16202840768848242,1739137710.7830682,52.43994998931885,1.9494701222992896,1739137710.7830734,52.43994998931885,0.0,1739137710.7830782,52.43994998931885,-0.17478219714950555,1739137710.7830832,52.43994998931885,3.271184259439548,1739137710.783088,52.43994998931885,2.0200915946851548 +1739137710.7996514,52.45994997024536,29.3378545791737,1739137710.799657,52.45994997024536,0.35583363604323104,1739137710.7996645,52.45994997024536,83.59444481039966,1739137710.799671,52.45994997024536,21.67280159841979,1739137710.7996743,52.45994997024536,-0.016,1739137710.7996788,52.45994997024536,-3.0931204021508285,1739137710.7996824,52.45994997024536,-0.6218328209464532,1739137710.7996857,52.45994997024536,-0.16202840768848242,1739137710.7996888,52.45994997024536,1.9494701222992896,1739137710.7996933,52.45994997024536,0.0,1739137710.7996967,52.45994997024536,-0.07062147238586514,1739137710.7997003,52.45994997024536,3.271184259439548,1739137710.7997036,52.45994997024536,2.0200915946851548 +1739137710.8190994,52.479949951171875,29.3378545791737,1739137710.8191123,52.479949951171875,0.35583363604323104,1739137710.8191237,52.479949951171875,83.59444481039966,1739137710.8191314,52.479949951171875,21.67280159841979,1739137710.8191347,52.479949951171875,-0.016,1739137710.819139,52.479949951171875,-3.0931204021508285,1739137710.8191426,52.479949951171875,-0.6218328209464532,1739137710.819146,52.479949951171875,-0.16202840768848242,1739137710.819149,52.479949951171875,1.9494701222992896,1739137710.8191526,52.479949951171875,0.0,1739137710.8191564,52.479949951171875,-0.07062147238586514,1739137710.81916,52.479949951171875,3.271184259439548,1739137710.8191633,52.479949951171875,2.0200915946851548 +1739137710.8387947,52.49994993209839,29.3378545791737,1739137710.838801,52.49994993209839,0.35583363604323104,1739137710.8388078,52.49994993209839,83.59444481039966,1739137710.8388152,52.49994993209839,21.67280159841979,1739137710.8388183,52.49994993209839,-0.016,1739137710.8388226,52.49994993209839,-3.0931204021508285,1739137710.838826,52.49994993209839,-0.6218328209464532,1739137710.8388293,52.49994993209839,-0.16202840768848242,1739137710.8388321,52.49994993209839,1.9494701222992896,1739137710.838836,52.49994993209839,0.0,1739137710.8388393,52.49994993209839,-0.07062147238586514,1739137710.8388433,52.49994993209839,3.271184259439548,1739137710.8388467,52.49994993209839,2.0200915946851548 +1739137710.8626232,52.52994990348816,29.117764815927828,1739137710.8626294,52.52994990348816,0.3263423500645324,1739137710.8626366,52.52994990348816,83.60541980727598,1739137710.8626437,52.52994990348816,21.677930798937933,1739137710.8626468,52.52994990348816,-0.016,1739137710.8626513,52.52994990348816,-3.095610305720154,1739137710.8626547,52.52994990348816,-0.6796262583099013,1739137710.8626578,52.52994990348816,-0.1879522578258848,1739137710.8626616,52.52994990348816,1.9049204107083981,1739137710.862673,52.52994990348816,0.0,1739137710.8626804,52.52994990348816,-0.14542283014161017,1739137710.862689,52.52994990348816,3.2789552210009925,1739137710.8626938,52.52994990348816,2.0147235288870036 +1739137710.8811762,52.54994988441467,29.117764815927828,1739137710.88118,52.54994988441467,0.3263423500645324,1739137710.8811846,52.54994988441467,83.60541980727598,1739137710.8811889,52.54994988441467,21.677930798937933,1739137710.881191,52.54994988441467,-0.016,1739137710.8811934,52.54994988441467,-3.095610305720154,1739137710.8811958,52.54994988441467,-0.6796262583099013,1739137710.881198,52.54994988441467,-0.1879522578258848,1739137710.8811998,52.54994988441467,1.9049204107083981,1739137710.8812022,52.54994988441467,0.0,1739137710.8812044,52.54994988441467,-0.10980311817860544,1739137710.8812068,52.54994988441467,3.2789552210009925,1739137710.881209,52.54994988441467,2.0147235288870036 +1739137710.89897,52.56994986534119,29.117764815927828,1739137710.8989725,52.56994986534119,0.3263423500645324,1739137710.8989758,52.56994986534119,83.60541980727598,1739137710.8989785,52.56994986534119,21.677930798937933,1739137710.8989801,52.56994986534119,-0.016,1739137710.8989816,52.56994986534119,-3.095610305720154,1739137710.8989832,52.56994986534119,-0.6796262583099013,1739137710.8989844,52.56994986534119,-0.1879522578258848,1739137710.8989856,52.56994986534119,1.9049204107083981,1739137710.8989873,52.56994986534119,0.0,1739137710.8989885,52.56994986534119,-0.10980311817860544,1739137710.8989904,52.56994986534119,3.2789552210009925,1739137710.8989916,52.56994986534119,2.0147235288870036 +1739137710.9188418,52.5899498462677,29.117764815927828,1739137710.9188442,52.5899498462677,0.3263423500645324,1739137710.9188466,52.5899498462677,83.60541980727598,1739137710.918849,52.5899498462677,21.677930798937933,1739137710.91885,52.5899498462677,-0.016,1739137710.9188519,52.5899498462677,-3.095610305720154,1739137710.918853,52.5899498462677,-0.6796262583099013,1739137710.9188545,52.5899498462677,-0.1879522578258848,1739137710.9188554,52.5899498462677,1.9049204107083981,1739137710.9188569,52.5899498462677,0.0,1739137710.918858,52.5899498462677,-0.10980311817860544,1739137710.9188595,52.5899498462677,3.2789552210009925,1739137710.9188604,52.5899498462677,2.0147235288870036 +1739137710.9388087,52.609949827194214,29.117764815927828,1739137710.9388106,52.609949827194214,0.3263423500645324,1739137710.9388134,52.609949827194214,83.60541980727598,1739137710.938816,52.609949827194214,21.677930798937933,1739137710.9388173,52.609949827194214,-0.016,1739137710.9388192,52.609949827194214,-3.095610305720154,1739137710.9388204,52.609949827194214,-0.6796262583099013,1739137710.9388216,52.609949827194214,-0.1879522578258848,1739137710.9388227,52.609949827194214,1.9049204107083981,1739137710.9388242,52.609949827194214,0.0,1739137710.9388251,52.609949827194214,-0.10980311817860544,1739137710.9388266,52.609949827194214,3.2789552210009925,1739137710.9388278,52.609949827194214,2.0147235288870036 +1739137710.9594698,52.62994980812073,29.117764815927828,1739137710.9594722,52.62994980812073,0.3263423500645324,1739137710.9594748,52.62994980812073,83.60541980727598,1739137710.9594774,52.62994980812073,21.677930798937933,1739137710.9594789,52.62994980812073,-0.016,1739137710.9594803,52.62994980812073,-3.095610305720154,1739137710.959482,52.62994980812073,-0.6796262583099013,1739137710.9594831,52.62994980812073,-0.1879522578258848,1739137710.9594843,52.62994980812073,1.9049204107083981,1739137710.9594858,52.62994980812073,0.0,1739137710.959487,52.62994980812073,-0.10980311817860544,1739137710.9594886,52.62994980812073,3.2789552210009925,1739137710.9594898,52.62994980812073,2.0147235288870036 +1739137710.9791517,52.64994978904724,28.898993298012392,1739137710.9791536,52.64994978904724,0.29539583734229513,1739137710.9791565,52.64994978904724,83.61632743665903,1739137710.979159,52.64994978904724,21.705214135020793,1739137710.9791603,52.64994978904724,-0.016,1739137710.9791617,52.64994978904724,-3.0983328375576096,1739137710.9791634,52.64994978904724,-0.7251816127552209,1739137710.9791646,52.64994978904724,-0.21447172091138014,1739137710.9791658,52.64994978904724,1.8705230296741784,1739137710.9791672,52.64994978904724,0.0,1739137710.9791684,52.64994978904724,-0.15116752273229422,1739137710.97917,52.64994978904724,3.285735961061177,1739137710.9791713,52.64994978904724,2.0019932070650315 +1739137710.9995513,52.669949769973755,28.898993298012392,1739137710.9995532,52.669949769973755,0.29539583734229513,1739137710.9995563,52.669949769973755,83.61632743665903,1739137710.9995592,52.669949769973755,21.705214135020793,1739137710.9995604,52.669949769973755,-0.016,1739137710.999562,52.669949769973755,-3.0983328375576096,1739137710.9995632,52.669949769973755,-0.7251816127552209,1739137710.9995646,52.669949769973755,-0.21447172091138014,1739137710.9995658,52.669949769973755,1.8705230296741784,1739137710.999567,52.669949769973755,0.0,1739137710.9995685,52.669949769973755,-0.1314701773908531,1739137710.99957,52.669949769973755,3.285735961061177,1739137710.999571,52.669949769973755,2.0019932070650315 +1739137711.0188606,52.68994975090027,28.898993298012392,1739137711.018863,52.68994975090027,0.29539583734229513,1739137711.0188656,52.68994975090027,83.61632743665903,1739137711.0188682,52.68994975090027,21.705214135020793,1739137711.0188694,52.68994975090027,-0.016,1739137711.0188713,52.68994975090027,-3.0983328375576096,1739137711.0188725,52.68994975090027,-0.7251816127552209,1739137711.0188744,52.68994975090027,-0.21447172091138014,1739137711.0188754,52.68994975090027,1.8705230296741784,1739137711.018877,52.68994975090027,0.0,1739137711.0188782,52.68994975090027,-0.1314701773908531,1739137711.0188794,52.68994975090027,3.285735961061177,1739137711.0188808,52.68994975090027,2.0019932070650315 +1739137711.0386767,52.70994973182678,28.898993298012392,1739137711.0386794,52.70994973182678,0.29539583734229513,1739137711.0386817,52.70994973182678,83.61632743665903,1739137711.0386844,52.70994973182678,21.705214135020793,1739137711.0386858,52.70994973182678,-0.016,1739137711.0386875,52.70994973182678,-3.0983328375576096,1739137711.0386891,52.70994973182678,-0.7251816127552209,1739137711.0386903,52.70994973182678,-0.21447172091138014,1739137711.0386913,52.70994973182678,1.8705230296741784,1739137711.038693,52.70994973182678,0.0,1739137711.038694,52.70994973182678,-0.1314701773908531,1739137711.0386953,52.70994973182678,3.285735961061177,1739137711.0386968,52.70994973182678,2.0019932070650315 +1739137711.0590196,52.729949712753296,28.898993298012392,1739137711.0590239,52.729949712753296,0.29539583734229513,1739137711.0590315,52.729949712753296,83.61632743665903,1739137711.0590367,52.729949712753296,21.705214135020793,1739137711.0590405,52.729949712753296,-0.016,1739137711.0590477,52.729949712753296,-3.0983328375576096,1739137711.0590518,52.729949712753296,-0.7251816127552209,1739137711.0590553,52.729949712753296,-0.21447172091138014,1739137711.0590599,52.729949712753296,1.8705230296741784,1739137711.0590632,52.729949712753296,0.0,1739137711.0590646,52.729949712753296,-0.1314701773908531,1739137711.059066,52.729949712753296,3.285735961061177,1739137711.0590672,52.729949712753296,2.0019932070650315 +1739137711.079561,52.74994969367981,28.681868531524593,1739137711.079563,52.74994969367981,0.263279672996962,1739137711.0795658,52.74994969367981,84.3427167937144,1739137711.0795686,52.74994969367981,21.022514410043307,1739137711.0795698,52.74994969367981,-0.017,1739137711.0795715,52.74994969367981,-3.1050158527878744,1739137711.0795727,52.74994969367981,-0.866895688189391,1739137711.079574,52.74994969367981,-0.22623938544446215,1739137711.0795753,52.74994969367981,1.7674405030802394,1739137711.0795765,52.74994969367981,0.0,1739137711.079578,52.74994969367981,-0.30046456790478726,1739137711.0795794,52.74994969367981,3.291517613089193,1739137711.0795808,52.74994969367981,1.9874315114926182 +1739137711.0990636,52.76994967460632,28.681868531524593,1739137711.0990663,52.76994967460632,0.263279672996962,1739137711.0990696,52.76994967460632,84.3427167937144,1739137711.0990725,52.76994967460632,21.022514410043307,1739137711.0990741,52.76994967460632,-0.017,1739137711.0990758,52.76994967460632,-3.1050158527878744,1739137711.0990775,52.76994967460632,-0.866895688189391,1739137711.099079,52.76994967460632,-0.22623938544446215,1739137711.09908,52.76994967460632,1.7674405030802394,1739137711.0990818,52.76994967460632,0.0,1739137711.0990832,52.76994967460632,-0.21999100841237884,1739137711.0990849,52.76994967460632,3.291517613089193,1739137711.0990865,52.76994967460632,1.9874315114926182 +1739137711.1189456,52.78994965553284,28.681868531524593,1739137711.118948,52.78994965553284,0.263279672996962,1739137711.118951,52.78994965553284,84.3427167937144,1739137711.1189544,52.78994965553284,21.022514410043307,1739137711.118956,52.78994965553284,-0.017,1739137711.1189578,52.78994965553284,-3.1050158527878744,1739137711.1189597,52.78994965553284,-0.866895688189391,1739137711.1189609,52.78994965553284,-0.22623938544446215,1739137711.1189625,52.78994965553284,1.7674405030802394,1739137711.1189644,52.78994965553284,0.0,1739137711.1189663,52.78994965553284,-0.21999100841237884,1739137711.118968,52.78994965553284,3.291517613089193,1739137711.1189697,52.78994965553284,1.9874315114926182 +1739137711.1392214,52.80994963645935,28.681868531524593,1739137711.1392245,52.80994963645935,0.263279672996962,1739137711.1392283,52.80994963645935,84.3427167937144,1739137711.1392322,52.80994963645935,21.022514410043307,1739137711.139234,52.80994963645935,-0.017,1739137711.139237,52.80994963645935,-3.1050158527878744,1739137711.1392386,52.80994963645935,-0.866895688189391,1739137711.1392403,52.80994963645935,-0.22623938544446215,1739137711.139242,52.80994963645935,1.7674405030802394,1739137711.1392438,52.80994963645935,0.0,1739137711.1392457,52.80994963645935,-0.21999100841237884,1739137711.139248,52.80994963645935,3.291517613089193,1739137711.1392493,52.80994963645935,1.9874315114926182 +1739137711.159393,52.829949617385864,28.681868531524593,1739137711.1593964,52.829949617385864,0.263279672996962,1739137711.1594002,52.829949617385864,84.3427167937144,1739137711.159404,52.829949617385864,21.022514410043307,1739137711.1594057,52.829949617385864,-0.017,1739137711.159408,52.829949617385864,-3.1050158527878744,1739137711.1594102,52.829949617385864,-0.866895688189391,1739137711.159412,52.829949617385864,-0.22623938544446215,1739137711.1594138,52.829949617385864,1.7674405030802394,1739137711.1594157,52.829949617385864,0.0,1739137711.1594176,52.829949617385864,-0.21999100841237884,1739137711.1594195,52.829949617385864,3.291517613089193,1739137711.1594214,52.829949617385864,1.9874315114926182 +1739137711.1792688,52.84994959831238,28.681868531524593,1739137711.179272,52.84994959831238,0.263279672996962,1739137711.1792755,52.84994959831238,84.3427167937144,1739137711.179279,52.84994959831238,21.022514410043307,1739137711.1792808,52.84994959831238,-0.017,1739137711.179283,52.84994959831238,-3.1050158527878744,1739137711.179285,52.84994959831238,-0.866895688189391,1739137711.1792865,52.84994959831238,-0.22623938544446215,1739137711.1792884,52.84994959831238,1.7674405030802394,1739137711.17929,52.84994959831238,0.0,1739137711.179292,52.84994959831238,-0.21999100841237884,1739137711.1792939,52.84994959831238,3.291517613089193,1739137711.1792955,52.84994959831238,1.9874315114926182 +1739137711.1995184,52.86994957923889,28.467192793548755,1739137711.1995223,52.86994957923889,0.23035721535543097,1739137711.1995258,52.86994957923889,84.36780093259993,1739137711.1995294,52.86994957923889,21.07677467450945,1739137711.1995316,52.86994957923889,-0.016856593868095907,1739137711.1995335,52.86994957923889,-3.1081545366718837,1739137711.1995354,52.86994957923889,-0.8944785639951048,1739137711.199537,52.86994957923889,-0.2506830630863259,1739137711.1995387,52.86994957923889,1.7480472474052842,1739137711.1995409,52.86994957923889,0.0,1739137711.1995425,52.86994957923889,-0.20652218255796875,1739137711.1995447,52.86994957923889,3.296292273539536,1739137711.1995463,52.86994957923889,1.9609831597645293 +1739137711.219173,52.889949560165405,28.467192793548755,1739137711.219176,52.889949560165405,0.23035721535543097,1739137711.2191799,52.889949560165405,84.36780093259993,1739137711.2191834,52.889949560165405,21.07677467450945,1739137711.2191849,52.889949560165405,-0.016856593868095907,1739137711.2191873,52.889949560165405,-3.1081545366718837,1739137711.2191892,52.889949560165405,-0.8944785639951048,1739137711.2191908,52.889949560165405,-0.2506830630863259,1739137711.2191925,52.889949560165405,1.7480472474052842,1739137711.2191944,52.889949560165405,0.0,1739137711.219196,52.889949560165405,-0.21293591235924514,1739137711.219198,52.889949560165405,3.296292273539536,1739137711.2191997,52.889949560165405,1.9609831597645293 +1739137711.239408,52.90994954109192,28.467192793548755,1739137711.239411,52.90994954109192,0.23035721535543097,1739137711.2394147,52.90994954109192,84.36780093259993,1739137711.2394183,52.90994954109192,21.07677467450945,1739137711.23942,52.90994954109192,-0.016856593868095907,1739137711.2394223,52.90994954109192,-3.1081545366718837,1739137711.2394242,52.90994954109192,-0.8944785639951048,1739137711.2394261,52.90994954109192,-0.2506830630863259,1739137711.2394278,52.90994954109192,1.7480472474052842,1739137711.2394302,52.90994954109192,0.0,1739137711.2394319,52.90994954109192,-0.21293591235924514,1739137711.2394338,52.90994954109192,3.296292273539536,1739137711.2394354,52.90994954109192,1.9609831597645293 +1739137711.2596636,52.92994952201843,28.467192793548755,1739137711.2596672,52.92994952201843,0.23035721535543097,1739137711.2596712,52.92994952201843,84.36780093259993,1739137711.2596748,52.92994952201843,21.07677467450945,1739137711.2596767,52.92994952201843,-0.016856593868095907,1739137711.259679,52.92994952201843,-3.1081545366718837,1739137711.2596807,52.92994952201843,-0.8944785639951048,1739137711.2596824,52.92994952201843,-0.2506830630863259,1739137711.259684,52.92994952201843,1.7480472474052842,1739137711.259686,52.92994952201843,0.0,1739137711.2596877,52.92994952201843,-0.21293591235924514,1739137711.2596898,52.92994952201843,3.296292273539536,1739137711.2596915,52.92994952201843,1.9609831597645293 +1739137711.279273,52.949949502944946,28.467192793548755,1739137711.279276,52.949949502944946,0.23035721535543097,1739137711.27928,52.949949502944946,84.36780093259993,1739137711.2792835,52.949949502944946,21.07677467450945,1739137711.2792852,52.949949502944946,-0.016856593868095907,1739137711.2792876,52.949949502944946,-3.1081545366718837,1739137711.2792892,52.949949502944946,-0.8944785639951048,1739137711.2792912,52.949949502944946,-0.2506830630863259,1739137711.2792928,52.949949502944946,1.7480472474052842,1739137711.279295,52.949949502944946,0.0,1739137711.2792964,52.949949502944946,-0.21293591235924514,1739137711.2792985,52.949949502944946,3.296292273539536,1739137711.2793005,52.949949502944946,1.9609831597645293 +1739137711.2994738,52.96994948387146,28.255268277519598,1739137711.2994773,52.96994948387146,0.1969196793872543,1739137711.299481,52.96994948387146,84.39256266343938,1739137711.2994845,52.96994948387146,21.121725307455225,1739137711.2994862,52.96994948387146,-0.01644795175040705,1739137711.2994885,52.96994948387146,-3.111691097328402,1739137711.2994902,52.96994948387146,-0.9149766929192411,1739137711.2994921,52.96994948387146,-0.27515797285415816,1739137711.2994936,52.96994948387146,1.7337731666255287,1739137711.2994957,52.96994948387146,0.0,1739137711.2994974,52.96994948387146,-0.19582282712382246,1739137711.2994995,52.96994948387146,3.3000547092749253,1739137711.2995014,52.96994948387146,1.937745086027523 +1739137711.3192313,52.989949464797974,28.255268277519598,1739137711.3192344,52.989949464797974,0.1969196793872543,1739137711.319238,52.989949464797974,84.39256266343938,1739137711.3192415,52.989949464797974,21.121725307455225,1739137711.319243,52.989949464797974,-0.01644795175040705,1739137711.3192453,52.989949464797974,-3.111691097328402,1739137711.319247,52.989949464797974,-0.9149766929192411,1739137711.319249,52.989949464797974,-0.27515797285415816,1739137711.3192503,52.989949464797974,1.7337731666255287,1739137711.3192525,52.989949464797974,0.0,1739137711.3192542,52.989949464797974,-0.20397191940199422,1739137711.3192563,52.989949464797974,3.3000547092749253,1739137711.319258,52.989949464797974,1.937745086027523 +1739137711.3394358,53.00994944572449,28.255268277519598,1739137711.3394387,53.00994944572449,0.1969196793872543,1739137711.3394423,53.00994944572449,84.39256266343938,1739137711.339446,53.00994944572449,21.121725307455225,1739137711.3394477,53.00994944572449,-0.01644795175040705,1739137711.3394501,53.00994944572449,-3.111691097328402,1739137711.3394518,53.00994944572449,-0.9149766929192411,1739137711.339454,53.00994944572449,-0.27515797285415816,1739137711.3394556,53.00994944572449,1.7337731666255287,1739137711.3394575,53.00994944572449,0.0,1739137711.3394594,53.00994944572449,-0.20397191940199422,1739137711.3394616,53.00994944572449,3.3000547092749253,1739137711.3394635,53.00994944572449,1.937745086027523 +1739137711.359345,53.029949426651,28.255268277519598,1739137711.3593483,53.029949426651,0.1969196793872543,1739137711.359352,53.029949426651,84.39256266343938,1739137711.3593557,53.029949426651,21.121725307455225,1739137711.3593574,53.029949426651,-0.01644795175040705,1739137711.3593595,53.029949426651,-3.111691097328402,1739137711.3593616,53.029949426651,-0.9149766929192411,1739137711.359363,53.029949426651,-0.27515797285415816,1739137711.3593647,53.029949426651,1.7337731666255287,1739137711.359367,53.029949426651,0.0,1739137711.3593688,53.029949426651,-0.20397191940199422,1739137711.3593707,53.029949426651,3.3000547092749253,1739137711.3593726,53.029949426651,1.937745086027523 +1739137711.379306,53.049949407577515,28.255268277519598,1739137711.3793097,53.049949407577515,0.1969196793872543,1739137711.3793135,53.049949407577515,84.39256266343938,1739137711.379317,53.049949407577515,21.121725307455225,1739137711.3793187,53.049949407577515,-0.01644795175040705,1739137711.379321,53.049949407577515,-3.111691097328402,1739137711.3793232,53.049949407577515,-0.9149766929192411,1739137711.379325,53.049949407577515,-0.27515797285415816,1739137711.3793268,53.049949407577515,1.7337731666255287,1739137711.3793287,53.049949407577515,0.0,1739137711.3793306,53.049949407577515,-0.20397191940199422,1739137711.3793323,53.049949407577515,3.3000547092749253,1739137711.3793342,53.049949407577515,1.937745086027523 +1739137711.3998206,53.06994938850403,28.255268277519598,1739137711.3998234,53.06994938850403,0.1969196793872543,1739137711.399827,53.06994938850403,84.39256266343938,1739137711.3998306,53.06994938850403,21.121725307455225,1739137711.3998322,53.06994938850403,-0.01644795175040705,1739137711.3998344,53.06994938850403,-3.111691097328402,1739137711.399836,53.06994938850403,-0.9149766929192411,1739137711.399838,53.06994938850403,-0.27515797285415816,1739137711.3998396,53.06994938850403,1.7337731666255287,1739137711.3998415,53.06994938850403,0.0,1739137711.3998432,53.06994938850403,-0.20397191940199422,1739137711.3998454,53.06994938850403,3.3000547092749253,1739137711.3998473,53.06994938850403,1.937745086027523 +1739137711.4197693,53.08994936943054,28.045921130182137,1739137711.4197762,53.08994936943054,0.16318073029732805,1739137711.4197805,53.08994936943054,84.41702254072877,1739137711.419787,53.08994936943054,21.163792138947446,1739137711.4197917,53.08994936943054,-0.016065526009568676,1739137711.4197967,53.08994936943054,-3.1155533651096823,1739137711.419801,53.08994936943054,-0.9276692948551296,1739137711.4198031,53.08994936943054,-0.29963790366504983,1739137711.4198236,53.08994936943054,1.7249930369631992,1739137711.419837,53.08994936943054,0.0,1739137711.419839,53.08994936943054,-0.1783976890240699,1739137711.419841,53.08994936943054,3.3027913292393603,1739137711.419845,53.08994936943054,1.9155689370126863 +1739137711.4395351,53.109949350357056,28.045921130182137,1739137711.4395385,53.109949350357056,0.16318073029732805,1739137711.439542,53.109949350357056,84.41702254072877,1739137711.4395454,53.109949350357056,21.163792138947446,1739137711.439547,53.109949350357056,-0.016065526009568676,1739137711.4395494,53.109949350357056,-3.1155533651096823,1739137711.439551,53.109949350357056,-0.9276692948551296,1739137711.439553,53.109949350357056,-0.29963790366504983,1739137711.439555,53.109949350357056,1.7249930369631992,1739137711.4395566,53.109949350357056,0.0,1739137711.4395587,53.109949350357056,-0.1905759000494871,1739137711.4395607,53.109949350357056,3.3027913292393603,1739137711.4395623,53.109949350357056,1.9155689370126863 +1739137711.4594758,53.12994933128357,28.045921130182137,1739137711.4594796,53.12994933128357,0.16318073029732805,1739137711.4594836,53.12994933128357,84.41702254072877,1739137711.4594872,53.12994933128357,21.163792138947446,1739137711.4594893,53.12994933128357,-0.016065526009568676,1739137711.4594915,53.12994933128357,-3.1155533651096823,1739137711.4594934,53.12994933128357,-0.9276692948551296,1739137711.459495,53.12994933128357,-0.29963790366504983,1739137711.459497,53.12994933128357,1.7249930369631992,1739137711.4594986,53.12994933128357,0.0,1739137711.4595006,53.12994933128357,-0.1905759000494871,1739137711.459503,53.12994933128357,3.3027913292393603,1739137711.4595046,53.12994933128357,1.9155689370126863 +1739137711.4792788,53.14994931221008,28.045921130182137,1739137711.479282,53.14994931221008,0.16318073029732805,1739137711.4792857,53.14994931221008,84.41702254072877,1739137711.4792893,53.14994931221008,21.163792138947446,1739137711.4792912,53.14994931221008,-0.016065526009568676,1739137711.4792933,53.14994931221008,-3.1155533651096823,1739137711.4792953,53.14994931221008,-0.9276692948551296,1739137711.479297,53.14994931221008,-0.29963790366504983,1739137711.4792988,53.14994931221008,1.7249930369631992,1739137711.479301,53.14994931221008,0.0,1739137711.4793026,53.14994931221008,-0.1905759000494871,1739137711.4793048,53.14994931221008,3.3027913292393603,1739137711.4793065,53.14994931221008,1.9155689370126863 +1739137711.4994905,53.1699492931366,28.045921130182137,1739137711.499494,53.1699492931366,0.16318073029732805,1739137711.4994981,53.1699492931366,84.41702254072877,1739137711.4995017,53.1699492931366,21.163792138947446,1739137711.4995039,53.1699492931366,-0.016065526009568676,1739137711.4995062,53.1699492931366,-3.1155533651096823,1739137711.4995081,53.1699492931366,-0.9276692948551296,1739137711.49951,53.1699492931366,-0.29963790366504983,1739137711.4995117,53.1699492931366,1.7249930369631992,1739137711.4995139,53.1699492931366,0.0,1739137711.4995155,53.1699492931366,-0.1905759000494871,1739137711.4995177,53.1699492931366,3.3027913292393603,1739137711.4995196,53.1699492931366,1.9155689370126863 +1739137711.5194917,53.18994927406311,27.83899196631854,1739137711.5194955,53.18994927406311,0.12935003431616732,1739137711.5194993,53.18994927406311,85.0439527310181,1739137711.5195029,53.18994927406311,20.599100390241603,1739137711.5195045,53.18994927406311,-0.017442133960617272,1739137711.5195067,53.18994927406311,-3.1213199662788718,1739137711.5195088,53.18994927406311,-1.0292977601946054,1739137711.5195105,53.18994927406311,-0.3004926151657902,1739137711.5195124,53.18994927406311,1.6562758659309627,1739137711.519514,53.18994927406311,0.0,1739137711.5195162,53.18994927406311,-0.28216348364476684,1739137711.519518,53.18994927406311,3.3044894987778255,1739137711.5195198,53.18994927406311,1.894826192743681 +1739137711.539388,53.209949254989624,27.83899196631854,1739137711.5393913,53.209949254989624,0.12935003431616732,1739137711.539395,53.209949254989624,85.0439527310181,1739137711.5393987,53.209949254989624,20.599100390241603,1739137711.5394008,53.209949254989624,-0.017442133960617272,1739137711.5394027,53.209949254989624,-3.1213199662788718,1739137711.5394046,53.209949254989624,-1.0292977601946054,1739137711.5394063,53.209949254989624,-0.3004926151657902,1739137711.5394082,53.209949254989624,1.6562758659309627,1739137711.53941,53.209949254989624,0.0,1739137711.5394118,53.209949254989624,-0.23855032681271826,1739137711.5394137,53.209949254989624,3.3044894987778255,1739137711.5394154,53.209949254989624,1.894826192743681 +1739137711.559059,53.22994923591614,27.83899196631854,1739137711.5590613,53.22994923591614,0.12935003431616732,1739137711.5590641,53.22994923591614,85.0439527310181,1739137711.5590665,53.22994923591614,20.599100390241603,1739137711.559068,53.22994923591614,-0.017442133960617272,1739137711.5590694,53.22994923591614,-3.1213199662788718,1739137711.5590708,53.22994923591614,-1.0292977601946054,1739137711.559072,53.22994923591614,-0.3004926151657902,1739137711.5590732,53.22994923591614,1.6562758659309627,1739137711.5590746,53.22994923591614,0.0,1739137711.5590758,53.22994923591614,-0.23855032681271826,1739137711.5590777,53.22994923591614,3.3044894987778255,1739137711.559079,53.22994923591614,1.894826192743681 +1739137711.578654,53.24994921684265,27.83899196631854,1739137711.5786562,53.24994921684265,0.12935003431616732,1739137711.5786586,53.24994921684265,85.0439527310181,1739137711.578661,53.24994921684265,20.599100390241603,1739137711.5786624,53.24994921684265,-0.017442133960617272,1739137711.5786638,53.24994921684265,-3.1213199662788718,1739137711.5786653,53.24994921684265,-1.0292977601946054,1739137711.5786664,53.24994921684265,-0.3004926151657902,1739137711.5786674,53.24994921684265,1.6562758659309627,1739137711.5786688,53.24994921684265,0.0,1739137711.57867,53.24994921684265,-0.23855032681271826,1739137711.5786715,53.24994921684265,3.3044894987778255,1739137711.5786726,53.24994921684265,1.894826192743681 +1739137711.5989325,53.269949197769165,27.83899196631854,1739137711.5989344,53.269949197769165,0.12935003431616732,1739137711.598937,53.269949197769165,85.0439527310181,1739137711.5989394,53.269949197769165,20.599100390241603,1739137711.5989406,53.269949197769165,-0.017442133960617272,1739137711.5989423,53.269949197769165,-3.1213199662788718,1739137711.5989435,53.269949197769165,-1.0292977601946054,1739137711.5989447,53.269949197769165,-0.3004926151657902,1739137711.598946,53.269949197769165,1.6562758659309627,1739137711.5989473,53.269949197769165,0.0,1739137711.5989487,53.269949197769165,-0.23855032681271826,1739137711.5989501,53.269949197769165,3.3044894987778255,1739137711.598951,53.269949197769165,1.894826192743681 +1739137711.6191027,53.28994917869568,27.83899196631854,1739137711.619105,53.28994917869568,0.12935003431616732,1739137711.6191077,53.28994917869568,85.0439527310181,1739137711.6191103,53.28994917869568,20.599100390241603,1739137711.6191118,53.28994917869568,-0.017442133960617272,1739137711.6191134,53.28994917869568,-3.1213199662788718,1739137711.6191146,53.28994917869568,-1.0292977601946054,1739137711.619116,53.28994917869568,-0.3004926151657902,1739137711.6191173,53.28994917869568,1.6562758659309627,1739137711.6191187,53.28994917869568,0.0,1739137711.6191196,53.28994917869568,-0.23855032681271826,1739137711.6191213,53.28994917869568,3.3044894987778255,1739137711.6191227,53.28994917869568,1.894826192743681 +1739137711.6388607,53.30994915962219,27.635122922906426,1739137711.638863,53.30994915962219,0.09576369431802068,1739137711.638866,53.30994915962219,85.06247122762859,1739137711.6388686,53.30994915962219,20.689216556656653,1739137711.6388698,53.30994915962219,-0.01789957642972921,1739137711.6388717,53.30994915962219,-3.12523004794836,1739137711.6388729,53.30994915962219,-1.0187818489732667,1739137711.6388743,53.30994915962219,-0.3230096519024196,1739137711.6388755,53.30994915962219,1.6632574391434134,1739137711.6388772,53.30994915962219,0.0,1739137711.6388783,53.30994915962219,-0.15608994338868465,1739137711.63888,53.30994915962219,3.3051401794804582,1739137711.6388812,53.30994915962219,1.8586142513971544 +1739137711.6587346,53.329949140548706,27.635122922906426,1739137711.658737,53.329949140548706,0.09576369431802068,1739137711.6587398,53.329949140548706,85.06247122762859,1739137711.6587424,53.329949140548706,20.689216556656653,1739137711.6587439,53.329949140548706,-0.01789957642972921,1739137711.6587455,53.329949140548706,-3.12523004794836,1739137711.658747,53.329949140548706,-1.0187818489732667,1739137711.6587484,53.329949140548706,-0.3230096519024196,1739137711.6587496,53.329949140548706,1.6632574391434134,1739137711.6587515,53.329949140548706,0.0,1739137711.6587527,53.329949140548706,-0.19535681225374102,1739137711.6587543,53.329949140548706,3.3051401794804582,1739137711.6587555,53.329949140548706,1.8586142513971544 +1739137711.6788905,53.34994912147522,27.635122922906426,1739137711.6788936,53.34994912147522,0.09576369431802068,1739137711.678897,53.34994912147522,85.06247122762859,1739137711.6789,53.34994912147522,20.689216556656653,1739137711.6789014,53.34994912147522,-0.01789957642972921,1739137711.6789036,53.34994912147522,-3.12523004794836,1739137711.6789052,53.34994912147522,-1.0187818489732667,1739137711.678907,53.34994912147522,-0.3230096519024196,1739137711.6789083,53.34994912147522,1.6632574391434134,1739137711.6789103,53.34994912147522,0.0,1739137711.6789114,53.34994912147522,-0.19535681225374102,1739137711.6789134,53.34994912147522,3.3051401794804582,1739137711.6789148,53.34994912147522,1.8586142513971544 +1739137711.6992435,53.36994910240173,27.635122922906426,1739137711.6992464,53.36994910240173,0.09576369431802068,1739137711.69925,53.36994910240173,85.06247122762859,1739137711.6992533,53.36994910240173,20.689216556656653,1739137711.6992548,53.36994910240173,-0.01789957642972921,1739137711.699257,53.36994910240173,-3.12523004794836,1739137711.6992586,53.36994910240173,-1.0187818489732667,1739137711.6992602,53.36994910240173,-0.3230096519024196,1739137711.699262,53.36994910240173,1.6632574391434134,1739137711.6992638,53.36994910240173,0.0,1739137711.6992655,53.36994910240173,-0.19535681225374102,1739137711.6992674,53.36994910240173,3.3051401794804582,1739137711.6992688,53.36994910240173,1.8586142513971544 +1739137711.7190213,53.38994908332825,27.635122922906426,1739137711.7190244,53.38994908332825,0.09576369431802068,1739137711.719028,53.38994908332825,85.06247122762859,1739137711.7190318,53.38994908332825,20.689216556656653,1739137711.7190337,53.38994908332825,-0.01789957642972921,1739137711.7190356,53.38994908332825,-3.12523004794836,1739137711.7190375,53.38994908332825,-1.0187818489732667,1739137711.7190394,53.38994908332825,-0.3230096519024196,1739137711.719041,53.38994908332825,1.6632574391434134,1739137711.719043,53.38994908332825,0.0,1739137711.719045,53.38994908332825,-0.19535681225374102,1739137711.7190468,53.38994908332825,3.3051401794804582,1739137711.719049,53.38994908332825,1.8586142513971544 +1739137711.739729,53.40994906425476,27.434521948079365,1739137711.7397327,53.40994906425476,0.06267976747914794,1739137711.7397382,53.40994906425476,85.08069283241102,1739137711.7397482,53.40994906425476,20.736772947790065,1739137711.739754,53.40994906425476,-0.017947518656453967,1739137711.73976,53.40994906425476,-3.129555267322799,1739137711.7397645,53.40994906425476,-1.0083060120286103,1739137711.73977,53.40994906425476,-0.34368228575848003,1739137711.739777,53.40994906425476,1.6702416675431606,1739137711.739782,53.40994906425476,0.0,1739137711.739787,53.40994906425476,-0.1401642215713054,1739137711.7397919,53.40994906425476,3.3047375415419027,1739137711.7397966,53.40994906425476,1.8366880882828278 +1739137711.7625973,53.429949045181274,27.434521948079365,1739137711.762603,53.429949045181274,0.06267976747914794,1739137711.7626107,53.429949045181274,85.08069283241102,1739137711.7626197,53.429949045181274,20.736772947790065,1739137711.7626245,53.429949045181274,-0.017947518656453967,1739137711.762631,53.429949045181274,-3.129555267322799,1739137711.762637,53.429949045181274,-1.0083060120286103,1739137711.7626424,53.429949045181274,-0.34368228575848003,1739137711.7626483,53.429949045181274,1.6702416675431606,1739137711.7626543,53.429949045181274,0.0,1739137711.7626598,53.429949045181274,-0.1664464207396672,1739137711.762702,53.429949045181274,3.3047375415419027,1739137711.762709,53.429949045181274,1.8366880882828278 +1739137711.780855,53.44994902610779,27.434521948079365,1739137711.7808583,53.44994902610779,0.06267976747914794,1739137711.7808626,53.44994902610779,85.08069283241102,1739137711.780867,53.44994902610779,20.736772947790065,1739137711.7808697,53.44994902610779,-0.017947518656453967,1739137711.7808733,53.44994902610779,-3.129555267322799,1739137711.780876,53.44994902610779,-1.0083060120286103,1739137711.780879,53.44994902610779,-0.34368228575848003,1739137711.7808821,53.44994902610779,1.6702416675431606,1739137711.7808852,53.44994902610779,0.0,1739137711.7808883,53.44994902610779,-0.1664464207396672,1739137711.7808917,53.44994902610779,3.3047375415419027,1739137711.7808945,53.44994902610779,1.8366880882828278 +1739137711.8007653,53.4699490070343,27.434521948079365,1739137711.8007681,53.4699490070343,0.06267976747914794,1739137711.8007724,53.4699490070343,85.08069283241102,1739137711.800777,53.4699490070343,20.736772947790065,1739137711.8007796,53.4699490070343,-0.017947518656453967,1739137711.800783,53.4699490070343,-3.129555267322799,1739137711.800786,53.4699490070343,-1.0083060120286103,1739137711.8007889,53.4699490070343,-0.34368228575848003,1739137711.800792,53.4699490070343,1.6702416675431606,1739137711.8007953,53.4699490070343,0.0,1739137711.8007984,53.4699490070343,-0.1664464207396672,1739137711.8008015,53.4699490070343,3.3047375415419027,1739137711.8008046,53.4699490070343,1.8366880882828278 +1739137711.8188992,53.489948987960815,27.434521948079365,1739137711.8189018,53.489948987960815,0.06267976747914794,1739137711.8189049,53.489948987960815,85.08069283241102,1739137711.8189075,53.489948987960815,20.736772947790065,1739137711.8189087,53.489948987960815,-0.017947518656453967,1739137711.8189104,53.489948987960815,-3.129555267322799,1739137711.8189118,53.489948987960815,-1.0083060120286103,1739137711.818913,53.489948987960815,-0.34368228575848003,1739137711.8189144,53.489948987960815,1.6702416675431606,1739137711.8189158,53.489948987960815,0.0,1739137711.818917,53.489948987960815,-0.1664464207396672,1739137711.8189187,53.489948987960815,3.3047375415419027,1739137711.81892,53.489948987960815,1.8366880882828278 +1739137711.8389325,53.50994896888733,27.434521948079365,1739137711.8389344,53.50994896888733,0.06267976747914794,1739137711.838937,53.50994896888733,85.08069283241102,1739137711.8389394,53.50994896888733,20.736772947790065,1739137711.8389406,53.50994896888733,-0.017947518656453967,1739137711.838942,53.50994896888733,-3.129555267322799,1739137711.8389432,53.50994896888733,-1.0083060120286103,1739137711.8389447,53.50994896888733,-0.34368228575848003,1739137711.8389459,53.50994896888733,1.6702416675431606,1739137711.8389473,53.50994896888733,0.0,1739137711.8389482,53.50994896888733,-0.1664464207396672,1739137711.8389497,53.50994896888733,3.3047375415419027,1739137711.8389509,53.50994896888733,1.8366880882828278 +1739137711.8587453,53.52994894981384,27.236001997306087,1739137711.858748,53.52994894981384,0.030119951407558965,1739137711.8587506,53.52994894981384,85.61361761025742,1739137711.858753,53.52994894981384,20.256983060305124,1739137711.8587544,53.52994894981384,-0.01567257327550114,1739137711.8587558,53.52994894981384,-3.1350312918927687,1739137711.858757,53.52994894981384,-1.0782017937442363,1739137711.8587584,53.52994894981384,-0.3385591989510926,1739137711.8587596,53.52994894981384,1.6241912740256483,1739137711.8587613,53.52994894981384,0.0,1739137711.8587627,53.52994894981384,-0.22055335393591846,1739137711.858764,53.52994894981384,3.303263792840904,1739137711.8587654,53.52994894981384,1.818979408806785 +1739137711.8823621,53.549948930740356,27.236001997306087,1739137711.8823705,53.549948930740356,0.030119951407558965,1739137711.88238,53.549948930740356,85.61361761025742,1739137711.8823895,53.549948930740356,20.256983060305124,1739137711.8823946,53.549948930740356,-0.01567257327550114,1739137711.8824003,53.549948930740356,-3.1350312918927687,1739137711.8824053,53.549948930740356,-1.0782017937442363,1739137711.882411,53.549948930740356,-0.3385591989510926,1739137711.882427,53.549948930740356,1.6241912740256483,1739137711.8824496,53.549948930740356,0.0,1739137711.8824625,53.549948930740356,-0.19478813478113666,1739137711.882497,53.549948930740356,3.303263792840904,1739137711.8825145,53.549948930740356,1.818979408806785 +1739137711.9017255,53.56994891166687,27.236001997306087,1739137711.9017313,53.56994891166687,0.030119951407558965,1739137711.9017382,53.56994891166687,85.61361761025742,1739137711.9017446,53.56994891166687,20.256983060305124,1739137711.9017484,53.56994891166687,-0.01567257327550114,1739137711.9017525,53.56994891166687,-3.1350312918927687,1739137711.9017565,53.56994891166687,-1.0782017937442363,1739137711.9017594,53.56994891166687,-0.3385591989510926,1739137711.9017627,53.56994891166687,1.6241912740256483,1739137711.9017665,53.56994891166687,0.0,1739137711.9017696,53.56994891166687,-0.19478813478113666,1739137711.9017735,53.56994891166687,3.303263792840904,1739137711.9017768,53.56994891166687,1.818979408806785 +1739137711.9210832,53.589948892593384,27.236001997306087,1739137711.9210875,53.589948892593384,0.030119951407558965,1739137711.9210927,53.589948892593384,85.61361761025742,1739137711.9210982,53.589948892593384,20.256983060305124,1739137711.921101,53.589948892593384,-0.01567257327550114,1739137711.9211042,53.589948892593384,-3.1350312918927687,1739137711.9211066,53.589948892593384,-1.0782017937442363,1739137711.9211092,53.589948892593384,-0.3385591989510926,1739137711.9211118,53.589948892593384,1.6241912740256483,1739137711.9211147,53.589948892593384,0.0,1739137711.921117,53.589948892593384,-0.19478813478113666,1739137711.92112,53.589948892593384,3.303263792840904,1739137711.9211226,53.589948892593384,1.818979408806785 +1739137711.9402258,53.6099488735199,27.236001997306087,1739137711.9402306,53.6099488735199,0.030119951407558965,1739137711.940236,53.6099488735199,85.61361761025742,1739137711.940241,53.6099488735199,20.256983060305124,1739137711.940244,53.6099488735199,-0.01567257327550114,1739137711.9402473,53.6099488735199,-3.1350312918927687,1739137711.9402502,53.6099488735199,-1.0782017937442363,1739137711.940253,53.6099488735199,-0.3385591989510926,1739137711.9402552,53.6099488735199,1.6241912740256483,1739137711.9402585,53.6099488735199,0.0,1739137711.9402611,53.6099488735199,-0.19478813478113666,1739137711.940264,53.6099488735199,3.303263792840904,1739137711.9402666,53.6099488735199,1.818979408806785 +1739137711.9601393,53.62994885444641,27.039557738521875,1739137711.9601438,53.62994885444641,-0.0017034591407663058,1739137711.960149,53.62994885444641,85.63126577013746,1739137711.9601538,53.62994885444641,20.303982651437856,1739137711.9601567,53.62994885444641,-0.01610075827007209,1739137711.9601598,53.62994885444641,-3.1394551557493617,1739137711.9601626,53.62994885444641,-1.0530139649062362,1739137711.960165,53.62994885444641,-0.3548476959296337,1739137711.9601674,53.62994885444641,1.6406379267220184,1739137711.9601703,53.62994885444641,0.0,1739137711.960173,53.62994885444641,-0.12224922757441697,1739137711.9601762,53.62994885444641,3.3007098959476067,1739137711.9601786,53.62994885444641,1.797429508316955 +1739137711.9830878,53.649948835372925,27.039557738521875,1739137711.983095,53.649948835372925,-0.0017034591407663058,1739137711.9831033,53.649948835372925,85.63126577013746,1739137711.983111,53.649948835372925,20.303982651437856,1739137711.9831154,53.649948835372925,-0.01610075827007209,1739137711.9831212,53.649948835372925,-3.1394551557493617,1739137711.9831266,53.649948835372925,-1.0530139649062362,1739137711.983132,53.649948835372925,-0.3548476959296337,1739137711.9831367,53.649948835372925,1.6406379267220184,1739137711.9831412,53.649948835372925,0.0,1739137711.983146,53.649948835372925,-0.15679158159493656,1739137711.9831512,53.649948835372925,3.3007098959476067,1739137711.983156,53.649948835372925,1.797429508316955 +1739137712.0010808,53.66994881629944,27.039557738521875,1739137712.0010839,53.66994881629944,-0.0017034591407663058,1739137712.0010881,53.66994881629944,85.63126577013746,1739137712.0010931,53.66994881629944,20.303982651437856,1739137712.001096,53.66994881629944,-0.01610075827007209,1739137712.0010996,53.66994881629944,-3.1394551557493617,1739137712.0011027,53.66994881629944,-1.0530139649062362,1739137712.001106,53.66994881629944,-0.3548476959296337,1739137712.001109,53.66994881629944,1.6406379267220184,1739137712.0011122,53.66994881629944,0.0,1739137712.0011153,53.66994881629944,-0.15679158159493656,1739137712.0011187,53.66994881629944,3.3007098959476067,1739137712.001122,53.66994881629944,1.797429508316955 +1739137712.0194304,53.68994879722595,27.039557738521875,1739137712.0194325,53.68994879722595,-0.0017034591407663058,1739137712.019435,53.68994879722595,85.63126577013746,1739137712.0194376,53.68994879722595,20.303982651437856,1739137712.0194387,53.68994879722595,-0.01610075827007209,1739137712.0194404,53.68994879722595,-3.1394551557493617,1739137712.0194414,53.68994879722595,-1.0530139649062362,1739137712.0194428,53.68994879722595,-0.3548476959296337,1739137712.0194445,53.68994879722595,1.6406379267220184,1739137712.0194457,53.68994879722595,0.0,1739137712.019447,53.68994879722595,-0.15679158159493656,1739137712.0194485,53.68994879722595,3.3007098959476067,1739137712.0194497,53.68994879722595,1.797429508316955 +1739137712.0393605,53.709948778152466,27.039557738521875,1739137712.0393627,53.709948778152466,-0.0017034591407663058,1739137712.0393653,53.709948778152466,85.63126577013746,1739137712.039368,53.709948778152466,20.303982651437856,1739137712.039369,53.709948778152466,-0.01610075827007209,1739137712.0393708,53.709948778152466,-3.1394551557493617,1739137712.039372,53.709948778152466,-1.0530139649062362,1739137712.0393734,53.709948778152466,-0.3548476959296337,1739137712.0393744,53.709948778152466,1.6406379267220184,1739137712.0393758,53.709948778152466,0.0,1739137712.0393772,53.709948778152466,-0.15679158159493656,1739137712.0393784,53.709948778152466,3.3007098959476067,1739137712.0393796,53.709948778152466,1.797429508316955 +1739137712.0591125,53.72994875907898,27.039557738521875,1739137712.059115,53.72994875907898,-0.0017034591407663058,1739137712.0591176,53.72994875907898,85.63126577013746,1739137712.0591202,53.72994875907898,20.303982651437856,1739137712.0591214,53.72994875907898,-0.01610075827007209,1739137712.0591233,53.72994875907898,-3.1394551557493617,1739137712.0591245,53.72994875907898,-1.0530139649062362,1739137712.0591257,53.72994875907898,-0.3548476959296337,1739137712.059127,53.72994875907898,1.6406379267220184,1739137712.0591285,53.72994875907898,0.0,1739137712.05913,53.72994875907898,-0.15679158159493656,1739137712.0591311,53.72994875907898,3.3007098959476067,1739137712.0591323,53.72994875907898,1.797429508316955 +1739137712.0790532,53.74994874000549,26.845074473445923,1739137712.079056,53.74994874000549,-0.03260150991091315,1739137712.079059,53.74994874000549,85.64873836594352,1739137712.0790617,53.74994874000549,20.335972716828703,1739137712.079063,53.74994874000549,-0.0163942451085202,1739137712.0790648,53.74994874000549,3.13910271996844,1739137712.0790663,53.74994874000549,-1.0239529724207659,1739137712.0790677,53.74994874000549,-0.36933839150134595,1739137712.0790691,53.74994874000549,1.659820630983513,1739137712.0790708,53.74994874000549,0.0,1739137712.079072,53.74994874000549,-0.08869292870917418,1739137712.0790734,53.74994874000549,3.2970693304666474,1739137712.079075,53.74994874000549,1.7809415058374642 +1739137712.0994134,53.76994872093201,26.845074473445923,1739137712.0994155,53.76994872093201,-0.03260150991091315,1739137712.0994182,53.76994872093201,85.64873836594352,1739137712.0994208,53.76994872093201,20.335972716828703,1739137712.0994222,53.76994872093201,-0.0163942451085202,1739137712.0994236,53.76994872093201,3.13910271996844,1739137712.099425,53.76994872093201,-1.0239529724207659,1739137712.0994265,53.76994872093201,-0.36933839150134595,1739137712.0994277,53.76994872093201,1.659820630983513,1739137712.0994291,53.76994872093201,0.0,1739137712.0994303,53.76994872093201,-0.12112087485395118,1739137712.099432,53.76994872093201,3.2970693304666474,1739137712.0994332,53.76994872093201,1.7809415058374642 +1739137712.1193573,53.78994870185852,26.845074473445923,1739137712.1193597,53.78994870185852,-0.03260150991091315,1739137712.1193624,53.78994870185852,85.64873836594352,1739137712.119365,53.78994870185852,20.335972716828703,1739137712.1193662,53.78994870185852,-0.0163942451085202,1739137712.1193676,53.78994870185852,3.13910271996844,1739137712.119369,53.78994870185852,-1.0239529724207659,1739137712.1193702,53.78994870185852,-0.36933839150134595,1739137712.1193714,53.78994870185852,1.659820630983513,1739137712.1193728,53.78994870185852,0.0,1739137712.119374,53.78994870185852,-0.12112087485395118,1739137712.1193757,53.78994870185852,3.2970693304666474,1739137712.119377,53.78994870185852,1.7809415058374642 +1739137712.1393666,53.809948682785034,26.845074473445923,1739137712.139369,53.809948682785034,-0.03260150991091315,1739137712.1393716,53.809948682785034,85.64873836594352,1739137712.139374,53.809948682785034,20.335972716828703,1739137712.1393754,53.809948682785034,-0.0163942451085202,1739137712.139377,53.809948682785034,3.13910271996844,1739137712.1393788,53.809948682785034,-1.0239529724207659,1739137712.13938,53.809948682785034,-0.36933839150134595,1739137712.139381,53.809948682785034,1.659820630983513,1739137712.1393826,53.809948682785034,0.0,1739137712.1393838,53.809948682785034,-0.12112087485395118,1739137712.1393855,53.809948682785034,3.2970693304666474,1739137712.1393867,53.809948682785034,1.7809415058374642 +1739137712.159388,53.82994866371155,26.845074473445923,1739137712.1593912,53.82994866371155,-0.03260150991091315,1739137712.1593943,53.82994866371155,85.64873836594352,1739137712.1593971,53.82994866371155,20.335972716828703,1739137712.1593986,53.82994866371155,-0.0163942451085202,1739137712.1594002,53.82994866371155,3.13910271996844,1739137712.1594017,53.82994866371155,-1.0239529724207659,1739137712.1594028,53.82994866371155,-0.36933839150134595,1739137712.1594043,53.82994866371155,1.659820630983513,1739137712.1594055,53.82994866371155,0.0,1739137712.159407,53.82994866371155,-0.12112087485395118,1739137712.1594086,53.82994866371155,3.2970693304666474,1739137712.15941,53.82994866371155,1.7809415058374642 +1739137712.178932,53.84994864463806,26.65210806040921,1739137712.1789346,53.84994864463806,-0.062440001908433906,1739137712.1789374,53.84994864463806,85.93899178742139,1739137712.17894,53.84994864463806,20.08461238657829,1739137712.1789415,53.84994864463806,-0.015,1739137712.1789432,53.84994864463806,3.13436932537191,1739137712.1789446,53.84994864463806,-1.033100212182274,1739137712.178946,53.84994864463806,-0.36605685753963135,1739137712.1789472,53.84994864463806,1.653758616976486,1739137712.178949,53.84994864463806,0.0,1739137712.17895,53.84994864463806,-0.10794769905888599,1739137712.1789517,53.84994864463806,3.2923262975123193,1739137712.178953,53.84994864463806,1.7679792600237745 +1739137712.1986876,53.869948625564575,26.65210806040921,1739137712.1986897,53.869948625564575,-0.062440001908433906,1739137712.1986923,53.869948625564575,85.93899178742139,1739137712.1986947,53.869948625564575,20.08461238657829,1739137712.1986961,53.869948625564575,-0.015,1739137712.1986978,53.869948625564575,3.13436932537191,1739137712.1986992,53.869948625564575,-1.033100212182274,1739137712.1987002,53.869948625564575,-0.36605685753963135,1739137712.1987016,53.869948625564575,1.653758616976486,1739137712.198703,53.869948625564575,0.0,1739137712.1987045,53.869948625564575,-0.11422064304728852,1739137712.198706,53.869948625564575,3.2923262975123193,1739137712.198707,53.869948625564575,1.7679792600237745 +1739137712.218585,53.88994860649109,26.65210806040921,1739137712.2185874,53.88994860649109,-0.062440001908433906,1739137712.2185903,53.88994860649109,85.93899178742139,1739137712.2185931,53.88994860649109,20.08461238657829,1739137712.2185943,53.88994860649109,-0.015,1739137712.218596,53.88994860649109,3.13436932537191,1739137712.2185974,53.88994860649109,-1.033100212182274,1739137712.2185988,53.88994860649109,-0.36605685753963135,1739137712.2186003,53.88994860649109,1.653758616976486,1739137712.2186017,53.88994860649109,0.0,1739137712.2186027,53.88994860649109,-0.11422064304728852,1739137712.2186043,53.88994860649109,3.2923262975123193,1739137712.2186055,53.88994860649109,1.7679792600237745 +1739137712.2384427,53.9099485874176,26.65210806040921,1739137712.2384448,53.9099485874176,-0.062440001908433906,1739137712.2384474,53.9099485874176,85.93899178742139,1739137712.2384503,53.9099485874176,20.08461238657829,1739137712.2384515,53.9099485874176,-0.015,1739137712.238453,53.9099485874176,3.13436932537191,1739137712.2384546,53.9099485874176,-1.033100212182274,1739137712.238456,53.9099485874176,-0.36605685753963135,1739137712.2384574,53.9099485874176,1.653758616976486,1739137712.2384586,53.9099485874176,0.0,1739137712.2384598,53.9099485874176,-0.11422064304728852,1739137712.2384613,53.9099485874176,3.2923262975123193,1739137712.2384624,53.9099485874176,1.7679792600237745 +1739137712.2585511,53.929948568344116,26.65210806040921,1739137712.2585533,53.929948568344116,-0.062440001908433906,1739137712.258556,53.929948568344116,85.93899178742139,1739137712.2585585,53.929948568344116,20.08461238657829,1739137712.2585597,53.929948568344116,-0.015,1739137712.2585616,53.929948568344116,3.13436932537191,1739137712.2585628,53.929948568344116,-1.033100212182274,1739137712.258564,53.929948568344116,-0.36605685753963135,1739137712.2585654,53.929948568344116,1.653758616976486,1739137712.2585669,53.929948568344116,0.0,1739137712.2585683,53.929948568344116,-0.11422064304728852,1739137712.2585695,53.929948568344116,3.2923262975123193,1739137712.2585707,53.929948568344116,1.7679792600237745 +1739137712.2785103,53.94994854927063,26.65210806040921,1739137712.2785127,53.94994854927063,-0.062440001908433906,1739137712.278515,53.94994854927063,85.93899178742139,1739137712.2785177,53.94994854927063,20.08461238657829,1739137712.2785194,53.94994854927063,-0.015,1739137712.2785208,53.94994854927063,3.13436932537191,1739137712.2785223,53.94994854927063,-1.033100212182274,1739137712.278524,53.94994854927063,-0.36605685753963135,1739137712.278525,53.94994854927063,1.653758616976486,1739137712.2785268,53.94994854927063,0.0,1739137712.278528,53.94994854927063,-0.11422064304728852,1739137712.2785292,53.94994854927063,3.2923262975123193,1739137712.2785306,53.94994854927063,1.7679792600237745 +1739137712.2987635,53.969948530197144,26.460369426786553,1739137712.2987664,53.969948530197144,-0.09105902837873536,1739137712.29877,53.969948530197144,85.94762002593441,1739137712.2987728,53.969948530197144,20.113143308699666,1739137712.2987742,53.969948530197144,-0.015,1739137712.2987761,53.969948530197144,3.1296101927856763,1739137712.2987778,53.969948530197144,-0.9916093251617736,1739137712.2987795,53.969948530197144,-0.3760267936894489,1739137712.298781,53.969948530197144,1.6814340017665677,1739137712.2987823,53.969948530197144,0.0,1739137712.2987843,53.969948530197144,-0.0377390442207638,1739137712.2987862,53.969948530197144,3.286468619319421,1739137712.2987876,53.969948530197144,1.755592873145638 +1739137712.3190024,53.98994851112366,26.460369426786553,1739137712.3190057,53.98994851112366,-0.09105902837873536,1739137712.3190095,53.98994851112366,85.94762002593441,1739137712.3190134,53.98994851112366,20.113143308699666,1739137712.3190155,53.98994851112366,-0.015,1739137712.3190176,53.98994851112366,3.1296101927856763,1739137712.3190198,53.98994851112366,-0.9916093251617736,1739137712.3190215,53.98994851112366,-0.3760267936894489,1739137712.3190236,53.98994851112366,1.6814340017665677,1739137712.3190258,53.98994851112366,0.0,1739137712.3190274,53.98994851112366,-0.0741588713790704,1739137712.3190298,53.98994851112366,3.286468619319421,1739137712.3190315,53.98994851112366,1.755592873145638 +1739137712.339647,54.00994849205017,26.460369426786553,1739137712.3396509,54.00994849205017,-0.09105902837873536,1739137712.3396552,54.00994849205017,85.94762002593441,1739137712.3396595,54.00994849205017,20.113143308699666,1739137712.3396618,54.00994849205017,-0.015,1739137712.3396647,54.00994849205017,3.1296101927856763,1739137712.3396668,54.00994849205017,-0.9916093251617736,1739137712.3396692,54.00994849205017,-0.3760267936894489,1739137712.3396714,54.00994849205017,1.6814340017665677,1739137712.3396735,54.00994849205017,0.0,1739137712.3396757,54.00994849205017,-0.0741588713790704,1739137712.3396785,54.00994849205017,3.286468619319421,1739137712.3396804,54.00994849205017,1.755592873145638 +1739137712.361185,54.029948472976685,26.460369426786553,1739137712.3611896,54.029948472976685,-0.09105902837873536,1739137712.361195,54.029948472976685,85.94762002593441,1739137712.3612,54.029948472976685,20.113143308699666,1739137712.3612027,54.029948472976685,-0.015,1739137712.3612058,54.029948472976685,3.1296101927856763,1739137712.3612087,54.029948472976685,-0.9916093251617736,1739137712.3612108,54.029948472976685,-0.3760267936894489,1739137712.3612134,54.029948472976685,1.6814340017665677,1739137712.3612165,54.029948472976685,0.0,1739137712.3612192,54.029948472976685,-0.0741588713790704,1739137712.3612218,54.029948472976685,3.286468619319421,1739137712.3612244,54.029948472976685,1.755592873145638 +1739137712.3802335,54.0499484539032,26.460369426786553,1739137712.3802378,54.0499484539032,-0.09105902837873536,1739137712.3802433,54.0499484539032,85.94762002593441,1739137712.3802483,54.0499484539032,20.113143308699666,1739137712.380251,54.0499484539032,-0.015,1739137712.3802543,54.0499484539032,3.1296101927856763,1739137712.3802567,54.0499484539032,-0.9916093251617736,1739137712.3802593,54.0499484539032,-0.3760267936894489,1739137712.380262,54.0499484539032,1.6814340017665677,1739137712.3802648,54.0499484539032,0.0,1739137712.3802674,54.0499484539032,-0.0741588713790704,1739137712.38027,54.0499484539032,3.286468619319421,1739137712.3802726,54.0499484539032,1.755592873145638 +1739137712.4001682,54.06994843482971,26.269572927994837,1739137712.4001727,54.06994843482971,-0.11829649419604671,1739137712.4001777,54.06994843482971,86.47053593993269,1739137712.4001827,54.06994843482971,19.61360042123884,1739137712.4001853,54.06994843482971,-0.012,1739137712.4001887,54.06994843482971,3.1256239189360193,1739137712.4001913,54.06994843482971,-1.0202013865077217,1739137712.400194,54.06994843482971,-0.35200100576717464,1739137712.4001963,54.06994843482971,1.6623132846755917,1739137712.4001992,54.06994843482971,0.0,1739137712.4002018,54.06994843482971,-0.09579697566824291,1739137712.4002047,54.06994843482971,3.2794868267057873,1739137712.400207,54.06994843482971,1.747806396011284 +1739137712.4216313,54.089948415756226,26.269572927994837,1739137712.4216356,54.089948415756226,-0.11829649419604671,1739137712.4216409,54.089948415756226,86.47053593993269,1739137712.421646,54.089948415756226,19.61360042123884,1739137712.4216487,54.089948415756226,-0.012,1739137712.421652,54.089948415756226,3.1256239189360193,1739137712.4216545,54.089948415756226,-1.0202013865077217,1739137712.421657,54.089948415756226,-0.35200100576717464,1739137712.4216597,54.089948415756226,1.6623132846755917,1739137712.4216626,54.089948415756226,0.0,1739137712.421665,54.089948415756226,-0.08549311133569226,1739137712.4216678,54.089948415756226,3.2794868267057873,1739137712.4216704,54.089948415756226,1.747806396011284 +1739137712.4410646,54.10994839668274,26.269572927994837,1739137712.441069,54.10994839668274,-0.11829649419604671,1739137712.441074,54.10994839668274,86.47053593993269,1739137712.4410791,54.10994839668274,19.61360042123884,1739137712.4410815,54.10994839668274,-0.012,1739137712.4410846,54.10994839668274,3.1256239189360193,1739137712.4410875,54.10994839668274,-1.0202013865077217,1739137712.44109,54.10994839668274,-0.35200100576717464,1739137712.4410923,54.10994839668274,1.6623132846755917,1739137712.4410954,54.10994839668274,0.0,1739137712.4410977,54.10994839668274,-0.08549311133569226,1739137712.4411006,54.10994839668274,3.2794868267057873,1739137712.4411032,54.10994839668274,1.747806396011284 +1739137712.4610815,54.12994837760925,26.269572927994837,1739137712.4610868,54.12994837760925,-0.11829649419604671,1739137712.4610922,54.12994837760925,86.47053593993269,1739137712.4610975,54.12994837760925,19.61360042123884,1739137712.4611003,54.12994837760925,-0.012,1739137712.4611037,54.12994837760925,3.1256239189360193,1739137712.461106,54.12994837760925,-1.0202013865077217,1739137712.4611092,54.12994837760925,-0.35200100576717464,1739137712.4611115,54.12994837760925,1.6623132846755917,1739137712.4611146,54.12994837760925,0.0,1739137712.4611173,54.12994837760925,-0.08549311133569226,1739137712.46112,54.12994837760925,3.2794868267057873,1739137712.4611225,54.12994837760925,1.747806396011284 +1739137712.4797676,54.14994835853577,26.269572927994837,1739137712.4797714,54.14994835853577,-0.11829649419604671,1739137712.4797754,54.14994835853577,86.47053593993269,1739137712.4797792,54.14994835853577,19.61360042123884,1739137712.4797814,54.14994835853577,-0.012,1739137712.4797838,54.14994835853577,3.1256239189360193,1739137712.4797854,54.14994835853577,-1.0202013865077217,1739137712.4797876,54.14994835853577,-0.35200100576717464,1739137712.4797893,54.14994835853577,1.6623132846755917,1739137712.4797912,54.14994835853577,0.0,1739137712.479793,54.14994835853577,-0.08549311133569226,1739137712.4797952,54.14994835853577,3.2794868267057873,1739137712.4797966,54.14994835853577,1.747806396011284 +1739137712.4993582,54.16994833946228,26.269572927994837,1739137712.4993615,54.16994833946228,-0.11829649419604671,1739137712.4993649,54.16994833946228,86.47053593993269,1739137712.499368,54.16994833946228,19.61360042123884,1739137712.4993694,54.16994833946228,-0.012,1739137712.4993713,54.16994833946228,3.1256239189360193,1739137712.4993725,54.16994833946228,-1.0202013865077217,1739137712.4993742,54.16994833946228,-0.35200100576717464,1739137712.4993753,54.16994833946228,1.6623132846755917,1739137712.499377,54.16994833946228,0.0,1739137712.4993784,54.16994833946228,-0.08549311133569226,1739137712.4993799,54.16994833946228,3.2794868267057873,1739137712.4993815,54.16994833946228,1.747806396011284 +1739137712.52118,54.189948320388794,26.079530185108798,1739137712.5211837,54.189948320388794,-0.1439745106790724,1739137712.521188,54.189948320388794,86.47471688027619,1739137712.521193,54.189948320388794,19.638125767076875,1739137712.521196,54.189948320388794,-0.012055688791607944,1739137712.5211997,54.189948320388794,3.121115693178954,1739137712.5212028,54.189948320388794,-0.9644474685947673,1739137712.521206,54.189948320388794,-0.35521420298921735,1739137712.5212092,54.189948320388794,1.699801950273209,1739137712.5212128,54.189948320388794,0.0,1739137712.521216,54.189948320388794,0.00434399788940238,1739137712.5212195,54.189948320388794,3.271375363899069,1739137712.5212228,54.189948320388794,1.738237549575558 +1739137712.544821,54.20994830131531,26.079530185108798,1739137712.5448294,54.20994830131531,-0.1439745106790724,1739137712.544839,54.20994830131531,86.47471688027619,1739137712.5448487,54.20994830131531,19.638125767076875,1739137712.5448534,54.20994830131531,-0.012055688791607944,1739137712.5448592,54.20994830131531,3.121115693178954,1739137712.5448642,54.20994830131531,-0.9644474685947673,1739137712.544869,54.20994830131531,-0.35521420298921735,1739137712.5448735,54.20994830131531,1.699801950273209,1739137712.5448785,54.20994830131531,0.0,1739137712.5448835,54.20994830131531,-0.03843559930234908,1739137712.5448885,54.20994830131531,3.271375363899069,1739137712.5448935,54.20994830131531,1.738237549575558 +1739137712.5862138,54.249948263168335,26.079530185108798,1739137712.5862224,54.249948263168335,-0.1439745106790724,1739137712.5862317,54.249948263168335,86.47471688027619,1739137712.5862415,54.249948263168335,19.638125767076875,1739137712.5862465,54.249948263168335,-0.012055688791607944,1739137712.5862517,54.249948263168335,3.121115693178954,1739137712.586257,54.249948263168335,-0.9644474685947673,1739137712.5862615,54.249948263168335,-0.35521420298921735,1739137712.5862663,54.249948263168335,1.699801950273209,1739137712.586272,54.249948263168335,0.0,1739137712.5862765,54.249948263168335,-0.03843559930234908,1739137712.5862823,54.249948263168335,3.271375363899069,1739137712.5862865,54.249948263168335,1.738237549575558 +1739137712.6059515,54.25994825363159,26.079530185108798,1739137712.6059573,54.25994825363159,-0.1439745106790724,1739137712.6059647,54.25994825363159,86.47471688027619,1739137712.6059716,54.25994825363159,19.638125767076875,1739137712.6059747,54.25994825363159,-0.012055688791607944,1739137712.6059787,54.25994825363159,3.121115693178954,1739137712.605982,54.25994825363159,-0.9644474685947673,1739137712.6059852,54.25994825363159,-0.35521420298921735,1739137712.6059885,54.25994825363159,1.699801950273209,1739137712.6059926,54.25994825363159,0.0,1739137712.6059954,54.25994825363159,-0.03843559930234908,1739137712.6059995,54.25994825363159,3.271375363899069,1739137712.6060026,54.25994825363159,1.738237549575558 +1739137712.6228592,54.28994822502136,25.890015739342648,1739137712.6228642,54.28994822502136,-0.16791836594736154,1739137712.6228695,54.28994822502136,86.47888619808305,1739137712.6228747,54.28994822502136,19.645413596986472,1739137712.6228771,54.28994822502136,-0.0121219417907861,1739137712.6228802,54.28994822502136,3.116648852937558,1739137712.622883,54.28994822502136,-0.9055711426637237,1739137712.6228862,54.28994822502136,-0.3548153198846584,1739137712.622889,54.28994822502136,1.740308288460706,1739137712.6228917,54.28994822502136,0.0,1739137712.6228943,54.28994822502136,0.046185824941302925,1739137712.6228971,54.28994822502136,3.2621330368987675,1739137712.6229,54.28994822502136,1.7344183999554847 +1739137712.6432624,54.309948205947876,25.890015739342648,1739137712.6432672,54.309948205947876,-0.16791836594736154,1739137712.6432722,54.309948205947876,86.47888619808305,1739137712.643278,54.309948205947876,19.645413596986472,1739137712.6432803,54.309948205947876,-0.0121219417907861,1739137712.6432834,54.309948205947876,3.116648852937558,1739137712.643286,54.309948205947876,-0.9055711426637237,1739137712.6432889,54.309948205947876,-0.3548153198846584,1739137712.6432915,54.309948205947876,1.740308288460706,1739137712.643294,54.309948205947876,0.0,1739137712.6432965,54.309948205947876,0.005889888505221208,1739137712.6432996,54.309948205947876,3.2621330368987675,1739137712.6433022,54.309948205947876,1.7344183999554847 +1739137712.6625051,54.32994818687439,25.890015739342648,1739137712.66251,54.32994818687439,-0.16791836594736154,1739137712.6625154,54.32994818687439,86.47888619808305,1739137712.6625211,54.32994818687439,19.645413596986472,1739137712.6625237,54.32994818687439,-0.0121219417907861,1739137712.6625264,54.32994818687439,3.116648852937558,1739137712.6625292,54.32994818687439,-0.9055711426637237,1739137712.6625319,54.32994818687439,-0.3548153198846584,1739137712.6625345,54.32994818687439,1.740308288460706,1739137712.662537,54.32994818687439,0.0,1739137712.6625397,54.32994818687439,0.005889888505221208,1739137712.6625428,54.32994818687439,3.2621330368987675,1739137712.6625454,54.32994818687439,1.7344183999554847 +1739137712.6825426,54.3499481678009,25.890015739342648,1739137712.6825457,54.3499481678009,-0.16791836594736154,1739137712.6825495,54.3499481678009,86.47888619808305,1739137712.682553,54.3499481678009,19.645413596986472,1739137712.682555,54.3499481678009,-0.0121219417907861,1739137712.6825573,54.3499481678009,3.116648852937558,1739137712.6825593,54.3499481678009,-0.9055711426637237,1739137712.682561,54.3499481678009,-0.3548153198846584,1739137712.6825635,54.3499481678009,1.740308288460706,1739137712.6825657,54.3499481678009,0.0,1739137712.6825674,54.3499481678009,0.005889888505221208,1739137712.6825693,54.3499481678009,3.2621330368987675,1739137712.682571,54.3499481678009,1.7344183999554847 +1739137712.7029474,54.36994814872742,25.890015739342648,1739137712.7029505,54.36994814872742,-0.16791836594736154,1739137712.7029555,54.36994814872742,86.47888619808305,1739137712.7029607,54.36994814872742,19.645413596986472,1739137712.7029638,54.36994814872742,-0.0121219417907861,1739137712.7029674,54.36994814872742,3.116648852937558,1739137712.7029707,54.36994814872742,-0.9055711426637237,1739137712.7029736,54.36994814872742,-0.3548153198846584,1739137712.702977,54.36994814872742,1.740308288460706,1739137712.7029803,54.36994814872742,0.0,1739137712.7029834,54.36994814872742,0.005889888505221208,1739137712.702987,54.36994814872742,3.2621330368987675,1739137712.70299,54.36994814872742,1.7344183999554847 +1739137712.721874,54.38994812965393,25.890015739342648,1739137712.7218776,54.38994812965393,-0.16791836594736154,1739137712.7218819,54.38994812965393,86.47888619808305,1739137712.7218866,54.38994812965393,19.645413596986472,1739137712.7218897,54.38994812965393,-0.0121219417907861,1739137712.7218933,54.38994812965393,3.116648852937558,1739137712.7218966,54.38994812965393,-0.9055711426637237,1739137712.7218997,54.38994812965393,-0.3548153198846584,1739137712.721903,54.38994812965393,1.740308288460706,1739137712.7219064,54.38994812965393,0.0,1739137712.7219095,54.38994812965393,0.005889888505221208,1739137712.7219129,54.38994812965393,3.2621330368987675,1739137712.7219162,54.38994812965393,1.7344183999554847 +1739137712.7419934,54.409948110580444,25.700402944006672,1739137712.741997,54.409948110580444,-0.1899960266792755,1739137712.742001,54.409948110580444,87.04382675517276,1739137712.742006,54.409948110580444,19.076142974718667,1739137712.7420087,54.409948110580444,-0.011,1739137712.7420118,54.409948110580444,3.1145779407103107,1739137712.742015,54.409948110580444,-0.9061207777258035,1739137712.742018,54.409948110580444,-0.315774845457316,1739137712.742021,54.409948110580444,1.7399257167355473,1739137712.7420242,54.409948110580444,0.0,1739137712.7420275,54.409948110580444,0.002401634373131451,1739137712.7420309,54.409948110580444,3.251745990646336,1739137712.742034,54.409948110580444,1.7358630081364035 +1739137712.762902,54.42994809150696,25.700402944006672,1739137712.7629056,54.42994809150696,-0.1899960266792755,1739137712.7629101,54.42994809150696,87.04382675517276,1739137712.7629154,54.42994809150696,19.076142974718667,1739137712.7629182,54.42994809150696,-0.011,1739137712.762922,54.42994809150696,3.1145779407103107,1739137712.7629251,54.42994809150696,-0.9061207777258035,1739137712.7629287,54.42994809150696,-0.315774845457316,1739137712.762932,54.42994809150696,1.7399257167355473,1739137712.7629354,54.42994809150696,0.0,1739137712.7629387,54.42994809150696,0.004062708599143816,1739137712.7629418,54.42994809150696,3.251745990646336,1739137712.762945,54.42994809150696,1.7358630081364035 +1739137712.7817807,54.44994807243347,25.700402944006672,1739137712.7817838,54.44994807243347,-0.1899960266792755,1739137712.7817876,54.44994807243347,87.04382675517276,1739137712.7817922,54.44994807243347,19.076142974718667,1739137712.7817948,54.44994807243347,-0.011,1739137712.7817981,54.44994807243347,3.1145779407103107,1739137712.7818012,54.44994807243347,-0.9061207777258035,1739137712.7818043,54.44994807243347,-0.315774845457316,1739137712.7818074,54.44994807243347,1.7399257167355473,1739137712.7818105,54.44994807243347,0.0,1739137712.7818136,54.44994807243347,0.004062708599143816,1739137712.7818165,54.44994807243347,3.251745990646336,1739137712.7818196,54.44994807243347,1.7358630081364035 +1739137712.8041341,54.469948053359985,25.700402944006672,1739137712.8041375,54.469948053359985,-0.1899960266792755,1739137712.8041418,54.469948053359985,87.04382675517276,1739137712.8041468,54.469948053359985,19.076142974718667,1739137712.8041494,54.469948053359985,-0.011,1739137712.8041716,54.469948053359985,3.1145779407103107,1739137712.804175,54.469948053359985,-0.9061207777258035,1739137712.8041782,54.469948053359985,-0.315774845457316,1739137712.8041816,54.469948053359985,1.7399257167355473,1739137712.804185,54.469948053359985,0.0,1739137712.8041883,54.469948053359985,0.004062708599143816,1739137712.804192,54.469948053359985,3.251745990646336,1739137712.8041954,54.469948053359985,1.7358630081364035 +1739137712.8232818,54.4899480342865,25.700402944006672,1739137712.823285,54.4899480342865,-0.1899960266792755,1739137712.8232892,54.4899480342865,87.04382675517276,1739137712.8232937,54.4899480342865,19.076142974718667,1739137712.8232965,54.4899480342865,-0.011,1739137712.8233,54.4899480342865,3.1145779407103107,1739137712.823303,54.4899480342865,-0.9061207777258035,1739137712.8233058,54.4899480342865,-0.315774845457316,1739137712.8233087,54.4899480342865,1.7399257167355473,1739137712.8233118,54.4899480342865,0.0,1739137712.823315,54.4899480342865,0.004062708599143816,1739137712.8233182,54.4899480342865,3.251745990646336,1739137712.823321,54.4899480342865,1.7358630081364035 +1739137712.8451402,54.50994801521301,25.51048969607527,1739137712.8451467,54.50994801521301,-0.21001135034567664,1739137712.8451545,54.50994801521301,87.05237285132966,1739137712.8451622,54.50994801521301,19.06631008564695,1739137712.8451657,54.50994801521301,-0.011,1739137712.8451703,54.50994801521301,3.1107201249538945,1739137712.8451738,54.50994801521301,-0.8325359915870977,1739137712.8451777,54.50994801521301,-0.3065699054145585,1739137712.845181,54.50994801521301,1.7918996878780744,1739137712.8451853,54.50994801521301,0.0,1739137712.8451889,54.50994801521301,0.10246692088656288,1739137712.8451927,54.50994801521301,3.2402120782433705,1739137712.8451962,54.50994801521301,1.73629193910801 +1739137712.8655813,54.529947996139526,25.51048969607527,1739137712.865588,54.529947996139526,-0.21001135034567664,1739137712.8655956,54.529947996139526,87.05237285132966,1739137712.865603,54.529947996139526,19.06631008564695,1739137712.8656073,54.529947996139526,-0.011,1739137712.8656116,54.529947996139526,3.1107201249538945,1739137712.8656154,54.529947996139526,-0.8325359915870977,1739137712.865619,54.529947996139526,-0.3065699054145585,1739137712.8656225,54.529947996139526,1.7918996878780744,1739137712.8656268,54.529947996139526,0.0,1739137712.8656301,54.529947996139526,0.05560774877006436,1739137712.8656342,54.529947996139526,3.2402120782433705,1739137712.8656375,54.529947996139526,1.73629193910801 +1739137712.8842835,54.54994797706604,25.51048969607527,1739137712.8842902,54.54994797706604,-0.21001135034567664,1739137712.8842983,54.54994797706604,87.05237285132966,1739137712.884306,54.54994797706604,19.06631008564695,1739137712.8843093,54.54994797706604,-0.011,1739137712.884314,54.54994797706604,3.1107201249538945,1739137712.8843179,54.54994797706604,-0.8325359915870977,1739137712.8843215,54.54994797706604,-0.3065699054145585,1739137712.8843248,54.54994797706604,1.7918996878780744,1739137712.8843288,54.54994797706604,0.0,1739137712.8843327,54.54994797706604,0.05560774877006436,1739137712.8843367,54.54994797706604,3.2402120782433705,1739137712.88434,54.54994797706604,1.73629193910801 +1739137712.908486,54.5599479675293,25.51048969607527,1739137712.9084926,54.5599479675293,-0.21001135034567664,1739137712.9085004,54.5599479675293,87.05237285132966,1739137712.9085088,54.5599479675293,19.06631008564695,1739137712.9085126,54.5599479675293,-0.011,1739137712.908517,54.5599479675293,3.1107201249538945,1739137712.9085205,54.5599479675293,-0.8325359915870977,1739137712.908524,54.5599479675293,-0.3065699054145585,1739137712.9085276,54.5599479675293,1.7918996878780744,1739137712.908537,54.5599479675293,0.0,1739137712.9085464,54.5599479675293,0.05560774877006436,1739137712.9085515,54.5599479675293,3.2402120782433705,1739137712.9085553,54.5599479675293,1.73629193910801 +1739137712.9274526,54.58994793891907,25.51048969607527,1739137712.927459,54.58994793891907,-0.21001135034567664,1739137712.9274664,54.58994793891907,87.05237285132966,1739137712.9274733,54.58994793891907,19.06631008564695,1739137712.927477,54.58994793891907,-0.011,1739137712.9274814,54.58994793891907,3.1107201249538945,1739137712.927485,54.58994793891907,-0.8325359915870977,1739137712.9274886,54.58994793891907,-0.3065699054145585,1739137712.9274921,54.58994793891907,1.7918996878780744,1739137712.927496,54.58994793891907,0.0,1739137712.9274995,54.58994793891907,0.05560774877006436,1739137712.9275033,54.58994793891907,3.2402120782433705,1739137712.9275072,54.58994793891907,1.73629193910801 +1739137712.945906,54.60994791984558,25.51048969607527,1739137712.9459114,54.60994791984558,-0.21001135034567664,1739137712.9459174,54.60994791984558,87.05237285132966,1739137712.945923,54.60994791984558,19.06631008564695,1739137712.945926,54.60994791984558,-0.011,1739137712.945929,54.60994791984558,3.1107201249538945,1739137712.9459317,54.60994791984558,-0.8325359915870977,1739137712.9459345,54.60994791984558,-0.3065699054145585,1739137712.9459374,54.60994791984558,1.7918996878780744,1739137712.9459407,54.60994791984558,0.0,1739137712.9459438,54.60994791984558,0.05560774877006436,1739137712.945947,54.60994791984558,3.2402120782433705,1739137712.9459498,54.60994791984558,1.73629193910801 +1739137712.9662058,54.629947900772095,25.31993363322317,1739137712.9662108,54.629947900772095,-0.22780176864678214,1739137712.966217,54.629947900772095,87.060947874158,1739137712.9662223,54.629947900772095,19.036673099661762,1739137712.9662254,54.629947900772095,-0.011,1739137712.966229,54.629947900772095,3.1071016771997,1739137712.9662318,54.629947900772095,-0.7585960889314801,1739137712.9662344,54.629947900772095,-0.29384812572898966,1739137712.966237,54.629947900772095,1.8456883480781472,1739137712.9662402,54.629947900772095,0.0,1739137712.9662428,54.629947900772095,0.14489216405355987,1739137712.966246,54.629947900772095,3.228057463564,1739137712.9662485,54.629947900772095,1.7433125934936273 +1739137712.9861498,54.64994788169861,25.31993363322317,1739137712.986155,54.64994788169861,-0.22780176864678214,1739137712.986161,54.64994788169861,87.060947874158,1739137712.9861665,54.64994788169861,19.036673099661762,1739137712.986169,54.64994788169861,-0.011,1739137712.9861724,54.64994788169861,3.1071016771997,1739137712.9861753,54.64994788169861,-0.7585960889314801,1739137712.9861782,54.64994788169861,-0.29384812572898966,1739137712.9861805,54.64994788169861,1.8456883480781472,1739137712.9861841,54.64994788169861,0.0,1739137712.9861867,54.64994788169861,0.10237575458451986,1739137712.9861898,54.64994788169861,3.228057463564,1739137712.9861925,54.64994788169861,1.7433125934936273 +1739137713.009586,54.659947872161865,25.31993363322317,1739137713.0095932,54.659947872161865,-0.22780176864678214,1739137713.0096025,54.659947872161865,87.060947874158,1739137713.0096133,54.659947872161865,19.036673099661762,1739137713.0096195,54.659947872161865,-0.011,1739137713.0096273,54.659947872161865,3.1071016771997,1739137713.0096345,54.659947872161865,-0.7585960889314801,1739137713.0096416,54.659947872161865,-0.29384812572898966,1739137713.0096486,54.659947872161865,1.8456883480781472,1739137713.0096557,54.659947872161865,0.0,1739137713.0096629,54.659947872161865,0.10237575458451986,1739137713.0096705,54.659947872161865,3.228057463564,1739137713.0096774,54.659947872161865,1.7433125934936273 +1739137713.0273495,54.689947843551636,25.31993363322317,1739137713.0273545,54.689947843551636,-0.22780176864678214,1739137713.02736,54.689947843551636,87.060947874158,1739137713.0273652,54.689947843551636,19.036673099661762,1739137713.0273676,54.689947843551636,-0.011,1739137713.0273712,54.689947843551636,3.1071016771997,1739137713.027374,54.689947843551636,-0.7585960889314801,1739137713.0273767,54.689947843551636,-0.29384812572898966,1739137713.0273795,54.689947843551636,1.8456883480781472,1739137713.0273829,54.689947843551636,0.0,1739137713.0273852,54.689947843551636,0.10237575458451986,1739137713.0273883,54.689947843551636,3.228057463564,1739137713.027391,54.689947843551636,1.7433125934936273 +1739137713.0477087,54.70994782447815,25.31993363322317,1739137713.0477135,54.70994782447815,-0.22780176864678214,1739137713.0477195,54.70994782447815,87.060947874158,1739137713.0477247,54.70994782447815,19.036673099661762,1739137713.0477276,54.70994782447815,-0.011,1739137713.0477312,54.70994782447815,3.1071016771997,1739137713.047734,54.70994782447815,-0.7585960889314801,1739137713.047737,54.70994782447815,-0.29384812572898966,1739137713.0477395,54.70994782447815,1.8456883480781472,1739137713.0477424,54.70994782447815,0.0,1739137713.0477452,54.70994782447815,0.10237575458451986,1739137713.0477483,54.70994782447815,3.228057463564,1739137713.047751,54.70994782447815,1.7433125934936273 +1739137713.0665019,54.72994780540466,25.12821354157748,1739137713.066507,54.72994780540466,-0.24335225011994055,1739137713.0665119,54.72994780540466,87.76932375120317,1739137713.0665164,54.72994780540466,18.293546499785165,1739137713.0665188,54.72994780540466,-0.008084618809754106,1739137713.0665214,54.72994780540466,3.1071835490480266,1739137713.0665236,54.72994780540466,-0.7420365029886973,1739137713.066526,54.72994780540466,-0.24317271702170187,1739137713.0665283,54.72994780540466,1.8579544615113706,1739137713.0665307,54.72994780540466,0.0,1739137713.0665329,54.72994780540466,0.10366993485076026,1739137713.0665355,54.72994780540466,3.215902848884629,1739137713.0665374,54.72994780540466,1.7549008032857247 +1739137713.0844138,54.74994778633118,25.12821354157748,1739137713.0844162,54.74994778633118,-0.24335225011994055,1739137713.0844188,54.74994778633118,87.76932375120317,1739137713.0844214,54.74994778633118,18.293546499785165,1739137713.0844228,54.74994778633118,-0.008084618809754106,1739137713.0844245,54.74994778633118,3.1071835490480266,1739137713.0844257,54.74994778633118,-0.7420365029886973,1739137713.084427,54.74994778633118,-0.24317271702170187,1739137713.0844283,54.74994778633118,1.8579544615113706,1739137713.0844297,54.74994778633118,0.0,1739137713.084431,54.74994778633118,0.10305365822564583,1739137713.0844321,54.74994778633118,3.215902848884629,1739137713.0844333,54.74994778633118,1.7549008032857247 +1739137713.1041358,54.76994776725769,25.12821354157748,1739137713.104138,54.76994776725769,-0.24335225011994055,1739137713.1041403,54.76994776725769,87.76932375120317,1739137713.104143,54.76994776725769,18.293546499785165,1739137713.104144,54.76994776725769,-0.008084618809754106,1739137713.1041458,54.76994776725769,3.1071835490480266,1739137713.104147,54.76994776725769,-0.7420365029886973,1739137713.104148,54.76994776725769,-0.24317271702170187,1739137713.1041493,54.76994776725769,1.8579544615113706,1739137713.1041505,54.76994776725769,0.0,1739137713.1041515,54.76994776725769,0.10305365822564583,1739137713.1041532,54.76994776725769,3.215902848884629,1739137713.104154,54.76994776725769,1.7549008032857247 +1739137713.1239178,54.789947748184204,25.12821354157748,1739137713.1239204,54.789947748184204,-0.24335225011994055,1739137713.1239226,54.789947748184204,87.76932375120317,1739137713.1239252,54.789947748184204,18.293546499785165,1739137713.1239269,54.789947748184204,-0.008084618809754106,1739137713.1239283,54.789947748184204,3.1071835490480266,1739137713.1239295,54.789947748184204,-0.7420365029886973,1739137713.123931,54.789947748184204,-0.24317271702170187,1739137713.1239321,54.789947748184204,1.8579544615113706,1739137713.1239338,54.789947748184204,0.0,1739137713.123948,54.789947748184204,0.10305365822564583,1739137713.1239495,54.789947748184204,3.215902848884629,1739137713.123951,54.789947748184204,1.7549008032857247 +1739137713.143757,54.80994772911072,25.12821354157748,1739137713.143759,54.80994772911072,-0.24335225011994055,1739137713.1437616,54.80994772911072,87.76932375120317,1739137713.143764,54.80994772911072,18.293546499785165,1739137713.1437652,54.80994772911072,-0.008084618809754106,1739137713.1437669,54.80994772911072,3.1071835490480266,1739137713.1437683,54.80994772911072,-0.7420365029886973,1739137713.1437693,54.80994772911072,-0.24317271702170187,1739137713.1437707,54.80994772911072,1.8579544615113706,1739137713.143772,54.80994772911072,0.0,1739137713.1437728,54.80994772911072,0.10305365822564583,1739137713.1437745,54.80994772911072,3.215902848884629,1739137713.1437757,54.80994772911072,1.7549008032857247 +1739137713.1657984,54.82994771003723,25.12821354157748,1739137713.1658003,54.82994771003723,-0.24335225011994055,1739137713.1658032,54.82994771003723,87.76932375120317,1739137713.1658058,54.82994771003723,18.293546499785165,1739137713.165807,54.82994771003723,-0.008084618809754106,1739137713.1658087,54.82994771003723,3.1071835490480266,1739137713.1658099,54.82994771003723,-0.7420365029886973,1739137713.1658113,54.82994771003723,-0.24317271702170187,1739137713.1658125,54.82994771003723,1.8579544615113706,1739137713.165814,54.82994771003723,0.0,1739137713.1658154,54.82994771003723,0.10305365822564583,1739137713.1658165,54.82994771003723,3.215902848884629,1739137713.1658177,54.82994771003723,1.7549008032857247 +1739137713.1838303,54.849947690963745,24.93506686495389,1739137713.1838326,54.849947690963745,-0.2566576572548831,1739137713.183835,54.849947690963745,87.79192191236812,1739137713.183838,54.849947690963745,18.237049068205152,1739137713.183839,54.849947690963745,-0.007956100757835016,1739137713.1838405,54.849947690963745,3.1044790828352364,1739137713.1838417,54.849947690963745,-0.6642724795607964,1739137713.1838431,54.849947690963745,-0.2266829768405761,1739137713.1838443,54.849947690963745,1.9166555000241792,1739137713.183846,54.849947690963745,0.0,1739137713.1838474,54.849947690963745,0.19354663354496113,1739137713.1838489,54.849947690963745,3.2037482342052583,1739137713.1838503,54.849947690963745,1.7662007810147098 +1739137713.2038646,54.86994767189026,24.93506686495389,1739137713.2038672,54.86994767189026,-0.2566576572548831,1739137713.20387,54.86994767189026,87.79192191236812,1739137713.2038727,54.86994767189026,18.237049068205152,1739137713.2038743,54.86994767189026,-0.007956100757835016,1739137713.2038758,54.86994767189026,3.1044790828352364,1739137713.2038774,54.86994767189026,-0.6642724795607964,1739137713.2038786,54.86994767189026,-0.2266829768405761,1739137713.2038798,54.86994767189026,1.9166555000241792,1739137713.2038815,54.86994767189026,0.0,1739137713.2038827,54.86994767189026,0.15045471900946938,1739137713.2038844,54.86994767189026,3.2037482342052583,1739137713.2038856,54.86994767189026,1.7662007810147098 +1739137713.2249842,54.88994765281677,24.93506686495389,1739137713.224987,54.88994765281677,-0.2566576572548831,1739137713.2249897,54.88994765281677,87.79192191236812,1739137713.2249928,54.88994765281677,18.237049068205152,1739137713.2249944,54.88994765281677,-0.007956100757835016,1739137713.2249959,54.88994765281677,3.1044790828352364,1739137713.224997,54.88994765281677,-0.6642724795607964,1739137713.2249987,54.88994765281677,-0.2266829768405761,1739137713.2249997,54.88994765281677,1.9166555000241792,1739137713.2250013,54.88994765281677,0.0,1739137713.2250028,54.88994765281677,0.15045471900946938,1739137713.2250042,54.88994765281677,3.2037482342052583,1739137713.2250056,54.88994765281677,1.7662007810147098 +1739137713.2450254,54.909947633743286,24.93506686495389,1739137713.2450278,54.909947633743286,-0.2566576572548831,1739137713.2450306,54.909947633743286,87.79192191236812,1739137713.2450335,54.909947633743286,18.237049068205152,1739137713.2450347,54.909947633743286,-0.007956100757835016,1739137713.2450366,54.909947633743286,3.1044790828352364,1739137713.2450378,54.909947633743286,-0.6642724795607964,1739137713.245039,54.909947633743286,-0.2266829768405761,1739137713.2450404,54.909947633743286,1.9166555000241792,1739137713.2450416,54.909947633743286,0.0,1739137713.245043,54.909947633743286,0.15045471900946938,1739137713.2450445,54.909947633743286,3.2037482342052583,1739137713.2450457,54.909947633743286,1.7662007810147098 +1739137713.264194,54.9299476146698,24.93506686495389,1739137713.2641962,54.9299476146698,-0.2566576572548831,1739137713.2641985,54.9299476146698,87.79192191236812,1739137713.2642012,54.9299476146698,18.237049068205152,1739137713.2642026,54.9299476146698,-0.007956100757835016,1739137713.264204,54.9299476146698,3.1044790828352364,1739137713.2642052,54.9299476146698,-0.6642724795607964,1739137713.2642066,54.9299476146698,-0.2266829768405761,1739137713.2642078,54.9299476146698,1.9166555000241792,1739137713.2642093,54.9299476146698,0.0,1739137713.2642107,54.9299476146698,0.15045471900946938,1739137713.264212,54.9299476146698,3.2037482342052583,1739137713.2642133,54.9299476146698,1.7662007810147098 +1739137713.2841747,54.94994759559631,24.74024937348394,1739137713.2841773,54.94994759559631,-0.26771762297076585,1739137713.2841806,54.94994759559631,87.8147155588701,1739137713.2841833,54.94994759559631,18.163693207700582,1739137713.2841847,54.94994759559631,-0.0071410356411175865,1739137713.2841861,54.94994759559631,3.101991325965779,1739137713.2841876,54.94994759559631,-0.5909834981494151,1739137713.2841892,54.94994759559631,-0.20921046863194592,1739137713.2841904,54.94994759559631,1.9736750897667277,1739137713.284192,54.94994759559631,0.0,1739137713.2841933,54.94994759559631,0.22713149842866165,1739137713.2841947,54.94994759559631,3.191904122810309,1739137713.2841961,54.94994759559631,1.7830563616821673 +1739137713.3041196,54.96994757652283,24.74024937348394,1739137713.3041227,54.96994757652283,-0.26771762297076585,1739137713.3041255,54.96994757652283,87.8147155588701,1739137713.3041282,54.96994757652283,18.163693207700582,1739137713.3041296,54.96994757652283,-0.0071410356411175865,1739137713.3041315,54.96994757652283,3.101991325965779,1739137713.3041332,54.96994757652283,-0.5909834981494151,1739137713.3041344,54.96994757652283,-0.20921046863194592,1739137713.3041356,54.96994757652283,1.9736750897667277,1739137713.3041372,54.96994757652283,0.0,1739137713.3041382,54.96994757652283,0.19061872808456037,1739137713.3041399,54.96994757652283,3.191904122810309,1739137713.304141,54.96994757652283,1.7830563616821673 +1739137713.3242085,54.98994755744934,24.74024937348394,1739137713.3242114,54.98994755744934,-0.26771762297076585,1739137713.3242145,54.98994755744934,87.8147155588701,1739137713.3242173,54.98994755744934,18.163693207700582,1739137713.3242185,54.98994755744934,-0.0071410356411175865,1739137713.324221,54.98994755744934,3.101991325965779,1739137713.3242226,54.98994755744934,-0.5909834981494151,1739137713.3242238,54.98994755744934,-0.20921046863194592,1739137713.324225,54.98994755744934,1.9736750897667277,1739137713.3242264,54.98994755744934,0.0,1739137713.3242276,54.98994755744934,0.19061872808456037,1739137713.324229,54.98994755744934,3.191904122810309,1739137713.3242304,54.98994755744934,1.7830563616821673 +1739137713.3440905,55.009947538375854,24.74024937348394,1739137713.3440933,55.009947538375854,-0.26771762297076585,1739137713.3440967,55.009947538375854,87.8147155588701,1739137713.3440993,55.009947538375854,18.163693207700582,1739137713.344101,55.009947538375854,-0.0071410356411175865,1739137713.3441021,55.009947538375854,3.101991325965779,1739137713.3441036,55.009947538375854,-0.5909834981494151,1739137713.344105,55.009947538375854,-0.20921046863194592,1739137713.3441062,55.009947538375854,1.9736750897667277,1739137713.344108,55.009947538375854,0.0,1739137713.3441093,55.009947538375854,0.19061872808456037,1739137713.344111,55.009947538375854,3.191904122810309,1739137713.3441122,55.009947538375854,1.7830563616821673 +1739137713.3641055,55.02994751930237,24.74024937348394,1739137713.3641088,55.02994751930237,-0.26771762297076585,1739137713.3641121,55.02994751930237,87.8147155588701,1739137713.364115,55.02994751930237,18.163693207700582,1739137713.3641162,55.02994751930237,-0.0071410356411175865,1739137713.364118,55.02994751930237,3.101991325965779,1739137713.3641195,55.02994751930237,-0.5909834981494151,1739137713.3641207,55.02994751930237,-0.20921046863194592,1739137713.3641224,55.02994751930237,1.9736750897667277,1739137713.3641236,55.02994751930237,0.0,1739137713.364125,55.02994751930237,0.19061872808456037,1739137713.3641264,55.02994751930237,3.191904122810309,1739137713.3641276,55.02994751930237,1.7830563616821673 +1739137713.3840573,55.04994750022888,24.74024937348394,1739137713.3840601,55.04994750022888,-0.26771762297076585,1739137713.384063,55.04994750022888,87.8147155588701,1739137713.3840659,55.04994750022888,18.163693207700582,1739137713.384067,55.04994750022888,-0.0071410356411175865,1739137713.384069,55.04994750022888,3.101991325965779,1739137713.3840702,55.04994750022888,-0.5909834981494151,1739137713.3840716,55.04994750022888,-0.20921046863194592,1739137713.3840733,55.04994750022888,1.9736750897667277,1739137713.3840747,55.04994750022888,0.0,1739137713.384076,55.04994750022888,0.19061872808456037,1739137713.3840775,55.04994750022888,3.191904122810309,1739137713.3840792,55.04994750022888,1.7830563616821673 +1739137713.4041913,55.069947481155396,24.543200184768434,1739137713.404194,55.069947481155396,-0.27661595522036375,1739137713.4041975,55.069947481155396,88.3204733637054,1739137713.4041998,55.069947481155396,17.593147884279265,1739137713.4042013,55.069947481155396,-0.002836789937134795,1739137713.4042027,55.069947481155396,3.102220621273995,1739137713.4042046,55.069947481155396,-0.5452314199387512,1739137713.4042058,55.069947481155396,-0.17291840458116542,1739137713.404207,55.069947481155396,2.0101275221186925,1739137713.4042087,55.069947481155396,0.0,1739137713.4042099,55.069947481155396,0.21896830032952036,1739137713.404212,55.069947481155396,3.180690302509204,1739137713.4042132,55.069947481155396,1.8046590248400374 +1739137713.4240887,55.08994746208191,24.543200184768434,1739137713.4240916,55.08994746208191,-0.27661595522036375,1739137713.424095,55.08994746208191,88.3204733637054,1739137713.4240978,55.08994746208191,17.593147884279265,1739137713.4240994,55.08994746208191,-0.002836789937134795,1739137713.4241009,55.08994746208191,3.102220621273995,1739137713.4241023,55.08994746208191,-0.5452314199387512,1739137713.4241037,55.08994746208191,-0.17291840458116542,1739137713.424105,55.08994746208191,2.0101275221186925,1739137713.4241066,55.08994746208191,0.0,1739137713.4241078,55.08994746208191,0.20546849727865513,1739137713.4241092,55.08994746208191,3.180690302509204,1739137713.4241104,55.08994746208191,1.8046590248400374 +1739137713.4439075,55.10994744300842,24.543200184768434,1739137713.4439104,55.10994744300842,-0.27661595522036375,1739137713.443913,55.10994744300842,88.3204733637054,1739137713.4439158,55.10994744300842,17.593147884279265,1739137713.4439173,55.10994744300842,-0.002836789937134795,1739137713.443919,55.10994744300842,3.102220621273995,1739137713.4439204,55.10994744300842,-0.5452314199387512,1739137713.4439218,55.10994744300842,-0.17291840458116542,1739137713.4439232,55.10994744300842,2.0101275221186925,1739137713.443925,55.10994744300842,0.0,1739137713.4439263,55.10994744300842,0.20546849727865513,1739137713.4439282,55.10994744300842,3.180690302509204,1739137713.4439297,55.10994744300842,1.8046590248400374 +1739137713.4639292,55.12994742393494,24.543200184768434,1739137713.4639316,55.12994742393494,-0.27661595522036375,1739137713.463935,55.12994742393494,88.3204733637054,1739137713.4639375,55.12994742393494,17.593147884279265,1739137713.4639392,55.12994742393494,-0.002836789937134795,1739137713.4639409,55.12994742393494,3.102220621273995,1739137713.4639423,55.12994742393494,-0.5452314199387512,1739137713.4639437,55.12994742393494,-0.17291840458116542,1739137713.4639452,55.12994742393494,2.0101275221186925,1739137713.4639468,55.12994742393494,0.0,1739137713.4639482,55.12994742393494,0.20546849727865513,1739137713.46395,55.12994742393494,3.180690302509204,1739137713.463951,55.12994742393494,1.8046590248400374 +1739137713.4839025,55.14994740486145,24.543200184768434,1739137713.4839048,55.14994740486145,-0.27661595522036375,1739137713.4839077,55.14994740486145,88.3204733637054,1739137713.48391,55.14994740486145,17.593147884279265,1739137713.483912,55.14994740486145,-0.002836789937134795,1739137713.4839134,55.14994740486145,3.102220621273995,1739137713.483915,55.14994740486145,-0.5452314199387512,1739137713.4839163,55.14994740486145,-0.17291840458116542,1739137713.4839175,55.14994740486145,2.0101275221186925,1739137713.4839191,55.14994740486145,0.0,1739137713.4839208,55.14994740486145,0.20546849727865513,1739137713.4839225,55.14994740486145,3.180690302509204,1739137713.4839237,55.14994740486145,1.8046590248400374 +1739137713.5040953,55.169947385787964,24.34367212798187,1739137713.5040977,55.169947385787964,-0.28344725894210043,1739137713.504101,55.169947385787964,88.36077119987257,1739137713.5041037,55.169947385787964,17.485035264665225,1739137713.5041053,55.169947385787964,-0.0017683714830813285,1739137713.504107,55.169947385787964,3.1005464973838466,1739137713.5041084,55.169947385787964,-0.47753385205397153,1739137713.5041099,55.169947385787964,-0.15552440785816668,1739137713.504111,55.169947385787964,2.0653035042823653,1739137713.5041127,55.169947385787964,0.0,1739137713.504114,55.169947385787964,0.2676461694693746,1739137713.504115,55.169947385787964,3.1701692713964436,1739137713.5041165,55.169947385787964,1.8272657649326092 +1739137713.5239956,55.18994736671448,24.34367212798187,1739137713.5239983,55.18994736671448,-0.28344725894210043,1739137713.5240014,55.18994736671448,88.36077119987257,1739137713.5240037,55.18994736671448,17.485035264665225,1739137713.5240054,55.18994736671448,-0.0017683714830813285,1739137713.524007,55.18994736671448,3.1005464973838466,1739137713.5240088,55.18994736671448,-0.47753385205397153,1739137713.5240102,55.18994736671448,-0.15552440785816668,1739137713.5240116,55.18994736671448,2.0653035042823653,1739137713.5240128,55.18994736671448,0.0,1739137713.524014,55.18994736671448,0.23803773934975614,1739137713.524016,55.18994736671448,3.1701692713964436,1739137713.524017,55.18994736671448,1.8272657649326092 +1739137713.5439706,55.20994734764099,24.34367212798187,1739137713.543974,55.20994734764099,-0.28344725894210043,1739137713.543977,55.20994734764099,88.36077119987257,1739137713.54398,55.20994734764099,17.485035264665225,1739137713.543981,55.20994734764099,-0.0017683714830813285,1739137713.5439827,55.20994734764099,3.1005464973838466,1739137713.5439847,55.20994734764099,-0.47753385205397153,1739137713.5439858,55.20994734764099,-0.15552440785816668,1739137713.5439873,55.20994734764099,2.0653035042823653,1739137713.5439887,55.20994734764099,0.0,1739137713.5439901,55.20994734764099,0.23803773934975614,1739137713.5439916,55.20994734764099,3.1701692713964436,1739137713.5439928,55.20994734764099,1.8272657649326092 +1739137713.5640407,55.229947328567505,24.34367212798187,1739137713.564044,55.229947328567505,-0.28344725894210043,1739137713.564047,55.229947328567505,88.36077119987257,1739137713.5640497,55.229947328567505,17.485035264665225,1739137713.5640512,55.229947328567505,-0.0017683714830813285,1739137713.564053,55.229947328567505,3.1005464973838466,1739137713.5640543,55.229947328567505,-0.47753385205397153,1739137713.564056,55.229947328567505,-0.15552440785816668,1739137713.564057,55.229947328567505,2.0653035042823653,1739137713.5640588,55.229947328567505,0.0,1739137713.56406,55.229947328567505,0.23803773934975614,1739137713.5640614,55.229947328567505,3.1701692713964436,1739137713.5640628,55.229947328567505,1.8272657649326092 +1739137713.5839741,55.24994730949402,24.34367212798187,1739137713.583977,55.24994730949402,-0.28344725894210043,1739137713.58398,55.24994730949402,88.36077119987257,1739137713.583983,55.24994730949402,17.485035264665225,1739137713.5839844,55.24994730949402,-0.0017683714830813285,1739137713.5839863,55.24994730949402,3.1005464973838466,1739137713.5839877,55.24994730949402,-0.47753385205397153,1739137713.583989,55.24994730949402,-0.15552440785816668,1739137713.5839903,55.24994730949402,2.0653035042823653,1739137713.583992,55.24994730949402,0.0,1739137713.5839934,55.24994730949402,0.23803773934975614,1739137713.5839949,55.24994730949402,3.1701692713964436,1739137713.5839965,55.24994730949402,1.8272657649326092 +1739137713.6041923,55.26994729042053,24.34367212798187,1739137713.6041949,55.26994729042053,-0.28344725894210043,1739137713.6041973,55.26994729042053,88.36077119987257,1739137713.6042,55.26994729042053,17.485035264665225,1739137713.6042013,55.26994729042053,-0.0017683714830813285,1739137713.6042027,55.26994729042053,3.1005464973838466,1739137713.6042042,55.26994729042053,-0.47753385205397153,1739137713.6042056,55.26994729042053,-0.15552440785816668,1739137713.6042066,55.26994729042053,2.0653035042823653,1739137713.6042082,55.26994729042053,0.0,1739137713.6042094,55.26994729042053,0.23803773934975614,1739137713.6042109,55.26994729042053,3.1701692713964436,1739137713.6042123,55.26994729042053,1.8272657649326092 +1739137713.6251712,55.289947271347046,24.141370836201457,1739137713.625174,55.289947271347046,-0.2883349353838156,1739137713.625177,55.289947271347046,88.65105213733987,1739137713.62518,55.289947271347046,17.114792097528166,1739137713.6251812,55.289947271347046,0.001,1739137713.6251829,55.289947271347046,3.100438688940755,1739137713.6251843,55.289947271347046,-0.42318144791328016,1739137713.6251855,55.289947271347046,-0.1313459339564738,1739137713.625187,55.289947271347046,2.1106968480611337,1739137713.6251886,55.289947271347046,0.0,1739137713.6251898,55.289947271347046,0.2738048004078851,1739137713.6251912,55.289947271347046,3.1606498877286757,1739137713.6251924,55.289947271347046,1.8539239899986522 +1739137713.6440096,55.30994725227356,24.141370836201457,1739137713.6440127,55.30994725227356,-0.2883349353838156,1739137713.6440156,55.30994725227356,88.65105213733987,1739137713.6440182,55.30994725227356,17.114792097528166,1739137713.6440194,55.30994725227356,0.001,1739137713.6440217,55.30994725227356,3.100438688940755,1739137713.6440232,55.30994725227356,-0.42318144791328016,1739137713.6440246,55.30994725227356,-0.1313459339564738,1739137713.644026,55.30994725227356,2.1106968480611337,1739137713.6440277,55.30994725227356,0.0,1739137713.644029,55.30994725227356,0.2567728580624815,1739137713.64403,55.30994725227356,3.1606498877286757,1739137713.644032,55.30994725227356,1.8539239899986522 +1739137713.6659822,55.32994723320007,24.141370836201457,1739137713.6659865,55.32994723320007,-0.2883349353838156,1739137713.665992,55.32994723320007,88.65105213733987,1739137713.6659973,55.32994723320007,17.114792097528166,1739137713.6660001,55.32994723320007,0.001,1739137713.666004,55.32994723320007,3.100438688940755,1739137713.6660075,55.32994723320007,-0.42318144791328016,1739137713.6660109,55.32994723320007,-0.1313459339564738,1739137713.6660142,55.32994723320007,2.1106968480611337,1739137713.666018,55.32994723320007,0.0,1739137713.6660216,55.32994723320007,0.2567728580624815,1739137713.6660252,55.32994723320007,3.1606498877286757,1739137713.6660285,55.32994723320007,1.8539239899986522 +1739137713.6849916,55.34994721412659,24.141370836201457,1739137713.6849952,55.34994721412659,-0.2883349353838156,1739137713.685,55.34994721412659,88.65105213733987,1739137713.6850054,55.34994721412659,17.114792097528166,1739137713.6850083,55.34994721412659,0.001,1739137713.6850123,55.34994721412659,3.100438688940755,1739137713.6850166,55.34994721412659,-0.42318144791328016,1739137713.6850195,55.34994721412659,-0.1313459339564738,1739137713.685022,55.34994721412659,2.1106968480611337,1739137713.685025,55.34994721412659,0.0,1739137713.685029,55.34994721412659,0.2567728580624815,1739137713.6850336,55.34994721412659,3.1606498877286757,1739137713.685037,55.34994721412659,1.8539239899986522 +1739137713.7063558,55.3699471950531,24.141370836201457,1739137713.7063596,55.3699471950531,-0.2883349353838156,1739137713.7063644,55.3699471950531,88.65105213733987,1739137713.7063696,55.3699471950531,17.114792097528166,1739137713.7063725,55.3699471950531,0.001,1739137713.7063766,55.3699471950531,3.100438688940755,1739137713.70638,55.3699471950531,-0.42318144791328016,1739137713.706383,55.3699471950531,-0.1313459339564738,1739137713.7063868,55.3699471950531,2.1106968480611337,1739137713.7063904,55.3699471950531,0.0,1739137713.706394,55.3699471950531,0.2567728580624815,1739137713.7063975,55.3699471950531,3.1606498877286757,1739137713.706401,55.3699471950531,1.8539239899986522 +1739137713.7269742,55.389947175979614,23.936046740251538,1739137713.7269785,55.389947175979614,-0.2914331565026025,1739137713.7269843,55.389947175979614,88.66008639756167,1739137713.7269917,55.389947175979614,17.021004059496118,1739137713.7269948,55.389947175979614,0.0012517693561430576,1739137713.7269986,55.389947175979614,3.0992920709822878,1739137713.7270021,55.389947175979614,-0.36545941277440885,1739137713.7270055,55.389947175979614,-0.1171231047483797,1739137713.7270088,55.389947175979614,2.1599972893492674,1739137713.7270124,55.389947175979614,0.0,1739137713.7270157,55.389947175979614,0.2969571020336438,1739137713.7270193,55.389947175979614,3.1521192765829014,1739137713.7270226,55.389947175979614,1.8821755511465559 +1739137713.7465715,55.40994715690613,23.936046740251538,1739137713.7465756,55.40994715690613,-0.2914331565026025,1739137713.746582,55.40994715690613,88.66008639756167,1739137713.7465878,55.40994715690613,17.021004059496118,1739137713.7465904,55.40994715690613,0.0012517693561430576,1739137713.746595,55.40994715690613,3.0992920709822878,1739137713.7465987,55.40994715690613,-0.36545941277440885,1739137713.7466018,55.40994715690613,-0.1171231047483797,1739137713.7466037,55.40994715690613,2.1599972893492674,1739137713.7466073,55.40994715690613,0.0,1739137713.7466116,55.40994715690613,0.2778217382027115,1739137713.7466156,55.40994715690613,3.1521192765829014,1739137713.7466192,55.40994715690613,1.8821755511465559 +1739137713.7638645,55.42994713783264,23.936046740251538,1739137713.763867,55.42994713783264,-0.2914331565026025,1739137713.7638698,55.42994713783264,88.66008639756167,1739137713.7638726,55.42994713783264,17.021004059496118,1739137713.7638738,55.42994713783264,0.0012517693561430576,1739137713.7638755,55.42994713783264,3.0992920709822878,1739137713.763877,55.42994713783264,-0.36545941277440885,1739137713.7638786,55.42994713783264,-0.1171231047483797,1739137713.76388,55.42994713783264,2.1599972893492674,1739137713.7638812,55.42994713783264,0.0,1739137713.7638824,55.42994713783264,0.2778217382027115,1739137713.763884,55.42994713783264,3.1521192765829014,1739137713.7638853,55.42994713783264,1.8821755511465559 +1739137713.7862725,55.449947118759155,23.936046740251538,1739137713.7862763,55.449947118759155,-0.2914331565026025,1739137713.7862804,55.449947118759155,88.66008639756167,1739137713.7862852,55.449947118759155,17.021004059496118,1739137713.786287,55.449947118759155,0.0012517693561430576,1739137713.78629,55.449947118759155,3.0992920709822878,1739137713.7862923,55.449947118759155,-0.36545941277440885,1739137713.7862945,55.449947118759155,-0.1171231047483797,1739137713.7862968,55.449947118759155,2.1599972893492674,1739137713.7862995,55.449947118759155,0.0,1739137713.7863019,55.449947118759155,0.2778217382027115,1739137713.7863047,55.449947118759155,3.1521192765829014,1739137713.786307,55.449947118759155,1.8821755511465559 +1739137713.8065982,55.45994710922241,23.936046740251538,1739137713.806601,55.45994710922241,-0.2914331565026025,1739137713.8066037,55.45994710922241,88.66008639756167,1739137713.8066065,55.45994710922241,17.021004059496118,1739137713.806608,55.45994710922241,0.0012517693561430576,1739137713.8066096,55.45994710922241,3.0992920709822878,1739137713.806611,55.45994710922241,-0.36545941277440885,1739137713.8066125,55.45994710922241,-0.1171231047483797,1739137713.8066134,55.45994710922241,2.1599972893492674,1739137713.806615,55.45994710922241,0.0,1739137713.8066163,55.45994710922241,0.2778217382027115,1739137713.8066177,55.45994710922241,3.1521192765829014,1739137713.8066194,55.45994710922241,1.8821755511465559 +1739137713.8243153,55.48994708061218,23.936046740251538,1739137713.824318,55.48994708061218,-0.2914331565026025,1739137713.8243213,55.48994708061218,88.66008639756167,1739137713.824324,55.48994708061218,17.021004059496118,1739137713.824325,55.48994708061218,0.0012517693561430576,1739137713.8243265,55.48994708061218,3.0992920709822878,1739137713.824328,55.48994708061218,-0.36545941277440885,1739137713.8243291,55.48994708061218,-0.1171231047483797,1739137713.8243303,55.48994708061218,2.1599972893492674,1739137713.8243318,55.48994708061218,0.0,1739137713.8243327,55.48994708061218,0.2778217382027115,1739137713.8243341,55.48994708061218,3.1521192765829014,1739137713.8243353,55.48994708061218,1.8821755511465559 +1739137713.8442361,55.509947061538696,23.72745281417265,1739137713.8442385,55.509947061538696,-0.29289319817520365,1739137713.8442416,55.509947061538696,88.66926453030914,1739137713.844244,55.509947061538696,16.919410411935885,1739137713.8442454,55.509947061538696,0.0019826589069360896,1739137713.8442473,55.509947061538696,3.09830683796427,1739137713.8442488,55.509947061538696,-0.3150486964061659,1739137713.8442502,55.509947061538696,-0.1041683620739838,1739137713.8442514,55.509947061538696,2.203994185901998,1739137713.8442528,55.509947061538696,0.0,1739137713.8442543,55.509947061538696,0.303004278771828,1739137713.8442554,55.509947061538696,3.1445559376465546,1739137713.8442569,55.509947061538696,1.9129815991058376 +1739137713.8638098,55.52994704246521,23.72745281417265,1739137713.8638127,55.52994704246521,-0.29289319817520365,1739137713.8638153,55.52994704246521,88.66926453030914,1739137713.8638182,55.52994704246521,16.919410411935885,1739137713.8638196,55.52994704246521,0.0019826589069360896,1739137713.8638213,55.52994704246521,3.09830683796427,1739137713.8638227,55.52994704246521,-0.3150486964061659,1739137713.863824,55.52994704246521,-0.1041683620739838,1739137713.863825,55.52994704246521,2.203994185901998,1739137713.8638268,55.52994704246521,0.0,1739137713.863828,55.52994704246521,0.2910125867961604,1739137713.8638296,55.52994704246521,3.1445559376465546,1739137713.8638308,55.52994704246521,1.9129815991058376 +1739137713.883845,55.549947023391724,23.72745281417265,1739137713.8838477,55.549947023391724,-0.29289319817520365,1739137713.883851,55.549947023391724,88.66926453030914,1739137713.883854,55.549947023391724,16.919410411935885,1739137713.8838553,55.549947023391724,0.0019826589069360896,1739137713.883857,55.549947023391724,3.09830683796427,1739137713.8838584,55.549947023391724,-0.3150486964061659,1739137713.8838599,55.549947023391724,-0.1041683620739838,1739137713.8838615,55.549947023391724,2.203994185901998,1739137713.8838632,55.549947023391724,0.0,1739137713.8838649,55.549947023391724,0.2910125867961604,1739137713.883866,55.549947023391724,3.1445559376465546,1739137713.8838677,55.549947023391724,1.9129815991058376 +1739137713.904024,55.56994700431824,23.72745281417265,1739137713.904026,55.56994700431824,-0.29289319817520365,1739137713.904029,55.56994700431824,88.66926453030914,1739137713.9040318,55.56994700431824,16.919410411935885,1739137713.9040332,55.56994700431824,0.0019826589069360896,1739137713.904035,55.56994700431824,3.09830683796427,1739137713.9040363,55.56994700431824,-0.3150486964061659,1739137713.904038,55.56994700431824,-0.1041683620739838,1739137713.9040391,55.56994700431824,2.203994185901998,1739137713.904041,55.56994700431824,0.0,1739137713.9040422,55.56994700431824,0.2910125867961604,1739137713.9040437,55.56994700431824,3.1445559376465546,1739137713.9040453,55.56994700431824,1.9129815991058376 +1739137713.923824,55.58994698524475,23.72745281417265,1739137713.9238272,55.58994698524475,-0.29289319817520365,1739137713.9238303,55.58994698524475,88.66926453030914,1739137713.9238331,55.58994698524475,16.919410411935885,1739137713.9238346,55.58994698524475,0.0019826589069360896,1739137713.9238362,55.58994698524475,3.09830683796427,1739137713.9238377,55.58994698524475,-0.3150486964061659,1739137713.9238393,55.58994698524475,-0.1041683620739838,1739137713.9238405,55.58994698524475,2.203994185901998,1739137713.923842,55.58994698524475,0.0,1739137713.9238436,55.58994698524475,0.2910125867961604,1739137713.923845,55.58994698524475,3.1445559376465546,1739137713.9238465,55.58994698524475,1.9129815991058376 +1739137713.9440653,55.609946966171265,23.51542441525765,1739137713.9440684,55.609946966171265,-0.2928658691487662,1739137713.9440718,55.609946966171265,89.59295839014118,1739137713.9440749,55.609946966171265,15.899899739080382,1739137713.9440763,55.609946966171265,0.008684617614697583,1739137713.944078,55.609946966171265,3.102016518445299,1739137713.9440796,55.609946966171265,-0.2737700767200637,1739137713.944081,55.609946966171265,-0.07237904648817585,1739137713.9440825,55.609946966171265,2.2406874165714137,1739137713.9440842,55.609946966171265,0.0,1739137713.9440856,55.609946966171265,0.30006670024109844,1739137713.944087,55.609946966171265,3.1379450433787976,1739137713.9440882,55.609946966171265,1.9449322010769179 +1739137713.964458,55.62994694709778,23.51542441525765,1739137713.9644613,55.62994694709778,-0.2928658691487662,1739137713.964465,55.62994694709778,89.59295839014118,1739137713.9644685,55.62994694709778,15.899899739080382,1739137713.964471,55.62994694709778,0.008684617614697583,1739137713.9644732,55.62994694709778,3.102016518445299,1739137713.9644754,55.62994694709778,-0.2737700767200637,1739137713.9644775,55.62994694709778,-0.07237904648817585,1739137713.9644792,55.62994694709778,2.2406874165714137,1739137713.9644814,55.62994694709778,0.0,1739137713.9644833,55.62994694709778,0.2957552154944958,1739137713.9644854,55.62994694709778,3.1379450433787976,1739137713.964487,55.62994694709778,1.9449322010769179 +1739137713.9923997,55.64994692802429,23.51542441525765,1739137713.9924085,55.64994692802429,-0.2928658691487662,1739137713.9924188,55.64994692802429,89.59295839014118,1739137713.992429,55.64994692802429,15.899899739080382,1739137713.992434,55.64994692802429,0.008684617614697583,1739137713.9924397,55.64994692802429,3.102016518445299,1739137713.992445,55.64994692802429,-0.2737700767200637,1739137713.9924495,55.64994692802429,-0.07237904648817585,1739137713.992454,55.64994692802429,2.2406874165714137,1739137713.9924595,55.64994692802429,0.0,1739137713.992464,55.64994692802429,0.2957552154944958,1739137713.9924695,55.64994692802429,3.1379450433787976,1739137713.992474,55.64994692802429,1.9449322010769179 +1739137714.0140054,55.65994691848755,23.51542441525765,1739137714.0140142,55.65994691848755,-0.2928658691487662,1739137714.0140238,55.65994691848755,89.59295839014118,1739137714.014033,55.65994691848755,15.899899739080382,1739137714.0140378,55.65994691848755,0.008684617614697583,1739137714.0140436,55.65994691848755,3.102016518445299,1739137714.0140486,55.65994691848755,-0.2737700767200637,1739137714.0140533,55.65994691848755,-0.07237904648817585,1739137714.0140579,55.65994691848755,2.2406874165714137,1739137714.0140631,55.65994691848755,0.0,1739137714.0140676,55.65994691848755,0.2957552154944958,1739137714.014073,55.65994691848755,3.1379450433787976,1739137714.0140777,55.65994691848755,1.9449322010769179 +1739137714.034465,55.67994689941406,23.51542441525765,1739137714.0345037,55.67994689941406,-0.2928658691487662,1739137714.0345151,55.67994689941406,89.59295839014118,1739137714.0345254,55.67994689941406,15.899899739080382,1739137714.0345304,55.67994689941406,0.008684617614697583,1739137714.0345361,55.67994689941406,3.102016518445299,1739137714.0345418,55.67994689941406,-0.2737700767200637,1739137714.0345466,55.67994689941406,-0.07237904648817585,1739137714.0345514,55.67994689941406,2.2406874165714137,1739137714.0345564,55.67994689941406,0.0,1739137714.034561,55.67994689941406,0.2957552154944958,1739137714.0345664,55.67994689941406,3.1379450433787976,1739137714.0345707,55.67994689941406,1.9449322010769179 +1739137714.0554876,55.699946880340576,23.51542441525765,1739137714.0554957,55.699946880340576,-0.2928658691487662,1739137714.0555048,55.699946880340576,89.59295839014118,1739137714.0555134,55.699946880340576,15.899899739080382,1739137714.0555177,55.699946880340576,0.008684617614697583,1739137714.0555232,55.699946880340576,3.102016518445299,1739137714.0555272,55.699946880340576,-0.2737700767200637,1739137714.0555315,55.699946880340576,-0.07237904648817585,1739137714.0555358,55.699946880340576,2.2406874165714137,1739137714.055541,55.699946880340576,0.0,1739137714.055545,55.699946880340576,0.2957552154944958,1739137714.0555499,55.699946880340576,3.1379450433787976,1739137714.0555544,55.699946880340576,1.9449322010769179 +1739137714.0968697,55.72994685173035,23.299856044354804,1739137714.096881,55.72994685173035,-0.2914967435759914,1739137714.0968957,55.72994685173035,89.63024898005622,1739137714.096913,55.72994685173035,15.765188440689908,1739137714.0969229,55.72994685173035,0.009,1739137714.0969353,55.72994685173035,3.1017318937782696,1739137714.0969462,55.72994685173035,-0.2295803808647957,1739137714.0969574,55.72994685173035,-0.06200771317167965,1739137714.0969687,55.72994685173035,2.2806456427593256,1739137714.0969803,55.72994685173035,0.0,1739137714.0969915,55.72994685173035,0.31004325437173774,1739137714.0970032,55.72994685173035,3.132182271110561,1739137714.0970142,55.72994685173035,1.9774062198231808 +1739137714.120546,55.74994683265686,23.299856044354804,1739137714.1205542,55.74994683265686,-0.2914967435759914,1739137714.1205637,55.74994683265686,89.63024898005622,1739137714.120574,55.74994683265686,15.765188440689908,1739137714.1205792,55.74994683265686,0.009,1739137714.1205854,55.74994683265686,3.1017318937782696,1739137714.1205912,55.74994683265686,-0.2295803808647957,1739137714.1205964,55.74994683265686,-0.06200771317167965,1739137714.120602,55.74994683265686,2.2806456427593256,1739137714.1206074,55.74994683265686,0.0,1739137714.1206129,55.74994683265686,0.3032394229361448,1739137714.1206186,55.74994683265686,3.132182271110561,1739137714.1206234,55.74994683265686,1.9774062198231808 +1739137714.1381776,55.769946813583374,23.299856044354804,1739137714.1381857,55.769946813583374,-0.2914967435759914,1739137714.1381953,55.769946813583374,89.63024898005622,1739137714.1382055,55.769946813583374,15.765188440689908,1739137714.1382103,55.769946813583374,0.009,1739137714.1382165,55.769946813583374,3.1017318937782696,1739137714.1382213,55.769946813583374,-0.2295803808647957,1739137714.138227,55.769946813583374,-0.06200771317167965,1739137714.1382318,55.769946813583374,2.2806456427593256,1739137714.138237,55.769946813583374,0.0,1739137714.1382418,55.769946813583374,0.3032394229361448,1739137714.138247,55.769946813583374,3.132182271110561,1739137714.1382515,55.769946813583374,1.9774062198231808 +1739137714.1581647,55.799946784973145,23.299856044354804,1739137714.1581726,55.799946784973145,-0.2914967435759914,1739137714.1581817,55.799946784973145,89.63024898005622,1739137714.15819,55.799946784973145,15.765188440689908,1739137714.1581945,55.799946784973145,0.009,1739137714.1582003,55.799946784973145,3.1017318937782696,1739137714.1582046,55.799946784973145,-0.2295803808647957,1739137714.158209,55.799946784973145,-0.06200771317167965,1739137714.1582136,55.799946784973145,2.2806456427593256,1739137714.1582189,55.799946784973145,0.0,1739137714.158223,55.799946784973145,0.3032394229361448,1739137714.1582277,55.799946784973145,3.132182271110561,1739137714.158232,55.799946784973145,1.9774062198231808 +1739137714.2200189,55.829946756362915,23.080687291643024,1739137714.2200232,55.829946756362915,-0.28893341786479,1739137714.2200277,55.829946756362915,89.66816004762393,1739137714.2200325,55.829946756362915,15.627356973696058,1739137714.2200353,55.829946756362915,0.009,1739137714.2200387,55.829946756362915,3.1016407297920194,1739137714.2200415,55.829946756362915,-0.19165017092577252,1739137714.2200444,55.829946756362915,-0.05290068381181677,1739137714.220047,55.829946756362915,2.315511615885802,1739137714.22005,55.829946756362915,0.0,1739137714.2200527,55.829946756362915,0.30621602789455504,1739137714.2200558,55.829946756362915,3.1273363995328216,1739137714.2200587,55.829946756362915,2.010713019631892 +1739137714.2394738,55.84994673728943,23.080687291643024,1739137714.2394762,55.84994673728943,-0.28893341786479,1739137714.2394788,55.84994673728943,89.66816004762393,1739137714.2394814,55.84994673728943,15.627356973696058,1739137714.2394826,55.84994673728943,0.009,1739137714.2394838,55.84994673728943,3.1016407297920194,1739137714.2394855,55.84994673728943,-0.19165017092577252,1739137714.2394865,55.84994673728943,-0.05290068381181677,1739137714.2394876,55.84994673728943,2.315511615885802,1739137714.239489,55.84994673728943,0.0,1739137714.2394903,55.84994673728943,0.3047985962539097,1739137714.2394922,55.84994673728943,3.1273363995328216,1739137714.2394931,55.84994673728943,2.010713019631892 +1739137714.2594674,55.86994671821594,23.080687291643024,1739137714.2594714,55.86994671821594,-0.28893341786479,1739137714.259476,55.86994671821594,89.66816004762393,1739137714.2594817,55.86994671821594,15.627356973696058,1739137714.2594845,55.86994671821594,0.009,1739137714.2594886,55.86994671821594,3.1016407297920194,1739137714.2594922,55.86994671821594,-0.19165017092577252,1739137714.2594957,55.86994671821594,-0.05290068381181677,1739137714.2594993,55.86994671821594,2.315511615885802,1739137714.259503,55.86994671821594,0.0,1739137714.2595065,55.86994671821594,0.3047985962539097,1739137714.2595103,55.86994671821594,3.1273363995328216,1739137714.259514,55.86994671821594,2.010713019631892 +1739137714.2781026,55.889946699142456,23.080687291643024,1739137714.2781072,55.889946699142456,-0.28893341786479,1739137714.278112,55.889946699142456,89.66816004762393,1739137714.2781172,55.889946699142456,15.627356973696058,1739137714.27812,55.889946699142456,0.009,1739137714.278124,55.889946699142456,3.1016407297920194,1739137714.2781284,55.889946699142456,-0.19165017092577252,1739137714.2781322,55.889946699142456,-0.05290068381181677,1739137714.2781382,55.889946699142456,2.315511615885802,1739137714.2781415,55.889946699142456,0.0,1739137714.27815,55.889946699142456,0.3047985962539097,1739137714.2781534,55.889946699142456,3.1273363995328216,1739137714.2781577,55.889946699142456,2.010713019631892 +1739137714.2984169,55.90994668006897,23.080687291643024,1739137714.2984204,55.90994668006897,-0.28893341786479,1739137714.2984254,55.90994668006897,89.66816004762393,1739137714.298431,55.90994668006897,15.627356973696058,1739137714.2984343,55.90994668006897,0.009,1739137714.298438,55.90994668006897,3.1016407297920194,1739137714.298442,55.90994668006897,-0.19165017092577252,1739137714.2984455,55.90994668006897,-0.05290068381181677,1739137714.2984495,55.90994668006897,2.315511615885802,1739137714.298453,55.90994668006897,0.0,1739137714.298457,55.90994668006897,0.3047985962539097,1739137714.2984607,55.90994668006897,3.1273363995328216,1739137714.2984643,55.90994668006897,2.010713019631892 +1739137714.31868,55.92994666099548,23.080687291643024,1739137714.3186834,55.92994666099548,-0.28893341786479,1739137714.318706,55.92994666099548,89.66816004762393,1739137714.3187113,55.92994666099548,15.627356973696058,1739137714.3187141,55.92994666099548,0.009,1739137714.3187184,55.92994666099548,3.1016407297920194,1739137714.3187218,55.92994666099548,-0.19165017092577252,1739137714.318742,55.92994666099548,-0.05290068381181677,1739137714.3187451,55.92994666099548,2.315511615885802,1739137714.3187487,55.92994666099548,0.0,1739137714.318752,55.92994666099548,0.3047985962539097,1739137714.3187556,55.92994666099548,3.1273363995328216,1739137714.3187716,55.92994666099548,2.010713019631892 +1739137714.3391573,55.949946641922,22.857863498601844,1739137714.3391614,55.949946641922,-0.28533665489798477,1739137714.3391666,55.949946641922,89.70670137029413,1739137714.3391724,55.949946641922,15.488601339336903,1739137714.3391755,55.949946641922,0.009,1739137714.3391795,55.949946641922,3.1016727429707944,1739137714.339183,55.949946641922,-0.15938563269416378,1739137714.339187,55.949946641922,-0.04500569946281772,1739137714.3391905,55.949946641922,2.3455888492465164,1739137714.3391943,55.949946641922,0.0,1739137714.3391979,55.949946641922,0.2984460223464913,1739137714.3392017,55.949946641922,3.123285632716884,1739137714.3392057,55.949946641922,2.0441177901948784 +1739137714.3574643,55.96994662284851,22.857863498601844,1739137714.3574672,55.96994662284851,-0.28533665489798477,1739137714.3574703,55.96994662284851,89.70670137029413,1739137714.3574727,55.96994662284851,15.488601339336903,1739137714.357474,55.96994662284851,0.009,1739137714.3574758,55.96994662284851,3.1016727429707944,1739137714.3574774,55.96994662284851,-0.15938563269416378,1739137714.3574786,55.96994662284851,-0.04500569946281772,1739137714.3574803,55.96994662284851,2.3455888492465164,1739137714.357482,55.96994662284851,0.0,1739137714.3574831,55.96994662284851,0.30147105905163807,1739137714.3574846,55.96994662284851,3.123285632716884,1739137714.3574858,55.96994662284851,2.0441177901948784 +1739137714.3847134,55.989946603775024,22.857863498601844,1739137714.3847218,55.989946603775024,-0.28533665489798477,1739137714.384732,55.989946603775024,89.70670137029413,1739137714.3847423,55.989946603775024,15.488601339336903,1739137714.384747,55.989946603775024,0.009,1739137714.3847528,55.989946603775024,3.1016727429707944,1739137714.3847573,55.989946603775024,-0.15938563269416378,1739137714.3847618,55.989946603775024,-0.04500569946281772,1739137714.384766,55.989946603775024,2.3455888492465164,1739137714.3847716,55.989946603775024,0.0,1739137714.384776,55.989946603775024,0.30147105905163807,1739137714.3847816,55.989946603775024,3.123285632716884,1739137714.384786,55.989946603775024,2.0441177901948784 +1739137714.4078305,56.019946575164795,22.857863498601844,1739137714.407839,56.019946575164795,-0.28533665489798477,1739137714.4078507,56.019946575164795,89.70670137029413,1739137714.407883,56.019946575164795,15.488601339336903,1739137714.407898,56.019946575164795,0.009,1739137714.4079163,56.019946575164795,3.1016727429707944,1739137714.407934,56.019946575164795,-0.15938563269416378,1739137714.4079444,56.019946575164795,-0.04500569946281772,1739137714.4079573,56.019946575164795,2.3455888492465164,1739137714.407972,56.019946575164795,0.0,1739137714.4079788,56.019946575164795,0.30147105905163807,1739137714.407984,56.019946575164795,3.123285632716884,1739137714.407989,56.019946575164795,2.0441177901948784 +1739137714.422465,56.019946575164795,22.857863498601844,1739137714.4224873,56.019946575164795,-0.28533665489798477,1739137714.4224935,56.019946575164795,89.70670137029413,1739137714.4224994,56.019946575164795,15.488601339336903,1739137714.4225018,56.019946575164795,0.009,1739137714.422505,56.019946575164795,3.1016727429707944,1739137714.4225078,56.019946575164795,-0.15938563269416378,1739137714.4225104,56.019946575164795,-0.04500569946281772,1739137714.422513,56.019946575164795,2.3455888492465164,1739137714.4225156,56.019946575164795,0.0,1739137714.4225183,56.019946575164795,0.30147105905163807,1739137714.422521,56.019946575164795,3.123285632716884,1739137714.4225237,56.019946575164795,2.0441177901948784 +1739137714.4418802,56.049946546554565,22.63140738017354,1739137714.4418838,56.049946546554565,-0.28079902789716193,1739137714.441888,56.049946546554565,90.01877307404938,1739137714.4418924,56.049946546554565,15.07766716843868,1739137714.4418943,56.049946546554565,0.009,1739137714.441897,56.049946546554565,3.1032464882537942,1739137714.4418993,56.049946546554565,-0.12338375076588386,1739137714.441901,56.049946546554565,-0.03316413297260727,1739137714.441903,56.049946546554565,2.379611482159735,1739137714.4419057,56.049946546554565,0.0,1739137714.4419074,56.049946546554565,0.30351088008496535,1739137714.4419098,56.049946546554565,3.1195693323078832,1739137714.4419117,56.049946546554565,2.0770719459092017 +1739137714.461828,56.06994652748108,22.63140738017354,1739137714.4618316,56.06994652748108,-0.28079902789716193,1739137714.4618363,56.06994652748108,90.01877307404938,1739137714.4618404,56.06994652748108,15.07766716843868,1739137714.4618428,56.06994652748108,0.009,1739137714.4618454,56.06994652748108,3.1032464882537942,1739137714.4618475,56.06994652748108,-0.12338375076588386,1739137714.46185,56.06994652748108,-0.03316413297260727,1739137714.4618516,56.06994652748108,2.379611482159735,1739137714.4618542,56.06994652748108,0.0,1739137714.4618564,56.06994652748108,0.3025395362505332,1739137714.4618585,56.06994652748108,3.1195693323078832,1739137714.4618604,56.06994652748108,2.0770719459092017 +1739137714.4864595,56.08994650840759,22.63140738017354,1739137714.4864635,56.08994650840759,-0.28079902789716193,1739137714.4864829,56.08994650840759,90.01877307404938,1739137714.4864964,56.08994650840759,15.07766716843868,1739137714.4865005,56.08994650840759,0.009,1739137714.4865036,56.08994650840759,3.1032464882537942,1739137714.4865062,56.08994650840759,-0.12338375076588386,1739137714.4865084,56.08994650840759,-0.03316413297260727,1739137714.4865103,56.08994650840759,2.379611482159735,1739137714.4865131,56.08994650840759,0.0,1739137714.4865153,56.08994650840759,0.3025395362505332,1739137714.4865174,56.08994650840759,3.1195693323078832,1739137714.4865198,56.08994650840759,2.0770719459092017 +1739137714.5011523,56.109946489334106,22.63140738017354,1739137714.5011551,56.109946489334106,-0.28079902789716193,1739137714.5011575,56.109946489334106,90.01877307404938,1739137714.5011604,56.109946489334106,15.07766716843868,1739137714.501162,56.109946489334106,0.009,1739137714.501164,56.109946489334106,3.1032464882537942,1739137714.5011656,56.109946489334106,-0.12338375076588386,1739137714.5011668,56.109946489334106,-0.03316413297260727,1739137714.5011685,56.109946489334106,2.379611482159735,1739137714.5011702,56.109946489334106,0.0,1739137714.501171,56.109946489334106,0.3025395362505332,1739137714.5011728,56.109946489334106,3.1195693323078832,1739137714.5011742,56.109946489334106,2.0770719459092017 +1739137714.520171,56.12994647026062,22.63140738017354,1739137714.520173,56.12994647026062,-0.28079902789716193,1739137714.5201757,56.12994647026062,90.01877307404938,1739137714.520178,56.12994647026062,15.07766716843868,1739137714.5201795,56.12994647026062,0.009,1739137714.520181,56.12994647026062,3.1032464882537942,1739137714.5201824,56.12994647026062,-0.12338375076588386,1739137714.5201833,56.12994647026062,-0.03316413297260727,1739137714.5201845,56.12994647026062,2.379611482159735,1739137714.5201862,56.12994647026062,0.0,1739137714.5201871,56.12994647026062,0.3025395362505332,1739137714.5201886,56.12994647026062,3.1195693323078832,1739137714.5201898,56.12994647026062,2.0770719459092017 +1739137714.5397336,56.149946451187134,22.63140738017354,1739137714.539736,56.149946451187134,-0.28079902789716193,1739137714.5397384,56.149946451187134,90.01877307404938,1739137714.5397406,56.149946451187134,15.07766716843868,1739137714.539742,56.149946451187134,0.009,1739137714.5397434,56.149946451187134,3.1032464882537942,1739137714.5397449,56.149946451187134,-0.12338375076588386,1739137714.539746,56.149946451187134,-0.03316413297260727,1739137714.539747,56.149946451187134,2.379611482159735,1739137714.5397487,56.149946451187134,0.0,1739137714.5397496,56.149946451187134,0.3025395362505332,1739137714.5397508,56.149946451187134,3.1195693323078832,1739137714.5397522,56.149946451187134,2.0770719459092017 +1739137714.560086,56.16994643211365,22.401332233140238,1739137714.5600882,56.16994643211365,-0.2753760763475297,1739137714.5600908,56.16994643211365,90.04361576697742,1739137714.5600934,56.16994643211365,14.953385416448798,1739137714.5600948,56.16994643211365,0.009,1739137714.5600963,56.16994643211365,3.103429383698525,1739137714.5600975,56.16994643211365,-0.09583655454100978,1739137714.560099,56.16994643211365,-0.026497524643381492,1739137714.5600998,56.16994643211365,2.405977125076407,1739137714.5601013,56.16994643211365,0.0,1739137714.5601025,56.16994643211365,0.28959453835519566,1739137714.5601037,56.16994643211365,3.116287882098609,1739137714.5601048,56.16994643211365,2.110218298929815 +1739137714.579949,56.18994641304016,22.401332233140238,1739137714.579951,56.18994641304016,-0.2753760763475297,1739137714.5799537,56.18994641304016,90.04361576697742,1739137714.5799563,56.18994641304016,14.953385416448798,1739137714.5799575,56.18994641304016,0.009,1739137714.5799592,56.18994641304016,3.103429383698525,1739137714.5799603,56.18994641304016,-0.09583655454100978,1739137714.5799615,56.18994641304016,-0.026497524643381492,1739137714.579963,56.18994641304016,2.405977125076407,1739137714.5799642,56.18994641304016,0.0,1739137714.5799654,56.18994641304016,0.2957588261465922,1739137714.5799668,56.18994641304016,3.116287882098609,1739137714.579968,56.18994641304016,2.110218298929815 +1739137714.5997205,56.209946393966675,22.401332233140238,1739137714.5997229,56.209946393966675,-0.2753760763475297,1739137714.5997255,56.209946393966675,90.04361576697742,1739137714.599728,56.209946393966675,14.953385416448798,1739137714.5997293,56.209946393966675,0.009,1739137714.599731,56.209946393966675,3.103429383698525,1739137714.5997322,56.209946393966675,-0.09583655454100978,1739137714.5997336,56.209946393966675,-0.026497524643381492,1739137714.5997345,56.209946393966675,2.405977125076407,1739137714.599736,56.209946393966675,0.0,1739137714.5997372,56.209946393966675,0.2957588261465922,1739137714.5997386,56.209946393966675,3.116287882098609,1739137714.5997396,56.209946393966675,2.110218298929815 +1739137714.6196804,56.22994637489319,22.401332233140238,1739137714.6196826,56.22994637489319,-0.2753760763475297,1739137714.6196852,56.22994637489319,90.04361576697742,1739137714.6196873,56.22994637489319,14.953385416448798,1739137714.6196887,56.22994637489319,0.009,1739137714.6196904,56.22994637489319,3.103429383698525,1739137714.6196918,56.22994637489319,-0.09583655454100978,1739137714.619693,56.22994637489319,-0.026497524643381492,1739137714.6196947,56.22994637489319,2.405977125076407,1739137714.6196961,56.22994637489319,0.0,1739137714.619697,56.22994637489319,0.2957588261465922,1739137714.6196988,56.22994637489319,3.116287882098609,1739137714.6197,56.22994637489319,2.110218298929815 +1739137714.6397014,56.2499463558197,22.401332233140238,1739137714.6397035,56.2499463558197,-0.2753760763475297,1739137714.639706,56.2499463558197,90.04361576697742,1739137714.6397085,56.2499463558197,14.953385416448798,1739137714.6397097,56.2499463558197,0.009,1739137714.6397111,56.2499463558197,3.103429383698525,1739137714.6397126,56.2499463558197,-0.09583655454100978,1739137714.6397138,56.2499463558197,-0.026497524643381492,1739137714.639715,56.2499463558197,2.405977125076407,1739137714.6397164,56.2499463558197,0.0,1739137714.6397176,56.2499463558197,0.2957588261465922,1739137714.639719,56.2499463558197,3.116287882098609,1739137714.6397202,56.2499463558197,2.110218298929815 +1739137714.6598685,56.269946336746216,22.16767593086037,1739137714.6598706,56.269946336746216,-0.2691445572115363,1739137714.6598732,56.269946336746216,90.35875526222476,1739137714.6598759,56.269946336746216,14.541351153373622,1739137714.6598773,56.269946336746216,0.009,1739137714.659879,56.269946336746216,3.1051371738953693,1739137714.6598804,56.269946336746216,-0.06290628466705066,1739137714.6598814,56.269946336746216,-0.01659101382254118,1739137714.6598828,56.269946336746216,2.437878558804549,1739137714.6598842,56.269946336746216,0.0,1739137714.6598856,56.269946336746216,0.29500125612038774,1739137714.6598868,56.269946336746216,3.1133803581011787,1739137714.659888,56.269946336746216,2.142516554872426 +1739137714.6797183,56.28994631767273,22.16767593086037,1739137714.6797204,56.28994631767273,-0.2691445572115363,1739137714.679723,56.28994631767273,90.35875526222476,1739137714.6797254,56.28994631767273,14.541351153373622,1739137714.6797266,56.28994631767273,0.009,1739137714.6797278,56.28994631767273,3.1051371738953693,1739137714.6797295,56.28994631767273,-0.06290628466705066,1739137714.6797307,56.28994631767273,-0.01659101382254118,1739137714.6797316,56.28994631767273,2.437878558804549,1739137714.679733,56.28994631767273,0.0,1739137714.6797342,56.28994631767273,0.295362003932123,1739137714.679736,56.28994631767273,3.1133803581011787,1739137714.6797369,56.28994631767273,2.142516554872426 +1739137714.6996236,56.30994629859924,22.16767593086037,1739137714.699626,56.30994629859924,-0.2691445572115363,1739137714.6996286,56.30994629859924,90.35875526222476,1739137714.6996312,56.30994629859924,14.541351153373622,1739137714.6996324,56.30994629859924,0.009,1739137714.6996338,56.30994629859924,3.1051371738953693,1739137714.6996353,56.30994629859924,-0.06290628466705066,1739137714.6996365,56.30994629859924,-0.01659101382254118,1739137714.6996377,56.30994629859924,2.437878558804549,1739137714.699639,56.30994629859924,0.0,1739137714.6996405,56.30994629859924,0.295362003932123,1739137714.6996422,56.30994629859924,3.1133803581011787,1739137714.6996434,56.30994629859924,2.142516554872426 +1739137714.719799,56.32994627952576,22.16767593086037,1739137714.7198017,56.32994627952576,-0.2691445572115363,1739137714.719804,56.32994627952576,90.35875526222476,1739137714.719807,56.32994627952576,14.541351153373622,1739137714.7198083,56.32994627952576,0.009,1739137714.7198098,56.32994627952576,3.1051371738953693,1739137714.7198114,56.32994627952576,-0.06290628466705066,1739137714.7198129,56.32994627952576,-0.01659101382254118,1739137714.719814,56.32994627952576,2.437878558804549,1739137714.7198157,56.32994627952576,0.0,1739137714.719817,56.32994627952576,0.295362003932123,1739137714.7198186,56.32994627952576,3.1133803581011787,1739137714.7198195,56.32994627952576,2.142516554872426 +1739137714.7396646,56.34994626045227,22.16767593086037,1739137714.7396667,56.34994626045227,-0.2691445572115363,1739137714.7396693,56.34994626045227,90.35875526222476,1739137714.7396717,56.34994626045227,14.541351153373622,1739137714.7396731,56.34994626045227,0.009,1739137714.7396746,56.34994626045227,3.1051371738953693,1739137714.739676,56.34994626045227,-0.06290628466705066,1739137714.7396774,56.34994626045227,-0.01659101382254118,1739137714.7396789,56.34994626045227,2.437878558804549,1739137714.7396803,56.34994626045227,0.0,1739137714.7396815,56.34994626045227,0.295362003932123,1739137714.7396832,56.34994626045227,3.1133803581011787,1739137714.7396843,56.34994626045227,2.142516554872426 +1739137714.759844,56.369946241378784,22.16767593086037,1739137714.7598486,56.369946241378784,-0.2691445572115363,1739137714.759854,56.369946241378784,90.35875526222476,1739137714.7598603,56.369946241378784,14.541351153373622,1739137714.7598631,56.369946241378784,0.009,1739137714.7598665,56.369946241378784,3.1051371738953693,1739137714.759869,56.369946241378784,-0.06290628466705066,1739137714.7598717,56.369946241378784,-0.01659101382254118,1739137714.759876,56.369946241378784,2.437878558804549,1739137714.7598827,56.369946241378784,0.0,1739137714.7598858,56.369946241378784,0.295362003932123,1739137714.759889,56.369946241378784,3.1133803581011787,1739137714.759892,56.369946241378784,2.142516554872426 +1739137714.7797668,56.3899462223053,21.930482396842052,1739137714.779769,56.3899462223053,-0.26217032870880086,1739137714.7797713,56.3899462223053,90.87796938665083,1739137714.779774,56.3899462223053,13.925145503555019,1739137714.7797751,56.3899462223053,0.008,1739137714.7797768,56.3899462223053,3.1078566810145927,1739137714.7797782,56.3899462223053,-0.024103925738373746,1739137714.7797797,56.3899462223053,-0.0057706517072475105,1739137714.7797809,56.3899462223053,2.4760119015575888,1739137714.779782,56.3899462223053,0.0,1739137714.7797835,56.3899462223053,0.3064374507419909,1739137714.7797847,56.3899462223053,3.110865954351812,1739137714.7797859,56.3899462223053,2.174848475740617 +1739137714.7996519,56.40994620323181,21.930482396842052,1739137714.7996542,56.40994620323181,-0.26217032870880086,1739137714.7996566,56.40994620323181,90.87796938665083,1739137714.7996593,56.40994620323181,13.925145503555019,1739137714.7996604,56.40994620323181,0.008,1739137714.799662,56.40994620323181,3.1078566810145927,1739137714.7996633,56.40994620323181,-0.024103925738373746,1739137714.7996647,56.40994620323181,-0.0057706517072475105,1739137714.799666,56.40994620323181,2.4760119015575888,1739137714.7996671,56.40994620323181,0.0,1739137714.7996686,56.40994620323181,0.30116342581697175,1739137714.7996697,56.40994620323181,3.110865954351812,1739137714.799671,56.40994620323181,2.174848475740617 +1739137714.8199573,56.429946184158325,21.930482396842052,1739137714.8199604,56.429946184158325,-0.26217032870880086,1739137714.8199632,56.429946184158325,90.87796938665083,1739137714.8199658,56.429946184158325,13.925145503555019,1739137714.8199673,56.429946184158325,0.008,1739137714.819969,56.429946184158325,3.1078566810145927,1739137714.8199706,56.429946184158325,-0.024103925738373746,1739137714.8199718,56.429946184158325,-0.0057706517072475105,1739137714.8199732,56.429946184158325,2.4760119015575888,1739137714.8199747,56.429946184158325,0.0,1739137714.8199759,56.429946184158325,0.30116342581697175,1739137714.8199775,56.429946184158325,3.110865954351812,1739137714.819979,56.429946184158325,2.174848475740617 +1739137714.8397062,56.44994616508484,21.930482396842052,1739137714.8397083,56.44994616508484,-0.26217032870880086,1739137714.8397112,56.44994616508484,90.87796938665083,1739137714.8397138,56.44994616508484,13.925145503555019,1739137714.8397152,56.44994616508484,0.008,1739137714.839717,56.44994616508484,3.1078566810145927,1739137714.839718,56.44994616508484,-0.024103925738373746,1739137714.8397195,56.44994616508484,-0.0057706517072475105,1739137714.8397207,56.44994616508484,2.4760119015575888,1739137714.8397222,56.44994616508484,0.0,1739137714.8397236,56.44994616508484,0.30116342581697175,1739137714.839725,56.44994616508484,3.110865954351812,1739137714.8397264,56.44994616508484,2.174848475740617 +1739137714.8599384,56.46994614601135,21.930482396842052,1739137714.8599408,56.46994614601135,-0.26217032870880086,1739137714.8599436,56.46994614601135,90.87796938665083,1739137714.8599465,56.46994614601135,13.925145503555019,1739137714.8599477,56.46994614601135,0.008,1739137714.8599494,56.46994614601135,3.1078566810145927,1739137714.8599508,56.46994614601135,-0.024103925738373746,1739137714.8599522,56.46994614601135,-0.0057706517072475105,1739137714.8599536,56.46994614601135,2.4760119015575888,1739137714.8599548,56.46994614601135,0.0,1739137714.8599563,56.46994614601135,0.30116342581697175,1739137714.8599582,56.46994614601135,3.110865954351812,1739137714.8599596,56.46994614601135,2.174848475740617 +1739137714.8797963,56.489946126937866,21.689718576460105,1739137714.8797984,56.489946126937866,-0.2545243152498111,1739137714.8798013,56.489946126937866,90.90493493453361,1739137714.879804,56.489946126937866,13.799208389173872,1739137714.8798053,56.489946126937866,0.008,1739137714.879807,56.489946126937866,3.1083340294944968,1739137714.8798082,56.489946126937866,-0.0032201427223051793,1739137714.8798099,56.489946126937866,-0.0007935525275092936,1739137714.879811,56.489946126937866,2.4967819302513936,1739137714.8798127,56.489946126937866,0.0,1739137714.879814,56.489946126937866,0.27783338222947157,1739137714.879815,56.489946126937866,3.1087419070513707,1739137714.8798168,56.489946126937866,2.20783899790674 +1739137714.899849,56.50994610786438,21.689718576460105,1739137714.899851,56.50994610786438,-0.2545243152498111,1739137714.8998537,56.50994610786438,90.90493493453361,1739137714.8998563,56.50994610786438,13.799208389173872,1739137714.8998578,56.50994610786438,0.008,1739137714.8998594,56.50994610786438,3.1083340294944968,1739137714.8998606,56.50994610786438,-0.0032201427223051793,1739137714.899862,56.50994610786438,-0.0007935525275092936,1739137714.8998635,56.50994610786438,2.4967819302513936,1739137714.899865,56.50994610786438,0.0,1739137714.899866,56.50994610786438,0.2889429323446535,1739137714.8998673,56.50994610786438,3.1087419070513707,1739137714.899869,56.50994610786438,2.20783899790674 +1739137714.9196703,56.529946088790894,21.689718576460105,1739137714.9196723,56.529946088790894,-0.2545243152498111,1739137714.919675,56.529946088790894,90.90493493453361,1739137714.9196777,56.529946088790894,13.799208389173872,1739137714.9196792,56.529946088790894,0.008,1739137714.9196808,56.529946088790894,3.1083340294944968,1739137714.9196823,56.529946088790894,-0.0032201427223051793,1739137714.919684,56.529946088790894,-0.0007935525275092936,1739137714.9196851,56.529946088790894,2.4967819302513936,1739137714.9196866,56.529946088790894,0.0,1739137714.919688,56.529946088790894,0.2889429323446535,1739137714.9196894,56.529946088790894,3.1087419070513707,1739137714.9196908,56.529946088790894,2.20783899790674 +1739137714.939705,56.54994606971741,21.689718576460105,1739137714.9397068,56.54994606971741,-0.2545243152498111,1739137714.9397094,56.54994606971741,90.90493493453361,1739137714.9397123,56.54994606971741,13.799208389173872,1739137714.9397135,56.54994606971741,0.008,1739137714.9397154,56.54994606971741,3.1083340294944968,1739137714.9397166,56.54994606971741,-0.0032201427223051793,1739137714.9397178,56.54994606971741,-0.0007935525275092936,1739137714.9397194,56.54994606971741,2.4967819302513936,1739137714.9397206,56.54994606971741,0.0,1739137714.939722,56.54994606971741,0.2889429323446535,1739137714.9397235,56.54994606971741,3.1087419070513707,1739137714.9397247,56.54994606971741,2.20783899790674 +1739137714.959918,56.56994605064392,21.689718576460105,1739137714.959921,56.56994605064392,-0.2545243152498111,1739137714.959924,56.56994605064392,90.90493493453361,1739137714.9599268,56.56994605064392,13.799208389173872,1739137714.9599283,56.56994605064392,0.008,1739137714.9599302,56.56994605064392,3.1083340294944968,1739137714.9599316,56.56994605064392,-0.0032201427223051793,1739137714.9599335,56.56994605064392,-0.0007935525275092936,1739137714.9599347,56.56994605064392,2.4967819302513936,1739137714.9599361,56.56994605064392,0.0,1739137714.9599376,56.56994605064392,0.2889429323446535,1739137714.959939,56.56994605064392,3.1087419070513707,1739137714.9599407,56.56994605064392,2.20783899790674 +1739137714.9796991,56.589946031570435,21.689718576460105,1739137714.9797015,56.589946031570435,-0.2545243152498111,1739137714.9797041,56.589946031570435,90.90493493453361,1739137714.9797065,56.589946031570435,13.799208389173872,1739137714.979708,56.589946031570435,0.008,1739137714.9797096,56.589946031570435,3.1083340294944968,1739137714.979711,56.589946031570435,-0.0032201427223051793,1739137714.9797125,56.589946031570435,-0.0007935525275092936,1739137714.9797137,56.589946031570435,2.4967819302513936,1739137714.979715,56.589946031570435,0.0,1739137714.9797163,56.589946031570435,0.2889429323446535,1739137714.979718,56.589946031570435,3.1087419070513707,1739137714.9797192,56.589946031570435,2.20783899790674 +1739137714.999734,56.60994601249695,21.445431082468694,1739137714.9997363,56.60994601249695,-0.24629886633070264,1739137714.999739,56.60994601249695,91.1312115980574,1739137714.9997416,56.60994601249695,13.478694033697472,1739137714.9997427,56.60994601249695,0.007,1739137714.9997442,56.60994601249695,3.1098088048493455,1739137714.9997458,56.60994601249695,0.02233445154482046,1739137714.999747,56.60994601249695,0.005399658191587646,1739137714.9997485,56.60994601249695,2.4777650175682036,1739137714.9997497,56.60994601249695,0.0,1739137714.9997509,56.60994601249695,0.19266571371321298,1739137714.9997525,56.60994601249695,3.1070067542365987,1739137714.9997537,56.60994601249695,2.2392529863663517 +1739137715.019707,56.62994599342346,21.445431082468694,1739137715.0197093,56.62994599342346,-0.24629886633070264,1739137715.019712,56.62994599342346,91.1312115980574,1739137715.0197148,56.62994599342346,13.478694033697472,1739137715.019716,56.62994599342346,0.007,1739137715.0197182,56.62994599342346,3.1098088048493455,1739137715.0197194,56.62994599342346,0.02233445154482046,1739137715.0197208,56.62994599342346,0.005399658191587646,1739137715.019722,56.62994599342346,2.4777650175682036,1739137715.0197234,56.62994599342346,0.0,1739137715.0197248,56.62994599342346,0.23851203120185183,1739137715.0197263,56.62994599342346,3.1070067542365987,1739137715.0197277,56.62994599342346,2.2392529863663517 +1739137715.0397167,56.649945974349976,21.445431082468694,1739137715.0397189,56.649945974349976,-0.24629886633070264,1739137715.0397215,56.649945974349976,91.1312115980574,1739137715.039724,56.649945974349976,13.478694033697472,1739137715.0397255,56.649945974349976,0.007,1739137715.0397272,56.649945974349976,3.1098088048493455,1739137715.0397286,56.649945974349976,0.02233445154482046,1739137715.0397296,56.649945974349976,0.005399658191587646,1739137715.039731,56.649945974349976,2.4777650175682036,1739137715.0397327,56.649945974349976,0.0,1739137715.0397341,56.649945974349976,0.23851203120185183,1739137715.0397356,56.649945974349976,3.1070067542365987,1739137715.0397367,56.649945974349976,2.2392529863663517 +1739137715.0598836,56.66994595527649,21.445431082468694,1739137715.0598862,56.66994595527649,-0.24629886633070264,1739137715.059889,56.66994595527649,91.1312115980574,1739137715.0598917,56.66994595527649,13.478694033697472,1739137715.0598931,56.66994595527649,0.007,1739137715.059895,56.66994595527649,3.1098088048493455,1739137715.0598965,56.66994595527649,0.02233445154482046,1739137715.059898,56.66994595527649,0.005399658191587646,1739137715.059899,56.66994595527649,2.4777650175682036,1739137715.0599008,56.66994595527649,0.0,1739137715.059902,56.66994595527649,0.23851203120185183,1739137715.0599034,56.66994595527649,3.1070067542365987,1739137715.0599048,56.66994595527649,2.2392529863663517 +1739137715.0796971,56.689945936203,21.445431082468694,1739137715.0796995,56.689945936203,-0.24629886633070264,1739137715.0797024,56.689945936203,91.1312115980574,1739137715.079705,56.689945936203,13.478694033697472,1739137715.0797064,56.689945936203,0.007,1739137715.079708,56.689945936203,3.1098088048493455,1739137715.0797095,56.689945936203,0.02233445154482046,1739137715.079711,56.689945936203,0.005399658191587646,1739137715.0797122,56.689945936203,2.4777650175682036,1739137715.0797138,56.689945936203,0.0,1739137715.079715,56.689945936203,0.23851203120185183,1739137715.0797167,56.689945936203,3.1070067542365987,1739137715.0797179,56.689945936203,2.2392529863663517 +1739137715.0997927,56.70994591712952,21.197989841756993,1739137715.0997946,56.70994591712952,-0.23756039207358182,1739137715.0997975,56.70994591712952,91.50066741635626,1739137715.0998,56.70994591712952,13.032224340526325,1739137715.0998015,56.70994591712952,0.006,1739137715.0998032,56.70994591712952,3.1117744812853725,1739137715.0998046,56.70994591712952,0.051357939683532076,1739137715.0998063,56.70994591712952,0.011819974910815153,1739137715.0998075,56.70994591712952,2.4491659940225228,1739137715.0998087,56.70994591712952,0.0,1739137715.0998104,56.70994591712952,0.13490229937230522,1739137715.0998118,56.70994591712952,3.105487814378033,1739137715.0998132,56.70994591712952,2.2649257024658556 +1739137715.1198301,56.72994589805603,21.197989841756993,1739137715.1198323,56.72994589805603,-0.23756039207358182,1739137715.1198351,56.72994589805603,91.50066741635626,1739137715.1198378,56.72994589805603,13.032224340526325,1739137715.119839,56.72994589805603,0.006,1739137715.1198409,56.72994589805603,3.1117744812853725,1739137715.119842,56.72994589805603,0.051357939683532076,1739137715.1198435,56.72994589805603,0.011819974910815153,1739137715.119845,56.72994589805603,2.4491659940225228,1739137715.119846,56.72994589805603,0.0,1739137715.1198475,56.72994589805603,0.1842402915566672,1739137715.119849,56.72994589805603,3.105487814378033,1739137715.11985,56.72994589805603,2.2649257024658556 +1739137715.1396766,56.749945878982544,21.197989841756993,1739137715.139679,56.749945878982544,-0.23756039207358182,1739137715.1396818,56.749945878982544,91.50066741635626,1739137715.1396844,56.749945878982544,13.032224340526325,1739137715.1396859,56.749945878982544,0.006,1739137715.1396875,56.749945878982544,3.1117744812853725,1739137715.1396887,56.749945878982544,0.051357939683532076,1739137715.1396902,56.749945878982544,0.011819974910815153,1739137715.1396914,56.749945878982544,2.4491659940225228,1739137715.1396928,56.749945878982544,0.0,1739137715.139694,56.749945878982544,0.1842402915566672,1739137715.1396956,56.749945878982544,3.105487814378033,1739137715.1396968,56.749945878982544,2.2649257024658556 +1739137715.1600344,56.76994585990906,21.197989841756993,1739137715.1600373,56.76994585990906,-0.23756039207358182,1739137715.1600409,56.76994585990906,91.50066741635626,1739137715.160044,56.76994585990906,13.032224340526325,1739137715.1600456,56.76994585990906,0.006,1739137715.1600473,56.76994585990906,3.1117744812853725,1739137715.160049,56.76994585990906,0.051357939683532076,1739137715.1600502,56.76994585990906,0.011819974910815153,1739137715.1600518,56.76994585990906,2.4491659940225228,1739137715.1600535,56.76994585990906,0.0,1739137715.1600547,56.76994585990906,0.1842402915566672,1739137715.1600566,56.76994585990906,3.105487814378033,1739137715.1600578,56.76994585990906,2.2649257024658556 +1739137715.1796947,56.78994584083557,21.197989841756993,1739137715.1796968,56.78994584083557,-0.23756039207358182,1739137715.1796994,56.78994584083557,91.50066741635626,1739137715.1797023,56.78994584083557,13.032224340526325,1739137715.1797037,56.78994584083557,0.006,1739137715.1797054,56.78994584083557,3.1117744812853725,1739137715.1797068,56.78994584083557,0.051357939683532076,1739137715.1797082,56.78994584083557,0.011819974910815153,1739137715.1797094,56.78994584083557,2.4491659940225228,1739137715.1797109,56.78994584083557,0.0,1739137715.1797123,56.78994584083557,0.1842402915566672,1739137715.1797137,56.78994584083557,3.105487814378033,1739137715.1797152,56.78994584083557,2.2649257024658556 +1739137715.1996799,56.809945821762085,21.197989841756993,1739137715.199682,56.809945821762085,-0.23756039207358182,1739137715.1996849,56.809945821762085,91.50066741635626,1739137715.1996877,56.809945821762085,13.032224340526325,1739137715.199689,56.809945821762085,0.006,1739137715.1996906,56.809945821762085,3.1117744812853725,1739137715.199692,56.809945821762085,0.051357939683532076,1739137715.1996932,56.809945821762085,0.011819974910815153,1739137715.1996946,56.809945821762085,2.4491659940225228,1739137715.199696,56.809945821762085,0.0,1739137715.1996975,56.809945821762085,0.1842402915566672,1739137715.199699,56.809945821762085,3.105487814378033,1739137715.1997,56.809945821762085,2.2649257024658556 +1739137715.2198153,56.8299458026886,20.94809917244826,1739137715.2198172,56.8299458026886,-0.22839001200089815,1739137715.2198203,56.8299458026886,92.18125267391761,1739137715.219823,56.8299458026886,12.294068479887066,1739137715.219824,56.8299458026886,0.004684931367232286,1739137715.219826,56.8299458026886,3.1146666324495613,1739137715.2198272,56.8299458026886,0.08991927474145159,1739137715.2198288,56.8299458026886,0.018428363919837917,1739137715.21983,56.8299458026886,2.4116786058021473,1739137715.2198312,56.8299458026886,0.0,1739137715.219833,56.8299458026886,0.07603382040515214,1739137715.2198343,56.8299458026886,3.10427976187113,1739137715.2198353,56.8299458026886,2.284117868632518 +1739137715.239769,56.84994578361511,20.94809917244826,1739137715.2397716,56.84994578361511,-0.22839001200089815,1739137715.2397742,56.84994578361511,92.18125267391761,1739137715.239777,56.84994578361511,12.294068479887066,1739137715.2397785,56.84994578361511,0.004684931367232286,1739137715.2397802,56.84994578361511,3.1146666324495613,1739137715.2397814,56.84994578361511,0.08991927474145159,1739137715.2397828,56.84994578361511,0.018428363919837917,1739137715.2397845,56.84994578361511,2.4116786058021473,1739137715.239786,56.84994578361511,0.0,1739137715.2397873,56.84994578361511,0.12756073716962923,1739137715.2397888,56.84994578361511,3.10427976187113,1739137715.23979,56.84994578361511,2.284117868632518 +1739137715.2597568,56.869945764541626,20.94809917244826,1739137715.2597592,56.869945764541626,-0.22839001200089815,1739137715.2597618,56.869945764541626,92.18125267391761,1739137715.2597647,56.869945764541626,12.294068479887066,1739137715.259766,56.869945764541626,0.004684931367232286,1739137715.2597675,56.869945764541626,3.1146666324495613,1739137715.2597687,56.869945764541626,0.08991927474145159,1739137715.2597704,56.869945764541626,0.018428363919837917,1739137715.2597713,56.869945764541626,2.4116786058021473,1739137715.259773,56.869945764541626,0.0,1739137715.2597742,56.869945764541626,0.12756073716962923,1739137715.2597756,56.869945764541626,3.10427976187113,1739137715.259777,56.869945764541626,2.284117868632518 +1739137715.279762,56.88994574546814,20.94809917244826,1739137715.2797644,56.88994574546814,-0.22839001200089815,1739137715.2797673,56.88994574546814,92.18125267391761,1739137715.2797704,56.88994574546814,12.294068479887066,1739137715.2797716,56.88994574546814,0.004684931367232286,1739137715.2797735,56.88994574546814,3.1146666324495613,1739137715.279775,56.88994574546814,0.08991927474145159,1739137715.2797763,56.88994574546814,0.018428363919837917,1739137715.2797775,56.88994574546814,2.4116786058021473,1739137715.2797794,56.88994574546814,0.0,1739137715.2797806,56.88994574546814,0.12756073716962923,1739137715.279782,56.88994574546814,3.10427976187113,1739137715.2797835,56.88994574546814,2.284117868632518 +1739137715.299862,56.90994572639465,20.94809917244826,1739137715.2998645,56.90994572639465,-0.22839001200089815,1739137715.2998674,56.90994572639465,92.18125267391761,1739137715.29987,56.90994572639465,12.294068479887066,1739137715.2998714,56.90994572639465,0.004684931367232286,1739137715.299873,56.90994572639465,3.1146666324495613,1739137715.2998745,56.90994572639465,0.08991927474145159,1739137715.2998757,56.90994572639465,0.018428363919837917,1739137715.2998772,56.90994572639465,2.4116786058021473,1739137715.2998784,56.90994572639465,0.0,1739137715.2998798,56.90994572639465,0.12756073716962923,1739137715.299881,56.90994572639465,3.10427976187113,1739137715.2998822,56.90994572639465,2.284117868632518 +1739137715.3197658,56.92994570732117,20.696359015834748,1739137715.319768,56.92994570732117,-0.21887638608716298,1739137715.3197708,56.92994570732117,92.20893457751919,1739137715.3197737,56.92994570732117,12.225932947635556,1739137715.3197749,56.92994570732117,0.004,1739137715.3197768,56.92994570732117,3.115286424074037,1739137715.319778,56.92994570732117,0.10140785005918475,1739137715.3197794,56.92994570732117,0.021694224706690756,1739137715.3197806,56.92994570732117,2.400621331205514,1739137715.3197823,56.92994570732117,0.0,1739137715.3197834,56.92994570732117,0.08070586128289638,1739137715.3197849,56.92994570732117,3.1033182912629713,1739137715.3197863,56.92994570732117,2.297603613116521 +1739137715.339706,56.94994568824768,20.696359015834748,1739137715.3397079,56.94994568824768,-0.21887638608716298,1739137715.3397107,56.94994568824768,92.20893457751919,1739137715.3397133,56.94994568824768,12.225932947635556,1739137715.339715,56.94994568824768,0.004,1739137715.3397167,56.94994568824768,3.115286424074037,1739137715.339718,56.94994568824768,0.10140785005918475,1739137715.3397195,56.94994568824768,0.021694224706690756,1739137715.3397207,56.94994568824768,2.400621331205514,1739137715.3397222,56.94994568824768,0.0,1739137715.3397238,56.94994568824768,0.10301771808899263,1739137715.3397253,56.94994568824768,3.1033182912629713,1739137715.3397267,56.94994568824768,2.297603613116521 +1739137715.3598793,56.969945669174194,20.696359015834748,1739137715.3598826,56.969945669174194,-0.21887638608716298,1739137715.3598855,56.969945669174194,92.20893457751919,1739137715.3598883,56.969945669174194,12.225932947635556,1739137715.3598897,56.969945669174194,0.004,1739137715.3598912,56.969945669174194,3.115286424074037,1739137715.3598928,56.969945669174194,0.10140785005918475,1739137715.3598943,56.969945669174194,0.021694224706690756,1739137715.3598955,56.969945669174194,2.400621331205514,1739137715.3598971,56.969945669174194,0.0,1739137715.3598983,56.969945669174194,0.10301771808899263,1739137715.3598998,56.969945669174194,3.1033182912629713,1739137715.3599012,56.969945669174194,2.297603613116521 +1739137715.3852372,56.98994565010071,20.696359015834748,1739137715.3852475,56.98994565010071,-0.21887638608716298,1739137715.3852603,56.98994565010071,92.20893457751919,1739137715.3852718,56.98994565010071,12.225932947635556,1739137715.3852785,56.98994565010071,0.004,1739137715.3852851,56.98994565010071,3.115286424074037,1739137715.3852901,56.98994565010071,0.10140785005918475,1739137715.3852952,56.98994565010071,0.021694224706690756,1739137715.3853004,56.98994565010071,2.400621331205514,1739137715.3853061,56.98994565010071,0.0,1739137715.3853111,56.98994565010071,0.10301771808899263,1739137715.385317,56.98994565010071,3.1033182912629713,1739137715.3853226,56.98994565010071,2.297603613116521 +1739137715.4058228,57.00994563102722,20.696359015834748,1739137715.4058409,57.00994563102722,-0.21887638608716298,1739137715.4058716,57.00994563102722,92.20893457751919,1739137715.4058993,57.00994563102722,12.225932947635556,1739137715.4059103,57.00994563102722,0.004,1739137715.405933,57.00994563102722,3.115286424074037,1739137715.4059463,57.00994563102722,0.10140785005918475,1739137715.405959,57.00994563102722,0.021694224706690756,1739137715.4059775,57.00994563102722,2.400621331205514,1739137715.4059923,57.00994563102722,0.0,1739137715.4060106,57.00994563102722,0.10301771808899263,1739137715.4060295,57.00994563102722,3.1033182912629713,1739137715.4060457,57.00994563102722,2.297603613116521 +1739137715.439642,57.03994560241699,20.443288802599675,1739137715.4396493,57.03994560241699,-0.20909581298366486,1739137715.4396582,57.03994560241699,92.23676252040195,1739137715.4396687,57.03994560241699,12.165598453245265,1739137715.4396744,57.03994560241699,0.004,1739137715.4396818,57.03994560241699,3.1158549479903126,1739137715.4396887,57.03994560241699,0.11008196030830097,1739137715.4396954,57.03994560241699,0.024659911571135895,1739137715.439702,57.03994560241699,2.3923064627268844,1739137715.4397087,57.03994560241699,0.0,1739137715.4397154,57.03994560241699,0.06645787434023506,1739137715.4397225,57.03994560241699,3.1025603285161303,1739137715.439729,57.03994560241699,2.308439130285694 +1739137715.4597895,57.059945583343506,20.443288802599675,1739137715.4597943,57.059945583343506,-0.20909581298366486,1739137715.4597995,57.059945583343506,92.23676252040195,1739137715.4598048,57.059945583343506,12.165598453245265,1739137715.4598072,57.059945583343506,0.004,1739137715.4598105,57.059945583343506,3.1158549479903126,1739137715.459813,57.059945583343506,0.11008196030830097,1739137715.4598157,57.059945583343506,0.024659911571135895,1739137715.4598181,57.059945583343506,2.3923064627268844,1739137715.459821,57.059945583343506,0.0,1739137715.4598234,57.059945583343506,0.08386733244119027,1739137715.4598265,57.059945583343506,3.1025603285161303,1739137715.459829,57.059945583343506,2.308439130285694 +1739137715.4760137,57.07994556427002,20.443288802599675,1739137715.4760175,57.07994556427002,-0.20909581298366486,1739137715.4760222,57.07994556427002,92.23676252040195,1739137715.4760265,57.07994556427002,12.165598453245265,1739137715.4760287,57.07994556427002,0.004,1739137715.4760313,57.07994556427002,3.1158549479903126,1739137715.4760334,57.07994556427002,0.11008196030830097,1739137715.4760356,57.07994556427002,0.024659911571135895,1739137715.4760377,57.07994556427002,2.3923064627268844,1739137715.47604,57.07994556427002,0.0,1739137715.476042,57.07994556427002,0.08386733244119027,1739137715.4760447,57.07994556427002,3.1025603285161303,1739137715.4760466,57.07994556427002,2.308439130285694 +1739137715.4961252,57.09994554519653,20.443288802599675,1739137715.496129,57.09994554519653,-0.20909581298366486,1739137715.4961329,57.09994554519653,92.23676252040195,1739137715.4961362,57.09994554519653,12.165598453245265,1739137715.4961383,57.09994554519653,0.004,1739137715.4961405,57.09994554519653,3.1158549479903126,1739137715.4961426,57.09994554519653,0.11008196030830097,1739137715.4961445,57.09994554519653,0.024659911571135895,1739137715.4961464,57.09994554519653,2.3923064627268844,1739137715.4961486,57.09994554519653,0.0,1739137715.4961503,57.09994554519653,0.08386733244119027,1739137715.4961522,57.09994554519653,3.1025603285161303,1739137715.496154,57.09994554519653,2.308439130285694 +1739137715.513976,57.11994552612305,20.443288802599675,1739137715.5139785,57.11994552612305,-0.20909581298366486,1739137715.5139809,57.11994552612305,92.23676252040195,1739137715.5139837,57.11994552612305,12.165598453245265,1739137715.513985,57.11994552612305,0.004,1739137715.5139866,57.11994552612305,3.1158549479903126,1739137715.5139878,57.11994552612305,0.11008196030830097,1739137715.5139892,57.11994552612305,0.024659911571135895,1739137715.5139904,57.11994552612305,2.3923064627268844,1739137715.5139916,57.11994552612305,0.0,1739137715.513993,57.11994552612305,0.08386733244119027,1739137715.5139945,57.11994552612305,3.1025603285161303,1739137715.513996,57.11994552612305,2.308439130285694 +1739137715.535324,57.13994550704956,20.443288802599675,1739137715.5353277,57.13994550704956,-0.20909581298366486,1739137715.5353322,57.13994550704956,92.23676252040195,1739137715.5353374,57.13994550704956,12.165598453245265,1739137715.5353403,57.13994550704956,0.004,1739137715.535344,57.13994550704956,3.1158549479903126,1739137715.535347,57.13994550704956,0.11008196030830097,1739137715.5353503,57.13994550704956,0.024659911571135895,1739137715.5353537,57.13994550704956,2.3923064627268844,1739137715.5353572,57.13994550704956,0.0,1739137715.5353603,57.13994550704956,0.08386733244119027,1739137715.5353637,57.13994550704956,3.1025603285161303,1739137715.535367,57.13994550704956,2.308439130285694 +1739137715.5536823,57.159945487976074,20.18914414664728,1739137715.5536845,57.159945487976074,-0.19909327693029155,1739137715.553687,57.159945487976074,92.26470843002065,1739137715.5536892,57.159945487976074,12.11166242977323,1739137715.5536907,57.159945487976074,0.004,1739137715.553692,57.159945487976074,3.1164548070103475,1739137715.5536935,57.159945487976074,0.11762326115326184,1739137715.5536947,57.159945487976074,0.02767232710041636,1739137715.553696,57.159945487976074,2.3851008949620898,1739137715.5536973,57.159945487976074,0.0,1739137715.5536983,57.159945487976074,0.05357207140734907,1739137715.5536997,57.159945487976074,3.1018970206953695,1739137715.5537012,57.159945487976074,2.317102501570143 +1739137715.5766878,57.17994546890259,20.18914414664728,1739137715.5766919,57.17994546890259,-0.19909327693029155,1739137715.5766964,57.17994546890259,92.26470843002065,1739137715.5767016,57.17994546890259,12.11166242977323,1739137715.5767047,57.17994546890259,0.004,1739137715.5767083,57.17994546890259,3.1164548070103475,1739137715.5767117,57.17994546890259,0.11762326115326184,1739137715.5767152,57.17994546890259,0.02767232710041636,1739137715.5767186,57.17994546890259,2.3851008949620898,1739137715.5767221,57.17994546890259,0.0,1739137715.5767255,57.17994546890259,0.0679983933919468,1739137715.576729,57.17994546890259,3.1018970206953695,1739137715.5767324,57.17994546890259,2.317102501570143 +1739137715.5935874,57.1999454498291,20.18914414664728,1739137715.5935898,57.1999454498291,-0.19909327693029155,1739137715.5935924,57.1999454498291,92.26470843002065,1739137715.593595,57.1999454498291,12.11166242977323,1739137715.5935965,57.1999454498291,0.004,1739137715.5935981,57.1999454498291,3.1164548070103475,1739137715.5935996,57.1999454498291,0.11762326115326184,1739137715.5936007,57.1999454498291,0.02767232710041636,1739137715.5936027,57.1999454498291,2.3851008949620898,1739137715.593604,57.1999454498291,0.0,1739137715.5936053,57.1999454498291,0.0679983933919468,1739137715.5936067,57.1999454498291,3.1018970206953695,1739137715.593608,57.1999454498291,2.317102501570143 +1739137715.6136382,57.219945430755615,20.18914414664728,1739137715.6136408,57.219945430755615,-0.19909327693029155,1739137715.6136432,57.219945430755615,92.26470843002065,1739137715.6136458,57.219945430755615,12.11166242977323,1739137715.6136472,57.219945430755615,0.004,1739137715.6136484,57.219945430755615,3.1164548070103475,1739137715.6136498,57.219945430755615,0.11762326115326184,1739137715.6136513,57.219945430755615,0.02767232710041636,1739137715.6136525,57.219945430755615,2.3851008949620898,1739137715.613654,57.219945430755615,0.0,1739137715.613655,57.219945430755615,0.0679983933919468,1739137715.6136565,57.219945430755615,3.1018970206953695,1739137715.613658,57.219945430755615,2.317102501570143 +1739137715.6336873,57.23994541168213,20.18914414664728,1739137715.6336896,57.23994541168213,-0.19909327693029155,1739137715.6336923,57.23994541168213,92.26470843002065,1739137715.6336946,57.23994541168213,12.11166242977323,1739137715.6336963,57.23994541168213,0.004,1739137715.6336977,57.23994541168213,3.1164548070103475,1739137715.6336992,57.23994541168213,0.11762326115326184,1739137715.6337004,57.23994541168213,0.02767232710041636,1739137715.6337016,57.23994541168213,2.3851008949620898,1739137715.6337032,57.23994541168213,0.0,1739137715.6337044,57.23994541168213,0.0679983933919468,1739137715.633706,57.23994541168213,3.1018970206953695,1739137715.633707,57.23994541168213,2.317102501570143 +1739137715.655481,57.25994539260864,19.934103102303524,1739137715.655485,57.25994539260864,-0.18889857733312798,1739137715.6554897,57.25994539260864,92.5864562955595,1739137715.6554954,57.25994539260864,11.768001850482298,1739137715.6554983,57.25994539260864,0.0023109399200193057,1739137715.655502,57.25994539260864,3.1181818999833433,1739137715.6555057,57.25994539260864,0.13735943557061175,1739137715.655509,57.25994539260864,0.03162030588389397,1739137715.6555123,57.25994539260864,2.3663459157687248,1739137715.6555161,57.25994539260864,0.0,1739137715.6555195,57.25994539260864,0.01824441753123335,1739137715.655523,57.25994539260864,3.1013650292359305,1739137715.6555264,57.25994539260864,2.3244091169446293 +1739137715.6766346,57.279945373535156,19.934103102303524,1739137715.676638,57.279945373535156,-0.18889857733312798,1739137715.6766427,57.279945373535156,92.5864562955595,1739137715.6766477,57.279945373535156,11.768001850482298,1739137715.6766505,57.279945373535156,0.0023109399200193057,1739137715.6766543,57.279945373535156,3.1181818999833433,1739137715.6766577,57.279945373535156,0.13735943557061175,1739137715.676661,57.279945373535156,0.03162030588389397,1739137715.6766644,57.279945373535156,2.3663459157687248,1739137715.676668,57.279945373535156,0.0,1739137715.6766713,57.279945373535156,0.04193679882409551,1739137715.6766748,57.279945373535156,3.1013650292359305,1739137715.6766782,57.279945373535156,2.3244091169446293 +1739137715.6939511,57.29994535446167,19.934103102303524,1739137715.6939535,57.29994535446167,-0.18889857733312798,1739137715.6939561,57.29994535446167,92.5864562955595,1739137715.693959,57.29994535446167,11.768001850482298,1739137715.6939602,57.29994535446167,0.0023109399200193057,1739137715.6939616,57.29994535446167,3.1181818999833433,1739137715.693963,57.29994535446167,0.13735943557061175,1739137715.6939642,57.29994535446167,0.03162030588389397,1739137715.693966,57.29994535446167,2.3663459157687248,1739137715.693967,57.29994535446167,0.0,1739137715.6939683,57.29994535446167,0.04193679882409551,1739137715.69397,57.29994535446167,3.1013650292359305,1739137715.6939712,57.29994535446167,2.3244091169446293 +1739137715.713823,57.319945335388184,19.934103102303524,1739137715.7138252,57.319945335388184,-0.18889857733312798,1739137715.7138278,57.319945335388184,92.5864562955595,1739137715.7138305,57.319945335388184,11.768001850482298,1739137715.7138317,57.319945335388184,0.0023109399200193057,1739137715.7138333,57.319945335388184,3.1181818999833433,1739137715.7138348,57.319945335388184,0.13735943557061175,1739137715.713836,57.319945335388184,0.03162030588389397,1739137715.7138374,57.319945335388184,2.3663459157687248,1739137715.7138386,57.319945335388184,0.0,1739137715.7138398,57.319945335388184,0.04193679882409551,1739137715.7138414,57.319945335388184,3.1013650292359305,1739137715.7138426,57.319945335388184,2.3244091169446293 +1739137715.7336953,57.3399453163147,19.934103102303524,1739137715.7336986,57.3399453163147,-0.18889857733312798,1739137715.733702,57.3399453163147,92.5864562955595,1739137715.7337048,57.3399453163147,11.768001850482298,1739137715.733706,57.3399453163147,0.0023109399200193057,1739137715.7337077,57.3399453163147,3.1181818999833433,1739137715.7337096,57.3399453163147,0.13735943557061175,1739137715.7337108,57.3399453163147,0.03162030588389397,1739137715.7337124,57.3399453163147,2.3663459157687248,1739137715.733714,57.3399453163147,0.0,1739137715.7337155,57.3399453163147,0.04193679882409551,1739137715.733717,57.3399453163147,3.1013650292359305,1739137715.7337182,57.3399453163147,2.3244091169446293 +1739137715.7536736,57.35994529724121,19.934103102303524,1739137715.7536762,57.35994529724121,-0.18889857733312798,1739137715.7536793,57.35994529724121,92.5864562955595,1739137715.7536821,57.35994529724121,11.768001850482298,1739137715.7536836,57.35994529724121,0.0023109399200193057,1739137715.7536852,57.35994529724121,3.1181818999833433,1739137715.7536867,57.35994529724121,0.13735943557061175,1739137715.7536886,57.35994529724121,0.03162030588389397,1739137715.7536898,57.35994529724121,2.3663459157687248,1739137715.7536914,57.35994529724121,0.0,1739137715.7536929,57.35994529724121,0.04193679882409551,1739137715.7536945,57.35994529724121,3.1013650292359305,1739137715.753696,57.35994529724121,2.3244091169446293 +1739137715.7740483,57.379945278167725,19.678441718058277,1739137715.7740517,57.379945278167725,-0.17856447368697737,1739137715.7740548,57.379945278167725,92.9072242326645,1739137715.7740574,57.379945278167725,11.434876921082978,1739137715.7740588,57.379945278167725,0.0006810927204016653,1739137715.7740602,57.379945278167725,3.119852383399796,1739137715.774062,57.379945278167725,0.15536872075858843,1739137715.7740633,57.379945278167725,0.03509939220033556,1739137715.7740648,57.379945278167725,2.349360688201819,1739137715.7740664,57.379945278167725,0.0,1739137715.7740679,57.379945278167725,0.0016424430106571075,1739137715.7740695,57.379945278167725,3.1010084484476907,1739137715.774071,57.379945278167725,2.3285304471234287 +1739137715.7938194,57.39994525909424,19.678441718058277,1739137715.7938223,57.39994525909424,-0.17856447368697737,1739137715.7938254,57.39994525909424,92.9072242326645,1739137715.793828,57.39994525909424,11.434876921082978,1739137715.7938297,57.39994525909424,0.0006810927204016653,1739137715.7938313,57.39994525909424,3.119852383399796,1739137715.793833,57.39994525909424,0.15536872075858843,1739137715.7938342,57.39994525909424,0.03509939220033556,1739137715.7938359,57.39994525909424,2.349360688201819,1739137715.7938373,57.39994525909424,0.0,1739137715.7938385,57.39994525909424,0.020830241078390266,1739137715.7938402,57.39994525909424,3.1010084484476907,1739137715.7938414,57.39994525909424,2.3285304471234287 +1739137715.8150253,57.41994524002075,19.678441718058277,1739137715.8150291,57.41994524002075,-0.17856447368697737,1739137715.815034,57.41994524002075,92.9072242326645,1739137715.8150392,57.41994524002075,11.434876921082978,1739137715.8150423,57.41994524002075,0.0006810927204016653,1739137715.8150458,57.41994524002075,3.119852383399796,1739137715.8150494,57.41994524002075,0.15536872075858843,1739137715.815053,57.41994524002075,0.03509939220033556,1739137715.8150563,57.41994524002075,2.349360688201819,1739137715.8150601,57.41994524002075,0.0,1739137715.8150637,57.41994524002075,0.020830241078390266,1739137715.8150673,57.41994524002075,3.1010084484476907,1739137715.8150706,57.41994524002075,2.3285304471234287 +1739137715.8338656,57.439945220947266,19.678441718058277,1739137715.8338685,57.439945220947266,-0.17856447368697737,1739137715.8338718,57.439945220947266,92.9072242326645,1739137715.8338747,57.439945220947266,11.434876921082978,1739137715.8338761,57.439945220947266,0.0006810927204016653,1739137715.8338783,57.439945220947266,3.119852383399796,1739137715.8338804,57.439945220947266,0.15536872075858843,1739137715.8338819,57.439945220947266,0.03509939220033556,1739137715.833883,57.439945220947266,2.349360688201819,1739137715.8338845,57.439945220947266,0.0,1739137715.833886,57.439945220947266,0.020830241078390266,1739137715.8338876,57.439945220947266,3.1010084484476907,1739137715.8338888,57.439945220947266,2.3285304471234287 +1739137715.8539417,57.45994520187378,19.678441718058277,1739137715.8539453,57.45994520187378,-0.17856447368697737,1739137715.8539488,57.45994520187378,92.9072242326645,1739137715.8539522,57.45994520187378,11.434876921082978,1739137715.8539543,57.45994520187378,0.0006810927204016653,1739137715.853956,57.45994520187378,3.119852383399796,1739137715.853958,57.45994520187378,0.15536872075858843,1739137715.8539593,57.45994520187378,0.03509939220033556,1739137715.8539608,57.45994520187378,2.349360688201819,1739137715.8539624,57.45994520187378,0.0,1739137715.853964,57.45994520187378,0.020830241078390266,1739137715.8539658,57.45994520187378,3.1010084484476907,1739137715.8539674,57.45994520187378,2.3285304471234287 +1739137715.8738313,57.47994518280029,19.422413151381342,1739137715.8738334,57.47994518280029,-0.1681399682941409,1739137715.8738365,57.47994518280029,93.22744592057043,1739137715.8738399,57.47994518280029,11.108350034792807,1739137715.873841,57.47994518280029,-0.0013611885678824652,1739137715.873843,57.47994518280029,3.1215355031509056,1739137715.8738444,57.47994518280029,0.17243228348625247,1739137715.873846,57.47994518280029,0.038298771452369054,1739137715.8738472,57.47994518280029,2.333379902680434,1739137715.873849,57.47994518280029,0.0,1739137715.8738503,57.47994518280029,-0.013696748476277356,1739137715.873852,57.47994518280029,3.1007983551373797,1739137715.8738534,57.47994518280029,2.330635219346037 +1739137715.8939445,57.49994516372681,19.422413151381342,1739137715.8939478,57.49994516372681,-0.1681399682941409,1739137715.8939512,57.49994516372681,93.22744592057043,1739137715.893954,57.49994516372681,11.108350034792807,1739137715.8939555,57.49994516372681,-0.0013611885678824652,1739137715.8939576,57.49994516372681,3.1215355031509056,1739137715.8939593,57.49994516372681,0.17243228348625247,1739137715.8939607,57.49994516372681,0.038298771452369054,1739137715.8939621,57.49994516372681,2.333379902680434,1739137715.893964,57.49994516372681,0.0,1739137715.8939655,57.49994516372681,0.0027446833343969246,1739137715.8939672,57.49994516372681,3.1007983551373797,1739137715.8939686,57.49994516372681,2.330635219346037 +1739137715.914462,57.51994514465332,19.422413151381342,1739137715.914465,57.51994514465332,-0.1681399682941409,1739137715.9144888,57.51994514465332,93.22744592057043,1739137715.9144976,57.51994514465332,11.108350034792807,1739137715.9144995,57.51994514465332,-0.0013611885678824652,1739137715.9145017,57.51994514465332,3.1215355031509056,1739137715.914503,57.51994514465332,0.17243228348625247,1739137715.9145048,57.51994514465332,0.038298771452369054,1739137715.914506,57.51994514465332,2.333379902680434,1739137715.9145076,57.51994514465332,0.0,1739137715.914509,57.51994514465332,0.0027446833343969246,1739137715.9145105,57.51994514465332,3.1007983551373797,1739137715.914512,57.51994514465332,2.330635219346037 +1739137715.9389756,57.539945125579834,19.422413151381342,1739137715.9389834,57.539945125579834,-0.1681399682941409,1739137715.938993,57.539945125579834,93.22744592057043,1739137715.939003,57.539945125579834,11.108350034792807,1739137715.9390078,57.539945125579834,-0.0013611885678824652,1739137715.9390137,57.539945125579834,3.1215355031509056,1739137715.9390185,57.539945125579834,0.17243228348625247,1739137715.939023,57.539945125579834,0.038298771452369054,1739137715.9390278,57.539945125579834,2.333379902680434,1739137715.9390328,57.539945125579834,0.0,1739137715.9390373,57.539945125579834,0.0027446833343969246,1739137715.9390426,57.539945125579834,3.1007983551373797,1739137715.9390469,57.539945125579834,2.330635219346037 +1739137715.9615684,57.55994510650635,19.422413151381342,1739137715.9615765,57.55994510650635,-0.1681399682941409,1739137715.9615867,57.55994510650635,93.22744592057043,1739137715.961597,57.55994510650635,11.108350034792807,1739137715.9616022,57.55994510650635,-0.0013611885678824652,1739137715.961608,57.55994510650635,3.1215355031509056,1739137715.9616125,57.55994510650635,0.17243228348625247,1739137715.9616175,57.55994510650635,0.038298771452369054,1739137715.9616222,57.55994510650635,2.333379902680434,1739137715.961628,57.55994510650635,0.0,1739137715.9616327,57.55994510650635,0.0027446833343969246,1739137715.9616382,57.55994510650635,3.1007983551373797,1739137715.9616427,57.55994510650635,2.330635219346037 +1739137715.9890313,57.58994507789612,19.166272874066344,1739137715.989036,57.58994507789612,-0.1576787431698925,1739137715.9890413,57.58994507789612,93.45209421041027,1739137715.9890468,57.58994507789612,10.883784697924984,1739137715.9890494,57.58994507789612,-0.003111052958613581,1739137715.9890528,57.58994507789612,3.1229328321784506,1739137715.9890554,57.58994507789612,0.18362708372896944,1739137715.989058,57.58994507789612,0.04109868325689031,1739137715.9890606,57.58994507789612,2.3229545732367187,1739137715.9890637,57.58994507789612,0.0,1739137715.989066,57.58994507789612,-0.01710980885793404,1739137715.989069,57.58994507789612,3.1007643544382346,1739137715.9890716,57.58994507789612,2.3306098572801184 +1739137716.0069127,57.61994504928589,19.166272874066344,1739137716.0069165,57.61994504928589,-0.1576787431698925,1739137716.00692,57.61994504928589,93.45209421041027,1739137716.0069237,57.61994504928589,10.883784697924984,1739137716.0069256,57.61994504928589,-0.003111052958613581,1739137716.0069277,57.61994504928589,3.1229328321784506,1739137716.0069296,57.61994504928589,0.18362708372896944,1739137716.0069315,57.61994504928589,0.04109868325689031,1739137716.006933,57.61994504928589,2.3229545732367187,1739137716.0069351,57.61994504928589,0.0,1739137716.0069368,57.61994504928589,-0.007655284043399657,1739137716.0069392,57.61994504928589,3.1007643544382346,1739137716.0069406,57.61994504928589,2.3306098572801184 +1739137716.027115,57.629945039749146,19.166272874066344,1739137716.0271175,57.629945039749146,-0.1576787431698925,1739137716.0271204,57.629945039749146,93.45209421041027,1739137716.0271235,57.629945039749146,10.883784697924984,1739137716.027141,57.629945039749146,-0.003111052958613581,1739137716.027143,57.629945039749146,3.1229328321784506,1739137716.0271442,57.629945039749146,0.18362708372896944,1739137716.0271454,57.629945039749146,0.04109868325689031,1739137716.0271468,57.629945039749146,2.3229545732367187,1739137716.0271482,57.629945039749146,0.0,1739137716.0271497,57.629945039749146,-0.007655284043399657,1739137716.0271723,57.629945039749146,3.1007643544382346,1739137716.0271735,57.629945039749146,2.3306098572801184 +1739137716.0482788,57.659945011138916,19.166272874066344,1739137716.0482826,57.659945011138916,-0.1576787431698925,1739137716.0482874,57.659945011138916,93.45209421041027,1739137716.0482929,57.659945011138916,10.883784697924984,1739137716.048296,57.659945011138916,-0.003111052958613581,1739137716.0482996,57.659945011138916,3.1229328321784506,1739137716.048303,57.659945011138916,0.18362708372896944,1739137716.0483062,57.659945011138916,0.04109868325689031,1739137716.0483096,57.659945011138916,2.3229545732367187,1739137716.048313,57.659945011138916,0.0,1739137716.0483162,57.659945011138916,-0.007655284043399657,1739137716.0483196,57.659945011138916,3.1007643544382346,1739137716.048323,57.659945011138916,2.3306098572801184 +1739137716.067981,57.67994499206543,19.166272874066344,1739137716.0679846,57.67994499206543,-0.1576787431698925,1739137716.0679877,57.67994499206543,93.45209421041027,1739137716.0679905,57.67994499206543,10.883784697924984,1739137716.0679927,57.67994499206543,-0.003111052958613581,1739137716.067994,57.67994499206543,3.1229328321784506,1739137716.0679955,57.67994499206543,0.18362708372896944,1739137716.067997,57.67994499206543,0.04109868325689031,1739137716.0679982,57.67994499206543,2.3229545732367187,1739137716.0679998,57.67994499206543,0.0,1739137716.0680013,57.67994499206543,-0.007655284043399657,1739137716.0680027,57.67994499206543,3.1007643544382346,1739137716.0680041,57.67994499206543,2.3306098572801184 +1739137716.0872135,57.68994498252869,19.166272874066344,1739137716.0872164,57.68994498252869,-0.1576787431698925,1739137716.08722,57.68994498252869,93.45209421041027,1739137716.0872228,57.68994498252869,10.883784697924984,1739137716.0872242,57.68994498252869,-0.003111052958613581,1739137716.0872262,57.68994498252869,3.1229328321784506,1739137716.0872273,57.68994498252869,0.18362708372896944,1739137716.087229,57.68994498252869,0.04109868325689031,1739137716.0872304,57.68994498252869,2.3229545732367187,1739137716.087232,57.68994498252869,0.0,1739137716.0872335,57.68994498252869,-0.007655284043399657,1739137716.087235,57.68994498252869,3.1007643544382346,1739137716.0872364,57.68994498252869,2.3306098572801184 +1739137716.1168327,57.71994495391846,18.91016684060786,1739137716.1168416,57.71994495391846,-0.1472213303683052,1739137716.116851,57.71994495391846,93.72803804137803,1739137716.116861,57.71994495391846,10.610618147781905,1739137716.116866,57.71994495391846,-0.00540657018670669,1739137716.1168723,57.71994495391846,3.1245072714685462,1739137716.1168773,57.71994495391846,0.1966160768265651,1739137716.116882,57.71994495391846,0.04382718815126675,1739137716.1168869,57.71994495391846,2.3109167358263396,1739137716.116892,57.71994495391846,0.0,1739137716.1168966,57.71994495391846,-0.02887539675882922,1739137716.1169019,57.71994495391846,3.100818541525912,1739137716.1169066,57.71994495391846,2.3296873119585935 +1739137716.1490574,57.74994492530823,18.91016684060786,1739137716.1490612,57.74994492530823,-0.1472213303683052,1739137716.1490657,57.74994492530823,93.72803804137803,1739137716.1490705,57.74994492530823,10.610618147781905,1739137716.1490738,57.74994492530823,-0.00540657018670669,1739137716.1490774,57.74994492530823,3.1245072714685462,1739137716.1490808,57.74994492530823,0.1966160768265651,1739137716.149084,57.74994492530823,0.04382718815126675,1739137716.1490874,57.74994492530823,2.3109167358263396,1739137716.1490908,57.74994492530823,0.0,1739137716.149094,57.74994492530823,-0.018770576132253858,1739137716.1490977,57.74994492530823,3.100818541525912,1739137716.149101,57.74994492530823,2.3296873119585935 +1739137716.1695786,57.76994490623474,18.91016684060786,1739137716.1695824,57.76994490623474,-0.1472213303683052,1739137716.169587,57.76994490623474,93.72803804137803,1739137716.1695924,57.76994490623474,10.610618147781905,1739137716.1695955,57.76994490623474,-0.00540657018670669,1739137716.169599,57.76994490623474,3.1245072714685462,1739137716.1696022,57.76994490623474,0.1966160768265651,1739137716.1696055,57.76994490623474,0.04382718815126675,1739137716.1696086,57.76994490623474,2.3109167358263396,1739137716.169612,57.76994490623474,0.0,1739137716.1696153,57.76994490623474,-0.018770576132253858,1739137716.169619,57.76994490623474,3.100818541525912,1739137716.1696222,57.76994490623474,2.3296873119585935 +1739137716.1889427,57.789944887161255,18.91016684060786,1739137716.1889462,57.789944887161255,-0.1472213303683052,1739137716.18895,57.789944887161255,93.72803804137803,1739137716.1889539,57.789944887161255,10.610618147781905,1739137716.1889555,57.789944887161255,-0.00540657018670669,1739137716.188958,57.789944887161255,3.1245072714685462,1739137716.18896,57.789944887161255,0.1966160768265651,1739137716.1889617,57.789944887161255,0.04382718815126675,1739137716.1889637,57.789944887161255,2.3109167358263396,1739137716.1889656,57.789944887161255,0.0,1739137716.1889675,57.789944887161255,-0.018770576132253858,1739137716.1889696,57.789944887161255,3.100818541525912,1739137716.1889715,57.789944887161255,2.3296873119585935 +1739137716.2102866,57.80994486808777,18.65421637364296,1739137716.210291,57.80994486808777,-0.13679582411492763,1739137716.2102964,57.80994486808777,93.73955581239144,1739137716.2103028,57.80994486808777,10.605502203524438,1739137716.2103064,57.80994486808777,-0.0054495613149206906,1739137716.210311,57.80994486808777,3.125275189406769,1739137716.210315,57.80994486808777,0.19540786496417273,1739137716.2103188,57.80994486808777,0.046315899054949844,1739137716.2103229,57.80994486808777,2.3120338365487565,1739137716.2103274,57.80994486808777,0.0,1739137716.2103314,57.80994486808777,-0.012564151673742177,1739137716.2103355,57.80994486808777,3.100997889863812,1739137716.2103395,57.80994486808777,2.32755342991721 +1739137716.2292593,57.82994484901428,18.65421637364296,1739137716.2292628,57.82994484901428,-0.13679582411492763,1739137716.2292674,57.82994484901428,93.73955581239144,1739137716.2292724,57.82994484901428,10.605502203524438,1739137716.2292752,57.82994484901428,-0.0054495613149206906,1739137716.2292788,57.82994484901428,3.125275189406769,1739137716.2292821,57.82994484901428,0.19540786496417273,1739137716.229285,57.82994484901428,0.046315899054949844,1739137716.2292883,57.82994484901428,2.3120338365487565,1739137716.2292917,57.82994484901428,0.0,1739137716.2292948,57.82994484901428,-0.015519593368453322,1739137716.229298,57.82994484901428,3.100997889863812,1739137716.2293015,57.82994484901428,2.32755342991721 +1739137716.2489603,57.849944829940796,18.65421637364296,1739137716.2489636,57.849944829940796,-0.13679582411492763,1739137716.248968,57.849944829940796,93.73955581239144,1739137716.248973,57.849944829940796,10.605502203524438,1739137716.2489755,57.849944829940796,-0.0054495613149206906,1739137716.248979,57.849944829940796,3.125275189406769,1739137716.2489824,57.849944829940796,0.19540786496417273,1739137716.2489858,57.849944829940796,0.046315899054949844,1739137716.2489889,57.849944829940796,2.3120338365487565,1739137716.2489922,57.849944829940796,0.0,1739137716.2489958,57.849944829940796,-0.015519593368453322,1739137716.248999,57.849944829940796,3.100997889863812,1739137716.2490025,57.849944829940796,2.32755342991721 +1739137716.2696667,57.86994481086731,18.65421637364296,1739137716.2696698,57.86994481086731,-0.13679582411492763,1739137716.269674,57.86994481086731,93.73955581239144,1739137716.2697003,57.86994481086731,10.605502203524438,1739137716.2697031,57.86994481086731,-0.0054495613149206906,1739137716.2697067,57.86994481086731,3.125275189406769,1739137716.26971,57.86994481086731,0.19540786496417273,1739137716.2697134,57.86994481086731,0.046315899054949844,1739137716.2697165,57.86994481086731,2.3120338365487565,1739137716.2697198,57.86994481086731,0.0,1739137716.2697232,57.86994481086731,-0.015519593368453322,1739137716.2697268,57.86994481086731,3.100997889863812,1739137716.26973,57.86994481086731,2.32755342991721 +1739137716.2891548,57.88994479179382,18.65421637364296,1739137716.2891583,57.88994479179382,-0.13679582411492763,1739137716.2891626,57.88994479179382,93.73955581239144,1739137716.2891676,57.88994479179382,10.605502203524438,1739137716.2891705,57.88994479179382,-0.0054495613149206906,1739137716.289174,57.88994479179382,3.125275189406769,1739137716.2891772,57.88994479179382,0.19540786496417273,1739137716.2891808,57.88994479179382,0.046315899054949844,1739137716.2891839,57.88994479179382,2.3120338365487565,1739137716.289187,57.88994479179382,0.0,1739137716.2891903,57.88994479179382,-0.015519593368453322,1739137716.2891939,57.88994479179382,3.100997889863812,1739137716.289197,57.88994479179382,2.32755342991721 +1739137716.308347,57.90994477272034,18.65421637364296,1739137716.3083506,57.90994477272034,-0.13679582411492763,1739137716.308355,57.90994477272034,93.73955581239144,1739137716.30836,57.90994477272034,10.605502203524438,1739137716.308363,57.90994477272034,-0.0054495613149206906,1739137716.3083665,57.90994477272034,3.125275189406769,1739137716.3083699,57.90994477272034,0.19540786496417273,1739137716.308373,57.90994477272034,0.046315899054949844,1739137716.3083763,57.90994477272034,2.3120338365487565,1739137716.3083797,57.90994477272034,0.0,1739137716.3083827,57.90994477272034,-0.015519593368453322,1739137716.3083863,57.90994477272034,3.100997889863812,1739137716.3083897,57.90994477272034,2.32755342991721 +1739137716.3292665,57.92994475364685,18.39848051355494,1739137716.3292706,57.92994475364685,-0.12644164291075288,1739137716.329275,57.92994475364685,94.22976093678248,1739137716.3292797,57.92994475364685,10.120408967704865,1739137716.3292825,57.92994475364685,-0.008744558837066364,1739137716.329286,57.92994475364685,3.1273756764140854,1739137716.3292892,57.92994475364685,0.21589374157595057,1739137716.3292925,57.92994475364685,0.048377952732699014,1739137716.3292956,57.92994475364685,2.2931656325087006,1739137716.3292992,57.92994475364685,0.0,1739137716.3293023,57.92994475364685,-0.048295659173589627,1739137716.329306,57.92994475364685,3.1012951579443655,1739137716.3293092,57.92994475364685,2.325853633502185 +1739137716.3549047,57.949944734573364,18.39848051355494,1739137716.354912,57.949944734573364,-0.12644164291075288,1739137716.354921,57.949944734573364,94.22976093678248,1739137716.3549323,57.949944734573364,10.120408967704865,1739137716.3549385,57.949944734573364,-0.008744558837066364,1739137716.3549464,57.949944734573364,3.1273756764140854,1739137716.3549533,57.949944734573364,0.21589374157595057,1739137716.3549604,57.949944734573364,0.048377952732699014,1739137716.3549674,57.949944734573364,2.2931656325087006,1739137716.3549747,57.949944734573364,0.0,1739137716.3549817,57.949944734573364,-0.032688000993484234,1739137716.354989,57.949944734573364,3.1012951579443655,1739137716.354996,57.949944734573364,2.325853633502185 +1739137716.3705833,57.96994471549988,18.39848051355494,1739137716.3705876,57.96994471549988,-0.12644164291075288,1739137716.3705928,57.96994471549988,94.22976093678248,1739137716.3705995,57.96994471549988,10.120408967704865,1739137716.370603,57.96994471549988,-0.008744558837066364,1739137716.3706074,57.96994471549988,3.1273756764140854,1739137716.3706114,57.96994471549988,0.21589374157595057,1739137716.3706155,57.96994471549988,0.048377952732699014,1739137716.3706195,57.96994471549988,2.2931656325087006,1739137716.3706236,57.96994471549988,0.0,1739137716.3706276,57.96994471549988,-0.032688000993484234,1739137716.370632,57.96994471549988,3.1012951579443655,1739137716.370636,57.96994471549988,2.325853633502185 +1739137716.3895497,57.98994469642639,18.39848051355494,1739137716.389553,57.98994469642639,-0.12644164291075288,1739137716.3895574,57.98994469642639,94.22976093678248,1739137716.389562,57.98994469642639,10.120408967704865,1739137716.3895645,57.98994469642639,-0.008744558837066364,1739137716.389568,57.98994469642639,3.1273756764140854,1739137716.3895712,57.98994469642639,0.21589374157595057,1739137716.3895743,57.98994469642639,0.048377952732699014,1739137716.3895772,57.98994469642639,2.2931656325087006,1739137716.3895805,57.98994469642639,0.0,1739137716.3895836,57.98994469642639,-0.032688000993484234,1739137716.3895867,57.98994469642639,3.1012951579443655,1739137716.38959,57.98994469642639,2.325853633502185 +1739137716.4091365,58.009944677352905,18.39848051355494,1739137716.4091399,58.009944677352905,-0.12644164291075288,1739137716.4091442,58.009944677352905,94.22976093678248,1739137716.4091487,58.009944677352905,10.120408967704865,1739137716.4091513,58.009944677352905,-0.008744558837066364,1739137716.4091547,58.009944677352905,3.1273756764140854,1739137716.409158,58.009944677352905,0.21589374157595057,1739137716.4091609,58.009944677352905,0.048377952732699014,1739137716.409164,58.009944677352905,2.2931656325087006,1739137716.409167,58.009944677352905,0.0,1739137716.4091702,58.009944677352905,-0.032688000993484234,1739137716.4091733,58.009944677352905,3.1012951579443655,1739137716.4091763,58.009944677352905,2.325853633502185 +1739137716.4290996,58.02994465827942,18.14300145040674,1739137716.429103,58.02994465827942,-0.11618198999319684,1739137716.429107,58.02994465827942,94.35783059185509,1739137716.429112,58.02994465827942,10.002509229717683,1739137716.4291148,58.02994465827942,-0.009,1739137716.4291182,58.02994465827942,3.1284268898821503,1739137716.4291215,58.02994465827942,0.21783768623698974,1739137716.4291246,58.02994465827942,0.050478521933816835,1739137716.429128,58.02994465827942,2.2913832107490837,1739137716.4291315,58.02994465827942,0.0,1739137716.4291348,58.02994465827942,-0.029619420938207526,1739137716.4291382,58.02994465827942,3.1016662468017038,1739137716.4291413,58.02994465827942,2.32246386101499 +1739137716.4480624,58.04994463920593,18.14300145040674,1739137716.448082,58.04994463920593,-0.11618198999319684,1739137716.4480863,58.04994463920593,94.35783059185509,1739137716.4480908,58.04994463920593,10.002509229717683,1739137716.4480934,58.04994463920593,-0.009,1739137716.4480968,58.04994463920593,3.1284268898821503,1739137716.4481,58.04994463920593,0.21783768623698974,1739137716.448103,58.04994463920593,0.050478521933816835,1739137716.448106,58.04994463920593,2.2913832107490837,1739137716.4481094,58.04994463920593,0.0,1739137716.448112,58.04994463920593,-0.03108065026590623,1739137716.4481153,58.04994463920593,3.1016662468017038,1739137716.4481184,58.04994463920593,2.32246386101499 +1739137716.4691644,58.069944620132446,18.14300145040674,1739137716.4691677,58.069944620132446,-0.11618198999319684,1739137716.4691718,58.069944620132446,94.35783059185509,1739137716.4691763,58.069944620132446,10.002509229717683,1739137716.4691792,58.069944620132446,-0.009,1739137716.4691825,58.069944620132446,3.1284268898821503,1739137716.4691856,58.069944620132446,0.21783768623698974,1739137716.4691887,58.069944620132446,0.050478521933816835,1739137716.4691913,58.069944620132446,2.2913832107490837,1739137716.4691944,58.069944620132446,0.0,1739137716.4691975,58.069944620132446,-0.03108065026590623,1739137716.4692008,58.069944620132446,3.1016662468017038,1739137716.4692037,58.069944620132446,2.32246386101499 +1739137716.4889524,58.08994460105896,18.14300145040674,1739137716.488956,58.08994460105896,-0.11618198999319684,1739137716.48896,58.08994460105896,94.35783059185509,1739137716.488965,58.08994460105896,10.002509229717683,1739137716.488968,58.08994460105896,-0.009,1739137716.4889712,58.08994460105896,3.1284268898821503,1739137716.4889746,58.08994460105896,0.21783768623698974,1739137716.4889777,58.08994460105896,0.050478521933816835,1739137716.488981,58.08994460105896,2.2913832107490837,1739137716.4889843,58.08994460105896,0.0,1739137716.4889874,58.08994460105896,-0.03108065026590623,1739137716.4889908,58.08994460105896,3.1016662468017038,1739137716.4889941,58.08994460105896,2.32246386101499 +1739137716.5094285,58.109944581985474,18.14300145040674,1739137716.5094326,58.109944581985474,-0.11618198999319684,1739137716.5094373,58.109944581985474,94.35783059185509,1739137716.5094433,58.109944581985474,10.002509229717683,1739137716.5094466,58.109944581985474,-0.009,1739137716.509451,58.109944581985474,3.1284268898821503,1739137716.5094545,58.109944581985474,0.21783768623698974,1739137716.5094588,58.109944581985474,0.050478521933816835,1739137716.5094624,58.109944581985474,2.2913832107490837,1739137716.5094664,58.109944581985474,0.0,1739137716.50947,58.109944581985474,-0.03108065026590623,1739137716.5094738,58.109944581985474,3.1016662468017038,1739137716.5094776,58.109944581985474,2.32246386101499 +1739137716.527312,58.12994456291199,18.14300145040674,1739137716.527315,58.12994456291199,-0.11618198999319684,1739137716.5273182,58.12994456291199,94.35783059185509,1739137716.527321,58.12994456291199,10.002509229717683,1739137716.5273223,58.12994456291199,-0.009,1739137716.5273244,58.12994456291199,3.1284268898821503,1739137716.5273259,58.12994456291199,0.21783768623698974,1739137716.5273275,58.12994456291199,0.050478521933816835,1739137716.527329,58.12994456291199,2.2913832107490837,1739137716.5273309,58.12994456291199,0.0,1739137716.527332,58.12994456291199,-0.03108065026590623,1739137716.5273337,58.12994456291199,3.1016662468017038,1739137716.527335,58.12994456291199,2.32246386101499 +1739137716.54773,58.1499445438385,17.887899454252743,1739137716.5477326,58.1499445438385,-0.10604465242193406,1739137716.5477352,58.1499445438385,94.68739854066222,1739137716.547738,58.1499445438385,9.683065950440701,1739137716.5477395,58.1499445438385,-0.01,1739137716.5477412,58.1499445438385,3.1298873257696105,1739137716.5477424,58.1499445438385,0.22770254050337008,1739137716.5477438,58.1499445438385,0.051941757595622876,1739137716.547745,58.1499445438385,2.282359361672093,1739137716.5477467,58.1499445438385,0.0,1739137716.5477479,58.1499445438385,-0.04186772829104451,1739137716.54775,58.1499445438385,3.102133420181254,1739137716.547751,58.1499445438385,2.319090383575634 +1739137716.5685449,58.169944524765015,17.887899454252743,1739137716.568549,58.169944524765015,-0.10604465242193406,1739137716.5685542,58.169944524765015,94.68739854066222,1739137716.56856,58.169944524765015,9.683065950440701,1739137716.568563,58.169944524765015,-0.01,1739137716.5685673,58.169944524765015,3.1298873257696105,1739137716.5685713,58.169944524765015,0.22770254050337008,1739137716.5685751,58.169944524765015,0.051941757595622876,1739137716.5685787,58.169944524765015,2.282359361672093,1739137716.5685828,58.169944524765015,0.0,1739137716.5685866,58.169944524765015,-0.03673102190354083,1739137716.5685906,58.169944524765015,3.102133420181254,1739137716.5685942,58.169944524765015,2.319090383575634 +1739137716.5869925,58.18994450569153,17.887899454252743,1739137716.5869954,58.18994450569153,-0.10604465242193406,1739137716.5869987,58.18994450569153,94.68739854066222,1739137716.5870018,58.18994450569153,9.683065950440701,1739137716.5870035,58.18994450569153,-0.01,1739137716.5870051,58.18994450569153,3.1298873257696105,1739137716.5870068,58.18994450569153,0.22770254050337008,1739137716.587008,58.18994450569153,0.051941757595622876,1739137716.5870092,58.18994450569153,2.282359361672093,1739137716.5870109,58.18994450569153,0.0,1739137716.587012,58.18994450569153,-0.03673102190354083,1739137716.587014,58.18994450569153,3.102133420181254,1739137716.5870154,58.18994450569153,2.319090383575634 +1739137716.6072602,58.20994448661804,17.887899454252743,1739137716.607263,58.20994448661804,-0.10604465242193406,1739137716.6072657,58.20994448661804,94.68739854066222,1739137716.6072686,58.20994448661804,9.683065950440701,1739137716.6072702,58.20994448661804,-0.01,1739137716.607272,58.20994448661804,3.1298873257696105,1739137716.607273,58.20994448661804,0.22770254050337008,1739137716.6072745,58.20994448661804,0.051941757595622876,1739137716.607276,58.20994448661804,2.282359361672093,1739137716.6072776,58.20994448661804,0.0,1739137716.6072788,58.20994448661804,-0.03673102190354083,1739137716.6072805,58.20994448661804,3.102133420181254,1739137716.607282,58.20994448661804,2.319090383575634 +1739137716.6274524,58.229944467544556,17.887899454252743,1739137716.6274555,58.229944467544556,-0.10604465242193406,1739137716.6274588,58.229944467544556,94.68739854066222,1739137716.627462,58.229944467544556,9.683065950440701,1739137716.6274633,58.229944467544556,-0.01,1739137716.6274652,58.229944467544556,3.1298873257696105,1739137716.6274667,58.229944467544556,0.22770254050337008,1739137716.627468,58.229944467544556,0.051941757595622876,1739137716.6274693,58.229944467544556,2.282359361672093,1739137716.6274712,58.229944467544556,0.0,1739137716.6274724,58.229944467544556,-0.03673102190354083,1739137716.6274738,58.229944467544556,3.102133420181254,1739137716.6274755,58.229944467544556,2.319090383575634 +1739137716.653409,58.24994444847107,17.633199714026134,1739137716.6534178,58.24994444847107,-0.09605036095335251,1739137716.6534274,58.24994444847107,94.81641061130783,1739137716.6534367,58.24994444847107,9.56624502630914,1739137716.6534414,58.24994444847107,-0.01,1739137716.6534472,58.24994444847107,3.130926038894188,1739137716.6534524,58.24994444847107,0.2278858351957925,1739137716.653457,58.24994444847107,0.053776604684685224,1739137716.6534615,58.24994444847107,2.282192030063489,1739137716.6534667,58.24994444847107,0.0,1739137716.6534717,58.24994444847107,-0.029292467451127624,1739137716.6534772,58.24994444847107,3.1026745864563523,1739137716.6534817,58.24994444847107,2.315026668070949 +1739137716.6738179,58.26994442939758,17.633199714026134,1739137716.6738253,58.26994442939758,-0.09605036095335251,1739137716.673833,58.26994442939758,94.81641061130783,1739137716.67384,58.26994442939758,9.56624502630914,1739137716.6738436,58.26994442939758,-0.01,1739137716.673848,58.26994442939758,3.130926038894188,1739137716.6738515,58.26994442939758,0.2278858351957925,1739137716.6738548,58.26994442939758,0.053776604684685224,1739137716.6738584,58.26994442939758,2.282192030063489,1739137716.6738625,58.26994442939758,0.0,1739137716.6738658,58.26994442939758,-0.032834638007460004,1739137716.6738694,58.26994442939758,3.1026745864563523,1739137716.6738725,58.26994442939758,2.315026668070949 +1739137716.6947725,58.27994441986084,17.633199714026134,1739137716.6947796,58.27994441986084,-0.09605036095335251,1739137716.6947875,58.27994441986084,94.81641061130783,1739137716.6947944,58.27994441986084,9.56624502630914,1739137716.6947978,58.27994441986084,-0.01,1739137716.6948018,58.27994441986084,3.130926038894188,1739137716.6948056,58.27994441986084,0.2278858351957925,1739137716.6948085,58.27994441986084,0.053776604684685224,1739137716.6948118,58.27994441986084,2.282192030063489,1739137716.6948168,58.27994441986084,0.0,1739137716.6948202,58.27994441986084,-0.032834638007460004,1739137716.6948245,58.27994441986084,3.1026745864563523,1739137716.6948278,58.27994441986084,2.315026668070949 +1739137716.7109034,58.29994440078735,17.633199714026134,1739137716.7109098,58.29994440078735,-0.09605036095335251,1739137716.7109175,58.29994440078735,94.81641061130783,1739137716.7109244,58.29994440078735,9.56624502630914,1739137716.710928,58.29994440078735,-0.01,1739137716.7109325,58.29994440078735,3.130926038894188,1739137716.7109358,58.29994440078735,0.2278858351957925,1739137716.7109396,58.29994440078735,0.053776604684685224,1739137716.7109432,58.29994440078735,2.282192030063489,1739137716.7109475,58.29994440078735,0.0,1739137716.710951,58.29994440078735,-0.032834638007460004,1739137716.710955,58.29994440078735,3.1026745864563523,1739137716.710958,58.29994440078735,2.315026668070949 +1739137716.7305748,58.31994438171387,17.633199714026134,1739137716.7305808,58.31994438171387,-0.09605036095335251,1739137716.7305882,58.31994438171387,94.81641061130783,1739137716.730595,58.31994438171387,9.56624502630914,1739137716.7305982,58.31994438171387,-0.01,1739137716.7306025,58.31994438171387,3.130926038894188,1739137716.7306058,58.31994438171387,0.2278858351957925,1739137716.7306094,58.31994438171387,0.053776604684685224,1739137716.7306125,58.31994438171387,2.282192030063489,1739137716.730616,58.31994438171387,0.0,1739137716.7306194,58.31994438171387,-0.032834638007460004,1739137716.7306232,58.31994438171387,3.1026745864563523,1739137716.7306263,58.31994438171387,2.315026668070949 +1739137716.748636,58.33994436264038,17.633199714026134,1739137716.7486403,58.33994436264038,-0.09605036095335251,1739137716.7486453,58.33994436264038,94.81641061130783,1739137716.7486494,58.33994436264038,9.56624502630914,1739137716.7486517,58.33994436264038,-0.01,1739137716.7486546,58.33994436264038,3.130926038894188,1739137716.748657,58.33994436264038,0.2278858351957925,1739137716.7486591,58.33994436264038,0.053776604684685224,1739137716.7486615,58.33994436264038,2.282192030063489,1739137716.748664,58.33994436264038,0.0,1739137716.748666,58.33994436264038,-0.032834638007460004,1739137716.7486684,58.33994436264038,3.1026745864563523,1739137716.7486708,58.33994436264038,2.315026668070949 +1739137716.767352,58.359944343566895,17.37891005585054,1739137716.7673554,58.359944343566895,-0.08622095607772806,1739137716.7673595,58.359944343566895,95.08244103728282,1739137716.7673626,58.359944343566895,9.31078742618145,1739137716.7673638,58.359944343566895,-0.01,1739137716.7673657,58.359944343566895,3.1321457609051793,1739137716.7673671,58.359944343566895,0.23267185775391283,1739137716.7673688,58.359944343566895,0.05489121764786927,1739137716.7673702,58.359944343566895,2.277827160454323,1739137716.7673721,58.359944343566895,0.0,1739137716.7673738,58.359944343566895,-0.034439409723640596,1739137716.7673755,58.359944343566895,3.1033046358470986,1739137716.767377,58.359944343566895,2.3115023927885185 +1739137716.787519,58.37994432449341,17.37891005585054,1739137716.7875218,58.37994432449341,-0.08622095607772806,1739137716.7875252,58.37994432449341,95.08244103728282,1739137716.787528,58.37994432449341,9.31078742618145,1739137716.7875295,58.37994432449341,-0.01,1739137716.787531,58.37994432449341,3.1321457609051793,1739137716.7875323,58.37994432449341,0.23267185775391283,1739137716.7875338,58.37994432449341,0.05489121764786927,1739137716.7875352,58.37994432449341,2.277827160454323,1739137716.7875369,58.37994432449341,0.0,1739137716.7875383,58.37994432449341,-0.03367523233419556,1739137716.78754,58.37994432449341,3.1033046358470986,1739137716.7875412,58.37994432449341,2.3115023927885185 +1739137716.808013,58.39994430541992,17.37891005585054,1739137716.8080163,58.39994430541992,-0.08622095607772806,1739137716.8080194,58.39994430541992,95.08244103728282,1739137716.8080223,58.39994430541992,9.31078742618145,1739137716.8080237,58.39994430541992,-0.01,1739137716.8080256,58.39994430541992,3.1321457609051793,1739137716.808027,58.39994430541992,0.23267185775391283,1739137716.8080287,58.39994430541992,0.05489121764786927,1739137716.80803,58.39994430541992,2.277827160454323,1739137716.8080318,58.39994430541992,0.0,1739137716.808033,58.39994430541992,-0.03367523233419556,1739137716.808035,58.39994430541992,3.1033046358470986,1739137716.808036,58.39994430541992,2.3115023927885185 +1739137716.827063,58.419944286346436,17.37891005585054,1739137716.827066,58.419944286346436,-0.08622095607772806,1739137716.8270686,58.419944286346436,95.08244103728282,1739137716.827072,58.419944286346436,9.31078742618145,1739137716.8270738,58.419944286346436,-0.01,1739137716.8270755,58.419944286346436,3.1321457609051793,1739137716.827077,58.419944286346436,0.23267185775391283,1739137716.8270783,58.419944286346436,0.05489121764786927,1739137716.8270798,58.419944286346436,2.277827160454323,1739137716.8270812,58.419944286346436,0.0,1739137716.8270826,58.419944286346436,-0.03367523233419556,1739137716.8270843,58.419944286346436,3.1033046358470986,1739137716.8270855,58.419944286346436,2.3115023927885185 +1739137716.8472693,58.43994426727295,17.37891005585054,1739137716.8472729,58.43994426727295,-0.08622095607772806,1739137716.847276,58.43994426727295,95.08244103728282,1739137716.8472793,58.43994426727295,9.31078742618145,1739137716.847281,58.43994426727295,-0.01,1739137716.8472834,58.43994426727295,3.1321457609051793,1739137716.847285,58.43994426727295,0.23267185775391283,1739137716.8472865,58.43994426727295,0.05489121764786927,1739137716.8472898,58.43994426727295,2.277827160454323,1739137716.8472917,58.43994426727295,0.0,1739137716.8472934,58.43994426727295,-0.03367523233419556,1739137716.8472953,58.43994426727295,3.1033046358470986,1739137716.8472967,58.43994426727295,2.3115023927885185 +1739137716.8681796,58.45994424819946,17.37891005585054,1739137716.8681839,58.45994424819946,-0.08622095607772806,1739137716.8681884,58.45994424819946,95.08244103728282,1739137716.8681943,58.45994424819946,9.31078742618145,1739137716.8681972,58.45994424819946,-0.01,1739137716.868201,58.45994424819946,3.1321457609051793,1739137716.8682044,58.45994424819946,0.23267185775391283,1739137716.8682077,58.45994424819946,0.05489121764786927,1739137716.8682115,58.45994424819946,2.277827160454323,1739137716.868215,58.45994424819946,0.0,1739137716.8682184,58.45994424819946,-0.03367523233419556,1739137716.868222,58.45994424819946,3.1033046358470986,1739137716.8682253,58.45994424819946,2.3115023927885185 +1739137716.8873677,58.47994422912598,17.1250140388153,1739137716.8873708,58.47994422912598,-0.07657638946661738,1739137716.8873749,58.47994422912598,95.3723506041223,1739137716.8873782,58.47994422912598,9.031987090461522,1739137716.8873796,58.47994422912598,-0.011,1739137716.887382,58.47994422912598,3.133490004879357,1739137716.8873835,58.47994422912598,0.23850535263523193,1739137716.8873854,58.47994422912598,0.05592275419106391,1739137716.8873868,58.47994422912598,2.2725182794966776,1739137716.8873897,58.47994422912598,0.0,1739137716.8873916,58.47994422912598,-0.03674357884192034,1739137716.887393,58.47994422912598,3.1040162296136895,1739137716.8873942,58.47994422912598,2.3078007402240748 +1739137716.9125512,58.49994421005249,17.1250140388153,1739137716.9125602,58.49994421005249,-0.07657638946661738,1739137716.9125707,58.49994421005249,95.3723506041223,1739137716.9125803,58.49994421005249,9.031987090461522,1739137716.912585,58.49994421005249,-0.011,1739137716.9125907,58.49994421005249,3.133490004879357,1739137716.9125955,58.49994421005249,0.23850535263523193,1739137716.9126005,58.49994421005249,0.05592275419106391,1739137716.9126053,58.49994421005249,2.2725182794966776,1739137716.9126105,58.49994421005249,0.0,1739137716.912615,58.49994421005249,-0.03528246072739716,1739137716.9126208,58.49994421005249,3.1040162296136895,1739137716.9126253,58.49994421005249,2.3078007402240748 +1739137716.929848,58.519944190979004,17.1250140388153,1739137716.9298532,58.519944190979004,-0.07657638946661738,1739137716.9298584,58.519944190979004,95.3723506041223,1739137716.9298642,58.519944190979004,9.031987090461522,1739137716.929867,58.519944190979004,-0.011,1739137716.9298704,58.519944190979004,3.133490004879357,1739137716.9298732,58.519944190979004,0.23850535263523193,1739137716.9298756,58.519944190979004,0.05592275419106391,1739137716.9298782,58.519944190979004,2.2725182794966776,1739137716.9298813,58.519944190979004,0.0,1739137716.929884,58.519944190979004,-0.03528246072739716,1739137716.9298868,58.519944190979004,3.1040162296136895,1739137716.9298892,58.519944190979004,2.3078007402240748 +1739137716.9513938,58.52994418144226,17.1250140388153,1739137716.9514003,58.52994418144226,-0.07657638946661738,1739137716.9514077,58.52994418144226,95.3723506041223,1739137716.951416,58.52994418144226,9.031987090461522,1739137716.951421,58.52994418144226,-0.011,1739137716.951427,58.52994418144226,3.133490004879357,1739137716.9514327,58.52994418144226,0.23850535263523193,1739137716.9514382,58.52994418144226,0.05592275419106391,1739137716.9514434,58.52994418144226,2.2725182794966776,1739137716.9514492,58.52994418144226,0.0,1739137716.9514544,58.52994418144226,-0.03528246072739716,1739137716.9514601,58.52994418144226,3.1040162296136895,1739137716.9514654,58.52994418144226,2.3078007402240748 +1739137716.969068,58.55994415283203,17.1250140388153,1739137716.969072,58.55994415283203,-0.07657638946661738,1739137716.9690766,58.55994415283203,95.3723506041223,1739137716.9690819,58.55994415283203,9.031987090461522,1739137716.9690845,58.55994415283203,-0.011,1739137716.9690883,58.55994415283203,3.133490004879357,1739137716.9690917,58.55994415283203,0.23850535263523193,1739137716.969095,58.55994415283203,0.05592275419106391,1739137716.9690983,58.55994415283203,2.2725182794966776,1739137716.9691017,58.55994415283203,0.0,1739137716.969105,58.55994415283203,-0.03528246072739716,1739137716.9691083,58.55994415283203,3.1040162296136895,1739137716.9691114,58.55994415283203,2.3078007402240748 +1739137716.989364,58.579944133758545,16.871525942049843,1739137716.9893677,58.579944133758545,-0.06712966361876482,1739137716.9893727,58.579944133758545,95.96027844658659,1739137716.9893777,58.579944133758545,8.45568049539428,1739137716.9893813,58.579944133758545,-0.010357656120027904,1739137716.989385,58.579944133758545,3.134846908706782,1739137716.9893887,58.579944133758545,0.2533826463599845,1739137716.989392,58.579944133758545,0.05494197409993904,1739137716.9893954,58.579944133758545,2.2590348698413845,1739137716.9893987,58.579944133758545,0.0,1739137716.989402,58.579944133758545,-0.05363150646725428,1739137716.9894056,58.579944133758545,3.104735236985852,1739137716.989409,58.579944133758545,2.3039287311153 +1739137717.0091293,58.59994411468506,16.871525942049843,1739137717.0091336,58.59994411468506,-0.06712966361876482,1739137717.0091386,58.59994411468506,95.96027844658659,1739137717.0091438,58.59994411468506,8.45568049539428,1739137717.009147,58.59994411468506,-0.010357656120027904,1739137717.0091505,58.59994411468506,3.134846908706782,1739137717.0091538,58.59994411468506,0.2533826463599845,1739137717.0091572,58.59994411468506,0.05494197409993904,1739137717.0091608,58.59994411468506,2.2590348698413845,1739137717.009164,58.59994411468506,0.0,1739137717.0091677,58.59994411468506,-0.04489386127391537,1739137717.0091717,58.59994411468506,3.104735236985852,1739137717.0091758,58.59994411468506,2.3039287311153 +1739137717.0294313,58.61994409561157,16.871525942049843,1739137717.0294344,58.61994409561157,-0.06712966361876482,1739137717.0294378,58.61994409561157,95.96027844658659,1739137717.0294404,58.61994409561157,8.45568049539428,1739137717.029442,58.61994409561157,-0.010357656120027904,1739137717.0294445,58.61994409561157,3.134846908706782,1739137717.029446,58.61994409561157,0.2533826463599845,1739137717.0294473,58.61994409561157,0.05494197409993904,1739137717.0294487,58.61994409561157,2.2590348698413845,1739137717.029451,58.61994409561157,0.0,1739137717.0294526,58.61994409561157,-0.04489386127391537,1739137717.029454,58.61994409561157,3.104735236985852,1739137717.0294557,58.61994409561157,2.3039287311153 +1739137717.047952,58.62994408607483,16.871525942049843,1739137717.047955,58.62994408607483,-0.06712966361876482,1739137717.0479584,58.62994408607483,95.96027844658659,1739137717.047961,58.62994408607483,8.45568049539428,1739137717.0479624,58.62994408607483,-0.010357656120027904,1739137717.047964,58.62994408607483,3.134846908706782,1739137717.0479658,58.62994408607483,0.2533826463599845,1739137717.047967,58.62994408607483,0.05494197409993904,1739137717.0479681,58.62994408607483,2.2590348698413845,1739137717.0479698,58.62994408607483,0.0,1739137717.047971,58.62994408607483,-0.04489386127391537,1739137717.0479727,58.62994408607483,3.104735236985852,1739137717.0479739,58.62994408607483,2.3039287311153 +1739137717.0691576,58.6599440574646,16.871525942049843,1739137717.0691614,58.6599440574646,-0.06712966361876482,1739137717.0691664,58.6599440574646,95.96027844658659,1739137717.0691717,58.6599440574646,8.45568049539428,1739137717.0691748,58.6599440574646,-0.010357656120027904,1739137717.0691786,58.6599440574646,3.134846908706782,1739137717.069182,58.6599440574646,0.2533826463599845,1739137717.0691855,58.6599440574646,0.05494197409993904,1739137717.0691888,58.6599440574646,2.2590348698413845,1739137717.0691926,58.6599440574646,0.0,1739137717.0691965,58.6599440574646,-0.04489386127391537,1739137717.0692003,58.6599440574646,3.104735236985852,1739137717.0692036,58.6599440574646,2.3039287311153 +1739137717.0880606,58.67994403839111,16.871525942049843,1739137717.0880632,58.67994403839111,-0.06712966361876482,1739137717.0880663,58.67994403839111,95.96027844658659,1739137717.0880692,58.67994403839111,8.45568049539428,1739137717.0880706,58.67994403839111,-0.010357656120027904,1739137717.0880723,58.67994403839111,3.134846908706782,1739137717.088074,58.67994403839111,0.2533826463599845,1739137717.0880756,58.67994403839111,0.05494197409993904,1739137717.088077,58.67994403839111,2.2590348698413845,1739137717.0880785,58.67994403839111,0.0,1739137717.08808,58.67994403839111,-0.04489386127391537,1739137717.0880814,58.67994403839111,3.104735236985852,1739137717.088083,58.67994403839111,2.3039287311153 +1739137717.10953,58.69994401931763,16.61852543455188,1739137717.1095343,58.69994401931763,-0.05788325816365525,1739137717.1095393,58.69994401931763,95.96609745825904,1739137717.1095452,58.69994401931763,8.465124899050386,1739137717.1095483,58.69994401931763,-0.010311585858290801,1739137717.1095526,58.69994401931763,3.135758139230736,1739137717.1095564,58.69994401931763,0.24704618269113426,1739137717.10956,58.69994401931763,0.05707220173232262,1739137717.1095638,58.69994401931763,2.264767849086978,1739137717.1095676,58.69994401931763,0.0,1739137717.1095717,58.69994401931763,-0.024235919345401327,1739137717.1095755,58.69994401931763,3.1054542443580146,1739137717.1095793,58.69994401931763,2.298840888550505 +1739137717.1281006,58.71994400024414,16.61852543455188,1739137717.1281035,58.71994400024414,-0.05788325816365525,1739137717.1281066,58.71994400024414,95.96609745825904,1739137717.1281092,58.71994400024414,8.465124899050386,1739137717.128111,58.71994400024414,-0.010311585858290801,1739137717.1281123,58.71994400024414,3.135758139230736,1739137717.128114,58.71994400024414,0.24704618269113426,1739137717.1281154,58.71994400024414,0.05707220173232262,1739137717.1281168,58.71994400024414,2.264767849086978,1739137717.1281188,58.71994400024414,0.0,1739137717.12812,58.71994400024414,-0.03407303946352691,1739137717.1281219,58.71994400024414,3.1054542443580146,1739137717.128123,58.71994400024414,2.298840888550505 +1739137717.1477888,58.739943981170654,16.61852543455188,1739137717.1477916,58.739943981170654,-0.05788325816365525,1739137717.1477945,58.739943981170654,95.96609745825904,1739137717.1477976,58.739943981170654,8.465124899050386,1739137717.147799,58.739943981170654,-0.010311585858290801,1739137717.147801,58.739943981170654,3.135758139230736,1739137717.1478024,58.739943981170654,0.24704618269113426,1739137717.1478035,58.739943981170654,0.05707220173232262,1739137717.147805,58.739943981170654,2.264767849086978,1739137717.1478064,58.739943981170654,0.0,1739137717.1478078,58.739943981170654,-0.03407303946352691,1739137717.1478093,58.739943981170654,3.1054542443580146,1739137717.1478105,58.739943981170654,2.298840888550505 +1739137717.1691413,58.75994396209717,16.61852543455188,1739137717.1691453,58.75994396209717,-0.05788325816365525,1739137717.16915,58.75994396209717,95.96609745825904,1739137717.169156,58.75994396209717,8.465124899050386,1739137717.1691592,58.75994396209717,-0.010311585858290801,1739137717.1691635,58.75994396209717,3.135758139230736,1739137717.169167,58.75994396209717,0.24704618269113426,1739137717.1691706,58.75994396209717,0.05707220173232262,1739137717.1691744,58.75994396209717,2.264767849086978,1739137717.169178,58.75994396209717,0.0,1739137717.169182,58.75994396209717,-0.03407303946352691,1739137717.1691859,58.75994396209717,3.1054542443580146,1739137717.16919,58.75994396209717,2.298840888550505 +1739137717.1875896,58.77994394302368,16.61852543455188,1739137717.187593,58.77994394302368,-0.05788325816365525,1739137717.187596,58.77994394302368,95.96609745825904,1739137717.1875994,58.77994394302368,8.465124899050386,1739137717.1876009,58.77994394302368,-0.010311585858290801,1739137717.1876032,58.77994394302368,3.135758139230736,1739137717.1876047,58.77994394302368,0.24704618269113426,1739137717.1876063,58.77994394302368,0.05707220173232262,1739137717.1876078,58.77994394302368,2.264767849086978,1739137717.1876097,58.77994394302368,0.0,1739137717.187611,58.77994394302368,-0.03407303946352691,1739137717.1876128,58.77994394302368,3.1054542443580146,1739137717.1876142,58.77994394302368,2.298840888550505 +1739137717.2096803,58.799943923950195,16.3659952303182,1739137717.2096848,58.799943923950195,-0.04884200010549122,1739137717.2096894,58.799943923950195,96.25143564844441,1739137717.2096934,58.799943923950195,8.190700275506986,1739137717.2096956,58.799943923950195,-0.011,1739137717.209699,58.799943923950195,3.1369638628182743,1739137717.2097013,58.799943923950195,0.2511392907034429,1739137717.209704,58.799943923950195,0.057708015794208256,1739137717.2097063,58.799943923950195,2.261062907088499,1739137717.2097087,58.799943923950195,0.0,1739137717.2097113,58.799943923950195,-0.03420218214186081,1739137717.2097137,58.799943923950195,3.1062400643289387,1739137717.2097166,58.799943923950195,2.295203592686147 +1739137717.228223,58.80994391441345,16.3659952303182,1739137717.2282274,58.80994391441345,-0.04884200010549122,1739137717.2282324,58.80994391441345,96.25143564844441,1739137717.2282376,58.80994391441345,8.190700275506986,1739137717.2282405,58.80994391441345,-0.011,1739137717.2282434,58.80994391441345,3.1369638628182743,1739137717.2282465,58.80994391441345,0.2511392907034429,1739137717.228249,58.80994391441345,0.057708015794208256,1739137717.2282524,58.80994391441345,2.261062907088499,1739137717.2282553,58.80994391441345,0.0,1739137717.2282581,58.80994391441345,-0.03414068559764827,1739137717.2282605,58.80994391441345,3.1062400643289387,1739137717.2282631,58.80994391441345,2.295203592686147 +1739137717.2488675,58.83994388580322,16.3659952303182,1739137717.2488725,58.83994388580322,-0.04884200010549122,1739137717.248878,58.83994388580322,96.25143564844441,1739137717.2488837,58.83994388580322,8.190700275506986,1739137717.2488863,58.83994388580322,-0.011,1739137717.248889,58.83994388580322,3.1369638628182743,1739137717.2488918,58.83994388580322,0.2511392907034429,1739137717.2488942,58.83994388580322,0.057708015794208256,1739137717.2488966,58.83994388580322,2.261062907088499,1739137717.2488992,58.83994388580322,0.0,1739137717.2489018,58.83994388580322,-0.03414068559764827,1739137717.2489045,58.83994388580322,3.1062400643289387,1739137717.248907,58.83994388580322,2.295203592686147 +1739137717.2687647,58.859943866729736,16.3659952303182,1739137717.2687714,58.859943866729736,-0.04884200010549122,1739137717.2687767,58.859943866729736,96.25143564844441,1739137717.268782,58.859943866729736,8.190700275506986,1739137717.2687843,58.859943866729736,-0.011,1739137717.2687883,58.859943866729736,3.1369638628182743,1739137717.268791,58.859943866729736,0.2511392907034429,1739137717.2687936,58.859943866729736,0.057708015794208256,1739137717.2687962,58.859943866729736,2.261062907088499,1739137717.2687998,58.859943866729736,0.0,1739137717.268803,58.859943866729736,-0.03414068559764827,1739137717.2688062,58.859943866729736,3.1062400643289387,1739137717.2688084,58.859943866729736,2.295203592686147 +1739137717.2896683,58.87994384765625,16.3659952303182,1739137717.2896726,58.87994384765625,-0.04884200010549122,1739137717.2896779,58.87994384765625,96.25143564844441,1739137717.289683,58.87994384765625,8.190700275506986,1739137717.289686,58.87994384765625,-0.011,1739137717.28969,58.87994384765625,3.1369638628182743,1739137717.2896936,58.87994384765625,0.2511392907034429,1739137717.289697,58.87994384765625,0.057708015794208256,1739137717.2897005,58.87994384765625,2.261062907088499,1739137717.289704,58.87994384765625,0.0,1739137717.2897074,58.87994384765625,-0.03414068559764827,1739137717.2897115,58.87994384765625,3.1062400643289387,1739137717.289715,58.87994384765625,2.295203592686147 +1739137717.3106527,58.899943828582764,16.3659952303182,1739137717.310659,58.899943828582764,-0.04884200010549122,1739137717.3106644,58.899943828582764,96.25143564844441,1739137717.310669,58.899943828582764,8.190700275506986,1739137717.3106716,58.899943828582764,-0.011,1739137717.3106756,58.899943828582764,3.1369638628182743,1739137717.3106782,58.899943828582764,0.2511392907034429,1739137717.3106813,58.899943828582764,0.057708015794208256,1739137717.310684,58.899943828582764,2.261062907088499,1739137717.3106868,58.899943828582764,0.0,1739137717.3106894,58.899943828582764,-0.03414068559764827,1739137717.3106923,58.899943828582764,3.1062400643289387,1739137717.3107107,58.899943828582764,2.295203592686147 +1739137717.328548,58.91994380950928,16.11386454730163,1739137717.328552,58.91994380950928,-0.04001665911625807,1739137717.3285563,58.91994380950928,96.91784774423475,1739137717.3285606,58.91994380950928,7.535511426311633,1739137717.3285635,58.91994380950928,-0.013,1739137717.3285663,58.91994380950928,3.1384432647254945,1739137717.3285692,58.91994380950928,0.2693390826542345,1739137717.3285716,58.91994380950928,0.0562118160529672,1739137717.328574,58.91994380950928,2.2446623271503707,1739137717.3285768,58.91994380950928,0.0,1739137717.32858,58.91994380950928,-0.05831446005076195,1739137717.3285828,58.91994380950928,3.107040731544032,1739137717.3285851,58.91994380950928,2.2914654602825726 +1739137717.3471298,58.93994379043579,16.11386454730163,1739137717.3471322,58.93994379043579,-0.04001665911625807,1739137717.3471348,58.93994379043579,96.91784774423475,1739137717.3471372,58.93994379043579,7.535511426311633,1739137717.3471386,58.93994379043579,-0.013,1739137717.3471403,58.93994379043579,3.1384432647254945,1739137717.3471417,58.93994379043579,0.2693390826542345,1739137717.347143,58.93994379043579,0.0562118160529672,1739137717.3471441,58.93994379043579,2.2446623271503707,1739137717.3471456,58.93994379043579,0.0,1739137717.3471467,58.93994379043579,-0.04680313313220186,1739137717.3471482,58.93994379043579,3.107040731544032,1739137717.3471496,58.93994379043579,2.2914654602825726 +1739137717.3671243,58.959943771362305,16.11386454730163,1739137717.3671262,58.959943771362305,-0.04001665911625807,1739137717.3671288,58.959943771362305,96.91784774423475,1739137717.3671315,58.959943771362305,7.535511426311633,1739137717.3671327,58.959943771362305,-0.013,1739137717.367134,58.959943771362305,3.1384432647254945,1739137717.3671355,58.959943771362305,0.2693390826542345,1739137717.3671367,58.959943771362305,0.0562118160529672,1739137717.3671381,58.959943771362305,2.2446623271503707,1739137717.3671393,58.959943771362305,0.0,1739137717.3671405,58.959943771362305,-0.04680313313220186,1739137717.367142,58.959943771362305,3.107040731544032,1739137717.3671432,58.959943771362305,2.2914654602825726 +1739137717.3870478,58.97994375228882,16.11386454730163,1739137717.3870504,58.97994375228882,-0.04001665911625807,1739137717.3870537,58.97994375228882,96.91784774423475,1739137717.3870564,58.97994375228882,7.535511426311633,1739137717.387058,58.97994375228882,-0.013,1739137717.3870597,58.97994375228882,3.1384432647254945,1739137717.3870609,58.97994375228882,0.2693390826542345,1739137717.3870625,58.97994375228882,0.0562118160529672,1739137717.3870637,58.97994375228882,2.2446623271503707,1739137717.3870654,58.97994375228882,0.0,1739137717.3870668,58.97994375228882,-0.04680313313220186,1739137717.3870685,58.97994375228882,3.107040731544032,1739137717.38707,58.97994375228882,2.2914654602825726 +1739137717.4070601,58.99994373321533,16.11386454730163,1739137717.4070628,58.99994373321533,-0.04001665911625807,1739137717.4070656,58.99994373321533,96.91784774423475,1739137717.4070685,58.99994373321533,7.535511426311633,1739137717.4070697,58.99994373321533,-0.013,1739137717.4070716,58.99994373321533,3.1384432647254945,1739137717.4070728,58.99994373321533,0.2693390826542345,1739137717.407074,58.99994373321533,0.0562118160529672,1739137717.4070754,58.99994373321533,2.2446623271503707,1739137717.4070768,58.99994373321533,0.0,1739137717.407078,58.99994373321533,-0.04680313313220186,1739137717.4070795,58.99994373321533,3.107040731544032,1739137717.4070807,58.99994373321533,2.2914654602825726 +1739137717.427158,59.019943714141846,15.862213706149166,1739137717.4271603,59.019943714141846,-0.0314098324534795,1739137717.427163,59.019943714141846,96.94729089264959,1739137717.4271653,59.019943714141846,7.521738541800967,1739137717.4271667,59.019943714141846,-0.013147349535544813,1739137717.4271684,59.019943714141846,3.139403035687693,1739137717.4271696,59.019943714141846,0.2631959783727399,1739137717.4271708,59.019943714141846,0.05810753868860807,1739137717.4271722,59.019943714141846,2.2501847872823033,1739137717.4271739,59.019943714141846,0.0,1739137717.4271753,59.019943714141846,-0.02628878017809244,1739137717.4271765,59.019943714141846,3.1078413987591254,1739137717.4271777,59.019943714141846,2.2862423118422672 +1739137717.4469864,59.03994369506836,15.862213706149166,1739137717.4469888,59.03994369506836,-0.0314098324534795,1739137717.4469917,59.03994369506836,96.94729089264959,1739137717.4469945,59.03994369506836,7.521738541800967,1739137717.4469957,59.03994369506836,-0.013147349535544813,1739137717.4469972,59.03994369506836,3.139403035687693,1739137717.4469986,59.03994369506836,0.2631959783727399,1739137717.4469998,59.03994369506836,0.05810753868860807,1739137717.447001,59.03994369506836,2.2501847872823033,1739137717.447003,59.03994369506836,0.0,1739137717.4470038,59.03994369506836,-0.036057524559963916,1739137717.4470055,59.03994369506836,3.1078413987591254,1739137717.4470067,59.03994369506836,2.2862423118422672 +1739137717.4753842,59.049943685531616,15.862213706149166,1739137717.475393,59.049943685531616,-0.0314098324534795,1739137717.4754028,59.049943685531616,96.94729089264959,1739137717.4754124,59.049943685531616,7.521738541800967,1739137717.4754174,59.049943685531616,-0.013147349535544813,1739137717.4754236,59.049943685531616,3.139403035687693,1739137717.4754286,59.049943685531616,0.2631959783727399,1739137717.475433,59.049943685531616,0.05810753868860807,1739137717.4754376,59.049943685531616,2.2501847872823033,1739137717.475443,59.049943685531616,0.0,1739137717.4754472,59.049943685531616,-0.036057524559963916,1739137717.4754527,59.049943685531616,3.1078413987591254,1739137717.4754574,59.049943685531616,2.2862423118422672 +1739137717.519257,59.089943647384644,15.862213706149166,1739137717.519266,59.089943647384644,-0.0314098324534795,1739137717.5192757,59.089943647384644,96.94729089264959,1739137717.519285,59.089943647384644,7.521738541800967,1739137717.5192902,59.089943647384644,-0.013147349535544813,1739137717.519296,59.089943647384644,3.139403035687693,1739137717.519301,59.089943647384644,0.2631959783727399,1739137717.5193052,59.089943647384644,0.05810753868860807,1739137717.5193098,59.089943647384644,2.2501847872823033,1739137717.5193152,59.089943647384644,0.0,1739137717.5193195,59.089943647384644,-0.036057524559963916,1739137717.5193248,59.089943647384644,3.1078413987591254,1739137717.519329,59.089943647384644,2.2862423118422672 +1739137717.5340545,59.10994362831116,15.862213706149166,1739137717.534063,59.10994362831116,-0.0314098324534795,1739137717.5340745,59.10994362831116,96.94729089264959,1739137717.5340881,59.10994362831116,7.521738541800967,1739137717.5340955,59.10994362831116,-0.013147349535544813,1739137717.5341053,59.10994362831116,3.139403035687693,1739137717.5341141,59.10994362831116,0.2631959783727399,1739137717.5341225,59.10994362831116,0.05810753868860807,1739137717.5341313,59.10994362831116,2.2501847872823033,1739137717.53414,59.10994362831116,0.0,1739137717.534149,59.10994362831116,-0.036057524559963916,1739137717.5341575,59.10994362831116,3.1078413987591254,1739137717.5341663,59.10994362831116,2.2862423118422672 +1739137717.551806,59.12994360923767,15.611046377193585,1739137717.551809,59.12994360923767,-0.023020884586597568,1739137717.5518126,59.12994360923767,96.97667747013737,1739137717.5518162,59.12994360923767,7.503614474461628,1739137717.551818,59.12994360923767,-0.013348728061537472,1739137717.55182,59.12994360923767,3.1403996553565072,1739137717.5518222,59.12994360923767,0.25742939994291447,1739137717.5518236,59.12994360923767,0.060148378598302396,1739137717.5518255,59.12994360923767,2.2553811248189324,1739137717.5518274,59.12994360923767,0.0,1739137717.5518293,59.12994360923767,-0.018970896058321494,1739137717.551831,59.12994360923767,3.1086420659742187,1739137717.5518327,59.12994360923767,2.282488514704475 +1739137717.57074,59.149943590164185,15.611046377193585,1739137717.5707445,59.149943590164185,-0.023020884586597568,1739137717.5707495,59.149943590164185,96.97667747013737,1739137717.5707548,59.149943590164185,7.503614474461628,1739137717.5707574,59.149943590164185,-0.013348728061537472,1739137717.5707605,59.149943590164185,3.1403996553565072,1739137717.570763,59.149943590164185,0.25742939994291447,1739137717.5707655,59.149943590164185,0.060148378598302396,1739137717.570768,59.149943590164185,2.2553811248189324,1739137717.570772,59.149943590164185,0.0,1739137717.5707746,59.149943590164185,-0.02710738988554251,1739137717.5707774,59.149943590164185,3.1086420659742187,1739137717.5707798,59.149943590164185,2.282488514704475 +1739137717.5901594,59.1699435710907,15.611046377193585,1739137717.5901628,59.1699435710907,-0.023020884586597568,1739137717.5901666,59.1699435710907,96.97667747013737,1739137717.5901701,59.1699435710907,7.503614474461628,1739137717.5901718,59.1699435710907,-0.013348728061537472,1739137717.5901742,59.1699435710907,3.1403996553565072,1739137717.5901763,59.1699435710907,0.25742939994291447,1739137717.590178,59.1699435710907,0.060148378598302396,1739137717.5901797,59.1699435710907,2.2553811248189324,1739137717.5901816,59.1699435710907,0.0,1739137717.5901833,59.1699435710907,-0.02710738988554251,1739137717.5901852,59.1699435710907,3.1086420659742187,1739137717.590187,59.1699435710907,2.282488514704475 +1739137717.612129,59.18994355201721,15.611046377193585,1739137717.6121328,59.18994355201721,-0.023020884586597568,1739137717.6121376,59.18994355201721,96.97667747013737,1739137717.612143,59.18994355201721,7.503614474461628,1739137717.612146,59.18994355201721,-0.013348728061537472,1739137717.61215,59.18994355201721,3.1403996553565072,1739137717.6121535,59.18994355201721,0.25742939994291447,1739137717.612157,59.18994355201721,0.060148378598302396,1739137717.6121607,59.18994355201721,2.2553811248189324,1739137717.6121643,59.18994355201721,0.0,1739137717.6121676,59.18994355201721,-0.02710738988554251,1739137717.6121712,59.18994355201721,3.1086420659742187,1739137717.6121747,59.18994355201721,2.282488514704475 +1739137717.6318407,59.209943532943726,15.611046377193585,1739137717.6318445,59.209943532943726,-0.023020884586597568,1739137717.6318493,59.209943532943726,96.97667747013737,1739137717.6318543,59.209943532943726,7.503614474461628,1739137717.6318572,59.209943532943726,-0.013348728061537472,1739137717.6318607,59.209943532943726,3.1403996553565072,1739137717.631864,59.209943532943726,0.25742939994291447,1739137717.6318674,59.209943532943726,0.060148378598302396,1739137717.6318707,59.209943532943726,2.2553811248189324,1739137717.6318746,59.209943532943726,0.0,1739137717.631878,59.209943532943726,-0.02710738988554251,1739137717.6318812,59.209943532943726,3.1086420659742187,1739137717.6318848,59.209943532943726,2.282488514704475 +1739137717.6532516,59.22994351387024,15.611046377193585,1739137717.6532552,59.22994351387024,-0.023020884586597568,1739137717.6532595,59.22994351387024,96.97667747013737,1739137717.653265,59.22994351387024,7.503614474461628,1739137717.6532683,59.22994351387024,-0.013348728061537472,1739137717.6532722,59.22994351387024,3.1403996553565072,1739137717.6532757,59.22994351387024,0.25742939994291447,1739137717.653279,59.22994351387024,0.060148378598302396,1739137717.6532826,59.22994351387024,2.2553811248189324,1739137717.6532862,59.22994351387024,0.0,1739137717.6532896,59.22994351387024,-0.02710738988554251,1739137717.6532931,59.22994351387024,3.1086420659742187,1739137717.6532965,59.22994351387024,2.282488514704475 +1739137717.6699002,59.24994349479675,15.36023889166766,1739137717.6699026,59.24994349479675,-0.014852631708286879,1739137717.6699054,59.24994349479675,97.31151089515592,1739137717.669908,59.24994349479675,7.177208298276817,1739137717.6699092,59.24994349479675,-0.015196321637145791,1739137717.6699107,59.24994349479675,-3.141550653266718,1739137717.6699123,59.24994349479675,0.2627736646211678,1739137717.6699135,59.24994349479675,0.06026792972983733,1739137717.669915,59.24994349479675,2.25056493298125,1739137717.6699162,59.24994349479675,0.0,1739137717.6699173,59.24994349479675,-0.03094438457814137,1739137717.669919,59.24994349479675,3.1095171097335244,1739137717.6699202,59.24994349479675,2.2796821763168453 +1739137717.690004,59.26994347572327,15.36023889166766,1739137717.690008,59.26994347572327,-0.014852631708286879,1739137717.6900108,59.26994347572327,97.31151089515592,1739137717.6900136,59.26994347572327,7.177208298276817,1739137717.6900153,59.26994347572327,-0.015196321637145791,1739137717.690017,59.26994347572327,-3.141550653266718,1739137717.6900191,59.26994347572327,0.2627736646211678,1739137717.6900203,59.26994347572327,0.06026792972983733,1739137717.690022,59.26994347572327,2.25056493298125,1739137717.6900237,59.26994347572327,0.0,1739137717.6900249,59.26994347572327,-0.02911724333559551,1739137717.6900268,59.26994347572327,3.1095171097335244,1739137717.6900282,59.26994347572327,2.2796821763168453 +1739137717.7111793,59.28994345664978,15.36023889166766,1739137717.7111816,59.28994345664978,-0.014852631708286879,1739137717.7111847,59.28994345664978,97.31151089515592,1739137717.7111874,59.28994345664978,7.177208298276817,1739137717.711189,59.28994345664978,-0.015196321637145791,1739137717.7111907,59.28994345664978,-3.141550653266718,1739137717.7111921,59.28994345664978,0.2627736646211678,1739137717.7111936,59.28994345664978,0.06026792972983733,1739137717.7111952,59.28994345664978,2.25056493298125,1739137717.7111964,59.28994345664978,0.0,1739137717.7111979,59.28994345664978,-0.02911724333559551,1739137717.7111998,59.28994345664978,3.1095171097335244,1739137717.711201,59.28994345664978,2.2796821763168453 +1739137717.7298782,59.309943437576294,15.36023889166766,1739137717.7298813,59.309943437576294,-0.014852631708286879,1739137717.7298844,59.309943437576294,97.31151089515592,1739137717.7298872,59.309943437576294,7.177208298276817,1739137717.729889,59.309943437576294,-0.015196321637145791,1739137717.7298908,59.309943437576294,-3.141550653266718,1739137717.7298923,59.309943437576294,0.2627736646211678,1739137717.729894,59.309943437576294,0.06026792972983733,1739137717.729895,59.309943437576294,2.25056493298125,1739137717.729897,59.309943437576294,0.0,1739137717.7298982,59.309943437576294,-0.02911724333559551,1739137717.7299,59.309943437576294,3.1095171097335244,1739137717.7299013,59.309943437576294,2.2796821763168453 +1739137717.7505984,59.32994341850281,15.36023889166766,1739137717.7506015,59.32994341850281,-0.014852631708286879,1739137717.7506046,59.32994341850281,97.31151089515592,1739137717.7506073,59.32994341850281,7.177208298276817,1739137717.7506092,59.32994341850281,-0.015196321637145791,1739137717.7506113,59.32994341850281,-3.141550653266718,1739137717.7506127,59.32994341850281,0.2627736646211678,1739137717.7506142,59.32994341850281,0.06026792972983733,1739137717.7506156,59.32994341850281,2.25056493298125,1739137717.7506173,59.32994341850281,0.0,1739137717.7506187,59.32994341850281,-0.02911724333559551,1739137717.7506204,59.32994341850281,3.1095171097335244,1739137717.7506218,59.32994341850281,2.2796821763168453 +1739137717.7703307,59.34994339942932,15.109760075550696,1739137717.7703338,59.34994339942932,-0.006916181388902487,1739137717.770337,59.34994339942932,97.55353839130069,1739137717.7703397,59.34994339942932,6.944789703730737,1739137717.7703414,59.34994339942932,-0.016292820875175123,1739137717.7703435,59.34994339942932,-3.1404442556241854,1739137717.770345,59.34994339942932,0.2640212081451193,1739137717.7703464,59.34994339942932,0.06082200345203763,1739137717.770348,59.34994339942932,2.2494421420677067,1739137717.7703497,59.34994339942932,0.0,1739137717.7703514,59.34994339942932,-0.02514914658123114,1739137717.7703528,59.34994339942932,3.1103995911472513,1739137717.7703543,59.34994339942932,2.2764808594758916 +1739137717.78978,59.369943380355835,15.109760075550696,1739137717.789782,59.369943380355835,-0.006916181388902487,1739137717.7897851,59.369943380355835,97.55353839130069,1739137717.789788,59.369943380355835,6.944789703730737,1739137717.7897892,59.369943380355835,-0.016292820875175123,1739137717.7897909,59.369943380355835,-3.1404442556241854,1739137717.7897925,59.369943380355835,0.2640212081451193,1739137717.7897937,59.369943380355835,0.06082200345203763,1739137717.7897952,59.369943380355835,2.2494421420677067,1739137717.7897966,59.369943380355835,0.0,1739137717.7897983,59.369943380355835,-0.027038717408184976,1739137717.7897997,59.369943380355835,3.1103995911472513,1739137717.7898014,59.369943380355835,2.2764808594758916 +1739137717.8101847,59.38994336128235,15.109760075550696,1739137717.8101873,59.38994336128235,-0.006916181388902487,1739137717.81019,59.38994336128235,97.55353839130069,1739137717.8101928,59.38994336128235,6.944789703730737,1739137717.8101945,59.38994336128235,-0.016292820875175123,1739137717.8101962,59.38994336128235,-3.1404442556241854,1739137717.8101976,59.38994336128235,0.2640212081451193,1739137717.810199,59.38994336128235,0.06082200345203763,1739137717.8102002,59.38994336128235,2.2494421420677067,1739137717.810202,59.38994336128235,0.0,1739137717.810203,59.38994336128235,-0.027038717408184976,1739137717.8102047,59.38994336128235,3.1103995911472513,1739137717.810206,59.38994336128235,2.2764808594758916 +1739137717.8298726,59.40994334220886,15.109760075550696,1739137717.829875,59.40994334220886,-0.006916181388902487,1739137717.8298776,59.40994334220886,97.55353839130069,1739137717.8298802,59.40994334220886,6.944789703730737,1739137717.8298817,59.40994334220886,-0.016292820875175123,1739137717.8298833,59.40994334220886,-3.1404442556241854,1739137717.829885,59.40994334220886,0.2640212081451193,1739137717.8298862,59.40994334220886,0.06082200345203763,1739137717.8298874,59.40994334220886,2.2494421420677067,1739137717.829889,59.40994334220886,0.0,1739137717.8298903,59.40994334220886,-0.027038717408184976,1739137717.8298922,59.40994334220886,3.1103995911472513,1739137717.8298934,59.40994334220886,2.2764808594758916 +1739137717.8502965,59.429943323135376,15.109760075550696,1739137717.8502991,59.429943323135376,-0.006916181388902487,1739137717.850302,59.429943323135376,97.55353839130069,1739137717.8503048,59.429943323135376,6.944789703730737,1739137717.8503063,59.429943323135376,-0.016292820875175123,1739137717.8503082,59.429943323135376,-3.1404442556241854,1739137717.8503096,59.429943323135376,0.2640212081451193,1739137717.8503108,59.429943323135376,0.06082200345203763,1739137717.8503122,59.429943323135376,2.2494421420677067,1739137717.8503137,59.429943323135376,0.0,1739137717.850315,59.429943323135376,-0.027038717408184976,1739137717.8503168,59.429943323135376,3.1103995911472513,1739137717.8503182,59.429943323135376,2.2764808594758916 +1739137717.8703883,59.44994330406189,15.109760075550696,1739137717.8703918,59.44994330406189,-0.006916181388902487,1739137717.8703964,59.44994330406189,97.55353839130069,1739137717.8704019,59.44994330406189,6.944789703730737,1739137717.870405,59.44994330406189,-0.016292820875175123,1739137717.870409,59.44994330406189,-3.1404442556241854,1739137717.8704126,59.44994330406189,0.2640212081451193,1739137717.8704162,59.44994330406189,0.06082200345203763,1739137717.8704195,59.44994330406189,2.2494421420677067,1739137717.8704233,59.44994330406189,0.0,1739137717.8704267,59.44994330406189,-0.027038717408184976,1739137717.8704305,59.44994330406189,3.1103995911472513,1739137717.870434,59.44994330406189,2.2764808594758916 +1739137717.8901954,59.4699432849884,14.859610304591126,1739137717.8901978,59.4699432849884,0.000781252844781477,1739137717.8902009,59.4699432849884,97.64463335889428,1739137717.8902037,59.4699432849884,6.862466075573946,1739137717.8902051,59.4699432849884,-0.017041217494782313,1739137717.8902068,59.4699432849884,-3.139364052938972,1739137717.8902082,59.4699432849884,0.25958048662123245,1739137717.8902094,59.4699432849884,0.062334536952561574,1739137717.890211,59.4699432849884,2.2534413513459324,1739137717.8902125,59.4699432849884,0.0,1739137717.8902142,59.4699432849884,-0.01382426060958315,1739137717.8902154,59.4699432849884,3.111356484565363,1739137717.890217,59.4699432849884,2.2735582135744696 +1739137717.9103637,59.48994326591492,14.859610304591126,1739137717.910366,59.48994326591492,0.000781252844781477,1739137717.910369,59.48994326591492,97.64463335889428,1739137717.9103718,59.48994326591492,6.862466075573946,1739137717.9103732,59.48994326591492,-0.017041217494782313,1739137717.9103749,59.48994326591492,-3.139364052938972,1739137717.9103765,59.48994326591492,0.25958048662123245,1739137717.910378,59.48994326591492,0.062334536952561574,1739137717.9103792,59.48994326591492,2.2534413513459324,1739137717.9103808,59.48994326591492,0.0,1739137717.910382,59.48994326591492,-0.020116862228537258,1739137717.910384,59.48994326591492,3.111356484565363,1739137717.9103851,59.48994326591492,2.2735582135744696 +1739137717.9370825,59.50994324684143,14.859610304591126,1739137717.9370918,59.50994324684143,0.000781252844781477,1739137717.9371014,59.50994324684143,97.64463335889428,1739137717.9371111,59.50994324684143,6.862466075573946,1739137717.9371161,59.50994324684143,-0.017041217494782313,1739137717.937122,59.50994324684143,-3.139364052938972,1739137717.9371274,59.50994324684143,0.25958048662123245,1739137717.937132,59.50994324684143,0.062334536952561574,1739137717.9371364,59.50994324684143,2.2534413513459324,1739137717.9371417,59.50994324684143,0.0,1739137717.9371464,59.50994324684143,-0.020116862228537258,1739137717.9371517,59.50994324684143,3.111356484565363,1739137717.9371562,59.50994324684143,2.2735582135744696 +1739137717.9804819,59.54994320869446,14.859610304591126,1739137717.9804907,59.54994320869446,0.000781252844781477,1739137717.9805007,59.54994320869446,97.64463335889428,1739137717.980511,59.54994320869446,6.862466075573946,1739137717.9805155,59.54994320869446,-0.017041217494782313,1739137717.9805217,59.54994320869446,-3.139364052938972,1739137717.980527,59.54994320869446,0.25958048662123245,1739137717.9805315,59.54994320869446,0.062334536952561574,1739137717.9805365,59.54994320869446,2.2534413513459324,1739137717.9805417,59.54994320869446,0.0,1739137717.9805462,59.54994320869446,-0.020116862228537258,1739137717.9805517,59.54994320869446,3.111356484565363,1739137717.9805562,59.54994320869446,2.2735582135744696 +1739137718.0051162,59.57994318008423,14.609736167007085,1739137718.005121,59.57994318008423,0.00822918414645546,1739137718.0051262,59.57994318008423,97.92388721250883,1739137718.0051308,59.57994318008423,6.589657796597878,1739137718.0051332,59.57994318008423,-0.019,1739137718.0051355,59.57994318008423,-3.138197539693517,1739137718.0051384,59.57994318008423,0.26194640121746204,1739137718.0051405,59.57994318008423,0.06254296941785295,1739137718.0051425,59.57994318008423,2.251309780214112,1739137718.005145,59.57994318008423,0.0,1739137718.0051472,59.57994318008423,-0.020094499724745266,1739137718.0051503,59.57994318008423,3.1123208191839136,1739137718.0051527,59.57994318008423,2.2714149287555063 +1739137718.022931,59.59994316101074,14.609736167007085,1739137718.022934,59.59994316101074,0.00822918414645546,1739137718.0229373,59.59994316101074,97.92388721250883,1739137718.0229406,59.59994316101074,6.589657796597878,1739137718.0229423,59.59994316101074,-0.019,1739137718.022944,59.59994316101074,-3.138197539693517,1739137718.0229456,59.59994316101074,0.26194640121746204,1739137718.022947,59.59994316101074,0.06254296941785295,1739137718.0229485,59.59994316101074,2.251309780214112,1739137718.0229502,59.59994316101074,0.0,1739137718.0229516,59.59994316101074,-0.020105148541394335,1739137718.0229535,59.59994316101074,3.1123208191839136,1739137718.022955,59.59994316101074,2.2714149287555063 +1739137718.0429542,59.619943141937256,14.609736167007085,1739137718.0429564,59.619943141937256,0.00822918414645546,1739137718.0429585,59.619943141937256,97.92388721250883,1739137718.0429611,59.619943141937256,6.589657796597878,1739137718.0429626,59.619943141937256,-0.019,1739137718.0429637,59.619943141937256,-3.138197539693517,1739137718.042965,59.619943141937256,0.26194640121746204,1739137718.0429664,59.619943141937256,0.06254296941785295,1739137718.0429673,59.619943141937256,2.251309780214112,1739137718.0429685,59.619943141937256,0.0,1739137718.04297,59.619943141937256,-0.020105148541394335,1739137718.0429714,59.619943141937256,3.1123208191839136,1739137718.0429723,59.619943141937256,2.2714149287555063 +1739137718.0626264,59.63994312286377,14.609736167007085,1739137718.0626287,59.63994312286377,0.00822918414645546,1739137718.0626318,59.63994312286377,97.92388721250883,1739137718.0626345,59.63994312286377,6.589657796597878,1739137718.0626364,59.63994312286377,-0.019,1739137718.062638,59.63994312286377,-3.138197539693517,1739137718.0626397,59.63994312286377,0.26194640121746204,1739137718.062641,59.63994312286377,0.06254296941785295,1739137718.062642,59.63994312286377,2.251309780214112,1739137718.062644,59.63994312286377,0.0,1739137718.0626452,59.63994312286377,-0.020105148541394335,1739137718.0626469,59.63994312286377,3.1123208191839136,1739137718.062648,59.63994312286377,2.2714149287555063 +1739137718.0822034,59.65994310379028,14.609736167007085,1739137718.0822062,59.65994310379028,0.00822918414645546,1739137718.0822093,59.65994310379028,97.92388721250883,1739137718.0822122,59.65994310379028,6.589657796597878,1739137718.0822136,59.65994310379028,-0.019,1739137718.0822153,59.65994310379028,-3.138197539693517,1739137718.0822167,59.65994310379028,0.26194640121746204,1739137718.082218,59.65994310379028,0.06254296941785295,1739137718.0822194,59.65994310379028,2.251309780214112,1739137718.082221,59.65994310379028,0.0,1739137718.0822222,59.65994310379028,-0.020105148541394335,1739137718.0822237,59.65994310379028,3.1123208191839136,1739137718.0822248,59.65994310379028,2.2714149287555063 +1739137718.1023808,59.6799430847168,14.360094089810701,1739137718.1023839,59.6799430847168,0.01542451736538375,1739137718.1023867,59.6799430847168,98.160614977618,1739137718.1023896,59.6799430847168,6.359524088059363,1739137718.102391,59.6799430847168,-0.019652554740191085,1739137718.1023932,59.6799430847168,-3.137208360052362,1739137718.1023943,59.6799430847168,0.2610323603308988,1739137718.1023955,59.6799430847168,0.06262853632650497,1739137718.102397,59.6799430847168,2.2521330463797025,1739137718.1023984,59.6799430847168,0.0,1739137718.1023998,59.6799430847168,-0.014339160621257108,1739137718.1024013,59.6799430847168,3.113344749174987,1739137718.102403,59.6799430847168,2.2692179169059603 +1739137718.1224246,59.69994306564331,14.360094089810701,1739137718.122427,59.69994306564331,0.01542451736538375,1739137718.1224296,59.69994306564331,98.160614977618,1739137718.1224322,59.69994306564331,6.359524088059363,1739137718.1224334,59.69994306564331,-0.019652554740191085,1739137718.122435,59.69994306564331,-3.137208360052362,1739137718.1224368,59.69994306564331,0.2610323603308988,1739137718.1224382,59.69994306564331,0.06262853632650497,1739137718.1224394,59.69994306564331,2.2521330463797025,1739137718.122441,59.69994306564331,0.0,1739137718.1224422,59.69994306564331,-0.017084870526257845,1739137718.1224434,59.69994306564331,3.113344749174987,1739137718.1224449,59.69994306564331,2.2692179169059603 +1739137718.1438386,59.719943046569824,14.360094089810701,1739137718.1438422,59.719943046569824,0.01542451736538375,1739137718.143847,59.719943046569824,98.160614977618,1739137718.1438522,59.719943046569824,6.359524088059363,1739137718.143855,59.719943046569824,-0.019652554740191085,1739137718.1438587,59.719943046569824,-3.137208360052362,1739137718.1438618,59.719943046569824,0.2610323603308988,1739137718.143865,59.719943046569824,0.06262853632650497,1739137718.1438684,59.719943046569824,2.2521330463797025,1739137718.1438718,59.719943046569824,0.0,1739137718.1438751,59.719943046569824,-0.017084870526257845,1739137718.1438787,59.719943046569824,3.113344749174987,1739137718.143882,59.719943046569824,2.2692179169059603 +1739137718.1635928,59.73994302749634,14.360094089810701,1739137718.163596,59.73994302749634,0.01542451736538375,1739137718.1636004,59.73994302749634,98.160614977618,1739137718.1636057,59.73994302749634,6.359524088059363,1739137718.1636086,59.73994302749634,-0.019652554740191085,1739137718.1636124,59.73994302749634,-3.137208360052362,1739137718.1636157,59.73994302749634,0.2610323603308988,1739137718.163635,59.73994302749634,0.06262853632650497,1739137718.1636384,59.73994302749634,2.2521330463797025,1739137718.1636417,59.73994302749634,0.0,1739137718.163645,59.73994302749634,-0.017084870526257845,1739137718.1636484,59.73994302749634,3.113344749174987,1739137718.1636515,59.73994302749634,2.2692179169059603 +1739137718.1836662,59.75994300842285,14.360094089810701,1739137718.1836696,59.75994300842285,0.01542451736538375,1739137718.1836736,59.75994300842285,98.160614977618,1739137718.1836786,59.75994300842285,6.359524088059363,1739137718.1836815,59.75994300842285,-0.019652554740191085,1739137718.1836853,59.75994300842285,-3.137208360052362,1739137718.1836884,59.75994300842285,0.2610323603308988,1739137718.183692,59.75994300842285,0.06262853632650497,1739137718.1836953,59.75994300842285,2.2521330463797025,1739137718.1836987,59.75994300842285,0.0,1739137718.183702,59.75994300842285,-0.017084870526257845,1739137718.1837056,59.75994300842285,3.113344749174987,1739137718.183709,59.75994300842285,2.2692179169059603 +1739137718.2037401,59.779942989349365,14.360094089810701,1739137718.2037435,59.779942989349365,0.01542451736538375,1739137718.2037477,59.779942989349365,98.160614977618,1739137718.203753,59.779942989349365,6.359524088059363,1739137718.2037559,59.779942989349365,-0.019652554740191085,1739137718.2037594,59.779942989349365,-3.137208360052362,1739137718.2037628,59.779942989349365,0.2610323603308988,1739137718.203766,59.779942989349365,0.06262853632650497,1739137718.2037694,59.779942989349365,2.2521330463797025,1739137718.2037728,59.779942989349365,0.0,1739137718.203776,59.779942989349365,-0.017084870526257845,1739137718.2037797,59.779942989349365,3.113344749174987,1739137718.2037828,59.779942989349365,2.2692179169059603 +1739137718.2253604,59.79994297027588,14.110662668604988,1739137718.2253654,59.79994297027588,0.022353606152676342,1739137718.2253716,59.79994297027588,98.33321627212263,1739137718.225379,59.79994297027588,6.192295186549423,1739137718.2253833,59.79994297027588,-0.021,1739137718.2253883,59.79994297027588,-3.1361176395715598,1739137718.225393,59.79994297027588,0.25870347837388946,1739137718.2253978,59.79994297027588,0.0633642897064291,1739137718.2254026,59.79994297027588,2.2542320046797366,1739137718.2254071,59.79994297027588,0.0,1739137718.2254121,59.79994297027588,-0.00966291203856286,1739137718.225417,59.79994297027588,3.1143910274307567,1739137718.225422,59.79994297027588,2.267429184430342 +1739137718.2438233,59.81994295120239,14.110662668604988,1739137718.2438278,59.81994295120239,0.022353606152676342,1739137718.2438328,59.81994295120239,98.33321627212263,1739137718.2438369,59.81994295120239,6.192295186549423,1739137718.2438388,59.81994295120239,-0.021,1739137718.243841,59.81994295120239,-3.1361176395715598,1739137718.243843,59.81994295120239,0.25870347837388946,1739137718.2438452,59.81994295120239,0.0633642897064291,1739137718.2438478,59.81994295120239,2.2542320046797366,1739137718.243851,59.81994295120239,0.0,1739137718.2438529,59.81994295120239,-0.013197179750605414,1739137718.2438571,59.81994295120239,3.1143910274307567,1739137718.2438612,59.81994295120239,2.267429184430342 +1739137718.262642,59.839942932128906,14.110662668604988,1739137718.2626448,59.839942932128906,0.022353606152676342,1739137718.262648,59.839942932128906,98.33321627212263,1739137718.262651,59.839942932128906,6.192295186549423,1739137718.2626526,59.839942932128906,-0.021,1739137718.2626543,59.839942932128906,-3.1361176395715598,1739137718.2626557,59.839942932128906,0.25870347837388946,1739137718.262657,59.839942932128906,0.0633642897064291,1739137718.2626584,59.839942932128906,2.2542320046797366,1739137718.2626595,59.839942932128906,0.0,1739137718.262661,59.839942932128906,-0.013197179750605414,1739137718.2626622,59.839942932128906,3.1143910274307567,1739137718.2626634,59.839942932128906,2.267429184430342 +1739137718.2826018,59.85994291305542,14.110662668604988,1739137718.2826042,59.85994291305542,0.022353606152676342,1739137718.282607,59.85994291305542,98.33321627212263,1739137718.28261,59.85994291305542,6.192295186549423,1739137718.2826111,59.85994291305542,-0.021,1739137718.2826128,59.85994291305542,-3.1361176395715598,1739137718.282614,59.85994291305542,0.25870347837388946,1739137718.2826157,59.85994291305542,0.0633642897064291,1739137718.2826166,59.85994291305542,2.2542320046797366,1739137718.282618,59.85994291305542,0.0,1739137718.2826195,59.85994291305542,-0.013197179750605414,1739137718.282621,59.85994291305542,3.1143910274307567,1739137718.282622,59.85994291305542,2.267429184430342 +1739137718.3023047,59.879942893981934,14.110662668604988,1739137718.302307,59.879942893981934,0.022353606152676342,1739137718.3023093,59.879942893981934,98.33321627212263,1739137718.3023117,59.879942893981934,6.192295186549423,1739137718.3023129,59.879942893981934,-0.021,1739137718.3023145,59.879942893981934,-3.1361176395715598,1739137718.3023157,59.879942893981934,0.25870347837388946,1739137718.3023171,59.879942893981934,0.0633642897064291,1739137718.3023183,59.879942893981934,2.2542320046797366,1739137718.3023195,59.879942893981934,0.0,1739137718.302321,59.879942893981934,-0.013197179750605414,1739137718.3023221,59.879942893981934,3.1143910274307567,1739137718.3023233,59.879942893981934,2.267429184430342 +1739137718.330517,59.89994287490845,13.86140460839794,1739137718.330595,59.89994287490845,0.029016888105020122,1739137718.3306248,59.89994287490845,98.6366463364247,1739137718.3306873,59.89994287490845,5.893104230627064,1739137718.3307052,59.89994287490845,-0.022,1739137718.3307242,59.89994287490845,-3.1351902605306843,1739137718.3307343,59.89994287490845,0.2593893453986034,1739137718.3307512,59.89994287490845,0.06273802378523585,1739137718.3307679,59.89994287490845,2.25361364814646,1739137718.3307855,59.89994287490845,0.0,1739137718.3307958,59.89994287490845,-0.011683009540573124,1739137718.330806,59.89994287490845,3.1154373056865263,1739137718.3308153,59.89994287490845,2.26601769148057 +1739137718.3474846,59.91994285583496,13.86140460839794,1739137718.3474903,59.91994285583496,0.029016888105020122,1739137718.3474972,59.91994285583496,98.6366463364247,1739137718.3475044,59.91994285583496,5.893104230627064,1739137718.347508,59.91994285583496,-0.022,1739137718.3475122,59.91994285583496,-3.1351902605306843,1739137718.3475163,59.91994285583496,0.2593893453986034,1739137718.34752,59.91994285583496,0.06273802378523585,1739137718.347524,59.91994285583496,2.25361364814646,1739137718.347528,59.91994285583496,0.0,1739137718.3475318,59.91994285583496,-0.012404043334109716,1739137718.3475356,59.91994285583496,3.1154373056865263,1739137718.3475392,59.91994285583496,2.26601769148057 +1739137718.3646808,59.94994282722473,13.86140460839794,1739137718.3646839,59.94994282722473,0.029016888105020122,1739137718.3646874,59.94994282722473,98.6366463364247,1739137718.364691,59.94994282722473,5.893104230627064,1739137718.3646924,59.94994282722473,-0.022,1739137718.3646948,59.94994282722473,-3.1351902605306843,1739137718.3646965,59.94994282722473,0.2593893453986034,1739137718.3646986,59.94994282722473,0.06273802378523585,1739137718.3647,59.94994282722473,2.25361364814646,1739137718.3647022,59.94994282722473,0.0,1739137718.364704,59.94994282722473,-0.012404043334109716,1739137718.364706,59.94994282722473,3.1154373056865263,1739137718.3647075,59.94994282722473,2.26601769148057 +1739137718.3842885,59.969942808151245,13.86140460839794,1739137718.3842916,59.969942808151245,0.029016888105020122,1739137718.3842955,59.969942808151245,98.6366463364247,1739137718.384299,59.969942808151245,5.893104230627064,1739137718.3843007,59.969942808151245,-0.022,1739137718.3843033,59.969942808151245,-3.1351902605306843,1739137718.3843052,59.969942808151245,0.2593893453986034,1739137718.384307,59.969942808151245,0.06273802378523585,1739137718.3843088,59.969942808151245,2.25361364814646,1739137718.3843107,59.969942808151245,0.0,1739137718.3843126,59.969942808151245,-0.012404043334109716,1739137718.3843148,59.969942808151245,3.1154373056865263,1739137718.3843164,59.969942808151245,2.26601769148057 +1739137718.4043424,59.98994278907776,13.86140460839794,1739137718.4043465,59.98994278907776,0.029016888105020122,1739137718.4043505,59.98994278907776,98.6366463364247,1739137718.404354,59.98994278907776,5.893104230627064,1739137718.4043558,59.98994278907776,-0.022,1739137718.4043581,59.98994278907776,-3.1351902605306843,1739137718.4043605,59.98994278907776,0.2593893453986034,1739137718.4043622,59.98994278907776,0.06273802378523585,1739137718.4043639,59.98994278907776,2.25361364814646,1739137718.404366,59.98994278907776,0.0,1739137718.4043677,59.98994278907776,-0.012404043334109716,1739137718.4043696,59.98994278907776,3.1154373056865263,1739137718.4043715,59.98994278907776,2.26601769148057 +1739137718.4247491,60.00994277000427,13.612292297041844,1739137718.4247527,60.00994277000427,0.035415453572944955,1739137718.4247563,60.00994277000427,98.87419358916472,1739137718.42476,60.00994277000427,5.659612234464175,1739137718.4247618,60.00994277000427,-0.023,1739137718.4247642,60.00994277000427,-3.1342474061319368,1739137718.424766,60.00994277000427,0.258060455966931,1739137718.4247677,60.00994277000427,0.06266125073481671,1739137718.4247692,60.00994277000427,2.2548118879279206,1739137718.4247718,60.00994277000427,0.0,1739137718.4247735,60.00994277000427,-0.007538876277663743,1739137718.4247754,60.00994277000427,3.116483583942296,1739137718.4247773,60.00994277000427,2.264667511580256 +1739137718.4444044,60.029942750930786,13.612292297041844,1739137718.4444082,60.029942750930786,0.035415453572944955,1739137718.4444122,60.029942750930786,98.87419358916472,1739137718.444416,60.029942750930786,5.659612234464175,1739137718.4444182,60.029942750930786,-0.023,1739137718.4444213,60.029942750930786,-3.1342474061319368,1739137718.4444234,60.029942750930786,0.258060455966931,1739137718.444425,60.029942750930786,0.06266125073481671,1739137718.4444273,60.029942750930786,2.2548118879279206,1739137718.4444294,60.029942750930786,0.0,1739137718.444431,60.029942750930786,-0.009855623652335499,1739137718.4444332,60.029942750930786,3.116483583942296,1739137718.4444346,60.029942750930786,2.264667511580256 +1739137718.4641128,60.0499427318573,13.612292297041844,1739137718.4641156,60.0499427318573,0.035415453572944955,1739137718.4641192,60.0499427318573,98.87419358916472,1739137718.4641232,60.0499427318573,5.659612234464175,1739137718.464125,60.0499427318573,-0.023,1739137718.4641273,60.0499427318573,-3.1342474061319368,1739137718.464129,60.0499427318573,0.258060455966931,1739137718.4641306,60.0499427318573,0.06266125073481671,1739137718.464132,60.0499427318573,2.2548118879279206,1739137718.4641342,60.0499427318573,0.0,1739137718.464136,60.0499427318573,-0.009855623652335499,1739137718.464138,60.0499427318573,3.116483583942296,1739137718.4641395,60.0499427318573,2.264667511580256 +1739137718.484051,60.06994271278381,13.612292297041844,1739137718.484054,60.06994271278381,0.035415453572944955,1739137718.4840574,60.06994271278381,98.87419358916472,1739137718.4840605,60.06994271278381,5.659612234464175,1739137718.484062,60.06994271278381,-0.023,1739137718.484064,60.06994271278381,-3.1342474061319368,1739137718.4840658,60.06994271278381,0.258060455966931,1739137718.4840674,60.06994271278381,0.06266125073481671,1739137718.4840689,60.06994271278381,2.2548118879279206,1739137718.4840705,60.06994271278381,0.0,1739137718.4840724,60.06994271278381,-0.009855623652335499,1739137718.4840744,60.06994271278381,3.116483583942296,1739137718.4840755,60.06994271278381,2.264667511580256 +1739137718.5041187,60.08994269371033,13.612292297041844,1739137718.504122,60.08994269371033,0.035415453572944955,1739137718.5041265,60.08994269371033,98.87419358916472,1739137718.5041296,60.08994269371033,5.659612234464175,1739137718.5041313,60.08994269371033,-0.023,1739137718.5041337,60.08994269371033,-3.1342474061319368,1739137718.5041354,60.08994269371033,0.258060455966931,1739137718.504137,60.08994269371033,0.06266125073481671,1739137718.5041387,60.08994269371033,2.2548118879279206,1739137718.5041406,60.08994269371033,0.0,1739137718.504142,60.08994269371033,-0.009855623652335499,1739137718.5041442,60.08994269371033,3.116483583942296,1739137718.5041454,60.08994269371033,2.264667511580256 +1739137718.5239515,60.10994267463684,13.612292297041844,1739137718.523955,60.10994267463684,0.035415453572944955,1739137718.5239613,60.10994267463684,98.87419358916472,1739137718.5239685,60.10994267463684,5.659612234464175,1739137718.5239716,60.10994267463684,-0.023,1739137718.5239775,60.10994267463684,-3.1342474061319368,1739137718.5239823,60.10994267463684,0.258060455966931,1739137718.5239847,60.10994267463684,0.06266125073481671,1739137718.523986,60.10994267463684,2.2548118879279206,1739137718.5239885,60.10994267463684,0.0,1739137718.52399,60.10994267463684,-0.009855623652335499,1739137718.5239918,60.10994267463684,3.116483583942296,1739137718.523993,60.10994267463684,2.264667511580256 +1739137718.543947,60.129942655563354,13.363304112778163,1739137718.5439525,60.129942655563354,0.04155015205450496,1739137718.5439577,60.129942655563354,99.11269289079505,1739137718.543962,60.129942655563354,5.424212085882432,1739137718.5439649,60.129942655563354,-0.023,1739137718.5439677,60.129942655563354,-3.1334621609000917,1739137718.543971,60.129942655563354,0.25554974531125335,1739137718.5439746,60.129942655563354,0.062263556331607864,1739137718.5439787,60.129942655563354,2.2570774974889396,1739137718.5439835,60.129942655563354,0.0,1739137718.5439878,60.129942655563354,-0.0035581778723372515,1739137718.5439906,60.129942655563354,3.1175298621980656,1739137718.543993,60.129942655563354,2.263634460564062 +1739137718.5638611,60.14994263648987,13.363304112778163,1739137718.563867,60.14994263648987,0.04155015205450496,1739137718.5638726,60.14994263648987,99.11269289079505,1739137718.563879,60.14994263648987,5.424212085882432,1739137718.5638824,60.14994263648987,-0.023,1739137718.5638866,60.14994263648987,-3.1334621609000917,1739137718.5638907,60.14994263648987,0.25554974531125335,1739137718.5638947,60.14994263648987,0.062263556331607864,1739137718.5638988,60.14994263648987,2.2570774974889396,1739137718.5639043,60.14994263648987,0.0,1739137718.5639079,60.14994263648987,-0.006556963075122546,1739137718.5639129,60.14994263648987,3.1175298621980656,1739137718.5639157,60.14994263648987,2.263634460564062 +1739137718.5840602,60.16994261741638,13.363304112778163,1739137718.5840652,60.16994261741638,0.04155015205450496,1739137718.584072,60.16994261741638,99.11269289079505,1739137718.5840795,60.16994261741638,5.424212085882432,1739137718.5840845,60.16994261741638,-0.023,1739137718.5840907,60.16994261741638,-3.1334621609000917,1739137718.5840957,60.16994261741638,0.25554974531125335,1739137718.5840974,60.16994261741638,0.062263556331607864,1739137718.5840988,60.16994261741638,2.2570774974889396,1739137718.584101,60.16994261741638,0.0,1739137718.5841024,60.16994261741638,-0.006556963075122546,1739137718.5841043,60.16994261741638,3.1175298621980656,1739137718.5841057,60.16994261741638,2.263634460564062 +1739137718.6036375,60.189942598342896,13.363304112778163,1739137718.60364,60.189942598342896,0.04155015205450496,1739137718.603643,60.189942598342896,99.11269289079505,1739137718.6036453,60.189942598342896,5.424212085882432,1739137718.6036472,60.189942598342896,-0.023,1739137718.6036522,60.189942598342896,-3.1334621609000917,1739137718.6036549,60.189942598342896,0.25554974531125335,1739137718.6036565,60.189942598342896,0.062263556331607864,1739137718.6036577,60.189942598342896,2.2570774974889396,1739137718.6036606,60.189942598342896,0.0,1739137718.6036632,60.189942598342896,-0.006556963075122546,1739137718.6036646,60.189942598342896,3.1175298621980656,1739137718.603666,60.189942598342896,2.263634460564062 +1739137718.6234107,60.20994257926941,13.363304112778163,1739137718.6234133,60.20994257926941,0.04155015205450496,1739137718.623416,60.20994257926941,99.11269289079505,1739137718.6234186,60.20994257926941,5.424212085882432,1739137718.6234202,60.20994257926941,-0.023,1739137718.6234221,60.20994257926941,-3.1334621609000917,1739137718.6234238,60.20994257926941,0.25554974531125335,1739137718.623425,60.20994257926941,0.062263556331607864,1739137718.6234262,60.20994257926941,2.2570774974889396,1739137718.6234279,60.20994257926941,0.0,1739137718.623429,60.20994257926941,-0.006556963075122546,1739137718.6234307,60.20994257926941,3.1175298621980656,1739137718.623432,60.20994257926941,2.263634460564062 +1739137718.6436434,60.22994256019592,13.114407654438786,1739137718.6436458,60.22994256019592,0.047422020554623856,1739137718.6436481,60.22994256019592,99.45421021420393,1739137718.643651,60.22994256019592,5.0847709273018085,1739137718.6436524,60.22994256019592,-0.024,1739137718.643654,60.22994256019592,-3.1326980871860854,1739137718.6436558,60.22994256019592,0.2562010249072809,1739137718.643657,60.22994256019592,0.061021941791398776,1739137718.6436598,60.22994256019592,2.2564895786638646,1739137718.6436617,60.22994256019592,0.0,1739137718.643665,60.22994256019592,-0.006361991047783996,1739137718.6436677,60.22994256019592,3.1185761404538352,1739137718.6436698,60.22994256019592,2.2629444135805703 +1739137718.663418,60.24994254112244,13.114407654438786,1739137718.6634204,60.24994254112244,0.047422020554623856,1739137718.6634233,60.24994254112244,99.45421021420393,1739137718.6634257,60.24994254112244,5.0847709273018085,1739137718.6634274,60.24994254112244,-0.024,1739137718.663429,60.24994254112244,-3.1326980871860854,1739137718.6634305,60.24994254112244,0.2562010249072809,1739137718.663432,60.24994254112244,0.061021941791398776,1739137718.6634333,60.24994254112244,2.2564895786638646,1739137718.6634347,60.24994254112244,0.0,1739137718.6634362,60.24994254112244,-0.006454834916705732,1739137718.6634378,60.24994254112244,3.1185761404538352,1739137718.663439,60.24994254112244,2.2629444135805703 +1739137718.685103,60.26994252204895,13.114407654438786,1739137718.685108,60.26994252204895,0.047422020554623856,1739137718.6851149,60.26994252204895,99.45421021420393,1739137718.6851218,60.26994252204895,5.0847709273018085,1739137718.685126,60.26994252204895,-0.024,1739137718.6851306,60.26994252204895,-3.1326980871860854,1739137718.6851342,60.26994252204895,0.2562010249072809,1739137718.6851375,60.26994252204895,0.061021941791398776,1739137718.685141,60.26994252204895,2.2564895786638646,1739137718.6851451,60.26994252204895,0.0,1739137718.6851485,60.26994252204895,-0.006454834916705732,1739137718.6851523,60.26994252204895,3.1185761404538352,1739137718.6851556,60.26994252204895,2.2629444135805703 +1739137718.7034473,60.289942502975464,13.114407654438786,1739137718.70345,60.289942502975464,0.047422020554623856,1739137718.7034523,60.289942502975464,99.45421021420393,1739137718.7034552,60.289942502975464,5.0847709273018085,1739137718.7034564,60.289942502975464,-0.024,1739137718.7034583,60.289942502975464,-3.1326980871860854,1739137718.7034597,60.289942502975464,0.2562010249072809,1739137718.7034612,60.289942502975464,0.061021941791398776,1739137718.7034624,60.289942502975464,2.2564895786638646,1739137718.703464,60.289942502975464,0.0,1739137718.7034652,60.289942502975464,-0.006454834916705732,1739137718.7034667,60.289942502975464,3.1185761404538352,1739137718.703468,60.289942502975464,2.2629444135805703 +1739137718.7236533,60.30994248390198,13.114407654438786,1739137718.7236564,60.30994248390198,0.047422020554623856,1739137718.7236595,60.30994248390198,99.45421021420393,1739137718.7236626,60.30994248390198,5.0847709273018085,1739137718.723664,60.30994248390198,-0.024,1739137718.723666,60.30994248390198,-3.1326980871860854,1739137718.7236674,60.30994248390198,0.2562010249072809,1739137718.723669,60.30994248390198,0.061021941791398776,1739137718.7236707,60.30994248390198,2.2564895786638646,1739137718.7236724,60.30994248390198,0.0,1739137718.7236738,60.30994248390198,-0.006454834916705732,1739137718.7236755,60.30994248390198,3.1185761404538352,1739137718.723677,60.30994248390198,2.2629444135805703 +1739137718.7435231,60.32994246482849,13.114407654438786,1739137718.7435257,60.32994246482849,0.047422020554623856,1739137718.7435286,60.32994246482849,99.45421021420393,1739137718.7435317,60.32994246482849,5.0847709273018085,1739137718.7435336,60.32994246482849,-0.024,1739137718.7435353,60.32994246482849,-3.1326980871860854,1739137718.743537,60.32994246482849,0.2562010249072809,1739137718.7435384,60.32994246482849,0.061021941791398776,1739137718.7435398,60.32994246482849,2.2564895786638646,1739137718.7435415,60.32994246482849,0.0,1739137718.7435431,60.32994246482849,-0.006454834916705732,1739137718.7435446,60.32994246482849,3.1185761404538352,1739137718.743546,60.32994246482849,2.2629444135805703 +1739137718.7637165,60.349942445755005,12.865582231689675,1739137718.7637208,60.349942445755005,0.05303173434803021,1739137718.763727,60.349942445755005,99.5182483703066,1739137718.7637346,60.349942445755005,5.022847230182308,1739137718.7637386,60.349942445755005,-0.024,1739137718.7637446,60.349942445755005,-3.1317709195487478,1739137718.7637498,60.349942445755005,0.2493060124213135,1739137718.7637537,60.349942445755005,0.062242162047429064,1739137718.7637575,60.349942445755005,2.2627215781841468,1739137718.7637615,60.349942445755005,0.0,1739137718.7637653,60.349942445755005,0.006788189534465883,1739137718.7637691,60.349942445755005,3.119622418709605,1739137718.763773,60.349942445755005,2.2622395939195115 +1739137718.7839544,60.36994242668152,12.865582231689675,1739137718.7839587,60.36994242668152,0.05303173434803021,1739137718.7839646,60.36994242668152,99.5182483703066,1739137718.7839708,60.36994242668152,5.022847230182308,1739137718.7839742,60.36994242668152,-0.024,1739137718.7839782,60.36994242668152,-3.1317709195487478,1739137718.783982,60.36994242668152,0.2493060124213135,1739137718.783986,60.36994242668152,0.062242162047429064,1739137718.78399,60.36994242668152,2.2627215781841468,1739137718.7839942,60.36994242668152,0.0,1739137718.783998,60.36994242668152,0.0004819842646353045,1739137718.784002,60.36994242668152,3.119622418709605,1739137718.784006,60.36994242668152,2.2622395939195115 +1739137718.8035889,60.38994240760803,12.865582231689675,1739137718.8035915,60.38994240760803,0.05303173434803021,1739137718.8035946,60.38994240760803,99.5182483703066,1739137718.8035975,60.38994240760803,5.022847230182308,1739137718.803599,60.38994240760803,-0.024,1739137718.8036008,60.38994240760803,-3.1317709195487478,1739137718.8036027,60.38994240760803,0.2493060124213135,1739137718.803604,60.38994240760803,0.062242162047429064,1739137718.8036056,60.38994240760803,2.2627215781841468,1739137718.803607,60.38994240760803,0.0,1739137718.803609,60.38994240760803,0.0004819842646353045,1739137718.8036106,60.38994240760803,3.119622418709605,1739137718.8036122,60.38994240760803,2.2622395939195115 +1739137718.8236399,60.409942388534546,12.865582231689675,1739137718.8236423,60.409942388534546,0.05303173434803021,1739137718.8236454,60.409942388534546,99.5182483703066,1739137718.8236482,60.409942388534546,5.022847230182308,1739137718.82365,60.409942388534546,-0.024,1739137718.8236518,60.409942388534546,-3.1317709195487478,1739137718.8236535,60.409942388534546,0.2493060124213135,1739137718.823655,60.409942388534546,0.062242162047429064,1739137718.823656,60.409942388534546,2.2627215781841468,1739137718.823658,60.409942388534546,0.0,1739137718.8236592,60.409942388534546,0.0004819842646353045,1739137718.823661,60.409942388534546,3.119622418709605,1739137718.8236623,60.409942388534546,2.2622395939195115 +1739137718.8436992,60.42994236946106,12.865582231689675,1739137718.8437018,60.42994236946106,0.05303173434803021,1739137718.8437045,60.42994236946106,99.5182483703066,1739137718.8437076,60.42994236946106,5.022847230182308,1739137718.8437095,60.42994236946106,-0.024,1739137718.8437119,60.42994236946106,-3.1317709195487478,1739137718.8437142,60.42994236946106,0.2493060124213135,1739137718.8437164,60.42994236946106,0.062242162047429064,1739137718.8437176,60.42994236946106,2.2627215781841468,1739137718.8437207,60.42994236946106,0.0,1739137718.843723,60.42994236946106,0.0004819842646353045,1739137718.8437257,60.42994236946106,3.119622418709605,1739137718.8437274,60.42994236946106,2.2622395939195115 +1739137718.8636503,60.44994235038757,12.6167868876548,1739137718.8636527,60.44994235038757,0.058380326461811904,1739137718.8636556,60.44994235038757,99.90706262341439,1739137718.8636587,60.44994235038757,4.633708347792392,1739137718.86366,60.44994235038757,-0.025,1739137718.8636618,60.44994235038757,-3.1311484002547814,1739137718.8636634,60.44994235038757,0.25038747553076574,1739137718.8636649,60.44994235038757,0.0603333002297329,1739137718.863666,60.44994235038757,2.261742969899652,1739137718.863668,60.44994235038757,0.0,1739137718.8636692,60.44994235038757,-0.0015959402000214954,1739137718.8636708,60.44994235038757,3.1206686969653745,1739137718.8636723,60.44994235038757,2.262349421765068 +1739137718.8836377,60.46994233131409,12.6167868876548,1739137718.8836403,60.46994233131409,0.058380326461811904,1739137718.8836436,60.46994233131409,99.90706262341439,1739137718.8836467,60.46994233131409,4.633708347792392,1739137718.8836482,60.46994233131409,-0.025,1739137718.88365,60.46994233131409,-3.1311484002547814,1739137718.8836517,60.46994233131409,0.25038747553076574,1739137718.8836532,60.46994233131409,0.0603333002297329,1739137718.8836546,60.46994233131409,2.261742969899652,1739137718.8836565,60.46994233131409,0.0,1739137718.8836577,60.46994233131409,-0.00060645186541608,1739137718.8836594,60.46994233131409,3.1206686969653745,1739137718.8836608,60.46994233131409,2.262349421765068 +1739137718.9036632,60.4899423122406,12.6167868876548,1739137718.9036658,60.4899423122406,0.058380326461811904,1739137718.9036694,60.4899423122406,99.90706262341439,1739137718.903672,60.4899423122406,4.633708347792392,1739137718.9036736,60.4899423122406,-0.025,1739137718.9036753,60.4899423122406,-3.1311484002547814,1739137718.903677,60.4899423122406,0.25038747553076574,1739137718.9036784,60.4899423122406,0.0603333002297329,1739137718.9036798,60.4899423122406,2.261742969899652,1739137718.9036815,60.4899423122406,0.0,1739137718.9036832,60.4899423122406,-0.00060645186541608,1739137718.9036849,60.4899423122406,3.1206686969653745,1739137718.9036863,60.4899423122406,2.262349421765068 +1739137718.9236894,60.509942293167114,12.6167868876548,1739137718.9236917,60.509942293167114,0.058380326461811904,1739137718.9236946,60.509942293167114,99.90706262341439,1739137718.9236977,60.509942293167114,4.633708347792392,1739137718.9236991,60.509942293167114,-0.025,1739137718.923701,60.509942293167114,-3.1311484002547814,1739137718.9237025,60.509942293167114,0.25038747553076574,1739137718.9237041,60.509942293167114,0.0603333002297329,1739137718.9237053,60.509942293167114,2.261742969899652,1739137718.9237068,60.509942293167114,0.0,1739137718.9237084,60.509942293167114,-0.00060645186541608,1739137718.92371,60.509942293167114,3.1206686969653745,1739137718.9237115,60.509942293167114,2.262349421765068 +1739137718.9440145,60.52994227409363,12.6167868876548,1739137718.9440212,60.52994227409363,0.058380326461811904,1739137718.9440281,60.52994227409363,99.90706262341439,1739137718.9440362,60.52994227409363,4.633708347792392,1739137718.9440396,60.52994227409363,-0.025,1739137718.9440455,60.52994227409363,-3.1311484002547814,1739137718.9440498,60.52994227409363,0.25038747553076574,1739137718.9440541,60.52994227409363,0.0603333002297329,1739137718.9440584,60.52994227409363,2.261742969899652,1739137718.9440613,60.52994227409363,0.0,1739137718.9440649,60.52994227409363,-0.00060645186541608,1739137718.9440684,60.52994227409363,3.1206686969653745,1739137718.9440708,60.52994227409363,2.262349421765068 +1739137718.9636304,60.54994225502014,12.6167868876548,1739137718.9636328,60.54994225502014,0.058380326461811904,1739137718.963636,60.54994225502014,99.90706262341439,1739137718.963639,60.54994225502014,4.633708347792392,1739137718.9636407,60.54994225502014,-0.025,1739137718.9636424,60.54994225502014,-3.1311484002547814,1739137718.9636443,60.54994225502014,0.25038747553076574,1739137718.9636455,60.54994225502014,0.0603333002297329,1739137718.963647,60.54994225502014,2.261742969899652,1739137718.9636486,60.54994225502014,0.0,1739137718.96365,60.54994225502014,-0.00060645186541608,1739137718.9636517,60.54994225502014,3.1206686969653745,1739137718.963653,60.54994225502014,2.262349421765068 +1739137718.9838645,60.569942235946655,12.367985686359667,1739137718.9838674,60.569942235946655,0.06346861685623129,1739137718.9838707,60.569942235946655,100.26906455328971,1739137718.9838736,60.569942235946655,4.27196919274722,1739137718.983875,60.569942235946655,-0.026,1739137718.983877,60.569942235946655,-3.1305421604089987,1739137718.9838784,60.569942235946655,0.2503703562271551,1739137718.98388,60.569942235946655,0.058657421995715456,1739137718.9838812,60.569942235946655,2.261758457738517,1739137718.983883,60.569942235946655,0.0,1739137718.9838843,60.569942235946655,-0.00041269397291268434,1739137718.983886,60.569942235946655,3.121714975221144,1739137718.9838874,60.569942235946655,2.262263417420617 +1739137719.0038576,60.58994221687317,12.367985686359667,1739137719.0038605,60.58994221687317,0.06346861685623129,1739137719.003864,60.58994221687317,100.26906455328971,1739137719.0038676,60.58994221687317,4.27196919274722,1739137719.00387,60.58994221687317,-0.026,1739137719.003872,60.58994221687317,-3.1305421604089987,1739137719.0038736,60.58994221687317,0.2503703562271551,1739137719.003875,60.58994221687317,0.058657421995715456,1739137719.0038767,60.58994221687317,2.261758457738517,1739137719.0038786,60.58994221687317,0.0,1739137719.00388,60.58994221687317,-0.0005049596821002922,1739137719.0038817,60.58994221687317,3.121714975221144,1739137719.0038834,60.58994221687317,2.262263417420617 +1739137719.0235755,60.60994219779968,12.367985686359667,1739137719.0235784,60.60994219779968,0.06346861685623129,1739137719.0235815,60.60994219779968,100.26906455328971,1739137719.0235844,60.60994219779968,4.27196919274722,1739137719.023586,60.60994219779968,-0.026,1739137719.023588,60.60994219779968,-3.1305421604089987,1739137719.0235894,60.60994219779968,0.2503703562271551,1739137719.0235908,60.60994219779968,0.058657421995715456,1739137719.0235922,60.60994219779968,2.261758457738517,1739137719.023594,60.60994219779968,0.0,1739137719.0235956,60.60994219779968,-0.0005049596821002922,1739137719.023597,60.60994219779968,3.121714975221144,1739137719.0235987,60.60994219779968,2.262263417420617 +1739137719.043456,60.629942178726196,12.367985686359667,1739137719.0434582,60.629942178726196,0.06346861685623129,1739137719.043461,60.629942178726196,100.26906455328971,1739137719.0434637,60.629942178726196,4.27196919274722,1739137719.0434651,60.629942178726196,-0.026,1739137719.043467,60.629942178726196,-3.1305421604089987,1739137719.0434682,60.629942178726196,0.2503703562271551,1739137719.0434697,60.629942178726196,0.058657421995715456,1739137719.0434709,60.629942178726196,2.261758457738517,1739137719.0434723,60.629942178726196,0.0,1739137719.0434737,60.629942178726196,-0.0005049596821002922,1739137719.0434752,60.629942178726196,3.121714975221144,1739137719.0434766,60.629942178726196,2.262263417420617 +1739137719.0633862,60.64994215965271,12.367985686359667,1739137719.063388,60.64994215965271,0.06346861685623129,1739137719.0633914,60.64994215965271,100.26906455328971,1739137719.063394,60.64994215965271,4.27196919274722,1739137719.0633953,60.64994215965271,-0.026,1739137719.0633972,60.64994215965271,-3.1305421604089987,1739137719.0633986,60.64994215965271,0.2503703562271551,1739137719.0634003,60.64994215965271,0.058657421995715456,1739137719.0634015,60.64994215965271,2.261758457738517,1739137719.063403,60.64994215965271,0.0,1739137719.0634043,60.64994215965271,-0.0005049596821002922,1739137719.0634058,60.64994215965271,3.121714975221144,1739137719.0634072,60.64994215965271,2.262263417420617 +1739137719.0834312,60.669942140579224,12.119186264224354,1739137719.0834332,60.669942140579224,0.06829645379003235,1739137719.0834358,60.669942140579224,100.40249888510168,1739137719.0834382,60.669942140579224,4.138701745669884,1739137719.0834394,60.669942140579224,-0.026781713983943422,1739137719.0834408,60.669942140579224,-3.1296793832252328,1739137719.0834422,60.669942140579224,0.2453361247974904,1739137719.0834434,60.669942140579224,0.05915293135726178,1739137719.0834446,60.669942140579224,2.266317532691332,1739137719.083446,60.669942140579224,0.0,1739137719.083447,60.669942140579224,0.00830254068833067,1739137719.0834486,60.669942140579224,3.122761253476914,1739137719.0834496,60.669942140579224,2.2622090418935556 +1739137719.1033685,60.68994212150574,12.119186264224354,1739137719.1033707,60.68994212150574,0.06829645379003235,1739137719.1033733,60.68994212150574,100.40249888510168,1739137719.103376,60.68994212150574,4.138701745669884,1739137719.1033773,60.68994212150574,-0.026781713983943422,1739137719.103379,60.68994212150574,-3.1296793832252328,1739137719.1033804,60.68994212150574,0.2453361247974904,1739137719.1033819,60.68994212150574,0.05915293135726178,1739137719.1033828,60.68994212150574,2.266317532691332,1739137719.1033845,60.68994212150574,0.0,1739137719.103386,60.68994212150574,0.004108490797776199,1739137719.103387,60.68994212150574,3.122761253476914,1739137719.1033883,60.68994212150574,2.2622090418935556 +1739137719.1233637,60.70994210243225,12.119186264224354,1739137719.123366,60.70994210243225,0.06829645379003235,1739137719.123369,60.70994210243225,100.40249888510168,1739137719.1233716,60.70994210243225,4.138701745669884,1739137719.1233728,60.70994210243225,-0.026781713983943422,1739137719.1233742,60.70994210243225,-3.1296793832252328,1739137719.123376,60.70994210243225,0.2453361247974904,1739137719.1233768,60.70994210243225,0.05915293135726178,1739137719.1233783,60.70994210243225,2.266317532691332,1739137719.1233795,60.70994210243225,0.0,1739137719.1233807,60.70994210243225,0.004108490797776199,1739137719.123382,60.70994210243225,3.122761253476914,1739137719.1233833,60.70994210243225,2.2622090418935556 +1739137719.1433983,60.729942083358765,12.119186264224354,1739137719.1434004,60.729942083358765,0.06829645379003235,1739137719.143403,60.729942083358765,100.40249888510168,1739137719.1434057,60.729942083358765,4.138701745669884,1739137719.143407,60.729942083358765,-0.026781713983943422,1739137719.143409,60.729942083358765,-3.1296793832252328,1739137719.1434102,60.729942083358765,0.2453361247974904,1739137719.1434116,60.729942083358765,0.05915293135726178,1739137719.143413,60.729942083358765,2.266317532691332,1739137719.1434145,60.729942083358765,0.0,1739137719.1434157,60.729942083358765,0.004108490797776199,1739137719.1434174,60.729942083358765,3.122761253476914,1739137719.1434183,60.729942083358765,2.2622090418935556 +1739137719.1633744,60.74994206428528,12.119186264224354,1739137719.1633763,60.74994206428528,0.06829645379003235,1739137719.163379,60.74994206428528,100.40249888510168,1739137719.1633816,60.74994206428528,4.138701745669884,1739137719.1633828,60.74994206428528,-0.026781713983943422,1739137719.1633844,60.74994206428528,-3.1296793832252328,1739137719.1633859,60.74994206428528,0.2453361247974904,1739137719.163387,60.74994206428528,0.05915293135726178,1739137719.1633885,60.74994206428528,2.266317532691332,1739137719.16339,60.74994206428528,0.0,1739137719.163391,60.74994206428528,0.004108490797776199,1739137719.1633925,60.74994206428528,3.122761253476914,1739137719.1633937,60.74994206428528,2.2622090418935556 +1739137719.1834538,60.76994204521179,12.119186264224354,1739137719.183456,60.76994204521179,0.06829645379003235,1739137719.1834588,60.76994204521179,100.40249888510168,1739137719.1834614,60.76994204521179,4.138701745669884,1739137719.1834626,60.76994204521179,-0.026781713983943422,1739137719.1834645,60.76994204521179,-3.1296793832252328,1739137719.183466,60.76994204521179,0.2453361247974904,1739137719.1834671,60.76994204521179,0.05915293135726178,1739137719.1834686,60.76994204521179,2.266317532691332,1739137719.18347,60.76994204521179,0.0,1739137719.1834712,60.76994204521179,0.004108490797776199,1739137719.1834726,60.76994204521179,3.122761253476914,1739137719.1834738,60.76994204521179,2.2622090418935556 +1739137719.203454,60.789942026138306,11.870354738163003,1739137719.2034562,60.789942026138306,0.07286446848883266,1739137719.2034588,60.789942026138306,100.66727194251446,1739137719.2034616,60.789942026138306,3.872332601504266,1739137719.2034626,60.789942026138306,-0.02733334037015129,1739137719.2034645,60.789942026138306,-3.1290654855291358,1739137719.2034657,60.789942026138306,0.24242026192445582,1739137719.203467,60.789942026138306,0.05819320769868104,1739137719.2034683,60.789942026138306,2.268962383256649,1739137719.2034698,60.789942026138306,0.0,1739137719.2034712,60.789942026138306,0.008140373599805753,1739137719.2034726,60.789942026138306,3.1238075317326834,1739137719.2034736,60.789942026138306,2.262741954807382 +1739137719.2233887,60.80994200706482,11.870354738163003,1739137719.223391,60.80994200706482,0.07286446848883266,1739137719.2233934,60.80994200706482,100.66727194251446,1739137719.2233963,60.80994200706482,3.872332601504266,1739137719.2233977,60.80994200706482,-0.02733334037015129,1739137719.2233992,60.80994200706482,-3.1290654855291358,1739137719.2234006,60.80994200706482,0.24242026192445582,1739137719.223402,60.80994200706482,0.05819320769868104,1739137719.2234032,60.80994200706482,2.268962383256649,1739137719.223405,60.80994200706482,0.0,1739137719.2234058,60.80994200706482,0.006220428449266624,1739137719.2234073,60.80994200706482,3.1238075317326834,1739137719.2234085,60.80994200706482,2.262741954807382 +1739137719.243381,60.82994198799133,11.870354738163003,1739137719.243383,60.82994198799133,0.07286446848883266,1739137719.2433856,60.82994198799133,100.66727194251446,1739137719.2433882,60.82994198799133,3.872332601504266,1739137719.2433894,60.82994198799133,-0.02733334037015129,1739137719.243391,60.82994198799133,-3.1290654855291358,1739137719.2433925,60.82994198799133,0.24242026192445582,1739137719.2433934,60.82994198799133,0.05819320769868104,1739137719.2433949,60.82994198799133,2.268962383256649,1739137719.2433963,60.82994198799133,0.0,1739137719.2433977,60.82994198799133,0.006220428449266624,1739137719.243399,60.82994198799133,3.1238075317326834,1739137719.2434,60.82994198799133,2.262741954807382 +1739137719.263412,60.84994196891785,11.870354738163003,1739137719.263414,60.84994196891785,0.07286446848883266,1739137719.2634168,60.84994196891785,100.66727194251446,1739137719.2634192,60.84994196891785,3.872332601504266,1739137719.2634203,60.84994196891785,-0.02733334037015129,1739137719.2634223,60.84994196891785,-3.1290654855291358,1739137719.2634234,60.84994196891785,0.24242026192445582,1739137719.2634249,60.84994196891785,0.05819320769868104,1739137719.2634258,60.84994196891785,2.268962383256649,1739137719.2634273,60.84994196891785,0.0,1739137719.2634287,60.84994196891785,0.006220428449266624,1739137719.26343,60.84994196891785,3.1238075317326834,1739137719.2634313,60.84994196891785,2.262741954807382 +1739137719.2833824,60.86994194984436,11.870354738163003,1739137719.2833848,60.86994194984436,0.07286446848883266,1739137719.2833874,60.86994194984436,100.66727194251446,1739137719.28339,60.86994194984436,3.872332601504266,1739137719.2833915,60.86994194984436,-0.02733334037015129,1739137719.283393,60.86994194984436,-3.1290654855291358,1739137719.2833943,60.86994194984436,0.24242026192445582,1739137719.2833955,60.86994194984436,0.05819320769868104,1739137719.283397,60.86994194984436,2.268962383256649,1739137719.2833982,60.86994194984436,0.0,1739137719.2833993,60.86994194984436,0.006220428449266624,1739137719.283401,60.86994194984436,3.1238075317326834,1739137719.283402,60.86994194984436,2.262741954807382 +1739137719.3033183,60.889941930770874,11.621455213048499,1739137719.3033206,60.889941930770874,0.07717322856055464,1739137719.3033235,60.889941930770874,100.98249738635249,1739137719.303326,60.889941930770874,3.555091209747331,1739137719.3033273,60.889941930770874,-0.024652424102784183,1739137719.303329,60.889941930770874,-3.1289698356242273,1739137719.3033304,60.889941930770874,0.23682668810058616,1739137719.3033316,60.889941930770874,0.05589162971825837,1739137719.3033328,60.889941930770874,2.27404471024841,1739137719.3033342,60.889941930770874,0.0,1739137719.3033354,60.889941930770874,0.014591151287053142,1739137719.3033369,60.889941930770874,3.124853809988453,1739137719.3033383,60.889941930770874,2.263439619446752 +1739137719.323484,60.90994191169739,11.621455213048499,1739137719.323486,60.90994191169739,0.07717322856055464,1739137719.323489,60.90994191169739,100.98249738635249,1739137719.3234918,60.90994191169739,3.555091209747331,1739137719.3234935,60.90994191169739,-0.024652424102784183,1739137719.3234951,60.90994191169739,-3.1289698356242273,1739137719.3234968,60.90994191169739,0.23682668810058616,1739137719.3234982,60.90994191169739,0.05589162971825837,1739137719.3234994,60.90994191169739,2.27404471024841,1739137719.323501,60.90994191169739,0.0,1739137719.3235023,60.90994191169739,0.010605090801657724,1739137719.3235042,60.90994191169739,3.124853809988453,1739137719.3235054,60.90994191169739,2.263439619446752 +1739137719.3436594,60.9299418926239,11.621455213048499,1739137719.3436618,60.9299418926239,0.07717322856055464,1739137719.3436651,60.9299418926239,100.98249738635249,1739137719.343668,60.9299418926239,3.555091209747331,1739137719.3436694,60.9299418926239,-0.024652424102784183,1739137719.3436716,60.9299418926239,-3.1289698356242273,1739137719.343673,60.9299418926239,0.23682668810058616,1739137719.3436747,60.9299418926239,0.05589162971825837,1739137719.3436759,60.9299418926239,2.27404471024841,1739137719.3436778,60.9299418926239,0.0,1739137719.343679,60.9299418926239,0.010605090801657724,1739137719.3436809,60.9299418926239,3.124853809988453,1739137719.3436823,60.9299418926239,2.263439619446752 +1739137719.3635278,60.949941873550415,11.621455213048499,1739137719.3635302,60.949941873550415,0.07717322856055464,1739137719.3635335,60.949941873550415,100.98249738635249,1739137719.3635366,60.949941873550415,3.555091209747331,1739137719.3635385,60.949941873550415,-0.024652424102784183,1739137719.3635402,60.949941873550415,-3.1289698356242273,1739137719.363542,60.949941873550415,0.23682668810058616,1739137719.3635435,60.949941873550415,0.05589162971825837,1739137719.3635452,60.949941873550415,2.27404471024841,1739137719.3635468,60.949941873550415,0.0,1739137719.3635485,60.949941873550415,0.010605090801657724,1739137719.36355,60.949941873550415,3.124853809988453,1739137719.3635514,60.949941873550415,2.263439619446752 +1739137719.3835278,60.96994185447693,11.621455213048499,1739137719.3835301,60.96994185447693,0.07717322856055464,1739137719.3835335,60.96994185447693,100.98249738635249,1739137719.3835366,60.96994185447693,3.555091209747331,1739137719.3835385,60.96994185447693,-0.024652424102784183,1739137719.3835404,60.96994185447693,-3.1289698356242273,1739137719.3835423,60.96994185447693,0.23682668810058616,1739137719.3835437,60.96994185447693,0.05589162971825837,1739137719.3835452,60.96994185447693,2.27404471024841,1739137719.3835468,60.96994185447693,0.0,1739137719.3835485,60.96994185447693,0.010605090801657724,1739137719.38355,60.96994185447693,3.124853809988453,1739137719.3835516,60.96994185447693,2.263439619446752 +1739137719.403691,60.98994183540344,11.621455213048499,1739137719.4036937,60.98994183540344,0.07717322856055464,1739137719.403697,60.98994183540344,100.98249738635249,1739137719.4036999,60.98994183540344,3.555091209747331,1739137719.4037015,60.98994183540344,-0.024652424102784183,1739137719.4037035,60.98994183540344,-3.1289698356242273,1739137719.4037051,60.98994183540344,0.23682668810058616,1739137719.4037066,60.98994183540344,0.05589162971825837,1739137719.4037082,60.98994183540344,2.27404471024841,1739137719.40371,60.98994183540344,0.0,1739137719.4037113,60.98994183540344,0.010605090801657724,1739137719.403713,60.98994183540344,3.124853809988453,1739137719.4037147,60.98994183540344,2.263439619446752 +1739137719.4236774,61.009941816329956,11.37244409612488,1739137719.4236803,61.009941816329956,0.08122330724668636,1739137719.4236834,61.009941816329956,101.22030930285459,1739137719.4236865,61.009941816329956,3.3139438816092093,1739137719.4236882,61.009941816329956,-0.011492038752053148,1739137719.42369,61.009941816329956,-3.1300878756663275,1739137719.4236917,61.009941816329956,0.21915728140867263,1739137719.4236934,61.009941816329956,0.05182484213244028,1739137719.4236946,61.009941816329956,2.2901740506089827,1739137719.4236963,61.009941816329956,0.0,1739137719.423698,61.009941816329956,0.039030167774419894,1739137719.4236994,61.009941816329956,3.1259000882442227,1739137719.423701,61.009941816329956,2.2646796405356757 +1739137719.4435594,61.02994179725647,11.37244409612488,1739137719.443562,61.02994179725647,0.08122330724668636,1739137719.4435656,61.02994179725647,101.22030930285459,1739137719.4435687,61.02994179725647,3.3139438816092093,1739137719.4435704,61.02994179725647,-0.011492038752053148,1739137719.4435725,61.02994179725647,-3.1300878756663275,1739137719.443574,61.02994179725647,0.21915728140867263,1739137719.4435756,61.02994179725647,0.05182484213244028,1739137719.4435773,61.02994179725647,2.2901740506089827,1739137719.4435792,61.02994179725647,0.0,1739137719.4435804,61.02994179725647,0.025494410073306994,1739137719.4435823,61.02994179725647,3.1259000882442227,1739137719.4435837,61.02994179725647,2.2646796405356757 +1739137719.4635143,61.04994177818298,11.37244409612488,1739137719.463517,61.04994177818298,0.08122330724668636,1739137719.46352,61.04994177818298,101.22030930285459,1739137719.4635231,61.04994177818298,3.3139438816092093,1739137719.4635246,61.04994177818298,-0.011492038752053148,1739137719.4635267,61.04994177818298,-3.1300878756663275,1739137719.4635282,61.04994177818298,0.21915728140867263,1739137719.4635298,61.04994177818298,0.05182484213244028,1739137719.463531,61.04994177818298,2.2901740506089827,1739137719.4635327,61.04994177818298,0.0,1739137719.4635344,61.04994177818298,0.025494410073306994,1739137719.463536,61.04994177818298,3.1259000882442227,1739137719.4635377,61.04994177818298,2.2646796405356757 +1739137719.483653,61.0699417591095,11.37244409612488,1739137719.483656,61.0699417591095,0.08122330724668636,1739137719.4836595,61.0699417591095,101.22030930285459,1739137719.4836626,61.0699417591095,3.3139438816092093,1739137719.4836643,61.0699417591095,-0.011492038752053148,1739137719.4836664,61.0699417591095,-3.1300878756663275,1739137719.4836679,61.0699417591095,0.21915728140867263,1739137719.4836695,61.0699417591095,0.05182484213244028,1739137719.483671,61.0699417591095,2.2901740506089827,1739137719.4836729,61.0699417591095,0.0,1739137719.4836743,61.0699417591095,0.025494410073306994,1739137719.483676,61.0699417591095,3.1259000882442227,1739137719.4836774,61.0699417591095,2.2646796405356757 +1739137719.5036585,61.08994174003601,11.37244409612488,1739137719.5036614,61.08994174003601,0.08122330724668636,1739137719.5036645,61.08994174003601,101.22030930285459,1739137719.5036674,61.08994174003601,3.3139438816092093,1739137719.503669,61.08994174003601,-0.011492038752053148,1739137719.503671,61.08994174003601,-3.1300878756663275,1739137719.5036726,61.08994174003601,0.21915728140867263,1739137719.5036743,61.08994174003601,0.05182484213244028,1739137719.5036757,61.08994174003601,2.2901740506089827,1739137719.5036774,61.08994174003601,0.0,1739137719.503679,61.08994174003601,0.025494410073306994,1739137719.5036805,61.08994174003601,3.1259000882442227,1739137719.5036824,61.08994174003601,2.2646796405356757 +1739137719.5235834,61.109941720962524,11.123210400919291,1739137719.523586,61.109941720962524,0.08501615669297191,1739137719.5235891,61.109941720962524,101.45933156400697,1739137719.523592,61.109941720962524,3.066504702711652,1739137719.5235934,61.109941720962524,0.0008598118915339203,1739137719.5235958,61.109941720962524,-3.1311475303063006,1739137719.5235972,61.109941720962524,0.20214392451708227,1739137719.523599,61.109941720962524,0.047824752907792534,1739137719.5236003,61.109941720962524,2.3058126225615965,1739137719.5236022,61.109941720962524,0.0,1739137719.5236034,61.109941720962524,0.04979263146152904,1739137719.5236053,61.109941720962524,3.1269463664999924,1739137719.5236068,61.109941720962524,2.2675905784935204 +1739137719.5438,61.12994170188904,11.123210400919291,1739137719.5438027,61.12994170188904,0.08501615669297191,1739137719.5438058,61.12994170188904,101.45933156400697,1739137719.5438087,61.12994170188904,3.066504702711652,1739137719.5438106,61.12994170188904,0.0008598118915339203,1739137719.5438125,61.12994170188904,-3.1311475303063006,1739137719.5438144,61.12994170188904,0.20214392451708227,1739137719.5438159,61.12994170188904,0.047824752907792534,1739137719.5438175,61.12994170188904,2.3058126225615965,1739137719.5438192,61.12994170188904,0.0,1739137719.5438206,61.12994170188904,0.038222044068076055,1739137719.543822,61.12994170188904,3.1269463664999924,1739137719.5438237,61.12994170188904,2.2675905784935204 +1739137719.5686085,61.14994168281555,11.123210400919291,1739137719.5686169,61.14994168281555,0.08501615669297191,1739137719.5686274,61.14994168281555,101.45933156400697,1739137719.568651,61.14994168281555,3.066504702711652,1739137719.5686562,61.14994168281555,0.0008598118915339203,1739137719.568663,61.14994168281555,-3.1311475303063006,1739137719.568668,61.14994168281555,0.20214392451708227,1739137719.5686724,61.14994168281555,0.047824752907792534,1739137719.568677,61.14994168281555,2.3058126225615965,1739137719.5686822,61.14994168281555,0.0,1739137719.5686872,61.14994168281555,0.038222044068076055,1739137719.5686922,61.14994168281555,3.1269463664999924,1739137719.5686967,61.14994168281555,2.2675905784935204 +1739137719.593681,61.169941663742065,11.123210400919291,1739137719.5936902,61.169941663742065,0.08501615669297191,1739137719.5937018,61.169941663742065,101.45933156400697,1739137719.5937152,61.169941663742065,3.066504702711652,1739137719.5937228,61.169941663742065,0.0008598118915339203,1739137719.5937326,61.169941663742065,-3.1311475303063006,1739137719.593741,61.169941663742065,0.20214392451708227,1739137719.5937498,61.169941663742065,0.047824752907792534,1739137719.5937586,61.169941663742065,2.3058126225615965,1739137719.5937672,61.169941663742065,0.0,1739137719.593776,61.169941663742065,0.038222044068076055,1739137719.5937848,61.169941663742065,3.1269463664999924,1739137719.5937936,61.169941663742065,2.2675905784935204 +1739137719.6084087,61.18994164466858,11.123210400919291,1739137719.6084132,61.18994164466858,0.08501615669297191,1739137719.6084194,61.18994164466858,101.45933156400697,1739137719.6084266,61.18994164466858,3.066504702711652,1739137719.6084304,61.18994164466858,0.0008598118915339203,1739137719.6084356,61.18994164466858,-3.1311475303063006,1739137719.6084402,61.18994164466858,0.20214392451708227,1739137719.608445,61.18994164466858,0.047824752907792534,1739137719.6084492,61.18994164466858,2.3058126225615965,1739137719.608454,61.18994164466858,0.0,1739137719.6084585,61.18994164466858,0.038222044068076055,1739137719.6084633,61.18994164466858,3.1269463664999924,1739137719.6084678,61.18994164466858,2.2675905784935204 +1739137719.6252697,61.199941635131836,11.123210400919291,1739137719.6252732,61.199941635131836,0.08501615669297191,1739137719.6252778,61.199941635131836,101.45933156400697,1739137719.6252828,61.199941635131836,3.066504702711652,1739137719.6252856,61.199941635131836,0.0008598118915339203,1739137719.6252892,61.199941635131836,-3.1311475303063006,1739137719.6252923,61.199941635131836,0.20214392451708227,1739137719.6252956,61.199941635131836,0.047824752907792534,1739137719.625299,61.199941635131836,2.3058126225615965,1739137719.6253023,61.199941635131836,0.0,1739137719.6253057,61.199941635131836,0.038222044068076055,1739137719.625309,61.199941635131836,3.1269463664999924,1739137719.6253123,61.199941635131836,2.2675905784935204 +1739137719.6439726,61.229941606521606,10.873568999345759,1739137719.643975,61.229941606521606,0.08855394708519881,1739137719.6439774,61.229941606521606,101.80356429400722,1739137719.6439798,61.229941606521606,2.709496316347555,1739137719.643981,61.229941606521606,0.018925184182622252,1739137719.6439826,61.229941606521606,-3.1330641804303845,1739137719.643984,61.229941606521606,0.18065036163329196,1739137719.6439855,61.229941606521606,0.04162525108439495,1739137719.643987,61.229941606521606,2.325722136645338,1739137719.6439884,61.229941606521606,0.0,1739137719.6439898,61.229941606521606,0.06780487116541183,1739137719.6439912,61.229941606521606,3.127992644755762,1739137719.6439924,61.229941606521606,2.2720043330395727 +1739137719.6635025,61.24994158744812,10.873568999345759,1739137719.6635044,61.24994158744812,0.08855394708519881,1739137719.663507,61.24994158744812,101.80356429400722,1739137719.6635096,61.24994158744812,2.709496316347555,1739137719.6635108,61.24994158744812,0.018925184182622252,1739137719.6635125,61.24994158744812,-3.1330641804303845,1739137719.6635141,61.24994158744812,0.18065036163329196,1739137719.6635153,61.24994158744812,0.04162525108439495,1739137719.6635165,61.24994158744812,2.325722136645338,1739137719.663518,61.24994158744812,0.0,1739137719.6635191,61.24994158744812,0.05371780360576528,1739137719.6635206,61.24994158744812,3.127992644755762,1739137719.6635218,61.24994158744812,2.2720043330395727 +1739137719.6835752,61.269941568374634,10.873568999345759,1739137719.6835775,61.269941568374634,0.08855394708519881,1739137719.6835806,61.269941568374634,101.80356429400722,1739137719.6835833,61.269941568374634,2.709496316347555,1739137719.6835845,61.269941568374634,0.018925184182622252,1739137719.6835861,61.269941568374634,-3.1330641804303845,1739137719.6835876,61.269941568374634,0.18065036163329196,1739137719.683589,61.269941568374634,0.04162525108439495,1739137719.6835904,61.269941568374634,2.325722136645338,1739137719.6835918,61.269941568374634,0.0,1739137719.6835933,61.269941568374634,0.05371780360576528,1739137719.6835947,61.269941568374634,3.127992644755762,1739137719.6835957,61.269941568374634,2.2720043330395727 +1739137719.7038045,61.28994154930115,10.873568999345759,1739137719.7038069,61.28994154930115,0.08855394708519881,1739137719.7038097,61.28994154930115,101.80356429400722,1739137719.7038126,61.28994154930115,2.709496316347555,1739137719.703814,61.28994154930115,0.018925184182622252,1739137719.7038157,61.28994154930115,-3.1330641804303845,1739137719.703817,61.28994154930115,0.18065036163329196,1739137719.7038183,61.28994154930115,0.04162525108439495,1739137719.7038193,61.28994154930115,2.325722136645338,1739137719.7038207,61.28994154930115,0.0,1739137719.7038224,61.28994154930115,0.05371780360576528,1739137719.7038236,61.28994154930115,3.127992644755762,1739137719.703825,61.28994154930115,2.2720043330395727 +1739137719.7235286,61.30994153022766,10.873568999345759,1739137719.7235312,61.30994153022766,0.08855394708519881,1739137719.7235339,61.30994153022766,101.80356429400722,1739137719.723536,61.30994153022766,2.709496316347555,1739137719.7235374,61.30994153022766,0.018925184182622252,1739137719.7235389,61.30994153022766,-3.1330641804303845,1739137719.7235405,61.30994153022766,0.18065036163329196,1739137719.7235417,61.30994153022766,0.04162525108439495,1739137719.7235427,61.30994153022766,2.325722136645338,1739137719.7235444,61.30994153022766,0.0,1739137719.7235456,61.30994153022766,0.05371780360576528,1739137719.723547,61.30994153022766,3.127992644755762,1739137719.7235482,61.30994153022766,2.2720043330395727 +1739137719.7435007,61.329941511154175,10.62336746662663,1739137719.743503,61.329941511154175,0.09183782957789433,1739137719.7435057,61.329941511154175,101.83333827640081,1739137719.7435083,61.329941511154175,2.661763119090332,1739137719.7435095,61.329941511154175,0.021070893098353805,1739137719.743511,61.329941511154175,-3.1327043605008607,1739137719.7435124,61.329941511154175,0.17070657099234476,1739137719.7435136,61.329941511154175,0.041359801352086716,1739137719.7435145,61.329941511154175,2.3349911558688414,1739137719.7435162,61.329941511154175,0.0,1739137719.7435174,61.329941511154175,0.05995362491283948,1739137719.7435188,61.329941511154175,3.1290389230115316,1739137719.74352,61.329941511154175,2.2780069711570214 +1739137719.7632914,61.34994149208069,10.62336746662663,1739137719.7632937,61.34994149208069,0.09183782957789433,1739137719.763296,61.34994149208069,101.83333827640081,1739137719.7632985,61.34994149208069,2.661763119090332,1739137719.7633,61.34994149208069,0.021070893098353805,1739137719.7633014,61.34994149208069,-3.1327043605008607,1739137719.7633026,61.34994149208069,0.17070657099234476,1739137719.763304,61.34994149208069,0.041359801352086716,1739137719.7633052,61.34994149208069,2.3349911558688414,1739137719.7633064,61.34994149208069,0.0,1739137719.7633078,61.34994149208069,0.056984184711819985,1739137719.7633092,61.34994149208069,3.1290389230115316,1739137719.7633107,61.34994149208069,2.2780069711570214 +1739137719.783339,61.3699414730072,10.62336746662663,1739137719.7833412,61.3699414730072,0.09183782957789433,1739137719.7833438,61.3699414730072,101.83333827640081,1739137719.7833462,61.3699414730072,2.661763119090332,1739137719.783348,61.3699414730072,0.021070893098353805,1739137719.7833498,61.3699414730072,-3.1327043605008607,1739137719.783351,61.3699414730072,0.17070657099234476,1739137719.7833524,61.3699414730072,0.041359801352086716,1739137719.7833536,61.3699414730072,2.3349911558688414,1739137719.783355,61.3699414730072,0.0,1739137719.7833562,61.3699414730072,0.056984184711819985,1739137719.7833576,61.3699414730072,3.1290389230115316,1739137719.783359,61.3699414730072,2.2780069711570214 +1739137719.8034148,61.389941453933716,10.62336746662663,1739137719.8034167,61.389941453933716,0.09183782957789433,1739137719.8034198,61.389941453933716,101.83333827640081,1739137719.8034225,61.389941453933716,2.661763119090332,1739137719.8034236,61.389941453933716,0.021070893098353805,1739137719.8034253,61.389941453933716,-3.1327043605008607,1739137719.8034265,61.389941453933716,0.17070657099234476,1739137719.803428,61.389941453933716,0.041359801352086716,1739137719.803429,61.389941453933716,2.3349911558688414,1739137719.8034303,61.389941453933716,0.0,1739137719.8034317,61.389941453933716,0.056984184711819985,1739137719.803433,61.389941453933716,3.1290389230115316,1739137719.8034341,61.389941453933716,2.2780069711570214 +1739137719.8235114,61.40994143486023,10.62336746662663,1739137719.8235135,61.40994143486023,0.09183782957789433,1739137719.8235164,61.40994143486023,101.83333827640081,1739137719.8235192,61.40994143486023,2.661763119090332,1739137719.8235204,61.40994143486023,0.021070893098353805,1739137719.8235223,61.40994143486023,-3.1327043605008607,1739137719.823524,61.40994143486023,0.17070657099234476,1739137719.8235254,61.40994143486023,0.041359801352086716,1739137719.8235266,61.40994143486023,2.3349911558688414,1739137719.8235283,61.40994143486023,0.0,1739137719.8235295,61.40994143486023,0.056984184711819985,1739137719.823531,61.40994143486023,3.1290389230115316,1739137719.8235323,61.40994143486023,2.2780069711570214 +1739137719.8435879,61.42994141578674,10.62336746662663,1739137719.8435905,61.42994141578674,0.09183782957789433,1739137719.8435934,61.42994141578674,101.83333827640081,1739137719.8435965,61.42994141578674,2.661763119090332,1739137719.8435981,61.42994141578674,0.021070893098353805,1739137719.8435998,61.42994141578674,-3.1327043605008607,1739137719.843602,61.42994141578674,0.17070657099234476,1739137719.8436034,61.42994141578674,0.041359801352086716,1739137719.8436048,61.42994141578674,2.3349911558688414,1739137719.8436067,61.42994141578674,0.0,1739137719.8436081,61.42994141578674,0.056984184711819985,1739137719.8436096,61.42994141578674,3.1290389230115316,1739137719.8436112,61.42994141578674,2.2780069711570214 +1739137719.863707,61.44994139671326,10.372486876015575,1739137719.8637097,61.44994139671326,0.09486809046896294,1739137719.8637128,61.44994139671326,102.15653909729821,1739137719.863716,61.44994139671326,2.3197725255383315,1739137719.8637176,61.44994139671326,0.028703141140914486,1739137719.8637195,61.44994139671326,-3.133376360602658,1739137719.8637211,61.44994139671326,0.15882474984898057,1739137719.8637228,61.44994139671326,0.03761601015055967,1739137719.8637242,61.44994139671326,2.346115148501712,1739137719.8637261,61.44994139671326,0.0,1739137719.8637276,61.44994139671326,0.06619890741942472,1739137719.8637292,61.44994139671326,3.1300852012673013,1739137719.8637307,61.44994139671326,2.284304206468365 +1739137719.8835917,61.46994137763977,10.372486876015575,1739137719.883594,61.46994137763977,0.09486809046896294,1739137719.8835976,61.46994137763977,102.15653909729821,1739137719.8836005,61.46994137763977,2.3197725255383315,1739137719.8836021,61.46994137763977,0.028703141140914486,1739137719.883604,61.46994137763977,-3.133376360602658,1739137719.8836055,61.46994137763977,0.15882474984898057,1739137719.8836071,61.46994137763977,0.03761601015055967,1739137719.8836083,61.46994137763977,2.346115148501712,1739137719.88361,61.46994137763977,0.0,1739137719.8836117,61.46994137763977,0.061810942033346805,1739137719.883613,61.46994137763977,3.1300852012673013,1739137719.8836148,61.46994137763977,2.284304206468365 +1739137719.9036672,61.489941358566284,10.372486876015575,1739137719.90367,61.489941358566284,0.09486809046896294,1739137719.9036732,61.489941358566284,102.15653909729821,1739137719.9036763,61.489941358566284,2.3197725255383315,1739137719.9036777,61.489941358566284,0.028703141140914486,1739137719.9036794,61.489941358566284,-3.133376360602658,1739137719.9036813,61.489941358566284,0.15882474984898057,1739137719.9036827,61.489941358566284,0.03761601015055967,1739137719.9036841,61.489941358566284,2.346115148501712,1739137719.9036858,61.489941358566284,0.0,1739137719.9036872,61.489941358566284,0.061810942033346805,1739137719.903689,61.489941358566284,3.1300852012673013,1739137719.9036903,61.489941358566284,2.284304206468365 +1739137719.9237692,61.5099413394928,10.372486876015575,1739137719.923772,61.5099413394928,0.09486809046896294,1739137719.9237752,61.5099413394928,102.15653909729821,1739137719.923778,61.5099413394928,2.3197725255383315,1739137719.9237797,61.5099413394928,0.028703141140914486,1739137719.9237819,61.5099413394928,-3.133376360602658,1739137719.9237835,61.5099413394928,0.15882474984898057,1739137719.923785,61.5099413394928,0.03761601015055967,1739137719.9237862,61.5099413394928,2.346115148501712,1739137719.9237883,61.5099413394928,0.0,1739137719.9237895,61.5099413394928,0.061810942033346805,1739137719.9237912,61.5099413394928,3.1300852012673013,1739137719.9237926,61.5099413394928,2.284304206468365 +1739137719.9436324,61.52994132041931,10.372486876015575,1739137719.943635,61.52994132041931,0.09486809046896294,1739137719.9436383,61.52994132041931,102.15653909729821,1739137719.9436412,61.52994132041931,2.3197725255383315,1739137719.9436429,61.52994132041931,0.028703141140914486,1739137719.9436448,61.52994132041931,-3.133376360602658,1739137719.9436464,61.52994132041931,0.15882474984898057,1739137719.943648,61.52994132041931,0.03761601015055967,1739137719.9436493,61.52994132041931,2.346115148501712,1739137719.9436514,61.52994132041931,0.0,1739137719.9436526,61.52994132041931,0.061810942033346805,1739137719.9436543,61.52994132041931,3.1300852012673013,1739137719.9436557,61.52994132041931,2.284304206468365 +1739137719.9639306,61.549941301345825,10.120887721860221,1739137719.9639332,61.549941301345825,0.09764374754705685,1739137719.9639366,61.549941301345825,103.0290997518882,1739137719.9639397,61.549941301345825,1.4269304636694868,1739137719.963941,61.549941301345825,0.04232557839390277,1739137719.963943,61.549941301345825,-3.135229909789852,1739137719.9639447,61.549941301345825,0.14626248364072583,1739137719.9639459,61.549941301345825,0.029720585938719297,1739137719.9639475,61.549941301345825,2.35793382673027,1739137719.9639492,61.549941301345825,0.0,1739137719.9639506,61.549941301345825,0.07139200451573093,1739137719.9639523,61.549941301345825,3.131131479523071,1739137719.963954,61.549941301345825,2.291104235199561 +1739137719.9838371,61.56994128227234,10.120887721860221,1739137719.9838398,61.56994128227234,0.09764374754705685,1739137719.9838428,61.56994128227234,103.0290997518882,1739137719.983846,61.56994128227234,1.4269304636694868,1739137719.9838474,61.56994128227234,0.04232557839390277,1739137719.9838495,61.56994128227234,-3.135229909789852,1739137719.983851,61.56994128227234,0.14626248364072583,1739137719.9838524,61.56994128227234,0.029720585938719297,1739137719.9838538,61.56994128227234,2.35793382673027,1739137719.9838552,61.56994128227234,0.0,1739137719.983857,61.56994128227234,0.06682959153070911,1739137719.9838586,61.56994128227234,3.131131479523071,1739137719.98386,61.56994128227234,2.291104235199561 +1739137720.0038755,61.58994126319885,10.120887721860221,1739137720.0038784,61.58994126319885,0.09764374754705685,1739137720.0038815,61.58994126319885,103.0290997518882,1739137720.0038846,61.58994126319885,1.4269304636694868,1739137720.003886,61.58994126319885,0.04232557839390277,1739137720.003888,61.58994126319885,-3.135229909789852,1739137720.0038896,61.58994126319885,0.14626248364072583,1739137720.003891,61.58994126319885,0.029720585938719297,1739137720.0038924,61.58994126319885,2.35793382673027,1739137720.0038943,61.58994126319885,0.0,1739137720.0038958,61.58994126319885,0.06682959153070911,1739137720.0038974,61.58994126319885,3.131131479523071,1739137720.0038986,61.58994126319885,2.291104235199561 +1739137720.0239255,61.609941244125366,10.120887721860221,1739137720.0239282,61.609941244125366,0.09764374754705685,1739137720.023931,61.609941244125366,103.0290997518882,1739137720.0239341,61.609941244125366,1.4269304636694868,1739137720.0239358,61.609941244125366,0.04232557839390277,1739137720.0239375,61.609941244125366,-3.135229909789852,1739137720.0239391,61.609941244125366,0.14626248364072583,1739137720.0239406,61.609941244125366,0.029720585938719297,1739137720.023942,61.609941244125366,2.35793382673027,1739137720.0239437,61.609941244125366,0.0,1739137720.0239449,61.609941244125366,0.06682959153070911,1739137720.0239468,61.609941244125366,3.131131479523071,1739137720.023948,61.609941244125366,2.291104235199561 +1739137720.043817,61.62994122505188,10.120887721860221,1739137720.0438194,61.62994122505188,0.09764374754705685,1739137720.0438228,61.62994122505188,103.0290997518882,1739137720.0438259,61.62994122505188,1.4269304636694868,1739137720.0438275,61.62994122505188,0.04232557839390277,1739137720.0438294,61.62994122505188,-3.135229909789852,1739137720.043831,61.62994122505188,0.14626248364072583,1739137720.0438325,61.62994122505188,0.029720585938719297,1739137720.0438344,61.62994122505188,2.35793382673027,1739137720.043836,61.62994122505188,0.0,1739137720.0438378,61.62994122505188,0.06682959153070911,1739137720.0438392,61.62994122505188,3.131131479523071,1739137720.043841,61.62994122505188,2.291104235199561 +1739137720.063839,61.649941205978394,10.120887721860221,1739137720.0638418,61.649941205978394,0.09764374754705685,1739137720.063845,61.649941205978394,103.0290997518882,1739137720.0638483,61.649941205978394,1.4269304636694868,1739137720.0638497,61.649941205978394,0.04232557839390277,1739137720.0638518,61.649941205978394,-3.135229909789852,1739137720.0638533,61.649941205978394,0.14626248364072583,1739137720.063855,61.649941205978394,0.029720585938719297,1739137720.0638561,61.649941205978394,2.35793382673027,1739137720.063858,61.649941205978394,0.0,1739137720.0638595,61.649941205978394,0.06682959153070911,1739137720.063861,61.649941205978394,3.131131479523071,1739137720.0638626,61.649941205978394,2.291104235199561 +1739137720.0838563,61.66994118690491,9.868503709063745,1739137720.0838587,61.66994118690491,0.10016396513313097,1739137720.083862,61.66994118690491,103.03515696819531,1739137720.083865,61.66994118690491,1.3986560153311338,1739137720.0838664,61.66994118690491,0.04269277902167359,1739137720.0838683,61.66994118690491,-3.134807371705778,1739137720.0838697,61.66994118690491,0.1372101945066111,1739137720.0838716,61.66994118690491,0.029375990432414942,1739137720.083873,61.66994118690491,2.366487182378144,1739137720.0838745,61.66994118690491,0.0,1739137720.0838761,61.66994118690491,0.06901897017522643,1739137720.0838776,61.66994118690491,3.1321777577788406,1739137720.0838792,61.66994118690491,2.2985107739830166 +1739137720.1137474,61.68994116783142,9.868503709063745,1739137720.1137633,61.68994116783142,0.10016396513313097,1739137720.1137815,61.68994116783142,103.03515696819531,1739137720.113802,61.68994116783142,1.3986560153311338,1739137720.1138122,61.68994116783142,0.04269277902167359,1739137720.1138256,61.68994116783142,-3.134807371705778,1739137720.113837,61.68994116783142,0.1372101945066111,1739137720.1138468,61.68994116783142,0.029375990432414942,1739137720.1138577,61.68994116783142,2.366487182378144,1739137720.1138701,61.68994116783142,0.0,1739137720.1138806,61.68994116783142,0.06797640839512731,1739137720.1138918,61.68994116783142,3.1321777577788406,1739137720.1139023,61.68994116783142,2.2985107739830166 +1739137720.127693,61.709941148757935,9.868503709063745,1739137720.1276968,61.709941148757935,0.10016396513313097,1739137720.1277013,61.709941148757935,103.03515696819531,1739137720.1277058,61.709941148757935,1.3986560153311338,1739137720.127708,61.709941148757935,0.04269277902167359,1739137720.1277106,61.709941148757935,-3.134807371705778,1739137720.1277125,61.709941148757935,0.1372101945066111,1739137720.1277146,61.709941148757935,0.029375990432414942,1739137720.1277163,61.709941148757935,2.366487182378144,1739137720.1277187,61.709941148757935,0.0,1739137720.1277206,61.709941148757935,0.06797640839512731,1739137720.127723,61.709941148757935,3.1321777577788406,1739137720.1277251,61.709941148757935,2.2985107739830166 +1739137720.145958,61.71994113922119,9.868503709063745,1739137720.1459615,61.71994113922119,0.10016396513313097,1739137720.1459658,61.71994113922119,103.03515696819531,1739137720.1459703,61.71994113922119,1.3986560153311338,1739137720.145973,61.71994113922119,0.04269277902167359,1739137720.1459758,61.71994113922119,-3.134807371705778,1739137720.1459785,61.71994113922119,0.1372101945066111,1739137720.1459808,61.71994113922119,0.029375990432414942,1739137720.1459835,61.71994113922119,2.366487182378144,1739137720.1459863,61.71994113922119,0.0,1739137720.145989,61.71994113922119,0.06797640839512731,1739137720.1459913,61.71994113922119,3.1321777577788406,1739137720.1459944,61.71994113922119,2.2985107739830166 +1739137720.1668398,61.74994111061096,9.868503709063745,1739137720.1668444,61.74994111061096,0.10016396513313097,1739137720.16685,61.74994111061096,103.03515696819531,1739137720.1668572,61.74994111061096,1.3986560153311338,1739137720.1668608,61.74994111061096,0.04269277902167359,1739137720.1668658,61.74994111061096,-3.134807371705778,1739137720.1668704,61.74994111061096,0.1372101945066111,1739137720.1668746,61.74994111061096,0.029375990432414942,1739137720.1668787,61.74994111061096,2.366487182378144,1739137720.1668832,61.74994111061096,0.0,1739137720.1668878,61.74994111061096,0.06797640839512731,1739137720.1668923,61.74994111061096,3.1321777577788406,1739137720.1668966,61.74994111061096,2.2985107739830166 +1739137720.1845043,61.769941091537476,9.615304939402504,1739137720.184507,61.769941091537476,0.10242737799297164,1739137720.18451,61.769941091537476,103.04123373866717,1739137720.1845129,61.769941091537476,1.3702495444267557,1739137720.184514,61.769941091537476,0.043,1739137720.1845324,61.769941091537476,-3.134385139983985,1739137720.1845343,61.769941091537476,0.12842420698351018,1739137720.1845357,61.769941091537476,0.029014483932588216,1739137720.1845372,61.769941091537476,2.3748185844652077,1739137720.1845388,61.769941091537476,0.0,1739137720.1845403,61.769941091537476,0.06967073432817607,1739137720.1845417,61.769941091537476,3.13322403603461,1739137720.184543,61.769941091537476,2.305954672412955 +1739137720.2048433,61.78994107246399,9.615304939402504,1739137720.2048457,61.78994107246399,0.10242737799297164,1739137720.204848,61.78994107246399,103.04123373866717,1739137720.2048507,61.78994107246399,1.3702495444267557,1739137720.2048519,61.78994107246399,0.043,1739137720.2048538,61.78994107246399,-3.134385139983985,1739137720.2048552,61.78994107246399,0.12842420698351018,1739137720.2048566,61.78994107246399,0.029014483932588216,1739137720.2048578,61.78994107246399,2.3748185844652077,1739137720.2048595,61.78994107246399,0.0,1739137720.2048607,61.78994107246399,0.06886391205225273,1739137720.204862,61.78994107246399,3.13322403603461,1739137720.2048635,61.78994107246399,2.305954672412955 +1739137720.2244635,61.8099410533905,9.615304939402504,1739137720.2244658,61.8099410533905,0.10242737799297164,1739137720.2244685,61.8099410533905,103.04123373866717,1739137720.224471,61.8099410533905,1.3702495444267557,1739137720.2244723,61.8099410533905,0.043,1739137720.224474,61.8099410533905,-3.134385139983985,1739137720.2244751,61.8099410533905,0.12842420698351018,1739137720.224476,61.8099410533905,0.029014483932588216,1739137720.2244775,61.8099410533905,2.3748185844652077,1739137720.224479,61.8099410533905,0.0,1739137720.2244818,61.8099410533905,0.06886391205225273,1739137720.2244856,61.8099410533905,3.13322403603461,1739137720.224487,61.8099410533905,2.305954672412955 +1739137720.2448184,61.82994103431702,9.615304939402504,1739137720.2448213,61.82994103431702,0.10242737799297164,1739137720.244825,61.82994103431702,103.04123373866717,1739137720.2448277,61.82994103431702,1.3702495444267557,1739137720.2448292,61.82994103431702,0.043,1739137720.2448313,61.82994103431702,-3.134385139983985,1739137720.244833,61.82994103431702,0.12842420698351018,1739137720.2448347,61.82994103431702,0.029014483932588216,1739137720.2448359,61.82994103431702,2.3748185844652077,1739137720.2448373,61.82994103431702,0.0,1739137720.2448387,61.82994103431702,0.06886391205225273,1739137720.2448404,61.82994103431702,3.13322403603461,1739137720.2448418,61.82994103431702,2.305954672412955 +1739137720.2636309,61.84994101524353,9.615304939402504,1739137720.2636333,61.84994101524353,0.10242737799297164,1739137720.2636359,61.84994101524353,103.04123373866717,1739137720.2636383,61.84994101524353,1.3702495444267557,1739137720.2636395,61.84994101524353,0.043,1739137720.2636414,61.84994101524353,-3.134385139983985,1739137720.2636425,61.84994101524353,0.12842420698351018,1739137720.263644,61.84994101524353,0.029014483932588216,1739137720.2636452,61.84994101524353,2.3748185844652077,1739137720.2636466,61.84994101524353,0.0,1739137720.2636478,61.84994101524353,0.06886391205225273,1739137720.2636492,61.84994101524353,3.13322403603461,1739137720.2636507,61.84994101524353,2.305954672412955 +1739137720.2837152,61.85994100570679,9.615304939402504,1739137720.2837174,61.85994100570679,0.10242737799297164,1739137720.28372,61.85994100570679,103.04123373866717,1739137720.2837224,61.85994100570679,1.3702495444267557,1739137720.2837238,61.85994100570679,0.043,1739137720.2837253,61.85994100570679,-3.134385139983985,1739137720.2837267,61.85994100570679,0.12842420698351018,1739137720.283728,61.85994100570679,0.029014483932588216,1739137720.283729,61.85994100570679,2.3748185844652077,1739137720.2837305,61.85994100570679,0.0,1739137720.2837317,61.85994100570679,0.06886391205225273,1739137720.2837331,61.85994100570679,3.13322403603461,1739137720.2837346,61.85994100570679,2.305954672412955 +1739137720.3036745,61.88994097709656,9.36127866172958,1739137720.3036764,61.88994097709656,0.10443238647325348,1739137720.303679,61.88994097709656,103.04733036933132,1739137720.3036814,61.88994097709656,1.3414888097739222,1739137720.3036826,61.88994097709656,0.043,1739137720.303684,61.88994097709656,-3.133932704128393,1739137720.3036854,61.88994097709656,0.1201538372278813,1739137720.3036866,61.88994097709656,0.028692220483963065,1739137720.3036876,61.88994097709656,2.382687844745418,1739137720.3036892,61.88994097709656,0.0,1739137720.3036902,61.88994097709656,0.06946443395801913,1739137720.3036916,61.88994097709656,3.13427031429038,1739137720.3036926,61.88994097709656,2.3135093737425194 +1739137720.3235054,61.90994095802307,9.36127866172958,1739137720.3235073,61.90994095802307,0.10443238647325348,1739137720.3235097,61.90994095802307,103.04733036933132,1739137720.323512,61.90994095802307,1.3414888097739222,1739137720.323513,61.90994095802307,0.043,1739137720.3235147,61.90994095802307,-3.133932704128393,1739137720.323516,61.90994095802307,0.1201538372278813,1739137720.3235173,61.90994095802307,0.028692220483963065,1739137720.3235185,61.90994095802307,2.382687844745418,1739137720.32352,61.90994095802307,0.0,1739137720.3235211,61.90994095802307,0.06917847100289842,1739137720.3235223,61.90994095802307,3.13427031429038,1739137720.3235235,61.90994095802307,2.3135093737425194 +1739137720.346178,61.929940938949585,9.36127866172958,1739137720.3461816,61.929940938949585,0.10443238647325348,1739137720.3461862,61.929940938949585,103.04733036933132,1739137720.3461914,61.929940938949585,1.3414888097739222,1739137720.3461945,61.929940938949585,0.043,1739137720.346198,61.929940938949585,-3.133932704128393,1739137720.3462014,61.929940938949585,0.1201538372278813,1739137720.346205,61.929940938949585,0.028692220483963065,1739137720.346208,61.929940938949585,2.382687844745418,1739137720.3462117,61.929940938949585,0.0,1739137720.3462148,61.929940938949585,0.06917847100289842,1739137720.3462183,61.929940938949585,3.13427031429038,1739137720.3462217,61.929940938949585,2.3135093737425194 +1739137720.363587,61.9499409198761,9.36127866172958,1739137720.363589,61.9499409198761,0.10443238647325348,1739137720.3635917,61.9499409198761,103.04733036933132,1739137720.3635945,61.9499409198761,1.3414888097739222,1739137720.3635957,61.9499409198761,0.043,1739137720.3635974,61.9499409198761,-3.133932704128393,1739137720.3635986,61.9499409198761,0.1201538372278813,1739137720.3635998,61.9499409198761,0.028692220483963065,1739137720.3636017,61.9499409198761,2.382687844745418,1739137720.3636029,61.9499409198761,0.0,1739137720.3636043,61.9499409198761,0.06917847100289842,1739137720.3636057,61.9499409198761,3.13427031429038,1739137720.363607,61.9499409198761,2.3135093737425194 +1739137720.3962147,61.96994090080261,9.36127866172958,1739137720.3962243,61.96994090080261,0.10443238647325348,1739137720.3962348,61.96994090080261,103.04733036933132,1739137720.396245,61.96994090080261,1.3414888097739222,1739137720.3962493,61.96994090080261,0.043,1739137720.3962557,61.96994090080261,-3.133932704128393,1739137720.396261,61.96994090080261,0.1201538372278813,1739137720.3962655,61.96994090080261,0.028692220483963065,1739137720.39627,61.96994090080261,2.382687844745418,1739137720.3962758,61.96994090080261,0.0,1739137720.3962803,61.96994090080261,0.06917847100289842,1739137720.3962858,61.96994090080261,3.13427031429038,1739137720.3962903,61.96994090080261,2.3135093737425194 +1739137720.415341,61.989940881729126,9.106419783381085,1739137720.4153495,61.989940881729126,0.10617729879779869,1739137720.4153607,61.989940881729126,103.32986159999768,1739137720.415374,61.989940881729126,1.0362727453296539,1739137720.4153814,61.989940881729126,0.04580823835422416,1739137720.4153912,61.989940881729126,-3.1341122527813514,1739137720.4154,61.989940881729126,0.11101627445338526,1739137720.4154084,61.989940881729126,0.026180602832051127,1739137720.4154172,61.989940881729126,2.391412563466832,1739137720.4154258,61.989940881729126,0.0,1739137720.4154346,61.989940881729126,0.07138589456033344,1739137720.4154434,61.989940881729126,3.1353165925461495,1739137720.4154522,61.989940881729126,2.3210778235065654 +1739137720.4282103,62.00994086265564,9.106419783381085,1739137720.428215,62.00994086265564,0.10617729879779869,1739137720.428221,62.00994086265564,103.32986159999768,1739137720.428228,62.00994086265564,1.0362727453296539,1739137720.4282317,62.00994086265564,0.04580823835422416,1739137720.4282367,62.00994086265564,-3.1341122527813514,1739137720.4282413,62.00994086265564,0.11101627445338526,1739137720.4282458,62.00994086265564,0.026180602832051127,1739137720.4282503,62.00994086265564,2.391412563466832,1739137720.428255,62.00994086265564,0.0,1739137720.4282596,62.00994086265564,0.07033473996026673,1739137720.4282641,62.00994086265564,3.1353165925461495,1739137720.428269,62.00994086265564,2.3210778235065654 +1739137720.4466379,62.02994084358215,9.106419783381085,1739137720.4466412,62.02994084358215,0.10617729879779869,1739137720.4466453,62.02994084358215,103.32986159999768,1739137720.4466505,62.02994084358215,1.0362727453296539,1739137720.4466531,62.02994084358215,0.04580823835422416,1739137720.4466567,62.02994084358215,-3.1341122527813514,1739137720.44666,62.02994084358215,0.11101627445338526,1739137720.4466631,62.02994084358215,0.026180602832051127,1739137720.4466665,62.02994084358215,2.391412563466832,1739137720.4466696,62.02994084358215,0.0,1739137720.446673,62.02994084358215,0.07033473996026673,1739137720.4466765,62.02994084358215,3.1353165925461495,1739137720.4466796,62.02994084358215,2.3210778235065654 +1739137720.4659011,62.03994083404541,9.106419783381085,1739137720.4659045,62.03994083404541,0.10617729879779869,1739137720.4659088,62.03994083404541,103.32986159999768,1739137720.4659135,62.03994083404541,1.0362727453296539,1739137720.4659164,62.03994083404541,0.04580823835422416,1739137720.46592,62.03994083404541,-3.1341122527813514,1739137720.465923,62.03994083404541,0.11101627445338526,1739137720.4659264,62.03994083404541,0.026180602832051127,1739137720.4659295,62.03994083404541,2.391412563466832,1739137720.465933,62.03994083404541,0.0,1739137720.4659362,62.03994083404541,0.07033473996026673,1739137720.4659395,62.03994083404541,3.1353165925461495,1739137720.4659429,62.03994083404541,2.3210778235065654 +1739137720.4857354,62.059940814971924,9.106419783381085,1739137720.485739,62.059940814971924,0.10617729879779869,1739137720.4857433,62.059940814971924,103.32986159999768,1739137720.4857488,62.059940814971924,1.0362727453296539,1739137720.4857516,62.059940814971924,0.04580823835422416,1739137720.4857554,62.059940814971924,-3.1341122527813514,1739137720.4857588,62.059940814971924,0.11101627445338526,1739137720.4857621,62.059940814971924,0.026180602832051127,1739137720.4857812,62.059940814971924,2.391412563466832,1739137720.4857845,62.059940814971924,0.0,1739137720.4857879,62.059940814971924,0.07033473996026673,1739137720.4857912,62.059940814971924,3.1353165925461495,1739137720.4857945,62.059940814971924,2.3210778235065654 +1739137720.5057623,62.07994079589844,9.106419783381085,1739137720.5057654,62.07994079589844,0.10617729879779869,1739137720.5057697,62.07994079589844,103.32986159999768,1739137720.5057745,62.07994079589844,1.0362727453296539,1739137720.5057774,62.07994079589844,0.04580823835422416,1739137720.505781,62.07994079589844,-3.1341122527813514,1739137720.5057843,62.07994079589844,0.11101627445338526,1739137720.5057874,62.07994079589844,0.026180602832051127,1739137720.505791,62.07994079589844,2.391412563466832,1739137720.505794,62.07994079589844,0.0,1739137720.5057974,62.07994079589844,0.07033473996026673,1739137720.5058007,62.07994079589844,3.1353165925461495,1739137720.5058038,62.07994079589844,2.3210778235065654 +1739137720.525959,62.10994076728821,8.85071782279183,1739137720.5259626,62.10994076728821,0.10766043613507659,1739137720.5259666,62.10994076728821,103.71736693874037,1739137720.5259714,62.10994076728821,0.6261203049776967,1739137720.5259743,62.10994076728821,0.06371633591111849,1739137720.5259778,62.10994076728821,-3.1362496952301187,1739137720.5259812,62.10994076728821,0.08695616174063246,1739137720.5259843,62.10994076728821,0.019744384511977735,1739137720.5259874,62.10994076728821,2.4145387309343733,1739137720.5259907,62.10994076728821,0.0,1739137720.5259943,62.10994076728821,0.09974568464612812,1739137720.5259976,62.10994076728821,3.136362870801919,1739137720.5260007,62.10994076728821,2.328798265039636 +1739137720.5460696,62.119940757751465,8.85071782279183,1739137720.5460734,62.119940757751465,0.10766043613507659,1739137720.5460775,62.119940757751465,103.71736693874037,1739137720.5460823,62.119940757751465,0.6261203049776967,1739137720.5460846,62.119940757751465,0.06371633591111849,1739137720.5460885,62.119940757751465,-3.1362496952301187,1739137720.5460908,62.119940757751465,0.08695616174063246,1739137720.546094,62.119940757751465,0.019744384511977735,1739137720.5460985,62.119940757751465,2.4145387309343733,1739137720.5461018,62.119940757751465,0.0,1739137720.5461051,62.119940757751465,0.08574046589473738,1739137720.546109,62.119940757751465,3.136362870801919,1739137720.5461123,62.119940757751465,2.328798265039636 +1739137720.5651577,62.13994073867798,8.85071782279183,1739137720.565161,62.13994073867798,0.10766043613507659,1739137720.5651658,62.13994073867798,103.71736693874037,1739137720.5651705,62.13994073867798,0.6261203049776967,1739137720.565173,62.13994073867798,0.06371633591111849,1739137720.5651758,62.13994073867798,-3.1362496952301187,1739137720.5651784,62.13994073867798,0.08695616174063246,1739137720.5651803,62.13994073867798,0.019744384511977735,1739137720.5651824,62.13994073867798,2.4145387309343733,1739137720.5651848,62.13994073867798,0.0,1739137720.5651867,62.13994073867798,0.08574046589473738,1739137720.56519,62.13994073867798,3.136362870801919,1739137720.5651925,62.13994073867798,2.328798265039636 +1739137720.5859537,62.16994071006775,8.85071782279183,1739137720.585956,62.16994071006775,0.10766043613507659,1739137720.585959,62.16994071006775,103.71736693874037,1739137720.5859616,62.16994071006775,0.6261203049776967,1739137720.585963,62.16994071006775,0.06371633591111849,1739137720.5859644,62.16994071006775,-3.1362496952301187,1739137720.5859659,62.16994071006775,0.08695616174063246,1739137720.585967,62.16994071006775,0.019744384511977735,1739137720.5859685,62.16994071006775,2.4145387309343733,1739137720.5859702,62.16994071006775,0.0,1739137720.5859714,62.16994071006775,0.08574046589473738,1739137720.5859728,62.16994071006775,3.136362870801919,1739137720.585974,62.16994071006775,2.328798265039636 +1739137720.6037421,62.18994069099426,8.85071782279183,1739137720.603745,62.18994069099426,0.10766043613507659,1739137720.6037478,62.18994069099426,103.71736693874037,1739137720.6037507,62.18994069099426,0.6261203049776967,1739137720.603752,62.18994069099426,0.06371633591111849,1739137720.6037538,62.18994069099426,-3.1362496952301187,1739137720.603755,62.18994069099426,0.08695616174063246,1739137720.6037562,62.18994069099426,0.019744384511977735,1739137720.6037576,62.18994069099426,2.4145387309343733,1739137720.6037593,62.18994069099426,0.0,1739137720.6037607,62.18994069099426,0.08574046589473738,1739137720.603762,62.18994069099426,3.136362870801919,1739137720.603764,62.18994069099426,2.328798265039636 +1739137720.6236832,62.209940671920776,8.59408624138612,1739137720.6236856,62.209940671920776,0.10888043388978907,1739137720.6236885,62.209940671920776,104.46746487793054,1739137720.623691,62.209940671920776,-0.15193920810812456,1739137720.6236923,62.209940671920776,0.065,1739137720.6236942,62.209940671920776,-3.136575509978627,1739137720.6236956,62.209940671920776,0.08046898027653002,1739137720.6236966,62.209940671920776,0.01615783275939367,1739137720.623698,62.209940671920776,2.4208122873137974,1739137720.6236994,62.209940671920776,0.0,1739137720.6237006,62.209940671920776,0.07983881156339305,1739137720.623702,62.209940671920776,3.1374091490576888,1739137720.6237032,62.209940671920776,2.3381631627601758 +1739137720.643648,62.22994065284729,8.59408624138612,1739137720.6436503,62.22994065284729,0.10888043388978907,1739137720.6436534,62.22994065284729,104.46746487793054,1739137720.643656,62.22994065284729,-0.15193920810812456,1739137720.6436574,62.22994065284729,0.065,1739137720.6436594,62.22994065284729,-3.136575509978627,1739137720.6436608,62.22994065284729,0.08046898027653002,1739137720.643662,62.22994065284729,0.01615783275939367,1739137720.6436634,62.22994065284729,2.4208122873137974,1739137720.6436648,62.22994065284729,0.0,1739137720.6436665,62.22994065284729,0.08264912455362161,1739137720.6436677,62.22994065284729,3.1374091490576888,1739137720.643669,62.22994065284729,2.3381631627601758 +1739137720.6698391,62.249940633773804,8.59408624138612,1739137720.669848,62.249940633773804,0.10888043388978907,1739137720.6698577,62.249940633773804,104.46746487793054,1739137720.6698673,62.249940633773804,-0.15193920810812456,1739137720.6698718,62.249940633773804,0.065,1739137720.6698785,62.249940633773804,-3.136575509978627,1739137720.6698837,62.249940633773804,0.08046898027653002,1739137720.669888,62.249940633773804,0.01615783275939367,1739137720.6698925,62.249940633773804,2.4208122873137974,1739137720.6698983,62.249940633773804,0.0,1739137720.6699028,62.249940633773804,0.08264912455362161,1739137720.669908,62.249940633773804,3.1374091490576888,1739137720.6699123,62.249940633773804,2.3381631627601758 +1739137720.6898909,62.26994061470032,8.59408624138612,1739137720.689899,62.26994061470032,0.10888043388978907,1739137720.6899087,62.26994061470032,104.46746487793054,1739137720.6899185,62.26994061470032,-0.15193920810812456,1739137720.6899235,62.26994061470032,0.065,1739137720.6899295,62.26994061470032,-3.136575509978627,1739137720.6899345,62.26994061470032,0.08046898027653002,1739137720.6899395,62.26994061470032,0.01615783275939367,1739137720.689944,62.26994061470032,2.4208122873137974,1739137720.6899495,62.26994061470032,0.0,1739137720.6899543,62.26994061470032,0.08264912455362161,1739137720.6899595,62.26994061470032,3.1374091490576888,1739137720.689964,62.26994061470032,2.3381631627601758 +1739137720.7096016,62.28994059562683,8.59408624138612,1739137720.7096097,62.28994059562683,0.10888043388978907,1739137720.7096195,62.28994059562683,104.46746487793054,1739137720.7096298,62.28994059562683,-0.15193920810812456,1739137720.7096345,62.28994059562683,0.065,1739137720.7096407,62.28994059562683,-3.136575509978627,1739137720.7096455,62.28994059562683,0.08046898027653002,1739137720.7096503,62.28994059562683,0.01615783275939367,1739137720.7096548,62.28994059562683,2.4208122873137974,1739137720.70966,62.28994059562683,0.0,1739137720.709665,62.28994059562683,0.08264912455362161,1739137720.7096698,62.28994059562683,3.1374091490576888,1739137720.7096746,62.28994059562683,2.3381631627601758 +1739137720.7300968,62.29994058609009,8.59408624138612,1739137720.7301047,62.29994058609009,0.10888043388978907,1739137720.730114,62.29994058609009,104.46746487793054,1739137720.7301233,62.29994058609009,-0.15193920810812456,1739137720.7301278,62.29994058609009,0.065,1739137720.7301335,62.29994058609009,-3.136575509978627,1739137720.7301383,62.29994058609009,0.08046898027653002,1739137720.7301433,62.29994058609009,0.01615783275939367,1739137720.7301476,62.29994058609009,2.4208122873137974,1739137720.7301528,62.29994058609009,0.0,1739137720.7301576,62.29994058609009,0.08264912455362161,1739137720.7301626,62.29994058609009,3.1374091490576888,1739137720.7301676,62.29994058609009,2.3381631627601758 +1739137720.756775,62.32994055747986,8.336442140967232,1739137720.756799,62.32994055747986,0.10983567715461184,1739137720.7568066,62.32994055747986,104.49709490472198,1739137720.7568133,62.32994055747986,-0.20854471938940078,1739137720.7568166,62.32994055747986,0.065,1739137720.7568204,62.32994055747986,-3.1363456863990224,1739137720.7568238,62.32994055747986,0.07164296984928493,1739137720.7568274,62.32994055747986,0.015070455817452522,1739137720.7568305,62.32994055747986,2.4293738370829794,1739137720.756834,62.32994055747986,0.0,1739137720.7568376,62.32994055747986,0.08182768361002553,1739137720.756841,62.32994055747986,3.1384554273134584,1739137720.7568443,62.32994055747986,2.3471549909234577 +1739137720.777851,62.34994053840637,8.336442140967232,1739137720.7778573,62.34994053840637,0.10983567715461184,1739137720.7778642,62.34994053840637,104.49709490472198,1739137720.7778707,62.34994053840637,-0.20854471938940078,1739137720.7778742,62.34994053840637,0.065,1739137720.777878,62.34994053840637,-3.1363456863990224,1739137720.7778816,62.34994053840637,0.07164296984928493,1739137720.777885,62.34994053840637,0.015070455817452522,1739137720.7778878,62.34994053840637,2.4293738370829794,1739137720.7778916,62.34994053840637,0.0,1739137720.7778952,62.34994053840637,0.08221884615952169,1739137720.7778988,62.34994053840637,3.1384554273134584,1739137720.7779021,62.34994053840637,2.3471549909234577 +1739137720.7951984,62.369940519332886,8.336442140967232,1739137720.7952046,62.369940519332886,0.10983567715461184,1739137720.795212,62.369940519332886,104.49709490472198,1739137720.795219,62.369940519332886,-0.20854471938940078,1739137720.7952228,62.369940519332886,0.065,1739137720.7952268,62.369940519332886,-3.1363456863990224,1739137720.7952302,62.369940519332886,0.07164296984928493,1739137720.7952335,62.369940519332886,0.015070455817452522,1739137720.7952366,62.369940519332886,2.4293738370829794,1739137720.7952402,62.369940519332886,0.0,1739137720.7952435,62.369940519332886,0.08221884615952169,1739137720.795247,62.369940519332886,3.1384554273134584,1739137720.7952504,62.369940519332886,2.3471549909234577 +1739137720.816266,62.3899405002594,8.336442140967232,1739137720.8162715,62.3899405002594,0.10983567715461184,1739137720.8162785,62.3899405002594,104.49709490472198,1739137720.8162854,62.3899405002594,-0.20854471938940078,1739137720.8162885,62.3899405002594,0.065,1739137720.8162925,62.3899405002594,-3.1363456863990224,1739137720.8162959,62.3899405002594,0.07164296984928493,1739137720.8162992,62.3899405002594,0.015070455817452522,1739137720.8163025,62.3899405002594,2.4293738370829794,1739137720.8163064,62.3899405002594,0.0,1739137720.8163097,62.3899405002594,0.08221884615952169,1739137720.8163133,62.3899405002594,3.1384554273134584,1739137720.8163166,62.3899405002594,2.3471549909234577 +1739137720.8356547,62.40994048118591,8.336442140967232,1739137720.8356607,62.40994048118591,0.10983567715461184,1739137720.8356676,62.40994048118591,104.49709490472198,1739137720.8356743,62.40994048118591,-0.20854471938940078,1739137720.8356776,62.40994048118591,0.065,1739137720.8356814,62.40994048118591,-3.1363456863990224,1739137720.8356848,62.40994048118591,0.07164296984928493,1739137720.835688,62.40994048118591,0.015070455817452522,1739137720.8356912,62.40994048118591,2.4293738370829794,1739137720.8356948,62.40994048118591,0.0,1739137720.8356981,62.40994048118591,0.08221884615952169,1739137720.8357017,62.40994048118591,3.1384554273134584,1739137720.835705,62.40994048118591,2.3471549909234577 +1739137720.8560522,62.42994046211243,8.077806503329418,1739137720.8560586,62.42994046211243,0.11052398959722698,1739137720.8560653,62.42994046211243,104.52683869136277,1739137720.8560724,62.42994046211243,-0.26524149273058795,1739137720.8560758,62.42994046211243,0.065,1739137720.8560803,62.42994046211243,-3.1361361899780946,1739137720.8560836,62.42994046211243,0.06296875706152567,1739137720.856087,62.42994046211243,0.013894752546595817,1739137720.85609,62.42994046211243,2.437817639521304,1739137720.8560936,62.42994046211243,0.0,1739137720.8560975,62.42994046211243,0.0811869315365411,1739137720.856101,62.42994046211243,3.139501705569228,1739137720.8561044,62.42994046211243,2.356139319823588 +1739137720.8753152,62.44994044303894,8.077806503329418,1739137720.8753211,62.44994044303894,0.11052398959722698,1739137720.8753283,62.44994044303894,104.52683869136277,1739137720.875335,62.44994044303894,-0.26524149273058795,1739137720.8753383,62.44994044303894,0.065,1739137720.8753424,62.44994044303894,-3.1361361899780946,1739137720.8753462,62.44994044303894,0.06296875706152567,1739137720.8753493,62.44994044303894,0.013894752546595817,1739137720.8753526,62.44994044303894,2.437817639521304,1739137720.8753562,62.44994044303894,0.0,1739137720.8753598,62.44994044303894,0.081678319697716,1739137720.8753633,62.44994044303894,3.139501705569228,1739137720.875367,62.44994044303894,2.356139319823588 +1739137720.8951726,62.469940423965454,8.077806503329418,1739137720.8951788,62.469940423965454,0.11052398959722698,1739137720.8951857,62.469940423965454,104.52683869136277,1739137720.8951924,62.469940423965454,-0.26524149273058795,1739137720.895196,62.469940423965454,0.065,1739137720.8952,62.469940423965454,-3.1361361899780946,1739137720.8952038,62.469940423965454,0.06296875706152567,1739137720.8952127,62.469940423965454,0.013894752546595817,1739137720.8952236,62.469940423965454,2.437817639521304,1739137720.895233,62.469940423965454,0.0,1739137720.895245,62.469940423965454,0.081678319697716,1739137720.8952532,62.469940423965454,3.139501705569228,1739137720.895262,62.469940423965454,2.356139319823588 +1739137720.9176073,62.48994040489197,8.077806503329418,1739137720.9176133,62.48994040489197,0.11052398959722698,1739137720.9176207,62.48994040489197,104.52683869136277,1739137720.9176276,62.48994040489197,-0.26524149273058795,1739137720.917631,62.48994040489197,0.065,1739137720.9176354,62.48994040489197,-3.1361361899780946,1739137720.9176385,62.48994040489197,0.06296875706152567,1739137720.9176419,62.48994040489197,0.013894752546595817,1739137720.9176452,62.48994040489197,2.437817639521304,1739137720.9176493,62.48994040489197,0.0,1739137720.9176524,62.48994040489197,0.081678319697716,1739137720.9176564,62.48994040489197,3.139501705569228,1739137720.9176598,62.48994040489197,2.356139319823588 +1739137720.9360063,62.50994038581848,8.077806503329418,1739137720.9360127,62.50994038581848,0.11052398959722698,1739137720.9360192,62.50994038581848,104.52683869136277,1739137720.9360259,62.50994038581848,-0.26524149273058795,1739137720.9360292,62.50994038581848,0.065,1739137720.9360335,62.50994038581848,-3.1361361899780946,1739137720.936037,62.50994038581848,0.06296875706152567,1739137720.9360406,62.50994038581848,0.013894752546595817,1739137720.9360437,62.50994038581848,2.437817639521304,1739137720.9360476,62.50994038581848,0.0,1739137720.936051,62.50994038581848,0.081678319697716,1739137720.9360547,62.50994038581848,3.139501705569228,1739137720.9360583,62.50994038581848,2.356139319823588 +1739137720.9553432,62.529940366744995,8.077806503329418,1739137720.955348,62.529940366744995,0.11052398959722698,1739137720.9553535,62.529940366744995,104.52683869136277,1739137720.9553587,62.529940366744995,-0.26524149273058795,1739137720.9553614,62.529940366744995,0.065,1739137720.9553647,62.529940366744995,-3.1361361899780946,1739137720.9553673,62.529940366744995,0.06296875706152567,1739137720.95537,62.529940366744995,0.013894752546595817,1739137720.9553726,62.529940366744995,2.437817639521304,1739137720.9553757,62.529940366744995,0.0,1739137720.9553783,62.529940366744995,0.081678319697716,1739137720.9553812,62.529940366744995,3.139501705569228,1739137720.9553838,62.529940366744995,2.356139319823588 +1739137720.9741812,62.54994034767151,7.818184374990583,1739137720.974185,62.54994034767151,0.11094328995086933,1739137720.9741893,62.54994034767151,104.65835305987603,1739137720.9741933,62.54994034767151,-0.4235546649111721,1739137720.9741955,62.54994034767151,0.065,1739137720.974198,62.54994034767151,-3.136018245828698,1739137720.9742,62.54994034767151,0.05455315889938226,1739137720.9742022,62.54994034767151,0.012335519886202009,1739137720.974204,62.54994034767151,2.446037744638104,1739137720.9742064,62.54994034767151,0.0,1739137720.9742084,62.54994034767151,0.08031746287803215,1739137720.9742105,62.54994034767151,3.1405479838249977,1739137720.974213,62.54994034767151,2.3650722543793616 +1739137720.9932451,62.56994032859802,7.818184374990583,1739137720.9932482,62.56994032859802,0.11094328995086933,1739137720.993252,62.56994032859802,104.65835305987603,1739137720.9932559,62.56994032859802,-0.4235546649111721,1739137720.9932578,62.56994032859802,0.065,1739137720.9932604,62.56994032859802,-3.136018245828698,1739137720.9932623,62.56994032859802,0.05455315889938226,1739137720.9932642,62.56994032859802,0.012335519886202009,1739137720.9932659,62.56994032859802,2.446037744638104,1739137720.9932683,62.56994032859802,0.0,1739137720.9932697,62.56994032859802,0.08096549025874245,1739137720.9932718,62.56994032859802,3.1405479838249977,1739137720.9932735,62.56994032859802,2.3650722543793616 +1739137721.012564,62.589940309524536,7.818184374990583,1739137721.0125668,62.589940309524536,0.11094328995086933,1739137721.0125701,62.589940309524536,104.65835305987603,1739137721.0125732,62.589940309524536,-0.4235546649111721,1739137721.0125747,62.589940309524536,0.065,1739137721.0125766,62.589940309524536,-3.136018245828698,1739137721.0125782,62.589940309524536,0.05455315889938226,1739137721.0125797,62.589940309524536,0.012335519886202009,1739137721.012581,62.589940309524536,2.446037744638104,1739137721.012583,62.589940309524536,0.0,1739137721.0125842,62.589940309524536,0.08096549025874245,1739137721.0125856,62.589940309524536,3.1405479838249977,1739137721.0125873,62.589940309524536,2.3650722543793616 +1739137721.033151,62.60994029045105,7.818184374990583,1739137721.0331533,62.60994029045105,0.11094328995086933,1739137721.0331562,62.60994029045105,104.65835305987603,1739137721.033159,62.60994029045105,-0.4235546649111721,1739137721.0331602,62.60994029045105,0.065,1739137721.0331616,62.60994029045105,-3.136018245828698,1739137721.0331633,62.60994029045105,0.05455315889938226,1739137721.0331645,62.60994029045105,0.012335519886202009,1739137721.0331655,62.60994029045105,2.446037744638104,1739137721.0331674,62.60994029045105,0.0,1739137721.0331686,62.60994029045105,0.08096549025874245,1739137721.0331702,62.60994029045105,3.1405479838249977,1739137721.0331714,62.60994029045105,2.3650722543793616 +1739137721.0524976,62.62994027137756,7.818184374990583,1739137721.0525005,62.62994027137756,0.11094328995086933,1739137721.0525038,62.62994027137756,104.65835305987603,1739137721.0525067,62.62994027137756,-0.4235546649111721,1739137721.0525079,62.62994027137756,0.065,1739137721.0525098,62.62994027137756,-3.136018245828698,1739137721.0525112,62.62994027137756,0.05455315889938226,1739137721.0525124,62.62994027137756,0.012335519886202009,1739137721.0525138,62.62994027137756,2.446037744638104,1739137721.0525157,62.62994027137756,0.0,1739137721.0525172,62.62994027137756,0.08096549025874245,1739137721.0525188,62.62994027137756,3.1405479838249977,1739137721.05252,62.62994027137756,2.3650722543793616 +1739137721.0721025,62.64994025230408,7.5575837211401,1739137721.0721052,62.64994025230408,0.11109151065787515,1739137721.072108,62.64994025230408,104.79859942113488,1739137721.0721107,62.64994025230408,-0.5903467711643837,1739137721.0721118,62.64994025230408,0.065,1739137721.072114,62.64994025230408,-3.135935877421765,1739137721.0721152,62.64994025230408,0.0460784047851566,1739137721.0721164,62.64994025230408,0.010660517689798966,1739137721.0721178,62.64994025230408,2.4543436421480047,1739137721.0721192,62.64994025230408,0.0,1739137721.0721207,62.64994025230408,0.07992945640164716,1739137721.072122,62.64994025230408,3.1415942620807673,1739137721.0721233,62.64994025230408,2.373920836044148 +1739137721.0924404,62.66994023323059,7.5575837211401,1739137721.0924425,62.66994023323059,0.11109151065787515,1739137721.0924454,62.66994023323059,104.79859942113488,1739137721.0924482,62.66994023323059,-0.5903467711643837,1739137721.0924494,62.66994023323059,0.065,1739137721.0924513,62.66994023323059,-3.135935877421765,1739137721.0924528,62.66994023323059,0.0460784047851566,1739137721.0924542,62.66994023323059,0.010660517689798966,1739137721.0924554,62.66994023323059,2.4543436421480047,1739137721.092457,62.66994023323059,0.0,1739137721.0924582,62.66994023323059,0.08042280610385655,1739137721.0924597,62.66994023323059,3.1415942620807673,1739137721.092461,62.66994023323059,2.373920836044148 +1739137721.1122391,62.689940214157104,7.5575837211401,1739137721.1122417,62.689940214157104,0.11109151065787515,1739137721.1122444,62.689940214157104,104.79859942113488,1739137721.112247,62.689940214157104,-0.5903467711643837,1739137721.1122484,62.689940214157104,0.065,1739137721.11225,62.689940214157104,-3.135935877421765,1739137721.1122513,62.689940214157104,0.0460784047851566,1739137721.112253,62.689940214157104,0.010660517689798966,1739137721.112254,62.689940214157104,2.4543436421480047,1739137721.1122556,62.689940214157104,0.0,1739137721.1122568,62.689940214157104,0.08042280610385655,1739137721.112258,62.689940214157104,3.1415942620807673,1739137721.1122594,62.689940214157104,2.373920836044148 +1739137721.1322122,62.70994019508362,7.5575837211401,1739137721.1322145,62.70994019508362,0.11109151065787515,1739137721.1322172,62.70994019508362,104.79859942113488,1739137721.1322196,62.70994019508362,-0.5903467711643837,1739137721.1322212,62.70994019508362,0.065,1739137721.1322227,62.70994019508362,-3.135935877421765,1739137721.132224,62.70994019508362,0.0460784047851566,1739137721.1322253,62.70994019508362,0.010660517689798966,1739137721.1322265,62.70994019508362,2.4543436421480047,1739137721.1322281,62.70994019508362,0.0,1739137721.1322293,62.70994019508362,0.08042280610385655,1739137721.132231,62.70994019508362,3.1415942620807673,1739137721.1322324,62.70994019508362,2.373920836044148 +1739137721.1524959,62.72994017601013,7.5575837211401,1739137721.1524982,62.72994017601013,0.11109151065787515,1739137721.152501,62.72994017601013,104.79859942113488,1739137721.1525035,62.72994017601013,-0.5903467711643837,1739137721.1525052,62.72994017601013,0.065,1739137721.1525068,62.72994017601013,-3.135935877421765,1739137721.1525083,62.72994017601013,0.0460784047851566,1739137721.1525097,62.72994017601013,0.010660517689798966,1739137721.152511,62.72994017601013,2.4543436421480047,1739137721.1525126,62.72994017601013,0.0,1739137721.1525137,62.72994017601013,0.08042280610385655,1739137721.1525154,62.72994017601013,3.1415942620807673,1739137721.1525166,62.72994017601013,2.373920836044148 +1739137721.1741061,62.749940156936646,7.5575837211401,1739137721.1741097,62.749940156936646,0.11109151065787515,1739137721.1741142,62.749940156936646,104.79859942113488,1739137721.1741195,62.749940156936646,-0.5903467711643837,1739137721.1741226,62.749940156936646,0.065,1739137721.1741264,62.749940156936646,-3.135935877421765,1739137721.17413,62.749940156936646,0.0460784047851566,1739137721.1741333,62.749940156936646,0.010660517689798966,1739137721.1741366,62.749940156936646,2.4543436421480047,1739137721.1741402,62.749940156936646,0.0,1739137721.1741438,62.749940156936646,0.08042280610385655,1739137721.1741474,62.749940156936646,3.1415942620807673,1739137721.174151,62.749940156936646,2.373920836044148 +1739137721.192307,62.76994013786316,7.296012370398559,1739137721.1923091,62.76994013786316,0.11096660783061196,1739137721.1923122,62.76994013786316,105.2201403041548,1739137721.1923149,62.76994013786316,-1.0382688043883017,1739137721.1923165,62.76994013786316,0.065,1739137721.192318,62.76994013786316,-3.1360773438966016,1739137721.1923196,62.76994013786316,0.0372332014050244,1739137721.192321,62.76994013786316,0.008233244216650464,1739137721.1923223,62.76994013786316,2.4630426895138826,1739137721.192324,62.76994013786316,0.0,1739137721.1923254,62.76994013786316,0.0802420735904506,1739137721.192327,62.76994013786316,3.142640540336537,1739137721.1923282,62.76994013786316,2.382714552778818 +1739137721.2124245,62.78994011878967,7.296012370398559,1739137721.2124267,62.78994011878967,0.11096660783061196,1739137721.2124295,62.78994011878967,105.2201403041548,1739137721.2124324,62.78994011878967,-1.0382688043883017,1739137721.2124343,62.78994011878967,0.065,1739137721.2124357,62.78994011878967,-3.1360773438966016,1739137721.2124372,62.78994011878967,0.0372332014050244,1739137721.2124386,62.78994011878967,0.008233244216650464,1739137721.2124398,62.78994011878967,2.4630426895138826,1739137721.2124417,62.78994011878967,0.0,1739137721.2124429,62.78994011878967,0.08032813673506478,1739137721.212444,62.78994011878967,3.142640540336537,1739137721.2124455,62.78994011878967,2.382714552778818 +1739137721.2453573,62.80994009971619,7.296012370398559,1739137721.2453663,62.80994009971619,0.11096660783061196,1739137721.2453766,62.80994009971619,105.2201403041548,1739137721.2453861,62.80994009971619,-1.0382688043883017,1739137721.245391,62.80994009971619,0.065,1739137721.2453969,62.80994009971619,-3.1360773438966016,1739137721.2454016,62.80994009971619,0.0372332014050244,1739137721.245406,62.80994009971619,0.008233244216650464,1739137721.2454104,62.80994009971619,2.4630426895138826,1739137721.2454164,62.80994009971619,0.0,1739137721.2454214,62.80994009971619,0.08032813673506478,1739137721.245427,62.80994009971619,3.142640540336537,1739137721.2454321,62.80994009971619,2.382714552778818 +1739137721.283892,62.849940061569214,7.296012370398559,1739137721.2839005,62.849940061569214,0.11096660783061196,1739137721.283911,62.849940061569214,105.2201403041548,1739137721.2839205,62.849940061569214,-1.0382688043883017,1739137721.2839258,62.849940061569214,0.065,1739137721.2839317,62.849940061569214,-3.1360773438966016,1739137721.2839365,62.849940061569214,0.0372332014050244,1739137721.283941,62.849940061569214,0.008233244216650464,1739137721.2839456,62.849940061569214,2.4630426895138826,1739137721.2839508,62.849940061569214,0.0,1739137721.2839556,62.849940061569214,0.08032813673506478,1739137721.283961,62.849940061569214,3.142640540336537,1739137721.2839656,62.849940061569214,2.382714552778818 +1739137721.3018677,62.86994004249573,7.033474479566305,1739137721.3018715,62.86994004249573,0.1105665558811113,1739137721.3018763,62.86994004249573,105.44931756029841,1739137721.3018806,62.86994004249573,-1.2937974205924045,1739137721.301883,62.86994004249573,0.065,1739137721.3018854,62.86994004249573,-3.136120741342349,1739137721.3018878,62.86994004249573,0.028127787331042223,1739137721.30189,62.86994004249573,0.006230281458488831,1739137721.3018918,62.86994004249573,2.472029855380325,1739137721.3018942,62.86994004249573,0.0,1739137721.301896,62.86994004249573,0.08071640625429087,1739137721.3018985,62.86994004249573,3.1436868185923066,1739137721.3019009,62.86994004249573,2.3914983394656453 +1739137721.3214793,62.88994002342224,7.033474479566305,1739137721.3214834,62.88994002342224,0.1105665558811113,1739137721.321488,62.88994002342224,105.44931756029841,1739137721.3214924,62.88994002342224,-1.2937974205924045,1739137721.321495,62.88994002342224,0.065,1739137721.3214982,62.88994002342224,-3.136120741342349,1739137721.3215008,62.88994002342224,0.028127787331042223,1739137721.3215032,62.88994002342224,0.006230281458488831,1739137721.3215058,62.88994002342224,2.472029855380325,1739137721.3215084,62.88994002342224,0.0,1739137721.3215106,62.88994002342224,0.08053151591467955,1739137721.3215132,62.88994002342224,3.1436868185923066,1739137721.3215156,62.88994002342224,2.3914983394656453 +1739137721.3404953,62.909940004348755,7.033474479566305,1739137721.3404982,62.909940004348755,0.1105665558811113,1739137721.3405015,62.909940004348755,105.44931756029841,1739137721.3405044,62.909940004348755,-1.2937974205924045,1739137721.3405058,62.909940004348755,0.065,1739137721.3405077,62.909940004348755,-3.136120741342349,1739137721.3405092,62.909940004348755,0.028127787331042223,1739137721.3405104,62.909940004348755,0.006230281458488831,1739137721.3405118,62.909940004348755,2.472029855380325,1739137721.3405135,62.909940004348755,0.0,1739137721.3405151,62.909940004348755,0.08053151591467955,1739137721.3405166,62.909940004348755,3.1436868185923066,1739137721.340518,62.909940004348755,2.3914983394656453 +1739137721.3597713,62.92993998527527,7.033474479566305,1739137721.3597734,62.92993998527527,0.1105665558811113,1739137721.3597758,62.92993998527527,105.44931756029841,1739137721.3597784,62.92993998527527,-1.2937974205924045,1739137721.3597796,62.92993998527527,0.065,1739137721.359781,62.92993998527527,-3.136120741342349,1739137721.3597825,62.92993998527527,0.028127787331042223,1739137721.3597836,62.92993998527527,0.006230281458488831,1739137721.3597848,62.92993998527527,2.472029855380325,1739137721.3597863,62.92993998527527,0.0,1739137721.3597875,62.92993998527527,0.08053151591467955,1739137721.3597891,62.92993998527527,3.1436868185923066,1739137721.35979,62.92993998527527,2.3914983394656453 +1739137721.3801928,62.94993996620178,7.033474479566305,1739137721.3801951,62.94993996620178,0.1105665558811113,1739137721.3801985,62.94993996620178,105.44931756029841,1739137721.3802006,62.94993996620178,-1.2937974205924045,1739137721.3802023,62.94993996620178,0.065,1739137721.3802037,62.94993996620178,-3.136120741342349,1739137721.3802054,62.94993996620178,0.028127787331042223,1739137721.3802063,62.94993996620178,0.006230281458488831,1739137721.3802075,62.94993996620178,2.472029855380325,1739137721.3802092,62.94993996620178,0.0,1739137721.3802102,62.94993996620178,0.08053151591467955,1739137721.3802118,62.94993996620178,3.1436868185923066,1739137721.3802133,62.94993996620178,2.3914983394656453 +1739137721.4006646,62.969939947128296,7.033474479566305,1739137721.4006672,62.969939947128296,0.1105665558811113,1739137721.4006698,62.969939947128296,105.44931756029841,1739137721.4006722,62.969939947128296,-1.2937974205924045,1739137721.4006739,62.969939947128296,0.065,1739137721.4006753,62.969939947128296,-3.136120741342349,1739137721.400677,62.969939947128296,0.028127787331042223,1739137721.4006782,62.969939947128296,0.006230281458488831,1739137721.4006793,62.969939947128296,2.472029855380325,1739137721.4006813,62.969939947128296,0.0,1739137721.4006824,62.969939947128296,0.08053151591467955,1739137721.4006839,62.969939947128296,3.1436868185923066,1739137721.400685,62.969939947128296,2.3914983394656453 +1739137721.4204965,62.98993992805481,6.76996842176044,1739137721.4204986,62.98993992805481,0.10988932681157326,1739137721.4205015,62.98993992805481,105.77898308815693,1739137721.420504,62.98993992805481,-1.6499251557544379,1739137721.4205055,62.98993992805481,0.065,1739137721.4205072,62.98993992805481,-3.136261362747917,1739137721.4205086,62.98993992805481,0.01844695089673042,1739137721.42051,62.98993992805481,0.003996593723761685,1739137721.4205112,62.98993992805481,2.4816209400160747,1739137721.4205124,62.98993992805481,0.0,1739137721.4205139,62.98993992805481,0.08200218260311065,1739137721.420515,62.98993992805481,3.1447330968480762,1739137721.4205165,62.98993992805481,2.400319075233485 +1739137721.4396493,63.00993990898132,6.76996842176044,1739137721.4396515,63.00993990898132,0.10988932681157326,1739137721.4396539,63.00993990898132,105.77898308815693,1739137721.4396565,63.00993990898132,-1.6499251557544379,1739137721.4396577,63.00993990898132,0.065,1739137721.4396594,63.00993990898132,-3.136261362747917,1739137721.4396605,63.00993990898132,0.01844695089673042,1739137721.4396617,63.00993990898132,0.003996593723761685,1739137721.439663,63.00993990898132,2.4816209400160747,1739137721.4396644,63.00993990898132,0.0,1739137721.4396656,63.00993990898132,0.08130186478258983,1739137721.439667,63.00993990898132,3.1447330968480762,1739137721.439668,63.00993990898132,2.400319075233485 +1739137721.45964,63.02993988990784,6.76996842176044,1739137721.459643,63.02993988990784,0.10988932681157326,1739137721.459646,63.02993988990784,105.77898308815693,1739137721.4596488,63.02993988990784,-1.6499251557544379,1739137721.45965,63.02993988990784,0.065,1739137721.459652,63.02993988990784,-3.136261362747917,1739137721.4596531,63.02993988990784,0.01844695089673042,1739137721.4596543,63.02993988990784,0.003996593723761685,1739137721.4596558,63.02993988990784,2.4816209400160747,1739137721.4596572,63.02993988990784,0.0,1739137721.4596584,63.02993988990784,0.08130186478258983,1739137721.45966,63.02993988990784,3.1447330968480762,1739137721.459661,63.02993988990784,2.400319075233485 +1739137721.4853811,63.04993987083435,6.76996842176044,1739137721.4853902,63.04993987083435,0.10988932681157326,1739137721.4854004,63.04993987083435,105.77898308815693,1739137721.48541,63.04993987083435,-1.6499251557544379,1739137721.4854152,63.04993987083435,0.065,1739137721.485421,63.04993987083435,-3.136261362747917,1739137721.4854262,63.04993987083435,0.01844695089673042,1739137721.4854307,63.04993987083435,0.003996593723761685,1739137721.4854355,63.04993987083435,2.4816209400160747,1739137721.485441,63.04993987083435,0.0,1739137721.4854457,63.04993987083435,0.08130186478258983,1739137721.4854507,63.04993987083435,3.1447330968480762,1739137721.4854553,63.04993987083435,2.400319075233485 +1739137721.505755,63.069939851760864,6.76996842176044,1739137721.5057635,63.069939851760864,0.10988932681157326,1739137721.5057733,63.069939851760864,105.77898308815693,1739137721.5057826,63.069939851760864,-1.6499251557544379,1739137721.5057871,63.069939851760864,0.065,1739137721.5057929,63.069939851760864,-3.136261362747917,1739137721.5057979,63.069939851760864,0.01844695089673042,1739137721.5058024,63.069939851760864,0.003996593723761685,1739137721.505807,63.069939851760864,2.4816209400160747,1739137721.5058124,63.069939851760864,0.0,1739137721.5058174,63.069939851760864,0.08130186478258983,1739137721.5058227,63.069939851760864,3.1447330968480762,1739137721.5058274,63.069939851760864,2.400319075233485 +1739137721.5230408,63.08993983268738,6.5054896580401,1739137721.523045,63.08993983268738,0.10893287625802728,1739137721.5230503,63.08993983268738,106.10698199636903,1739137721.523055,63.08993983268738,-2.004615642741278,1739137721.5230577,63.08993983268738,0.065,1739137721.523061,63.08993983268738,-3.1364302631809586,1739137721.523064,63.08993983268738,0.00830315435639694,1739137721.523066,63.08993983268738,0.0017609735604497885,1739137721.5230687,63.08993983268738,2.4917106188656786,1739137721.5230718,63.08993983268738,0.0,1739137721.5230744,63.08993983268738,0.08357842985449347,1739137721.5230775,63.08993983268738,3.145779375103846,1739137721.52308,63.08993983268738,2.4092162681583984 +1739137721.5515842,63.10993981361389,6.5054896580401,1739137721.5515933,63.10993981361389,0.10893287625802728,1739137721.5516033,63.10993981361389,106.10698199636903,1739137721.5516126,63.10993981361389,-2.004615642741278,1739137721.5516174,63.10993981361389,0.065,1739137721.551623,63.10993981361389,-3.1364302631809586,1739137721.551628,63.10993981361389,0.00830315435639694,1739137721.5516326,63.10993981361389,0.0017609735604497885,1739137721.5516372,63.10993981361389,2.4917106188656786,1739137721.551643,63.10993981361389,0.0,1739137721.5516474,63.10993981361389,0.08249435070728017,1739137721.551653,63.10993981361389,3.145779375103846,1739137721.5516574,63.10993981361389,2.4092162681583984 +1739137721.5960033,63.14993977546692,6.5054896580401,1739137721.5960207,63.14993977546692,0.10893287625802728,1739137721.5960374,63.14993977546692,106.10698199636903,1739137721.5960538,63.14993977546692,-2.004615642741278,1739137721.5960665,63.14993977546692,0.065,1739137721.596077,63.14993977546692,-3.1364302631809586,1739137721.5960853,63.14993977546692,0.00830315435639694,1739137721.5960932,63.14993977546692,0.0017609735604497885,1739137721.5961008,63.14993977546692,2.4917106188656786,1739137721.59611,63.14993977546692,0.0,1739137721.5961185,63.14993977546692,0.08249435070728017,1739137721.5961304,63.14993977546692,3.145779375103846,1739137721.5961382,63.14993977546692,2.4092162681583984 +1739137721.6077676,63.159939765930176,6.5054896580401,1739137721.6077724,63.159939765930176,0.10893287625802728,1739137721.607778,63.159939765930176,106.10698199636903,1739137721.607783,63.159939765930176,-2.004615642741278,1739137721.6077857,63.159939765930176,0.065,1739137721.607789,63.159939765930176,-3.1364302631809586,1739137721.6077917,63.159939765930176,0.00830315435639694,1739137721.6077943,63.159939765930176,0.0017609735604497885,1739137721.607797,63.159939765930176,2.4917106188656786,1739137721.6078,63.159939765930176,0.0,1739137721.6078026,63.159939765930176,0.08249435070728017,1739137721.6078055,63.159939765930176,3.145779375103846,1739137721.607808,63.159939765930176,2.4092162681583984 +1739137721.626466,63.189939737319946,6.5054896580401,1739137721.6264946,63.189939737319946,0.10893287625802728,1739137721.6264987,63.189939737319946,106.10698199636903,1739137721.626502,63.189939737319946,-2.004615642741278,1739137721.6265042,63.189939737319946,0.065,1739137721.6265063,63.189939737319946,-3.1364302631809586,1739137721.6265078,63.189939737319946,0.00830315435639694,1739137721.6265094,63.189939737319946,0.0017609735604497885,1739137721.6265109,63.189939737319946,2.4917106188656786,1739137721.6265125,63.189939737319946,0.0,1739137721.6265142,63.189939737319946,0.08249435070728017,1739137721.6265159,63.189939737319946,3.145779375103846,1739137721.6265175,63.189939737319946,2.4092162681583984 +1739137721.6461842,63.20993971824646,6.24002346622734,1739137721.6461864,63.20993971824646,0.10769509739230809,1739137721.6461887,63.20993971824646,106.33389473773138,1739137721.6461911,63.20993971824646,-2.2587148980625,1739137721.6461923,63.20993971824646,0.065,1739137721.646194,63.20993971824646,-3.136568997560564,1739137721.6461954,63.20993971824646,-0.001779180117152142,1739137721.6461964,63.20993971824646,-0.00037834783258467483,1739137721.6461976,63.20993971824646,2.4982214528290667,1739137721.646199,63.20993971824646,0.0,1739137721.6462004,63.20993971824646,0.07762361354252112,1739137721.6462016,63.20993971824646,3.1468256533596155,1739137721.6462026,63.20993971824646,2.418278439478019 +1739137721.6666484,63.229939699172974,6.24002346622734,1739137721.6666512,63.229939699172974,0.10769509739230809,1739137721.6666543,63.229939699172974,106.33389473773138,1739137721.666657,63.229939699172974,-2.2587148980625,1739137721.6666584,63.229939699172974,0.065,1739137721.66666,63.229939699172974,-3.136568997560564,1739137721.6666613,63.229939699172974,-0.001779180117152142,1739137721.666663,63.229939699172974,-0.00037834783258467483,1739137721.6666644,63.229939699172974,2.4982214528290667,1739137721.6666658,63.229939699172974,0.0,1739137721.666667,63.229939699172974,0.07994301335104792,1739137721.666669,63.229939699172974,3.1468256533596155,1739137721.66667,63.229939699172974,2.418278439478019 +1739137721.6862993,63.24993968009949,6.24002346622734,1739137721.6863022,63.24993968009949,0.10769509739230809,1739137721.6863053,63.24993968009949,106.33389473773138,1739137721.686308,63.24993968009949,-2.2587148980625,1739137721.686309,63.24993968009949,0.065,1739137721.686311,63.24993968009949,-3.136568997560564,1739137721.6863124,63.24993968009949,-0.001779180117152142,1739137721.6863136,63.24993968009949,-0.00037834783258467483,1739137721.6863153,63.24993968009949,2.4982214528290667,1739137721.6863167,63.24993968009949,0.0,1739137721.6863182,63.24993968009949,0.07994301335104792,1739137721.6863196,63.24993968009949,3.1468256533596155,1739137721.6863205,63.24993968009949,2.418278439478019 +1739137721.7069044,63.269939661026,6.24002346622734,1739137721.7069068,63.269939661026,0.10769509739230809,1739137721.70691,63.269939661026,106.33389473773138,1739137721.7069125,63.269939661026,-2.2587148980625,1739137721.7069137,63.269939661026,0.065,1739137721.7069154,63.269939661026,-3.136568997560564,1739137721.706917,63.269939661026,-0.001779180117152142,1739137721.7069185,63.269939661026,-0.00037834783258467483,1739137721.7069194,63.269939661026,2.4982214528290667,1739137721.7069395,63.269939661026,0.0,1739137721.7069407,63.269939661026,0.07994301335104792,1739137721.7069423,63.269939661026,3.1468256533596155,1739137721.7069435,63.269939661026,2.418278439478019 +1739137721.7272868,63.289939641952515,6.24002346622734,1739137721.7272892,63.289939641952515,0.10769509739230809,1739137721.7272918,63.289939641952515,106.33389473773138,1739137721.7272944,63.289939641952515,-2.2587148980625,1739137721.727296,63.289939641952515,0.065,1739137721.7272978,63.289939641952515,-3.136568997560564,1739137721.727299,63.289939641952515,-0.001779180117152142,1739137721.7273004,63.289939641952515,-0.00037834783258467483,1739137721.7273016,63.289939641952515,2.4982214528290667,1739137721.7273033,63.289939641952515,0.0,1739137721.7273045,63.289939641952515,0.07994301335104792,1739137721.727306,63.289939641952515,3.1468256533596155,1739137721.7273073,63.289939641952515,2.418278439478019 +1739137721.7463145,63.30993962287903,5.973581075752051,1739137721.746317,63.30993962287903,0.106173990064244,1739137721.7463193,63.30993962287903,106.65617109594693,1739137721.746322,63.30993962287903,-2.607154340269609,1739137721.746323,63.30993962287903,0.065,1739137721.746325,63.30993962287903,-3.13679426836242,1739137721.7463262,63.30993962287903,-0.01270729092568363,1739137721.7463276,63.30993962287903,-0.002650849394711156,1739137721.7463288,63.30993962287903,2.487324949474634,1739137721.7463303,63.30993962287903,0.0,1739137721.7463315,63.30993962287903,0.042491345580907634,1739137721.746333,63.30993962287903,3.147871931615385,1739137721.7463343,63.30993962287903,2.4269994674752056 +1739137721.7663348,63.32993960380554,5.973581075752051,1739137721.7663376,63.32993960380554,0.106173990064244,1739137721.7663405,63.32993960380554,106.65617109594693,1739137721.7663436,63.32993960380554,-2.607154340269609,1739137721.7663453,63.32993960380554,0.065,1739137721.766347,63.32993960380554,-3.13679426836242,1739137721.7663486,63.32993960380554,-0.01270729092568363,1739137721.76635,63.32993960380554,-0.002650849394711156,1739137721.7663517,63.32993960380554,2.487324949474634,1739137721.7663534,63.32993960380554,0.0,1739137721.766355,63.32993960380554,0.060325481999428554,1739137721.7663567,63.32993960380554,3.147871931615385,1739137721.766358,63.32993960380554,2.4269994674752056 +1739137721.7913165,63.349939584732056,5.973581075752051,1739137721.7913253,63.349939584732056,0.106173990064244,1739137721.7913349,63.349939584732056,106.65617109594693,1739137721.7913446,63.349939584732056,-2.607154340269609,1739137721.7913494,63.349939584732056,0.065,1739137721.7913554,63.349939584732056,-3.13679426836242,1739137721.7913601,63.349939584732056,-0.01270729092568363,1739137721.7913651,63.349939584732056,-0.002650849394711156,1739137721.7913697,63.349939584732056,2.487324949474634,1739137721.7913754,63.349939584732056,0.0,1739137721.7913802,63.349939584732056,0.060325481999428554,1739137721.7913857,63.349939584732056,3.147871931615385,1739137721.7913902,63.349939584732056,2.4269994674752056 +1739137721.816222,63.35993957519531,5.973581075752051,1739137721.8162284,63.35993957519531,0.106173990064244,1739137721.8162355,63.35993957519531,106.65617109594693,1739137721.8162422,63.35993957519531,-2.607154340269609,1739137721.8162456,63.35993957519531,0.065,1739137721.8162498,63.35993957519531,-3.13679426836242,1739137721.8162534,63.35993957519531,-0.01270729092568363,1739137721.8162565,63.35993957519531,-0.002650849394711156,1739137721.8162599,63.35993957519531,2.487324949474634,1739137721.8162637,63.35993957519531,0.0,1739137721.8162668,63.35993957519531,0.060325481999428554,1739137721.8162708,63.35993957519531,3.147871931615385,1739137721.8162742,63.35993957519531,2.4269994674752056 +1739137721.8338876,63.379939556121826,5.973581075752051,1739137721.8338926,63.379939556121826,0.106173990064244,1739137721.8338985,63.379939556121826,106.65617109594693,1739137721.8339038,63.379939556121826,-2.607154340269609,1739137721.8339064,63.379939556121826,0.065,1739137721.8339097,63.379939556121826,-3.13679426836242,1739137721.8339126,63.379939556121826,-0.01270729092568363,1739137721.8339152,63.379939556121826,-0.002650849394711156,1739137721.8339176,63.379939556121826,2.487324949474634,1739137721.8339207,63.379939556121826,0.0,1739137721.8339233,63.379939556121826,0.060325481999428554,1739137721.8339267,63.379939556121826,3.147871931615385,1739137721.8339293,63.379939556121826,2.4269994674752056 +1739137721.8536494,63.39993953704834,5.973581075752051,1739137721.8536549,63.39993953704834,0.106173990064244,1739137721.8536603,63.39993953704834,106.65617109594693,1739137721.853666,63.39993953704834,-2.607154340269609,1739137721.8536687,63.39993953704834,0.065,1739137721.853672,63.39993953704834,-3.13679426836242,1739137721.8536744,63.39993953704834,-0.01270729092568363,1739137721.853677,63.39993953704834,-0.002650849394711156,1739137721.8536797,63.39993953704834,2.487324949474634,1739137721.8536828,63.39993953704834,0.0,1739137721.8536856,63.39993953704834,0.060325481999428554,1739137721.8536882,63.39993953704834,3.147871931615385,1739137721.8536906,63.39993953704834,2.4269994674752056 +1739137721.8737538,63.42993950843811,5.706320176106525,1739137721.8737595,63.42993950843811,0.1043685924012161,1739137721.8737657,63.42993950843811,106.87998608473069,1739137721.8737707,63.42993950843811,-2.849718835530147,1739137721.8737733,63.42993950843811,0.065,1739137721.8737764,63.42993950843811,-3.1369914222818482,1739137721.8737793,63.42993950843811,-0.023309648667074048,1739137721.8737817,63.42993950843811,-0.004890709326992347,1739137721.8737843,63.42993950843811,2.476798682328025,1739137721.8737874,63.42993950843811,0.0,1739137721.87379,63.42993950843811,0.028298362417081026,1739137721.8737936,63.42993950843811,3.148918209871155,1739137721.873796,63.42993950843811,2.433249302967467 +1739137721.8923223,63.449939489364624,5.706320176106525,1739137721.892326,63.449939489364624,0.1043685924012161,1739137721.8923304,63.449939489364624,106.87998608473069,1739137721.892334,63.449939489364624,-2.849718835530147,1739137721.8923361,63.449939489364624,0.065,1739137721.8923385,63.449939489364624,-3.1369914222818482,1739137721.8923404,63.449939489364624,-0.023309648667074048,1739137721.8923423,63.449939489364624,-0.004890709326992347,1739137721.8923438,63.449939489364624,2.476798682328025,1739137721.892346,63.449939489364624,0.0,1739137721.8923478,63.449939489364624,0.043549379360557694,1739137721.8923497,63.449939489364624,3.148918209871155,1739137721.8923514,63.449939489364624,2.433249302967467 +1739137721.9100745,63.45993947982788,5.706320176106525,1739137721.9100783,63.45993947982788,0.1043685924012161,1739137721.9100816,63.45993947982788,106.87998608473069,1739137721.9100842,63.45993947982788,-2.849718835530147,1739137721.910086,63.45993947982788,0.065,1739137721.9100876,63.45993947982788,-3.1369914222818482,1739137721.9100895,63.45993947982788,-0.023309648667074048,1739137721.9100907,63.45993947982788,-0.004890709326992347,1739137721.910092,63.45993947982788,2.476798682328025,1739137721.9100938,63.45993947982788,0.0,1739137721.9100952,63.45993947982788,0.043549379360557694,1739137721.910097,63.45993947982788,3.148918209871155,1739137721.910099,63.45993947982788,2.433249302967467 +1739137721.9321897,63.479939460754395,5.706320176106525,1739137721.9321935,63.479939460754395,0.1043685924012161,1739137721.932198,63.479939460754395,106.87998608473069,1739137721.9322033,63.479939460754395,-2.849718835530147,1739137721.9322062,63.479939460754395,0.065,1739137721.93221,63.479939460754395,-3.1369914222818482,1739137721.9322133,63.479939460754395,-0.023309648667074048,1739137721.9322166,63.479939460754395,-0.004890709326992347,1739137721.93222,63.479939460754395,2.476798682328025,1739137721.9322233,63.479939460754395,0.0,1739137721.932227,63.479939460754395,0.043549379360557694,1739137721.9322302,63.479939460754395,3.148918209871155,1739137721.9322336,63.479939460754395,2.433249302967467 +1739137721.9516351,63.509939432144165,5.706320176106525,1739137721.9516377,63.509939432144165,0.1043685924012161,1739137721.9516404,63.509939432144165,106.87998608473069,1739137721.951643,63.509939432144165,-2.849718835530147,1739137721.9516442,63.509939432144165,0.065,1739137721.9516459,63.509939432144165,-3.1369914222818482,1739137721.9516475,63.509939432144165,-0.023309648667074048,1739137721.9516487,63.509939432144165,-0.004890709326992347,1739137721.9516504,63.509939432144165,2.476798682328025,1739137721.9516518,63.509939432144165,0.0,1739137721.951653,63.509939432144165,0.043549379360557694,1739137721.9516547,63.509939432144165,3.148918209871155,1739137721.9516559,63.509939432144165,2.433249302967467 +1739137721.9721384,63.51993942260742,5.706320176106525,1739137721.9721422,63.51993942260742,0.1043685924012161,1739137721.9721475,63.51993942260742,106.87998608473069,1739137721.972153,63.51993942260742,-2.849718835530147,1739137721.9721558,63.51993942260742,0.065,1739137721.9721594,63.51993942260742,-3.1369914222818482,1739137721.972163,63.51993942260742,-0.023309648667074048,1739137721.9721663,63.51993942260742,-0.004890709326992347,1739137721.9721696,63.51993942260742,2.476798682328025,1739137721.9721732,63.51993942260742,0.0,1739137721.9721766,63.51993942260742,0.043549379360557694,1739137721.97218,63.51993942260742,3.148918209871155,1739137721.9721835,63.51993942260742,2.433249302967467 +1739137721.992196,63.539939403533936,5.438441845144689,1739137721.9922001,63.539939403533936,0.10227875126998942,1739137721.9922054,63.539939403533936,107.19845129268747,1739137721.9922104,63.539939403533936,-3.182057249315512,1739137721.9922132,63.539939403533936,0.065,1739137721.992217,63.539939403533936,-3.137268249807075,1739137721.9922204,63.539939403533936,-0.03489110413092552,1739137721.9922237,63.539939403533936,-0.0072116086242537195,1739137721.992227,63.539939403533936,2.4653512449449537,1739137721.9922307,63.539939403533936,0.0,1739137721.992234,63.539939403533936,0.012866763077126657,1739137721.9922376,63.539939403533936,3.1499644881269244,1739137721.9922411,63.539939403533936,2.437873704910329 +1739137722.012303,63.55993938446045,5.438441845144689,1739137722.0123072,63.55993938446045,0.10227875126998942,1739137722.0123122,63.55993938446045,107.19845129268747,1739137722.0123174,63.55993938446045,-3.182057249315512,1739137722.0123205,63.55993938446045,0.065,1739137722.0123243,63.55993938446045,-3.137268249807075,1739137722.0123277,63.55993938446045,-0.03489110413092552,1739137722.012331,63.55993938446045,-0.0072116086242537195,1739137722.0123343,63.55993938446045,2.4653512449449537,1739137722.012338,63.55993938446045,0.0,1739137722.0123415,63.55993938446045,0.02747754003462477,1739137722.012345,63.55993938446045,3.1499644881269244,1739137722.0123484,63.55993938446045,2.437873704910329 +1739137722.03088,63.58993935585022,5.438441845144689,1739137722.0308828,63.58993935585022,0.10227875126998942,1739137722.030886,63.58993935585022,107.19845129268747,1739137722.0308888,63.58993935585022,-3.182057249315512,1739137722.03089,63.58993935585022,0.065,1739137722.0308917,63.58993935585022,-3.137268249807075,1739137722.0308933,63.58993935585022,-0.03489110413092552,1739137722.0308948,63.58993935585022,-0.0072116086242537195,1739137722.0308962,63.58993935585022,2.4653512449449537,1739137722.0308976,63.58993935585022,0.0,1739137722.030899,63.58993935585022,0.02747754003462477,1739137722.0309005,63.58993935585022,3.1499644881269244,1739137722.030902,63.58993935585022,2.437873704910329 +1739137722.0507088,63.60993933677673,5.438441845144689,1739137722.0507116,63.60993933677673,0.10227875126998942,1739137722.050714,63.60993933677673,107.19845129268747,1739137722.0507169,63.60993933677673,-3.182057249315512,1739137722.0507183,63.60993933677673,0.065,1739137722.05072,63.60993933677673,-3.137268249807075,1739137722.0507216,63.60993933677673,-0.03489110413092552,1739137722.050723,63.60993933677673,-0.0072116086242537195,1739137722.0507243,63.60993933677673,2.4653512449449537,1739137722.050726,63.60993933677673,0.0,1739137722.0507271,63.60993933677673,0.02747754003462477,1739137722.0507288,63.60993933677673,3.1499644881269244,1739137722.05073,63.60993933677673,2.437873704910329 +1739137722.0720437,63.61993932723999,5.438441845144689,1739137722.0720477,63.61993932723999,0.10227875126998942,1739137722.0720525,63.61993932723999,107.19845129268747,1739137722.072058,63.61993932723999,-3.182057249315512,1739137722.0720606,63.61993932723999,0.065,1739137722.0720642,63.61993932723999,-3.137268249807075,1739137722.0720677,63.61993932723999,-0.03489110413092552,1739137722.072071,63.61993932723999,-0.0072116086242537195,1739137722.0720744,63.61993932723999,2.4653512449449537,1739137722.072078,63.61993932723999,0.0,1739137722.0720813,63.61993932723999,0.02747754003462477,1739137722.0720851,63.61993932723999,3.1499644881269244,1739137722.0720885,63.61993932723999,2.437873704910329 +1739137722.092181,63.639939308166504,5.170144771504784,1739137722.0921848,63.639939308166504,0.09990492717102484,1739137722.0921898,63.639939308166504,107.42010400617094,1739137722.092195,63.639939308166504,-3.4123274410956763,1739137722.092198,63.639939308166504,0.065,1739137722.0922017,63.639939308166504,-3.137525674535278,1739137722.0922053,63.639939308166504,-0.045926117252888324,1739137722.0922086,63.639939308166504,-0.009576735115797935,1739137722.0922122,63.639939308166504,2.4544931530763288,1739137722.0922158,63.639939308166504,0.0,1739137722.092219,63.639939308166504,0.0012645938288855518,1739137722.0922227,63.639939308166504,3.151010766382694,1739137722.0922263,63.639939308166504,2.440746197675892 +1739137722.1103306,63.65993928909302,5.170144771504784,1739137722.110334,63.65993928909302,0.09990492717102484,1739137722.1103373,63.65993928909302,107.42010400617094,1739137722.11034,63.65993928909302,-3.4123274410956763,1739137722.1103418,63.65993928909302,0.065,1739137722.1103437,63.65993928909302,-3.137525674535278,1739137722.1103451,63.65993928909302,-0.045926117252888324,1739137722.1103466,63.65993928909302,-0.009576735115797935,1739137722.1103477,63.65993928909302,2.4544931530763288,1739137722.1103497,63.65993928909302,0.0,1739137722.1103508,63.65993928909302,0.0137469554004368,1739137722.1103523,63.65993928909302,3.151010766382694,1739137722.1103537,63.65993928909302,2.440746197675892 +1739137722.131743,63.67993927001953,5.170144771504784,1739137722.1317468,63.67993927001953,0.09990492717102484,1739137722.1317518,63.67993927001953,107.42010400617094,1739137722.1317568,63.67993927001953,-3.4123274410956763,1739137722.13176,63.67993927001953,0.065,1739137722.1317637,63.67993927001953,-3.137525674535278,1739137722.131767,63.67993927001953,-0.045926117252888324,1739137722.1317706,63.67993927001953,-0.009576735115797935,1739137722.131774,63.67993927001953,2.4544931530763288,1739137722.1317775,63.67993927001953,0.0,1739137722.131781,63.67993927001953,0.0137469554004368,1739137722.1317847,63.67993927001953,3.151010766382694,1739137722.131788,63.67993927001953,2.440746197675892 +1739137722.152141,63.699939250946045,5.170144771504784,1739137722.1521454,63.699939250946045,0.09990492717102484,1739137722.15215,63.699939250946045,107.42010400617094,1739137722.1521554,63.699939250946045,-3.4123274410956763,1739137722.1521583,63.699939250946045,0.065,1739137722.152162,63.699939250946045,-3.137525674535278,1739137722.1521654,63.699939250946045,-0.045926117252888324,1739137722.152169,63.699939250946045,-0.009576735115797935,1739137722.1521723,63.699939250946045,2.4544931530763288,1739137722.1521757,63.699939250946045,0.0,1739137722.1521792,63.699939250946045,0.0137469554004368,1739137722.1521826,63.699939250946045,3.151010766382694,1739137722.1521862,63.699939250946045,2.440746197675892 +1739137722.172177,63.71993923187256,5.170144771504784,1739137722.172181,63.71993923187256,0.09990492717102484,1739137722.1721861,63.71993923187256,107.42010400617094,1739137722.1721914,63.71993923187256,-3.4123274410956763,1739137722.1721942,63.71993923187256,0.065,1739137722.172198,63.71993923187256,-3.137525674535278,1739137722.1722016,63.71993923187256,-0.045926117252888324,1739137722.172205,63.71993923187256,-0.009576735115797935,1739137722.1722083,63.71993923187256,2.4544931530763288,1739137722.1722124,63.71993923187256,0.0,1739137722.1722157,63.71993923187256,0.0137469554004368,1739137722.1722193,63.71993923187256,3.151010766382694,1739137722.172223,63.71993923187256,2.440746197675892 +1739137722.19211,63.73993921279907,5.170144771504784,1739137722.1921144,63.73993921279907,0.09990492717102484,1739137722.1921191,63.73993921279907,107.42010400617094,1739137722.1921244,63.73993921279907,-3.4123274410956763,1739137722.1921272,63.73993921279907,0.065,1739137722.192131,63.73993921279907,-3.137525674535278,1739137722.1921344,63.73993921279907,-0.045926117252888324,1739137722.1921377,63.73993921279907,-0.009576735115797935,1739137722.192141,63.73993921279907,2.4544931530763288,1739137722.1921444,63.73993921279907,0.0,1739137722.192148,63.73993921279907,0.0137469554004368,1739137722.1921515,63.73993921279907,3.151010766382694,1739137722.192155,63.73993921279907,2.440746197675892 +1739137722.2107377,63.76993918418884,4.901624076940168,1739137722.2107403,63.76993918418884,0.09724816626787813,1739137722.2107437,63.76993918418884,107.54445286526087,1739137722.2107463,63.76993918418884,-3.5404485062747066,1739137722.2107477,63.76993918418884,0.065,1739137722.2107494,63.76993918418884,-3.1377727374380004,1739137722.2107513,63.76993918418884,-0.05609313586287304,1739137722.2107525,63.76993918418884,-0.012089103169481665,1739137722.2107542,63.76993918418884,2.444531471899368,1739137722.2107558,63.76993918418884,0.0,1739137722.210757,63.76993918418884,-0.007671304084433842,1739137722.2107584,63.76993918418884,3.1520570446384637,1739137722.2107596,63.76993918418884,2.442003599705596 +1739137722.2329628,63.7799391746521,4.901624076940168,1739137722.2329671,63.7799391746521,0.09724816626787813,1739137722.2329721,63.7799391746521,107.54445286526087,1739137722.2329774,63.7799391746521,-3.5404485062747066,1739137722.2329807,63.7799391746521,0.065,1739137722.2329845,63.7799391746521,-3.1377727374380004,1739137722.232988,63.7799391746521,-0.05609313586287304,1739137722.2329917,63.7799391746521,-0.012089103169481665,1739137722.2329953,63.7799391746521,2.444531471899368,1739137722.2329986,63.7799391746521,0.0,1739137722.2330022,63.7799391746521,0.0025278721937720405,1739137722.2330062,63.7799391746521,3.1520570446384637,1739137722.2330098,63.7799391746521,2.442003599705596 +1739137722.2508528,63.80993914604187,4.901624076940168,1739137722.2508557,63.80993914604187,0.09724816626787813,1739137722.2508588,63.80993914604187,107.54445286526087,1739137722.2508616,63.80993914604187,-3.5404485062747066,1739137722.2508628,63.80993914604187,0.065,1739137722.2508647,63.80993914604187,-3.1377727374380004,1739137722.2508662,63.80993914604187,-0.05609313586287304,1739137722.2508674,63.80993914604187,-0.012089103169481665,1739137722.2508688,63.80993914604187,2.444531471899368,1739137722.2508702,63.80993914604187,0.0,1739137722.250872,63.80993914604187,0.0025278721937720405,1739137722.250873,63.80993914604187,3.1520570446384637,1739137722.2508743,63.80993914604187,2.442003599705596 +1739137722.2706063,63.81993913650513,4.901624076940168,1739137722.2706094,63.81993913650513,0.09724816626787813,1739137722.2706125,63.81993913650513,107.54445286526087,1739137722.2706153,63.81993913650513,-3.5404485062747066,1739137722.2706168,63.81993913650513,0.065,1739137722.2706187,63.81993913650513,-3.1377727374380004,1739137722.2706203,63.81993913650513,-0.05609313586287304,1739137722.2706218,63.81993913650513,-0.012089103169481665,1739137722.270623,63.81993913650513,2.444531471899368,1739137722.2706244,63.81993913650513,0.0,1739137722.2706258,63.81993913650513,0.0025278721937720405,1739137722.2706273,63.81993913650513,3.1520570446384637,1739137722.270629,63.81993913650513,2.442003599705596 +1739137722.2916749,63.8499391078949,4.901624076940168,1739137722.2916777,63.8499391078949,0.09724816626787813,1739137722.2916806,63.8499391078949,107.54445286526087,1739137722.2916834,63.8499391078949,-3.5404485062747066,1739137722.2916846,63.8499391078949,0.065,1739137722.2916863,63.8499391078949,-3.1377727374380004,1739137722.2916882,63.8499391078949,-0.05609313586287304,1739137722.2916894,63.8499391078949,-0.012089103169481665,1739137722.2916908,63.8499391078949,2.444531471899368,1739137722.2916923,63.8499391078949,0.0,1739137722.2916934,63.8499391078949,0.0025278721937720405,1739137722.291695,63.8499391078949,3.1520570446384637,1739137722.2916965,63.8499391078949,2.442003599705596 +1739137722.3116295,63.859939098358154,4.633000164559833,1739137722.3116326,63.859939098358154,0.09430930934123083,1739137722.3116357,63.859939098358154,107.85440334109089,1739137722.3116384,63.859939098358154,-3.851281105213665,1739137722.31164,63.859939098358154,0.065,1739137722.311642,63.859939098358154,-3.1381381249362716,1739137722.3116434,63.859939098358154,-0.06835023172991994,1739137722.3116446,63.859939098358154,-0.014584531650152903,1739137722.311646,63.859939098358154,2.4325756619100707,1739137722.3116474,63.859939098358154,0.0,1739137722.311649,63.859939098358154,-0.02085821765728067,1739137722.3116505,63.859939098358154,3.1531033228942333,1739137722.311652,63.859939098358154,2.4422976407419075 +1739137722.333108,63.87993907928467,4.633000164559833,1739137722.3331118,63.87993907928467,0.09430930934123083,1739137722.3331172,63.87993907928467,107.85440334109089,1739137722.3331225,63.87993907928467,-3.851281105213665,1739137722.3331256,63.87993907928467,0.065,1739137722.3331294,63.87993907928467,-3.1381381249362716,1739137722.3331327,63.87993907928467,-0.06835023172991994,1739137722.3331363,63.87993907928467,-0.014584531650152903,1739137722.3331397,63.87993907928467,2.4325756619100707,1739137722.3331435,63.87993907928467,0.0,1739137722.3331468,63.87993907928467,-0.009721978831836786,1739137722.3331506,63.87993907928467,3.1531033228942333,1739137722.3331542,63.87993907928467,2.4422976407419075 +1739137722.3595035,63.90993905067444,4.633000164559833,1739137722.3595128,63.90993905067444,0.09430930934123083,1739137722.3595226,63.90993905067444,107.85440334109089,1739137722.3595319,63.90993905067444,-3.851281105213665,1739137722.3595364,63.90993905067444,0.065,1739137722.3595424,63.90993905067444,-3.1381381249362716,1739137722.3595471,63.90993905067444,-0.06835023172991994,1739137722.359552,63.90993905067444,-0.014584531650152903,1739137722.3595564,63.90993905067444,2.4325756619100707,1739137722.359562,63.90993905067444,0.0,1739137722.3595667,63.90993905067444,-0.009721978831836786,1739137722.3595717,63.90993905067444,3.1531033228942333,1739137722.3595765,63.90993905067444,2.4422976407419075 +1739137722.379685,63.90993905067444,4.633000164559833,1739137722.3796897,63.90993905067444,0.09430930934123083,1739137722.3796952,63.90993905067444,107.85440334109089,1739137722.3797002,63.90993905067444,-3.851281105213665,1739137722.3797028,63.90993905067444,0.065,1739137722.379706,63.90993905067444,-3.1381381249362716,1739137722.3797088,63.90993905067444,-0.06835023172991994,1739137722.379711,63.90993905067444,-0.014584531650152903,1739137722.3797135,63.90993905067444,2.4325756619100707,1739137722.3797164,63.90993905067444,0.0,1739137722.379719,63.90993905067444,-0.009721978831836786,1739137722.3797216,63.90993905067444,3.1531033228942333,1739137722.3797243,63.90993905067444,2.4422976407419075 +1739137722.3967354,63.93993902206421,4.633000164559833,1739137722.3967392,63.93993902206421,0.09430930934123083,1739137722.396744,63.93993902206421,107.85440334109089,1739137722.396748,63.93993902206421,-3.851281105213665,1739137722.39675,63.93993902206421,0.065,1739137722.3967528,63.93993902206421,-3.1381381249362716,1739137722.3967552,63.93993902206421,-0.06835023172991994,1739137722.3967574,63.93993902206421,-0.014584531650152903,1739137722.3967593,63.93993902206421,2.4325756619100707,1739137722.3967617,63.93993902206421,0.0,1739137722.3967636,63.93993902206421,-0.009721978831836786,1739137722.396766,63.93993902206421,3.1531033228942333,1739137722.396768,63.93993902206421,2.4422976407419075 +1739137722.415953,63.95993900299072,4.633000164559833,1739137722.4159572,63.95993900299072,0.09430930934123083,1739137722.4159617,63.95993900299072,107.85440334109089,1739137722.4159658,63.95993900299072,-3.851281105213665,1739137722.415968,63.95993900299072,0.065,1739137722.4159703,63.95993900299072,-3.1381381249362716,1739137722.415972,63.95993900299072,-0.06835023172991994,1739137722.415974,63.95993900299072,-0.014584531650152903,1739137722.4159756,63.95993900299072,2.4325756619100707,1739137722.4159777,63.95993900299072,0.0,1739137722.4159796,63.95993900299072,-0.009721978831836786,1739137722.4159818,63.95993900299072,3.1531033228942333,1739137722.415984,63.95993900299072,2.4422976407419075 +1739137722.4412978,63.979938983917236,4.364441111774253,1739137722.4413064,63.979938983917236,0.09109015072801352,1739137722.4413166,63.979938983917236,108.16134368438746,1739137722.4413269,63.979938983917236,-4.154367076489756,1739137722.4413316,63.979938983917236,0.065,1739137722.4413376,63.979938983917236,-3.1385300104854927,1739137722.4413428,63.979938983917236,-0.0808793227472165,1739137722.4413474,63.979938983917236,-0.01711836393482887,1739137722.441352,63.979938983917236,2.420414975083488,1739137722.4413574,63.979938983917236,0.0,1739137722.441362,63.979938983917236,-0.030485062735069485,1739137722.4413671,63.979938983917236,3.154149601150003,1739137722.441372,63.979938983917236,2.441012850068412 +1739137722.4669962,63.99993896484375,4.364441111774253,1739137722.4670117,63.99993896484375,0.09109015072801352,1739137722.4670303,63.99993896484375,108.16134368438746,1739137722.4670506,63.99993896484375,-4.154367076489756,1739137722.4670618,63.99993896484375,0.065,1739137722.4670765,63.99993896484375,-3.1385300104854927,1739137722.467089,63.99993896484375,-0.0808793227472165,1739137722.4671018,63.99993896484375,-0.01711836393482887,1739137722.4671137,63.99993896484375,2.420414975083488,1739137722.4671273,63.99993896484375,0.0,1739137722.4671397,63.99993896484375,-0.020597874984924047,1739137722.4671526,63.99993896484375,3.154149601150003,1739137722.4671655,63.99993896484375,2.441012850068412 +1739137722.4922037,64.02993893623352,4.364441111774253,1739137722.4922094,64.02993893623352,0.09109015072801352,1739137722.4922152,64.02993893623352,108.16134368438746,1739137722.4922202,64.02993893623352,-4.154367076489756,1739137722.4922228,64.02993893623352,0.065,1739137722.4922261,64.02993893623352,-3.1385300104854927,1739137722.4922287,64.02993893623352,-0.0808793227472165,1739137722.4922314,64.02993893623352,-0.01711836393482887,1739137722.492234,64.02993893623352,2.420414975083488,1739137722.4922369,64.02993893623352,0.0,1739137722.4922397,64.02993893623352,-0.020597874984924047,1739137722.4922423,64.02993893623352,3.154149601150003,1739137722.492245,64.02993893623352,2.441012850068412 +1739137722.513051,64.05993890762329,4.364441111774253,1739137722.5130553,64.05993890762329,0.09109015072801352,1739137722.5130594,64.05993890762329,108.16134368438746,1739137722.513063,64.05993890762329,-4.154367076489756,1739137722.5130649,64.05993890762329,0.065,1739137722.513067,64.05993890762329,-3.1385300104854927,1739137722.5130694,64.05993890762329,-0.0808793227472165,1739137722.5130708,64.05993890762329,-0.01711836393482887,1739137722.5130727,64.05993890762329,2.420414975083488,1739137722.5130746,64.05993890762329,0.0,1739137722.5130765,64.05993890762329,-0.020597874984924047,1739137722.5130787,64.05993890762329,3.154149601150003,1739137722.5130806,64.05993890762329,2.441012850068412 +1739137722.5508826,64.08993887901306,4.096078063047093,1739137722.5508852,64.08993887901306,0.08759889176635749,1739137722.5508885,64.08993887901306,108.3733773417536,1739137722.550891,64.08993887901306,-4.359080917358391,1739137722.5508926,64.08993887901306,0.065,1739137722.550894,64.08993887901306,-3.1389198667143727,1739137722.5508955,64.08993887901306,-0.09186568442603098,1739137722.5508966,64.08993887901306,-0.01973747559553905,1739137722.5508978,64.08993887901306,2.4098016907083295,1739137722.5508993,64.08993887901306,0.0,1739137722.5509005,64.08993887901306,-0.03620154174337813,1739137722.5509024,64.08993887901306,3.15513066062564,1739137722.5509036,64.08993887901306,2.438572911235912 +1739137722.5852373,64.11993885040283,4.096078063047093,1739137722.585247,64.11993885040283,0.08759889176635749,1739137722.5852575,64.11993885040283,108.3733773417536,1739137722.5852673,64.11993885040283,-4.359080917358391,1739137722.5852723,64.11993885040283,0.065,1739137722.5852792,64.11993885040283,-3.1389198667143727,1739137722.5852842,64.11993885040283,-0.09186568442603098,1739137722.5852892,64.11993885040283,-0.01973747559553905,1739137722.5852942,64.11993885040283,2.4098016907083295,1739137722.585301,64.11993885040283,0.0,1739137722.5853062,64.11993885040283,-0.028771220527582297,1739137722.5853112,64.11993885040283,3.15513066062564,1739137722.585317,64.11993885040283,2.438572911235912 +1739137722.598721,64.11993885040283,4.096078063047093,1739137722.5987246,64.11993885040283,0.08759889176635749,1739137722.5987291,64.11993885040283,108.3733773417536,1739137722.5987334,64.11993885040283,-4.359080917358391,1739137722.5987356,64.11993885040283,0.065,1739137722.5987384,64.11993885040283,-3.1389198667143727,1739137722.5987408,64.11993885040283,-0.09186568442603098,1739137722.5987427,64.11993885040283,-0.01973747559553905,1739137722.598745,64.11993885040283,2.4098016907083295,1739137722.5987475,64.11993885040283,0.0,1739137722.5987494,64.11993885040283,-0.028771220527582297,1739137722.5987518,64.11993885040283,3.15513066062564,1739137722.5987537,64.11993885040283,2.438572911235912 +1739137722.618554,64.1499388217926,4.096078063047093,1739137722.6185575,64.1499388217926,0.08759889176635749,1739137722.618561,64.1499388217926,108.3733773417536,1739137722.6185646,64.1499388217926,-4.359080917358391,1739137722.6185665,64.1499388217926,0.065,1739137722.6185684,64.1499388217926,-3.1389198667143727,1739137722.6185706,64.1499388217926,-0.09186568442603098,1739137722.6185725,64.1499388217926,-0.01973747559553905,1739137722.6185744,64.1499388217926,2.4098016907083295,1739137722.6185763,64.1499388217926,0.0,1739137722.6185782,64.1499388217926,-0.028771220527582297,1739137722.6185806,64.1499388217926,3.15513066062564,1739137722.6185822,64.1499388217926,2.438572911235912 +1739137722.6386786,64.16993880271912,4.096078063047093,1739137722.638682,64.16993880271912,0.08759889176635749,1739137722.6386857,64.16993880271912,108.3733773417536,1739137722.6386893,64.16993880271912,-4.359080917358391,1739137722.6386912,64.16993880271912,0.065,1739137722.6386933,64.16993880271912,-3.1389198667143727,1739137722.6386952,64.16993880271912,-0.09186568442603098,1739137722.638697,64.16993880271912,-0.01973747559553905,1739137722.6386988,64.16993880271912,2.4098016907083295,1739137722.6387007,64.16993880271912,0.0,1739137722.6387024,64.16993880271912,-0.028771220527582297,1739137722.6387043,64.16993880271912,3.15513066062564,1739137722.6387062,64.16993880271912,2.438572911235912 +1739137722.6579497,64.18993878364563,3.828028245576121,1739137722.6579535,64.18993878364563,0.08386336516698467,1739137722.6579576,64.18993878364563,108.67908029896206,1739137722.6579611,64.18993878364563,-4.654922598259255,1739137722.657963,64.18993878364563,0.065,1739137722.657965,64.18993878364563,-3.1393689776045393,1739137722.657967,64.18993878364563,-0.1031294881251168,1739137722.657969,64.18993878364563,-0.022012543919331044,1739137722.6579707,64.18993878364563,2.398968699891146,1739137722.6579728,64.18993878364563,0.0,1739137722.6579742,64.18993878364563,-0.043177033706766794,1739137722.6579764,64.18993878364563,3.155973864801613,1739137722.657978,64.18993878364563,2.435285819133379 +1739137722.678258,64.20993876457214,3.828028245576121,1739137722.678261,64.20993876457214,0.08386336516698467,1739137722.6782646,64.20993876457214,108.67908029896206,1739137722.6782682,64.20993876457214,-4.654922598259255,1739137722.6782699,64.20993876457214,0.065,1739137722.6782722,64.20993876457214,-3.1393689776045393,1739137722.6782744,64.20993876457214,-0.1031294881251168,1739137722.678276,64.20993876457214,-0.022012543919331044,1739137722.6782777,64.20993876457214,2.398968699891146,1739137722.6782796,64.20993876457214,0.0,1739137722.6782815,64.20993876457214,-0.03631711924223291,1739137722.6782832,64.20993876457214,3.155973864801613,1739137722.6782854,64.20993876457214,2.435285819133379 +1739137722.6981153,64.22993874549866,3.828028245576121,1739137722.6981184,64.22993874549866,0.08386336516698467,1739137722.6981225,64.22993874549866,108.67908029896206,1739137722.698126,64.22993874549866,-4.654922598259255,1739137722.698128,64.22993874549866,0.065,1739137722.6981301,64.22993874549866,-3.1393689776045393,1739137722.698132,64.22993874549866,-0.1031294881251168,1739137722.6981337,64.22993874549866,-0.022012543919331044,1739137722.6981356,64.22993874549866,2.398968699891146,1739137722.6981373,64.22993874549866,0.0,1739137722.6981392,64.22993874549866,-0.03631711924223291,1739137722.698141,64.22993874549866,3.155973864801613,1739137722.6981428,64.22993874549866,2.435285819133379 +1739137722.7178335,64.24993872642517,3.828028245576121,1739137722.717837,64.24993872642517,0.08386336516698467,1739137722.7178411,64.24993872642517,108.67908029896206,1739137722.7178447,64.24993872642517,-4.654922598259255,1739137722.717847,64.24993872642517,0.065,1739137722.7178493,64.24993872642517,-3.1393689776045393,1739137722.7178514,64.24993872642517,-0.1031294881251168,1739137722.717853,64.24993872642517,-0.022012543919331044,1739137722.717855,64.24993872642517,2.398968699891146,1739137722.7178571,64.24993872642517,0.0,1739137722.7178588,64.24993872642517,-0.03631711924223291,1739137722.717861,64.24993872642517,3.155973864801613,1739137722.7178626,64.24993872642517,2.435285819133379 +1739137722.7388449,64.26993870735168,3.828028245576121,1739137722.7388484,64.26993870735168,0.08386336516698467,1739137722.738852,64.26993870735168,108.67908029896206,1739137722.7388556,64.26993870735168,-4.654922598259255,1739137722.7388573,64.26993870735168,0.065,1739137722.7388594,64.26993870735168,-3.1393689776045393,1739137722.7388616,64.26993870735168,-0.1031294881251168,1739137722.7388635,64.26993870735168,-0.022012543919331044,1739137722.7388651,64.26993870735168,2.398968699891146,1739137722.7388673,64.26993870735168,0.0,1739137722.738869,64.26993870735168,-0.03631711924223291,1739137722.738871,64.26993870735168,3.155973864801613,1739137722.7388728,64.26993870735168,2.435285819133379 +1739137722.758085,64.2899386882782,3.828028245576121,1739137722.7580874,64.2899386882782,0.08386336516698467,1739137722.75809,64.2899386882782,108.67908029896206,1739137722.7580926,64.2899386882782,-4.654922598259255,1739137722.758094,64.2899386882782,0.065,1739137722.7580955,64.2899386882782,-3.1393689776045393,1739137722.758097,64.2899386882782,-0.1031294881251168,1739137722.7580981,64.2899386882782,-0.022012543919331044,1739137722.7580996,64.2899386882782,2.398968699891146,1739137722.7581007,64.2899386882782,0.0,1739137722.758102,64.2899386882782,-0.03631711924223291,1739137722.7581036,64.2899386882782,3.155973864801613,1739137722.758105,64.2899386882782,2.435285819133379 +1739137722.777914,64.30993866920471,3.5603879358219093,1739137722.7779167,64.30993866920471,0.07992390489241696,1739137722.7779193,64.30993866920471,109.73701044169124,1739137722.7779217,64.30993866920471,-5.700519296220271,1739137722.777923,64.30993866920471,0.065,1739137722.7779248,64.30993866920471,-3.139981160071956,1739137722.7779262,64.30993866920471,-0.12505552256483624,1739137722.7779274,64.30993866920471,-0.022396379983159957,1739137722.7779284,64.30993866920471,2.3780207471408663,1739137722.77793,64.30993866920471,0.0,1739137722.7779312,64.30993866920471,-0.06846012423743522,1739137722.777933,64.30993866920471,3.156708133049091,1739137722.7779338,64.30993866920471,2.4311746708773274 +1739137722.796909,64.32993865013123,3.5603879358219093,1739137722.7969115,64.32993865013123,0.07992390489241696,1739137722.796914,64.32993865013123,109.73701044169124,1739137722.796917,64.32993865013123,-5.700519296220271,1739137722.7969182,64.32993865013123,0.065,1739137722.79692,64.32993865013123,-3.139981160071956,1739137722.7969213,64.32993865013123,-0.12505552256483624,1739137722.796923,64.32993865013123,-0.022396379983159957,1739137722.796924,64.32993865013123,2.3780207471408663,1739137722.7969258,64.32993865013123,0.0,1739137722.796927,64.32993865013123,-0.053153923736461106,1739137722.7969282,64.32993865013123,3.156708133049091,1739137722.7969296,64.32993865013123,2.4311746708773274 +1739137722.816934,64.34993863105774,3.5603879358219093,1739137722.8169377,64.34993863105774,0.07992390489241696,1739137722.816942,64.34993863105774,109.73701044169124,1739137722.8169475,64.34993863105774,-5.700519296220271,1739137722.8169506,64.34993863105774,0.065,1739137722.8169556,64.34993863105774,-3.139981160071956,1739137722.8169599,64.34993863105774,-0.12505552256483624,1739137722.8169641,64.34993863105774,-0.022396379983159957,1739137722.816966,64.34993863105774,2.3780207471408663,1739137722.8169682,64.34993863105774,0.0,1739137722.8169703,64.34993863105774,-0.053153923736461106,1739137722.8169723,64.34993863105774,3.156708133049091,1739137722.8169742,64.34993863105774,2.4311746708773274 +1739137722.8371997,64.36993861198425,3.5603879358219093,1739137722.8372033,64.36993861198425,0.07992390489241696,1739137722.8372064,64.36993861198425,109.73701044169124,1739137722.8372087,64.36993861198425,-5.700519296220271,1739137722.8372104,64.36993861198425,0.065,1739137722.837212,64.36993861198425,-3.139981160071956,1739137722.8372138,64.36993861198425,-0.12505552256483624,1739137722.837215,64.36993861198425,-0.022396379983159957,1739137722.8372161,64.36993861198425,2.3780207471408663,1739137722.8372183,64.36993861198425,0.0,1739137722.8372195,64.36993861198425,-0.053153923736461106,1739137722.8372211,64.36993861198425,3.156708133049091,1739137722.8372223,64.36993861198425,2.4311746708773274 +1739137722.8569322,64.38993859291077,3.5603879358219093,1739137722.856935,64.38993859291077,0.07992390489241696,1739137722.856938,64.38993859291077,109.73701044169124,1739137722.856941,64.38993859291077,-5.700519296220271,1739137722.8569427,64.38993859291077,0.065,1739137722.8569443,64.38993859291077,-3.139981160071956,1739137722.8569465,64.38993859291077,-0.12505552256483624,1739137722.8569477,64.38993859291077,-0.022396379983159957,1739137722.856949,64.38993859291077,2.3780207471408663,1739137722.8569505,64.38993859291077,0.0,1739137722.8569517,64.38993859291077,-0.053153923736461106,1739137722.8569531,64.38993859291077,3.156708133049091,1739137722.8569546,64.38993859291077,2.4311746708773274 +1739137722.8768005,64.40993857383728,3.293290833608472,1739137722.8768036,64.40993857383728,0.07579805223004232,1739137722.8768065,64.40993857383728,109.93927504083257,1739137722.8768091,64.40993857383728,-5.884930799401992,1739137722.8768106,64.40993857383728,0.065,1739137722.876812,64.40993857383728,-3.1404161678085742,1739137722.8768137,64.40993857383728,-0.13460303495218892,1739137722.8768148,64.40993857383728,-0.02454249418218398,1739137722.876816,64.40993857383728,2.3689563935470384,1739137722.8768182,64.40993857383728,0.0,1739137722.8768194,64.40993857383728,-0.05909754041319541,1739137722.876821,64.40993857383728,3.1574351359688335,1739137722.8768222,64.40993857383728,2.42522363889079 +1739137722.8973799,64.4299385547638,3.293290833608472,1739137722.8973825,64.4299385547638,0.07579805223004232,1739137722.897386,64.4299385547638,109.93927504083257,1739137722.8973892,64.4299385547638,-5.884930799401992,1739137722.8973906,64.4299385547638,0.065,1739137722.8973923,64.4299385547638,-3.1404161678085742,1739137722.8973942,64.4299385547638,-0.13460303495218892,1739137722.8973956,64.4299385547638,-0.02454249418218398,1739137722.8973973,64.4299385547638,2.3689563935470384,1739137722.8973987,64.4299385547638,0.0,1739137722.8974004,64.4299385547638,-0.056267245343751604,1739137722.897402,64.4299385547638,3.1574351359688335,1739137722.8974037,64.4299385547638,2.42522363889079 +1739137722.9171257,64.44993853569031,3.293290833608472,1739137722.9171288,64.44993853569031,0.07579805223004232,1739137722.9171321,64.44993853569031,109.93927504083257,1739137722.9171355,64.44993853569031,-5.884930799401992,1739137722.9171371,64.44993853569031,0.065,1739137722.9171393,64.44993853569031,-3.1404161678085742,1739137722.917141,64.44993853569031,-0.13460303495218892,1739137722.9171426,64.44993853569031,-0.02454249418218398,1739137722.917144,64.44993853569031,2.3689563935470384,1739137722.917146,64.44993853569031,0.0,1739137722.9171479,64.44993853569031,-0.056267245343751604,1739137722.9171498,64.44993853569031,3.1574351359688335,1739137722.9171512,64.44993853569031,2.42522363889079 +1739137722.937118,64.46993851661682,3.293290833608472,1739137722.9371204,64.46993851661682,0.07579805223004232,1739137722.9371238,64.46993851661682,109.93927504083257,1739137722.9371269,64.46993851661682,-5.884930799401992,1739137722.9371288,64.46993851661682,0.065,1739137722.9371307,64.46993851661682,-3.1404161678085742,1739137722.9371326,64.46993851661682,-0.13460303495218892,1739137722.937134,64.46993851661682,-0.02454249418218398,1739137722.9371357,64.46993851661682,2.3689563935470384,1739137722.9371374,64.46993851661682,0.0,1739137722.937139,64.46993851661682,-0.056267245343751604,1739137722.9371407,64.46993851661682,3.1574351359688335,1739137722.9371426,64.46993851661682,2.42522363889079 +1739137722.9571128,64.48993849754333,3.293290833608472,1739137722.9571161,64.48993849754333,0.07579805223004232,1739137722.9571197,64.48993849754333,109.93927504083257,1739137722.957123,64.48993849754333,-5.884930799401992,1739137722.957125,64.48993849754333,0.065,1739137722.957127,64.48993849754333,-3.1404161678085742,1739137722.9571288,64.48993849754333,-0.13460303495218892,1739137722.9571302,64.48993849754333,-0.02454249418218398,1739137722.9571319,64.48993849754333,2.3689563935470384,1739137722.957134,64.48993849754333,0.0,1739137722.9571357,64.48993849754333,-0.056267245343751604,1739137722.9571373,64.48993849754333,3.1574351359688335,1739137722.957139,64.48993849754333,2.42522363889079 +1739137722.977298,64.50993847846985,3.293290833608472,1739137722.9773006,64.50993847846985,0.07579805223004232,1739137722.9773045,64.50993847846985,109.93927504083257,1739137722.9773078,64.50993847846985,-5.884930799401992,1739137722.9773095,64.50993847846985,0.065,1739137722.9773118,64.50993847846985,-3.1404161678085742,1739137722.9773133,64.50993847846985,-0.13460303495218892,1739137722.9773147,64.50993847846985,-0.02454249418218398,1739137722.9773164,64.50993847846985,2.3689563935470384,1739137722.9773183,64.50993847846985,0.0,1739137722.97732,64.50993847846985,-0.056267245343751604,1739137722.977322,64.50993847846985,3.1574351359688335,1739137722.9773235,64.50993847846985,2.42522363889079 +1739137722.9974616,64.52993845939636,3.026864869179305,1739137722.9974647,64.52993845939636,0.07149675432815705,1739137722.997468,64.52993845939636,109.94459495752535,1739137722.9974713,64.52993845939636,-5.871605435398742,1739137722.9974728,64.52993845939636,0.065,1739137722.997475,64.52993845939636,-3.140862555836872,1739137722.9974766,64.52993845939636,-0.14029313688928097,1739137722.9974782,64.52993845939636,-0.02721352416760703,1739137722.9974794,64.52993845939636,2.3635706835742583,1739137722.997481,64.52993845939636,0.0,1739137722.9974828,64.52993845939636,-0.054683875947975864,1739137722.9974844,64.52993845939636,3.1580893839620794,1739137722.9974859,64.52993845939636,2.419008545325443 +1739137723.0173173,64.54993844032288,3.026864869179305,1739137723.0173204,64.54993844032288,0.07149675432815705,1739137723.0173237,64.54993844032288,109.94459495752535,1739137723.017327,64.54993844032288,-5.871605435398742,1739137723.0173287,64.54993844032288,0.065,1739137723.017331,64.54993844032288,-3.140862555836872,1739137723.0173328,64.54993844032288,-0.14029313688928097,1739137723.0173342,64.54993844032288,-0.02721352416760703,1739137723.017336,64.54993844032288,2.3635706835742583,1739137723.0173378,64.54993844032288,0.0,1739137723.0173395,64.54993844032288,-0.05543786175118459,1739137723.0173411,64.54993844032288,3.1580893839620794,1739137723.0173428,64.54993844032288,2.419008545325443 +1739137723.0373843,64.56993842124939,3.026864869179305,1739137723.0373876,64.56993842124939,0.07149675432815705,1739137723.037391,64.56993842124939,109.94459495752535,1739137723.0373938,64.56993842124939,-5.871605435398742,1739137723.0373955,64.56993842124939,0.065,1739137723.0373976,64.56993842124939,-3.140862555836872,1739137723.0373993,64.56993842124939,-0.14029313688928097,1739137723.0374007,64.56993842124939,-0.02721352416760703,1739137723.0374024,64.56993842124939,2.3635706835742583,1739137723.037404,64.56993842124939,0.0,1739137723.0374057,64.56993842124939,-0.05543786175118459,1739137723.0374074,64.56993842124939,3.1580893839620794,1739137723.037409,64.56993842124939,2.419008545325443 +1739137723.0575929,64.5899384021759,3.026864869179305,1739137723.0575964,64.5899384021759,0.07149675432815705,1739137723.0576,64.5899384021759,109.94459495752535,1739137723.0576038,64.5899384021759,-5.871605435398742,1739137723.057606,64.5899384021759,0.065,1739137723.057608,64.5899384021759,-3.140862555836872,1739137723.0576098,64.5899384021759,-0.14029313688928097,1739137723.0576117,64.5899384021759,-0.02721352416760703,1739137723.0576134,64.5899384021759,2.3635706835742583,1739137723.057615,64.5899384021759,0.0,1739137723.057617,64.5899384021759,-0.05543786175118459,1739137723.0576184,64.5899384021759,3.1580893839620794,1739137723.05762,64.5899384021759,2.419008545325443 +1739137723.0773354,64.60993838310242,3.026864869179305,1739137723.0773385,64.60993838310242,0.07149675432815705,1739137723.0773416,64.60993838310242,109.94459495752535,1739137723.0773447,64.60993838310242,-5.871605435398742,1739137723.0773466,64.60993838310242,0.065,1739137723.0773487,64.60993838310242,-3.140862555836872,1739137723.0773501,64.60993838310242,-0.14029313688928097,1739137723.0773516,64.60993838310242,-0.02721352416760703,1739137723.0773532,64.60993838310242,2.3635706835742583,1739137723.077355,64.60993838310242,0.0,1739137723.0773568,64.60993838310242,-0.05543786175118459,1739137723.0773585,64.60993838310242,3.1580893839620794,1739137723.0773602,64.60993838310242,2.419008545325443 +1739137723.097406,64.62993836402893,2.7611141587050083,1739137723.0974085,64.62993836402893,0.06704546293116298,1739137723.0974114,64.62993836402893,109.94990106915205,1739137723.0974143,64.62993836402893,-5.858745142890903,1739137723.0974157,64.62993836402893,0.065,1739137723.0974174,64.62993836402893,-3.1413553570375874,1739137723.097419,64.62993836402893,-0.14465636015993424,1739137723.0974205,64.62993836402893,-0.0299029467170592,1739137723.097422,64.62993836402893,2.3594491665968436,1739137723.0974233,64.62993836402893,0.0,1739137723.0974247,64.62993836402893,-0.05174577167304315,1739137723.0974262,64.62993836402893,3.1586124916833884,1739137723.0974274,64.62993836402893,2.4129530772806023 +1739137723.116992,64.64993834495544,2.7611141587050083,1739137723.1169953,64.64993834495544,0.06704546293116298,1739137723.1169994,64.64993834495544,109.94990106915205,1739137723.1170025,64.64993834495544,-5.858745142890903,1739137723.1170037,64.64993834495544,0.065,1739137723.1170063,64.64993834495544,-3.1413553570375874,1739137723.117008,64.64993834495544,-0.14465636015993424,1739137723.1170094,64.64993834495544,-0.0299029467170592,1739137723.1170106,64.64993834495544,2.3594491665968436,1739137723.1170127,64.64993834495544,0.0,1739137723.1170142,64.64993834495544,-0.053503910683758704,1739137723.1170158,64.64993834495544,3.1586124916833884,1739137723.1170173,64.64993834495544,2.4129530772806023 +1739137723.1395316,64.66993832588196,2.7611141587050083,1739137723.1395352,64.66993832588196,0.06704546293116298,1739137723.13954,64.66993832588196,109.94990106915205,1739137723.1395457,64.66993832588196,-5.858745142890903,1739137723.139549,64.66993832588196,0.065,1739137723.1395528,64.66993832588196,-3.1413553570375874,1739137723.139557,64.66993832588196,-0.14465636015993424,1739137723.1395605,64.66993832588196,-0.0299029467170592,1739137723.139564,64.66993832588196,2.3594491665968436,1739137723.1395679,64.66993832588196,0.0,1739137723.1395714,64.66993832588196,-0.053503910683758704,1739137723.139575,64.66993832588196,3.1586124916833884,1739137723.1395788,64.66993832588196,2.4129530772806023 +1739137723.1569216,64.68993830680847,2.7611141587050083,1739137723.1569254,64.68993830680847,0.06704546293116298,1739137723.1569288,64.68993830680847,109.94990106915205,1739137723.1569319,64.68993830680847,-5.858745142890903,1739137723.156933,64.68993830680847,0.065,1739137723.1569352,64.68993830680847,-3.1413553570375874,1739137723.1569366,64.68993830680847,-0.14465636015993424,1739137723.1569386,64.68993830680847,-0.0299029467170592,1739137723.1569397,64.68993830680847,2.3594491665968436,1739137723.156942,64.68993830680847,0.0,1739137723.1569433,64.68993830680847,-0.053503910683758704,1739137723.1569452,64.68993830680847,3.1586124916833884,1739137723.1569464,64.68993830680847,2.4129530772806023 +1739137723.1870143,64.70993828773499,2.7611141587050083,1739137723.1870239,64.70993828773499,0.06704546293116298,1739137723.1870348,64.70993828773499,109.94990106915205,1739137723.1870458,64.70993828773499,-5.858745142890903,1739137723.187051,64.70993828773499,0.065,1739137723.1870577,64.70993828773499,-3.1413553570375874,1739137723.187063,64.70993828773499,-0.14465636015993424,1739137723.187068,64.70993828773499,-0.0299029467170592,1739137723.187073,64.70993828773499,2.3594491665968436,1739137723.1870792,64.70993828773499,0.0,1739137723.1870842,64.70993828773499,-0.053503910683758704,1739137723.1870902,64.70993828773499,3.1586124916833884,1739137723.187095,64.70993828773499,2.4129530772806023 +1739137723.2185755,64.73993825912476,2.4960186700334335,1739137723.218582,64.73993825912476,0.06248242170721774,1739137723.2185898,64.73993825912476,109.95519385284302,1739137723.218596,64.73993825912476,-5.846572600976593,1739137723.2185993,64.73993825912476,0.065,1739137723.2186036,64.73993825912476,3.14129087946056,1739137723.2186072,64.73993825912476,-0.1479507687218948,1739137723.2186105,64.73993825912476,-0.03265046124727118,1739137723.2186134,64.73993825912476,2.35634201847517,1739137723.2186177,64.73993825912476,0.0,1739137723.2186208,64.73993825912476,-0.04832143845006176,1739137723.2186246,64.73993825912476,3.159026198568676,1739137723.2186277,64.73993825912476,2.4071313020788363 +1739137723.232757,64.75993824005127,2.4960186700334335,1739137723.2327619,64.75993824005127,0.06248242170721774,1739137723.2327666,64.75993824005127,109.95519385284302,1739137723.2327714,64.75993824005127,-5.846572600976593,1739137723.2327738,64.75993824005127,0.065,1739137723.2327766,64.75993824005127,3.14129087946056,1739137723.232779,64.75993824005127,-0.1479507687218948,1739137723.2327814,64.75993824005127,-0.03265046124727118,1739137723.2327836,64.75993824005127,2.35634201847517,1739137723.2327864,64.75993824005127,0.0,1739137723.2327888,64.75993824005127,-0.0507892836036663,1739137723.2327912,64.75993824005127,3.159026198568676,1739137723.2327945,64.75993824005127,2.4071313020788363 +1739137723.2499962,64.77993822097778,2.4960186700334335,1739137723.2499988,64.77993822097778,0.06248242170721774,1739137723.2500021,64.77993822097778,109.95519385284302,1739137723.250005,64.77993822097778,-5.846572600976593,1739137723.2500064,64.77993822097778,0.065,1739137723.2500083,64.77993822097778,3.14129087946056,1739137723.2500098,64.77993822097778,-0.1479507687218948,1739137723.2500114,64.77993822097778,-0.03265046124727118,1739137723.2500126,64.77993822097778,2.35634201847517,1739137723.2500145,64.77993822097778,0.0,1739137723.2500157,64.77993822097778,-0.0507892836036663,1739137723.2500172,64.77993822097778,3.159026198568676,1739137723.250019,64.77993822097778,2.4071313020788363 +1739137723.27045,64.7999382019043,2.4960186700334335,1739137723.270456,64.7999382019043,0.06248242170721774,1739137723.27046,64.7999382019043,109.95519385284302,1739137723.2704635,64.7999382019043,-5.846572600976593,1739137723.2704651,64.7999382019043,0.065,1739137723.2705104,64.7999382019043,3.14129087946056,1739137723.2705157,64.7999382019043,-0.1479507687218948,1739137723.2705183,64.7999382019043,-0.03265046124727118,1739137723.2705197,64.7999382019043,2.35634201847517,1739137723.2705219,64.7999382019043,0.0,1739137723.2705245,64.7999382019043,-0.0507892836036663,1739137723.2705264,64.7999382019043,3.159026198568676,1739137723.2705278,64.7999382019043,2.4071313020788363 +1739137723.2920105,64.81993818283081,2.4960186700334335,1739137723.2920144,64.81993818283081,0.06248242170721774,1739137723.2920187,64.81993818283081,109.95519385284302,1739137723.2920237,64.81993818283081,-5.846572600976593,1739137723.2920263,64.81993818283081,0.065,1739137723.29203,64.81993818283081,3.14129087946056,1739137723.2920334,64.81993818283081,-0.1479507687218948,1739137723.2920365,64.81993818283081,-0.03265046124727118,1739137723.2920396,64.81993818283081,2.35634201847517,1739137723.292043,64.81993818283081,0.0,1739137723.2920463,64.81993818283081,-0.0507892836036663,1739137723.2920496,64.81993818283081,3.159026198568676,1739137723.2920527,64.81993818283081,2.4071313020788363 +1739137723.3119648,64.83993816375732,2.4960186700334335,1739137723.3119686,64.83993816375732,0.06248242170721774,1739137723.311973,64.83993816375732,109.95519385284302,1739137723.3119783,64.83993816375732,-5.846572600976593,1739137723.311981,64.83993816375732,0.065,1739137723.3119845,64.83993816375732,3.14129087946056,1739137723.3119879,64.83993816375732,-0.1479507687218948,1739137723.3119912,64.83993816375732,-0.03265046124727118,1739137723.3119946,64.83993816375732,2.35634201847517,1739137723.311998,64.83993816375732,0.0,1739137723.312001,64.83993816375732,-0.0507892836036663,1739137723.3120046,64.83993816375732,3.159026198568676,1739137723.312008,64.83993816375732,2.4071313020788363 +1739137723.3318276,64.85993814468384,2.2315488794674403,1739137723.3318312,64.85993814468384,0.05783668767264771,1739137723.3318357,64.85993814468384,110.23649833527116,1739137723.3318408,64.85993814468384,-6.111345291129616,1739137723.3318436,64.85993814468384,0.065,1739137723.3318474,64.85993814468384,3.1407340414079084,1739137723.3318505,64.85993814468384,-0.1548328568543529,1739137723.3318539,64.85993814468384,-0.03416660099901877,1739137723.3318572,64.85993814468384,2.3498643172115474,1739137723.3318605,64.85993814468384,0.0,1739137723.3318639,64.85993814468384,-0.0526355735885148,1739137723.3318672,64.85993814468384,3.1592937505443532,1739137723.3318706,64.85993814468384,2.4016207046537996 +1739137723.351795,64.87993812561035,2.2315488794674403,1739137723.3517983,64.87993812561035,0.05783668767264771,1739137723.3518023,64.87993812561035,110.23649833527116,1739137723.351807,64.87993812561035,-6.111345291129616,1739137723.35181,64.87993812561035,0.065,1739137723.3518136,64.87993812561035,3.1407340414079084,1739137723.3518167,64.87993812561035,-0.1548328568543529,1739137723.35182,64.87993812561035,-0.03416660099901877,1739137723.3518233,64.87993812561035,2.3498643172115474,1739137723.3518267,64.87993812561035,0.0,1739137723.3518298,64.87993812561035,-0.051756387442252194,1739137723.351833,64.87993812561035,3.1592937505443532,1739137723.3518364,64.87993812561035,2.4016207046537996 +1739137723.370772,64.89993810653687,2.2315488794674403,1739137723.3707745,64.89993810653687,0.05783668767264771,1739137723.3707771,64.89993810653687,110.23649833527116,1739137723.3707798,64.89993810653687,-6.111345291129616,1739137723.3707812,64.89993810653687,0.065,1739137723.370783,64.89993810653687,3.1407340414079084,1739137723.370784,64.89993810653687,-0.1548328568543529,1739137723.3707855,64.89993810653687,-0.03416660099901877,1739137723.3707867,64.89993810653687,2.3498643172115474,1739137723.370788,64.89993810653687,0.0,1739137723.3707893,64.89993810653687,-0.051756387442252194,1739137723.3707907,64.89993810653687,3.1592937505443532,1739137723.370792,64.89993810653687,2.4016207046537996 +1739137723.39015,64.91993808746338,2.2315488794674403,1739137723.3901527,64.91993808746338,0.05783668767264771,1739137723.3901553,64.91993808746338,110.23649833527116,1739137723.390158,64.91993808746338,-6.111345291129616,1739137723.3901594,64.91993808746338,0.065,1739137723.3901608,64.91993808746338,3.1407340414079084,1739137723.3901625,64.91993808746338,-0.1548328568543529,1739137723.3901637,64.91993808746338,-0.03416660099901877,1739137723.390165,64.91993808746338,2.3498643172115474,1739137723.390167,64.91993808746338,0.0,1739137723.390168,64.91993808746338,-0.051756387442252194,1739137723.3901696,64.91993808746338,3.1592937505443532,1739137723.3901708,64.91993808746338,2.4016207046537996 +1739137723.4122746,64.93993806838989,2.2315488794674403,1739137723.4122777,64.93993806838989,0.05783668767264771,1739137723.4122822,64.93993806838989,110.23649833527116,1739137723.412287,64.93993806838989,-6.111345291129616,1739137723.4122899,64.93993806838989,0.065,1739137723.4122934,64.93993806838989,3.1407340414079084,1739137723.4122965,64.93993806838989,-0.1548328568543529,1739137723.4122999,64.93993806838989,-0.03416660099901877,1739137723.4123027,64.93993806838989,2.3498643172115474,1739137723.4123065,64.93993806838989,0.0,1739137723.4123096,64.93993806838989,-0.051756387442252194,1739137723.412313,64.93993806838989,3.1592937505443532,1739137723.412316,64.93993806838989,2.4016207046537996 +1739137723.4305682,64.9599380493164,1.9676962802666802,1739137723.4305708,64.9599380493164,0.053136263962381136,1739137723.4305732,64.9599380493164,110.53309667244402,1739137723.4305758,64.9599380493164,-6.390939935854739,1739137723.4305768,64.9599380493164,0.065,1739137723.4305787,64.9599380493164,3.14017331582173,1739137723.43058,64.9599380493164,-0.16186391118685087,1739137723.430581,64.9599380493164,-0.035583540309690215,1739137723.4305823,64.9599380493164,2.3432647924097423,1739137723.4305837,64.9599380493164,0.0,1739137723.4305851,64.9599380493164,-0.053534949495755504,1739137723.4305863,64.9599380493164,3.1595393777110075,1739137723.4305875,64.9599380493164,2.395952807171225 +1739137723.4506037,64.97993803024292,1.9676962802666802,1739137723.450606,64.97993803024292,0.053136263962381136,1739137723.450609,64.97993803024292,110.53309667244402,1739137723.4506114,64.97993803024292,-6.390939935854739,1739137723.450613,64.97993803024292,0.065,1739137723.4506145,64.97993803024292,3.14017331582173,1739137723.450616,64.97993803024292,-0.16186391118685087,1739137723.450617,64.97993803024292,-0.035583540309690215,1739137723.4506183,64.97993803024292,2.3432647924097423,1739137723.45062,64.97993803024292,0.0,1739137723.4506211,64.97993803024292,-0.05268801476148255,1739137723.4506228,64.97993803024292,3.1595393777110075,1739137723.450624,64.97993803024292,2.395952807171225 +1739137723.4769988,64.99993801116943,1.9676962802666802,1739137723.4770074,64.99993801116943,0.053136263962381136,1739137723.4770172,64.99993801116943,110.53309667244402,1739137723.4770274,64.99993801116943,-6.390939935854739,1739137723.4770324,64.99993801116943,0.065,1739137723.4770384,64.99993801116943,3.14017331582173,1739137723.4770432,64.99993801116943,-0.16186391118685087,1739137723.477048,64.99993801116943,-0.035583540309690215,1739137723.4770522,64.99993801116943,2.3432647924097423,1739137723.4770575,64.99993801116943,0.0,1739137723.4770625,64.99993801116943,-0.05268801476148255,1739137723.4770677,64.99993801116943,3.1595393777110075,1739137723.4770725,64.99993801116943,2.395952807171225 +1739137723.4956636,65.01993799209595,1.9676962802666802,1739137723.4956741,65.01993799209595,0.053136263962381136,1739137723.4956884,65.01993799209595,110.53309667244402,1739137723.4957037,65.01993799209595,-6.390939935854739,1739137723.4957118,65.01993799209595,0.065,1739137723.495722,65.01993799209595,3.14017331582173,1739137723.4957304,65.01993799209595,-0.16186391118685087,1739137723.4957385,65.01993799209595,-0.035583540309690215,1739137723.4957469,65.01993799209595,2.3432647924097423,1739137723.4957552,65.01993799209595,0.0,1739137723.4957638,65.01993799209595,-0.05268801476148255,1739137723.4957724,65.01993799209595,3.1595393777110075,1739137723.49578,65.01993799209595,2.395952807171225 +1739137723.5148058,65.03993797302246,1.9676962802666802,1739137723.514811,65.03993797302246,0.053136263962381136,1739137723.5148165,65.03993797302246,110.53309667244402,1739137723.5148215,65.03993797302246,-6.390939935854739,1739137723.5148244,65.03993797302246,0.065,1739137723.5148277,65.03993797302246,3.14017331582173,1739137723.5148304,65.03993797302246,-0.16186391118685087,1739137723.514833,65.03993797302246,-0.035583540309690215,1739137723.5148351,65.03993797302246,2.3432647924097423,1739137723.5148385,65.03993797302246,0.0,1739137723.514841,65.03993797302246,-0.05268801476148255,1739137723.5148437,65.03993797302246,3.1595393777110075,1739137723.5148463,65.03993797302246,2.395952807171225 +1739137723.5315711,65.05993795394897,1.9676962802666802,1739137723.5315738,65.05993795394897,0.053136263962381136,1739137723.531577,65.05993795394897,110.53309667244402,1739137723.5315802,65.05993795394897,-6.390939935854739,1739137723.5315816,65.05993795394897,0.065,1739137723.5315835,65.05993795394897,3.14017331582173,1739137723.5315852,65.05993795394897,-0.16186391118685087,1739137723.531587,65.05993795394897,-0.035583540309690215,1739137723.531588,65.05993795394897,2.3432647924097423,1739137723.53159,65.05993795394897,0.0,1739137723.5315914,65.05993795394897,-0.05268801476148255,1739137723.5315933,65.05993795394897,3.1595393777110075,1739137723.5315948,65.05993795394897,2.395952807171225 +1739137723.559033,65.07993793487549,1.7044747912782565,1739137723.559041,65.07993793487549,0.04839028969010872,1739137723.5590506,65.07993793487549,110.82512678760318,1739137723.5590603,65.07993793487549,-6.665617505301917,1739137723.559065,65.07993793487549,0.065,1739137723.5590708,65.07993793487549,3.139608244348055,1739137723.559076,65.07993793487549,-0.16825761143752058,1739137723.5590804,65.07993793487549,-0.03688772260485374,1739137723.5590851,65.07993793487549,2.3372795961060007,1739137723.5590904,65.07993793487549,0.0,1739137723.5590951,65.07993793487549,-0.05307176969890803,1739137723.5591006,65.07993793487549,3.1597117997609465,1739137723.5591054,65.07993793487549,2.3901686252672287 +1739137723.5797145,65.099937915802,1.7044747912782565,1739137723.5797207,65.099937915802,0.04839028969010872,1739137723.579728,65.099937915802,110.82512678760318,1739137723.5797343,65.099937915802,-6.665617505301917,1739137723.5797377,65.099937915802,0.065,1739137723.579742,65.099937915802,3.139608244348055,1739137723.5797453,65.099937915802,-0.16825761143752058,1739137723.5797489,65.099937915802,-0.03688772260485374,1739137723.579752,65.099937915802,2.3372795961060007,1739137723.5797555,65.099937915802,0.0,1739137723.579759,65.099937915802,-0.05288902916122806,1739137723.5797625,65.099937915802,3.1597117997609465,1739137723.5797658,65.099937915802,2.3901686252672287 +1739137723.6017098,65.11993789672852,1.7044747912782565,1739137723.6017191,65.11993789672852,0.04839028969010872,1739137723.6017306,65.11993789672852,110.82512678760318,1739137723.601744,65.11993789672852,-6.665617505301917,1739137723.6017516,65.11993789672852,0.065,1739137723.601761,65.11993789672852,3.139608244348055,1739137723.6017697,65.11993789672852,-0.16825761143752058,1739137723.6017785,65.11993789672852,-0.03688772260485374,1739137723.6017869,65.11993789672852,2.3372795961060007,1739137723.601796,65.11993789672852,0.0,1739137723.6018045,65.11993789672852,-0.05288902916122806,1739137723.6018138,65.11993789672852,3.1597117997609465,1739137723.6018224,65.11993789672852,2.3901686252672287 +1739137723.6188366,65.14993786811829,1.7044747912782565,1739137723.6188412,65.14993786811829,0.04839028969010872,1739137723.6188462,65.14993786811829,110.82512678760318,1739137723.6188512,65.14993786811829,-6.665617505301917,1739137723.6188538,65.14993786811829,0.065,1739137723.618857,65.14993786811829,3.139608244348055,1739137723.6188598,65.14993786811829,-0.16825761143752058,1739137723.6188622,65.14993786811829,-0.03688772260485374,1739137723.6188645,65.14993786811829,2.3372795961060007,1739137723.6188674,65.14993786811829,0.0,1739137723.61887,65.14993786811829,-0.05288902916122806,1739137723.6188726,65.14993786811829,3.1597117997609465,1739137723.618875,65.14993786811829,2.3901686252672287 +1739137723.659435,65.17993783950806,1.4418883536523195,1739137723.65944,65.17993783950806,0.04361711805676283,1739137723.659446,65.17993783950806,111.57817119103584,1739137723.6594515,65.17993783950806,-7.401333755728636,1739137723.659454,65.17993783950806,0.065,1739137723.6594574,65.17993783950806,3.139174661594823,1739137723.6594605,65.17993783950806,-0.18254379045901498,1739137723.6594632,65.17993783950806,-0.035852050448419964,1739137723.6594656,65.17993783950806,2.3239613677739532,1739137723.6594687,65.17993783950806,0.0,1739137723.659471,65.17993783950806,-0.06728773787570758,1739137723.6594741,65.17993783950806,3.1598182935915067,1739137723.6594768,65.17993783950806,2.384392574265248 +1739137723.6797674,65.19993782043457,1.4418883536523195,1739137723.6797721,65.19993782043457,0.04361711805676283,1739137723.6797776,65.19993782043457,111.57817119103584,1739137723.6797826,65.19993782043457,-7.401333755728636,1739137723.6797855,65.19993782043457,0.065,1739137723.6797888,65.19993782043457,3.139174661594823,1739137723.6797917,65.19993782043457,-0.18254379045901498,1739137723.679794,65.19993782043457,-0.035852050448419964,1739137723.6797967,65.19993782043457,2.3239613677739532,1739137723.6797996,65.19993782043457,0.0,1739137723.6798022,65.19993782043457,-0.06043120649129463,1739137723.679805,65.19993782043457,3.1598182935915067,1739137723.6798074,65.19993782043457,2.384392574265248 +1739137723.6990383,65.22993779182434,1.4418883536523195,1739137723.6990428,65.22993779182434,0.04361711805676283,1739137723.6990485,65.22993779182434,111.57817119103584,1739137723.6990538,65.22993779182434,-7.401333755728636,1739137723.6990566,65.22993779182434,0.065,1739137723.6990602,65.22993779182434,3.139174661594823,1739137723.699063,65.22993779182434,-0.18254379045901498,1739137723.6990654,65.22993779182434,-0.035852050448419964,1739137723.6990678,65.22993779182434,2.3239613677739532,1739137723.6990707,65.22993779182434,0.0,1739137723.6990733,65.22993779182434,-0.06043120649129463,1739137723.6990762,65.22993779182434,3.1598182935915067,1739137723.6990786,65.22993779182434,2.384392574265248 +1739137723.7184045,65.2399377822876,1.4418883536523195,1739137723.71841,65.2399377822876,0.04361711805676283,1739137723.7184174,65.2399377822876,111.57817119103584,1739137723.7184258,65.2399377822876,-7.401333755728636,1739137723.7184305,65.2399377822876,0.065,1739137723.7184362,65.2399377822876,3.139174661594823,1739137723.718442,65.2399377822876,-0.18254379045901498,1739137723.7184474,65.2399377822876,-0.035852050448419964,1739137723.7184527,65.2399377822876,2.3239613677739532,1739137723.7184582,65.2399377822876,0.0,1739137723.7184634,65.2399377822876,-0.06043120649129463,1739137723.7184823,65.2399377822876,3.1598182935915067,1739137723.7184901,65.2399377822876,2.384392574265248 +1739137723.7375991,65.25993776321411,1.4418883536523195,1739137723.7376025,65.25993776321411,0.04361711805676283,1739137723.737606,65.25993776321411,111.57817119103584,1739137723.7376094,65.25993776321411,-7.401333755728636,1739137723.737611,65.25993776321411,0.065,1739137723.737613,65.25993776321411,3.139174661594823,1739137723.7376146,65.25993776321411,-0.18254379045901498,1739137723.737616,65.25993776321411,-0.035852050448419964,1739137723.737618,65.25993776321411,2.3239613677739532,1739137723.7376199,65.25993776321411,0.0,1739137723.7376215,65.25993776321411,-0.06043120649129463,1739137723.7376232,65.25993776321411,3.1598182935915067,1739137723.737625,65.25993776321411,2.384392574265248 +1739137723.7559507,65.27993774414062,1.4418883536523195,1739137723.7559526,65.27993774414062,0.04361711805676283,1739137723.7559552,65.27993774414062,111.57817119103584,1739137723.7559578,65.27993774414062,-7.401333755728636,1739137723.755959,65.27993774414062,0.065,1739137723.755961,65.27993774414062,3.139174661594823,1739137723.7559621,65.27993774414062,-0.18254379045901498,1739137723.7559633,65.27993774414062,-0.035852050448419964,1739137723.7559648,65.27993774414062,2.3239613677739532,1739137723.755966,65.27993774414062,0.0,1739137723.7559671,65.27993774414062,-0.06043120649129463,1739137723.7559686,65.27993774414062,3.1598182935915067,1739137723.7559698,65.27993774414062,2.384392574265248 +1739137723.7774675,65.29993772506714,1.1799783353314917,1739137723.7774696,65.29993772506714,0.038833051867003476,1739137723.777472,65.29993772506714,111.7330856283533,1739137723.777487,65.29993772506714,-7.536439917386183,1739137723.7774885,65.29993772506714,0.065,1739137723.77749,65.29993772506714,3.1385906327174986,1739137723.777491,65.29993772506714,-0.18575262157073813,1739137723.7774923,65.29993772506714,-0.03755116787644922,1739137723.7774932,65.29993772506714,2.320980401450958,1739137723.7774947,65.29993772506714,0.0,1739137723.7774959,65.29993772506714,-0.05351687272978375,1739137723.777497,65.29993772506714,3.1599028095316766,1739137723.777498,65.29993772506714,2.3777898157119437 +1739137723.7973666,65.31993770599365,1.1799783353314917,1739137723.7973692,65.31993770599365,0.038833051867003476,1739137723.797372,65.31993770599365,111.7330856283533,1739137723.7973747,65.31993770599365,-7.536439917386183,1739137723.7973764,65.31993770599365,0.065,1739137723.7973783,65.31993770599365,3.1385906327174986,1739137723.7973795,65.31993770599365,-0.18575262157073813,1739137723.797381,65.31993770599365,-0.03755116787644922,1739137723.797382,65.31993770599365,2.320980401450958,1739137723.7973838,65.31993770599365,0.0,1739137723.797385,65.31993770599365,-0.05680941426098585,1739137723.7973862,65.31993770599365,3.1599028095316766,1739137723.7973876,65.31993770599365,2.3777898157119437 +1739137723.817046,65.33993768692017,1.1799783353314917,1739137723.8170488,65.33993768692017,0.038833051867003476,1739137723.817052,65.33993768692017,111.7330856283533,1739137723.8170547,65.33993768692017,-7.536439917386183,1739137723.817056,65.33993768692017,0.065,1739137723.8170578,65.33993768692017,3.1385906327174986,1739137723.8170593,65.33993768692017,-0.18575262157073813,1739137723.8170607,65.33993768692017,-0.03755116787644922,1739137723.8170621,65.33993768692017,2.320980401450958,1739137723.8170636,65.33993768692017,0.0,1739137723.817065,65.33993768692017,-0.05680941426098585,1739137723.8170664,65.33993768692017,3.1599028095316766,1739137723.8170679,65.33993768692017,2.3777898157119437 +1739137723.83641,65.35993766784668,1.1799783353314917,1739137723.8364124,65.35993766784668,0.038833051867003476,1739137723.836415,65.35993766784668,111.7330856283533,1739137723.8364172,65.35993766784668,-7.536439917386183,1739137723.8364189,65.35993766784668,0.065,1739137723.8364203,65.35993766784668,3.1385906327174986,1739137723.836422,65.35993766784668,-0.18575262157073813,1739137723.8364232,65.35993766784668,-0.03755116787644922,1739137723.836424,65.35993766784668,2.320980401450958,1739137723.8364258,65.35993766784668,0.0,1739137723.836427,65.35993766784668,-0.05680941426098585,1739137723.8364284,65.35993766784668,3.1599028095316766,1739137723.8364296,65.35993766784668,2.3777898157119437 +1739137723.856415,65.3799376487732,1.1799783353314917,1739137723.856418,65.3799376487732,0.038833051867003476,1739137723.8564212,65.3799376487732,111.7330856283533,1739137723.8564234,65.3799376487732,-7.536439917386183,1739137723.856425,65.3799376487732,0.065,1739137723.8564267,65.3799376487732,3.1385906327174986,1739137723.8564281,65.3799376487732,-0.18575262157073813,1739137723.8564293,65.3799376487732,-0.03755116787644922,1739137723.8564305,65.3799376487732,2.320980401450958,1739137723.8564322,65.3799376487732,0.0,1739137723.8564334,65.3799376487732,-0.05680941426098585,1739137723.856435,65.3799376487732,3.1599028095316766,1739137723.8564365,65.3799376487732,2.3777898157119437 +1739137723.876434,65.3999376296997,0.9187776805153014,1739137723.8764372,65.3999376296997,0.034039859599436895,1739137723.8764405,65.3999376296997,111.74144404930742,1739137723.8764434,65.3999376296997,-7.526161499246037,1739137723.8764448,65.3999376296997,0.065,1739137723.8764465,65.3999376296997,3.137926552385639,1739137723.876448,65.3999376296997,-0.18628802772523806,1739137723.8764496,65.3999376296997,-0.04011911835602119,1739137723.8764508,65.3999376296997,2.320483387797127,1739137723.8764527,65.3999376296997,0.0,1739137723.876454,65.3999376296997,-0.04589844685784897,1739137723.8764553,65.3999376296997,3.1599873254718465,1739137723.876457,65.3999376296997,2.3715775360138545 +1739137723.8959715,65.41993761062622,0.9187776805153014,1739137723.8959742,65.41993761062622,0.034039859599436895,1739137723.895977,65.41993761062622,111.74144404930742,1739137723.89598,65.41993761062622,-7.526161499246037,1739137723.895981,65.41993761062622,0.065,1739137723.8959832,65.41993761062622,3.137926552385639,1739137723.8959846,65.41993761062622,-0.18628802772523806,1739137723.8959858,65.41993761062622,-0.04011911835602119,1739137723.8959873,65.41993761062622,2.320483387797127,1739137723.8959887,65.41993761062622,0.0,1739137723.8959904,65.41993761062622,-0.05109414821672731,1739137723.8959918,65.41993761062622,3.1599873254718465,1739137723.895993,65.41993761062622,2.3715775360138545 +1739137723.9163227,65.43993759155273,0.9187776805153014,1739137723.9163253,65.43993759155273,0.034039859599436895,1739137723.9163282,65.43993759155273,111.74144404930742,1739137723.916331,65.43993759155273,-7.526161499246037,1739137723.9163322,65.43993759155273,0.065,1739137723.9163342,65.43993759155273,3.137926552385639,1739137723.9163353,65.43993759155273,-0.18628802772523806,1739137723.9163365,65.43993759155273,-0.04011911835602119,1739137723.916338,65.43993759155273,2.320483387797127,1739137723.9163396,65.43993759155273,0.0,1739137723.916341,65.43993759155273,-0.05109414821672731,1739137723.9163425,65.43993759155273,3.1599873254718465,1739137723.9163435,65.43993759155273,2.3715775360138545 +1739137723.9362922,65.45993757247925,0.9187776805153014,1739137723.9362943,65.45993757247925,0.034039859599436895,1739137723.9362972,65.45993757247925,111.74144404930742,1739137723.9362998,65.45993757247925,-7.526161499246037,1739137723.936301,65.45993757247925,0.065,1739137723.9363031,65.45993757247925,3.137926552385639,1739137723.9363043,65.45993757247925,-0.18628802772523806,1739137723.9363058,65.45993757247925,-0.04011911835602119,1739137723.936307,65.45993757247925,2.320483387797127,1739137723.9363084,65.45993757247925,0.0,1739137723.9363098,65.45993757247925,-0.05109414821672731,1739137723.936311,65.45993757247925,3.1599873254718465,1739137723.9363124,65.45993757247925,2.3715775360138545 +1739137723.956824,65.48993754386902,0.9187776805153014,1739137723.956827,65.48993754386902,0.034039859599436895,1739137723.95683,65.48993754386902,111.74144404930742,1739137723.9568334,65.48993754386902,-7.526161499246037,1739137723.9568348,65.48993754386902,0.065,1739137723.9568367,65.48993754386902,3.137926552385639,1739137723.9568384,65.48993754386902,-0.18628802772523806,1739137723.9568396,65.48993754386902,-0.04011911835602119,1739137723.9568412,65.48993754386902,2.320483387797127,1739137723.9568427,65.48993754386902,0.0,1739137723.9568443,65.48993754386902,-0.05109414821672731,1739137723.9568458,65.48993754386902,3.1599873254718465,1739137723.9568474,65.48993754386902,2.3715775360138545 +1739137723.976783,65.49993753433228,0.9187776805153014,1739137723.9767864,65.49993753433228,0.034039859599436895,1739137723.97679,65.49993753433228,111.74144404930742,1739137723.976793,65.49993753433228,-7.526161499246037,1739137723.9767947,65.49993753433228,0.065,1739137723.9767966,65.49993753433228,3.137926552385639,1739137723.9767983,65.49993753433228,-0.18628802772523806,1739137723.9767997,65.49993753433228,-0.04011911835602119,1739137723.976801,65.49993753433228,2.320483387797127,1739137723.9768028,65.49993753433228,0.0,1739137723.9768043,65.49993753433228,-0.05109414821672731,1739137723.9768062,65.49993753433228,3.1599873254718465,1739137723.9768074,65.49993753433228,2.3715775360138545 +1739137723.997015,65.51993751525879,0.658228845004504,1739137723.9970176,65.51993751525879,0.02924772368281392,1739137723.997021,65.51993751525879,111.74978161204375,1739137723.9970238,65.51993751525879,-7.517722571845958,1739137723.9970255,65.51993751525879,0.065,1739137723.9970276,65.51993751525879,3.1372198232470847,1739137723.997029,65.51993751525879,-0.18580261509977436,1739137723.9970307,65.51993751525879,-0.04269026135453366,1739137723.997032,65.51993751525879,2.320933988314594,1739137723.9970338,65.51993751525879,0.0,1739137723.9970355,65.51993751525879,-0.03955795735763251,1739137723.9970372,65.51993751525879,3.1599470662768328,1739137723.9970386,65.51993751525879,2.3659853726350497 +1739137724.0168087,65.5399374961853,0.658228845004504,1739137724.0168118,65.5399374961853,0.02924772368281392,1739137724.0168152,65.5399374961853,111.74978161204375,1739137724.0168185,65.5399374961853,-7.517722571845958,1739137724.0168204,65.5399374961853,0.065,1739137724.0168223,65.5399374961853,3.1372198232470847,1739137724.016824,65.5399374961853,-0.18580261509977436,1739137724.0168257,65.5399374961853,-0.04269026135453366,1739137724.016827,65.5399374961853,2.320933988314594,1739137724.016829,65.5399374961853,0.0,1739137724.0168304,65.5399374961853,-0.045051384320455856,1739137724.016832,65.5399374961853,3.1599470662768328,1739137724.0168335,65.5399374961853,2.3659853726350497 +1739137724.0363474,65.55993747711182,0.658228845004504,1739137724.036351,65.55993747711182,0.02924772368281392,1739137724.0363545,65.55993747711182,111.74978161204375,1739137724.036358,65.55993747711182,-7.517722571845958,1739137724.0363598,65.55993747711182,0.065,1739137724.036362,65.55993747711182,3.1372198232470847,1739137724.0363638,65.55993747711182,-0.18580261509977436,1739137724.0363653,65.55993747711182,-0.04269026135453366,1739137724.036367,65.55993747711182,2.320933988314594,1739137724.0363686,65.55993747711182,0.0,1739137724.0363708,65.55993747711182,-0.045051384320455856,1739137724.0363724,65.55993747711182,3.1599470662768328,1739137724.0363743,65.55993747711182,2.3659853726350497 +1739137724.0564206,65.57993745803833,0.658228845004504,1739137724.0564232,65.57993745803833,0.02924772368281392,1739137724.0564268,65.57993745803833,111.74978161204375,1739137724.0564303,65.57993745803833,-7.517722571845958,1739137724.0564318,65.57993745803833,0.065,1739137724.0564342,65.57993745803833,3.1372198232470847,1739137724.0564358,65.57993745803833,-0.18580261509977436,1739137724.0564375,65.57993745803833,-0.04269026135453366,1739137724.056439,65.57993745803833,2.320933988314594,1739137724.0564408,65.57993745803833,0.0,1739137724.0564427,65.57993745803833,-0.045051384320455856,1739137724.0564444,65.57993745803833,3.1599470662768328,1739137724.0564458,65.57993745803833,2.3659853726350497 +1739137724.076511,65.59993743896484,0.658228845004504,1739137724.0765147,65.59993743896484,0.02924772368281392,1739137724.0765183,65.59993743896484,111.74978161204375,1739137724.0765219,65.59993743896484,-7.517722571845958,1739137724.076524,65.59993743896484,0.065,1739137724.0765262,65.59993743896484,3.1372198232470847,1739137724.0765278,65.59993743896484,-0.18580261509977436,1739137724.07653,65.59993743896484,-0.04269026135453366,1739137724.0765314,65.59993743896484,2.320933988314594,1739137724.0765336,65.59993743896484,0.0,1739137724.0765352,65.59993743896484,-0.045051384320455856,1739137724.0765374,65.59993743896484,3.1599470662768328,1739137724.0765388,65.59993743896484,2.3659853726350497 +1739137724.0972946,65.61993741989136,0.39826324394445844,1739137724.097298,65.61993741989136,0.024489628467037505,1739137724.0973015,65.61993741989136,112.02760255703697,1739137724.0973046,65.61993741989136,-7.780749019672832,1739137724.0973063,65.61993741989136,0.065,1739137724.0973084,65.61993741989136,3.136639727861472,1739137724.0973103,65.61993741989136,-0.18950595627991415,1739137724.0973117,65.61993741989136,-0.04350821418801565,1739137724.0973136,65.61993741989136,2.317498449371272,1739137724.0973153,65.61993741989136,0.0,1739137724.0973172,65.61993741989136,-0.04219545917307476,1739137724.0973191,65.61993741989136,3.1598113022417857,1739137724.0973208,65.61993741989136,2.3610538735796043 +1739137724.1184244,65.63993740081787,0.39826324394445844,1739137724.1184292,65.63993740081787,0.024489628467037505,1739137724.1184351,65.63993740081787,112.02760255703697,1739137724.1184418,65.63993740081787,-7.780749019672832,1739137724.1184456,65.63993740081787,0.065,1739137724.1184504,65.63993740081787,3.136639727861472,1739137724.1184547,65.63993740081787,-0.18950595627991415,1739137724.1184592,65.63993740081787,-0.04350821418801565,1739137724.1184635,65.63993740081787,2.317498449371272,1739137724.1184802,65.63993740081787,0.0,1739137724.1184857,65.63993740081787,-0.04355542420833247,1739137724.1184905,65.63993740081787,3.1598113022417857,1739137724.118495,65.63993740081787,2.3610538735796043 +1739137724.136668,65.65993738174438,0.39826324394445844,1739137724.136671,65.65993738174438,0.024489628467037505,1739137724.1366744,65.65993738174438,112.02760255703697,1739137724.1366777,65.65993738174438,-7.780749019672832,1739137724.1366792,65.65993738174438,0.065,1739137724.1366813,65.65993738174438,3.136639727861472,1739137724.136683,65.65993738174438,-0.18950595627991415,1739137724.1366847,65.65993738174438,-0.04350821418801565,1739137724.136686,65.65993738174438,2.317498449371272,1739137724.1366878,65.65993738174438,0.0,1739137724.1366897,65.65993738174438,-0.04355542420833247,1739137724.1366916,65.65993738174438,3.1598113022417857,1739137724.136693,65.65993738174438,2.3610538735796043 +1739137724.15927,65.68993735313416,0.39826324394445844,1739137724.1592746,65.68993735313416,0.024489628467037505,1739137724.1592793,65.68993735313416,112.02760255703697,1739137724.159284,65.68993735313416,-7.780749019672832,1739137724.1592867,65.68993735313416,0.065,1739137724.1592898,65.68993735313416,3.136639727861472,1739137724.1592925,65.68993735313416,-0.18950595627991415,1739137724.1592953,65.68993735313416,-0.04350821418801565,1739137724.1592977,65.68993735313416,2.317498449371272,1739137724.1593008,65.68993735313416,0.0,1739137724.1593037,65.68993735313416,-0.04355542420833247,1739137724.159307,65.68993735313416,3.1598113022417857,1739137724.1593096,65.68993735313416,2.3610538735796043 +1739137724.1773064,65.69993734359741,0.39826324394445844,1739137724.1773107,65.69993734359741,0.024489628467037505,1739137724.1773152,65.69993734359741,112.02760255703697,1739137724.1773198,65.69993734359741,-7.780749019672832,1739137724.177322,65.69993734359741,0.065,1739137724.1773264,65.69993734359741,3.136639727861472,1739137724.1773288,65.69993734359741,-0.18950595627991415,1739137724.1773314,65.69993734359741,-0.04350821418801565,1739137724.177334,65.69993734359741,2.317498449371272,1739137724.1773367,65.69993734359741,0.0,1739137724.177339,65.69993734359741,-0.04355542420833247,1739137724.177342,65.69993734359741,3.1598113022417857,1739137724.1773462,65.69993734359741,2.3610538735796043 +1739137724.1974726,65.71993732452393,0.39826324394445844,1739137724.1974766,65.71993732452393,0.024489628467037505,1739137724.1974812,65.71993732452393,112.02760255703697,1739137724.1974852,65.71993732452393,-7.780749019672832,1739137724.197488,65.71993732452393,0.065,1739137724.197491,65.71993732452393,3.136639727861472,1739137724.1974936,65.71993732452393,-0.18950595627991415,1739137724.1974964,65.71993732452393,-0.04350821418801565,1739137724.1974986,65.71993732452393,2.317498449371272,1739137724.1975014,65.71993732452393,0.0,1739137724.197504,65.71993732452393,-0.04355542420833247,1739137724.1975076,65.71993732452393,3.1598113022417857,1739137724.1975102,65.71993732452393,2.3610538735796043 +1739137724.2177162,65.73993730545044,0.13882632615041057,1739137724.2177205,65.73993730545044,0.019781125367727803,1739137724.217726,65.73993730545044,112.75827786648497,1739137724.2177305,65.73993730545044,-8.497201531121924,1739137724.2177334,65.73993730545044,0.065,1739137724.2177362,65.73993730545044,3.136356628169404,1739137724.217739,65.73993730545044,-0.20117687086650052,1739137724.2177415,65.73993730545044,-0.04142873572160999,1739137724.2177436,65.73993730545044,2.306704732899867,1739137724.2177467,65.73993730545044,0.0,1739137724.2177494,65.73993730545044,-0.055110743992965186,1739137724.217752,65.73993730545044,3.159653485854577,1739137724.2177546,65.73993730545044,2.3563129409132975 +1739137724.2380877,65.75993728637695,0.13882632615041057,1739137724.238092,65.75993728637695,0.019781125367727803,1739137724.2380967,65.75993728637695,112.75827786648497,1739137724.238101,65.75993728637695,-8.497201531121924,1739137724.2381034,65.75993728637695,0.065,1739137724.238106,65.75993728637695,3.136356628169404,1739137724.2381086,65.75993728637695,-0.20117687086650052,1739137724.238111,65.75993728637695,-0.04142873572160999,1739137724.2381132,65.75993728637695,2.306704732899867,1739137724.2381165,65.75993728637695,0.0,1739137724.2381191,65.75993728637695,-0.04960820801343058,1739137724.238122,65.75993728637695,3.159653485854577,1739137724.2381246,65.75993728637695,2.3563129409132975 +1739137724.2572472,65.77993726730347,0.13882632615041057,1739137724.257251,65.77993726730347,0.019781125367727803,1739137724.2572558,65.77993726730347,112.75827786648497,1739137724.2572603,65.77993726730347,-8.497201531121924,1739137724.2572627,65.77993726730347,0.065,1739137724.2572653,65.77993726730347,3.136356628169404,1739137724.2572677,65.77993726730347,-0.20117687086650052,1739137724.25727,65.77993726730347,-0.04142873572160999,1739137724.257272,65.77993726730347,2.306704732899867,1739137724.2572749,65.77993726730347,0.0,1739137724.257277,65.77993726730347,-0.04960820801343058,1739137724.2572794,65.77993726730347,3.159653485854577,1739137724.2572815,65.77993726730347,2.3563129409132975 +1739137724.2772942,65.79993724822998,0.13882632615041057,1739137724.277299,65.79993724822998,0.019781125367727803,1739137724.277305,65.79993724822998,112.75827786648497,1739137724.2773092,65.79993724822998,-8.497201531121924,1739137724.2773118,65.79993724822998,0.065,1739137724.2773159,65.79993724822998,3.136356628169404,1739137724.2773187,65.79993724822998,-0.20117687086650052,1739137724.2773218,65.79993724822998,-0.04142873572160999,1739137724.2773242,65.79993724822998,2.306704732899867,1739137724.277327,65.79993724822998,0.0,1739137724.27733,65.79993724822998,-0.04960820801343058,1739137724.277333,65.79993724822998,3.159653485854577,1739137724.2773356,65.79993724822998,2.3563129409132975 +1739137724.297341,65.8199372291565,0.13882632615041057,1739137724.297344,65.8199372291565,0.019781125367727803,1739137724.2973468,65.8199372291565,112.75827786648497,1739137724.2973495,65.8199372291565,-8.497201531121924,1739137724.297351,65.8199372291565,0.065,1739137724.2973526,65.8199372291565,3.136356628169404,1739137724.297354,65.8199372291565,-0.20117687086650052,1739137724.2973554,65.8199372291565,-0.04142873572160999,1739137724.2973568,65.8199372291565,2.306704732899867,1739137724.2973583,65.8199372291565,0.0,1739137724.2973597,65.8199372291565,-0.04960820801343058,1739137724.2973611,65.8199372291565,3.159653485854577,1739137724.2973623,65.8199372291565,2.3563129409132975 +1739137724.316735,65.83993721008301,-0.12004747696748597,1739137724.3167377,65.83993721008301,0.01512370884543568,1739137724.3167405,65.83993721008301,112.76138900953892,1739137724.3167431,65.83993721008301,-8.483723327193992,1739137724.3167448,65.83993721008301,0.065,1739137724.3167465,65.83993721008301,3.1356292828403474,1739137724.3167481,65.83993721008301,-0.19959532111938008,1739137724.3167493,65.83993721008301,-0.043822873452113775,1739137724.3167505,65.83993721008301,2.3081644618927877,1739137724.3167522,65.83993721008301,0.0,1739137724.3167534,65.83993721008301,-0.036264589433273826,1739137724.316755,65.83993721008301,3.1594956694673684,1739137724.3167562,65.83993721008301,2.3507831585860046 +1739137724.336922,65.85993719100952,-0.12004747696748597,1739137724.3369243,65.85993719100952,0.01512370884543568,1739137724.3369274,65.85993719100952,112.76138900953892,1739137724.3369303,65.85993719100952,-8.483723327193992,1739137724.3369315,65.85993719100952,0.065,1739137724.3369336,65.85993719100952,3.1356292828403474,1739137724.3369348,65.85993719100952,-0.19959532111938008,1739137724.3369362,65.85993719100952,-0.043822873452113775,1739137724.3369374,65.85993719100952,2.3081644618927877,1739137724.336939,65.85993719100952,0.0,1739137724.3369403,65.85993719100952,-0.04261869669321694,1739137724.3369417,65.85993719100952,3.1594956694673684,1739137724.3369434,65.85993719100952,2.3507831585860046 +1739137724.3571904,65.87993717193604,-0.12004747696748597,1739137724.3571928,65.87993717193604,0.01512370884543568,1739137724.3571956,65.87993717193604,112.76138900953892,1739137724.357198,65.87993717193604,-8.483723327193992,1739137724.3571994,65.87993717193604,0.065,1739137724.357201,65.87993717193604,3.1356292828403474,1739137724.3572028,65.87993717193604,-0.19959532111938008,1739137724.3572042,65.87993717193604,-0.043822873452113775,1739137724.3572052,65.87993717193604,2.3081644618927877,1739137724.357207,65.87993717193604,0.0,1739137724.3572083,65.87993717193604,-0.04261869669321694,1739137724.3572097,65.87993717193604,3.1594956694673684,1739137724.3572109,65.87993717193604,2.3507831585860046 +1739137724.3767362,65.89993715286255,-0.12004747696748597,1739137724.3767393,65.89993715286255,0.01512370884543568,1739137724.3767424,65.89993715286255,112.76138900953892,1739137724.3767452,65.89993715286255,-8.483723327193992,1739137724.3767467,65.89993715286255,0.065,1739137724.3767486,65.89993715286255,3.1356292828403474,1739137724.3767498,65.89993715286255,-0.19959532111938008,1739137724.3767512,65.89993715286255,-0.043822873452113775,1739137724.3767524,65.89993715286255,2.3081644618927877,1739137724.3767538,65.89993715286255,0.0,1739137724.3767552,65.89993715286255,-0.04261869669321694,1739137724.3767567,65.89993715286255,3.1594956694673684,1739137724.376758,65.89993715286255,2.3507831585860046 +1739137724.3990684,65.92993712425232,-0.12004747696748597,1739137724.3990731,65.92993712425232,0.01512370884543568,1739137724.3990784,65.92993712425232,112.76138900953892,1739137724.399083,65.92993712425232,-8.483723327193992,1739137724.3990855,65.92993712425232,0.065,1739137724.3990884,65.92993712425232,3.1356292828403474,1739137724.399091,65.92993712425232,-0.19959532111938008,1739137724.3990934,65.92993712425232,-0.043822873452113775,1739137724.3990953,65.92993712425232,2.3081644618927877,1739137724.3990982,65.92993712425232,0.0,1739137724.3991,65.92993712425232,-0.04261869669321694,1739137724.3991024,65.92993712425232,3.1594956694673684,1739137724.3991048,65.92993712425232,2.3507831585860046 +1739137724.4174392,65.93993711471558,-0.12004747696748597,1739137724.4174447,65.93993711471558,0.01512370884543568,1739137724.417451,65.93993711471558,112.76138900953892,1739137724.4174588,65.93993711471558,-8.483723327193992,1739137724.4174633,65.93993711471558,0.065,1739137724.417469,65.93993711471558,3.1356292828403474,1739137724.417472,65.93993711471558,-0.19959532111938008,1739137724.4174743,65.93993711471558,-0.043822873452113775,1739137724.4174767,65.93993711471558,2.3081644618927877,1739137724.4174798,65.93993711471558,0.0,1739137724.4174829,65.93993711471558,-0.04261869669321694,1739137724.4174852,65.93993711471558,3.1594956694673684,1739137724.4174871,65.93993711471558,2.3507831585860046 +1739137724.436369,65.95993709564209,-0.3783709900919239,1739137724.4363718,65.95993709564209,0.01052474747144938,1739137724.4363744,65.95993709564209,112.76449349065778,1739137724.4363773,65.95993709564209,-8.47320939055873,1739137724.4363787,65.95993709564209,0.065,1739137724.4363801,65.95993709564209,3.1348631270076144,1739137724.4363816,65.95993709564209,-0.19750838757224498,1739137724.436383,65.95993709564209,-0.046292032955913054,1739137724.436384,65.95993709564209,2.310092060674095,1739137724.4363856,65.95993709564209,0.0,1739137724.4363873,65.95993709564209,-0.030272463933105925,1739137724.436389,65.95993709564209,3.159264295564246,1739137724.4363902,65.95993709564209,2.3462436860012947 +1739137724.4582503,65.9799370765686,-0.3783709900919239,1739137724.4582546,65.9799370765686,0.01052474747144938,1739137724.4582598,65.9799370765686,112.76449349065778,1739137724.458264,65.9799370765686,-8.47320939055873,1739137724.4582663,65.9799370765686,0.065,1739137724.4582698,65.9799370765686,3.1348631270076144,1739137724.458273,65.9799370765686,-0.19750838757224498,1739137724.4582758,65.9799370765686,-0.046292032955913054,1739137724.4582782,65.9799370765686,2.310092060674095,1739137724.4582818,65.9799370765686,0.0,1739137724.4582846,65.9799370765686,-0.03615162532719962,1739137724.4582875,65.9799370765686,3.159264295564246,1739137724.4582896,65.9799370765686,2.3462436860012947 +1739137724.477314,65.99993705749512,-0.3783709900919239,1739137724.4773178,65.99993705749512,0.01052474747144938,1739137724.4773228,65.99993705749512,112.76449349065778,1739137724.4773278,65.99993705749512,-8.47320939055873,1739137724.4773307,65.99993705749512,0.065,1739137724.4773345,65.99993705749512,3.1348631270076144,1739137724.4773378,65.99993705749512,-0.19750838757224498,1739137724.4773417,65.99993705749512,-0.046292032955913054,1739137724.477345,65.99993705749512,2.310092060674095,1739137724.4773486,65.99993705749512,0.0,1739137724.4773521,65.99993705749512,-0.03615162532719962,1739137724.4773557,65.99993705749512,3.159264295564246,1739137724.4773593,65.99993705749512,2.3462436860012947 +1739137724.4981601,66.01993703842163,-0.3783709900919239,1739137724.4981637,66.01993703842163,0.01052474747144938,1739137724.4981685,66.01993703842163,112.76449349065778,1739137724.4981737,66.01993703842163,-8.47320939055873,1739137724.4981766,66.01993703842163,0.065,1739137724.4981804,66.01993703842163,3.1348631270076144,1739137724.4981837,66.01993703842163,-0.19750838757224498,1739137724.498187,66.01993703842163,-0.046292032955913054,1739137724.4981902,66.01993703842163,2.310092060674095,1739137724.498194,66.01993703842163,0.0,1739137724.4981973,66.01993703842163,-0.03615162532719962,1739137724.4982007,66.01993703842163,3.159264295564246,1739137724.4982042,66.01993703842163,2.3462436860012947 +1739137724.517565,66.03993701934814,-0.3783709900919239,1739137724.5175683,66.03993701934814,0.01052474747144938,1739137724.517572,66.03993701934814,112.76449349065778,1739137724.5175745,66.03993701934814,-8.47320939055873,1739137724.5175765,66.03993701934814,0.065,1739137724.5175781,66.03993701934814,3.1348631270076144,1739137724.5175803,66.03993701934814,-0.19750838757224498,1739137724.517582,66.03993701934814,-0.046292032955913054,1739137724.5175834,66.03993701934814,2.310092060674095,1739137724.517585,66.03993701934814,0.0,1739137724.5175867,66.03993701934814,-0.03615162532719962,1739137724.5175884,66.03993701934814,3.159264295564246,1739137724.51759,66.03993701934814,2.3462436860012947 +1739137724.5375154,66.05993700027466,-0.6362279326340667,1739137724.537518,66.05993700027466,0.006001714994570584,1739137724.5375214,66.05993700027466,112.77801515810295,1739137724.537524,66.05993700027466,-8.475204630242779,1739137724.5375254,66.05993700027466,0.065,1739137724.537527,66.05993700027466,3.1340665218844497,1739137724.5375285,66.05993700027466,-0.19511902380366047,1739137724.53753,66.05993700027466,-0.048765112497941965,1739137724.5375311,66.05993700027466,2.312300976195241,1739137724.5375326,66.05993700027466,0.0,1739137724.5375338,66.05993700027466,-0.024599600056359836,1739137724.5375352,66.05993700027466,3.158959267084502,1739137724.5375366,66.05993700027466,2.34240154341426 +1739137724.5579247,66.07993698120117,-0.6362279326340667,1739137724.5579288,66.07993698120117,0.006001714994570584,1739137724.5579336,66.07993698120117,112.77801515810295,1739137724.5579386,66.07993698120117,-8.475204630242779,1739137724.5579414,66.07993698120117,0.065,1739137724.5579455,66.07993698120117,3.1340665218844497,1739137724.5579488,66.07993698120117,-0.19511902380366047,1739137724.5579524,66.07993698120117,-0.048765112497941965,1739137724.5579557,66.07993698120117,2.312300976195241,1739137724.5579588,66.07993698120117,0.0,1739137724.5579622,66.07993698120117,-0.03010056721901888,1739137724.5579658,66.07993698120117,3.158959267084502,1739137724.557969,66.07993698120117,2.34240154341426 +1739137724.5767746,66.09993696212769,-0.6362279326340667,1739137724.576777,66.09993696212769,0.006001714994570584,1739137724.5767803,66.09993696212769,112.77801515810295,1739137724.5767827,66.09993696212769,-8.475204630242779,1739137724.5767844,66.09993696212769,0.065,1739137724.5767863,66.09993696212769,3.1340665218844497,1739137724.5767875,66.09993696212769,-0.19511902380366047,1739137724.5767887,66.09993696212769,-0.048765112497941965,1739137724.57679,66.09993696212769,2.312300976195241,1739137724.5767913,66.09993696212769,0.0,1739137724.5767925,66.09993696212769,-0.03010056721901888,1739137724.576794,66.09993696212769,3.158959267084502,1739137724.576795,66.09993696212769,2.34240154341426 +1739137724.5971136,66.1199369430542,-0.6362279326340667,1739137724.5971165,66.1199369430542,0.006001714994570584,1739137724.5971198,66.1199369430542,112.77801515810295,1739137724.5971222,66.1199369430542,-8.475204630242779,1739137724.5971239,66.1199369430542,0.065,1739137724.5971253,66.1199369430542,3.1340665218844497,1739137724.597127,66.1199369430542,-0.19511902380366047,1739137724.5971282,66.1199369430542,-0.048765112497941965,1739137724.597129,66.1199369430542,2.312300976195241,1739137724.5971308,66.1199369430542,0.0,1739137724.597132,66.1199369430542,-0.03010056721901888,1739137724.5971339,66.1199369430542,3.158959267084502,1739137724.597135,66.1199369430542,2.34240154341426 +1739137724.6181161,66.13993692398071,-0.6362279326340667,1739137724.6181195,66.13993692398071,0.006001714994570584,1739137724.6181242,66.13993692398071,112.77801515810295,1739137724.6181295,66.13993692398071,-8.475204630242779,1739137724.618132,66.13993692398071,0.065,1739137724.6181362,66.13993692398071,3.1340665218844497,1739137724.6181397,66.13993692398071,-0.19511902380366047,1739137724.618143,66.13993692398071,-0.048765112497941965,1739137724.618146,66.13993692398071,2.312300976195241,1739137724.6181493,66.13993692398071,0.0,1739137724.6181526,66.13993692398071,-0.03010056721901888,1739137724.618156,66.13993692398071,3.158959267084502,1739137724.6181593,66.13993692398071,2.34240154341426 +1739137724.6514277,66.16993689537048,-0.8936882295979967,1739137724.6514323,66.16993689537048,0.0015736904319449962,1739137724.6514373,66.16993689537048,112.77801515810295,1739137724.6514428,66.16993689537048,-8.465314268360665,1739137724.6514459,66.16993689537048,0.065,1739137724.6514494,66.16993689537048,3.1332160082386684,1739137724.6514523,66.16993689537048,-0.19198064365325873,1739137724.6514554,66.16993689537048,-0.05142772681261071,1739137724.6514587,66.16993689537048,2.3152055507397935,1739137724.6514618,66.16993689537048,0.0,1739137724.6514652,66.16993689537048,-0.01826159833254218,1739137724.6514683,66.16993689537048,3.158573108738822,1739137724.6514714,66.16993689537048,2.3391047561202223 +1739137724.6836202,66.19993686676025,-0.8936882295979967,1739137724.6836233,66.19993686676025,0.0015736904319449962,1739137724.683627,66.19993686676025,112.77801515810295,1739137724.6836302,66.19993686676025,-8.465314268360665,1739137724.6836321,66.19993686676025,0.065,1739137724.6836343,66.19993686676025,3.1332160082386684,1739137724.683636,66.19993686676025,-0.19198064365325873,1739137724.6836379,66.19993686676025,-0.05142772681261071,1739137724.6836393,66.19993686676025,2.3152055507397935,1739137724.6836407,66.19993686676025,0.0,1739137724.6836424,66.19993686676025,-0.02389920538042878,1739137724.6836438,66.19993686676025,3.158573108738822,1739137724.6836452,66.19993686676025,2.3391047561202223 +1739137724.7084343,66.22993683815002,-0.8936882295979967,1739137724.7084394,66.22993683815002,0.0015736904319449962,1739137724.7084455,66.22993683815002,112.77801515810295,1739137724.7084496,66.22993683815002,-8.465314268360665,1739137724.7084515,66.22993683815002,0.065,1739137724.7084556,66.22993683815002,3.1332160082386684,1739137724.70846,66.22993683815002,-0.19198064365325873,1739137724.7084637,66.22993683815002,-0.05142772681261071,1739137724.708467,66.22993683815002,2.3152055507397935,1739137724.7084706,66.22993683815002,0.0,1739137724.7084742,66.22993683815002,-0.02389920538042878,1739137724.7084782,66.22993683815002,3.158573108738822,1739137724.7084816,66.22993683815002,2.3391047561202223 +1739137724.72679,66.24993681907654,-0.8936882295979967,1739137724.7267928,66.24993681907654,0.0015736904319449962,1739137724.7267962,66.24993681907654,112.77801515810295,1739137724.7267988,66.24993681907654,-8.465314268360665,1739137724.7268004,66.24993681907654,0.065,1739137724.726802,66.24993681907654,3.1332160082386684,1739137724.7268038,66.24993681907654,-0.19198064365325873,1739137724.726805,66.24993681907654,-0.05142772681261071,1739137724.7268066,66.24993681907654,2.3152055507397935,1739137724.726808,66.24993681907654,0.0,1739137724.7268095,66.24993681907654,-0.02389920538042878,1739137724.7268112,66.24993681907654,3.158573108738822,1739137724.7268126,66.24993681907654,2.3391047561202223 +1739137724.7466745,66.26993680000305,-0.8936882295979967,1739137724.7466772,66.26993680000305,0.0015736904319449962,1739137724.7466805,66.26993680000305,112.77801515810295,1739137724.7466834,66.26993680000305,-8.465314268360665,1739137724.7466848,66.26993680000305,0.065,1739137724.7466865,66.26993680000305,3.1332160082386684,1739137724.746688,66.26993680000305,-0.19198064365325873,1739137724.7466893,66.26993680000305,-0.05142772681261071,1739137724.7466905,66.26993680000305,2.3152055507397935,1739137724.746692,66.26993680000305,0.0,1739137724.7466934,66.26993680000305,-0.02389920538042878,1739137724.7466948,66.26993680000305,3.158573108738822,1739137724.7466962,66.26993680000305,2.3391047561202223 +1739137724.7666585,66.28993678092957,-1.1508377959867588,1739137724.766662,66.28993678092957,-0.0027323876737188613,1739137724.7666655,66.28993678092957,112.77801515810295,1739137724.766669,66.28993678092957,-8.457968561759749,1739137724.7666707,66.28993678092957,0.065,1739137724.766673,66.28993678092957,3.1323235642484337,1739137724.7666748,66.28993678092957,-0.18784080077202234,1739137724.7666771,66.28993678092957,-0.05402603827257983,1739137724.7666788,66.28993678092957,2.3190425616746078,1739137724.7666805,66.28993678092957,0.0,1739137724.7666824,66.28993678092957,-0.01189945667301118,1739137724.7666862,66.28993678092957,3.15803179766737,1739137724.7666876,66.28993678092957,2.336656187253247 +1739137724.7869527,66.30993676185608,-1.1508377959867588,1739137724.7869563,66.30993676185608,-0.0027323876737188613,1739137724.7869613,66.30993676185608,112.77801515810295,1739137724.7869642,66.30993676185608,-8.457968561759749,1739137724.7869658,66.30993676185608,0.065,1739137724.7869678,66.30993676185608,3.1323235642484337,1739137724.7869694,66.30993676185608,-0.18784080077202234,1739137724.7869709,66.30993676185608,-0.05402603827257983,1739137724.7869725,66.30993676185608,2.3190425616746078,1739137724.7869742,66.30993676185608,0.0,1739137724.786976,66.30993676185608,-0.017613625578639436,1739137724.7869782,66.30993676185608,3.15803179766737,1739137724.78698,66.30993676185608,2.336656187253247 +1739137724.8078904,66.32993674278259,-1.1508377959867588,1739137724.8078942,66.32993674278259,-0.0027323876737188613,1739137724.8078992,66.32993674278259,112.77801515810295,1739137724.8079045,66.32993674278259,-8.457968561759749,1739137724.8079073,66.32993674278259,0.065,1739137724.8079112,66.32993674278259,3.1323235642484337,1739137724.8079145,66.32993674278259,-0.18784080077202234,1739137724.807918,66.32993674278259,-0.05402603827257983,1739137724.8079214,66.32993674278259,2.3190425616746078,1739137724.807925,66.32993674278259,0.0,1739137724.8079286,66.32993674278259,-0.017613625578639436,1739137724.8079321,66.32993674278259,3.15803179766737,1739137724.807936,66.32993674278259,2.336656187253247 +1739137724.8271298,66.3499367237091,-1.1508377959867588,1739137724.8271344,66.3499367237091,-0.0027323876737188613,1739137724.8271403,66.3499367237091,112.77801515810295,1739137724.8271458,66.3499367237091,-8.457968561759749,1739137724.827149,66.3499367237091,0.065,1739137724.8271534,66.3499367237091,3.1323235642484337,1739137724.827157,66.3499367237091,-0.18784080077202234,1739137724.8271608,66.3499367237091,-0.05402603827257983,1739137724.8271646,66.3499367237091,2.3190425616746078,1739137724.8271685,66.3499367237091,0.0,1739137724.827172,66.3499367237091,-0.017613625578639436,1739137724.8271768,66.3499367237091,3.15803179766737,1739137724.8271809,66.3499367237091,2.336656187253247 +1739137724.8459911,66.36993670463562,-1.1508377959867588,1739137724.8459938,66.36993670463562,-0.0027323876737188613,1739137724.845997,66.36993670463562,112.77801515810295,1739137724.8460004,66.36993670463562,-8.457968561759749,1739137724.8460019,66.36993670463562,0.065,1739137724.846004,66.36993670463562,3.1323235642484337,1739137724.8460054,66.36993670463562,-0.18784080077202234,1739137724.8460069,66.36993670463562,-0.05402603827257983,1739137724.846008,66.36993670463562,2.3190425616746078,1739137724.8460095,66.36993670463562,0.0,1739137724.846011,66.36993670463562,-0.017613625578639436,1739137724.8460126,66.36993670463562,3.15803179766737,1739137724.8460143,66.36993670463562,2.336656187253247 +1739137724.866772,66.38993668556213,-1.4077434906030688,1739137724.866778,66.38993668556213,-0.00688404610433313,1739137724.8667831,66.38993668556213,112.77801515810295,1739137724.8667874,66.38993668556213,-8.4523444228548,1739137724.866789,66.38993668556213,0.065,1739137724.8667922,66.38993668556213,3.1313888745550393,1739137724.8667946,66.38993668556213,-0.18323890166819487,1739137724.8667967,66.38993668556213,-0.05670210292440455,1739137724.8667986,66.38993668556213,2.3233152929583087,1739137724.8668013,66.38993668556213,0.0,1739137724.8668034,66.38993668556213,-0.005877590313279422,1739137724.8668056,66.38993668556213,3.157401707676176,1739137724.8668082,66.38993668556213,2.3347814742849335 +1739137724.8856688,66.40993666648865,-1.4077434906030688,1739137724.8856716,66.40993666648865,-0.00688404610433313,1739137724.8856745,66.40993666648865,112.77801515810295,1739137724.8856773,66.40993666648865,-8.4523444228548,1739137724.8856788,66.40993666648865,0.065,1739137724.8856807,66.40993666648865,3.1313888745550393,1739137724.8856819,66.40993666648865,-0.18323890166819487,1739137724.8856833,66.40993666648865,-0.05670210292440455,1739137724.8856845,66.40993666648865,2.3233152929583087,1739137724.8856862,66.40993666648865,0.0,1739137724.8856876,66.40993666648865,-0.011466181326624802,1739137724.885689,66.40993666648865,3.157401707676176,1739137724.8856905,66.40993666648865,2.3347814742849335 +1739137724.9055212,66.42993664741516,-1.4077434906030688,1739137724.905524,66.42993664741516,-0.00688404610433313,1739137724.9055269,66.42993664741516,112.77801515810295,1739137724.9055293,66.42993664741516,-8.4523444228548,1739137724.9055307,66.42993664741516,0.065,1739137724.9055324,66.42993664741516,3.1313888745550393,1739137724.9055338,66.42993664741516,-0.18323890166819487,1739137724.905535,66.42993664741516,-0.05670210292440455,1739137724.9055362,66.42993664741516,2.3233152929583087,1739137724.9055378,66.42993664741516,0.0,1739137724.905539,66.42993664741516,-0.011466181326624802,1739137724.9055407,66.42993664741516,3.157401707676176,1739137724.905542,66.42993664741516,2.3347814742849335 +1739137724.9263866,66.44993662834167,-1.4077434906030688,1739137724.9263895,66.44993662834167,-0.00688404610433313,1739137724.9263928,66.44993662834167,112.77801515810295,1739137724.926396,66.44993662834167,-8.4523444228548,1739137724.926397,66.44993662834167,0.065,1739137724.926399,66.44993662834167,3.1313888745550393,1739137724.9264004,66.44993662834167,-0.18323890166819487,1739137724.926402,66.44993662834167,-0.05670210292440455,1739137724.9264033,66.44993662834167,2.3233152929583087,1739137724.9264047,66.44993662834167,0.0,1739137724.9264061,66.44993662834167,-0.011466181326624802,1739137724.926408,66.44993662834167,3.157401707676176,1739137724.9264092,66.44993662834167,2.3347814742849335 +1739137724.9470212,66.46993660926819,-1.4077434906030688,1739137724.9470258,66.46993660926819,-0.00688404610433313,1739137724.9470305,66.46993660926819,112.77801515810295,1739137724.9470367,66.46993660926819,-8.4523444228548,1739137724.94704,66.46993660926819,0.065,1739137724.947044,66.46993660926819,3.1313888745550393,1739137724.9470475,66.46993660926819,-0.18323890166819487,1739137724.947051,66.46993660926819,-0.05670210292440455,1739137724.9470544,66.46993660926819,2.3233152929583087,1739137724.9470577,66.46993660926819,0.0,1739137724.947061,66.46993660926819,-0.011466181326624802,1739137724.9470646,66.46993660926819,3.157401707676176,1739137724.9470682,66.46993660926819,2.3347814742849335 +1739137724.9673543,66.4899365901947,-1.4077434906030688,1739137724.9673595,66.4899365901947,-0.00688404610433313,1739137724.9673648,66.4899365901947,112.77801515810295,1739137724.9673696,66.4899365901947,-8.4523444228548,1739137724.9673715,66.4899365901947,0.065,1739137724.967375,66.4899365901947,3.1313888745550393,1739137724.9673774,66.4899365901947,-0.18323890166819487,1739137724.9673803,66.4899365901947,-0.05670210292440455,1739137724.9673822,66.4899365901947,2.3233152929583087,1739137724.9673843,66.4899365901947,0.0,1739137724.9673865,66.4899365901947,-0.011466181326624802,1739137724.9673884,66.4899365901947,3.157401707676176,1739137724.9673908,66.4899365901947,2.3347814742849335 +1739137724.9877715,66.50993657112122,-1.6644908085856982,1739137724.987777,66.50993657112122,-0.010860256033169868,1739137724.9877822,66.50993657112122,112.77801515810295,1739137724.9877868,66.50993657112122,-8.449077436186322,1739137724.9877892,66.50993657112122,0.065,1739137724.9877915,66.50993657112122,3.1304118552497737,1739137724.987794,66.50993657112122,-0.1782273430059204,1739137724.9877963,66.50993657112122,-0.05945763121344092,1739137724.987798,66.50993657112122,2.327977336570759,1739137724.9878004,66.50993657112122,0.0,1739137724.987802,66.50993657112122,-0.00048691974598814424,1739137724.9878047,66.50993657112122,3.1566826826326966,1739137724.987807,66.50993657112122,2.333692478728776 +1739137725.007055,66.52993655204773,-1.6644908085856982,1739137725.0070596,66.52993655204773,-0.010860256033169868,1739137725.007064,66.52993655204773,112.77801515810295,1739137725.0070689,66.52993655204773,-8.449077436186322,1739137725.0070713,66.52993655204773,0.065,1739137725.0070744,66.52993655204773,3.1304118552497737,1739137725.0070772,66.52993655204773,-0.1782273430059204,1739137725.0070794,66.52993655204773,-0.05945763121344092,1739137725.0070817,66.52993655204773,2.327977336570759,1739137725.0070841,66.52993655204773,0.0,1739137725.0070863,66.52993655204773,-0.005715142158016828,1739137725.0070894,66.52993655204773,3.1566826826326966,1739137725.0070922,66.52993655204773,2.333692478728776 +1739137725.0314083,66.54993653297424,-1.6644908085856982,1739137725.0314171,66.54993653297424,-0.010860256033169868,1739137725.031428,66.54993653297424,112.77801515810295,1739137725.031439,66.54993653297424,-8.449077436186322,1739137725.031444,66.54993653297424,0.065,1739137725.0314503,66.54993653297424,3.1304118552497737,1739137725.0314555,66.54993653297424,-0.1782273430059204,1739137725.03146,66.54993653297424,-0.05945763121344092,1739137725.0314648,66.54993653297424,2.327977336570759,1739137725.0314698,66.54993653297424,0.0,1739137725.031474,66.54993653297424,-0.005715142158016828,1739137725.0314796,66.54993653297424,3.1566826826326966,1739137725.031484,66.54993653297424,2.333692478728776 +1739137725.0565717,66.56993651390076,-1.6644908085856982,1739137725.056579,66.56993651390076,-0.010860256033169868,1739137725.0565882,66.56993651390076,112.77801515810295,1739137725.0565991,66.56993651390076,-8.449077436186322,1739137725.056605,66.56993651390076,0.065,1739137725.056613,66.56993651390076,3.1304118552497737,1739137725.0566194,66.56993651390076,-0.1782273430059204,1739137725.056626,66.56993651390076,-0.05945763121344092,1739137725.0566328,66.56993651390076,2.327977336570759,1739137725.0566394,66.56993651390076,0.0,1739137725.056646,66.56993651390076,-0.005715142158016828,1739137725.0566535,66.56993651390076,3.1566826826326966,1739137725.0566602,66.56993651390076,2.333692478728776 +1739137725.0699718,66.58993649482727,-1.6644908085856982,1739137725.0699763,66.58993649482727,-0.010860256033169868,1739137725.069981,66.58993649482727,112.77801515810295,1739137725.0699859,66.58993649482727,-8.449077436186322,1739137725.0699878,66.58993649482727,0.065,1739137725.0699906,66.58993649482727,3.1304118552497737,1739137725.069996,66.58993649482727,-0.1782273430059204,1739137725.070003,66.58993649482727,-0.05945763121344092,1739137725.0700126,66.58993649482727,2.327977336570759,1739137725.070017,66.58993649482727,0.0,1739137725.0700207,66.58993649482727,-0.005715142158016828,1739137725.0700245,66.58993649482727,3.1566826826326966,1739137725.07003,66.58993649482727,2.333692478728776 +1739137725.0885124,66.60993647575378,-1.9211312847483626,1739137725.0885167,66.60993647575378,-0.014640014375059351,1739137725.0885212,66.60993647575378,112.77801515810295,1739137725.0885248,66.60993647575378,-8.447020519696146,1739137725.0885262,66.60993647575378,0.065,1739137725.0885282,66.60993647575378,3.129389556317427,1739137725.0885298,66.60993647575378,-0.17263705662071607,1739137725.0885313,66.60993647575378,-0.06224705895966842,1739137725.0885324,66.60993647575378,2.333188785101063,1739137725.088534,66.60993647575378,0.0,1739137725.088536,66.60993647575378,0.005542938824414066,1739137725.0885377,66.60993647575378,3.1558448536956307,1739137725.0885391,66.60993647575378,2.3330068398987143 +1739137725.108248,66.6299364566803,-1.9211312847483626,1739137725.1082509,66.6299364566803,-0.014640014375059351,1739137725.1082542,66.6299364566803,112.77801515810295,1739137725.108257,66.6299364566803,-8.447020519696146,1739137725.1082585,66.6299364566803,0.065,1739137725.1082606,66.6299364566803,3.129389556317427,1739137725.1082618,66.6299364566803,-0.17263705662071607,1739137725.1082633,66.6299364566803,-0.06224705895966842,1739137725.1082644,66.6299364566803,2.333188785101063,1739137725.1082659,66.6299364566803,0.0,1739137725.1082673,66.6299364566803,0.00018194520234882106,1739137725.108269,66.6299364566803,3.1558448536956307,1739137725.1082704,66.6299364566803,2.3330068398987143 +1739137725.1283069,66.64993643760681,-1.9211312847483626,1739137725.1283119,66.64993643760681,-0.014640014375059351,1739137725.1283162,66.64993643760681,112.77801515810295,1739137725.1283195,66.64993643760681,-8.447020519696146,1739137725.128321,66.64993643760681,0.065,1739137725.128323,66.64993643760681,3.129389556317427,1739137725.1283255,66.64993643760681,-0.17263705662071607,1739137725.128327,66.64993643760681,-0.06224705895966842,1739137725.128328,66.64993643760681,2.333188785101063,1739137725.12833,66.64993643760681,0.0,1739137725.1283314,66.64993643760681,0.00018194520234882106,1739137725.1283333,66.64993643760681,3.1558448536956307,1739137725.1283357,66.64993643760681,2.3330068398987143 +1739137725.1483934,66.66993641853333,-1.9211312847483626,1739137725.148398,66.66993641853333,-0.014640014375059351,1739137725.1484015,66.66993641853333,112.77801515810295,1739137725.1484048,66.66993641853333,-8.447020519696146,1739137725.148406,66.66993641853333,0.065,1739137725.1484082,66.66993641853333,3.129389556317427,1739137725.14841,66.66993641853333,-0.17263705662071607,1739137725.1484122,66.66993641853333,-0.06224705895966842,1739137725.148415,66.66993641853333,2.333188785101063,1739137725.1484168,66.66993641853333,0.0,1739137725.1484182,66.66993641853333,0.00018194520234882106,1739137725.1484206,66.66993641853333,3.1558448536956307,1739137725.1484222,66.66993641853333,2.3330068398987143 +1739137725.1685097,66.68993639945984,-1.9211312847483626,1739137725.1685169,66.68993639945984,-0.014640014375059351,1739137725.1685214,66.68993639945984,112.77801515810295,1739137725.1685245,66.68993639945984,-8.447020519696146,1739137725.1685262,66.68993639945984,0.065,1739137725.1685288,66.68993639945984,3.129389556317427,1739137725.1685305,66.68993639945984,-0.17263705662071607,1739137725.168532,66.68993639945984,-0.06224705895966842,1739137725.1685343,66.68993639945984,2.333188785101063,1739137725.1685357,66.68993639945984,0.0,1739137725.1685376,66.68993639945984,0.00018194520234882106,1739137725.168539,66.68993639945984,3.1558448536956307,1739137725.1685407,66.68993639945984,2.3330068398987143 +1739137725.1878238,66.70993638038635,-1.9211312847483626,1739137725.1878264,66.70993638038635,-0.014640014375059351,1739137725.1878297,66.70993638038635,112.77801515810295,1739137725.1878326,66.70993638038635,-8.447020519696146,1739137725.1878338,66.70993638038635,0.065,1739137725.1878357,66.70993638038635,3.129389556317427,1739137725.187837,66.70993638038635,-0.17263705662071607,1739137725.1878383,66.70993638038635,-0.06224705895966842,1739137725.1878395,66.70993638038635,2.333188785101063,1739137725.1878407,66.70993638038635,0.0,1739137725.1878421,66.70993638038635,0.00018194520234882106,1739137725.1878436,66.70993638038635,3.1558448536956307,1739137725.1878448,66.70993638038635,2.3330068398987143 +1739137725.2075987,66.72993636131287,-2.1777486706449003,1739137725.207603,66.72993636131287,-0.01818600052395425,1739137725.2076077,66.72993636131287,112.77801515810295,1739137725.2076106,66.72993636131287,-8.447398990282927,1739137725.2076123,66.72993636131287,0.065,1739137725.2076142,66.72993636131287,3.128325387408067,1739137725.2076159,66.72993636131287,-0.16648729943228327,1739137725.2076173,66.72993636131287,-0.06503410994894988,1739137725.2076187,66.72993636131287,2.3389352678993793,1739137725.2076204,66.72993636131287,0.0,1739137725.2076228,66.72993636131287,0.01091166322569018,1739137725.2076242,66.72993636131287,3.154880650585149,1739137725.2076256,66.72993636131287,2.333132996760978 +1739137725.2280807,66.74993634223938,-2.1777486706449003,1739137725.228085,66.74993634223938,-0.01818600052395425,1739137725.228089,66.74993634223938,112.77801515810295,1739137725.2280934,66.74993634223938,-8.447398990282927,1739137725.2280953,66.74993634223938,0.065,1739137725.2280977,66.74993634223938,3.128325387408067,1739137725.2280998,66.74993634223938,-0.16648729943228327,1739137725.2281015,66.74993634223938,-0.06503410994894988,1739137725.2281032,66.74993634223938,2.3389352678993793,1739137725.2281053,66.74993634223938,0.0,1739137725.2281075,66.74993634223938,0.005802271138401149,1739137725.2281098,66.74993634223938,3.154880650585149,1739137725.2281113,66.74993634223938,2.333132996760978 +1739137725.2479095,66.7699363231659,-2.1777486706449003,1739137725.247913,66.7699363231659,-0.01818600052395425,1739137725.2479177,66.7699363231659,112.77801515810295,1739137725.2479208,66.7699363231659,-8.447398990282927,1739137725.2479224,66.7699363231659,0.065,1739137725.2479246,66.7699363231659,3.128325387408067,1739137725.2479267,66.7699363231659,-0.16648729943228327,1739137725.2479286,66.7699363231659,-0.06503410994894988,1739137725.24793,66.7699363231659,2.3389352678993793,1739137725.247932,66.7699363231659,0.0,1739137725.247935,66.7699363231659,0.005802271138401149,1739137725.2479372,66.7699363231659,3.154880650585149,1739137725.2479386,66.7699363231659,2.333132996760978 +1739137725.267986,66.78993630409241,-2.1777486706449003,1739137725.2679899,66.78993630409241,-0.01818600052395425,1739137725.2679937,66.78993630409241,112.77801515810295,1739137725.267997,66.78993630409241,-8.447398990282927,1739137725.2679985,66.78993630409241,0.065,1739137725.2680004,66.78993630409241,3.128325387408067,1739137725.2680023,66.78993630409241,-0.16648729943228327,1739137725.2680037,66.78993630409241,-0.06503410994894988,1739137725.2680051,66.78993630409241,2.3389352678993793,1739137725.2680066,66.78993630409241,0.0,1739137725.2680082,66.78993630409241,0.005802271138401149,1739137725.2680101,66.78993630409241,3.154880650585149,1739137725.2680118,66.78993630409241,2.333132996760978 +1739137725.2947428,66.80993628501892,-2.1777486706449003,1739137725.2947528,66.80993628501892,-0.01818600052395425,1739137725.294763,66.80993628501892,112.77801515810295,1739137725.2947724,66.80993628501892,-8.447398990282927,1739137725.2947774,66.80993628501892,0.065,1739137725.2947836,66.80993628501892,3.128325387408067,1739137725.2947886,66.80993628501892,-0.16648729943228327,1739137725.2947938,66.80993628501892,-0.06503410994894988,1739137725.2947984,66.80993628501892,2.3389352678993793,1739137725.294803,66.80993628501892,0.0,1739137725.294808,66.80993628501892,0.005802271138401149,1739137725.2948132,66.80993628501892,3.154880650585149,1739137725.2948182,66.80993628501892,2.333132996760978 +1739137725.3411798,66.83993625640869,-2.4344071171730297,1739137725.341189,66.83993625640869,-0.02147216643149541,1739137725.3411996,66.83993625640869,112.77801515810295,1739137725.3412094,66.83993625640869,-8.449441216342429,1739137725.341214,66.83993625640869,0.065,1739137725.34122,66.83993625640869,3.1272176378060155,1739137725.3412251,66.83993625640869,-0.15978517179072557,1739137725.34123,66.83993625640869,-0.06780906989043753,1739137725.3412347,66.83993625640869,2.345214017419415,1739137725.3412392,66.83993625640869,0.0,1739137725.3412442,66.83993625640869,0.016489381219409766,1739137725.3412495,66.83993625640869,3.1537823177200015,1739137725.3412545,66.83993625640869,2.33381373878081 +1739137725.355582,66.8599362373352,-2.4344071171730297,1739137725.3555887,66.8599362373352,-0.02147216643149541,1739137725.3555968,66.8599362373352,112.77801515810295,1739137725.355604,66.8599362373352,-8.449441216342429,1739137725.3556075,66.8599362373352,0.065,1739137725.3556116,66.8599362373352,3.1272176378060155,1739137725.3556151,66.8599362373352,-0.15978517179072557,1739137725.3556185,66.8599362373352,-0.06780906989043753,1739137725.3556218,66.8599362373352,2.345214017419415,1739137725.3556254,66.8599362373352,0.0,1739137725.3556287,66.8599362373352,0.011400278638605155,1739137725.3556323,66.8599362373352,3.1537823177200015,1739137725.355636,66.8599362373352,2.33381373878081 +1739137725.3726244,66.87993621826172,-2.4344071171730297,1739137725.372628,66.87993621826172,-0.02147216643149541,1739137725.3726323,66.87993621826172,112.77801515810295,1739137725.3726358,66.87993621826172,-8.449441216342429,1739137725.3726377,66.87993621826172,0.065,1739137725.3726406,66.87993621826172,3.1272176378060155,1739137725.3726423,66.87993621826172,-0.15978517179072557,1739137725.3726442,66.87993621826172,-0.06780906989043753,1739137725.3726459,66.87993621826172,2.345214017419415,1739137725.3726482,66.87993621826172,0.0,1739137725.37265,66.87993621826172,0.011400278638605155,1739137725.372652,66.87993621826172,3.1537823177200015,1739137725.3726537,66.87993621826172,2.33381373878081 +1739137725.3927534,66.90993618965149,-2.4344071171730297,1739137725.392759,66.90993618965149,-0.02147216643149541,1739137725.3927643,66.90993618965149,112.77801515810295,1739137725.392769,66.90993618965149,-8.449441216342429,1739137725.3927715,66.90993618965149,0.065,1739137725.3927746,66.90993618965149,3.1272176378060155,1739137725.392777,66.90993618965149,-0.15978517179072557,1739137725.3927796,66.90993618965149,-0.06780906989043753,1739137725.392782,66.90993618965149,2.345214017419415,1739137725.3927844,66.90993618965149,0.0,1739137725.3927877,66.90993618965149,0.011400278638605155,1739137725.3927908,66.90993618965149,3.1537823177200015,1739137725.3927934,66.90993618965149,2.33381373878081 +1739137725.4132442,66.929936170578,-2.4344071171730297,1739137725.413248,66.929936170578,-0.02147216643149541,1739137725.4132526,66.929936170578,112.77801515810295,1739137725.4132578,66.929936170578,-8.449441216342429,1739137725.4132605,66.929936170578,0.065,1739137725.413264,66.929936170578,3.1272176378060155,1739137725.4132671,66.929936170578,-0.15978517179072557,1739137725.4132705,66.929936170578,-0.06780906989043753,1739137725.4132736,66.929936170578,2.345214017419415,1739137725.413277,66.929936170578,0.0,1739137725.413296,66.929936170578,0.011400278638605155,1739137725.4132998,66.929936170578,3.1537823177200015,1739137725.413303,66.929936170578,2.33381373878081 +1739137725.4334493,66.94993615150452,-2.6911685874256452,1739137725.4334528,66.94993615150452,-0.0244647093310979,1739137725.4334576,66.94993615150452,112.77801515810295,1739137725.4334629,66.94993615150452,-8.453151592783392,1739137725.4334655,66.94993615150452,0.065,1739137725.4334693,66.94993615150452,3.126067178951911,1739137725.4334724,66.94993615150452,-0.15280724201844761,1739137725.4334757,66.94993615150452,-0.07066529692885087,1739137725.433479,66.94993615150452,2.3517690567704075,1739137725.4334824,66.94993615150452,0.0,1739137725.4334857,66.94993615150452,0.021553300638873566,1739137725.4334893,66.94993615150452,3.152586996308958,1739137725.433493,66.94993615150452,2.3350505309277954 +1739137725.4537928,66.96993613243103,-2.6911685874256452,1739137725.4537966,66.96993613243103,-0.0244647093310979,1739137725.4538012,66.96993613243103,112.77801515810295,1739137725.4538066,66.96993613243103,-8.453151592783392,1739137725.4538093,66.96993613243103,0.065,1739137725.453813,66.96993613243103,3.126067178951911,1739137725.4538164,66.96993613243103,-0.15280724201844761,1739137725.4538193,66.96993613243103,-0.07066529692885087,1739137725.4538226,66.96993613243103,2.3517690567704075,1739137725.4538257,66.96993613243103,0.0,1739137725.453829,66.96993613243103,0.01671852584261213,1739137725.4538326,66.96993613243103,3.152586996308958,1739137725.4538357,66.96993613243103,2.3350505309277954 +1739137725.473563,66.98993611335754,-2.6911685874256452,1739137725.4735675,66.98993611335754,-0.0244647093310979,1739137725.4735723,66.98993611335754,112.77801515810295,1739137725.4735775,66.98993611335754,-8.453151592783392,1739137725.4735806,66.98993611335754,0.065,1739137725.4735844,66.98993611335754,3.126067178951911,1739137725.4736037,66.98993611335754,-0.15280724201844761,1739137725.473644,66.98993611335754,-0.07066529692885087,1739137725.4736474,66.98993611335754,2.3517690567704075,1739137725.4736507,66.98993611335754,0.0,1739137725.4736538,66.98993611335754,0.01671852584261213,1739137725.4736571,66.98993611335754,3.152586996308958,1739137725.4736605,66.98993611335754,2.3350505309277954 +1739137725.4924042,67.00993609428406,-2.6911685874256452,1739137725.4924107,67.00993609428406,-0.0244647093310979,1739137725.4924185,67.00993609428406,112.77801515810295,1739137725.4924245,67.00993609428406,-8.453151592783392,1739137725.4924273,67.00993609428406,0.065,1739137725.4924316,67.00993609428406,3.126067178951911,1739137725.4924362,67.00993609428406,-0.15280724201844761,1739137725.49244,67.00993609428406,-0.07066529692885087,1739137725.4924433,67.00993609428406,2.3517690567704075,1739137725.4924467,67.00993609428406,0.0,1739137725.49245,67.00993609428406,0.01671852584261213,1739137725.4924536,67.00993609428406,3.152586996308958,1739137725.4924564,67.00993609428406,2.3350505309277954 +1739137725.5139017,67.02993607521057,-2.6911685874256452,1739137725.5139058,67.02993607521057,-0.0244647093310979,1739137725.51391,67.02993607521057,112.77801515810295,1739137725.5139148,67.02993607521057,-8.453151592783392,1739137725.5139177,67.02993607521057,0.065,1739137725.5139215,67.02993607521057,3.126067178951911,1739137725.5139248,67.02993607521057,-0.15280724201844761,1739137725.513928,67.02993607521057,-0.07066529692885087,1739137725.5139313,67.02993607521057,2.3517690567704075,1739137725.5139344,67.02993607521057,0.0,1739137725.5139377,67.02993607521057,0.01671852584261213,1739137725.513941,67.02993607521057,3.152586996308958,1739137725.5139444,67.02993607521057,2.3350505309277954 +1739137725.533206,67.04993605613708,-2.948104698740641,1739137725.5332096,67.04993605613708,-0.027136228238327398,1739137725.5332139,67.04993605613708,112.77801515810295,1739137725.5332189,67.04993605613708,-8.458768251122514,1739137725.5332217,67.04993605613708,0.065,1739137725.5332253,67.04993605613708,3.1248745862702085,1739137725.5332284,67.04993605613708,-0.14530609613269543,1739137725.5332315,67.04993605613708,-0.07346137510802461,1739137725.5332346,67.04993605613708,2.3588360386747724,1739137725.533238,67.04993605613708,0.0,1739137725.533241,67.04993605613708,0.026635804129791333,1739137725.5332444,67.04993605613708,3.151242123579341,1739137725.5332477,67.04993605613708,2.3369227503741694 +1739137725.5537446,67.0699360370636,-2.948104698740641,1739137725.5537477,67.0699360370636,-0.027136228238327398,1739137725.5537524,67.0699360370636,112.77801515810295,1739137725.5537574,67.0699360370636,-8.458768251122514,1739137725.55376,67.0699360370636,0.065,1739137725.5537636,67.0699360370636,3.1248745862702085,1739137725.5537672,67.0699360370636,-0.14530609613269543,1739137725.5537705,67.0699360370636,-0.07346137510802461,1739137725.5537739,67.0699360370636,2.3588360386747724,1739137725.553777,67.0699360370636,0.0,1739137725.5537803,67.0699360370636,0.021913288300603018,1739137725.5537837,67.0699360370636,3.151242123579341,1739137725.553787,67.0699360370636,2.3369227503741694 +1739137725.5726967,67.08993601799011,-2.948104698740641,1739137725.5727003,67.08993601799011,-0.027136228238327398,1739137725.5727046,67.08993601799011,112.77801515810295,1739137725.5727096,67.08993601799011,-8.458768251122514,1739137725.5727124,67.08993601799011,0.065,1739137725.572716,67.08993601799011,3.1248745862702085,1739137725.5727193,67.08993601799011,-0.14530609613269543,1739137725.5727224,67.08993601799011,-0.07346137510802461,1739137725.5727258,67.08993601799011,2.3588360386747724,1739137725.5727289,67.08993601799011,0.0,1739137725.572732,67.08993601799011,0.021913288300603018,1739137725.5727355,67.08993601799011,3.151242123579341,1739137725.572739,67.08993601799011,2.3369227503741694 +1739137725.592803,67.10993599891663,-2.948104698740641,1739137725.5928063,67.10993599891663,-0.027136228238327398,1739137725.592811,67.10993599891663,112.77801515810295,1739137725.5928159,67.10993599891663,-8.458768251122514,1739137725.5928185,67.10993599891663,0.065,1739137725.592822,67.10993599891663,3.1248745862702085,1739137725.5928254,67.10993599891663,-0.14530609613269543,1739137725.5928288,67.10993599891663,-0.07346137510802461,1739137725.5928319,67.10993599891663,2.3588360386747724,1739137725.5928352,67.10993599891663,0.0,1739137725.592838,67.10993599891663,0.021913288300603018,1739137725.5928414,67.10993599891663,3.151242123579341,1739137725.5928447,67.10993599891663,2.3369227503741694 +1739137725.6139784,67.12993597984314,-2.948104698740641,1739137725.613982,67.12993597984314,-0.027136228238327398,1739137725.6139863,67.12993597984314,112.77801515810295,1739137725.6139913,67.12993597984314,-8.458768251122514,1739137725.613994,67.12993597984314,0.065,1739137725.6139975,67.12993597984314,3.1248745862702085,1739137725.6140006,67.12993597984314,-0.14530609613269543,1739137725.614004,67.12993597984314,-0.07346137510802461,1739137725.614007,67.12993597984314,2.3588360386747724,1739137725.61401,67.12993597984314,0.0,1739137725.6140134,67.12993597984314,0.021913288300603018,1739137725.6140168,67.12993597984314,3.151242123579341,1739137725.6140199,67.12993597984314,2.3369227503741694 +1739137725.6324682,67.14993596076965,-2.948104698740641,1739137725.6324713,67.14993596076965,-0.027136228238327398,1739137725.6324747,67.14993596076965,112.77801515810295,1739137725.6324773,67.14993596076965,-8.458768251122514,1739137725.6324785,67.14993596076965,0.065,1739137725.63248,67.14993596076965,3.1248745862702085,1739137725.6324813,67.14993596076965,-0.14530609613269543,1739137725.6324825,67.14993596076965,-0.07346137510802461,1739137725.632484,67.14993596076965,2.3588360386747724,1739137725.632485,67.14993596076965,0.0,1739137725.632486,67.14993596076965,0.021913288300603018,1739137725.6324878,67.14993596076965,3.151242123579341,1739137725.632489,67.14993596076965,2.3369227503741694 +1739137725.6517246,67.16993594169617,-3.2052848945031744,1739137725.651727,67.16993594169617,-0.02944843883175885,1739137725.6517298,67.16993594169617,112.77801515810295,1739137725.6517324,67.16993594169617,-8.46624551135725,1739137725.6517339,67.16993594169617,0.065,1739137725.6517355,67.16993594169617,3.123641883610644,1739137725.651737,67.16993594169617,-0.13754396451341716,1739137725.6517384,67.16993594169617,-0.07629025563029157,1739137725.6517396,67.16993594169617,2.3661712584906094,1739137725.6517415,67.16993594169617,0.0,1739137725.6517427,67.16993594169617,0.031158637452780424,1739137725.6517444,67.16993594169617,3.149784917371285,1739137725.6517456,67.16993594169617,2.3394151704524173 +1739137725.6720312,67.18993592262268,-3.2052848945031744,1739137725.6720335,67.18993592262268,-0.02944843883175885,1739137725.672037,67.18993592262268,112.77801515810295,1739137725.6720395,67.18993592262268,-8.46624551135725,1739137725.6720407,67.18993592262268,0.065,1739137725.6720426,67.18993592262268,3.123641883610644,1739137725.672044,67.18993592262268,-0.13754396451341716,1739137725.6720452,67.18993592262268,-0.07629025563029157,1739137725.6720467,67.18993592262268,2.3661712584906094,1739137725.672048,67.18993592262268,0.0,1739137725.6720495,67.18993592262268,0.026756088038192072,1739137725.6720512,67.18993592262268,3.149784917371285,1739137725.6720524,67.18993592262268,2.3394151704524173 +1739137725.6912794,67.2099359035492,-3.2052848945031744,1739137725.6912816,67.2099359035492,-0.02944843883175885,1739137725.6912847,67.2099359035492,112.77801515810295,1739137725.6912875,67.2099359035492,-8.46624551135725,1739137725.6912892,67.2099359035492,0.065,1739137725.6912906,67.2099359035492,3.123641883610644,1739137725.6912925,67.2099359035492,-0.13754396451341716,1739137725.6912937,67.2099359035492,-0.07629025563029157,1739137725.6912947,67.2099359035492,2.3661712584906094,1739137725.6912963,67.2099359035492,0.0,1739137725.6912975,67.2099359035492,0.026756088038192072,1739137725.691299,67.2099359035492,3.149784917371285,1739137725.6913004,67.2099359035492,2.3394151704524173 +1739137725.711087,67.22993588447571,-3.2052848945031744,1739137725.7110896,67.22993588447571,-0.02944843883175885,1739137725.7110927,67.22993588447571,112.77801515810295,1739137725.7110958,67.22993588447571,-8.46624551135725,1739137725.7110972,67.22993588447571,0.065,1739137725.7110994,67.22993588447571,3.123641883610644,1739137725.7111008,67.22993588447571,-0.13754396451341716,1739137725.711102,67.22993588447571,-0.07629025563029157,1739137725.7111032,67.22993588447571,2.3661712584906094,1739137725.7111049,67.22993588447571,0.0,1739137725.711106,67.22993588447571,0.026756088038192072,1739137725.7111077,67.22993588447571,3.149784917371285,1739137725.7111092,67.22993588447571,2.3394151704524173 +1739137725.7319865,67.24993586540222,-3.2052848945031744,1739137725.7319891,67.24993586540222,-0.02944843883175885,1739137725.7319927,67.24993586540222,112.77801515810295,1739137725.7319953,67.24993586540222,-8.46624551135725,1739137725.731997,67.24993586540222,0.065,1739137725.7319987,67.24993586540222,3.123641883610644,1739137725.7320004,67.24993586540222,-0.13754396451341716,1739137725.7320015,67.24993586540222,-0.07629025563029157,1739137725.7320027,67.24993586540222,2.3661712584906094,1739137725.7320046,67.24993586540222,0.0,1739137725.7320058,67.24993586540222,0.026756088038192072,1739137725.7320077,67.24993586540222,3.149784917371285,1739137725.732009,67.24993586540222,2.3394151704524173 +1739137725.7512016,67.26993584632874,-3.4627624549525655,1739137725.751204,67.26993584632874,-0.03137508713526671,1739137725.751207,67.26993584632874,112.77801515810295,1739137725.75121,67.26993584632874,-8.47514334431505,1739137725.7512112,67.26993584632874,0.065,1739137725.7512133,67.26993584632874,3.1223676155306594,1739137725.7512145,67.26993584632874,-0.129454138434132,1739137725.751216,67.26993584632874,-0.07909660608711558,1739137725.7512171,67.26993584632874,2.3738404258264465,1739137725.7512183,67.26993584632874,0.0,1739137725.7512197,67.26993584632874,0.03573497242014099,1739137725.7512214,67.26993584632874,3.148192589068657,1739137725.7512228,67.26993584632874,2.3423811147716846 +1739137725.7812228,67.28993582725525,-3.4627624549525655,1739137725.78123,67.28993582725525,-0.03137508713526671,1739137725.7812383,67.28993582725525,112.77801515810295,1739137725.7812455,67.28993582725525,-8.47514334431505,1739137725.781249,67.28993582725525,0.065,1739137725.7812533,67.28993582725525,3.1223676155306594,1739137725.781257,67.28993582725525,-0.129454138434132,1739137725.7812603,67.28993582725525,-0.07909660608711558,1739137725.7812634,67.28993582725525,2.3738404258264465,1739137725.7812703,67.28993582725525,0.0,1739137725.7812815,67.28993582725525,0.03145931105476185,1739137725.7812874,67.28993582725525,3.148192589068657,1739137725.7812943,67.28993582725525,2.3423811147716846 +1739137725.7932703,67.30993580818176,-3.4627624549525655,1739137725.7932746,67.30993580818176,-0.03137508713526671,1739137725.7932796,67.30993580818176,112.77801515810295,1739137725.7932842,67.30993580818176,-8.47514334431505,1739137725.7932863,67.30993580818176,0.065,1739137725.7932892,67.30993580818176,3.1223676155306594,1739137725.793292,67.30993580818176,-0.129454138434132,1739137725.7932944,67.30993580818176,-0.07909660608711558,1739137725.7932963,67.30993580818176,2.3738404258264465,1739137725.7932985,67.30993580818176,0.0,1739137725.7933004,67.30993580818176,0.03145931105476185,1739137725.7933028,67.30993580818176,3.148192589068657,1739137725.793305,67.30993580818176,2.3423811147716846 +1739137725.8120658,67.32993578910828,-3.4627624549525655,1739137725.812069,67.32993578910828,-0.03137508713526671,1739137725.8120723,67.32993578910828,112.77801515810295,1739137725.8120754,67.32993578910828,-8.47514334431505,1739137725.8120766,67.32993578910828,0.065,1739137725.8120785,67.32993578910828,3.1223676155306594,1739137725.81208,67.32993578910828,-0.129454138434132,1739137725.8120813,67.32993578910828,-0.07909660608711558,1739137725.8120828,67.32993578910828,2.3738404258264465,1739137725.812084,67.32993578910828,0.0,1739137725.8120854,67.32993578910828,0.03145931105476185,1739137725.8120868,67.32993578910828,3.148192589068657,1739137725.8120885,67.32993578910828,2.3423811147716846 +1739137725.8333972,67.34993577003479,-3.4627624549525655,1739137725.8334007,67.34993577003479,-0.03137508713526671,1739137725.8334057,67.34993577003479,112.77801515810295,1739137725.833411,67.34993577003479,-8.47514334431505,1739137725.833414,67.34993577003479,0.065,1739137725.833418,67.34993577003479,3.1223676155306594,1739137725.8334212,67.34993577003479,-0.129454138434132,1739137725.8334248,67.34993577003479,-0.07909660608711558,1739137725.8334281,67.34993577003479,2.3738404258264465,1739137725.8334317,67.34993577003479,0.0,1739137725.833435,67.34993577003479,0.03145931105476185,1739137725.8334389,67.34993577003479,3.148192589068657,1739137725.8334422,67.34993577003479,2.3423811147716846 +1739137725.8532922,67.3699357509613,-3.4627624549525655,1739137725.8532953,67.3699357509613,-0.03137508713526671,1739137725.8532996,67.3699357509613,112.77801515810295,1739137725.8533046,67.3699357509613,-8.47514334431505,1739137725.8533072,67.3699357509613,0.065,1739137725.8533108,67.3699357509613,3.1223676155306594,1739137725.8533137,67.3699357509613,-0.129454138434132,1739137725.8533168,67.3699357509613,-0.07909660608711558,1739137725.85332,67.3699357509613,2.3738404258264465,1739137725.8533232,67.3699357509613,0.0,1739137725.8533263,67.3699357509613,0.03145931105476185,1739137725.8533294,67.3699357509613,3.148192589068657,1739137725.8533328,67.3699357509613,2.3423811147716846 +1739137725.8748221,67.38993573188782,-3.7206005821082004,1739137725.874827,67.38993573188782,-0.03287781179158067,1739137725.874833,67.38993573188782,112.77801515810295,1739137725.8748405,67.38993573188782,-8.485728968091742,1739137725.8748448,67.38993573188782,0.065,1739137725.87485,67.38993573188782,3.121055106192213,1739137725.8748546,67.38993573188782,-0.12120113869220396,1739137725.8748593,67.38993573188782,-0.08193274627781887,1739137725.8748639,67.38993573188782,2.3816898968029503,1739137725.8748684,67.38993573188782,0.0,1739137725.8748734,67.38993573188782,0.03970836244361361,1739137725.8748784,67.38993573188782,3.1464875044111973,1739137725.8748832,67.38993573188782,2.345909656030582 +1739137725.8928785,67.40993571281433,-3.7206005821082004,1739137725.892882,67.40993571281433,-0.03287781179158067,1739137725.8928866,67.40993571281433,112.77801515810295,1739137725.8928912,67.40993571281433,-8.485728968091742,1739137725.892894,67.40993571281433,0.065,1739137725.8928974,67.40993571281433,3.121055106192213,1739137725.8929007,67.40993571281433,-0.12120113869220396,1739137725.8929036,67.40993571281433,-0.08193274627781887,1739137725.8929064,67.40993571281433,2.3816898968029503,1739137725.8929095,67.40993571281433,0.0,1739137725.8929126,67.40993571281433,0.03578024077236819,1739137725.892916,67.40993571281433,3.1464875044111973,1739137725.8929188,67.40993571281433,2.345909656030582 +1739137725.9132905,67.42993569374084,-3.7206005821082004,1739137725.9132936,67.42993569374084,-0.03287781179158067,1739137725.9132977,67.42993569374084,112.77801515810295,1739137725.9133024,67.42993569374084,-8.485728968091742,1739137725.913305,67.42993569374084,0.065,1739137725.9133086,67.42993569374084,3.121055106192213,1739137725.9133117,67.42993569374084,-0.12120113869220396,1739137725.9133148,67.42993569374084,-0.08193274627781887,1739137725.913318,67.42993569374084,2.3816898968029503,1739137725.913321,67.42993569374084,0.0,1739137725.9133239,67.42993569374084,0.03578024077236819,1739137725.9133272,67.42993569374084,3.1464875044111973,1739137725.9133303,67.42993569374084,2.345909656030582 +1739137725.9328318,67.44993567466736,-3.7206005821082004,1739137725.932835,67.44993567466736,-0.03287781179158067,1739137725.9328394,67.44993567466736,112.77801515810295,1739137725.9328446,67.44993567466736,-8.485728968091742,1739137725.9328475,67.44993567466736,0.065,1739137725.9328508,67.44993567466736,3.121055106192213,1739137725.9328542,67.44993567466736,-0.12120113869220396,1739137725.9328575,67.44993567466736,-0.08193274627781887,1739137725.9328606,67.44993567466736,2.3816898968029503,1739137725.932864,67.44993567466736,0.0,1739137725.932867,67.44993567466736,0.03578024077236819,1739137725.9328706,67.44993567466736,3.1464875044111973,1739137725.9328737,67.44993567466736,2.345909656030582 +1739137725.9516964,67.46993565559387,-3.7206005821082004,1739137725.9516988,67.46993565559387,-0.03287781179158067,1739137725.9517014,67.46993565559387,112.77801515810295,1739137725.9517043,67.46993565559387,-8.485728968091742,1739137725.9517057,67.46993565559387,0.065,1739137725.9517074,67.46993565559387,3.121055106192213,1739137725.9517086,67.46993565559387,-0.12120113869220396,1739137725.95171,67.46993565559387,-0.08193274627781887,1739137725.9517117,67.46993565559387,2.3816898968029503,1739137725.951713,67.46993565559387,0.0,1739137725.9517143,67.46993565559387,0.03578024077236819,1739137725.951716,67.46993565559387,3.1464875044111973,1739137725.9517171,67.46993565559387,2.345909656030582 diff --git a/tuning logs/2025-02-09_15-47-37 (before tuning)/behavior.json b/tuning logs/2025-02-09_15-47-37 (before tuning)/behavior.json new file mode 100644 index 000000000..f59c84c89 --- /dev/null +++ b/tuning logs/2025-02-09_15-47-37 (before tuning)/behavior.json @@ -0,0 +1,6790 @@ +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137657.2075586, "x": 4.0, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.0, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": 0.0, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": -1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137657.2575586} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": -2, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 0, "brake_pedal_position": 0, "brake_pedal_speed": 0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": -1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137657.2575586} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.0, "x": 0.0, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.0, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": 0.0, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": -1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137657.2775586} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.36000000000000004, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.155615808686748, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": -1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137657.2775586} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.0, "x": 0.0, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.0, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": 0.0, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": -1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137657.2975585} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.36000000000000004, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.155615808686748, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.015995993600000008, "gear": 1, "accelerator_pedal_position": 0.36000000000000004, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.0934595651055797, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137657.2975585} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137657.3175585, "x": 4.000479839636078, "y": 4.999999992617307, "z": null, "yaw": -5.035974732880535e-05, "pitch": null, "roll": null}, "v": 0.03197591848874033, "accelerator_pedal_position": 0.36000000000000004, "brake_pedal_position": 0.0, "acceleration": 0.7983909794819313, "steering_wheel_angle": -0.18668973814341416, "front_wheel_angle": -0.00859465085092568, "heading_rate": -0.00010735493050679263, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137657.3175585} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392257443282891, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.8001890528904205, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.03197591848874033, "gear": 1, "accelerator_pedal_position": 0.36000000000000004, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.18668973814341416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137657.3175585} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.1099998950958252, "x": 0.00047983963607833857, "y": -7.382692679414049e-09, "z": null, "yaw": 6.2831349474322575, "pitch": null, "roll": null}, "v": 0.03197591848874033, "accelerator_pedal_position": 0.36000000000000004, "brake_pedal_position": 0.0, "acceleration": 0.7983909794819313, "steering_wheel_angle": -0.18668973814341416, "front_wheel_angle": -0.00859465085092568, "heading_rate": -0.00010735493050679263, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137657.3375585} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392257443282891, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.8001890528904205, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.05197084453690334, "gear": 1, "accelerator_pedal_position": 0.392257443282891, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2785293311711188, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137657.3375585} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.1099998950958252, "x": 0.00047983963607833857, "y": -7.382692679414049e-09, "z": null, "yaw": 6.2831349474322575, "pitch": null, "roll": null}, "v": 0.03197591848874033, "accelerator_pedal_position": 0.36000000000000004, "brake_pedal_position": 0.0, "acceleration": 0.7983909794819313, "steering_wheel_angle": -0.18668973814341416, "front_wheel_angle": -0.00859465085092568, "heading_rate": -0.00010735493050679263, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137657.3575585} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392257443282891, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.8001890528904205, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.1217917987298889, "gear": 1, "accelerator_pedal_position": 0.392257443282891, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5982063271470346, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137657.3575585} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.1099998950958252, "x": 0.00047983963607833857, "y": -7.382692679414049e-09, "z": null, "yaw": 6.2831349474322575, "pitch": null, "roll": null}, "v": 0.03197591848874033, "accelerator_pedal_position": 0.36000000000000004, "brake_pedal_position": 0.0, "acceleration": 0.7983909794819313, "steering_wheel_angle": -0.18668973814341416, "front_wheel_angle": -0.00859465085092568, "heading_rate": -0.00010735493050679263, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137657.4075584} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392257443282891, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.8001890528904205, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.13174550971148086, "gear": 1, "accelerator_pedal_position": 0.392257443282891, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6436507767790162, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137657.4075584} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137657.4275584, "x": 4.00948876032511, "y": 4.999996128562262, "z": null, "yaw": -0.0008756557225847718, "pitch": null, "roll": null}, "v": 0.1416939914738729, "accelerator_pedal_position": 0.392257443282891, "brake_pedal_position": 0.0, "acceleration": 0.9943235490721771, "steering_wheel_angle": -0.6890393032484248, "front_wheel_angle": -0.03193447566030208, "heading_rate": -0.0017681492727022027, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137657.4275584} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3931656754313427, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.825884419085885, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.1416939914738729, "gear": 1, "accelerator_pedal_position": 0.392257443282891, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6890393032484248, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137657.4275584} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3931656754313427, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.825884419085885, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.1516939914738729, "gear": 1, "accelerator_pedal_position": 0.3931656754313427, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7329036637869958, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137657.4375584} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.2199997901916504, "x": 0.009488760325109702, "y": -3.871437738389716e-06, "z": null, "yaw": 6.282309651457002, "pitch": null, "roll": null}, "v": 0.1416939914738729, "accelerator_pedal_position": 0.392257443282891, "brake_pedal_position": 0.0, "acceleration": 0.9943235490721771, "steering_wheel_angle": -0.6890393032484248, "front_wheel_angle": -0.03193447566030208, "heading_rate": -0.0017681492727022027, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137657.4475584} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3931656754313427, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.825884419085885, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.16168869808588995, "gear": 1, "accelerator_pedal_position": 0.3931656754313427, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7767156670973981, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137657.4475584} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.2199997901916504, "x": 0.009488760325109702, "y": -3.871437738389716e-06, "z": null, "yaw": 6.282309651457002, "pitch": null, "roll": null}, "v": 0.1416939914738729, "accelerator_pedal_position": 0.392257443282891, "brake_pedal_position": 0.0, "acceleration": 0.9943235490721771, "steering_wheel_angle": -0.6890393032484248, "front_wheel_angle": -0.03193447566030208, "heading_rate": -0.0017681492727022027, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137657.4675584} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3931656754313427, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.825884419085885, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.2414537357782337, "gear": 1, "accelerator_pedal_position": 0.3931656754313427, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1253268333665574, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137657.4675584} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.2199997901916504, "x": 0.009488760325109702, "y": -3.871437738389716e-06, "z": null, "yaw": 6.282309651457002, "pitch": null, "roll": null}, "v": 0.1416939914738729, "accelerator_pedal_position": 0.392257443282891, "brake_pedal_position": 0.0, "acceleration": 0.9943235490721771, "steering_wheel_angle": -0.6890393032484248, "front_wheel_angle": -0.03193447566030208, "heading_rate": -0.0017681492727022027, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137657.5275583} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3931656754313427, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.825884419085885, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.2414537357782337, "gear": 1, "accelerator_pedal_position": 0.3931656754313427, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1253268333665574, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137657.5275583} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137657.5375583, "x": 4.030566275467517, "y": 4.999960216026343, "z": null, "yaw": -0.0026900767372767284, "pitch": null, "roll": null}, "v": 0.25140003363415137, "accelerator_pedal_position": 0.3931656754313427, "brake_pedal_position": 0.0, "acceleration": 0.9940834499950715, "steering_wheel_angle": -1.1686676216234446, "front_wheel_angle": -0.05451791343579329, "heading_rate": -0.005359140721009597, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137657.5475583} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.39411232343213126, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.906446883293525, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.26134086813410207, "gear": 1, "accelerator_pedal_position": 0.3931656754313427, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.2119560526521636, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137657.5475583} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.3299996852874756, "x": 0.030566275467516668, "y": -3.978397365678177e-05, "z": null, "yaw": 6.28049523044231, "pitch": null, "roll": null}, "v": 0.25140003363415137, "accelerator_pedal_position": 0.3931656754313427, "brake_pedal_position": 0.0, "acceleration": 0.9940834499950715, "steering_wheel_angle": -1.1686676216234446, "front_wheel_angle": -0.05451791343579329, "heading_rate": -0.005359140721009597, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137657.5675583} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.39411232343213126, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.906446883293525, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.2913078219256408, "gear": 1, "accelerator_pedal_position": 0.39411232343213126, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.3377835136459768, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137657.5675583} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.3299996852874756, "x": 0.030566275467516668, "y": -3.978397365678177e-05, "z": null, "yaw": 6.28049523044231, "pitch": null, "roll": null}, "v": 0.25140003363415137, "accelerator_pedal_position": 0.3931656754313427, "brake_pedal_position": 0.0, "acceleration": 0.9940834499950715, "steering_wheel_angle": -1.1686676216234446, "front_wheel_angle": -0.05451791343579329, "heading_rate": -0.005359140721009597, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137657.5875583} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.39411232343213126, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.906446883293525, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.3012857022044747, "gear": 1, "accelerator_pedal_position": 0.39411232343213126, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.3796272296366736, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137657.5875583} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.3299996852874756, "x": 0.030566275467516668, "y": -3.978397365678177e-05, "z": null, "yaw": 6.28049523044231, "pitch": null, "roll": null}, "v": 0.25140003363415137, "accelerator_pedal_position": 0.3931656754313427, "brake_pedal_position": 0.0, "acceleration": 0.9940834499950715, "steering_wheel_angle": -1.1686676216234446, "front_wheel_angle": -0.05451791343579329, "heading_rate": -0.005359140721009597, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137657.6075583} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.39411232343213126, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.906446883293525, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.3212247053194262, "gear": 1, "accelerator_pedal_position": 0.39411232343213126, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.4631665051072054, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137657.6075583} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.3299996852874756, "x": 0.030566275467516668, "y": -3.978397365678177e-05, "z": null, "yaw": 6.28049523044231, "pitch": null, "roll": null}, "v": 0.25140003363415137, "accelerator_pedal_position": 0.3931656754313427, "brake_pedal_position": 0.0, "acceleration": 0.9940834499950715, "steering_wheel_angle": -1.1686676216234446, "front_wheel_angle": -0.05451791343579329, "heading_rate": -0.005359140721009597, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137657.6275582} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.39411232343213126, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.906446883293525, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.3411412535642692, "gear": 1, "accelerator_pedal_position": 0.39411232343213126, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.5465082385632551, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137657.6275582} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137657.6475582, "x": 4.06370495600806, "y": 4.999829105075102, "z": null, "yaw": -0.005467303131319996, "pitch": null, "roll": null}, "v": 0.3610352136046854, "accelerator_pedal_position": 0.39411232343213126, "brake_pedal_position": 0.0, "acceleration": 0.9938467965159603, "steering_wheel_angle": -1.6296524300048227, "front_wheel_angle": -0.07651020184320678, "heading_rate": -0.010811290341023834, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137657.6475582} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3950968359895776, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.1776877999406925, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.3610352136046854, "gear": 1, "accelerator_pedal_position": 0.39411232343213126, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.6296524300048227, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137657.6475582} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.4399995803833008, "x": 0.06370495600805981, "y": -0.00017089492489841263, "z": null, "yaw": 6.277718004048266, "pitch": null, "roll": null}, "v": 0.3610352136046854, "accelerator_pedal_position": 0.39411232343213126, "brake_pedal_position": 0.0, "acceleration": 0.9938467965159603, "steering_wheel_angle": -1.6296524300048227, "front_wheel_angle": -0.07651020184320678, "heading_rate": -0.010811290341023834, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137657.6675582} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3950968359895776, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.1776877999406925, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.3810294815342582, "gear": 1, "accelerator_pedal_position": 0.3950968359895776, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.6296524300048227, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137657.6675582} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.4399995803833008, "x": 0.06370495600805981, "y": -0.00017089492489841263, "z": null, "yaw": 6.277718004048266, "pitch": null, "roll": null}, "v": 0.3610352136046854, "accelerator_pedal_position": 0.39411232343213126, "brake_pedal_position": 0.0, "acceleration": 0.9938467965159603, "steering_wheel_angle": -1.6296524300048227, "front_wheel_angle": -0.07651020184320678, "heading_rate": -0.010811290341023834, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137657.6875582} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3950968359895776, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.1776877999406925, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.4010007544375735, "gear": 1, "accelerator_pedal_position": 0.3950968359895776, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.6296524300048227, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137657.6875582} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.4399995803833008, "x": 0.06370495600805981, "y": -0.00017089492489841263, "z": null, "yaw": 6.277718004048266, "pitch": null, "roll": null}, "v": 0.3610352136046854, "accelerator_pedal_position": 0.39411232343213126, "brake_pedal_position": 0.0, "acceleration": 0.9938467965159603, "steering_wheel_angle": -1.6296524300048227, "front_wheel_angle": -0.07651020184320678, "heading_rate": -0.010811290341023834, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137657.7075582} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3950968359895776, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.1776877999406925, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.4209488992663323, "gear": 1, "accelerator_pedal_position": 0.3950968359895776, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.6296524300048227, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137657.7075582} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.4399995803833008, "x": 0.06370495600805981, "y": -0.00017089492489841263, "z": null, "yaw": 6.277718004048266, "pitch": null, "roll": null}, "v": 0.3610352136046854, "accelerator_pedal_position": 0.39411232343213126, "brake_pedal_position": 0.0, "acceleration": 0.9938467965159603, "steering_wheel_angle": -1.6296524300048227, "front_wheel_angle": -0.07651020184320678, "heading_rate": -0.010811290341023834, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137657.7275581} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3950968359895776, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.1776877999406925, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.440873783679471, "gear": 1, "accelerator_pedal_position": 0.3950968359895776, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.6296524300048227, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137657.7275581} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.4399995803833008, "x": 0.06370495600805981, "y": -0.00017089492489841263, "z": null, "yaw": 6.277718004048266, "pitch": null, "roll": null}, "v": 0.3610352136046854, "accelerator_pedal_position": 0.39411232343213126, "brake_pedal_position": 0.0, "acceleration": 0.9938467965159603, "steering_wheel_angle": -1.6296524300048227, "front_wheel_angle": -0.07651020184320678, "heading_rate": -0.010811290341023834, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137657.747558} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3950968359895776, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.1776877999406925, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.4607752760459256, "gear": 1, "accelerator_pedal_position": 0.3950968359895776, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.6296524300048227, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137657.747558} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137657.757558, "x": 4.10890817722579, "y": 4.999510993679369, "z": null, "yaw": -0.008761280817426756, "pitch": null, "roll": null}, "v": 0.4707172092717497, "accelerator_pedal_position": 0.3950968359895776, "brake_pedal_position": 0.0, "acceleration": 0.9936036175602267, "steering_wheel_angle": -1.6296524300048227, "front_wheel_angle": -0.07651020184320678, "heading_rate": -0.014095745307341728, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137657.767558} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.39612025717994137, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.639804796057543, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.49064733214413875, "gear": 1, "accelerator_pedal_position": 0.39612025717994137, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.6296524300048227, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137657.767558} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.549999475479126, "x": 0.10890817722579005, "y": -0.0004890063206310913, "z": null, "yaw": 6.274424026362159, "pitch": null, "roll": null}, "v": 0.4707172092717497, "accelerator_pedal_position": 0.3950968359895776, "brake_pedal_position": 0.0, "acceleration": 0.9936036175602267, "steering_wheel_angle": -1.6296524300048227, "front_wheel_angle": -0.07651020184320678, "heading_rate": -0.014095745307341728, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137657.787558} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.39612025717994137, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.639804796057543, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.500635451071359, "gear": 1, "accelerator_pedal_position": 0.39612025717994137, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.6296524300048227, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137657.787558} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.549999475479126, "x": 0.10890817722579005, "y": -0.0004890063206310913, "z": null, "yaw": 6.274424026362159, "pitch": null, "roll": null}, "v": 0.4707172092717497, "accelerator_pedal_position": 0.3950968359895776, "brake_pedal_position": 0.0, "acceleration": 0.9936036175602267, "steering_wheel_angle": -1.6296524300048227, "front_wheel_angle": -0.07651020184320678, "heading_rate": -0.014095745307341728, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137657.807558} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.39612025717994137, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.639804796057543, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5205937200830156, "gear": 1, "accelerator_pedal_position": 0.39612025717994137, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.6296524300048227, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137657.807558} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.549999475479126, "x": 0.10890817722579005, "y": -0.0004890063206310913, "z": null, "yaw": 6.274424026362159, "pitch": null, "roll": null}, "v": 0.4707172092717497, "accelerator_pedal_position": 0.3950968359895776, "brake_pedal_position": 0.0, "acceleration": 0.9936036175602267, "steering_wheel_angle": -1.6296524300048227, "front_wheel_angle": -0.07651020184320678, "heading_rate": -0.014095745307341728, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137657.827558} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.39612025717994137, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.639804796057543, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5405279218710027, "gear": 1, "accelerator_pedal_position": 0.39612025717994137, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.6296524300048227, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137657.827558} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.549999475479126, "x": 0.10890817722579005, "y": -0.0004890063206310913, "z": null, "yaw": 6.274424026362159, "pitch": null, "roll": null}, "v": 0.4707172092717497, "accelerator_pedal_position": 0.3950968359895776, "brake_pedal_position": 0.0, "acceleration": 0.9936036175602267, "steering_wheel_angle": -1.6296524300048227, "front_wheel_angle": -0.07651020184320678, "heading_rate": -0.014095745307341728, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137657.847558} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.39612025717994137, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.639804796057543, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5604379265567787, "gear": 1, "accelerator_pedal_position": 0.39612025717994137, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.6296524300048227, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137657.847558} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137657.867558, "x": 4.166167744808772, "y": 4.998920288989687, "z": null, "yaw": -0.012055258503533516, "pitch": null, "roll": null}, "v": 0.5803236049971447, "accelerator_pedal_position": 0.39612025717994137, "brake_pedal_position": 0.0, "acceleration": 0.9933676722596074, "steering_wheel_angle": -1.6296524300048227, "front_wheel_angle": -0.07651020184320678, "heading_rate": -0.017377936414378445, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137657.867558} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3971814296184042, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1944435460330307, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5803236049971447, "gear": 1, "accelerator_pedal_position": 0.39612025717994137, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.6296524300048227, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137657.867558} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.6599993705749512, "x": 0.16616774480877172, "y": -0.0010797110103126784, "z": null, "yaw": 6.271130048676053, "pitch": null, "roll": null}, "v": 0.5803236049971447, "accelerator_pedal_position": 0.39612025717994137, "brake_pedal_position": 0.0, "acceleration": 0.9933676722596074, "steering_wheel_angle": -1.6296524300048227, "front_wheel_angle": -0.07651020184320678, "heading_rate": -0.017377936414378445, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137657.887558} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3971814296184042, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1944435460330307, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6003174343499348, "gear": 1, "accelerator_pedal_position": 0.3971814296184042, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.6296524300048227, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137657.887558} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.6599993705749512, "x": 0.16616774480877172, "y": -0.0010797110103126784, "z": null, "yaw": 6.271130048676053, "pitch": null, "roll": null}, "v": 0.5803236049971447, "accelerator_pedal_position": 0.39612025717994137, "brake_pedal_position": 0.0, "acceleration": 0.9933676722596074, "steering_wheel_angle": -1.6296524300048227, "front_wheel_angle": -0.07651020184320678, "heading_rate": -0.017377936414378445, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137657.907558} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3971814296184042, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1944435460330307, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6202865164657343, "gear": 1, "accelerator_pedal_position": 0.3971814296184042, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.6296524300048227, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137657.907558} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.6599993705749512, "x": 0.16616774480877172, "y": -0.0010797110103126784, "z": null, "yaw": 6.271130048676053, "pitch": null, "roll": null}, "v": 0.5803236049971447, "accelerator_pedal_position": 0.39612025717994137, "brake_pedal_position": 0.0, "acceleration": 0.9933676722596074, "steering_wheel_angle": -1.6296524300048227, "front_wheel_angle": -0.07651020184320678, "heading_rate": -0.017377936414378445, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137657.927558} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3971814296184042, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1944435460330307, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6402307225193243, "gear": 1, "accelerator_pedal_position": 0.3971814296184042, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.6296524300048227, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137657.927558} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.6599993705749512, "x": 0.16616774480877172, "y": -0.0010797110103126784, "z": null, "yaw": 6.271130048676053, "pitch": null, "roll": null}, "v": 0.5803236049971447, "accelerator_pedal_position": 0.39612025717994137, "brake_pedal_position": 0.0, "acceleration": 0.9933676722596074, "steering_wheel_angle": -1.6296524300048227, "front_wheel_angle": -0.07651020184320678, "heading_rate": -0.017377936414378445, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137657.947558} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3971814296184042, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1944435460330307, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6601499244409249, "gear": 1, "accelerator_pedal_position": 0.3971814296184042, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.6296524300048227, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137657.947558} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.6599993705749512, "x": 0.16616774480877172, "y": -0.0010797110103126784, "z": null, "yaw": 6.271130048676053, "pitch": null, "roll": null}, "v": 0.5803236049971447, "accelerator_pedal_position": 0.39612025717994137, "brake_pedal_position": 0.0, "acceleration": 0.9933676722596074, "steering_wheel_angle": -1.6296524300048227, "front_wheel_angle": -0.07651020184320678, "heading_rate": -0.017377936414378445, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137657.967558} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3971814296184042, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1944435460330307, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.680043994918599, "gear": 1, "accelerator_pedal_position": 0.3971814296184042, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.6296524300048227, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137657.967558} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137657.977558, "x": 4.235486664614753, "y": 4.997977500272175, "z": null, "yaw": -0.015349236189640276, "pitch": null, "roll": null}, "v": 0.6899815662887875, "accelerator_pedal_position": 0.3971814296184042, "brake_pedal_position": 0.0, "acceleration": 0.9931241111824034, "steering_wheel_angle": -1.6296524300048227, "front_wheel_angle": -0.07651020184320678, "heading_rate": -0.02066167166527508, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137657.987558} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.39828157182921964, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.789828571653052, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6999128074006116, "gear": 1, "accelerator_pedal_position": 0.3971814296184042, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.6296524300048227, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137657.987558} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.7699992656707764, "x": 0.23548666461475332, "y": -0.002022499727824645, "z": null, "yaw": 6.267836070989946, "pitch": null, "roll": null}, "v": 0.6899815662887875, "accelerator_pedal_position": 0.3971814296184042, "brake_pedal_position": 0.0, "acceleration": 0.9931241111824034, "steering_wheel_angle": -1.6296524300048227, "front_wheel_angle": -0.07651020184320678, "heading_rate": -0.02066167166527508, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137658.0075579} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.39828157182921964, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.789828571653052, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7198937097326464, "gear": 1, "accelerator_pedal_position": 0.39828157182921964, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.6296524300048227, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137658.0075579} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.7699992656707764, "x": 0.23548666461475332, "y": -0.002022499727824645, "z": null, "yaw": 6.267836070989946, "pitch": null, "roll": null}, "v": 0.6899815662887875, "accelerator_pedal_position": 0.3971814296184042, "brake_pedal_position": 0.0, "acceleration": 0.9931241111824034, "steering_wheel_angle": -1.6296524300048227, "front_wheel_angle": -0.07651020184320678, "heading_rate": -0.02066167166527508, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137658.0275578} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.39828157182921964, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.789828571653052, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7398489257089986, "gear": 1, "accelerator_pedal_position": 0.39828157182921964, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.6296524300048227, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137658.0275578} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.7699992656707764, "x": 0.23548666461475332, "y": -0.002022499727824645, "z": null, "yaw": 6.267836070989946, "pitch": null, "roll": null}, "v": 0.6899815662887875, "accelerator_pedal_position": 0.3971814296184042, "brake_pedal_position": 0.0, "acceleration": 0.9931241111824034, "steering_wheel_angle": -1.6296524300048227, "front_wheel_angle": -0.07651020184320678, "heading_rate": -0.02066167166527508, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137658.0475578} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.39828157182921964, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.789828571653052, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.759778329117958, "gear": 1, "accelerator_pedal_position": 0.39828157182921964, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.6296524300048227, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137658.0475578} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.7699992656707764, "x": 0.23548666461475332, "y": -0.002022499727824645, "z": null, "yaw": 6.267836070989946, "pitch": null, "roll": null}, "v": 0.6899815662887875, "accelerator_pedal_position": 0.3971814296184042, "brake_pedal_position": 0.0, "acceleration": 0.9931241111824034, "steering_wheel_angle": -1.6296524300048227, "front_wheel_angle": -0.07651020184320678, "heading_rate": -0.02066167166527508, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137658.0675578} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.39828157182921964, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.789828571653052, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7796817945280288, "gear": 1, "accelerator_pedal_position": 0.39828157182921964, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.6296524300048227, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137658.0675578} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137658.0875578, "x": 4.316855545673209, "y": 4.996603305925321, "z": null, "yaw": -0.018643213875747053, "pitch": null, "roll": null}, "v": 0.7995591972901228, "accelerator_pedal_position": 0.39828157182921964, "brake_pedal_position": 0.0, "acceleration": 0.9928889149684043, "steering_wheel_angle": -1.6296524300048227, "front_wheel_angle": -0.07651020184320678, "heading_rate": -0.023943001405409982, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137658.0875578} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.39941934543427493, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.41762085702487545, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7995591972901228, "gear": 1, "accelerator_pedal_position": 0.39828157182921964, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.6296524300048227, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137658.0875578} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.8799991607666016, "x": 0.31685554567320917, "y": -0.0033966940746790186, "z": null, "yaw": 6.264542093303839, "pitch": null, "roll": null}, "v": 0.7995591972901228, "accelerator_pedal_position": 0.39828157182921964, "brake_pedal_position": 0.0, "acceleration": 0.9928889149684043, "steering_wheel_angle": -1.6296524300048227, "front_wheel_angle": -0.07651020184320678, "heading_rate": -0.023943001405409982, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137658.1075578} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.39941934543427493, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.41762085702487545, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8195525881717283, "gear": 1, "accelerator_pedal_position": 0.39941934543427493, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.5522488253828977, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137658.1075578} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.8799991607666016, "x": 0.31685554567320917, "y": -0.0033966940746790186, "z": null, "yaw": 6.264542093303839, "pitch": null, "roll": null}, "v": 0.7995591972901228, "accelerator_pedal_position": 0.39828157182921964, "brake_pedal_position": 0.0, "acceleration": 0.9928889149684043, "steering_wheel_angle": -1.6296524300048227, "front_wheel_angle": -0.07651020184320678, "heading_rate": -0.023943001405409982, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137658.1275578} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.39941934543427493, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.41762085702487545, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8395194801812504, "gear": 1, "accelerator_pedal_position": 0.39941934543427493, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.4746739870819434, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137658.1275578} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.8799991607666016, "x": 0.31685554567320917, "y": -0.0033966940746790186, "z": null, "yaw": 6.264542093303839, "pitch": null, "roll": null}, "v": 0.7995591972901228, "accelerator_pedal_position": 0.39828157182921964, "brake_pedal_position": 0.0, "acceleration": 0.9928889149684043, "steering_wheel_angle": -1.6296524300048227, "front_wheel_angle": -0.07651020184320678, "heading_rate": -0.023943001405409982, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137658.1475577} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.39941934543427493, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.41762085702487545, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8594597490223164, "gear": 1, "accelerator_pedal_position": 0.39941934543427493, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.3969279151019616, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137658.1475577} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.8799991607666016, "x": 0.31685554567320917, "y": -0.0033966940746790186, "z": null, "yaw": 6.264542093303839, "pitch": null, "roll": null}, "v": 0.7995591972901228, "accelerator_pedal_position": 0.39828157182921964, "brake_pedal_position": 0.0, "acceleration": 0.9928889149684043, "steering_wheel_angle": -1.6296524300048227, "front_wheel_angle": -0.07651020184320678, "heading_rate": -0.023943001405409982, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137658.1675577} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.39941934543427493, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.41762085702487545, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8793732712010119, "gear": 1, "accelerator_pedal_position": 0.39941934543427493, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.3190106094429506, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137658.1675577} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.8799991607666016, "x": 0.31685554567320917, "y": -0.0033966940746790186, "z": null, "yaw": 6.264542093303839, "pitch": null, "roll": null}, "v": 0.7995591972901228, "accelerator_pedal_position": 0.39828157182921964, "brake_pedal_position": 0.0, "acceleration": 0.9928889149684043, "steering_wheel_angle": -1.6296524300048227, "front_wheel_angle": -0.07651020184320678, "heading_rate": -0.023943001405409982, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137658.1875577} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.39941934543427493, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.41762085702487545, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8992599240279028, "gear": 1, "accelerator_pedal_position": 0.39941934543427493, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.2409220701049117, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137658.1875577} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137658.1975577, "x": 4.410277263566342, "y": 4.994728787221056, "z": null, "yaw": -0.021536383763132716, "pitch": null, "roll": null}, "v": 0.9091931363144348, "accelerator_pedal_position": 0.39941934543427493, "brake_pedal_position": 0.0, "acceleration": 0.9926449305572835, "steering_wheel_angle": -1.2409220701049117, "front_wheel_angle": -0.057946112790157704, "heading_rate": -0.020602833658529485, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137658.2075577} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.40059615654510955, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.12291150689167886, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9191195856200076, "gear": 1, "accelerator_pedal_position": 0.39941934543427493, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.2409220701049117, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137658.2075577} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.9899990558624268, "x": 0.41027726356634187, "y": -0.0052712127789442675, "z": null, "yaw": 6.261648923416454, "pitch": null, "roll": null}, "v": 0.9091931363144348, "accelerator_pedal_position": 0.39941934543427493, "brake_pedal_position": 0.0, "acceleration": 0.9926449305572835, "steering_wheel_angle": -1.2409220701049117, "front_wheel_angle": -0.057946112790157704, "heading_rate": -0.020602833658529485, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137658.2275577} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.40059615654510955, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.12291150689167886, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9390991858493927, "gear": 1, "accelerator_pedal_position": 0.40059615654510955, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1632728356801327, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137658.2275577} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.9899990558624268, "x": 0.41027726356634187, "y": -0.0052712127789442675, "z": null, "yaw": 6.261648923416454, "pitch": null, "roll": null}, "v": 0.9091931363144348, "accelerator_pedal_position": 0.39941934543427493, "brake_pedal_position": 0.0, "acceleration": 0.9926449305572835, "steering_wheel_angle": -1.2409220701049117, "front_wheel_angle": -0.057946112790157704, "heading_rate": -0.020602833658529485, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137658.2475576} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.40059615654510955, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.12291150689167886, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9590513507049764, "gear": 1, "accelerator_pedal_position": 0.40059615654510955, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.0854550260173375, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137658.2475576} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.9899990558624268, "x": 0.41027726356634187, "y": -0.0052712127789442675, "z": null, "yaw": 6.261648923416454, "pitch": null, "roll": null}, "v": 0.9091931363144348, "accelerator_pedal_position": 0.39941934543427493, "brake_pedal_position": 0.0, "acceleration": 0.9926449305572835, "steering_wheel_angle": -1.2409220701049117, "front_wheel_angle": -0.057946112790157704, "heading_rate": -0.020602833658529485, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137658.2675576} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.40059615654510955, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.12291150689167886, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9789759586796619, "gear": 1, "accelerator_pedal_position": 0.40059615654510955, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.0074686411165257, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137658.2675576} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.9899990558624268, "x": 0.41027726356634187, "y": -0.0052712127789442675, "z": null, "yaw": 6.261648923416454, "pitch": null, "roll": null}, "v": 0.9091931363144348, "accelerator_pedal_position": 0.39941934543427493, "brake_pedal_position": 0.0, "acceleration": 0.9926449305572835, "steering_wheel_angle": -1.2409220701049117, "front_wheel_angle": -0.057946112790157704, "heading_rate": -0.020602833658529485, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137658.2875576} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.40059615654510955, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.12291150689167886, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9988728890927698, "gear": 1, "accelerator_pedal_position": 0.40059615654510955, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.9684122329518636, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137658.2875576} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137658.3075576, "x": 4.5157428689552095, "y": 4.992343563769289, "z": null, "yaw": -0.02372600725444891, "pitch": null, "roll": null}, "v": 1.0187420220918342, "accelerator_pedal_position": 0.40059615654510955, "brake_pedal_position": 0.0, "acceleration": 0.9924105242265853, "steering_wheel_angle": -0.9684122329518636, "front_wheel_angle": -0.04505251911146372, "heading_rate": -0.017940614223441193, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137658.3075576} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4018104726688559, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0954550675785204, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0187420220918342, "gear": 1, "accelerator_pedal_position": 0.40059615654510955, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.9684122329518636, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137658.3075576} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.099998950958252, "x": 0.5157428689552095, "y": -0.0076564362307109946, "z": null, "yaw": 6.259459299925138, "pitch": null, "roll": null}, "v": 1.0187420220918342, "accelerator_pedal_position": 0.40059615654510955, "brake_pedal_position": 0.0, "acceleration": 0.9924105242265853, "steering_wheel_angle": -0.9684122329518636, "front_wheel_angle": -0.04505251911146372, "heading_rate": -0.017940614223441193, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137658.3275576} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4018104726688559, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0954550675785204, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.03873497460779, "gear": 1, "accelerator_pedal_position": 0.4018104726688559, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.8901470945711165, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137658.3275576} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.099998950958252, "x": 0.5157428689552095, "y": -0.0076564362307109946, "z": null, "yaw": 6.259459299925138, "pitch": null, "roll": null}, "v": 1.0187420220918342, "accelerator_pedal_position": 0.40059615654510955, "brake_pedal_position": 0.0, "acceleration": 0.9924105242265853, "steering_wheel_angle": -0.9684122329518636, "front_wheel_angle": -0.04505251911146372, "heading_rate": -0.017940614223441193, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137658.3475575} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4018104726688559, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0954550675785204, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0586996771918415, "gear": 1, "accelerator_pedal_position": 0.4018104726688559, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.8117132694855322, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137658.3475575} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.099998950958252, "x": 0.5157428689552095, "y": -0.0076564362307109946, "z": null, "yaw": 6.259459299925138, "pitch": null, "roll": null}, "v": 1.0187420220918342, "accelerator_pedal_position": 0.40059615654510955, "brake_pedal_position": 0.0, "acceleration": 0.9924105242265853, "steering_wheel_angle": -0.9684122329518636, "front_wheel_angle": -0.04505251911146372, "heading_rate": -0.017940614223441193, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137658.3675575} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4018104726688559, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0954550675785204, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.078636010381946, "gear": 1, "accelerator_pedal_position": 0.4018104726688559, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7331107576951109, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137658.3675575} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.099998950958252, "x": 0.5157428689552095, "y": -0.0076564362307109946, "z": null, "yaw": 6.259459299925138, "pitch": null, "roll": null}, "v": 1.0187420220918342, "accelerator_pedal_position": 0.40059615654510955, "brake_pedal_position": 0.0, "acceleration": 0.9924105242265853, "steering_wheel_angle": -0.9684122329518636, "front_wheel_angle": -0.04505251911146372, "heading_rate": -0.017940614223441193, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137658.3875575} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4018104726688559, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0954550675785204, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0985438555642764, "gear": 1, "accelerator_pedal_position": 0.4018104726688559, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7331107576951109, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137658.3875575} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.099998950958252, "x": 0.5157428689552095, "y": -0.0076564362307109946, "z": null, "yaw": 6.259459299925138, "pitch": null, "roll": null}, "v": 1.0187420220918342, "accelerator_pedal_position": 0.40059615654510955, "brake_pedal_position": 0.0, "acceleration": 0.9924105242265853, "steering_wheel_angle": -0.9684122329518636, "front_wheel_angle": -0.04505251911146372, "heading_rate": -0.017940614223441193, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137658.4075575} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4018104726688559, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0954550675785204, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1184230949748366, "gear": 1, "accelerator_pedal_position": 0.4018104726688559, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7331107576951109, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137658.4075575} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137658.4175575, "x": 4.633257469564769, "y": 4.989461690241806, "z": null, "yaw": -0.025338754401902308, "pitch": null, "roll": null}, "v": 1.1283519509472153, "accelerator_pedal_position": 0.4018104726688559, "brake_pedal_position": 0.0, "acceleration": 0.9921660753809247, "steering_wheel_angle": -0.7331107576951109, "front_wheel_angle": -0.033997214154872196, "heading_rate": -0.014990472279678287, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137658.4275575} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.403063900607908, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.2609932621188237, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1382736117010246, "gear": 1, "accelerator_pedal_position": 0.4018104726688559, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7331107576951109, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137658.4275575} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.2099988460540771, "x": 0.6332574695647688, "y": -0.010538309758193698, "z": null, "yaw": 6.257846552777684, "pitch": null, "roll": null}, "v": 1.1283519509472153, "accelerator_pedal_position": 0.4018104726688559, "brake_pedal_position": 0.0, "acceleration": 0.9921660753809247, "steering_wheel_angle": -0.7331107576951109, "front_wheel_angle": -0.033997214154872196, "heading_rate": -0.014990472279678287, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137658.4475574} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.403063900607908, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.2609932621188237, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1582519110156557, "gear": 1, "accelerator_pedal_position": 0.403063900607908, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6539932314904111, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137658.4475574} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.2099988460540771, "x": 0.6332574695647688, "y": -0.010538309758193698, "z": null, "yaw": 6.257846552777684, "pitch": null, "roll": null}, "v": 1.1283519509472153, "accelerator_pedal_position": 0.4018104726688559, "brake_pedal_position": 0.0, "acceleration": 0.9921660753809247, "steering_wheel_angle": -0.7331107576951109, "front_wheel_angle": -0.033997214154872196, "heading_rate": -0.014990472279678287, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137658.4675574} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.403063900607908, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.2609932621188237, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1881646041716043, "gear": 1, "accelerator_pedal_position": 0.403063900607908, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5747055336149938, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137658.4675574} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.2099988460540771, "x": 0.6332574695647688, "y": -0.010538309758193698, "z": null, "yaw": 6.257846552777684, "pitch": null, "roll": null}, "v": 1.1283519509472153, "accelerator_pedal_position": 0.4018104726688559, "brake_pedal_position": 0.0, "acceleration": 0.9921660753809247, "steering_wheel_angle": -0.7331107576951109, "front_wheel_angle": -0.033997214154872196, "heading_rate": -0.014990472279678287, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137658.4875574} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.403063900607908, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.2609932621188237, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1981208421448521, "gear": 1, "accelerator_pedal_position": 0.403063900607908, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5747055336149938, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137658.4875574} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.2099988460540771, "x": 0.6332574695647688, "y": -0.010538309758193698, "z": null, "yaw": 6.257846552777684, "pitch": null, "roll": null}, "v": 1.1283519509472153, "accelerator_pedal_position": 0.4018104726688559, "brake_pedal_position": 0.0, "acceleration": 0.9921660753809247, "steering_wheel_angle": -0.7331107576951109, "front_wheel_angle": -0.033997214154872196, "heading_rate": -0.014990472279678287, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137658.5075574} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.403063900607908, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.2609932621188237, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2180112418351263, "gear": 1, "accelerator_pedal_position": 0.403063900607908, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5747055336149938, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137658.5075574} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137658.5275574, "x": 4.762812706675279, "y": 4.986099395074287, "z": null, "yaw": -0.02658305879638915, "pitch": null, "roll": null}, "v": 1.2378721109798767, "accelerator_pedal_position": 0.403063900607908, "brake_pedal_position": 0.0, "acceleration": 0.991932499619013, "steering_wheel_angle": -0.5747055336149938, "front_wheel_angle": -0.02659464161455273, "heading_rate": -0.012862706522212962, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137658.5275574} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4043547006688659, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3650496510634345, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2378721109798767, "gear": 1, "accelerator_pedal_position": 0.403063900607908, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5747055336149938, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137658.5275574} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.3199987411499023, "x": 0.7628127066752786, "y": -0.013900604925712656, "z": null, "yaw": 6.256602248383197, "pitch": null, "roll": null}, "v": 1.2378721109798767, "accelerator_pedal_position": 0.403063900607908, "brake_pedal_position": 0.0, "acceleration": 0.991932499619013, "steering_wheel_angle": -0.5747055336149938, "front_wheel_angle": -0.02659464161455273, "heading_rate": -0.012862706522212962, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137658.5475574} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4043547006688659, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3650496510634345, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2578646252356547, "gear": 1, "accelerator_pedal_position": 0.4043547006688659, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.49502666717676597, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137658.5475574} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.3199987411499023, "x": 0.7628127066752786, "y": -0.013900604925712656, "z": null, "yaw": 6.256602248383197, "pitch": null, "roll": null}, "v": 1.2378721109798767, "accelerator_pedal_position": 0.403063900607908, "brake_pedal_position": 0.0, "acceleration": 0.991932499619013, "steering_wheel_angle": -0.5747055336149938, "front_wheel_angle": -0.02659464161455273, "heading_rate": -0.012862706522212962, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137658.5675573} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4043547006688659, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3650496510634345, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2778271390746105, "gear": 1, "accelerator_pedal_position": 0.4043547006688659, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.49502666717676597, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137658.5675573} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.3199987411499023, "x": 0.7628127066752786, "y": -0.013900604925712656, "z": null, "yaw": 6.256602248383197, "pitch": null, "roll": null}, "v": 1.2378721109798767, "accelerator_pedal_position": 0.403063900607908, "brake_pedal_position": 0.0, "acceleration": 0.991932499619013, "steering_wheel_angle": -0.5747055336149938, "front_wheel_angle": -0.02659464161455273, "heading_rate": -0.012862706522212962, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137658.5875573} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4043547006688659, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3650496510634345, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2977595381742348, "gear": 1, "accelerator_pedal_position": 0.4043547006688659, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.49502666717676597, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137658.5875573} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.3199987411499023, "x": 0.7628127066752786, "y": -0.013900604925712656, "z": null, "yaw": 6.256602248383197, "pitch": null, "roll": null}, "v": 1.2378721109798767, "accelerator_pedal_position": 0.403063900607908, "brake_pedal_position": 0.0, "acceleration": 0.991932499619013, "steering_wheel_angle": -0.5747055336149938, "front_wheel_angle": -0.02659464161455273, "heading_rate": -0.012862706522212962, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137658.6075573} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4043547006688659, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3650496510634345, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3176617091046494, "gear": 1, "accelerator_pedal_position": 0.4043547006688659, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.49502666717676597, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137658.6075573} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.3199987411499023, "x": 0.7628127066752786, "y": -0.013900604925712656, "z": null, "yaw": 6.256602248383197, "pitch": null, "roll": null}, "v": 1.2378721109798767, "accelerator_pedal_position": 0.403063900607908, "brake_pedal_position": 0.0, "acceleration": 0.991932499619013, "steering_wheel_angle": -0.5747055336149938, "front_wheel_angle": -0.02659464161455273, "heading_rate": -0.012862706522212962, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137658.6275573} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4043547006688659, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3650496510634345, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3375335393297907, "gear": 1, "accelerator_pedal_position": 0.4043547006688659, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.49502666717676597, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137658.6275573} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137658.6375573, "x": 4.904414389655124, "y": 4.982267254959578, "z": null, "yaw": -0.02758824793894342, "pitch": null, "roll": null}, "v": 1.3474580417550468, "accelerator_pedal_position": 0.4043547006688659, "brake_pedal_position": 0.0, "acceleration": 0.9916875453497559, "steering_wheel_angle": -0.49502666717676597, "front_wheel_angle": -0.02288307196571315, "heading_rate": -0.012046625931448266, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137658.6475573} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.405684693412905, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.48260417911135345, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3573749172085443, "gear": 1, "accelerator_pedal_position": 0.4043547006688659, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.49502666717676597, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137658.6475573} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.4299986362457275, "x": 0.9044143896551242, "y": -0.017732745040421882, "z": null, "yaw": 6.2555970592406425, "pitch": null, "roll": null}, "v": 1.3474580417550468, "accelerator_pedal_position": 0.4043547006688659, "brake_pedal_position": 0.0, "acceleration": 0.9916875453497559, "steering_wheel_angle": -0.49502666717676597, "front_wheel_angle": -0.02288307196571315, "heading_rate": -0.012046625931448266, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137658.6675572} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.405684693412905, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.48260417911135345, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3773519167948929, "gear": 1, "accelerator_pedal_position": 0.405684693412905, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.41492424603617667, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137658.6675572} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.4299986362457275, "x": 0.9044143896551242, "y": -0.017732745040421882, "z": null, "yaw": 6.2555970592406425, "pitch": null, "roll": null}, "v": 1.3474580417550468, "accelerator_pedal_position": 0.4043547006688659, "brake_pedal_position": 0.0, "acceleration": 0.9916875453497559, "steering_wheel_angle": -0.49502666717676597, "front_wheel_angle": -0.02288307196571315, "heading_rate": -0.012046625931448266, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137658.6875572} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.405684693412905, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.48260417911135345, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3972979851439806, "gear": 1, "accelerator_pedal_position": 0.405684693412905, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3748084600701244, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137658.6875572} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.4299986362457275, "x": 0.9044143896551242, "y": -0.017732745040421882, "z": null, "yaw": 6.2555970592406425, "pitch": null, "roll": null}, "v": 1.3474580417550468, "accelerator_pedal_position": 0.4043547006688659, "brake_pedal_position": 0.0, "acceleration": 0.9916875453497559, "steering_wheel_angle": -0.49502666717676597, "front_wheel_angle": -0.02288307196571315, "heading_rate": -0.012046625931448266, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137658.7075572} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.405684693412905, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.48260417911135345, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.417213011071673, "gear": 1, "accelerator_pedal_position": 0.405684693412905, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3748084600701244, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137658.7075572} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.4299986362457275, "x": 0.9044143896551242, "y": -0.017732745040421882, "z": null, "yaw": 6.2555970592406425, "pitch": null, "roll": null}, "v": 1.3474580417550468, "accelerator_pedal_position": 0.4043547006688659, "brake_pedal_position": 0.0, "acceleration": 0.9916875453497559, "steering_wheel_angle": -0.49502666717676597, "front_wheel_angle": -0.02288307196571315, "heading_rate": -0.012046625931448266, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137658.7275572} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.405684693412905, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.48260417911135345, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4370968843086358, "gear": 1, "accelerator_pedal_position": 0.405684693412905, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3748084600701244, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137658.7275572} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137658.7475572, "x": 5.058053549121723, "y": 4.9779666572599, "z": null, "yaw": -0.028397075335432124, "pitch": null, "roll": null}, "v": 1.456949495501272, "accelerator_pedal_position": 0.405684693412905, "brake_pedal_position": 0.0, "acceleration": 0.9914548407311782, "steering_wheel_angle": -0.3748084600701244, "front_wheel_angle": -0.01729813586842601, "heading_rate": -0.00984571264536928, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137658.7475572} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3872153777563191, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5881979066950825, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.456949495501272, "gear": 1, "accelerator_pedal_position": 0.405684693412905, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3748084600701244, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137658.7475572} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.5399985313415527, "x": 1.0580535491217233, "y": -0.022033342740099826, "z": null, "yaw": 6.254788231844154, "pitch": null, "roll": null}, "v": 1.456949495501272, "accelerator_pedal_position": 0.405684693412905, "brake_pedal_position": 0.0, "acceleration": 0.9914548407311782, "steering_wheel_angle": -0.3748084600701244, "front_wheel_angle": -0.01729813586842601, "heading_rate": -0.00984571264536928, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137658.7675571} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4053141861776481, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5881979066950825, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.474462987438086, "gear": 1, "accelerator_pedal_position": 0.3872153777563191, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2942181964946994, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137658.7675571} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.5399985313415527, "x": 1.0580535491217233, "y": -0.022033342740099826, "z": null, "yaw": 6.254788231844154, "pitch": null, "roll": null}, "v": 1.456949495501272, "accelerator_pedal_position": 0.405684693412905, "brake_pedal_position": 0.0, "acceleration": 0.9914548407311782, "steering_wheel_angle": -0.3748084600701244, "front_wheel_angle": -0.01729813586842601, "heading_rate": -0.00984571264536928, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137658.7875571} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4053141861776481, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5881979066950825, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.494210128193634, "gear": 1, "accelerator_pedal_position": 0.4053141861776481, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2538581202775665, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137658.7875571} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.5399985313415527, "x": 1.0580535491217233, "y": -0.022033342740099826, "z": null, "yaw": 6.254788231844154, "pitch": null, "roll": null}, "v": 1.456949495501272, "accelerator_pedal_position": 0.405684693412905, "brake_pedal_position": 0.0, "acceleration": 0.9914548407311782, "steering_wheel_angle": -0.3748084600701244, "front_wheel_angle": -0.01729813586842601, "heading_rate": -0.00984571264536928, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137658.807557} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4053141861776481, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5881979066950825, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5139257708382918, "gear": 1, "accelerator_pedal_position": 0.4053141861776481, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2538581202775665, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137658.807557} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.5399985313415527, "x": 1.0580535491217233, "y": -0.022033342740099826, "z": null, "yaw": 6.254788231844154, "pitch": null, "roll": null}, "v": 1.456949495501272, "accelerator_pedal_position": 0.405684693412905, "brake_pedal_position": 0.0, "acceleration": 0.9914548407311782, "steering_wheel_angle": -0.3748084600701244, "front_wheel_angle": -0.01729813586842601, "heading_rate": -0.00984571264536928, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137658.827557} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4053141861776481, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5881979066950825, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.533609810193548, "gear": 1, "accelerator_pedal_position": 0.4053141861776481, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2538581202775665, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137658.827557} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.5399985313415527, "x": 1.0580535491217233, "y": -0.022033342740099826, "z": null, "yaw": 6.254788231844154, "pitch": null, "roll": null}, "v": 1.456949495501272, "accelerator_pedal_position": 0.405684693412905, "brake_pedal_position": 0.0, "acceleration": 0.9914548407311782, "steering_wheel_angle": -0.3748084600701244, "front_wheel_angle": -0.01729813586842601, "heading_rate": -0.00984571264536928, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137658.847557} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4053141861776481, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5881979066950825, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5532621419959585, "gear": 1, "accelerator_pedal_position": 0.4053141861776481, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2538581202775665, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137658.847557} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137658.857557, "x": 5.22346310414798, "y": 4.973223757141026, "z": null, "yaw": -0.02894348041386695, "pitch": null, "roll": null}, "v": 1.5630763852328877, "accelerator_pedal_position": 0.4053141861776481, "brake_pedal_position": 0.0, "acceleration": 0.9806277664879289, "steering_wheel_angle": -0.2538581202775665, "front_wheel_angle": -0.01169726418757777, "heading_rate": -0.00714240287694703, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137658.867557} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.37101963665070004, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6670627692208652, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.572882662897767, "gear": 1, "accelerator_pedal_position": 0.4053141861776481, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2538581202775665, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137658.867557} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.649998426437378, "x": 1.2234631041479798, "y": -0.02677624285897373, "z": null, "yaw": 6.254241826765719, "pitch": null, "roll": null}, "v": 1.5630763852328877, "accelerator_pedal_position": 0.4053141861776481, "brake_pedal_position": 0.0, "acceleration": 0.9806277664879289, "steering_wheel_angle": -0.2538581202775665, "front_wheel_angle": -0.01169726418757777, "heading_rate": -0.00714240287694703, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137658.887557} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3879988709280984, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6670627692208652, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.588186201488493, "gear": 1, "accelerator_pedal_position": 0.37101963665070004, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.1728347969881057, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137658.887557} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.649998426437378, "x": 1.2234631041479798, "y": -0.02677624285897373, "z": null, "yaw": 6.254241826765719, "pitch": null, "roll": null}, "v": 1.5630763852328877, "accelerator_pedal_position": 0.4053141861776481, "brake_pedal_position": 0.0, "acceleration": 0.9806277664879289, "steering_wheel_angle": -0.2538581202775665, "front_wheel_angle": -0.01169726418757777, "heading_rate": -0.00714240287694703, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137658.907557} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3879988709280984, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6670627692208652, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6142756286660636, "gear": 1, "accelerator_pedal_position": 0.3879988709280984, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.1728347969881057, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137658.907557} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.649998426437378, "x": 1.2234631041479798, "y": -0.02677624285897373, "z": null, "yaw": 6.254241826765719, "pitch": null, "roll": null}, "v": 1.5630763852328877, "accelerator_pedal_position": 0.4053141861776481, "brake_pedal_position": 0.0, "acceleration": 0.9806277664879289, "steering_wheel_angle": -0.2538581202775665, "front_wheel_angle": -0.01169726418757777, "heading_rate": -0.00714240287694703, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137658.927557} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3879988709280984, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6670627692208652, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6229578317042062, "gear": 1, "accelerator_pedal_position": 0.3879988709280984, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.1728347969881057, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137658.927557} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.649998426437378, "x": 1.2234631041479798, "y": -0.02677624285897373, "z": null, "yaw": 6.254241826765719, "pitch": null, "roll": null}, "v": 1.5630763852328877, "accelerator_pedal_position": 0.4053141861776481, "brake_pedal_position": 0.0, "acceleration": 0.9806277664879289, "steering_wheel_angle": -0.2538581202775665, "front_wheel_angle": -0.01169726418757777, "heading_rate": -0.00714240287694703, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137658.947557} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3879988709280984, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6670627692208652, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6403007734140211, "gear": 1, "accelerator_pedal_position": 0.3879988709280984, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.1728347969881057, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137658.947557} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137658.967557, "x": 5.400041027160577, "y": 4.968078371283747, "z": null, "yaw": -0.029321864823991517, "pitch": null, "roll": null}, "v": 1.6576150350828986, "accelerator_pedal_position": 0.3879988709280984, "brake_pedal_position": 0.0, "acceleration": 0.8646353155011413, "steering_wheel_angle": -0.1728347969881057, "front_wheel_angle": -0.007955355595081511, "heading_rate": -0.005151248140893563, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137658.967557} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.35432977553910594, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7157730827375364, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6576150350828986, "gear": 1, "accelerator_pedal_position": 0.3879988709280984, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.1728347969881057, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137658.967557} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.7599983215332031, "x": 1.4000410271605768, "y": -0.031921628716252926, "z": null, "yaw": 6.253863442355595, "pitch": null, "roll": null}, "v": 1.6576150350828986, "accelerator_pedal_position": 0.3879988709280984, "brake_pedal_position": 0.0, "acceleration": 0.8646353155011413, "steering_wheel_angle": -0.1728347969881057, "front_wheel_angle": -0.007955355595081511, "heading_rate": -0.005151248140893563, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137658.987557} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3709548182713406, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7157730827375364, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6706936603371156, "gear": 1, "accelerator_pedal_position": 0.35432977553910594, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.13220406269519916, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137658.987557} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.7599983215332031, "x": 1.4000410271605768, "y": -0.031921628716252926, "z": null, "yaw": 6.253863442355595, "pitch": null, "roll": null}, "v": 1.6576150350828986, "accelerator_pedal_position": 0.3879988709280984, "brake_pedal_position": 0.0, "acceleration": 0.8646353155011413, "steering_wheel_angle": -0.1728347969881057, "front_wheel_angle": -0.007955355595081511, "heading_rate": -0.005151248140893563, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137659.007557} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3709548182713406, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7157730827375364, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6858277551652006, "gear": 1, "accelerator_pedal_position": 0.3709548182713406, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.13220406269519916, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137659.007557} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.7599983215332031, "x": 1.4000410271605768, "y": -0.031921628716252926, "z": null, "yaw": 6.253863442355595, "pitch": null, "roll": null}, "v": 1.6576150350828986, "accelerator_pedal_position": 0.3879988709280984, "brake_pedal_position": 0.0, "acceleration": 0.8646353155011413, "steering_wheel_angle": -0.1728347969881057, "front_wheel_angle": -0.007955355595081511, "heading_rate": -0.005151248140893563, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137659.027557} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3709548182713406, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7157730827375364, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.70093654400876, "gear": 1, "accelerator_pedal_position": 0.3709548182713406, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.13220406269519916, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137659.027557} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.7599983215332031, "x": 1.4000410271605768, "y": -0.031921628716252926, "z": null, "yaw": 6.253863442355595, "pitch": null, "roll": null}, "v": 1.6576150350828986, "accelerator_pedal_position": 0.3879988709280984, "brake_pedal_position": 0.0, "acceleration": 0.8646353155011413, "steering_wheel_angle": -0.1728347969881057, "front_wheel_angle": -0.007955355595081511, "heading_rate": -0.005151248140893563, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137659.0475569} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3709548182713406, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7157730827375364, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7160199779105, "gear": 1, "accelerator_pedal_position": 0.3709548182713406, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.13220406269519916, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137659.0475569} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.7599983215332031, "x": 1.4000410271605768, "y": -0.031921628716252926, "z": null, "yaw": 6.253863442355595, "pitch": null, "roll": null}, "v": 1.6576150350828986, "accelerator_pedal_position": 0.3879988709280984, "brake_pedal_position": 0.0, "acceleration": 0.8646353155011413, "steering_wheel_angle": -0.1728347969881057, "front_wheel_angle": -0.007955355595081511, "heading_rate": -0.005151248140893563, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137659.0675569} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3709548182713406, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7157730827375364, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7310780084543749, "gear": 1, "accelerator_pedal_position": 0.3709548182713406, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.13220406269519916, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137659.0675569} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137659.0775568, "x": 5.586260360563645, "y": 4.962592931140578, "z": null, "yaw": -0.029590519004004185, "pitch": null, "roll": null}, "v": 1.738597482484971, "accelerator_pedal_position": 0.3709548182713406, "brake_pedal_position": 0.0, "acceleration": 0.751310528010599, "steering_wheel_angle": -0.13220406269519916, "front_wheel_angle": -0.006081919675191413, "heading_rate": -0.0041305236775573875, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137659.0875568} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.345083452718855, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7638868486276033, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.746110587765077, "gear": 1, "accelerator_pedal_position": 0.3709548182713406, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.13220406269519916, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137659.0875568} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.8699982166290283, "x": 1.586260360563645, "y": -0.03740706885942213, "z": null, "yaw": 6.253594788175582, "pitch": null, "roll": null}, "v": 1.738597482484971, "accelerator_pedal_position": 0.3709548182713406, "brake_pedal_position": 0.0, "acceleration": 0.751310528010599, "steering_wheel_angle": -0.13220406269519916, "front_wheel_angle": -0.006081919675191413, "heading_rate": -0.0041305236775573875, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137659.1075568} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.357921210986264, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7638868486276033, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7578851231380972, "gear": 1, "accelerator_pedal_position": 0.345083452718855, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.09147627250049953, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137659.1075568} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.8699982166290283, "x": 1.586260360563645, "y": -0.03740706885942213, "z": null, "yaw": 6.253594788175582, "pitch": null, "roll": null}, "v": 1.738597482484971, "accelerator_pedal_position": 0.3709548182713406, "brake_pedal_position": 0.0, "acceleration": 0.751310528010599, "steering_wheel_angle": -0.13220406269519916, "front_wheel_angle": -0.006081919675191413, "heading_rate": -0.0041305236775573875, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137659.1275568} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.357921210986264, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7638868486276033, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7712436625645325, "gear": 1, "accelerator_pedal_position": 0.357921210986264, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.09147627250049953, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137659.1275568} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.8699982166290283, "x": 1.586260360563645, "y": -0.03740706885942213, "z": null, "yaw": 6.253594788175582, "pitch": null, "roll": null}, "v": 1.738597482484971, "accelerator_pedal_position": 0.3709548182713406, "brake_pedal_position": 0.0, "acceleration": 0.751310528010599, "steering_wheel_angle": -0.13220406269519916, "front_wheel_angle": -0.006081919675191413, "heading_rate": -0.0041305236775573875, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137659.1475568} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.357921210986264, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7638868486276033, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7845794065459137, "gear": 1, "accelerator_pedal_position": 0.357921210986264, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.09147627250049953, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137659.1475568} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.8699982166290283, "x": 1.586260360563645, "y": -0.03740706885942213, "z": null, "yaw": 6.253594788175582, "pitch": null, "roll": null}, "v": 1.738597482484971, "accelerator_pedal_position": 0.3709548182713406, "brake_pedal_position": 0.0, "acceleration": 0.751310528010599, "steering_wheel_angle": -0.13220406269519916, "front_wheel_angle": -0.006081919675191413, "heading_rate": -0.0041305236775573875, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137659.1675568} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.357921210986264, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7638868486276033, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7978923228747539, "gear": 1, "accelerator_pedal_position": 0.357921210986264, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.09147627250049953, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137659.1675568} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137659.1875567, "x": 5.781040198230289, "y": 4.956809003945142, "z": null, "yaw": -0.02978590344850027, "pitch": null, "roll": null}, "v": 1.8111823797635642, "accelerator_pedal_position": 0.357921210986264, "brake_pedal_position": 0.0, "acceleration": 0.6636446335483117, "steering_wheel_angle": -0.09147627250049953, "front_wheel_angle": -0.004206022804016835, "heading_rate": -0.0029757497318348217, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137659.1875567} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3326221996990557, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7945804841822743, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8111823797635642, "gear": 1, "accelerator_pedal_position": 0.357921210986264, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.09147627250049953, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137659.1875567} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.9799981117248535, "x": 1.781040198230289, "y": -0.04319099605485821, "z": null, "yaw": 6.253399403731086, "pitch": null, "roll": null}, "v": 1.8111823797635642, "accelerator_pedal_position": 0.357921210986264, "brake_pedal_position": 0.0, "acceleration": 0.6636446335483117, "steering_wheel_angle": -0.09147627250049953, "front_wheel_angle": -0.004206022804016835, "heading_rate": -0.0029757497318348217, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137659.2075567} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3451421807705226, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7945804841822743, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8212885346401109, "gear": 1, "accelerator_pedal_position": 0.3326221996990557, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.05067052007024927, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137659.2075567} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.9799981117248535, "x": 1.781040198230289, "y": -0.04319099605485821, "z": null, "yaw": 6.253399403731086, "pitch": null, "roll": null}, "v": 1.8111823797635642, "accelerator_pedal_position": 0.357921210986264, "brake_pedal_position": 0.0, "acceleration": 0.6636446335483117, "steering_wheel_angle": -0.09147627250049953, "front_wheel_angle": -0.004206022804016835, "heading_rate": -0.0029757497318348217, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137659.2275567} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3451421807705226, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7945804841822743, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8329415591321871, "gear": 1, "accelerator_pedal_position": 0.3451421807705226, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.05067052007024927, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137659.2275567} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.9799981117248535, "x": 1.781040198230289, "y": -0.04319099605485821, "z": null, "yaw": 6.253399403731086, "pitch": null, "roll": null}, "v": 1.8111823797635642, "accelerator_pedal_position": 0.357921210986264, "brake_pedal_position": 0.0, "acceleration": 0.6636446335483117, "steering_wheel_angle": -0.09147627250049953, "front_wheel_angle": -0.004206022804016835, "heading_rate": -0.0029757497318348217, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137659.2475567} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3451421807705226, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7945804841822743, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.844574409199155, "gear": 1, "accelerator_pedal_position": 0.3451421807705226, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.05067052007024927, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137659.2475567} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.9799981117248535, "x": 1.781040198230289, "y": -0.04319099605485821, "z": null, "yaw": 6.253399403731086, "pitch": null, "roll": null}, "v": 1.8111823797635642, "accelerator_pedal_position": 0.357921210986264, "brake_pedal_position": 0.0, "acceleration": 0.6636446335483117, "steering_wheel_angle": -0.09147627250049953, "front_wheel_angle": -0.004206022804016835, "heading_rate": -0.0029757497318348217, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137659.2675567} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3451421807705226, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7945804841822743, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8619858153854763, "gear": 1, "accelerator_pedal_position": 0.3451421807705226, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.05067052007024927, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137659.2675567} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.9799981117248535, "x": 1.781040198230289, "y": -0.04319099605485821, "z": null, "yaw": 6.253399403731086, "pitch": null, "roll": null}, "v": 1.8111823797635642, "accelerator_pedal_position": 0.357921210986264, "brake_pedal_position": 0.0, "acceleration": 0.6636446335483117, "steering_wheel_angle": -0.09147627250049953, "front_wheel_angle": -0.004206022804016835, "heading_rate": -0.0029757497318348217, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137659.2875566} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3451421807705226, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7945804841822743, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8677795096582714, "gear": 1, "accelerator_pedal_position": 0.3451421807705226, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.05067052007024927, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137659.2875566} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137659.2975566, "x": 5.983234537713815, "y": 4.950774068742484, "z": null, "yaw": -0.029893292506694886, "pitch": null, "roll": null}, "v": 1.87356814617193, "accelerator_pedal_position": 0.3451421807705226, "brake_pedal_position": 0.0, "acceleration": 0.5783576465236685, "steering_wheel_angle": -0.05067052007024927, "front_wheel_angle": -0.0023285509205309136, "heading_rate": -0.001704182311145084, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137659.3075566} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.32510949222621155, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8438707672112554, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8793517226371668, "gear": 1, "accelerator_pedal_position": 0.3451421807705226, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.05067052007024927, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137659.3075566} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.0899980068206787, "x": 1.9832345377138152, "y": -0.04922593125751629, "z": null, "yaw": 6.253292014672891, "pitch": null, "roll": null}, "v": 1.87356814617193, "accelerator_pedal_position": 0.3451421807705226, "brake_pedal_position": 0.0, "acceleration": 0.5783576465236685, "steering_wheel_angle": -0.05067052007024927, "front_wheel_angle": -0.0023285509205309136, "heading_rate": -0.001704182311145084, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137659.3275566} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.33506167636562545, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8438707672112554, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.893541246916667, "gear": 1, "accelerator_pedal_position": 0.33506167636562545, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.009765740189997724, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137659.3275566} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.0899980068206787, "x": 1.9832345377138152, "y": -0.04922593125751629, "z": null, "yaw": 6.253292014672891, "pitch": null, "roll": null}, "v": 1.87356814617193, "accelerator_pedal_position": 0.3451421807705226, "brake_pedal_position": 0.0, "acceleration": 0.5783576465236685, "steering_wheel_angle": -0.05067052007024927, "front_wheel_angle": -0.0023285509205309136, "heading_rate": -0.001704182311145084, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137659.3475566} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.33506167636562545, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8438707672112554, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.898677281220683, "gear": 1, "accelerator_pedal_position": 0.33506167636562545, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.009765740189997724, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137659.3475566} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.0899980068206787, "x": 1.9832345377138152, "y": -0.04922593125751629, "z": null, "yaw": 6.253292014672891, "pitch": null, "roll": null}, "v": 1.87356814617193, "accelerator_pedal_position": 0.3451421807705226, "brake_pedal_position": 0.0, "acceleration": 0.5783576465236685, "steering_wheel_angle": -0.05067052007024927, "front_wheel_angle": -0.0023285509205309136, "heading_rate": -0.001704182311145084, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137659.3675566} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.33506167636562545, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8438707672112554, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.908935801389424, "gear": 1, "accelerator_pedal_position": 0.33506167636562545, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.009765740189997724, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137659.3675566} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.0899980068206787, "x": 1.9832345377138152, "y": -0.04922593125751629, "z": null, "yaw": 6.253292014672891, "pitch": null, "roll": null}, "v": 1.87356814617193, "accelerator_pedal_position": 0.3451421807705226, "brake_pedal_position": 0.0, "acceleration": 0.5783576465236685, "steering_wheel_angle": -0.05067052007024927, "front_wheel_angle": -0.0023285509205309136, "heading_rate": -0.001704182311145084, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137659.3875566} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.33506167636562545, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8438707672112554, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9191762483910015, "gear": 1, "accelerator_pedal_position": 0.33506167636562545, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.009765740189997724, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137659.3875566} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137659.4075565, "x": 6.192017944306566, "y": 4.944526489249131, "z": null, "yaw": -0.029927253379527233, "pitch": null, "roll": null}, "v": 1.9293986121380227, "accelerator_pedal_position": 0.33506167636562545, "brake_pedal_position": 0.0, "acceleration": 0.5104397566330565, "steering_wheel_angle": -0.009765740189997724, "front_wheel_angle": -0.0004485414351236973, "heading_rate": -0.000338052843926377, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137659.4075565} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3151400544650978, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8595214300895957, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9293986121380227, "gear": 1, "accelerator_pedal_position": 0.33506167636562545, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.009765740189997724, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137659.4075565} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.199997901916504, "x": 2.192017944306566, "y": -0.05547351075086926, "z": null, "yaw": 6.253258053800059, "pitch": null, "roll": null}, "v": 1.9293986121380227, "accelerator_pedal_position": 0.33506167636562545, "brake_pedal_position": 0.0, "acceleration": 0.5104397566330565, "steering_wheel_angle": -0.009765740189997724, "front_wheel_angle": -0.0004485414351236973, "heading_rate": -0.000338052843926377, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137659.4275565} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3250010021901808, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8595214300895957, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.937113784171457, "gear": 1, "accelerator_pedal_position": 0.3151400544650978, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.03117506765060259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137659.4275565} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.199997901916504, "x": 2.192017944306566, "y": -0.05547351075086926, "z": null, "yaw": 6.253258053800059, "pitch": null, "roll": null}, "v": 1.9293986121380227, "accelerator_pedal_position": 0.33506167636562545, "brake_pedal_position": 0.0, "acceleration": 0.5104397566330565, "steering_wheel_angle": -0.009765740189997724, "front_wheel_angle": -0.0004485414351236973, "heading_rate": -0.000338052843926377, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137659.4475565} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3250010021901808, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8595214300895957, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9460473460179606, "gear": 1, "accelerator_pedal_position": 0.3250010021901808, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.03117506765060259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137659.4475565} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.199997901916504, "x": 2.192017944306566, "y": -0.05547351075086926, "z": null, "yaw": 6.253258053800059, "pitch": null, "roll": null}, "v": 1.9293986121380227, "accelerator_pedal_position": 0.33506167636562545, "brake_pedal_position": 0.0, "acceleration": 0.5104397566330565, "steering_wheel_angle": -0.009765740189997724, "front_wheel_angle": -0.0004485414351236973, "heading_rate": -0.000338052843926377, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137659.4675565} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3250010021901808, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8595214300895957, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9549650352898962, "gear": 1, "accelerator_pedal_position": 0.3250010021901808, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.03117506765060259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137659.4675565} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.199997901916504, "x": 2.192017944306566, "y": -0.05547351075086926, "z": null, "yaw": 6.253258053800059, "pitch": null, "roll": null}, "v": 1.9293986121380227, "accelerator_pedal_position": 0.33506167636562545, "brake_pedal_position": 0.0, "acceleration": 0.5104397566330565, "steering_wheel_angle": -0.009765740189997724, "front_wheel_angle": -0.0004485414351236973, "heading_rate": -0.000338052843926377, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137659.4875565} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3250010021901808, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8595214300895957, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9683118003055813, "gear": 1, "accelerator_pedal_position": 0.3250010021901808, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.03117506765060259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137659.4875565} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.199997901916504, "x": 2.192017944306566, "y": -0.05547351075086926, "z": null, "yaw": 6.253258053800059, "pitch": null, "roll": null}, "v": 1.9293986121380227, "accelerator_pedal_position": 0.33506167636562545, "brake_pedal_position": 0.0, "acceleration": 0.5104397566330565, "steering_wheel_angle": -0.009765740189997724, "front_wheel_angle": -0.0004485414351236973, "heading_rate": -0.000338052843926377, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137659.5075564} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3250010021901808, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8595214300895957, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9771897928000723, "gear": 1, "accelerator_pedal_position": 0.3250010021901808, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.03117506765060259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137659.5075564} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137659.5175564, "x": 6.406494226768466, "y": 4.9381104830297184, "z": null, "yaw": -0.029873057177264812, "pitch": null, "roll": null}, "v": 1.9771897928000723, "accelerator_pedal_position": 0.3250010021901808, "brake_pedal_position": 0.0, "acceleration": 0.4433039792810983, "steering_wheel_angle": 0.03117506765060259, "front_wheel_angle": 0.001432275945040912, "heading_rate": 0.001106204420102977, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137659.5275564} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.30818008222530885, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.878256643120228, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9816228325928833, "gear": 1, "accelerator_pedal_position": 0.3250010021901808, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.03117506765060259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137659.5275564} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.309997797012329, "x": 2.4064942267684657, "y": -0.061889516970281555, "z": null, "yaw": 6.253312250002321, "pitch": null, "roll": null}, "v": 1.9771897928000723, "accelerator_pedal_position": 0.3250010021901808, "brake_pedal_position": 0.0, "acceleration": 0.4433039792810983, "steering_wheel_angle": 0.03117506765060259, "front_wheel_angle": 0.001432275945040912, "heading_rate": 0.001106204420102977, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137659.5475564} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3165143578961392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.878256643120228, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.988375325517396, "gear": 1, "accelerator_pedal_position": 0.30818008222530885, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.03117506765060259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137659.5475564} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.309997797012329, "x": 2.4064942267684657, "y": -0.061889516970281555, "z": null, "yaw": 6.253312250002321, "pitch": null, "roll": null}, "v": 1.9771897928000723, "accelerator_pedal_position": 0.3250010021901808, "brake_pedal_position": 0.0, "acceleration": 0.4433039792810983, "steering_wheel_angle": 0.03117506765060259, "front_wheel_angle": 0.001432275945040912, "heading_rate": 0.001106204420102977, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137659.5675564} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3165143578961392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.878256643120228, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9961570218402167, "gear": 1, "accelerator_pedal_position": 0.3165143578961392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.03117506765060259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137659.5675564} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.309997797012329, "x": 2.4064942267684657, "y": -0.061889516970281555, "z": null, "yaw": 6.253312250002321, "pitch": null, "roll": null}, "v": 1.9771897928000723, "accelerator_pedal_position": 0.3250010021901808, "brake_pedal_position": 0.0, "acceleration": 0.4433039792810983, "steering_wheel_angle": 0.03117506765060259, "front_wheel_angle": 0.001432275945040912, "heading_rate": 0.001106204420102977, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137659.5875564} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3165143578961392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.878256643120228, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0039247354167773, "gear": 1, "accelerator_pedal_position": 0.3165143578961392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.03117506765060259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137659.5875564} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.309997797012329, "x": 2.4064942267684657, "y": -0.061889516970281555, "z": null, "yaw": 6.253312250002321, "pitch": null, "roll": null}, "v": 1.9771897928000723, "accelerator_pedal_position": 0.3250010021901808, "brake_pedal_position": 0.0, "acceleration": 0.4433039792810983, "steering_wheel_angle": 0.03117506765060259, "front_wheel_angle": 0.001432275945040912, "heading_rate": 0.001106204420102977, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137659.6075563} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3165143578961392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.878256643120228, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0116784672482546, "gear": 1, "accelerator_pedal_position": 0.3165143578961392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.03117506765060259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137659.6075563} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137659.6275563, "x": 6.625992561937591, "y": 4.93155761473165, "z": null, "yaw": -0.02981151402816785, "pitch": null, "roll": null}, "v": 2.019418218464236, "accelerator_pedal_position": 0.3165143578961392, "brake_pedal_position": 0.0, "acceleration": 0.3864633265170053, "steering_wheel_angle": 0.03117506765060259, "front_wheel_angle": 0.001432275945040912, "heading_rate": 0.0011298305137100724, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137659.6275563} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2991868666832543, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8667420821850865, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.019418218464236, "gear": 1, "accelerator_pedal_position": 0.3165143578961392, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.03117506765060259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137659.6275563} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.4199976921081543, "x": 2.625992561937591, "y": -0.06844238526834978, "z": null, "yaw": 6.253373793151418, "pitch": null, "roll": null}, "v": 2.019418218464236, "accelerator_pedal_position": 0.3165143578961392, "brake_pedal_position": 0.0, "acceleration": 0.3864633265170053, "steering_wheel_angle": 0.03117506765060259, "front_wheel_angle": 0.001432275945040912, "heading_rate": 0.0011298305137100724, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137659.6475563} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3077275144549658, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8667420821850865, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.024979033517645, "gear": 1, "accelerator_pedal_position": 0.2991868666832543, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.03117506765060259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137659.6475563} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.4199976921081543, "x": 2.625992561937591, "y": -0.06844238526834978, "z": null, "yaw": 6.253373793151418, "pitch": null, "roll": null}, "v": 2.019418218464236, "accelerator_pedal_position": 0.3165143578961392, "brake_pedal_position": 0.0, "acceleration": 0.3864633265170053, "steering_wheel_angle": 0.03117506765060259, "front_wheel_angle": 0.001432275945040912, "heading_rate": 0.0011298305137100724, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137659.6675563} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3077275144549658, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8667420821850865, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.034901321373322, "gear": 1, "accelerator_pedal_position": 0.3077275144549658, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.03117506765060259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137659.6675563} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.4199976921081543, "x": 2.625992561937591, "y": -0.06844238526834978, "z": null, "yaw": 6.253373793151418, "pitch": null, "roll": null}, "v": 2.019418218464236, "accelerator_pedal_position": 0.3165143578961392, "brake_pedal_position": 0.0, "acceleration": 0.3864633265170053, "steering_wheel_angle": 0.03117506765060259, "front_wheel_angle": 0.001432275945040912, "heading_rate": 0.0011298305137100724, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137659.6875563} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3077275144549658, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8667420821850865, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.038202758027298, "gear": 1, "accelerator_pedal_position": 0.3077275144549658, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.03117506765060259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137659.6875563} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.4199976921081543, "x": 2.625992561937591, "y": -0.06844238526834978, "z": null, "yaw": 6.253373793151418, "pitch": null, "roll": null}, "v": 2.019418218464236, "accelerator_pedal_position": 0.3165143578961392, "brake_pedal_position": 0.0, "acceleration": 0.3864633265170053, "steering_wheel_angle": 0.03117506765060259, "front_wheel_angle": 0.001432275945040912, "heading_rate": 0.0011298305137100724, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137659.7075562} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3077275144549658, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8667420821850865, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.04479664559259, "gear": 1, "accelerator_pedal_position": 0.3077275144549658, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.03117506765060259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137659.7075562} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.4199976921081543, "x": 2.625992561937591, "y": -0.06844238526834978, "z": null, "yaw": 6.253373793151418, "pitch": null, "roll": null}, "v": 2.019418218464236, "accelerator_pedal_position": 0.3165143578961392, "brake_pedal_position": 0.0, "acceleration": 0.3864633265170053, "steering_wheel_angle": 0.03117506765060259, "front_wheel_angle": 0.001432275945040912, "heading_rate": 0.0011298305137100724, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137659.7275562} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3077275144549658, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8667420821850865, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0546650207781343, "gear": 1, "accelerator_pedal_position": 0.3077275144549658, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.03117506765060259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137659.7275562} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137659.7375562, "x": 6.849746814777905, "y": 4.924891469727749, "z": null, "yaw": -0.02974997087907089, "pitch": null, "roll": null}, "v": 2.0546650207781343, "accelerator_pedal_position": 0.3077275144549658, "brake_pedal_position": 0.0, "acceleration": 0.3283472308285374, "steering_wheel_angle": 0.03117506765060259, "front_wheel_angle": 0.001432275945040912, "heading_rate": 0.001149550506528219, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137659.7475562} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29353607052655073, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8697557619324351, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0612289732932925, "gear": 1, "accelerator_pedal_position": 0.3077275144549658, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.03117506765060259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137659.7475562} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.5299975872039795, "x": 2.8497468147779053, "y": -0.07510853027225117, "z": null, "yaw": 6.253435336300515, "pitch": null, "roll": null}, "v": 2.0546650207781343, "accelerator_pedal_position": 0.3077275144549658, "brake_pedal_position": 0.0, "acceleration": 0.3283472308285374, "steering_wheel_angle": 0.03117506765060259, "front_wheel_angle": 0.001432275945040912, "heading_rate": 0.001149550506528219, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137659.7675562} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.30053758630858834, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8697557619324351, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.06600783884334, "gear": 1, "accelerator_pedal_position": 0.29353607052655073, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.03117506765060259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137659.7675562} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.5299975872039795, "x": 2.8497468147779053, "y": -0.07510853027225117, "z": null, "yaw": 6.253435336300515, "pitch": null, "roll": null}, "v": 2.0546650207781343, "accelerator_pedal_position": 0.3077275144549658, "brake_pedal_position": 0.0, "acceleration": 0.3283472308285374, "steering_wheel_angle": 0.03117506765060259, "front_wheel_angle": 0.001432275945040912, "heading_rate": 0.001149550506528219, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137659.7875562} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.30053758630858834, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8697557619324351, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.068831595229189, "gear": 1, "accelerator_pedal_position": 0.30053758630858834, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.03117506765060259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137659.7875562} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.5299975872039795, "x": 2.8497468147779053, "y": -0.07510853027225117, "z": null, "yaw": 6.253435336300515, "pitch": null, "roll": null}, "v": 2.0546650207781343, "accelerator_pedal_position": 0.3077275144549658, "brake_pedal_position": 0.0, "acceleration": 0.3283472308285374, "steering_wheel_angle": 0.03117506765060259, "front_wheel_angle": 0.001432275945040912, "heading_rate": 0.001149550506528219, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137659.8075562} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.30053758630858834, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8697557619324351, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0744713703962874, "gear": 1, "accelerator_pedal_position": 0.30053758630858834, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.03117506765060259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137659.8075562} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.5299975872039795, "x": 2.8497468147779053, "y": -0.07510853027225117, "z": null, "yaw": 6.253435336300515, "pitch": null, "roll": null}, "v": 2.0546650207781343, "accelerator_pedal_position": 0.3077275144549658, "brake_pedal_position": 0.0, "acceleration": 0.3283472308285374, "steering_wheel_angle": 0.03117506765060259, "front_wheel_angle": 0.001432275945040912, "heading_rate": 0.001149550506528219, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137659.8275561} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.30053758630858834, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8697557619324351, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0801008338672893, "gear": 1, "accelerator_pedal_position": 0.30053758630858834, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.03117506765060259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137659.8275561} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137659.847556, "x": 7.077233552548215, "y": 4.918128135053721, "z": null, "yaw": -0.02968842772997393, "pitch": null, "roll": null}, "v": 2.085719991825431, "accelerator_pedal_position": 0.30053758630858834, "brake_pedal_position": 0.0, "acceleration": 0.28057163599440277, "steering_wheel_angle": 0.03117506765060259, "front_wheel_angle": 0.001432275945040912, "heading_rate": 0.0011669252402860943, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137659.847556} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2914688162403633, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9168080742665718, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.085719991825431, "gear": 1, "accelerator_pedal_position": 0.30053758630858834, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.03117506765060259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137659.847556} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.6399974822998047, "x": 3.077233552548215, "y": -0.08187186494627863, "z": null, "yaw": 6.253496879449612, "pitch": null, "roll": null}, "v": 2.085719991825431, "accelerator_pedal_position": 0.30053758630858834, "brake_pedal_position": 0.0, "acceleration": 0.28057163599440277, "steering_wheel_angle": 0.03117506765060259, "front_wheel_angle": 0.001432275945040912, "heading_rate": 0.0011669252402860943, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137659.867556} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29600355045580834, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9168080742665718, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.090195774375098, "gear": 1, "accelerator_pedal_position": 0.2914688162403633, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.07213889718196956, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137659.867556} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.6399974822998047, "x": 3.077233552548215, "y": -0.08187186494627863, "z": null, "yaw": 6.253496879449612, "pitch": null, "roll": null}, "v": 2.085719991825431, "accelerator_pedal_position": 0.30053758630858834, "brake_pedal_position": 0.0, "acceleration": 0.28057163599440277, "steering_wheel_angle": 0.03117506765060259, "front_wheel_angle": 0.001432275945040912, "heading_rate": 0.0011669252402860943, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137659.887556} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29600355045580834, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9168080742665718, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0952299262627654, "gear": 1, "accelerator_pedal_position": 0.29600355045580834, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.07213889718196956, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137659.887556} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.6399974822998047, "x": 3.077233552548215, "y": -0.08187186494627863, "z": null, "yaw": 6.253496879449612, "pitch": null, "roll": null}, "v": 2.085719991825431, "accelerator_pedal_position": 0.30053758630858834, "brake_pedal_position": 0.0, "acceleration": 0.28057163599440277, "steering_wheel_angle": 0.03117506765060259, "front_wheel_angle": 0.001432275945040912, "heading_rate": 0.0011669252402860943, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137659.907556} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29600355045580834, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9168080742665718, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1002548317014456, "gear": 1, "accelerator_pedal_position": 0.29600355045580834, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.07213889718196956, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137659.907556} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.6399974822998047, "x": 3.077233552548215, "y": -0.08187186494627863, "z": null, "yaw": 6.253496879449612, "pitch": null, "roll": null}, "v": 2.085719991825431, "accelerator_pedal_position": 0.30053758630858834, "brake_pedal_position": 0.0, "acceleration": 0.28057163599440277, "steering_wheel_angle": 0.03117506765060259, "front_wheel_angle": 0.001432275945040912, "heading_rate": 0.0011669252402860943, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137659.927556} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29600355045580834, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9168080742665718, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.105270497579272, "gear": 1, "accelerator_pedal_position": 0.29600355045580834, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.07213889718196956, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137659.927556} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.6399974822998047, "x": 3.077233552548215, "y": -0.08187186494627863, "z": null, "yaw": 6.253496879449612, "pitch": null, "roll": null}, "v": 2.085719991825431, "accelerator_pedal_position": 0.30053758630858834, "brake_pedal_position": 0.0, "acceleration": 0.28057163599440277, "steering_wheel_angle": 0.03117506765060259, "front_wheel_angle": 0.001432275945040912, "heading_rate": 0.0011669252402860943, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137659.947556} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29600355045580834, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9168080742665718, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.110276930827384, "gear": 1, "accelerator_pedal_position": 0.29600355045580834, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.07213889718196956, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137659.947556} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137659.957556, "x": 7.307891293370223, "y": 4.9112916989719135, "z": null, "yaw": -0.029553298853230495, "pitch": null, "roll": null}, "v": 2.11277668739298, "accelerator_pedal_position": 0.29600355045580834, "brake_pedal_position": 0.0, "acceleration": 0.24974510267124056, "steering_wheel_angle": 0.07213889718196956, "front_wheel_angle": 0.0033160593973950284, "heading_rate": 0.0027367651051521187, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137659.967556} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28772146911877877, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9538187741660752, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1152741384196925, "gear": 1, "accelerator_pedal_position": 0.29600355045580834, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.07213889718196956, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137659.967556} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.74999737739563, "x": 3.307891293370223, "y": -0.08870830102808647, "z": null, "yaw": 6.253632008326356, "pitch": null, "roll": null}, "v": 2.11277668739298, "accelerator_pedal_position": 0.29600355045580834, "brake_pedal_position": 0.0, "acceleration": 0.24974510267124056, "steering_wheel_angle": 0.07213889718196956, "front_wheel_angle": 0.0033160593973950284, "heading_rate": 0.0027367651051521187, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137659.987556} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29185494300075127, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9538187741660752, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.119227345237978, "gear": 1, "accelerator_pedal_position": 0.28772146911877877, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.11310041171614209, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137659.987556} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.74999737739563, "x": 3.307891293370223, "y": -0.08870830102808647, "z": null, "yaw": 6.253632008326356, "pitch": null, "roll": null}, "v": 2.11277668739298, "accelerator_pedal_position": 0.29600355045580834, "brake_pedal_position": 0.0, "acceleration": 0.24974510267124056, "steering_wheel_angle": 0.07213889718196956, "front_wheel_angle": 0.0033160593973950284, "heading_rate": 0.0027367651051521187, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137660.007556} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29185494300075127, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9538187741660752, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.123689698146326, "gear": 1, "accelerator_pedal_position": 0.29185494300075127, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.11310041171614209, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137660.007556} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.74999737739563, "x": 3.307891293370223, "y": -0.08870830102808647, "z": null, "yaw": 6.253632008326356, "pitch": null, "roll": null}, "v": 2.11277668739298, "accelerator_pedal_position": 0.29600355045580834, "brake_pedal_position": 0.0, "acceleration": 0.24974510267124056, "steering_wheel_angle": 0.07213889718196956, "front_wheel_angle": 0.0033160593973950284, "heading_rate": 0.0027367651051521187, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137660.027556} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29185494300075127, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9538187741660752, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1281438038468794, "gear": 1, "accelerator_pedal_position": 0.29185494300075127, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.11310041171614209, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137660.027556} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.74999737739563, "x": 3.307891293370223, "y": -0.08870830102808647, "z": null, "yaw": 6.253632008326356, "pitch": null, "roll": null}, "v": 2.11277668739298, "accelerator_pedal_position": 0.29600355045580834, "brake_pedal_position": 0.0, "acceleration": 0.24974510267124056, "steering_wheel_angle": 0.07213889718196956, "front_wheel_angle": 0.0033160593973950284, "heading_rate": 0.0027367651051521187, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137660.047556} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29185494300075127, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9538187741660752, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1325896696499664, "gear": 1, "accelerator_pedal_position": 0.29185494300075127, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.11310041171614209, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137660.047556} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137660.067556, "x": 7.541404971040643, "y": 4.904409407888491, "z": null, "yaw": -0.029344515787988915, "pitch": null, "roll": null}, "v": 2.137027302896401, "accelerator_pedal_position": 0.29185494300075127, "brake_pedal_position": 0.0, "acceleration": 0.22157317167662866, "steering_wheel_angle": 0.11310041171614209, "front_wheel_angle": 0.005201766593203637, "heading_rate": 0.004342350584850947, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137660.067556} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28026856401820777, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9192957306672436, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.137027302896401, "gear": 1, "accelerator_pedal_position": 0.29185494300075127, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.11310041171614209, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137660.067556} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.859997272491455, "x": 3.5414049710406426, "y": -0.09559059211150878, "z": null, "yaw": 6.253840791391597, "pitch": null, "roll": null}, "v": 2.137027302896401, "accelerator_pedal_position": 0.29185494300075127, "brake_pedal_position": 0.0, "acceleration": 0.22157317167662866, "steering_wheel_angle": 0.11310041171614209, "front_wheel_angle": 0.005201766593203637, "heading_rate": 0.004342350584850947, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137660.087556} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2859567956628824, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9192957306672436, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1400090854323865, "gear": 1, "accelerator_pedal_position": 0.28026856401820777, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.11310041171614209, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137660.087556} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.859997272491455, "x": 3.5414049710406426, "y": -0.09559059211150878, "z": null, "yaw": 6.253840791391597, "pitch": null, "roll": null}, "v": 2.137027302896401, "accelerator_pedal_position": 0.29185494300075127, "brake_pedal_position": 0.0, "acceleration": 0.22157317167662866, "steering_wheel_angle": 0.11310041171614209, "front_wheel_angle": 0.005201766593203637, "heading_rate": 0.004342350584850947, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137660.1075559} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2859567956628824, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9192957306672436, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1436960361447164, "gear": 1, "accelerator_pedal_position": 0.2859567956628824, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.11310041171614209, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137660.1075559} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.859997272491455, "x": 3.5414049710406426, "y": -0.09559059211150878, "z": null, "yaw": 6.253840791391597, "pitch": null, "roll": null}, "v": 2.137027302896401, "accelerator_pedal_position": 0.29185494300075127, "brake_pedal_position": 0.0, "acceleration": 0.22157317167662866, "steering_wheel_angle": 0.11310041171614209, "front_wheel_angle": 0.005201766593203637, "heading_rate": 0.004342350584850947, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137660.1275558} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2859567956628824, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9192957306672436, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1473761429646148, "gear": 1, "accelerator_pedal_position": 0.2859567956628824, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.11310041171614209, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137660.1275558} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.859997272491455, "x": 3.5414049710406426, "y": -0.09559059211150878, "z": null, "yaw": 6.253840791391597, "pitch": null, "roll": null}, "v": 2.137027302896401, "accelerator_pedal_position": 0.29185494300075127, "brake_pedal_position": 0.0, "acceleration": 0.22157317167662866, "steering_wheel_angle": 0.11310041171614209, "front_wheel_angle": 0.005201766593203637, "heading_rate": 0.004342350584850947, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137660.1475558} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2859567956628824, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9192957306672436, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1510494131812794, "gear": 1, "accelerator_pedal_position": 0.2859567956628824, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.11310041171614209, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137660.1475558} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.859997272491455, "x": 3.5414049710406426, "y": -0.09559059211150878, "z": null, "yaw": 6.253840791391597, "pitch": null, "roll": null}, "v": 2.137027302896401, "accelerator_pedal_position": 0.29185494300075127, "brake_pedal_position": 0.0, "acceleration": 0.22157317167662866, "steering_wheel_angle": 0.11310041171614209, "front_wheel_angle": 0.005201766593203637, "heading_rate": 0.004342350584850947, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137660.1675558} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2859567956628824, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9192957306672436, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1547158541005382, "gear": 1, "accelerator_pedal_position": 0.2859567956628824, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.11310041171614209, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137660.1675558} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137660.1775558, "x": 7.7773228653955755, "y": 4.897508553204753, "z": null, "yaw": -0.029121000363695446, "pitch": null, "roll": null}, "v": 2.1565465158612267, "accelerator_pedal_position": 0.2859567956628824, "brake_pedal_position": 0.0, "acceleration": 0.1828957183492217, "steering_wheel_angle": 0.11310041171614209, "front_wheel_angle": 0.005201766593203637, "heading_rate": 0.004382012813648288, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137660.1875558} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2803084539860887, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9547672536797631, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.158375473044719, "gear": 1, "accelerator_pedal_position": 0.2859567956628824, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.11310041171614209, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137660.1875558} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.9699971675872803, "x": 3.7773228653955755, "y": -0.10249144679524669, "z": null, "yaw": 6.2540643068158905, "pitch": null, "roll": null}, "v": 2.1565465158612267, "accelerator_pedal_position": 0.2859567956628824, "brake_pedal_position": 0.0, "acceleration": 0.1828957183492217, "steering_wheel_angle": 0.11310041171614209, "front_wheel_angle": 0.005201766593203637, "heading_rate": 0.004382012813648288, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137660.2075558} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2831363539088959, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9547672536797631, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.161322563660675, "gear": 1, "accelerator_pedal_position": 0.2803084539860887, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.11310041171614209, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137660.2075558} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.9699971675872803, "x": 3.7773228653955755, "y": -0.10249144679524669, "z": null, "yaw": 6.2540643068158905, "pitch": null, "roll": null}, "v": 2.1565465158612267, "accelerator_pedal_position": 0.2859567956628824, "brake_pedal_position": 0.0, "acceleration": 0.1828957183492217, "steering_wheel_angle": 0.11310041171614209, "front_wheel_angle": 0.005201766593203637, "heading_rate": 0.004382012813648288, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137660.2275558} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2831363539088959, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9547672536797631, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1646174854334235, "gear": 1, "accelerator_pedal_position": 0.2831363539088959, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.11310041171614209, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137660.2275558} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.9699971675872803, "x": 3.7773228653955755, "y": -0.10249144679524669, "z": null, "yaw": 6.2540643068158905, "pitch": null, "roll": null}, "v": 2.1565465158612267, "accelerator_pedal_position": 0.2859567956628824, "brake_pedal_position": 0.0, "acceleration": 0.1828957183492217, "steering_wheel_angle": 0.11310041171614209, "front_wheel_angle": 0.005201766593203637, "heading_rate": 0.004382012813648288, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137660.2475557} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2831363539088959, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9547672536797631, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1679062633391526, "gear": 1, "accelerator_pedal_position": 0.2831363539088959, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.11310041171614209, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137660.2475557} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.9699971675872803, "x": 3.7773228653955755, "y": -0.10249144679524669, "z": null, "yaw": 6.2540643068158905, "pitch": null, "roll": null}, "v": 2.1565465158612267, "accelerator_pedal_position": 0.2859567956628824, "brake_pedal_position": 0.0, "acceleration": 0.1828957183492217, "steering_wheel_angle": 0.11310041171614209, "front_wheel_angle": 0.005201766593203637, "heading_rate": 0.004382012813648288, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137660.2675557} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2831363539088959, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9547672536797631, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1711889045096013, "gear": 1, "accelerator_pedal_position": 0.2831363539088959, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.11310041171614209, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137660.2675557} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137660.2875557, "x": 8.01533677818498, "y": 4.890599628396863, "z": null, "yaw": -0.028897484939401977, "pitch": null, "roll": null}, "v": 2.174465416087404, "accelerator_pedal_position": 0.2831363539088959, "brake_pedal_position": 0.0, "acceleration": 0.16359594266862754, "steering_wheel_angle": 0.11310041171614209, "front_wheel_angle": 0.005201766593203637, "heading_rate": 0.004418423273529436, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137660.2875557} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2779689015920294, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9937401757318417, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.174465416087404, "gear": 1, "accelerator_pedal_position": 0.2831363539088959, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.11310041171614209, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137660.2875557} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.0799970626831055, "x": 4.015336778184979, "y": -0.10940037160313665, "z": null, "yaw": 6.254287822240184, "pitch": null, "roll": null}, "v": 2.174465416087404, "accelerator_pedal_position": 0.2831363539088959, "brake_pedal_position": 0.0, "acceleration": 0.16359594266862754, "steering_wheel_angle": 0.11310041171614209, "front_wheel_angle": 0.005201766593203637, "heading_rate": 0.004418423273529436, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137660.3075557} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2805569860619264, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9937401757318417, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.177090175720085, "gear": 1, "accelerator_pedal_position": 0.2779689015920294, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.15406290074251494, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137660.3075557} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.0799970626831055, "x": 4.015336778184979, "y": -0.10940037160313665, "z": null, "yaw": 6.254287822240184, "pitch": null, "roll": null}, "v": 2.174465416087404, "accelerator_pedal_position": 0.2831363539088959, "brake_pedal_position": 0.0, "acceleration": 0.16359594266862754, "steering_wheel_angle": 0.11310041171614209, "front_wheel_angle": 0.005201766593203637, "heading_rate": 0.004418423273529436, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137660.3275557} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2805569860619264, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9937401757318417, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1800333870479833, "gear": 1, "accelerator_pedal_position": 0.2805569860619264, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.15406290074251494, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137660.3275557} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.0799970626831055, "x": 4.015336778184979, "y": -0.10940037160313665, "z": null, "yaw": 6.254287822240184, "pitch": null, "roll": null}, "v": 2.174465416087404, "accelerator_pedal_position": 0.2831363539088959, "brake_pedal_position": 0.0, "acceleration": 0.16359594266862754, "steering_wheel_angle": 0.11310041171614209, "front_wheel_angle": 0.005201766593203637, "heading_rate": 0.004418423273529436, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137660.3475556} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2805569860619264, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9937401757318417, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1829710920893857, "gear": 1, "accelerator_pedal_position": 0.2805569860619264, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.15406290074251494, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137660.3475556} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.0799970626831055, "x": 4.015336778184979, "y": -0.10940037160313665, "z": null, "yaw": 6.254287822240184, "pitch": null, "roll": null}, "v": 2.174465416087404, "accelerator_pedal_position": 0.2831363539088959, "brake_pedal_position": 0.0, "acceleration": 0.16359594266862754, "steering_wheel_angle": 0.11310041171614209, "front_wheel_angle": 0.005201766593203637, "heading_rate": 0.004418423273529436, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137660.3675556} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2805569860619264, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9937401757318417, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.18590329769526, "gear": 1, "accelerator_pedal_position": 0.2805569860619264, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.15406290074251494, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137660.3675556} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.0799970626831055, "x": 4.015336778184979, "y": -0.10940037160313665, "z": null, "yaw": 6.254287822240184, "pitch": null, "roll": null}, "v": 2.174465416087404, "accelerator_pedal_position": 0.2831363539088959, "brake_pedal_position": 0.0, "acceleration": 0.16359594266862754, "steering_wheel_angle": 0.11310041171614209, "front_wheel_angle": 0.005201766593203637, "heading_rate": 0.004418423273529436, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137660.3875556} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2805569860619264, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9937401757318417, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1888300107231253, "gear": 1, "accelerator_pedal_position": 0.2805569860619264, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.15406290074251494, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137660.3875556} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137660.3975556, "x": 8.255206926136404, "y": 4.883697730975869, "z": null, "yaw": -0.028600224955887373, "pitch": null, "roll": null}, "v": 2.19029130966505, "accelerator_pedal_position": 0.2805569860619264, "brake_pedal_position": 0.0, "acceleration": 0.14599283719184514, "steering_wheel_angle": 0.15406290074251494, "front_wheel_angle": 0.007089555446572156, "heading_rate": 0.006065801502935864, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137660.4075556} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2760525794231955, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.036234468172559, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1917512380369684, "gear": 1, "accelerator_pedal_position": 0.2805569860619264, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.15406290074251494, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137660.4075556} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.1899969577789307, "x": 4.255206926136404, "y": -0.1163022690241311, "z": null, "yaw": 6.254585082223699, "pitch": null, "roll": null}, "v": 2.19029130966505, "accelerator_pedal_position": 0.2805569860619264, "brake_pedal_position": 0.0, "acceleration": 0.14599283719184514, "steering_wheel_angle": 0.15406290074251494, "front_wheel_angle": 0.007089555446572156, "heading_rate": 0.006065801502935864, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137660.4275556} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27831045467874405, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.036234468172559, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.194104199920965, "gear": 1, "accelerator_pedal_position": 0.2760525794231955, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1950292886775053, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137660.4275556} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.1899969577789307, "x": 4.255206926136404, "y": -0.1163022690241311, "z": null, "yaw": 6.254585082223699, "pitch": null, "roll": null}, "v": 2.19029130966505, "accelerator_pedal_position": 0.2805569860619264, "brake_pedal_position": 0.0, "acceleration": 0.14599283719184514, "steering_wheel_angle": 0.15406290074251494, "front_wheel_angle": 0.007089555446572156, "heading_rate": 0.006065801502935864, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137660.4475555} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27831045467874405, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.036234468172559, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1967348483009266, "gear": 1, "accelerator_pedal_position": 0.27831045467874405, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1950292886775053, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137660.4475555} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.1899969577789307, "x": 4.255206926136404, "y": -0.1163022690241311, "z": null, "yaw": 6.254585082223699, "pitch": null, "roll": null}, "v": 2.19029130966505, "accelerator_pedal_position": 0.2805569860619264, "brake_pedal_position": 0.0, "acceleration": 0.14599283719184514, "steering_wheel_angle": 0.15406290074251494, "front_wheel_angle": 0.007089555446572156, "heading_rate": 0.006065801502935864, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137660.4675555} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27831045467874405, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.036234468172559, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2006715619631114, "gear": 1, "accelerator_pedal_position": 0.27831045467874405, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1950292886775053, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137660.4675555} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.1899969577789307, "x": 4.255206926136404, "y": -0.1163022690241311, "z": null, "yaw": 6.254585082223699, "pitch": null, "roll": null}, "v": 2.19029130966505, "accelerator_pedal_position": 0.2805569860619264, "brake_pedal_position": 0.0, "acceleration": 0.14599283719184514, "steering_wheel_angle": 0.15406290074251494, "front_wheel_angle": 0.007089555446572156, "heading_rate": 0.006065801502935864, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137660.4875555} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27831045467874405, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.036234468172559, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.201981334067188, "gear": 1, "accelerator_pedal_position": 0.27831045467874405, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1950292886775053, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137660.4875555} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137660.5075555, "x": 8.496755040191557, "y": 4.876826880819593, "z": null, "yaw": -0.02822914046348022, "pitch": null, "roll": null}, "v": 2.204597184490952, "accelerator_pedal_position": 0.27831045467874405, "brake_pedal_position": 0.0, "acceleration": 0.13060799505894827, "steering_wheel_angle": 0.1950292886775053, "front_wheel_angle": 0.008979567710415873, "heading_rate": 0.0077331491352503326, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137660.5075555} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2724028673822599, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0310393006002319, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.204597184490952, "gear": 1, "accelerator_pedal_position": 0.27831045467874405, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1950292886775053, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137660.5075555} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.299996852874756, "x": 4.496755040191557, "y": -0.1231731191804073, "z": null, "yaw": 6.254956166716106, "pitch": null, "roll": null}, "v": 2.204597184490952, "accelerator_pedal_position": 0.27831045467874405, "brake_pedal_position": 0.0, "acceleration": 0.13060799505894827, "steering_wheel_angle": 0.1950292886775053, "front_wheel_angle": 0.008979567710415873, "heading_rate": 0.0077331491352503326, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137660.5275555} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2753184072456353, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0310393006002319, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.206470014386521, "gear": 1, "accelerator_pedal_position": 0.2724028673822599, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1950292886775053, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137660.5275555} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.299996852874756, "x": 4.496755040191557, "y": -0.1231731191804073, "z": null, "yaw": 6.254956166716106, "pitch": null, "roll": null}, "v": 2.204597184490952, "accelerator_pedal_position": 0.27831045467874405, "brake_pedal_position": 0.0, "acceleration": 0.13060799505894827, "steering_wheel_angle": 0.1950292886775053, "front_wheel_angle": 0.008979567710415873, "heading_rate": 0.0077331491352503326, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137660.5475554} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2753184072456353, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0310393006002319, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.208703591446728, "gear": 1, "accelerator_pedal_position": 0.2753184072456353, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1950292886775053, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137660.5475554} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.299996852874756, "x": 4.496755040191557, "y": -0.1231731191804073, "z": null, "yaw": 6.254956166716106, "pitch": null, "roll": null}, "v": 2.204597184490952, "accelerator_pedal_position": 0.27831045467874405, "brake_pedal_position": 0.0, "acceleration": 0.13060799505894827, "steering_wheel_angle": 0.1950292886775053, "front_wheel_angle": 0.008979567710415873, "heading_rate": 0.0077331491352503326, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137660.5675554} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2753184072456353, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0310393006002319, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2109329640855613, "gear": 1, "accelerator_pedal_position": 0.2753184072456353, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1950292886775053, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137660.5675554} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.299996852874756, "x": 4.496755040191557, "y": -0.1231731191804073, "z": null, "yaw": 6.254956166716106, "pitch": null, "roll": null}, "v": 2.204597184490952, "accelerator_pedal_position": 0.27831045467874405, "brake_pedal_position": 0.0, "acceleration": 0.13060799505894827, "steering_wheel_angle": 0.1950292886775053, "front_wheel_angle": 0.008979567710415873, "heading_rate": 0.0077331491352503326, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137660.5875554} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2753184072456353, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0310393006002319, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.213158138230198, "gear": 1, "accelerator_pedal_position": 0.2753184072456353, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1950292886775053, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137660.5875554} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.299996852874756, "x": 4.496755040191557, "y": -0.1231731191804073, "z": null, "yaw": 6.254956166716106, "pitch": null, "roll": null}, "v": 2.204597184490952, "accelerator_pedal_position": 0.27831045467874405, "brake_pedal_position": 0.0, "acceleration": 0.13060799505894827, "steering_wheel_angle": 0.1950292886775053, "front_wheel_angle": 0.008979567710415873, "heading_rate": 0.0077331491352503326, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137660.6075554} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2753184072456353, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0310393006002319, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2153791198078774, "gear": 1, "accelerator_pedal_position": 0.2753184072456353, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1950292886775053, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137660.6075554} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137660.6175554, "x": 8.7397443547549, "y": 4.870008371743345, "z": null, "yaw": -0.02784328929263519, "pitch": null, "roll": null}, "v": 2.2164880402363774, "accelerator_pedal_position": 0.2753184072456353, "brake_pedal_position": 0.0, "acceleration": 0.11078745094829257, "steering_wheel_angle": 0.1950292886775053, "front_wheel_angle": 0.008979567710415873, "heading_rate": 0.007774859140811442, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137660.6275554} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2710746228402862, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0519421989846518, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.21759591474586, "gear": 1, "accelerator_pedal_position": 0.2753184072456353, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1950292886775053, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137660.6275554} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.409996747970581, "x": 4.739744354754899, "y": -0.1299916282566551, "z": null, "yaw": 6.255342017886951, "pitch": null, "roll": null}, "v": 2.2164880402363774, "accelerator_pedal_position": 0.2753184072456353, "brake_pedal_position": 0.0, "acceleration": 0.11078745094829257, "steering_wheel_angle": 0.1950292886775053, "front_wheel_angle": 0.008979567710415873, "heading_rate": 0.007774859140811442, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137660.6475554} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27318082581144815, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0519421989846518, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.219278306228146, "gear": 1, "accelerator_pedal_position": 0.2710746228402862, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2359691326973456, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137660.6475554} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.409996747970581, "x": 4.739744354754899, "y": -0.1299916282566551, "z": null, "yaw": 6.255342017886951, "pitch": null, "roll": null}, "v": 2.2164880402363774, "accelerator_pedal_position": 0.2753184072456353, "brake_pedal_position": 0.0, "acceleration": 0.11078745094829257, "steering_wheel_angle": 0.1950292886775053, "front_wheel_angle": 0.008979567710415873, "heading_rate": 0.007774859140811442, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137660.6675553} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27318082581144815, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0519421989846518, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.221220674723246, "gear": 1, "accelerator_pedal_position": 0.27318082581144815, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2359691326973456, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137660.6675553} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.409996747970581, "x": 4.739744354754899, "y": -0.1299916282566551, "z": null, "yaw": 6.255342017886951, "pitch": null, "roll": null}, "v": 2.2164880402363774, "accelerator_pedal_position": 0.2753184072456353, "brake_pedal_position": 0.0, "acceleration": 0.11078745094829257, "steering_wheel_angle": 0.1950292886775053, "front_wheel_angle": 0.008979567710415873, "heading_rate": 0.007774859140811442, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137660.6875553} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27318082581144815, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0519421989846518, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.223159377187138, "gear": 1, "accelerator_pedal_position": 0.27318082581144815, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2359691326973456, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137660.6875553} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.409996747970581, "x": 4.739744354754899, "y": -0.1299916282566551, "z": null, "yaw": 6.255342017886951, "pitch": null, "roll": null}, "v": 2.2164880402363774, "accelerator_pedal_position": 0.2753184072456353, "brake_pedal_position": 0.0, "acceleration": 0.11078745094829257, "steering_wheel_angle": 0.1950292886775053, "front_wheel_angle": 0.008979567710415873, "heading_rate": 0.007774859140811442, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137660.7075553} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27318082581144815, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0519421989846518, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.225094419036381, "gear": 1, "accelerator_pedal_position": 0.27318082581144815, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2359691326973456, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137660.7075553} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137660.7275553, "x": 8.98399002679426, "y": 4.863254834044731, "z": null, "yaw": -0.02739095684596402, "pitch": null, "roll": null}, "v": 2.2270258056858183, "accelerator_pedal_position": 0.27318082581144815, "brake_pedal_position": 0.0, "acceleration": 0.09643243164535426, "steering_wheel_angle": 0.2359691326973456, "front_wheel_angle": 0.010870403833980686, "heading_rate": 0.00945688415867771, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137660.7275553} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26924678561547744, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0540258518136767, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2270258056858183, "gear": 1, "accelerator_pedal_position": 0.27318082581144815, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2359691326973456, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137660.7275553} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.5199966430664062, "x": 4.98399002679426, "y": -0.13674516595526942, "z": null, "yaw": 6.255794350333622, "pitch": null, "roll": null}, "v": 2.2270258056858183, "accelerator_pedal_position": 0.27318082581144815, "brake_pedal_position": 0.0, "acceleration": 0.09643243164535426, "steering_wheel_angle": 0.2359691326973456, "front_wheel_angle": 0.010870403833980686, "heading_rate": 0.00945688415867771, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137660.7475553} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2711959588988193, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0540258518136767, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2284620200192955, "gear": 1, "accelerator_pedal_position": 0.26924678561547744, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2359691326973456, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137660.7475553} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.5199966430664062, "x": 4.98399002679426, "y": -0.13674516595526942, "z": null, "yaw": 6.255794350333622, "pitch": null, "roll": null}, "v": 2.2270258056858183, "accelerator_pedal_position": 0.27318082581144815, "brake_pedal_position": 0.0, "acceleration": 0.09643243164535426, "steering_wheel_angle": 0.2359691326973456, "front_wheel_angle": 0.010870403833980686, "heading_rate": 0.00945688415867771, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137660.7675552} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2711959588988193, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0540258518136767, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2301390508434946, "gear": 1, "accelerator_pedal_position": 0.2711959588988193, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2359691326973456, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137660.7675552} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.5199966430664062, "x": 4.98399002679426, "y": -0.13674516595526942, "z": null, "yaw": 6.255794350333622, "pitch": null, "roll": null}, "v": 2.2270258056858183, "accelerator_pedal_position": 0.27318082581144815, "brake_pedal_position": 0.0, "acceleration": 0.09643243164535426, "steering_wheel_angle": 0.2359691326973456, "front_wheel_angle": 0.010870403833980686, "heading_rate": 0.00945688415867771, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137660.7875552} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2711959588988193, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0540258518136767, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.231812910414097, "gear": 1, "accelerator_pedal_position": 0.2711959588988193, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2359691326973456, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137660.7875552} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.5199966430664062, "x": 4.98399002679426, "y": -0.13674516595526942, "z": null, "yaw": 6.255794350333622, "pitch": null, "roll": null}, "v": 2.2270258056858183, "accelerator_pedal_position": 0.27318082581144815, "brake_pedal_position": 0.0, "acceleration": 0.09643243164535426, "steering_wheel_angle": 0.2359691326973456, "front_wheel_angle": 0.010870403833980686, "heading_rate": 0.00945688415867771, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137660.8075552} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2711959588988193, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0540258518136767, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2334836036077292, "gear": 1, "accelerator_pedal_position": 0.2711959588988193, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2359691326973456, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137660.8075552} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.5199966430664062, "x": 4.98399002679426, "y": -0.13674516595526942, "z": null, "yaw": 6.255794350333622, "pitch": null, "roll": null}, "v": 2.2270258056858183, "accelerator_pedal_position": 0.27318082581144815, "brake_pedal_position": 0.0, "acceleration": 0.09643243164535426, "steering_wheel_angle": 0.2359691326973456, "front_wheel_angle": 0.010870403833980686, "heading_rate": 0.00945688415867771, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137660.8275552} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2711959588988193, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0540258518136767, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2351511352981484, "gear": 1, "accelerator_pedal_position": 0.2711959588988193, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2359691326973456, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137660.8275552} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137660.8375552, "x": 9.229310016499634, "y": 4.856585767557714, "z": null, "yaw": -0.026923850782442593, "pitch": null, "roll": null}, "v": 2.235983717101913, "accelerator_pedal_position": 0.2711959588988193, "brake_pedal_position": 0.0, "acceleration": 0.08317932543107609, "steering_wheel_angle": 0.2359691326973456, "front_wheel_angle": 0.010870403833980686, "heading_rate": 0.009494923201759035, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137660.8475552} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2673432271293103, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0430263214050448, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.236815510356224, "gear": 1, "accelerator_pedal_position": 0.2711959588988193, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2359691326973456, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137660.8475552} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.6299965381622314, "x": 5.229310016499634, "y": -0.1434142324422858, "z": null, "yaw": 6.2562614563971435, "pitch": null, "roll": null}, "v": 2.235983717101913, "accelerator_pedal_position": 0.2711959588988193, "brake_pedal_position": 0.0, "acceleration": 0.08317932543107609, "steering_wheel_angle": 0.2359691326973456, "front_wheel_angle": 0.010870403833980686, "heading_rate": 0.009494923201759035, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137660.8675551} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2692424480071801, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0430263214050448, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2379953703339464, "gear": 1, "accelerator_pedal_position": 0.2673432271293103, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2359691326973456, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137660.8675551} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.6299965381622314, "x": 5.229310016499634, "y": -0.1434142324422858, "z": null, "yaw": 6.2562614563971435, "pitch": null, "roll": null}, "v": 2.235983717101913, "accelerator_pedal_position": 0.2711959588988193, "brake_pedal_position": 0.0, "acceleration": 0.08317932543107609, "steering_wheel_angle": 0.2359691326973456, "front_wheel_angle": 0.010870403833980686, "heading_rate": 0.009494923201759035, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137660.8875551} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2692424480071801, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0430263214050448, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.239410285554906, "gear": 1, "accelerator_pedal_position": 0.2692424480071801, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2359691326973456, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137660.8875551} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.6299965381622314, "x": 5.229310016499634, "y": -0.1434142324422858, "z": null, "yaw": 6.2562614563971435, "pitch": null, "roll": null}, "v": 2.235983717101913, "accelerator_pedal_position": 0.2711959588988193, "brake_pedal_position": 0.0, "acceleration": 0.08317932543107609, "steering_wheel_angle": 0.2359691326973456, "front_wheel_angle": 0.010870403833980686, "heading_rate": 0.009494923201759035, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137660.907555} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2692424480071801, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0430263214050448, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.240822519901742, "gear": 1, "accelerator_pedal_position": 0.2692424480071801, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2359691326973456, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137660.907555} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.6299965381622314, "x": 5.229310016499634, "y": -0.1434142324422858, "z": null, "yaw": 6.2562614563971435, "pitch": null, "roll": null}, "v": 2.235983717101913, "accelerator_pedal_position": 0.2711959588988193, "brake_pedal_position": 0.0, "acceleration": 0.08317932543107609, "steering_wheel_angle": 0.2359691326973456, "front_wheel_angle": 0.010870403833980686, "heading_rate": 0.009494923201759035, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137660.927555} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2692424480071801, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0430263214050448, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2422320776565874, "gear": 1, "accelerator_pedal_position": 0.2692424480071801, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2359691326973456, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137660.927555} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137660.947555, "x": 9.475561623925422, "y": 4.8500064777524745, "z": null, "yaw": -0.026456744718921166, "pitch": null, "roll": null}, "v": 2.2436389630979923, "accelerator_pedal_position": 0.2692424480071801, "brake_pedal_position": 0.0, "acceleration": 0.07024419392266162, "steering_wheel_angle": 0.2359691326973456, "front_wheel_angle": 0.010870403833980686, "heading_rate": 0.009527430581963734, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137660.947555} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2643747221203678, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0043126801600126, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2436389630979923, "gear": 1, "accelerator_pedal_position": 0.2692424480071801, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2359691326973456, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137660.947555} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.7399964332580566, "x": 5.475561623925422, "y": -0.1499935222475255, "z": null, "yaw": 6.256728562460665, "pitch": null, "roll": null}, "v": 2.2436389630979923, "accelerator_pedal_position": 0.2692424480071801, "brake_pedal_position": 0.0, "acceleration": 0.07024419392266162, "steering_wheel_angle": 0.2359691326973456, "front_wheel_angle": 0.010870403833980686, "heading_rate": 0.009527430581963734, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137660.967555} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26674797856139854, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0043126801600126, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2444350034327236, "gear": 1, "accelerator_pedal_position": 0.2643747221203678, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2359691326973456, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137660.967555} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.7399964332580566, "x": 5.475561623925422, "y": -0.1499935222475255, "z": null, "yaw": 6.256728562460665, "pitch": null, "roll": null}, "v": 2.2436389630979923, "accelerator_pedal_position": 0.2692424480071801, "brake_pedal_position": 0.0, "acceleration": 0.07024419392266162, "steering_wheel_angle": 0.2359691326973456, "front_wheel_angle": 0.010870403833980686, "heading_rate": 0.009527430581963734, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137660.987555} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26674797856139854, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0043126801600126, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2455260501370122, "gear": 1, "accelerator_pedal_position": 0.26674797856139854, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2359691326973456, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137660.987555} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.7399964332580566, "x": 5.475561623925422, "y": -0.1499935222475255, "z": null, "yaw": 6.256728562460665, "pitch": null, "roll": null}, "v": 2.2436389630979923, "accelerator_pedal_position": 0.2692424480071801, "brake_pedal_position": 0.0, "acceleration": 0.07024419392266162, "steering_wheel_angle": 0.2359691326973456, "front_wheel_angle": 0.010870403833980686, "heading_rate": 0.009527430581963734, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137661.007555} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26674797856139854, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0043126801600126, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.246615026906875, "gear": 1, "accelerator_pedal_position": 0.26674797856139854, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2359691326973456, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137661.007555} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.7399964332580566, "x": 5.475561623925422, "y": -0.1499935222475255, "z": null, "yaw": 6.256728562460665, "pitch": null, "roll": null}, "v": 2.2436389630979923, "accelerator_pedal_position": 0.2692424480071801, "brake_pedal_position": 0.0, "acceleration": 0.07024419392266162, "steering_wheel_angle": 0.2359691326973456, "front_wheel_angle": 0.010870403833980686, "heading_rate": 0.009527430581963734, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137661.027555} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26674797856139854, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0043126801600126, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.24770193719527, "gear": 1, "accelerator_pedal_position": 0.26674797856139854, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2359691326973456, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137661.027555} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.7399964332580566, "x": 5.475561623925422, "y": -0.1499935222475255, "z": null, "yaw": 6.256728562460665, "pitch": null, "roll": null}, "v": 2.2436389630979923, "accelerator_pedal_position": 0.2692424480071801, "brake_pedal_position": 0.0, "acceleration": 0.07024419392266162, "steering_wheel_angle": 0.2359691326973456, "front_wheel_angle": 0.010870403833980686, "heading_rate": 0.009527430581963734, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137661.047555} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26674797856139854, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0043126801600126, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2487867844513008, "gear": 1, "accelerator_pedal_position": 0.26674797856139854, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2359691326973456, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137661.047555} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137661.057555, "x": 9.722548498165324, "y": 4.843522985497032, "z": null, "yaw": -0.02598963865539974, "pitch": null, "roll": null}, "v": 2.2493284355189704, "accelerator_pedal_position": 0.26674797856139854, "brake_pedal_position": 0.0, "acceleration": 0.05411366012445007, "steering_wheel_angle": 0.2359691326973456, "front_wheel_angle": 0.010870403833980686, "heading_rate": 0.009551590464382614, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137661.067555} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26604214004534954, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.042294120370222, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.249869572120215, "gear": 1, "accelerator_pedal_position": 0.26674797856139854, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2359691326973456, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137661.067555} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.849996328353882, "x": 5.722548498165324, "y": -0.15647701450296836, "z": null, "yaw": 6.2571956685241865, "pitch": null, "roll": null}, "v": 2.2493284355189704, "accelerator_pedal_position": 0.26674797856139854, "brake_pedal_position": 0.0, "acceleration": 0.05411366012445007, "steering_wheel_angle": 0.2359691326973456, "front_wheel_angle": 0.010870403833980686, "heading_rate": 0.009551590464382614, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137661.087555} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26641940427094346, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.042294120370222, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2508621157414783, "gear": 1, "accelerator_pedal_position": 0.26604214004534954, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2359691326973456, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137661.087555} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.849996328353882, "x": 5.722548498165324, "y": -0.15647701450296836, "z": null, "yaw": 6.2571956685241865, "pitch": null, "roll": null}, "v": 2.2493284355189704, "accelerator_pedal_position": 0.26674797856139854, "brake_pedal_position": 0.0, "acceleration": 0.05411366012445007, "steering_wheel_angle": 0.2359691326973456, "front_wheel_angle": 0.010870403833980686, "heading_rate": 0.009551590464382614, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137661.107555} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26641940427094346, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.042294120370222, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.251899909803827, "gear": 1, "accelerator_pedal_position": 0.26641940427094346, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2359691326973456, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137661.107555} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.849996328353882, "x": 5.722548498165324, "y": -0.15647701450296836, "z": null, "yaw": 6.2571956685241865, "pitch": null, "roll": null}, "v": 2.2493284355189704, "accelerator_pedal_position": 0.26674797856139854, "brake_pedal_position": 0.0, "acceleration": 0.05411366012445007, "steering_wheel_angle": 0.2359691326973456, "front_wheel_angle": 0.010870403833980686, "heading_rate": 0.009551590464382614, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137661.127555} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26641940427094346, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.042294120370222, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2529357323137797, "gear": 1, "accelerator_pedal_position": 0.26641940427094346, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2359691326973456, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137661.127555} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.849996328353882, "x": 5.722548498165324, "y": -0.15647701450296836, "z": null, "yaw": 6.2571956685241865, "pitch": null, "roll": null}, "v": 2.2493284355189704, "accelerator_pedal_position": 0.26674797856139854, "brake_pedal_position": 0.0, "acceleration": 0.05411366012445007, "steering_wheel_angle": 0.2359691326973456, "front_wheel_angle": 0.010870403833980686, "heading_rate": 0.009551590464382614, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137661.1475549} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26641940427094346, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.042294120370222, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.253969586587832, "gear": 1, "accelerator_pedal_position": 0.26641940427094346, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2359691326973456, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137661.1475549} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137661.1675549, "x": 9.970175897670964, "y": 4.837138425215974, "z": null, "yaw": -0.025522532591878314, "pitch": null, "roll": null}, "v": 2.2550014759386223, "accelerator_pedal_position": 0.26641940427094346, "brake_pedal_position": 0.0, "acceleration": 0.051520886331611726, "steering_wheel_angle": 0.2359691326973456, "front_wheel_angle": 0.010870403833980686, "heading_rate": 0.00957568056964281, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137661.1675549} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26567912179371883, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0839269770510047, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2550014759386223, "gear": 1, "accelerator_pedal_position": 0.26641940427094346, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2359691326973456, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137661.1675549} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.959996223449707, "x": 5.9701758976709645, "y": -0.16286157478402608, "z": null, "yaw": 6.257662774587708, "pitch": null, "roll": null}, "v": 2.2550014759386223, "accelerator_pedal_position": 0.26641940427094346, "brake_pedal_position": 0.0, "acceleration": 0.051520886331611726, "steering_wheel_angle": 0.2359691326973456, "front_wheel_angle": 0.010870403833980686, "heading_rate": 0.00957568056964281, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137661.1875548} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2660727181777773, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0839269770510047, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2559389123703832, "gear": 1, "accelerator_pedal_position": 0.26567912179371883, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2359691326973456, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137661.1875548} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.959996223449707, "x": 5.9701758976709645, "y": -0.16286157478402608, "z": null, "yaw": 6.257662774587708, "pitch": null, "roll": null}, "v": 2.2550014759386223, "accelerator_pedal_position": 0.26641940427094346, "brake_pedal_position": 0.0, "acceleration": 0.051520886331611726, "steering_wheel_angle": 0.2359691326973456, "front_wheel_angle": 0.010870403833980686, "heading_rate": 0.00957568056964281, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137661.2075548} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2660727181777773, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0839269770510047, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.256923742528612, "gear": 1, "accelerator_pedal_position": 0.2660727181777773, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2359691326973456, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137661.2075548} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.959996223449707, "x": 5.9701758976709645, "y": -0.16286157478402608, "z": null, "yaw": 6.257662774587708, "pitch": null, "roll": null}, "v": 2.2550014759386223, "accelerator_pedal_position": 0.26641940427094346, "brake_pedal_position": 0.0, "acceleration": 0.051520886331611726, "steering_wheel_angle": 0.2359691326973456, "front_wheel_angle": 0.010870403833980686, "heading_rate": 0.00957568056964281, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137661.2275548} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2660727181777773, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0839269770510047, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2579066997704014, "gear": 1, "accelerator_pedal_position": 0.2660727181777773, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2359691326973456, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137661.2275548} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.959996223449707, "x": 5.9701758976709645, "y": -0.16286157478402608, "z": null, "yaw": 6.257662774587708, "pitch": null, "roll": null}, "v": 2.2550014759386223, "accelerator_pedal_position": 0.26641940427094346, "brake_pedal_position": 0.0, "acceleration": 0.051520886331611726, "steering_wheel_angle": 0.2359691326973456, "front_wheel_angle": 0.010870403833980686, "heading_rate": 0.00957568056964281, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137661.2475548} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2660727181777773, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0839269770510047, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.258887787271301, "gear": 1, "accelerator_pedal_position": 0.2660727181777773, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2359691326973456, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137661.2475548} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.959996223449707, "x": 5.9701758976709645, "y": -0.16286157478402608, "z": null, "yaw": 6.257662774587708, "pitch": null, "roll": null}, "v": 2.2550014759386223, "accelerator_pedal_position": 0.26641940427094346, "brake_pedal_position": 0.0, "acceleration": 0.051520886331611726, "steering_wheel_angle": 0.2359691326973456, "front_wheel_angle": 0.010870403833980686, "heading_rate": 0.00957568056964281, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137661.2675548} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2660727181777773, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0839269770510047, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2603559196955594, "gear": 1, "accelerator_pedal_position": 0.2660727181777773, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2359691326973456, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137661.2675548} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137661.2775548, "x": 10.21841254541659, "y": 4.830854183968024, "z": null, "yaw": -0.025055426528356888, "pitch": null, "roll": null}, "v": 2.2603559196955594, "accelerator_pedal_position": 0.2660727181777773, "brake_pedal_position": 0.0, "acceleration": 0.04884460378930239, "steering_wheel_angle": 0.2359691326973456, "front_wheel_angle": 0.010870403833980686, "heading_rate": 0.009598417780057808, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137661.2875547} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26290599169952195, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0590350010750813, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2608443657334525, "gear": 1, "accelerator_pedal_position": 0.2660727181777773, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2359691326973456, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137661.2875547} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.069996118545532, "x": 6.218412545416591, "y": -0.16914581603197565, "z": null, "yaw": 6.2581298806512295, "pitch": null, "roll": null}, "v": 2.2603559196955594, "accelerator_pedal_position": 0.2660727181777773, "brake_pedal_position": 0.0, "acceleration": 0.04884460378930239, "steering_wheel_angle": 0.2359691326973456, "front_wheel_angle": 0.010870403833980686, "heading_rate": 0.009598417780057808, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137661.3075547} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2644527760873791, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0590350010750813, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2614242106858824, "gear": 1, "accelerator_pedal_position": 0.26290599169952195, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2359691326973456, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137661.3075547} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.069996118545532, "x": 6.218412545416591, "y": -0.16914581603197565, "z": null, "yaw": 6.2581298806512295, "pitch": null, "roll": null}, "v": 2.2603559196955594, "accelerator_pedal_position": 0.2660727181777773, "brake_pedal_position": 0.0, "acceleration": 0.04884460378930239, "steering_wheel_angle": 0.2359691326973456, "front_wheel_angle": 0.010870403833980686, "heading_rate": 0.009598417780057808, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137661.3275547} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2644527760873791, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0590350010750813, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2621962078233726, "gear": 1, "accelerator_pedal_position": 0.2644527760873791, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2359691326973456, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137661.3275547} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.069996118545532, "x": 6.218412545416591, "y": -0.16914581603197565, "z": null, "yaw": 6.2581298806512295, "pitch": null, "roll": null}, "v": 2.2603559196955594, "accelerator_pedal_position": 0.2660727181777773, "brake_pedal_position": 0.0, "acceleration": 0.04884460378930239, "steering_wheel_angle": 0.2359691326973456, "front_wheel_angle": 0.010870403833980686, "heading_rate": 0.009598417780057808, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137661.3475547} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2644527760873791, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0590350010750813, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.262966735160006, "gear": 1, "accelerator_pedal_position": 0.2644527760873791, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2359691326973456, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137661.3475547} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.069996118545532, "x": 6.218412545416591, "y": -0.16914581603197565, "z": null, "yaw": 6.2581298806512295, "pitch": null, "roll": null}, "v": 2.2603559196955594, "accelerator_pedal_position": 0.2660727181777773, "brake_pedal_position": 0.0, "acceleration": 0.04884460378930239, "steering_wheel_angle": 0.2359691326973456, "front_wheel_angle": 0.010870403833980686, "heading_rate": 0.009598417780057808, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137661.3675547} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2644527760873791, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0590350010750813, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2637357952567556, "gear": 1, "accelerator_pedal_position": 0.2644527760873791, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2359691326973456, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137661.3675547} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137661.3875546, "x": 10.467180965756313, "y": 4.8246727494623425, "z": null, "yaw": -0.024588320464835462, "pitch": null, "roll": null}, "v": 2.264503390671075, "accelerator_pedal_position": 0.2644527760873791, "brake_pedal_position": 0.0, "acceleration": 0.03832492494895756, "steering_wheel_angle": 0.2359691326973456, "front_wheel_angle": 0.010870403833980686, "heading_rate": 0.00961602967861183, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137661.3875546} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26283597448258444, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0763561712728447, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.264503390671075, "gear": 1, "accelerator_pedal_position": 0.2644527760873791, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2359691326973456, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137661.3875546} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.179996013641357, "x": 6.467180965756313, "y": -0.17532725053765752, "z": null, "yaw": 6.258596986714751, "pitch": null, "roll": null}, "v": 2.264503390671075, "accelerator_pedal_position": 0.2644527760873791, "brake_pedal_position": 0.0, "acceleration": 0.03832492494895756, "steering_wheel_angle": 0.2359691326973456, "front_wheel_angle": 0.010870403833980686, "heading_rate": 0.00961602967861183, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137661.4075546} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2636359787531033, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0763561712728447, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2650675200537305, "gear": 1, "accelerator_pedal_position": 0.26283597448258444, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2359691326973456, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137661.4075546} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.179996013641357, "x": 6.467180965756313, "y": -0.17532725053765752, "z": null, "yaw": 6.258596986714751, "pitch": null, "roll": null}, "v": 2.264503390671075, "accelerator_pedal_position": 0.2644527760873791, "brake_pedal_position": 0.0, "acceleration": 0.03832492494895756, "steering_wheel_angle": 0.2359691326973456, "front_wheel_angle": 0.010870403833980686, "heading_rate": 0.00961602967861183, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137661.4275546} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2636359787531033, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0763561712728447, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2657305276145365, "gear": 1, "accelerator_pedal_position": 0.2636359787531033, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2359691326973456, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137661.4275546} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.179996013641357, "x": 6.467180965756313, "y": -0.17532725053765752, "z": null, "yaw": 6.258596986714751, "pitch": null, "roll": null}, "v": 2.264503390671075, "accelerator_pedal_position": 0.2644527760873791, "brake_pedal_position": 0.0, "acceleration": 0.03832492494895756, "steering_wheel_angle": 0.2359691326973456, "front_wheel_angle": 0.010870403833980686, "heading_rate": 0.00961602967861183, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137661.4475546} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2636359787531033, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0763561712728447, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2663922719354646, "gear": 1, "accelerator_pedal_position": 0.2636359787531033, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2359691326973456, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137661.4475546} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.179996013641357, "x": 6.467180965756313, "y": -0.17532725053765752, "z": null, "yaw": 6.258596986714751, "pitch": null, "roll": null}, "v": 2.264503390671075, "accelerator_pedal_position": 0.2644527760873791, "brake_pedal_position": 0.0, "acceleration": 0.03832492494895756, "steering_wheel_angle": 0.2359691326973456, "front_wheel_angle": 0.010870403833980686, "heading_rate": 0.00961602967861183, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137661.4675546} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2636359787531033, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0763561712728447, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2670527552483084, "gear": 1, "accelerator_pedal_position": 0.2636359787531033, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2359691326973456, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137661.4675546} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.179996013641357, "x": 6.467180965756313, "y": -0.17532725053765752, "z": null, "yaw": 6.258596986714751, "pitch": null, "roll": null}, "v": 2.264503390671075, "accelerator_pedal_position": 0.2644527760873791, "brake_pedal_position": 0.0, "acceleration": 0.03832492494895756, "steering_wheel_angle": 0.2359691326973456, "front_wheel_angle": 0.010870403833980686, "heading_rate": 0.00961602967861183, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137661.4875546} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2636359787531033, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0763561712728447, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2677119797816108, "gear": 1, "accelerator_pedal_position": 0.2636359787531033, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2359691326973456, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137661.4875546} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137661.4975545, "x": 10.716375011023906, "y": 4.81859720730345, "z": null, "yaw": -0.024121214401314036, "pitch": null, "roll": null}, "v": 2.2680411207014646, "accelerator_pedal_position": 0.2636359787531033, "brake_pedal_position": 0.0, "acceleration": 0.03288270591989473, "steering_wheel_angle": 0.2359691326973456, "front_wheel_angle": 0.010870403833980686, "heading_rate": 0.009631052361778166, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137661.5075545} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26212780376299344, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.080638861280886, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2683699477606636, "gear": 1, "accelerator_pedal_position": 0.2636359787531033, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2359691326973456, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137661.5075545} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.289995908737183, "x": 6.716375011023906, "y": -0.18140279269654958, "z": null, "yaw": 6.259064092778273, "pitch": null, "roll": null}, "v": 2.2680411207014646, "accelerator_pedal_position": 0.2636359787531033, "brake_pedal_position": 0.0, "acceleration": 0.03288270591989473, "steering_wheel_angle": 0.2359691326973456, "front_wheel_angle": 0.010870403833980686, "heading_rate": 0.009631052361778166, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137661.5275545} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2628716768491068, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.080638861280886, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.268838229433255, "gear": 1, "accelerator_pedal_position": 0.26212780376299344, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2359691326973456, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137661.5275545} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.289995908737183, "x": 6.716375011023906, "y": -0.18140279269654958, "z": null, "yaw": 6.259064092778273, "pitch": null, "roll": null}, "v": 2.2680411207014646, "accelerator_pedal_position": 0.2636359787531033, "brake_pedal_position": 0.0, "acceleration": 0.03288270591989473, "steering_wheel_angle": 0.2359691326973456, "front_wheel_angle": 0.010870403833980686, "heading_rate": 0.009631052361778166, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137661.5475545} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2628716768491068, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.080638861280886, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2693985580806753, "gear": 1, "accelerator_pedal_position": 0.2628716768491068, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2359691326973456, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137661.5475545} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.289995908737183, "x": 6.716375011023906, "y": -0.18140279269654958, "z": null, "yaw": 6.259064092778273, "pitch": null, "roll": null}, "v": 2.2680411207014646, "accelerator_pedal_position": 0.2636359787531033, "brake_pedal_position": 0.0, "acceleration": 0.03288270591989473, "steering_wheel_angle": 0.2359691326973456, "front_wheel_angle": 0.010870403833980686, "heading_rate": 0.009631052361778166, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137661.5675545} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2628716768491068, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.080638861280886, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2699578182970552, "gear": 1, "accelerator_pedal_position": 0.2628716768491068, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2359691326973456, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137661.5675545} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.289995908737183, "x": 6.716375011023906, "y": -0.18140279269654958, "z": null, "yaw": 6.259064092778273, "pitch": null, "roll": null}, "v": 2.2680411207014646, "accelerator_pedal_position": 0.2636359787531033, "brake_pedal_position": 0.0, "acceleration": 0.03288270591989473, "steering_wheel_angle": 0.2359691326973456, "front_wheel_angle": 0.010870403833980686, "heading_rate": 0.009631052361778166, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137661.5875545} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2628716768491068, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.080638861280886, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2705160119946237, "gear": 1, "accelerator_pedal_position": 0.2628716768491068, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2359691326973456, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137661.5875545} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137661.6075544, "x": 10.96593920718159, "y": 4.81262927908424, "z": null, "yaw": -0.02365410833779261, "pitch": null, "roll": null}, "v": 2.271073141082677, "accelerator_pedal_position": 0.2628716768491068, "brake_pedal_position": 0.0, "acceleration": 0.02781659113131213, "steering_wheel_angle": 0.2359691326973456, "front_wheel_angle": 0.010870403833980686, "heading_rate": 0.009643927590003484, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137661.6075544} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26171997109880285, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.088150050627636, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.271073141082677, "gear": 1, "accelerator_pedal_position": 0.2628716768491068, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2359691326973456, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137661.6075544} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.399995803833008, "x": 6.96593920718159, "y": -0.18737072091575957, "z": null, "yaw": 6.259531198841794, "pitch": null, "roll": null}, "v": 2.271073141082677, "accelerator_pedal_position": 0.2628716768491068, "brake_pedal_position": 0.0, "acceleration": 0.02781659113131213, "steering_wheel_angle": 0.2359691326973456, "front_wheel_angle": 0.010870403833980686, "heading_rate": 0.009643927590003484, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137661.6275544} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2622904391040054, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.088150050627636, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.271485312938187, "gear": 1, "accelerator_pedal_position": 0.26171997109880285, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2359691326973456, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137661.6275544} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.399995803833008, "x": 6.96593920718159, "y": -0.18737072091575957, "z": null, "yaw": 6.259531198841794, "pitch": null, "roll": null}, "v": 2.271073141082677, "accelerator_pedal_position": 0.2628716768491068, "brake_pedal_position": 0.0, "acceleration": 0.02781659113131213, "steering_wheel_angle": 0.2359691326973456, "front_wheel_angle": 0.010870403833980686, "heading_rate": 0.009643927590003484, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137661.6475544} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2622904391040054, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.088150050627636, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.271967972991563, "gear": 1, "accelerator_pedal_position": 0.2622904391040054, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2359691326973456, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137661.6475544} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.399995803833008, "x": 6.96593920718159, "y": -0.18737072091575957, "z": null, "yaw": 6.259531198841794, "pitch": null, "roll": null}, "v": 2.271073141082677, "accelerator_pedal_position": 0.2628716768491068, "brake_pedal_position": 0.0, "acceleration": 0.02781659113131213, "steering_wheel_angle": 0.2359691326973456, "front_wheel_angle": 0.010870403833980686, "heading_rate": 0.009643927590003484, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137661.6675544} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2622904391040054, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.088150050627636, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2724497122125364, "gear": 1, "accelerator_pedal_position": 0.2622904391040054, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2359691326973456, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137661.6675544} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.399995803833008, "x": 6.96593920718159, "y": -0.18737072091575957, "z": null, "yaw": 6.259531198841794, "pitch": null, "roll": null}, "v": 2.271073141082677, "accelerator_pedal_position": 0.2628716768491068, "brake_pedal_position": 0.0, "acceleration": 0.02781659113131213, "steering_wheel_angle": 0.2359691326973456, "front_wheel_angle": 0.010870403833980686, "heading_rate": 0.009643927590003484, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137661.6875544} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2622904391040054, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.088150050627636, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.272930532265112, "gear": 1, "accelerator_pedal_position": 0.2622904391040054, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2359691326973456, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137661.6875544} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.399995803833008, "x": 6.96593920718159, "y": -0.18737072091575957, "z": null, "yaw": 6.259531198841794, "pitch": null, "roll": null}, "v": 2.271073141082677, "accelerator_pedal_position": 0.2628716768491068, "brake_pedal_position": 0.0, "acceleration": 0.02781659113131213, "steering_wheel_angle": 0.2359691326973456, "front_wheel_angle": 0.010870403833980686, "heading_rate": 0.009643927590003484, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137661.7075543} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2622904391040054, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.088150050627636, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2734104348106516, "gear": 1, "accelerator_pedal_position": 0.2622904391040054, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2359691326973456, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137661.7075543} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137661.7175543, "x": 11.21581446388954, "y": 4.806770694309247, "z": null, "yaw": -0.023187002274271184, "pitch": null, "roll": null}, "v": 2.273650042536736, "accelerator_pedal_position": 0.2622904391040054, "brake_pedal_position": 0.0, "acceleration": 0.023937897113923856, "steering_wheel_angle": 0.2359691326973456, "front_wheel_angle": 0.010870403833980686, "heading_rate": 0.009654870192678829, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137661.7275543} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26121949969673497, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.104970506728995, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2738894215078753, "gear": 1, "accelerator_pedal_position": 0.2622904391040054, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2359691326973456, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137661.7275543} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.509995698928833, "x": 7.21581446388954, "y": -0.19322930569075325, "z": null, "yaw": 6.259998304905315, "pitch": null, "roll": null}, "v": 2.273650042536736, "accelerator_pedal_position": 0.2622904391040054, "brake_pedal_position": 0.0, "acceleration": 0.023937897113923856, "steering_wheel_angle": 0.2359691326973456, "front_wheel_angle": 0.010870403833980686, "heading_rate": 0.009654870192678829, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137661.7475543} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26174821077273075, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.104970506728995, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2742336904965383, "gear": 1, "accelerator_pedal_position": 0.26121949969673497, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.27692486011790013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137661.7475543} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.509995698928833, "x": 7.21581446388954, "y": -0.19322930569075325, "z": null, "yaw": 6.259998304905315, "pitch": null, "roll": null}, "v": 2.273650042536736, "accelerator_pedal_position": 0.2622904391040054, "brake_pedal_position": 0.0, "acceleration": 0.023937897113923856, "steering_wheel_angle": 0.2359691326973456, "front_wheel_angle": 0.010870403833980686, "heading_rate": 0.009654870192678829, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137661.7675543} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26174821077273075, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.104970506728995, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2746433596935636, "gear": 1, "accelerator_pedal_position": 0.26174821077273075, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.27692486011790013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137661.7675543} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.509995698928833, "x": 7.21581446388954, "y": -0.19322930569075325, "z": null, "yaw": 6.259998304905315, "pitch": null, "roll": null}, "v": 2.273650042536736, "accelerator_pedal_position": 0.2622904391040054, "brake_pedal_position": 0.0, "acceleration": 0.023937897113923856, "steering_wheel_angle": 0.2359691326973456, "front_wheel_angle": 0.010870403833980686, "heading_rate": 0.009654870192678829, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137661.7875543} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26174821077273075, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.104970506728995, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.275052246871212, "gear": 1, "accelerator_pedal_position": 0.26174821077273075, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.27692486011790013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137661.7875543} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.509995698928833, "x": 7.21581446388954, "y": -0.19322930569075325, "z": null, "yaw": 6.259998304905315, "pitch": null, "roll": null}, "v": 2.273650042536736, "accelerator_pedal_position": 0.2622904391040054, "brake_pedal_position": 0.0, "acceleration": 0.023937897113923856, "steering_wheel_angle": 0.2359691326973456, "front_wheel_angle": 0.010870403833980686, "heading_rate": 0.009654870192678829, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137661.8075542} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26174821077273075, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.104970506728995, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.27546035345544, "gear": 1, "accelerator_pedal_position": 0.26174821077273075, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.27692486011790013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137661.8075542} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137661.8275542, "x": 11.465960545587583, "y": 4.801028726826741, "z": null, "yaw": -0.02265331412532835, "pitch": null, "roll": null}, "v": 2.275867680869865, "accelerator_pedal_position": 0.26174821077273075, "brake_pedal_position": 0.0, "acceleration": 0.020337196277794067, "steering_wheel_angle": 0.27692486011790013, "front_wheel_angle": 0.012764029234597036, "heading_rate": 0.011347976284092107, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137661.8275542} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25911755214280024, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0630016180833068, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.275867680869865, "gear": 1, "accelerator_pedal_position": 0.26174821077273075, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.27692486011790013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137661.8275542} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.619995594024658, "x": 7.465960545587583, "y": -0.19897127317325936, "z": null, "yaw": 6.260531993054258, "pitch": null, "roll": null}, "v": 2.275867680869865, "accelerator_pedal_position": 0.26174821077273075, "brake_pedal_position": 0.0, "acceleration": 0.020337196277794067, "steering_wheel_angle": 0.27692486011790013, "front_wheel_angle": 0.012764029234597036, "heading_rate": 0.011347976284092107, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137661.8475542} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2603863825063682, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0630016180833068, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2759455552569796, "gear": 1, "accelerator_pedal_position": 0.25911755214280024, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.27692486011790013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137661.8475542} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.619995594024658, "x": 7.465960545587583, "y": -0.19897127317325936, "z": null, "yaw": 6.260531993054258, "pitch": null, "roll": null}, "v": 2.275867680869865, "accelerator_pedal_position": 0.26174821077273075, "brake_pedal_position": 0.0, "acceleration": 0.020337196277794067, "steering_wheel_angle": 0.27692486011790013, "front_wheel_angle": 0.012764029234597036, "heading_rate": 0.011347976284092107, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137661.8675542} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2603863825063682, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0630016180833068, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2761818089921104, "gear": 1, "accelerator_pedal_position": 0.2603863825063682, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.27692486011790013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137661.8675542} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.619995594024658, "x": 7.465960545587583, "y": -0.19897127317325936, "z": null, "yaw": 6.260531993054258, "pitch": null, "roll": null}, "v": 2.275867680869865, "accelerator_pedal_position": 0.26174821077273075, "brake_pedal_position": 0.0, "acceleration": 0.020337196277794067, "steering_wheel_angle": 0.27692486011790013, "front_wheel_angle": 0.012764029234597036, "heading_rate": 0.011347976284092107, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137661.8875542} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2603863825063682, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0630016180833068, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2764176115920796, "gear": 1, "accelerator_pedal_position": 0.2603863825063682, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.27692486011790013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137661.8875542} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.619995594024658, "x": 7.465960545587583, "y": -0.19897127317325936, "z": null, "yaw": 6.260531993054258, "pitch": null, "roll": null}, "v": 2.275867680869865, "accelerator_pedal_position": 0.26174821077273075, "brake_pedal_position": 0.0, "acceleration": 0.020337196277794067, "steering_wheel_angle": 0.27692486011790013, "front_wheel_angle": 0.012764029234597036, "heading_rate": 0.011347976284092107, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137661.9075541} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2603863825063682, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0630016180833068, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2766529638961153, "gear": 1, "accelerator_pedal_position": 0.2603863825063682, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.27692486011790013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137661.9075541} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.619995594024658, "x": 7.465960545587583, "y": -0.19897127317325936, "z": null, "yaw": 6.260531993054258, "pitch": null, "roll": null}, "v": 2.275867680869865, "accelerator_pedal_position": 0.26174821077273075, "brake_pedal_position": 0.0, "acceleration": 0.020337196277794067, "steering_wheel_angle": 0.27692486011790013, "front_wheel_angle": 0.012764029234597036, "heading_rate": 0.011347976284092107, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137661.9275541} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2603863825063682, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0630016180833068, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.276887866741971, "gear": 1, "accelerator_pedal_position": 0.2603863825063682, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.27692486011790013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137661.9275541} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137661.9375541, "x": 11.71629299805653, "y": 4.795419345133961, "z": null, "yaw": -0.02210482995740298, "pitch": null, "roll": null}, "v": 2.2770051498794763, "accelerator_pedal_position": 0.2603863825063682, "brake_pedal_position": 0.0, "acceleration": 0.011717108645050767, "steering_wheel_angle": 0.27692486011790013, "front_wheel_angle": 0.012764029234597036, "heading_rate": 0.011353647954485539, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137661.947554} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2611937384824405, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1037716126549038, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.277122320965927, "gear": 1, "accelerator_pedal_position": 0.2603863825063682, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.27692486011790013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137661.947554} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.729995489120483, "x": 7.716292998056529, "y": -0.2045806548660387, "z": null, "yaw": 6.261080477222183, "pitch": null, "roll": null}, "v": 2.2770051498794763, "accelerator_pedal_position": 0.2603863825063682, "brake_pedal_position": 0.0, "acceleration": 0.011717108645050767, "steering_wheel_angle": 0.27692486011790013, "front_wheel_angle": 0.012764029234597036, "heading_rate": 0.011353647954485539, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137661.967554} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2608175619987163, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1037716126549038, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2774571986878875, "gear": 1, "accelerator_pedal_position": 0.2611937384824405, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.27692486011790013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137661.967554} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.729995489120483, "x": 7.716292998056529, "y": -0.2045806548660387, "z": null, "yaw": 6.261080477222183, "pitch": null, "roll": null}, "v": 2.2770051498794763, "accelerator_pedal_position": 0.2603863825063682, "brake_pedal_position": 0.0, "acceleration": 0.011717108645050767, "steering_wheel_angle": 0.27692486011790013, "front_wheel_angle": 0.012764029234597036, "heading_rate": 0.011353647954485539, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137661.987554} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2608175619987163, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1037716126549038, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2777444371860485, "gear": 1, "accelerator_pedal_position": 0.2608175619987163, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.27692486011790013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137661.987554} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.729995489120483, "x": 7.716292998056529, "y": -0.2045806548660387, "z": null, "yaw": 6.261080477222183, "pitch": null, "roll": null}, "v": 2.2770051498794763, "accelerator_pedal_position": 0.2603863825063682, "brake_pedal_position": 0.0, "acceleration": 0.011717108645050767, "steering_wheel_angle": 0.27692486011790013, "front_wheel_angle": 0.012764029234597036, "heading_rate": 0.011353647954485539, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137662.007554} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2608175619987163, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1037716126549038, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2780311270138713, "gear": 1, "accelerator_pedal_position": 0.2608175619987163, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.27692486011790013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137662.007554} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.729995489120483, "x": 7.716292998056529, "y": -0.2045806548660387, "z": null, "yaw": 6.261080477222183, "pitch": null, "roll": null}, "v": 2.2770051498794763, "accelerator_pedal_position": 0.2603863825063682, "brake_pedal_position": 0.0, "acceleration": 0.011717108645050767, "steering_wheel_angle": 0.27692486011790013, "front_wheel_angle": 0.012764029234597036, "heading_rate": 0.011353647954485539, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137662.027554} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2608175619987163, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1037716126549038, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2783172691865414, "gear": 1, "accelerator_pedal_position": 0.2608175619987163, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.27692486011790013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137662.027554} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137662.047554, "x": 11.96678406278003, "y": 4.789943869126567, "z": null, "yaw": -0.02155634578947761, "pitch": null, "roll": null}, "v": 2.2786028647174925, "accelerator_pedal_position": 0.2608175619987163, "brake_pedal_position": 0.0, "acceleration": 0.014259309105114581, "steering_wheel_angle": 0.27692486011790013, "front_wheel_angle": 0.012764029234597036, "heading_rate": 0.011361614511699277, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137662.047554} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25955460921881557, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0955134943697862, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2786028647174925, "gear": 1, "accelerator_pedal_position": 0.2608175619987163, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.27692486011790013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137662.047554} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.839995384216309, "x": 7.966784062780031, "y": -0.21005613087343278, "z": null, "yaw": 6.261628961390109, "pitch": null, "roll": null}, "v": 2.2786028647174925, "accelerator_pedal_position": 0.2608175619987163, "brake_pedal_position": 0.0, "acceleration": 0.014259309105114581, "steering_wheel_angle": 0.27692486011790013, "front_wheel_angle": 0.012764029234597036, "heading_rate": 0.011361614511699277, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137662.067554} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.260167647714883, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0955134943697862, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.278831972787205, "gear": 1, "accelerator_pedal_position": 0.260167647714883, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.27692486011790013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137662.067554} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.839995384216309, "x": 7.966784062780031, "y": -0.21005613087343278, "z": null, "yaw": 6.261628961390109, "pitch": null, "roll": null}, "v": 2.2786028647174925, "accelerator_pedal_position": 0.2608175619987163, "brake_pedal_position": 0.0, "acceleration": 0.014259309105114581, "steering_wheel_angle": 0.27692486011790013, "front_wheel_angle": 0.012764029234597036, "heading_rate": 0.011361614511699277, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137662.087554} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.260167647714883, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0955134943697862, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.278933727266972, "gear": 1, "accelerator_pedal_position": 0.260167647714883, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.27692486011790013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137662.087554} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.839995384216309, "x": 7.966784062780031, "y": -0.21005613087343278, "z": null, "yaw": 6.261628961390109, "pitch": null, "roll": null}, "v": 2.2786028647174925, "accelerator_pedal_position": 0.2608175619987163, "brake_pedal_position": 0.0, "acceleration": 0.014259309105114581, "steering_wheel_angle": 0.27692486011790013, "front_wheel_angle": 0.012764029234597036, "heading_rate": 0.011361614511699277, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137662.107554} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.260167647714883, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0955134943697862, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2792384075424486, "gear": 1, "accelerator_pedal_position": 0.260167647714883, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.27692486011790013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137662.107554} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.839995384216309, "x": 7.966784062780031, "y": -0.21005613087343278, "z": null, "yaw": 6.261628961390109, "pitch": null, "roll": null}, "v": 2.2786028647174925, "accelerator_pedal_position": 0.2608175619987163, "brake_pedal_position": 0.0, "acceleration": 0.014259309105114581, "steering_wheel_angle": 0.27692486011790013, "front_wheel_angle": 0.012764029234597036, "heading_rate": 0.011361614511699277, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137662.127554} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.260167647714883, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0955134943697862, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2793397735490157, "gear": 1, "accelerator_pedal_position": 0.260167647714883, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.27692486011790013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137662.127554} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.839995384216309, "x": 7.966784062780031, "y": -0.21005613087343278, "z": null, "yaw": 6.261628961390109, "pitch": null, "roll": null}, "v": 2.2786028647174925, "accelerator_pedal_position": 0.2608175619987163, "brake_pedal_position": 0.0, "acceleration": 0.014259309105114581, "steering_wheel_angle": 0.27692486011790013, "front_wheel_angle": 0.012764029234597036, "heading_rate": 0.011361614511699277, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137662.147554} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.260167647714883, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0955134943697862, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.279542214978243, "gear": 1, "accelerator_pedal_position": 0.260167647714883, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.27692486011790013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137662.147554} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137662.157554, "x": 12.2174221452223, "y": 4.784602711785094, "z": null, "yaw": -0.02100786162155224, "pitch": null, "roll": null}, "v": 2.279643290581947, "accelerator_pedal_position": 0.260167647714883, "brake_pedal_position": 0.0, "acceleration": 0.010097898365968305, "steering_wheel_angle": 0.27692486011790013, "front_wheel_angle": 0.012764029234597036, "heading_rate": 0.011366802303649764, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137662.167554} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25985485004484776, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1062886118921482, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2797442695656067, "gear": 1, "accelerator_pedal_position": 0.260167647714883, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.27692486011790013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137662.167554} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.949995279312134, "x": 8.2174221452223, "y": -0.21539728821490556, "z": null, "yaw": 6.262177445558034, "pitch": null, "roll": null}, "v": 2.279643290581947, "accelerator_pedal_position": 0.260167647714883, "brake_pedal_position": 0.0, "acceleration": 0.010097898365968305, "steering_wheel_angle": 0.27692486011790013, "front_wheel_angle": 0.012764029234597036, "heading_rate": 0.011366802303649764, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137662.187554} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26001137826802395, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1062886118921482, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.279906857014257, "gear": 1, "accelerator_pedal_position": 0.25985485004484776, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.27692486011790013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137662.187554} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.949995279312134, "x": 8.2174221452223, "y": -0.21539728821490556, "z": null, "yaw": 6.262177445558034, "pitch": null, "roll": null}, "v": 2.279643290581947, "accelerator_pedal_position": 0.260167647714883, "brake_pedal_position": 0.0, "acceleration": 0.010097898365968305, "steering_wheel_angle": 0.27692486011790013, "front_wheel_angle": 0.012764029234597036, "heading_rate": 0.011366802303649764, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137662.2075539} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26001137826802395, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1062886118921482, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.280088690428343, "gear": 1, "accelerator_pedal_position": 0.26001137826802395, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.27692486011790013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137662.2075539} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.949995279312134, "x": 8.2174221452223, "y": -0.21539728821490556, "z": null, "yaw": 6.262177445558034, "pitch": null, "roll": null}, "v": 2.279643290581947, "accelerator_pedal_position": 0.260167647714883, "brake_pedal_position": 0.0, "acceleration": 0.010097898365968305, "steering_wheel_angle": 0.27692486011790013, "front_wheel_angle": 0.012764029234597036, "heading_rate": 0.011366802303649764, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137662.2275538} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26001137826802395, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1062886118921482, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.280270176339986, "gear": 1, "accelerator_pedal_position": 0.26001137826802395, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.27692486011790013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137662.2275538} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.949995279312134, "x": 8.2174221452223, "y": -0.21539728821490556, "z": null, "yaw": 6.262177445558034, "pitch": null, "roll": null}, "v": 2.279643290581947, "accelerator_pedal_position": 0.260167647714883, "brake_pedal_position": 0.0, "acceleration": 0.010097898365968305, "steering_wheel_angle": 0.27692486011790013, "front_wheel_angle": 0.012764029234597036, "heading_rate": 0.011366802303649764, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137662.2475538} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26001137826802395, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1062886118921482, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.28045131540013, "gear": 1, "accelerator_pedal_position": 0.26001137826802395, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.27692486011790013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137662.2475538} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137662.2675538, "x": 12.468178205323406, "y": 4.779396636500484, "z": null, "yaw": -0.02045937745362687, "pitch": null, "roll": null}, "v": 2.280632108258551, "accelerator_pedal_position": 0.26001137826802395, "brake_pedal_position": 0.0, "acceleration": 0.009026680630023598, "steering_wheel_angle": 0.27692486011790013, "front_wheel_angle": 0.012764029234597036, "heading_rate": 0.011371732765836872, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137662.2675538} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25973077513907955, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1165146711225509, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.280704837369292, "gear": 1, "accelerator_pedal_position": 0.25973077513907955, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.27692486011790013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137662.2675538} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.059995174407959, "x": 8.468178205323406, "y": -0.22060336349951637, "z": null, "yaw": 6.262725929725959, "pitch": null, "roll": null}, "v": 2.280632108258551, "accelerator_pedal_position": 0.26001137826802395, "brake_pedal_position": 0.0, "acceleration": 0.009026680630023598, "steering_wheel_angle": 0.27692486011790013, "front_wheel_angle": 0.012764029234597036, "heading_rate": 0.011371732765836872, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137662.2875538} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25987159831411094, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1165146711225509, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.28077749694128, "gear": 1, "accelerator_pedal_position": 0.25973077513907955, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.27692486011790013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137662.2875538} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.059995174407959, "x": 8.468178205323406, "y": -0.22060336349951637, "z": null, "yaw": 6.262725929725959, "pitch": null, "roll": null}, "v": 2.280632108258551, "accelerator_pedal_position": 0.26001137826802395, "brake_pedal_position": 0.0, "acceleration": 0.009026680630023598, "steering_wheel_angle": 0.27692486011790013, "front_wheel_angle": 0.012764029234597036, "heading_rate": 0.011371732765836872, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137662.3075538} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25987159831411094, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1165146711225509, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2809402022118546, "gear": 1, "accelerator_pedal_position": 0.25987159831411094, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.27692486011790013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137662.3075538} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.059995174407959, "x": 8.468178205323406, "y": -0.22060336349951637, "z": null, "yaw": 6.262725929725959, "pitch": null, "roll": null}, "v": 2.280632108258551, "accelerator_pedal_position": 0.26001137826802395, "brake_pedal_position": 0.0, "acceleration": 0.009026680630023598, "steering_wheel_angle": 0.27692486011790013, "front_wheel_angle": 0.012764029234597036, "heading_rate": 0.011371732765836872, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137662.3275537} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25987159831411094, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1165146711225509, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2811025964801677, "gear": 1, "accelerator_pedal_position": 0.25987159831411094, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.27692486011790013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137662.3275537} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.059995174407959, "x": 8.468178205323406, "y": -0.22060336349951637, "z": null, "yaw": 6.262725929725959, "pitch": null, "roll": null}, "v": 2.280632108258551, "accelerator_pedal_position": 0.26001137826802395, "brake_pedal_position": 0.0, "acceleration": 0.009026680630023598, "steering_wheel_angle": 0.27692486011790013, "front_wheel_angle": 0.012764029234597036, "heading_rate": 0.011371732765836872, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137662.3475537} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25987159831411094, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1165146711225509, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.28126468033014, "gear": 1, "accelerator_pedal_position": 0.25987159831411094, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.27692486011790013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137662.3475537} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.059995174407959, "x": 8.468178205323406, "y": -0.22060336349951637, "z": null, "yaw": 6.262725929725959, "pitch": null, "roll": null}, "v": 2.280632108258551, "accelerator_pedal_position": 0.26001137826802395, "brake_pedal_position": 0.0, "acceleration": 0.009026680630023598, "steering_wheel_angle": 0.27692486011790013, "front_wheel_angle": 0.012764029234597036, "heading_rate": 0.011371732765836872, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137662.3675537} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25987159831411094, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1165146711225509, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.281426454344636, "gear": 1, "accelerator_pedal_position": 0.25987159831411094, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.27692486011790013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137662.3675537} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137662.3775537, "x": 12.719039541677391, "y": 4.774326026233835, "z": null, "yaw": -0.0199108932857015, "pitch": null, "roll": null}, "v": 2.281507225345437, "accelerator_pedal_position": 0.25987159831411094, "brake_pedal_position": 0.0, "acceleration": 0.008069376002887096, "steering_wheel_angle": 0.27692486011790013, "front_wheel_angle": 0.012764029234597036, "heading_rate": 0.011376096291902673, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137662.3875537} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25861351366324103, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.094496258242629, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.281587919105466, "gear": 1, "accelerator_pedal_position": 0.25987159831411094, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.27692486011790013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137662.3875537} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.169995069503784, "x": 8.719039541677391, "y": -0.22567397376616505, "z": null, "yaw": 6.2632744138938845, "pitch": null, "roll": null}, "v": 2.281507225345437, "accelerator_pedal_position": 0.25987159831411094, "brake_pedal_position": 0.0, "acceleration": 0.008069376002887096, "steering_wheel_angle": 0.27692486011790013, "front_wheel_angle": 0.012764029234597036, "heading_rate": 0.011376096291902673, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137662.4075537} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2592189775072675, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.094496258242629, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.281591889808209, "gear": 1, "accelerator_pedal_position": 0.25861351366324103, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.27692486011790013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137662.4075537} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.169995069503784, "x": 8.719039541677391, "y": -0.22567397376616505, "z": null, "yaw": 6.2632744138938845, "pitch": null, "roll": null}, "v": 2.281507225345437, "accelerator_pedal_position": 0.25987159831411094, "brake_pedal_position": 0.0, "acceleration": 0.008069376002887096, "steering_wheel_angle": 0.27692486011790013, "front_wheel_angle": 0.012764029234597036, "heading_rate": 0.011376096291902673, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137662.4275537} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2592189775072675, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.094496258242629, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2817112475729937, "gear": 1, "accelerator_pedal_position": 0.2592189775072675, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.27692486011790013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137662.4275537} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.169995069503784, "x": 8.719039541677391, "y": -0.22567397376616505, "z": null, "yaw": 6.2632744138938845, "pitch": null, "roll": null}, "v": 2.281507225345437, "accelerator_pedal_position": 0.25987159831411094, "brake_pedal_position": 0.0, "acceleration": 0.008069376002887096, "steering_wheel_angle": 0.27692486011790013, "front_wheel_angle": 0.012764029234597036, "heading_rate": 0.011376096291902673, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137662.4475536} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2592189775072675, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.094496258242629, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2817906292940053, "gear": 1, "accelerator_pedal_position": 0.2592189775072675, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.27692486011790013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137662.4475536} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.169995069503784, "x": 8.719039541677391, "y": -0.22567397376616505, "z": null, "yaw": 6.2632744138938845, "pitch": null, "roll": null}, "v": 2.281507225345437, "accelerator_pedal_position": 0.25987159831411094, "brake_pedal_position": 0.0, "acceleration": 0.008069376002887096, "steering_wheel_angle": 0.27692486011790013, "front_wheel_angle": 0.012764029234597036, "heading_rate": 0.011376096291902673, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137662.4675536} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2592189775072675, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.094496258242629, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.281869859253543, "gear": 1, "accelerator_pedal_position": 0.2592189775072675, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.27692486011790013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137662.4675536} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137662.4875536, "x": 12.969976358576414, "y": 4.769391577376427, "z": null, "yaw": -0.01936240911777613, "pitch": null, "roll": null}, "v": 2.2819094174126633, "accelerator_pedal_position": 0.2592189775072675, "brake_pedal_position": 0.0, "acceleration": 0.003952032657022819, "steering_wheel_angle": 0.27692486011790013, "front_wheel_angle": 0.012764029234597036, "heading_rate": 0.011378101709914844, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137662.4875536} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2601940480720574, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1358474362153181, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2819094174126633, "gear": 1, "accelerator_pedal_position": 0.2592189775072675, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.27692486011790013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137662.4875536} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.279994964599609, "x": 8.969976358576414, "y": -0.23060842262357273, "z": null, "yaw": 6.26382289806181, "pitch": null, "roll": null}, "v": 2.2819094174126633, "accelerator_pedal_position": 0.2592189775072675, "brake_pedal_position": 0.0, "acceleration": 0.003952032657022819, "steering_wheel_angle": 0.27692486011790013, "front_wheel_angle": 0.012764029234597036, "heading_rate": 0.011378101709914844, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137662.5075536} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25973265906238535, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1358474362153181, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.28211024580513, "gear": 1, "accelerator_pedal_position": 0.2601940480720574, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3178712380015408, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137662.5075536} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.279994964599609, "x": 8.969976358576414, "y": -0.23060842262357273, "z": null, "yaw": 6.26382289806181, "pitch": null, "roll": null}, "v": 2.2819094174126633, "accelerator_pedal_position": 0.2592189775072675, "brake_pedal_position": 0.0, "acceleration": 0.003952032657022819, "steering_wheel_angle": 0.27692486011790013, "front_wheel_angle": 0.012764029234597036, "heading_rate": 0.011378101709914844, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137662.5275536} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25973265906238535, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1358474362153181, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.282324340959915, "gear": 1, "accelerator_pedal_position": 0.25973265906238535, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3178712380015408, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137662.5275536} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.279994964599609, "x": 8.969976358576414, "y": -0.23060842262357273, "z": null, "yaw": 6.26382289806181, "pitch": null, "roll": null}, "v": 2.2819094174126633, "accelerator_pedal_position": 0.2592189775072675, "brake_pedal_position": 0.0, "acceleration": 0.003952032657022819, "steering_wheel_angle": 0.27692486011790013, "front_wheel_angle": 0.012764029234597036, "heading_rate": 0.011378101709914844, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137662.5475535} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25973265906238535, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1358474362153181, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2823955695411002, "gear": 1, "accelerator_pedal_position": 0.25973265906238535, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3178712380015408, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137662.5475535} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.279994964599609, "x": 8.969976358576414, "y": -0.23060842262357273, "z": null, "yaw": 6.26382289806181, "pitch": null, "roll": null}, "v": 2.2819094174126633, "accelerator_pedal_position": 0.2592189775072675, "brake_pedal_position": 0.0, "acceleration": 0.003952032657022819, "steering_wheel_angle": 0.27692486011790013, "front_wheel_angle": 0.012764029234597036, "heading_rate": 0.011378101709914844, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137662.5675535} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25973265906238535, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1358474362153181, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.282537822383192, "gear": 1, "accelerator_pedal_position": 0.25973265906238535, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3178712380015408, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137662.5675535} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.279994964599609, "x": 8.969976358576414, "y": -0.23060842262357273, "z": null, "yaw": 6.26382289806181, "pitch": null, "roll": null}, "v": 2.2819094174126633, "accelerator_pedal_position": 0.2592189775072675, "brake_pedal_position": 0.0, "acceleration": 0.003952032657022819, "steering_wheel_angle": 0.27692486011790013, "front_wheel_angle": 0.012764029234597036, "heading_rate": 0.011378101709914844, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137662.5875535} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25973265906238535, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1358474362153181, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.282679803225615, "gear": 1, "accelerator_pedal_position": 0.25973265906238535, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3178712380015408, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137662.5875535} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137662.5975535, "x": 13.220985418540275, "y": 4.76460104335228, "z": null, "yaw": -0.01873987760001281, "pitch": null, "roll": null}, "v": 2.2827506918069957, "accelerator_pedal_position": 0.25973265906238535, "brake_pedal_position": 0.0, "acceleration": 0.007082077340105408, "steering_wheel_angle": 0.3178712380015408, "front_wheel_angle": 0.014659284451994874, "heading_rate": 0.01307261287957127, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137662.6075535} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2590301038396264, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1277036921531813, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2828751735586685, "gear": 1, "accelerator_pedal_position": 0.2590301038396264, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3178712380015408, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137662.6075535} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.389994859695435, "x": 9.220985418540275, "y": -0.23539895664772015, "z": null, "yaw": 6.264445429579573, "pitch": null, "roll": null}, "v": 2.2827506918069957, "accelerator_pedal_position": 0.25973265906238535, "brake_pedal_position": 0.0, "acceleration": 0.007082077340105408, "steering_wheel_angle": 0.3178712380015408, "front_wheel_angle": 0.014659284451994874, "heading_rate": 0.01307261287957127, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137662.6275535} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2593707847853274, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1277036921531813, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2829019655560607, "gear": 1, "accelerator_pedal_position": 0.2590301038396264, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3178712380015408, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137662.6275535} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.389994859695435, "x": 9.220985418540275, "y": -0.23539895664772015, "z": null, "yaw": 6.264445429579573, "pitch": null, "roll": null}, "v": 2.2827506918069957, "accelerator_pedal_position": 0.25973265906238535, "brake_pedal_position": 0.0, "acceleration": 0.007082077340105408, "steering_wheel_angle": 0.3178712380015408, "front_wheel_angle": 0.014659284451994874, "heading_rate": 0.01307261287957127, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137662.6475534} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2593707847853274, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1277036921531813, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.282950024483932, "gear": 1, "accelerator_pedal_position": 0.2593707847853274, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3178712380015408, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137662.6475534} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.389994859695435, "x": 9.220985418540275, "y": -0.23539895664772015, "z": null, "yaw": 6.264445429579573, "pitch": null, "roll": null}, "v": 2.2827506918069957, "accelerator_pedal_position": 0.25973265906238535, "brake_pedal_position": 0.0, "acceleration": 0.007082077340105408, "steering_wheel_angle": 0.3178712380015408, "front_wheel_angle": 0.014659284451994874, "heading_rate": 0.01307261287957127, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137662.6675534} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2593707847853274, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1277036921531813, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.283046004465812, "gear": 1, "accelerator_pedal_position": 0.2593707847853274, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3178712380015408, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137662.6675534} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.389994859695435, "x": 9.220985418540275, "y": -0.23539895664772015, "z": null, "yaw": 6.264445429579573, "pitch": null, "roll": null}, "v": 2.2827506918069957, "accelerator_pedal_position": 0.25973265906238535, "brake_pedal_position": 0.0, "acceleration": 0.007082077340105408, "steering_wheel_angle": 0.3178712380015408, "front_wheel_angle": 0.014659284451994874, "heading_rate": 0.01307261287957127, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137662.6875534} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2593707847853274, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1277036921531813, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2831418009057765, "gear": 1, "accelerator_pedal_position": 0.2593707847853274, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3178712380015408, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137662.6875534} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137662.7075534, "x": 13.472068828507563, "y": 4.759967141517084, "z": null, "yaw": -0.018109941347265693, "pitch": null, "roll": null}, "v": 2.2832374141511425, "accelerator_pedal_position": 0.2593707847853274, "brake_pedal_position": 0.0, "acceleration": 0.004773803306942936, "steering_wheel_angle": 0.3178712380015408, "front_wheel_angle": 0.014659284451994874, "heading_rate": 0.01307540018911309, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137662.7075534} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2589677249845214, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1158391381344264, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2832599609466615, "gear": 1, "accelerator_pedal_position": 0.2589677249845214, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3178712380015408, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137662.7075534} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.49999475479126, "x": 9.472068828507563, "y": -0.2400328584829161, "z": null, "yaw": 6.26507536583232, "pitch": null, "roll": null}, "v": 2.2832374141511425, "accelerator_pedal_position": 0.2593707847853274, "brake_pedal_position": 0.0, "acceleration": 0.004773803306942936, "steering_wheel_angle": 0.3178712380015408, "front_wheel_angle": 0.014659284451994874, "heading_rate": 0.01307540018911309, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137662.7275534} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25916320573410306, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1158391381344264, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2832824861727947, "gear": 1, "accelerator_pedal_position": 0.2589677249845214, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3178712380015408, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137662.7275534} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.49999475479126, "x": 9.472068828507563, "y": -0.2400328584829161, "z": null, "yaw": 6.26507536583232, "pitch": null, "roll": null}, "v": 2.2832374141511425, "accelerator_pedal_position": 0.2593707847853274, "brake_pedal_position": 0.0, "acceleration": 0.004773803306942936, "steering_wheel_angle": 0.3178712380015408, "front_wheel_angle": 0.014659284451994874, "heading_rate": 0.01307540018911309, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137662.7475533} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25916320573410306, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1158391381344264, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.283351895404647, "gear": 1, "accelerator_pedal_position": 0.25916320573410306, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3178712380015408, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137662.7475533} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.49999475479126, "x": 9.472068828507563, "y": -0.2400328584829161, "z": null, "yaw": 6.26507536583232, "pitch": null, "roll": null}, "v": 2.2832374141511425, "accelerator_pedal_position": 0.2593707847853274, "brake_pedal_position": 0.0, "acceleration": 0.004773803306942936, "steering_wheel_angle": 0.3178712380015408, "front_wheel_angle": 0.014659284451994874, "heading_rate": 0.01307540018911309, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137662.7675533} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25916320573410306, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1158391381344264, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2834211718969932, "gear": 1, "accelerator_pedal_position": 0.25916320573410306, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3178712380015408, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137662.7675533} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.49999475479126, "x": 9.472068828507563, "y": -0.2400328584829161, "z": null, "yaw": 6.26507536583232, "pitch": null, "roll": null}, "v": 2.2832374141511425, "accelerator_pedal_position": 0.2593707847853274, "brake_pedal_position": 0.0, "acceleration": 0.004773803306942936, "steering_wheel_angle": 0.3178712380015408, "front_wheel_angle": 0.014659284451994874, "heading_rate": 0.01307540018911309, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137662.7875533} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25916320573410306, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1158391381344264, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.283490315901768, "gear": 1, "accelerator_pedal_position": 0.25916320573410306, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3178712380015408, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137662.7875533} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.49999475479126, "x": 9.472068828507563, "y": -0.2400328584829161, "z": null, "yaw": 6.26507536583232, "pitch": null, "roll": null}, "v": 2.2832374141511425, "accelerator_pedal_position": 0.2593707847853274, "brake_pedal_position": 0.0, "acceleration": 0.004773803306942936, "steering_wheel_angle": 0.3178712380015408, "front_wheel_angle": 0.014659284451994874, "heading_rate": 0.01307540018911309, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137662.8075533} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25916320573410306, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1158391381344264, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.283559327670435, "gear": 1, "accelerator_pedal_position": 0.25916320573410306, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3178712380015408, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137662.8075533} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137662.8175533, "x": 13.723201798349523, "y": 4.755490574270433, "z": null, "yaw": -0.017480005094518577, "pitch": null, "roll": null}, "v": 2.2835937840446823, "accelerator_pedal_position": 0.25916320573410306, "brake_pedal_position": 0.0, "acceleration": 0.0034423409306347796, "steering_wheel_angle": 0.3178712380015408, "front_wheel_angle": 0.014659284451994874, "heading_rate": 0.01307744101016153, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137662.8275533} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2574499756442709, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1015851861628898, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2835555210490406, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3178712380015408, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137662.8275533} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.609994649887085, "x": 9.723201798349523, "y": -0.24450942572956702, "z": null, "yaw": 6.265705302085068, "pitch": null, "roll": null}, "v": 2.2835937840446823, "accelerator_pedal_position": 0.25916320573410306, "brake_pedal_position": 0.0, "acceleration": 0.0034423409306347796, "steering_wheel_angle": 0.3178712380015408, "front_wheel_angle": 0.014659284451994874, "heading_rate": 0.01307744101016153, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137662.8475533} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25826839749064034, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1015851861628898, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2834829041845115, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3178712380015408, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137662.8475533} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.609994649887085, "x": 9.723201798349523, "y": -0.24450942572956702, "z": null, "yaw": 6.265705302085068, "pitch": null, "roll": null}, "v": 2.2835937840446823, "accelerator_pedal_position": 0.25916320573410306, "brake_pedal_position": 0.0, "acceleration": 0.0034423409306347796, "steering_wheel_angle": 0.3178712380015408, "front_wheel_angle": 0.014659284451994874, "heading_rate": 0.01307744101016153, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137662.8675532} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25826839749064034, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1015851861628898, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2834401326013762, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3178712380015408, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137662.8675532} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.609994649887085, "x": 9.723201798349523, "y": -0.24450942572956702, "z": null, "yaw": 6.265705302085068, "pitch": null, "roll": null}, "v": 2.2835937840446823, "accelerator_pedal_position": 0.25916320573410306, "brake_pedal_position": 0.0, "acceleration": 0.0034423409306347796, "steering_wheel_angle": 0.3178712380015408, "front_wheel_angle": 0.014659284451994874, "heading_rate": 0.01307744101016153, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137662.8875532} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25826839749064034, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1015851861628898, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2833974428174, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3178712380015408, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137662.8875532} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.609994649887085, "x": 9.723201798349523, "y": -0.24450942572956702, "z": null, "yaw": 6.265705302085068, "pitch": null, "roll": null}, "v": 2.2835937840446823, "accelerator_pedal_position": 0.25916320573410306, "brake_pedal_position": 0.0, "acceleration": 0.0034423409306347796, "steering_wheel_angle": 0.3178712380015408, "front_wheel_angle": 0.014659284451994874, "heading_rate": 0.01307744101016153, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137662.9075532} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25826839749064034, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1015851861628898, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.283354834675416, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3178712380015408, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137662.9075532} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137662.9275532, "x": 13.974345095868738, "y": 4.751172071822244, "z": null, "yaw": -0.01685006884177146, "pitch": null, "roll": null}, "v": 2.283312308018562, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3663007663604187, "steering_wheel_angle": 0.3178712380015408, "front_wheel_angle": 0.014659284451994874, "heading_rate": 0.013075829083314873, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137662.9275532} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25955528140106465, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1414485775520107, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.283312308018562, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3178712380015408, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137662.9275532} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.71999454498291, "x": 9.974345095868738, "y": -0.24882792817775634, "z": null, "yaw": 6.266335238337815, "pitch": null, "roll": null}, "v": 2.283312308018562, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3663007663604187, "steering_wheel_angle": 0.3178712380015408, "front_wheel_angle": 0.014659284451994874, "heading_rate": 0.013075829083314873, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137662.9475532} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2589404275329855, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1414485775520107, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.283430646234183, "gear": 1, "accelerator_pedal_position": 0.25955528140106465, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3178712380015408, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137662.9475532} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.71999454498291, "x": 9.974345095868738, "y": -0.24882792817775634, "z": null, "yaw": 6.266335238337815, "pitch": null, "roll": null}, "v": 2.283312308018562, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3663007663604187, "steering_wheel_angle": 0.3178712380015408, "front_wheel_angle": 0.014659284451994874, "heading_rate": 0.013075829083314873, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137662.9675531} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2589404275329855, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1414485775520107, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.283471938165136, "gear": 1, "accelerator_pedal_position": 0.2589404275329855, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3178712380015408, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137662.9675531} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.71999454498291, "x": 9.974345095868738, "y": -0.24882792817775634, "z": null, "yaw": 6.266335238337815, "pitch": null, "roll": null}, "v": 2.283312308018562, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3663007663604187, "steering_wheel_angle": 0.3178712380015408, "front_wheel_angle": 0.014659284451994874, "heading_rate": 0.013075829083314873, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137662.9875531} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2589404275329855, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1414485775520107, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2835131511265345, "gear": 1, "accelerator_pedal_position": 0.2589404275329855, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3178712380015408, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137662.9875531} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.71999454498291, "x": 9.974345095868738, "y": -0.24882792817775634, "z": null, "yaw": 6.266335238337815, "pitch": null, "roll": null}, "v": 2.283312308018562, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3663007663604187, "steering_wheel_angle": 0.3178712380015408, "front_wheel_angle": 0.014659284451994874, "heading_rate": 0.013075829083314873, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137663.007553} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2589404275329855, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1414485775520107, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.283574822829528, "gear": 1, "accelerator_pedal_position": 0.2589404275329855, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3178712380015408, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137663.007553} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.71999454498291, "x": 9.974345095868738, "y": -0.24882792817775634, "z": null, "yaw": 6.266335238337815, "pitch": null, "roll": null}, "v": 2.283312308018562, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3663007663604187, "steering_wheel_angle": 0.3178712380015408, "front_wheel_angle": 0.014659284451994874, "heading_rate": 0.013075829083314873, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137663.027553} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2589404275329855, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1414485775520107, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2835953407417784, "gear": 1, "accelerator_pedal_position": 0.2589404275329855, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3178712380015408, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137663.027553} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137663.037553, "x": 14.22549365144374, "y": 4.747011735034429, "z": null, "yaw": -0.016220132589024345, "pitch": null, "roll": null}, "v": 2.2836158390241934, "accelerator_pedal_position": 0.2589404275329855, "brake_pedal_position": 0.0, "acceleration": 0.0020478671275280247, "steering_wheel_angle": 0.3178712380015408, "front_wheel_angle": 0.014659284451994874, "heading_rate": 0.013077567312262872, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137663.047553} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2533124156387049, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1210267654972392, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2836363176954686, "gear": 1, "accelerator_pedal_position": 0.2589404275329855, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3178712380015408, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137663.047553} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.829994440078735, "x": 10.22549365144374, "y": -0.2529882649655706, "z": null, "yaw": 6.2669651745905615, "pitch": null, "roll": null}, "v": 2.2836158390241934, "accelerator_pedal_position": 0.2589404275329855, "brake_pedal_position": 0.0, "acceleration": 0.0020478671275280247, "steering_wheel_angle": 0.3178712380015408, "front_wheel_angle": 0.014659284451994874, "heading_rate": 0.013077567312262872, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137663.067553} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2559946351067786, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1210267654972392, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.282974051311104, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3178712380015408, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137663.067553} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.829994440078735, "x": 10.22549365144374, "y": -0.2529882649655706, "z": null, "yaw": 6.2669651745905615, "pitch": null, "roll": null}, "v": 2.2836158390241934, "accelerator_pedal_position": 0.2589404275329855, "brake_pedal_position": 0.0, "acceleration": 0.0020478671275280247, "steering_wheel_angle": 0.3178712380015408, "front_wheel_angle": 0.014659284451994874, "heading_rate": 0.013077567312262872, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137663.087553} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2559946351067786, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1210267654972392, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.282648168485187, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3178712380015408, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137663.087553} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.829994440078735, "x": 10.22549365144374, "y": -0.2529882649655706, "z": null, "yaw": 6.2669651745905615, "pitch": null, "roll": null}, "v": 2.2836158390241934, "accelerator_pedal_position": 0.2589404275329855, "brake_pedal_position": 0.0, "acceleration": 0.0020478671275280247, "steering_wheel_angle": 0.3178712380015408, "front_wheel_angle": 0.014659284451994874, "heading_rate": 0.013077567312262872, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137663.107553} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2559946351067786, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1210267654972392, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.282322908804879, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3178712380015408, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137663.107553} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.829994440078735, "x": 10.22549365144374, "y": -0.2529882649655706, "z": null, "yaw": 6.2669651745905615, "pitch": null, "roll": null}, "v": 2.2836158390241934, "accelerator_pedal_position": 0.2589404275329855, "brake_pedal_position": 0.0, "acceleration": 0.0020478671275280247, "steering_wheel_angle": 0.3178712380015408, "front_wheel_angle": 0.014659284451994874, "heading_rate": 0.013077567312262872, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137663.127553} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2559946351067786, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1210267654972392, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2819982710363176, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3178712380015408, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137663.127553} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137663.147553, "x": 14.476559710422896, "y": 4.743010948850078, "z": null, "yaw": -0.015590196336277227, "pitch": null, "roll": null}, "v": 2.281674253948243, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3661440867087149, "steering_wheel_angle": 0.3178712380015408, "front_wheel_angle": 0.014659284451994874, "heading_rate": 0.013066448450198017, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137663.147553} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2579550546630937, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1637881362137512, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.281674253948243, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3178712380015408, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137663.147553} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.9399943351745605, "x": 10.476559710422896, "y": -0.25698905114992243, "z": null, "yaw": 6.267595110843309, "pitch": null, "roll": null}, "v": 2.281674253948243, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3661440867087149, "steering_wheel_angle": 0.3178712380015408, "front_wheel_angle": 0.014659284451994874, "heading_rate": 0.013066448450198017, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137663.167553} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25700737110611216, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1637881362137512, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2815957915828973, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3178712380015408, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137663.167553} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.9399943351745605, "x": 10.476559710422896, "y": -0.25698905114992243, "z": null, "yaw": 6.267595110843309, "pitch": null, "roll": null}, "v": 2.281674253948243, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3661440867087149, "steering_wheel_angle": 0.3178712380015408, "front_wheel_angle": 0.014659284451994874, "heading_rate": 0.013066448450198017, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137663.187553} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25700737110611216, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1637881362137512, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2813008583963894, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3178712380015408, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137663.187553} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.9399943351745605, "x": 10.476559710422896, "y": -0.25698905114992243, "z": null, "yaw": 6.267595110843309, "pitch": null, "roll": null}, "v": 2.281674253948243, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3661440867087149, "steering_wheel_angle": 0.3178712380015408, "front_wheel_angle": 0.014659284451994874, "heading_rate": 0.013066448450198017, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137663.207553} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25700737110611216, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1637881362137512, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2812027353006714, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3178712380015408, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137663.207553} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.9399943351745605, "x": 10.476559710422896, "y": -0.25698905114992243, "z": null, "yaw": 6.267595110843309, "pitch": null, "roll": null}, "v": 2.281674253948243, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3661440867087149, "steering_wheel_angle": 0.3178712380015408, "front_wheel_angle": 0.014659284451994874, "heading_rate": 0.013066448450198017, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137663.227553} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25700737110611216, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1637881362137512, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2810067705083235, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3178712380015408, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137663.227553} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.9399943351745605, "x": 10.476559710422896, "y": -0.25698905114992243, "z": null, "yaw": 6.267595110843309, "pitch": null, "roll": null}, "v": 2.281674253948243, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3661440867087149, "steering_wheel_angle": 0.3178712380015408, "front_wheel_angle": 0.014659284451994874, "heading_rate": 0.013066448450198017, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137663.2475529} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25700737110611216, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1637881362137512, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2808111803042386, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3178712380015408, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137663.2475529} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137663.2575529, "x": 14.727471687439705, "y": 4.739170721143206, "z": null, "yaw": -0.014960260083530092, "pitch": null, "roll": null}, "v": 2.2807135254441984, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36605221812365096, "steering_wheel_angle": 0.3178712380015408, "front_wheel_angle": 0.014659284451994874, "heading_rate": 0.013060946652800333, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137663.2675529} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2586114538958424, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2101862388371618, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2806159639570938, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3178712380015408, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137663.2675529} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.049994230270386, "x": 10.727471687439705, "y": -0.26082927885679386, "z": null, "yaw": 6.268225047096056, "pitch": null, "roll": null}, "v": 2.2807135254441984, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36605221812365096, "steering_wheel_angle": 0.3178712380015408, "front_wheel_angle": 0.014659284451994874, "heading_rate": 0.013060946652800333, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137663.2875528} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25784060505203615, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2101862388371618, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.280621535230419, "gear": 1, "accelerator_pedal_position": 0.2586114538958424, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3588580072642818, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137663.2875528} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.049994230270386, "x": 10.727471687439705, "y": -0.26082927885679386, "z": null, "yaw": 6.268225047096056, "pitch": null, "roll": null}, "v": 2.2807135254441984, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36605221812365096, "steering_wheel_angle": 0.3178712380015408, "front_wheel_angle": 0.014659284451994874, "heading_rate": 0.013060946652800333, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137663.3075528} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25784060505203615, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2101862388371618, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.280530785813707, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3588580072642818, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137663.3075528} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.049994230270386, "x": 10.727471687439705, "y": -0.26082927885679386, "z": null, "yaw": 6.268225047096056, "pitch": null, "roll": null}, "v": 2.2807135254441984, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36605221812365096, "steering_wheel_angle": 0.3178712380015408, "front_wheel_angle": 0.014659284451994874, "heading_rate": 0.013060946652800333, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137663.3275528} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25784060505203615, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2101862388371618, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2804402098470136, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3588580072642818, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137663.3275528} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.049994230270386, "x": 10.727471687439705, "y": -0.26082927885679386, "z": null, "yaw": 6.268225047096056, "pitch": null, "roll": null}, "v": 2.2807135254441984, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36605221812365096, "steering_wheel_angle": 0.3178712380015408, "front_wheel_angle": 0.014659284451994874, "heading_rate": 0.013060946652800333, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137663.3475528} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25784060505203615, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2101862388371618, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.280349806995541, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3588580072642818, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137663.3475528} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137663.3675528, "x": 14.978301282884582, "y": 4.735495892276179, "z": null, "yaw": -0.014263538914986709, "pitch": null, "roll": null}, "v": 2.280259576925152, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36600881622784637, "steering_wheel_angle": 0.3588580072642818, "front_wheel_angle": 0.01655848091756134, "heading_rate": 0.014750424182661311, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137663.3675528} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2566648202772658, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2248387447616405, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.280259576925152, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3588580072642818, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137663.3675528} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.159994125366211, "x": 10.978301282884582, "y": -0.2645041077238206, "z": null, "yaw": 6.268921768264599, "pitch": null, "roll": null}, "v": 2.280259576925152, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36600881622784637, "steering_wheel_angle": 0.3588580072642818, "front_wheel_angle": 0.01655848091756134, "heading_rate": 0.014750424182661311, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137663.3875527} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2572214112559938, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2248387447616405, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.280022616461274, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137663.3875527} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.159994125366211, "x": 10.978301282884582, "y": -0.2645041077238206, "z": null, "yaw": 6.268921768264599, "pitch": null, "roll": null}, "v": 2.280259576925152, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36600881622784637, "steering_wheel_angle": 0.3588580072642818, "front_wheel_angle": 0.01655848091756134, "heading_rate": 0.014750424182661311, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137663.4075527} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2572214112559938, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2248387447616405, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2798556494735642, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137663.4075527} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.159994125366211, "x": 10.978301282884582, "y": -0.2645041077238206, "z": null, "yaw": 6.268921768264599, "pitch": null, "roll": null}, "v": 2.280259576925152, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36600881622784637, "steering_wheel_angle": 0.3588580072642818, "front_wheel_angle": 0.01655848091756134, "heading_rate": 0.014750424182661311, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137663.4275527} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2572214112559938, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2248387447616405, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2796890015672933, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137663.4275527} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.159994125366211, "x": 10.978301282884582, "y": -0.2645041077238206, "z": null, "yaw": 6.268921768264599, "pitch": null, "roll": null}, "v": 2.280259576925152, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36600881622784637, "steering_wheel_angle": 0.3588580072642818, "front_wheel_angle": 0.01655848091756134, "heading_rate": 0.014750424182661311, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137663.4475527} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2572214112559938, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2248387447616405, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.279522672121578, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137663.4475527} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.159994125366211, "x": 10.978301282884582, "y": -0.2645041077238206, "z": null, "yaw": 6.268921768264599, "pitch": null, "roll": null}, "v": 2.280259576925152, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36600881622784637, "steering_wheel_angle": 0.3588580072642818, "front_wheel_angle": 0.01655848091756134, "heading_rate": 0.014750424182661311, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137663.4675527} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2572214112559938, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2248387447616405, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.279356660516787, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137663.4675527} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137663.4775527, "x": 15.229053056766126, "y": 4.732007770821679, "z": null, "yaw": -0.013477736055211294, "pitch": null, "roll": null}, "v": 2.279273773711444, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3659145780408603, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.01643619376890892, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137663.4875526} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2542425484132582, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1294283323185355, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2791909661345353, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137663.4875526} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.269994020462036, "x": 11.229053056766126, "y": -0.2679922291783212, "z": null, "yaw": 6.269707571124375, "pitch": null, "roll": null}, "v": 2.279273773711444, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3659145780408603, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.01643619376890892, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137663.5075526} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25565387518152416, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1294283323185355, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.278653408452724, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137663.5075526} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.269994020462036, "x": 11.229053056766126, "y": -0.2679922291783212, "z": null, "yaw": 6.269707571124375, "pitch": null, "roll": null}, "v": 2.279273773711444, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3659145780408603, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.01643619376890892, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137663.5275526} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25565387518152416, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1294283323185355, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2782932093764896, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137663.5275526} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.269994020462036, "x": 11.229053056766126, "y": -0.2679922291783212, "z": null, "yaw": 6.269707571124375, "pitch": null, "roll": null}, "v": 2.279273773711444, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3659145780408603, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.01643619376890892, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137663.5475526} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25565387518152416, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1294283323185355, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.27793369843898, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137663.5475526} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.269994020462036, "x": 11.229053056766126, "y": -0.2679922291783212, "z": null, "yaw": 6.269707571124375, "pitch": null, "roll": null}, "v": 2.279273773711444, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3659145780408603, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.01643619376890892, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137663.5675526} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25565387518152416, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1294283323185355, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.277574874273872, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137663.5675526} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137663.5875525, "x": 15.479647274835985, "y": 4.728720477968958, "z": null, "yaw": -0.012684509135552594, "pitch": null, "roll": null}, "v": 2.27721673551775, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36571799738110866, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.0164213601500907, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137663.5875525} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25810131805896164, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1662302803229376, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.27721673551775, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137663.5875525} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.379993915557861, "x": 11.479647274835985, "y": -0.2712795220310422, "z": null, "yaw": 6.270500798044034, "pitch": null, "roll": null}, "v": 2.27721673551775, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36571799738110866, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.0164213601500907, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137663.6075525} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25692089090595444, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1662302803229376, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2771650650233437, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137663.6075525} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.379993915557861, "x": 11.479647274835985, "y": -0.2712795220310422, "z": null, "yaw": 6.270500798044034, "pitch": null, "roll": null}, "v": 2.27721673551775, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36571799738110866, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.0164213601500907, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137663.6275525} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25692089090595444, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1662302803229376, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2769660103110705, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137663.6275525} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.379993915557861, "x": 11.479647274835985, "y": -0.2712795220310422, "z": null, "yaw": 6.270500798044034, "pitch": null, "roll": null}, "v": 2.27721673551775, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36571799738110866, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.0164213601500907, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137663.6475525} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25692089090595444, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1662302803229376, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.276767335772103, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137663.6475525} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.379993915557861, "x": 11.479647274835985, "y": -0.2712795220310422, "z": null, "yaw": 6.270500798044034, "pitch": null, "roll": null}, "v": 2.27721673551775, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36571799738110866, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.0164213601500907, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137663.6675525} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25692089090595444, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1662302803229376, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2765690406645698, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137663.6675525} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.379993915557861, "x": 11.479647274835985, "y": -0.2712795220310422, "z": null, "yaw": 6.270500798044034, "pitch": null, "roll": null}, "v": 2.27721673551775, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36571799738110866, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.0164213601500907, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137663.6875525} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25692089090595444, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1662302803229376, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2763711242481066, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137663.6875525} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137663.6975524, "x": 15.73008141400305, "y": 4.725633976402989, "z": null, "yaw": -0.011891282215893893, "pitch": null, "roll": null}, "v": 2.2762723078180738, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3656277715842979, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016414549736681112, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137663.7075524} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2589762912280884, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2057924661235522, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.276173585783853, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137663.7075524} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.4899938106536865, "x": 11.73008141400305, "y": -0.2743660235970111, "z": null, "yaw": 6.271294024963693, "pitch": null, "roll": null}, "v": 2.2762723078180738, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3656277715842979, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016414549736681112, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137663.7275524} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.257990654331137, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2057924661235522, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.27623322686374, "gear": 1, "accelerator_pedal_position": 0.2589762912280884, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137663.7275524} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.4899938106536865, "x": 11.73008141400305, "y": -0.2743660235970111, "z": null, "yaw": 6.271294024963693, "pitch": null, "roll": null}, "v": 2.2762723078180738, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3656277715842979, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016414549736681112, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137663.7475524} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.257990654331137, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2057924661235522, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.276169608287787, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137663.7475524} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.4899938106536865, "x": 11.73008141400305, "y": -0.2743660235970111, "z": null, "yaw": 6.271294024963693, "pitch": null, "roll": null}, "v": 2.2762723078180738, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3656277715842979, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016414549736681112, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137663.7675524} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.257990654331137, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2057924661235522, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.276106111195432, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137663.7675524} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.4899938106536865, "x": 11.73008141400305, "y": -0.2743660235970111, "z": null, "yaw": 6.271294024963693, "pitch": null, "roll": null}, "v": 2.2762723078180738, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3656277715842979, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016414549736681112, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137663.7875524} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.257990654331137, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2057924661235522, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2760427353530823, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137663.7875524} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137663.8075523, "x": 15.980441020380663, "y": 4.7227470189732745, "z": null, "yaw": -0.011098055296235192, "pitch": null, "roll": null}, "v": 2.275979480527601, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36559979998420694, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.01641243811404826, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137663.8075523} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2579697438611535, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1658627649502817, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.275979480527601, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137663.8075523} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.599993705749512, "x": 11.980441020380663, "y": -0.27725298102672546, "z": null, "yaw": 6.2720872518833515, "pitch": null, "roll": null}, "v": 2.275979480527601, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36559979998420694, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.01641243811404826, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137663.8275523} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25797757006219113, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1658627649502817, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2759137339258984, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137663.8275523} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.599993705749512, "x": 11.980441020380663, "y": -0.27725298102672546, "z": null, "yaw": 6.2720872518833515, "pitch": null, "roll": null}, "v": 2.275979480527601, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36559979998420694, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.01641243811404826, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137663.8475523} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25797757006219113, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1658627649502817, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2758168153477984, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137663.8475523} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.599993705749512, "x": 11.980441020380663, "y": -0.27725298102672546, "z": null, "yaw": 6.2720872518833515, "pitch": null, "roll": null}, "v": 2.275979480527601, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36559979998420694, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.01641243811404826, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137663.8675523} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25797757006219113, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1658627649502817, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2757523571534786, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137663.8675523} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.599993705749512, "x": 11.980441020380663, "y": -0.27725298102672546, "z": null, "yaw": 6.2720872518833515, "pitch": null, "roll": null}, "v": 2.275979480527601, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36559979998420694, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.01641243811404826, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137663.8875523} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25797757006219113, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1658627649502817, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.275688022035317, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137663.8875523} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.599993705749512, "x": 11.980441020380663, "y": -0.27725298102672546, "z": null, "yaw": 6.2720872518833515, "pitch": null, "roll": null}, "v": 2.275979480527601, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36559979998420694, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.01641243811404826, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137663.9075522} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25797757006219113, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1658627649502817, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.275655900555823, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137663.9075522} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137663.9175522, "x": 16.230766463994954, "y": 4.720059044254816, "z": null, "yaw": -0.01030482837657649, "pitch": null, "roll": null}, "v": 2.2756238097566586, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.365565827723147, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016409873317411467, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137663.9275522} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2597713626214361, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2000776959197446, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2755597200813082, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137663.9275522} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.709993600845337, "x": 12.230766463994954, "y": -0.2799409557451842, "z": null, "yaw": 6.2728804788030095, "pitch": null, "roll": null}, "v": 2.2756238097566586, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.365565827723147, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016409873317411467, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137663.9475522} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25891458689771796, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2000776959197446, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.275639833181142, "gear": 1, "accelerator_pedal_position": 0.2597713626214361, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137663.9475522} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.709993600845337, "x": 12.230766463994954, "y": -0.2799409557451842, "z": null, "yaw": 6.2728804788030095, "pitch": null, "roll": null}, "v": 2.2756238097566586, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.365565827723147, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016409873317411467, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137663.9675522} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25891458689771796, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2000776959197446, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2757192216048243, "gear": 1, "accelerator_pedal_position": 0.25891458689771796, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137663.9675522} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.709993600845337, "x": 12.230766463994954, "y": -0.2799409557451842, "z": null, "yaw": 6.2728804788030095, "pitch": null, "roll": null}, "v": 2.2756238097566586, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.365565827723147, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016409873317411467, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137663.9875522} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25891458689771796, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2000776959197446, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.275745633877571, "gear": 1, "accelerator_pedal_position": 0.25891458689771796, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137663.9875522} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.709993600845337, "x": 12.230766463994954, "y": -0.2799409557451842, "z": null, "yaw": 6.2728804788030095, "pitch": null, "roll": null}, "v": 2.2756238097566586, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.365565827723147, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016409873317411467, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137664.0075521} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25891458689771796, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2000776959197446, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2757983827642527, "gear": 1, "accelerator_pedal_position": 0.25891458689771796, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137664.0075521} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137664.0275521, "x": 16.48108042237343, "y": 4.717569774412788, "z": null, "yaw": -0.00951160145691779, "pitch": null, "roll": null}, "v": 2.275851030932118, "accelerator_pedal_position": 0.25891458689771796, "brake_pedal_position": 0.0, "acceleration": 0.002628637414183399, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016411511844257747, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137664.0275521} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2591875715430084, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.144110436692102, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.275851030932118, "gear": 1, "accelerator_pedal_position": 0.25891458689771796, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137664.0275521} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.819993495941162, "x": 12.48108042237343, "y": -0.28243022558721176, "z": null, "yaw": 6.273673705722668, "pitch": null, "roll": null}, "v": 2.275851030932118, "accelerator_pedal_position": 0.25891458689771796, "brake_pedal_position": 0.0, "acceleration": 0.002628637414183399, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016411511844257747, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137664.047552} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25905923235054246, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.144110436692102, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2759376853562387, "gear": 1, "accelerator_pedal_position": 0.2591875715430084, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137664.047552} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.819993495941162, "x": 12.48108042237343, "y": -0.28243022558721176, "z": null, "yaw": 6.273673705722668, "pitch": null, "roll": null}, "v": 2.275851030932118, "accelerator_pedal_position": 0.25891458689771796, "brake_pedal_position": 0.0, "acceleration": 0.002628637414183399, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016411511844257747, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137664.067552} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25905923235054246, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.144110436692102, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.276043316227449, "gear": 1, "accelerator_pedal_position": 0.25905923235054246, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137664.067552} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.819993495941162, "x": 12.48108042237343, "y": -0.28243022558721176, "z": null, "yaw": 6.273673705722668, "pitch": null, "roll": null}, "v": 2.275851030932118, "accelerator_pedal_position": 0.25891458689771796, "brake_pedal_position": 0.0, "acceleration": 0.002628637414183399, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016411511844257747, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137664.087552} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25905923235054246, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.144110436692102, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.27607845927351, "gear": 1, "accelerator_pedal_position": 0.25905923235054246, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137664.087552} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.819993495941162, "x": 12.48108042237343, "y": -0.28243022558721176, "z": null, "yaw": 6.273673705722668, "pitch": null, "roll": null}, "v": 2.275851030932118, "accelerator_pedal_position": 0.25891458689771796, "brake_pedal_position": 0.0, "acceleration": 0.002628637414183399, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016411511844257747, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137664.107552} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25905923235054246, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.144110436692102, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.276148644690254, "gear": 1, "accelerator_pedal_position": 0.25905923235054246, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137664.107552} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.819993495941162, "x": 12.48108042237343, "y": -0.28243022558721176, "z": null, "yaw": 6.273673705722668, "pitch": null, "roll": null}, "v": 2.275851030932118, "accelerator_pedal_position": 0.25891458689771796, "brake_pedal_position": 0.0, "acceleration": 0.002628637414183399, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016411511844257747, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137664.127552} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25905923235054246, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.144110436692102, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.276218696085139, "gear": 1, "accelerator_pedal_position": 0.25905923235054246, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137664.127552} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137664.137552, "x": 16.73143443836285, "y": 4.7152787127727915, "z": null, "yaw": -0.008718374537259089, "pitch": null, "roll": null}, "v": 2.2762536716037647, "accelerator_pedal_position": 0.25905923235054246, "brake_pedal_position": 0.0, "acceleration": 0.003494210835805811, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.0164144153480732, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137664.147552} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2591787284647373, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0992151644155543, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2762886137121225, "gear": 1, "accelerator_pedal_position": 0.25905923235054246, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137664.147552} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.929993391036987, "x": 12.73143443836285, "y": -0.28472128722720846, "z": null, "yaw": 6.274466932642327, "pitch": null, "roll": null}, "v": 2.2762536716037647, "accelerator_pedal_position": 0.25905923235054246, "brake_pedal_position": 0.0, "acceleration": 0.003494210835805811, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.0164144153480732, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137664.167552} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25912475586214234, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0992151644155543, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.276373327704557, "gear": 1, "accelerator_pedal_position": 0.2591787284647373, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137664.167552} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.929993391036987, "x": 12.73143443836285, "y": -0.28472128722720846, "z": null, "yaw": 6.274466932642327, "pitch": null, "roll": null}, "v": 2.2762536716037647, "accelerator_pedal_position": 0.25905923235054246, "brake_pedal_position": 0.0, "acceleration": 0.003494210835805811, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.0164144153480732, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137664.187552} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25912475586214234, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0992151644155543, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2764511365718723, "gear": 1, "accelerator_pedal_position": 0.25912475586214234, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137664.187552} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.929993391036987, "x": 12.73143443836285, "y": -0.28472128722720846, "z": null, "yaw": 6.274466932642327, "pitch": null, "roll": null}, "v": 2.2762536716037647, "accelerator_pedal_position": 0.25905923235054246, "brake_pedal_position": 0.0, "acceleration": 0.003494210835805811, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.0164144153480732, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137664.207552} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25912475586214234, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0992151644155543, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2765675713573676, "gear": 1, "accelerator_pedal_position": 0.25912475586214234, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137664.207552} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.929993391036987, "x": 12.73143443836285, "y": -0.28472128722720846, "z": null, "yaw": 6.274466932642327, "pitch": null, "roll": null}, "v": 2.2762536716037647, "accelerator_pedal_position": 0.25905923235054246, "brake_pedal_position": 0.0, "acceleration": 0.003494210835805811, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.0164144153480732, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137664.227552} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25912475586214234, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0992151644155543, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.276645009280813, "gear": 1, "accelerator_pedal_position": 0.25912475586214234, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137664.227552} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137664.247552, "x": 16.98183516261841, "y": 4.713185863769836, "z": null, "yaw": -0.007925147617600388, "pitch": null, "roll": null}, "v": 2.276683672767728, "accelerator_pedal_position": 0.25912475586214234, "brake_pedal_position": 0.0, "acceleration": 0.003862655041531715, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.0164175161526072, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137664.247552} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26069381081784354, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1230763295197093, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.276683672767728, "gear": 1, "accelerator_pedal_position": 0.25912475586214234, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137664.247552} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.0399932861328125, "x": 12.98183516261841, "y": -0.2868141362301637, "z": null, "yaw": 6.275260159561986, "pitch": null, "roll": null}, "v": 2.276683672767728, "accelerator_pedal_position": 0.25912475586214234, "brake_pedal_position": 0.0, "acceleration": 0.003862655041531715, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.0164175161526072, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137664.267552} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25994977115234535, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1230763295197093, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.277093358576532, "gear": 1, "accelerator_pedal_position": 0.26069381081784354, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137664.267552} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.0399932861328125, "x": 12.98183516261841, "y": -0.2868141362301637, "z": null, "yaw": 6.275260159561986, "pitch": null, "roll": null}, "v": 2.276683672767728, "accelerator_pedal_position": 0.25912475586214234, "brake_pedal_position": 0.0, "acceleration": 0.003862655041531715, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.0164175161526072, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137664.2875519} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25994977115234535, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1230763295197093, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2771831571778978, "gear": 1, "accelerator_pedal_position": 0.25994977115234535, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137664.2875519} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.0399932861328125, "x": 12.98183516261841, "y": -0.2868141362301637, "z": null, "yaw": 6.275260159561986, "pitch": null, "roll": null}, "v": 2.276683672767728, "accelerator_pedal_position": 0.25912475586214234, "brake_pedal_position": 0.0, "acceleration": 0.003862655041531715, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.0164175161526072, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137664.3075519} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25994977115234535, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1230763295197093, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.277452038526969, "gear": 1, "accelerator_pedal_position": 0.25994977115234535, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137664.3075519} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.0399932861328125, "x": 12.98183516261841, "y": -0.2868141362301637, "z": null, "yaw": 6.275260159561986, "pitch": null, "roll": null}, "v": 2.276683672767728, "accelerator_pedal_position": 0.25912475586214234, "brake_pedal_position": 0.0, "acceleration": 0.003862655041531715, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.0164175161526072, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137664.3275518} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25994977115234535, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1230763295197093, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.277541494425948, "gear": 1, "accelerator_pedal_position": 0.25994977115234535, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137664.3275518} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.0399932861328125, "x": 12.98183516261841, "y": -0.2868141362301637, "z": null, "yaw": 6.275260159561986, "pitch": null, "roll": null}, "v": 2.276683672767728, "accelerator_pedal_position": 0.25912475586214234, "brake_pedal_position": 0.0, "acceleration": 0.003862655041531715, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.0164175161526072, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137664.3475518} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25994977115234535, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1230763295197093, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.277809349592784, "gear": 1, "accelerator_pedal_position": 0.25994977115234535, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137664.3475518} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137664.3575518, "x": 17.23232516305435, "y": 4.711290981478269, "z": null, "yaw": -0.007131920697941687, "pitch": null, "roll": null}, "v": 2.277809349592784, "accelerator_pedal_position": 0.25994977115234535, "brake_pedal_position": 0.0, "acceleration": 0.008911447891596147, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.01642563358133875, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137664.3675518} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2602656154387176, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0664167686918649, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.277987493395424, "gear": 1, "accelerator_pedal_position": 0.25994977115234535, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137664.3675518} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.149993181228638, "x": 13.232325163054352, "y": -0.2887090185217307, "z": null, "yaw": 6.276053386481644, "pitch": null, "roll": null}, "v": 2.277809349592784, "accelerator_pedal_position": 0.25994977115234535, "brake_pedal_position": 0.0, "acceleration": 0.008911447891596147, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.01642563358133875, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137664.3875518} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26012340781902177, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0664167686918649, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2782047585680223, "gear": 1, "accelerator_pedal_position": 0.2602656154387176, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137664.3875518} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.149993181228638, "x": 13.232325163054352, "y": -0.2887090185217307, "z": null, "yaw": 6.276053386481644, "pitch": null, "roll": null}, "v": 2.277809349592784, "accelerator_pedal_position": 0.25994977115234535, "brake_pedal_position": 0.0, "acceleration": 0.008911447891596147, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.01642563358133875, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137664.4075518} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26012340781902177, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0664167686918649, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.278304347485231, "gear": 1, "accelerator_pedal_position": 0.26012340781902177, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137664.4075518} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.149993181228638, "x": 13.232325163054352, "y": -0.2887090185217307, "z": null, "yaw": 6.276053386481644, "pitch": null, "roll": null}, "v": 2.277809349592784, "accelerator_pedal_position": 0.25994977115234535, "brake_pedal_position": 0.0, "acceleration": 0.008911447891596147, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.01642563358133875, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137664.4275517} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26012340781902177, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0664167686918649, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.278503239891901, "gear": 1, "accelerator_pedal_position": 0.26012340781902177, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137664.4275517} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.149993181228638, "x": 13.232325163054352, "y": -0.2887090185217307, "z": null, "yaw": 6.276053386481644, "pitch": null, "roll": null}, "v": 2.277809349592784, "accelerator_pedal_position": 0.25994977115234535, "brake_pedal_position": 0.0, "acceleration": 0.008911447891596147, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.01642563358133875, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137664.4475517} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26012340781902177, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0664167686918649, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.278701752320982, "gear": 1, "accelerator_pedal_position": 0.26012340781902177, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137664.4475517} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137664.4675517, "x": 17.482932539481194, "y": 4.709594009977286, "z": null, "yaw": -0.006338693778282986, "pitch": null, "roll": null}, "v": 2.2788998854826534, "accelerator_pedal_position": 0.26012340781902177, "brake_pedal_position": 0.0, "acceleration": 0.009892457714224812, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016433497603381465, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137664.4675517} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26155899952371253, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0931011912845663, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2788998854826534, "gear": 1, "accelerator_pedal_position": 0.26012340781902177, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137664.4675517} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26155899952371253, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0931011912845663, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.279088534541339, "gear": 1, "accelerator_pedal_position": 0.26155899952371253, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137664.4775517} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.259993076324463, "x": 13.482932539481194, "y": -0.2904059900227143, "z": null, "yaw": 6.276846613401303, "pitch": null, "roll": null}, "v": 2.2788998854826534, "accelerator_pedal_position": 0.26012340781902177, "brake_pedal_position": 0.0, "acceleration": 0.009892457714224812, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016433497603381465, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137664.4975517} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2608833246101667, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0931011912845663, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2794652918922877, "gear": 1, "accelerator_pedal_position": 0.26155899952371253, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137664.4975517} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.259993076324463, "x": 13.482932539481194, "y": -0.2904059900227143, "z": null, "yaw": 6.276846613401303, "pitch": null, "roll": null}, "v": 2.2788998854826534, "accelerator_pedal_position": 0.26012340781902177, "brake_pedal_position": 0.0, "acceleration": 0.009892457714224812, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016433497603381465, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137664.5075517} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2608833246101667, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0931011912845663, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.279611170832783, "gear": 1, "accelerator_pedal_position": 0.2608833246101667, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137664.5075517} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.259993076324463, "x": 13.482932539481194, "y": -0.2904059900227143, "z": null, "yaw": 6.276846613401303, "pitch": null, "roll": null}, "v": 2.2788998854826534, "accelerator_pedal_position": 0.26012340781902177, "brake_pedal_position": 0.0, "acceleration": 0.009892457714224812, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016433497603381465, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137664.5275517} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2608833246101667, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0931011912845663, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2799025105024375, "gear": 1, "accelerator_pedal_position": 0.2608833246101667, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137664.5275517} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.259993076324463, "x": 13.482932539481194, "y": -0.2904059900227143, "z": null, "yaw": 6.276846613401303, "pitch": null, "roll": null}, "v": 2.2788998854826534, "accelerator_pedal_position": 0.26012340781902177, "brake_pedal_position": 0.0, "acceleration": 0.009892457714224812, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016433497603381465, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137664.5475516} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2608833246101667, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0931011912845663, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2801932934167435, "gear": 1, "accelerator_pedal_position": 0.2608833246101667, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137664.5475516} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.259993076324463, "x": 13.482932539481194, "y": -0.2904059900227143, "z": null, "yaw": 6.276846613401303, "pitch": null, "roll": null}, "v": 2.2788998854826534, "accelerator_pedal_position": 0.26012340781902177, "brake_pedal_position": 0.0, "acceleration": 0.009892457714224812, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016433497603381465, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137664.5675516} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2608833246101667, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0931011912845663, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.280628426124922, "gear": 1, "accelerator_pedal_position": 0.2608833246101667, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137664.5675516} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137664.5775516, "x": 17.733698697701737, "y": 4.7080948902467865, "z": null, "yaw": -0.005545466858624285, "pitch": null, "roll": null}, "v": 2.280628426124922, "accelerator_pedal_position": 0.2608833246101667, "brake_pedal_position": 0.0, "acceleration": 0.014476697326805454, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016445962375828477, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137664.5875516} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26150649157606126, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.078644395812885, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2807731930981903, "gear": 1, "accelerator_pedal_position": 0.2608833246101667, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137664.5875516} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.369992971420288, "x": 13.733698697701737, "y": -0.2919051097532135, "z": null, "yaw": 6.277639840320962, "pitch": null, "roll": null}, "v": 2.280628426124922, "accelerator_pedal_position": 0.2608833246101667, "brake_pedal_position": 0.0, "acceleration": 0.014476697326805454, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016445962375828477, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137664.6075516} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26122233499946385, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.078644395812885, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.281140170549545, "gear": 1, "accelerator_pedal_position": 0.26150649157606126, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137664.6075516} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.369992971420288, "x": 13.733698697701737, "y": -0.2919051097532135, "z": null, "yaw": 6.277639840320962, "pitch": null, "roll": null}, "v": 2.280628426124922, "accelerator_pedal_position": 0.2608833246101667, "brake_pedal_position": 0.0, "acceleration": 0.014476697326805454, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016445962375828477, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137664.6275516} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26122233499946385, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.078644395812885, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2814709439326104, "gear": 1, "accelerator_pedal_position": 0.26122233499946385, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137664.6275516} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.369992971420288, "x": 13.733698697701737, "y": -0.2919051097532135, "z": null, "yaw": 6.277639840320962, "pitch": null, "roll": null}, "v": 2.280628426124922, "accelerator_pedal_position": 0.2608833246101667, "brake_pedal_position": 0.0, "acceleration": 0.014476697326805454, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016445962375828477, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137664.6475515} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26122233499946385, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.078644395812885, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2818010849957755, "gear": 1, "accelerator_pedal_position": 0.26122233499946385, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137664.6475515} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.369992971420288, "x": 13.733698697701737, "y": -0.2919051097532135, "z": null, "yaw": 6.277639840320962, "pitch": null, "roll": null}, "v": 2.280628426124922, "accelerator_pedal_position": 0.2608833246101667, "brake_pedal_position": 0.0, "acceleration": 0.014476697326805454, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016445962375828477, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137664.6675515} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26122233499946385, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.078644395812885, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2821305949042325, "gear": 1, "accelerator_pedal_position": 0.26122233499946385, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137664.6675515} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137664.6875515, "x": 17.98465635737784, "y": 4.706793699215699, "z": null, "yaw": -0.004752239938965584, "pitch": null, "roll": null}, "v": 2.2824594748211955, "accelerator_pedal_position": 0.26122233499946385, "brake_pedal_position": 0.0, "acceleration": 0.0164204074635787, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016459166349620205, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137664.6875515} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2618623895526985, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0629401335776874, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2824594748211955, "gear": 1, "accelerator_pedal_position": 0.26122233499946385, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137664.6875515} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.479992866516113, "x": 13.98465635737784, "y": -0.2932063007843011, "z": null, "yaw": 6.278433067240621, "pitch": null, "roll": null}, "v": 2.2824594748211955, "accelerator_pedal_position": 0.26122233499946385, "brake_pedal_position": 0.0, "acceleration": 0.0164204074635787, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016459166349620205, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137664.7075515} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2615709428424314, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0629401335776874, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.282867694462648, "gear": 1, "accelerator_pedal_position": 0.2618623895526985, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137664.7075515} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.479992866516113, "x": 13.98465635737784, "y": -0.2932063007843011, "z": null, "yaw": 6.278433067240621, "pitch": null, "roll": null}, "v": 2.2824594748211955, "accelerator_pedal_position": 0.26122233499946385, "brake_pedal_position": 0.0, "acceleration": 0.0164204074635787, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016459166349620205, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137664.7275515} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2615709428424314, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0629401335776874, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.283238720096391, "gear": 1, "accelerator_pedal_position": 0.2615709428424314, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137664.7275515} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.479992866516113, "x": 13.98465635737784, "y": -0.2932063007843011, "z": null, "yaw": 6.278433067240621, "pitch": null, "roll": null}, "v": 2.2824594748211955, "accelerator_pedal_position": 0.26122233499946385, "brake_pedal_position": 0.0, "acceleration": 0.0164204074635787, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016459166349620205, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137664.7475514} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2615709428424314, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0629401335776874, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2836090362017756, "gear": 1, "accelerator_pedal_position": 0.2615709428424314, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137664.7475514} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.479992866516113, "x": 13.98465635737784, "y": -0.2932063007843011, "z": null, "yaw": 6.278433067240621, "pitch": null, "roll": null}, "v": 2.2824594748211955, "accelerator_pedal_position": 0.26122233499946385, "brake_pedal_position": 0.0, "acceleration": 0.0164204074635787, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016459166349620205, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137664.7675514} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2615709428424314, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0629401335776874, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.284163182841786, "gear": 1, "accelerator_pedal_position": 0.2615709428424314, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137664.7675514} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.479992866516113, "x": 13.98465635737784, "y": -0.2932063007843011, "z": null, "yaw": 6.278433067240621, "pitch": null, "roll": null}, "v": 2.2824594748211955, "accelerator_pedal_position": 0.26122233499946385, "brake_pedal_position": 0.0, "acceleration": 0.0164204074635787, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016459166349620205, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137664.7875514} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2615709428424314, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0629401335776874, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.284347545033432, "gear": 1, "accelerator_pedal_position": 0.2615709428424314, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137664.7875514} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137664.7975514, "x": 18.23582992042916, "y": 4.705690632517502, "z": null, "yaw": -0.003959013019306883, "pitch": null, "roll": null}, "v": 2.284531730817917, "accelerator_pedal_position": 0.2615709428424314, "brake_pedal_position": 0.0, "acceleration": 0.0184009539331611, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016474109706356786, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137664.8075514} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2623588491371512, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0176900661903205, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2849488179567183, "gear": 1, "accelerator_pedal_position": 0.2623588491371512, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137664.8075514} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.5899927616119385, "x": 14.235829920429161, "y": -0.2943093674824979, "z": null, "yaw": 6.27922629416028, "pitch": null, "roll": null}, "v": 2.284531730817917, "accelerator_pedal_position": 0.2615709428424314, "brake_pedal_position": 0.0, "acceleration": 0.0184009539331611, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016474109706356786, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137664.8275514} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2619987604397066, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0176900661903205, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.285181672508744, "gear": 1, "accelerator_pedal_position": 0.2623588491371512, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137664.8275514} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.5899927616119385, "x": 14.235829920429161, "y": -0.2943093674824979, "z": null, "yaw": 6.27922629416028, "pitch": null, "roll": null}, "v": 2.284531730817917, "accelerator_pedal_position": 0.2615709428424314, "brake_pedal_position": 0.0, "acceleration": 0.0184009539331611, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016474109706356786, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137664.8475513} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2619987604397066, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0176900661903205, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.285601723733136, "gear": 1, "accelerator_pedal_position": 0.2619987604397066, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137664.8475513} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.5899927616119385, "x": 14.235829920429161, "y": -0.2943093674824979, "z": null, "yaw": 6.27922629416028, "pitch": null, "roll": null}, "v": 2.284531730817917, "accelerator_pedal_position": 0.2615709428424314, "brake_pedal_position": 0.0, "acceleration": 0.0184009539331611, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016474109706356786, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137664.8675513} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2619987604397066, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0176900661903205, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2860209712808186, "gear": 1, "accelerator_pedal_position": 0.2619987604397066, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137664.8675513} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.5899927616119385, "x": 14.235829920429161, "y": -0.2943093674824979, "z": null, "yaw": 6.27922629416028, "pitch": null, "roll": null}, "v": 2.284531730817917, "accelerator_pedal_position": 0.2615709428424314, "brake_pedal_position": 0.0, "acceleration": 0.0184009539331611, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016474109706356786, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137664.8875513} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2619987604397066, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0176900661903205, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.286439416619179, "gear": 1, "accelerator_pedal_position": 0.2619987604397066, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137664.8875513} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137664.9075513, "x": 18.487243505710737, "y": 4.704785944945837, "z": null, "yaw": -0.0031657860996481824, "pitch": null, "roll": null}, "v": 2.2868570612131993, "accelerator_pedal_position": 0.2619987604397066, "brake_pedal_position": 0.0, "acceleration": 0.020852247503299448, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016490878021508042, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137664.9075513} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2621981410668454, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9821633040161931, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2868570612131993, "gear": 1, "accelerator_pedal_position": 0.2619987604397066, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137664.9075513} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.699992656707764, "x": 14.487243505710737, "y": -0.29521405505416265, "z": null, "yaw": 6.280019521079938, "pitch": null, "roll": null}, "v": 2.2868570612131993, "accelerator_pedal_position": 0.2619987604397066, "brake_pedal_position": 0.0, "acceleration": 0.020852247503299448, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016490878021508042, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137664.9275513} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2621201553130854, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9821633040161931, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.287298817173236, "gear": 1, "accelerator_pedal_position": 0.2621981410668454, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137664.9275513} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.699992656707764, "x": 14.487243505710737, "y": -0.29521405505416265, "z": null, "yaw": 6.280019521079938, "pitch": null, "roll": null}, "v": 2.2868570612131993, "accelerator_pedal_position": 0.2619987604397066, "brake_pedal_position": 0.0, "acceleration": 0.020852247503299448, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016490878021508042, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137664.9475513} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2621201553130854, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9821633040161931, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2877299840783913, "gear": 1, "accelerator_pedal_position": 0.2621201553130854, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137664.9475513} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.699992656707764, "x": 14.487243505710737, "y": -0.29521405505416265, "z": null, "yaw": 6.280019521079938, "pitch": null, "roll": null}, "v": 2.2868570612131993, "accelerator_pedal_position": 0.2619987604397066, "brake_pedal_position": 0.0, "acceleration": 0.020852247503299448, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016490878021508042, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137664.9675512} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2621201553130854, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9821633040161931, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2883751874498075, "gear": 1, "accelerator_pedal_position": 0.2621201553130854, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137664.9675512} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.699992656707764, "x": 14.487243505710737, "y": -0.29521405505416265, "z": null, "yaw": 6.280019521079938, "pitch": null, "roll": null}, "v": 2.2868570612131993, "accelerator_pedal_position": 0.2619987604397066, "brake_pedal_position": 0.0, "acceleration": 0.020852247503299448, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016490878021508042, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137664.9875512} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2621201553130854, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9821633040161931, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.288589843463297, "gear": 1, "accelerator_pedal_position": 0.2621201553130854, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137664.9875512} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.699992656707764, "x": 14.487243505710737, "y": -0.29521405505416265, "z": null, "yaw": 6.280019521079938, "pitch": null, "roll": null}, "v": 2.2868570612131993, "accelerator_pedal_position": 0.2619987604397066, "brake_pedal_position": 0.0, "acceleration": 0.020852247503299448, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016490878021508042, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137665.0075512} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2621201553130854, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9821633040161931, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.289018538952012, "gear": 1, "accelerator_pedal_position": 0.2621201553130854, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137665.0075512} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137665.0175512, "x": 18.738916227554128, "y": 4.70407996074217, "z": null, "yaw": -0.0023725591799894814, "pitch": null, "roll": null}, "v": 2.2892325788024372, "accelerator_pedal_position": 0.2621201553130854, "brake_pedal_position": 0.0, "acceleration": 0.021383483768157352, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016508008244234464, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137665.0275512} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2628360770017607, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9619593565774746, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.289446413640119, "gear": 1, "accelerator_pedal_position": 0.2621201553130854, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137665.0275512} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.809992551803589, "x": 14.738916227554128, "y": -0.2959200392578296, "z": null, "yaw": 6.2808127479995965, "pitch": null, "roll": null}, "v": 2.2892325788024372, "accelerator_pedal_position": 0.2621201553130854, "brake_pedal_position": 0.0, "acceleration": 0.021383483768157352, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016508008244234464, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137665.0475512} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2625124936888435, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9619593565774746, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.289962916374081, "gear": 1, "accelerator_pedal_position": 0.2628360770017607, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137665.0475512} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.809992551803589, "x": 14.738916227554128, "y": -0.2959200392578296, "z": null, "yaw": 6.2808127479995965, "pitch": null, "roll": null}, "v": 2.2892325788024372, "accelerator_pedal_position": 0.2621201553130854, "brake_pedal_position": 0.0, "acceleration": 0.021383483768157352, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016508008244234464, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137665.0675511} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2625124936888435, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9619593565774746, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.29043800145844, "gear": 1, "accelerator_pedal_position": 0.2625124936888435, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137665.0675511} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.809992551803589, "x": 14.738916227554128, "y": -0.2959200392578296, "z": null, "yaw": 6.2808127479995965, "pitch": null, "roll": null}, "v": 2.2892325788024372, "accelerator_pedal_position": 0.2621201553130854, "brake_pedal_position": 0.0, "acceleration": 0.021383483768157352, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016508008244234464, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137665.087551} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2625124936888435, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9619593565774746, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.290912176655197, "gear": 1, "accelerator_pedal_position": 0.2625124936888435, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137665.087551} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.809992551803589, "x": 14.738916227554128, "y": -0.2959200392578296, "z": null, "yaw": 6.2808127479995965, "pitch": null, "roll": null}, "v": 2.2892325788024372, "accelerator_pedal_position": 0.2621201553130854, "brake_pedal_position": 0.0, "acceleration": 0.021383483768157352, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016508008244234464, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137665.107551} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2625124936888435, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9619593565774746, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2913854436170853, "gear": 1, "accelerator_pedal_position": 0.2625124936888435, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137665.107551} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137665.127551, "x": 18.9908629986351, "y": 4.7035730618223885, "z": null, "yaw": -0.0015793322603307805, "pitch": null, "roll": null}, "v": 2.291857803994186, "accelerator_pedal_position": 0.2625124936888435, "brake_pedal_position": 0.0, "acceleration": 0.023584073418271956, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016526939146891385, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137665.127551} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2631617940122183, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9402426468621877, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.291857803994186, "gear": 1, "accelerator_pedal_position": 0.2625124936888435, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137665.127551} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.919992446899414, "x": 14.990862998635102, "y": -0.29642693817761145, "z": null, "yaw": 6.281605974919255, "pitch": null, "roll": null}, "v": 2.291857803994186, "accelerator_pedal_position": 0.2625124936888435, "brake_pedal_position": 0.0, "acceleration": 0.023584073418271956, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016526939146891385, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137665.147551} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2628717670617966, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9402426468621877, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2924103830803446, "gear": 1, "accelerator_pedal_position": 0.2631617940122183, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137665.147551} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.919992446899414, "x": 14.990862998635102, "y": -0.29642693817761145, "z": null, "yaw": 6.281605974919255, "pitch": null, "roll": null}, "v": 2.291857803994186, "accelerator_pedal_position": 0.2625124936888435, "brake_pedal_position": 0.0, "acceleration": 0.023584073418271956, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016526939146891385, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137665.167551} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2628717670617966, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9402426468621877, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2929256674366374, "gear": 1, "accelerator_pedal_position": 0.2628717670617966, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137665.167551} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.919992446899414, "x": 14.990862998635102, "y": -0.29642693817761145, "z": null, "yaw": 6.281605974919255, "pitch": null, "roll": null}, "v": 2.291857803994186, "accelerator_pedal_position": 0.2625124936888435, "brake_pedal_position": 0.0, "acceleration": 0.023584073418271956, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016526939146891385, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137665.187551} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2628717670617966, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9402426468621877, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2934399644051098, "gear": 1, "accelerator_pedal_position": 0.2628717670617966, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137665.187551} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.919992446899414, "x": 14.990862998635102, "y": -0.29642693817761145, "z": null, "yaw": 6.281605974919255, "pitch": null, "roll": null}, "v": 2.291857803994186, "accelerator_pedal_position": 0.2625124936888435, "brake_pedal_position": 0.0, "acceleration": 0.023584073418271956, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016526939146891385, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137665.207551} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2628717670617966, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9402426468621877, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.293953275772044, "gear": 1, "accelerator_pedal_position": 0.2628717670617966, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137665.207551} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.919992446899414, "x": 14.990862998635102, "y": -0.29642693817761145, "z": null, "yaw": 6.281605974919255, "pitch": null, "roll": null}, "v": 2.291857803994186, "accelerator_pedal_position": 0.2625124936888435, "brake_pedal_position": 0.0, "acceleration": 0.023584073418271956, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016526939146891385, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137665.227551} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2628717670617966, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9402426468621877, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2944656033209077, "gear": 1, "accelerator_pedal_position": 0.2628717670617966, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137665.227551} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137665.237551, "x": 19.24311224793079, "y": 4.703265647280943, "z": null, "yaw": -0.0007861053406720792, "pitch": null, "roll": null}, "v": 2.294721398720127, "accelerator_pedal_position": 0.2628717670617966, "brake_pedal_position": 0.0, "acceleration": 0.025555011222781754, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016547588968924196, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137665.247551} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26346238734375593, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8761166974002482, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.294976948832355, "gear": 1, "accelerator_pedal_position": 0.2628717670617966, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137665.247551} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.02999234199524, "x": 15.243112247930789, "y": -0.29673435271905735, "z": null, "yaw": 6.282399201838914, "pitch": null, "roll": null}, "v": 2.294721398720127, "accelerator_pedal_position": 0.2628717670617966, "brake_pedal_position": 0.0, "acceleration": 0.025555011222781754, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016547588968924196, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137665.267551} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2632020553290764, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8761166974002482, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2955611062173222, "gear": 1, "accelerator_pedal_position": 0.26346238734375593, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137665.267551} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.02999234199524, "x": 15.243112247930789, "y": -0.29673435271905735, "z": null, "yaw": 6.282399201838914, "pitch": null, "roll": null}, "v": 2.294721398720127, "accelerator_pedal_position": 0.2628717670617966, "brake_pedal_position": 0.0, "acceleration": 0.025555011222781754, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016547588968924196, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137665.287551} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2632020553290764, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8761166974002482, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2961116177333505, "gear": 1, "accelerator_pedal_position": 0.2632020553290764, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137665.287551} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.02999234199524, "x": 15.243112247930789, "y": -0.29673435271905735, "z": null, "yaw": 6.282399201838914, "pitch": null, "roll": null}, "v": 2.294721398720127, "accelerator_pedal_position": 0.2628717670617966, "brake_pedal_position": 0.0, "acceleration": 0.025555011222781754, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016547588968924196, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137665.307551} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2632020553290764, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8761166974002482, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2966610736603292, "gear": 1, "accelerator_pedal_position": 0.2632020553290764, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137665.307551} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.02999234199524, "x": 15.243112247930789, "y": -0.29673435271905735, "z": null, "yaw": 6.282399201838914, "pitch": null, "roll": null}, "v": 2.294721398720127, "accelerator_pedal_position": 0.2628717670617966, "brake_pedal_position": 0.0, "acceleration": 0.025555011222781754, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016547588968924196, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137665.327551} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2632020553290764, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8761166974002482, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2972094759016155, "gear": 1, "accelerator_pedal_position": 0.2632020553290764, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137665.327551} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137665.3475509, "x": 19.4956837429954, "y": 4.703158188053778, "z": null, "yaw": 7.121578986622875e-06, "pitch": null, "roll": null}, "v": 2.297756826357611, "accelerator_pedal_position": 0.2632020553290764, "brake_pedal_position": 0.0, "acceleration": 0.02732814015811702, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.01656947790451263, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137665.3475509} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26364022145286353, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8553740070726618, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.297756826357611, "gear": 1, "accelerator_pedal_position": 0.2632020553290764, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137665.3475509} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.139992237091064, "x": 15.4956837429954, "y": -0.29684181194622195, "z": null, "yaw": 7.121578986622875e-06, "pitch": null, "roll": null}, "v": 2.297756826357611, "accelerator_pedal_position": 0.2632020553290764, "brake_pedal_position": 0.0, "acceleration": 0.02732814015811702, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.01656947790451263, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137665.3675508} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2634537554139247, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8553740070726618, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.298357871411983, "gear": 1, "accelerator_pedal_position": 0.26364022145286353, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137665.3675508} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.139992237091064, "x": 15.4956837429954, "y": -0.29684181194622195, "z": null, "yaw": 7.121578986622875e-06, "pitch": null, "roll": null}, "v": 2.297756826357611, "accelerator_pedal_position": 0.2632020553290764, "brake_pedal_position": 0.0, "acceleration": 0.02732814015811702, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.01656947790451263, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137665.3875508} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2634537554139247, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8553740070726618, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.298934466374254, "gear": 1, "accelerator_pedal_position": 0.2634537554139247, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137665.3875508} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.139992237091064, "x": 15.4956837429954, "y": -0.29684181194622195, "z": null, "yaw": 7.121578986622875e-06, "pitch": null, "roll": null}, "v": 2.297756826357611, "accelerator_pedal_position": 0.2632020553290764, "brake_pedal_position": 0.0, "acceleration": 0.02732814015811702, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.01656947790451263, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137665.4075508} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2634537554139247, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8553740070726618, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.299509955084334, "gear": 1, "accelerator_pedal_position": 0.2634537554139247, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137665.4075508} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.139992237091064, "x": 15.4956837429954, "y": -0.29684181194622195, "z": null, "yaw": 7.121578986622875e-06, "pitch": null, "roll": null}, "v": 2.297756826357611, "accelerator_pedal_position": 0.2632020553290764, "brake_pedal_position": 0.0, "acceleration": 0.02732814015811702, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.01656947790451263, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137665.4275508} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2634537554139247, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8553740070726618, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3000843395322614, "gear": 1, "accelerator_pedal_position": 0.2634537554139247, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137665.4275508} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.139992237091064, "x": 15.4956837429954, "y": -0.29684181194622195, "z": null, "yaw": 7.121578986622875e-06, "pitch": null, "roll": null}, "v": 2.297756826357611, "accelerator_pedal_position": 0.2632020553290764, "brake_pedal_position": 0.0, "acceleration": 0.02732814015811702, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.01656947790451263, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137665.4475508} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2634537554139247, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8553740070726618, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.300657621705019, "gear": 1, "accelerator_pedal_position": 0.2634537554139247, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137665.4475508} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137665.4575508, "x": 19.74859767564854, "y": 4.703251202210555, "z": null, "yaw": 0.000800348498645325, "pitch": null, "roll": null}, "v": 2.300943850058306, "accelerator_pedal_position": 0.2634537554139247, "brake_pedal_position": 0.0, "acceleration": 0.028595352822902487, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.01659246002263065, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137665.4675508} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26434868620154994, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.868881930291177, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3012298035865353, "gear": 1, "accelerator_pedal_position": 0.2634537554139247, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137665.4675508} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.24999213218689, "x": 15.74859767564854, "y": -0.2967487977894452, "z": null, "yaw": 0.000800348498645325, "pitch": null, "roll": null}, "v": 2.300943850058306, "accelerator_pedal_position": 0.2634537554139247, "brake_pedal_position": 0.0, "acceleration": 0.028595352822902487, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.01659246002263065, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137665.4875507} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2639458361292884, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.868881930291177, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.301912699793027, "gear": 1, "accelerator_pedal_position": 0.26434868620154994, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137665.4875507} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.24999213218689, "x": 15.74859767564854, "y": -0.2967487977894452, "z": null, "yaw": 0.000800348498645325, "pitch": null, "roll": null}, "v": 2.300943850058306, "accelerator_pedal_position": 0.2634537554139247, "brake_pedal_position": 0.0, "acceleration": 0.028595352822902487, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.01659246002263065, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137665.5075507} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2639458361292884, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.868881930291177, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3025439529160594, "gear": 1, "accelerator_pedal_position": 0.2639458361292884, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137665.5075507} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.24999213218689, "x": 15.74859767564854, "y": -0.2967487977894452, "z": null, "yaw": 0.000800348498645325, "pitch": null, "roll": null}, "v": 2.300943850058306, "accelerator_pedal_position": 0.2634537554139247, "brake_pedal_position": 0.0, "acceleration": 0.028595352822902487, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.01659246002263065, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137665.5275507} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2639458361292884, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.868881930291177, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.303173994012953, "gear": 1, "accelerator_pedal_position": 0.2639458361292884, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137665.5275507} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2639458361292884, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.868881930291177, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3034885607293574, "gear": 1, "accelerator_pedal_position": 0.2639458361292884, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137665.5375507} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.24999213218689, "x": 15.74859767564854, "y": -0.2967487977894452, "z": null, "yaw": 0.000800348498645325, "pitch": null, "roll": null}, "v": 2.300943850058306, "accelerator_pedal_position": 0.2634537554139247, "brake_pedal_position": 0.0, "acceleration": 0.028595352822902487, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.01659246002263065, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137665.5575507} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2639458361292884, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.868881930291177, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.304430448798771, "gear": 1, "accelerator_pedal_position": 0.2639458361292884, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137665.5575507} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137665.5675507, "x": 20.001876213289002, "y": 4.703545260247998, "z": null, "yaw": 0.0015935754183040263, "pitch": null, "roll": null}, "v": 2.304430448798771, "accelerator_pedal_position": 0.2639458361292884, "brake_pedal_position": 0.0, "acceleration": 0.03133595643460485, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.0166176024224396, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137665.5775506} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26438230552039027, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7719776394423095, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.304743808363117, "gear": 1, "accelerator_pedal_position": 0.2639458361292884, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137665.5775506} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.359992027282715, "x": 16.001876213289002, "y": -0.29645473975200165, "z": null, "yaw": 0.0015935754183040263, "pitch": null, "roll": null}, "v": 2.304430448798771, "accelerator_pedal_position": 0.2639458361292884, "brake_pedal_position": 0.0, "acceleration": 0.03133595643460485, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.0166176024224396, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137665.5975506} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26419997911806714, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7719776394423095, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.305763840843876, "gear": 1, "accelerator_pedal_position": 0.26438230552039027, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137665.5975506} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.359992027282715, "x": 16.001876213289002, "y": -0.29645473975200165, "z": null, "yaw": 0.0015935754183040263, "pitch": null, "roll": null}, "v": 2.304430448798771, "accelerator_pedal_position": 0.2639458361292884, "brake_pedal_position": 0.0, "acceleration": 0.03133595643460485, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.0166176024224396, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137665.6175506} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26419997911806714, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7719776394423095, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3064194497824198, "gear": 1, "accelerator_pedal_position": 0.26419997911806714, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137665.6175506} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.359992027282715, "x": 16.001876213289002, "y": -0.29645473975200165, "z": null, "yaw": 0.0015935754183040263, "pitch": null, "roll": null}, "v": 2.304430448798771, "accelerator_pedal_position": 0.2639458361292884, "brake_pedal_position": 0.0, "acceleration": 0.03133595643460485, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.0166176024224396, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137665.6375506} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26419997911806714, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7719776394423095, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3067467816845744, "gear": 1, "accelerator_pedal_position": 0.26419997911806714, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137665.6375506} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.359992027282715, "x": 16.001876213289002, "y": -0.29645473975200165, "z": null, "yaw": 0.0015935754183040263, "pitch": null, "roll": null}, "v": 2.304430448798771, "accelerator_pedal_position": 0.2639458361292884, "brake_pedal_position": 0.0, "acceleration": 0.03133595643460485, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.0166176024224396, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137665.6575506} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26419997911806714, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7719776394423095, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.307726890497632, "gear": 1, "accelerator_pedal_position": 0.26419997911806714, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137665.6575506} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137665.6775506, "x": 20.255544778573626, "y": 4.70404098925448, "z": null, "yaw": 0.002386802337962727, "pitch": null, "roll": null}, "v": 2.3080529654071498, "accelerator_pedal_position": 0.26419997911806714, "brake_pedal_position": 0.0, "acceleration": 0.032576136306314674, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016643724946900296, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137665.6775506} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2649486836211001, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7785150898128251, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3080529654071498, "gear": 1, "accelerator_pedal_position": 0.26419997911806714, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137665.6775506} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.46999192237854, "x": 16.255544778573626, "y": -0.2959590107455199, "z": null, "yaw": 0.002386802337962727, "pitch": null, "roll": null}, "v": 2.3080529654071498, "accelerator_pedal_position": 0.26419997911806714, "brake_pedal_position": 0.0, "acceleration": 0.032576136306314674, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016643724946900296, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137665.6975505} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2646186880782873, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7785150898128251, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3091695571061845, "gear": 1, "accelerator_pedal_position": 0.2649486836211001, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137665.6975505} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.46999192237854, "x": 16.255544778573626, "y": -0.2959590107455199, "z": null, "yaw": 0.002386802337962727, "pitch": null, "roll": null}, "v": 2.3080529654071498, "accelerator_pedal_position": 0.26419997911806714, "brake_pedal_position": 0.0, "acceleration": 0.032576136306314674, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016643724946900296, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137665.7175505} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2646186880782873, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7785150898128251, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.309870933271872, "gear": 1, "accelerator_pedal_position": 0.2646186880782873, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137665.7175505} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.46999192237854, "x": 16.255544778573626, "y": -0.2959590107455199, "z": null, "yaw": 0.002386802337962727, "pitch": null, "roll": null}, "v": 2.3080529654071498, "accelerator_pedal_position": 0.26419997911806714, "brake_pedal_position": 0.0, "acceleration": 0.032576136306314674, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016643724946900296, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137665.7375505} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2646186880782873, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7785150898128251, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.310570960724245, "gear": 1, "accelerator_pedal_position": 0.2646186880782873, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137665.7375505} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.46999192237854, "x": 16.255544778573626, "y": -0.2959590107455199, "z": null, "yaw": 0.002386802337962727, "pitch": null, "roll": null}, "v": 2.3080529654071498, "accelerator_pedal_position": 0.26419997911806714, "brake_pedal_position": 0.0, "acceleration": 0.032576136306314674, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016643724946900296, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137665.7575505} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2646186880782873, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7785150898128251, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.311269641860894, "gear": 1, "accelerator_pedal_position": 0.2646186880782873, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137665.7575505} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.46999192237854, "x": 16.255544778573626, "y": -0.2959590107455199, "z": null, "yaw": 0.002386802337962727, "pitch": null, "roll": null}, "v": 2.3080529654071498, "accelerator_pedal_position": 0.26419997911806714, "brake_pedal_position": 0.0, "acceleration": 0.032576136306314674, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016643724946900296, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137665.7775505} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2646186880782873, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7785150898128251, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.31196697907593, "gear": 1, "accelerator_pedal_position": 0.2646186880782873, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137665.7775505} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137665.7875504, "x": 20.509628190719855, "y": 4.704739077799564, "z": null, "yaw": 0.003180029257621428, "pitch": null, "roll": null}, "v": 2.31196697907593, "accelerator_pedal_position": 0.2646186880782873, "brake_pedal_position": 0.0, "acceleration": 0.03481653841212429, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016671949501500194, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137665.7975504} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26539647576852377, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7653979114343455, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3126629747599843, "gear": 1, "accelerator_pedal_position": 0.2646186880782873, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137665.7975504} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.579991817474365, "x": 16.509628190719855, "y": -0.29526092220043587, "z": null, "yaw": 0.003180029257621428, "pitch": null, "roll": null}, "v": 2.31196697907593, "accelerator_pedal_position": 0.2646186880782873, "brake_pedal_position": 0.0, "acceleration": 0.03481653841212429, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016671949501500194, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137665.8175504} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2650547884230999, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7653979114343455, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3134334525084115, "gear": 1, "accelerator_pedal_position": 0.2650547884230999, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137665.8175504} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.579991817474365, "x": 16.509628190719855, "y": -0.29526092220043587, "z": null, "yaw": 0.003180029257621428, "pitch": null, "roll": null}, "v": 2.31196697907593, "accelerator_pedal_position": 0.2646186880782873, "brake_pedal_position": 0.0, "acceleration": 0.03481653841212429, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016671949501500194, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137665.8375504} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2650547884230999, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7653979114343455, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3141811126724043, "gear": 1, "accelerator_pedal_position": 0.2650547884230999, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137665.8375504} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.579991817474365, "x": 16.509628190719855, "y": -0.29526092220043587, "z": null, "yaw": 0.003180029257621428, "pitch": null, "roll": null}, "v": 2.31196697907593, "accelerator_pedal_position": 0.2646186880782873, "brake_pedal_position": 0.0, "acceleration": 0.03481653841212429, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016671949501500194, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137665.8575504} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2650547884230999, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7653979114343455, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3149273338368146, "gear": 1, "accelerator_pedal_position": 0.2650547884230999, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137665.8575504} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.579991817474365, "x": 16.509628190719855, "y": -0.29526092220043587, "z": null, "yaw": 0.003180029257621428, "pitch": null, "roll": null}, "v": 2.31196697907593, "accelerator_pedal_position": 0.2646186880782873, "brake_pedal_position": 0.0, "acceleration": 0.03481653841212429, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016671949501500194, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137665.8775504} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2650547884230999, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7653979114343455, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3156721185486115, "gear": 1, "accelerator_pedal_position": 0.2650547884230999, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137665.8775504} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137665.8975503, "x": 20.764145388397047, "y": 4.705640251396424, "z": null, "yaw": 0.0039732561772801295, "pitch": null, "roll": null}, "v": 2.3160439730297187, "accelerator_pedal_position": 0.2650547884230999, "brake_pedal_position": 0.0, "acceleration": 0.03714963214281536, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016701349332004112, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137665.8975503} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26587457003954296, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7510844444434539, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3160439730297187, "gear": 1, "accelerator_pedal_position": 0.2650547884230999, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137665.8975503} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.68999171257019, "x": 16.764145388397047, "y": -0.2943597486035756, "z": null, "yaw": 0.0039732561772801295, "pitch": null, "roll": null}, "v": 2.3160439730297187, "accelerator_pedal_position": 0.2650547884230999, "brake_pedal_position": 0.0, "acceleration": 0.03714963214281536, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016701349332004112, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137665.9175503} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2655141049696934, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7510844444434539, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3168890311769323, "gear": 1, "accelerator_pedal_position": 0.26587457003954296, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137665.9175503} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.68999171257019, "x": 16.764145388397047, "y": -0.2943597486035756, "z": null, "yaw": 0.0039732561772801295, "pitch": null, "roll": null}, "v": 2.3160439730297187, "accelerator_pedal_position": 0.2650547884230999, "brake_pedal_position": 0.0, "acceleration": 0.03714963214281536, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016701349332004112, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137665.9375503} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2655141049696934, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7510844444434539, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3180860458790074, "gear": 1, "accelerator_pedal_position": 0.2655141049696934, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137665.9375503} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.68999171257019, "x": 16.764145388397047, "y": -0.2943597486035756, "z": null, "yaw": 0.0039732561772801295, "pitch": null, "roll": null}, "v": 2.3160439730297187, "accelerator_pedal_position": 0.2650547884230999, "brake_pedal_position": 0.0, "acceleration": 0.03714963214281536, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016701349332004112, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137665.9575503} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2655141049696934, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7510844444434539, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.318882134607961, "gear": 1, "accelerator_pedal_position": 0.2655141049696934, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137665.9575503} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.68999171257019, "x": 16.764145388397047, "y": -0.2943597486035756, "z": null, "yaw": 0.0039732561772801295, "pitch": null, "roll": null}, "v": 2.3160439730297187, "accelerator_pedal_position": 0.2650547884230999, "brake_pedal_position": 0.0, "acceleration": 0.03714963214281536, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016701349332004112, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137665.9775503} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2655141049696934, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7510844444434539, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3196766896366174, "gear": 1, "accelerator_pedal_position": 0.2655141049696934, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137665.9775503} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.68999171257019, "x": 16.764145388397047, "y": -0.2943597486035756, "z": null, "yaw": 0.0039732561772801295, "pitch": null, "roll": null}, "v": 2.3160439730297187, "accelerator_pedal_position": 0.2650547884230999, "brake_pedal_position": 0.0, "acceleration": 0.03714963214281536, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016701349332004112, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137665.9975502} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2655141049696934, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7510844444434539, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3200733928579607, "gear": 1, "accelerator_pedal_position": 0.2655141049696934, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137665.9975502} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137666.0075502, "x": 21.019131564092273, "y": 4.706745352771789, "z": null, "yaw": 0.00476648309693883, "pitch": null, "roll": null}, "v": 2.320469713667313, "accelerator_pedal_position": 0.2655141049696934, "brake_pedal_position": 0.0, "acceleration": 0.03959387345674553, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.01673326402848745, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137666.0175502} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2662433787139043, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6992059837765585, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3217019646033292, "gear": 1, "accelerator_pedal_position": 0.2662433787139043, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137666.0175502} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.799991607666016, "x": 17.019131564092273, "y": -0.2932546472282107, "z": null, "yaw": 0.00476648309693883, "pitch": null, "roll": null}, "v": 2.320469713667313, "accelerator_pedal_position": 0.2655141049696934, "brake_pedal_position": 0.0, "acceleration": 0.03959387345674553, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.01673326402848745, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137666.0375502} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26592859960054116, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6992059837765585, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3217019646033292, "gear": 1, "accelerator_pedal_position": 0.2662433787139043, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137666.0375502} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.799991607666016, "x": 17.019131564092273, "y": -0.2932546472282107, "z": null, "yaw": 0.00476648309693883, "pitch": null, "roll": null}, "v": 2.320469713667313, "accelerator_pedal_position": 0.2655141049696934, "brake_pedal_position": 0.0, "acceleration": 0.03959387345674553, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.01673326402848745, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137666.0675502} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26592859960054116, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6992059837765585, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.322962717412454, "gear": 1, "accelerator_pedal_position": 0.26592859960054116, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137666.0675502} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.799991607666016, "x": 17.019131564092273, "y": -0.2932546472282107, "z": null, "yaw": 0.00476648309693883, "pitch": null, "roll": null}, "v": 2.320469713667313, "accelerator_pedal_position": 0.2655141049696934, "brake_pedal_position": 0.0, "acceleration": 0.03959387345674553, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.01673326402848745, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137666.0875502} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26592859960054116, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6992059837765585, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3238011938810033, "gear": 1, "accelerator_pedal_position": 0.26592859960054116, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137666.0875502} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.799991607666016, "x": 17.019131564092273, "y": -0.2932546472282107, "z": null, "yaw": 0.00476648309693883, "pitch": null, "roll": null}, "v": 2.320469713667313, "accelerator_pedal_position": 0.2655141049696934, "brake_pedal_position": 0.0, "acceleration": 0.03959387345674553, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.01673326402848745, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137666.1075501} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26592859960054116, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6992059837765585, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3246380533427295, "gear": 1, "accelerator_pedal_position": 0.26592859960054116, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137666.1075501} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137666.1175501, "x": 21.27460787925969, "y": 4.708055234965686, "z": null, "yaw": 0.005559710016597531, "pitch": null, "roll": null}, "v": 2.325055877583187, "accelerator_pedal_position": 0.26592859960054116, "brake_pedal_position": 0.0, "acceleration": 0.04174210528538158, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016766335561905984, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137666.1275501} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26684041048376994, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6622436536975542, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.325473298636041, "gear": 1, "accelerator_pedal_position": 0.26592859960054116, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137666.1275501} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.90999150276184, "x": 17.27460787925969, "y": -0.2919447650343141, "z": null, "yaw": 0.005559710016597531, "pitch": null, "roll": null}, "v": 2.325055877583187, "accelerator_pedal_position": 0.26592859960054116, "brake_pedal_position": 0.0, "acceleration": 0.04174210528538158, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016766335561905984, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137666.14755} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26643991821467666, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6622436536975542, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.326420853951829, "gear": 1, "accelerator_pedal_position": 0.26684041048376994, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137666.14755} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.90999150276184, "x": 17.27460787925969, "y": -0.2919447650343141, "z": null, "yaw": 0.005559710016597531, "pitch": null, "roll": null}, "v": 2.325055877583187, "accelerator_pedal_position": 0.26592859960054116, "brake_pedal_position": 0.0, "acceleration": 0.04174210528538158, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016766335561905984, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137666.16755} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26643991821467666, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6622436536975542, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3282105045532497, "gear": 1, "accelerator_pedal_position": 0.26643991821467666, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137666.16755} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.90999150276184, "x": 17.27460787925969, "y": -0.2919447650343141, "z": null, "yaw": 0.005559710016597531, "pitch": null, "roll": null}, "v": 2.325055877583187, "accelerator_pedal_position": 0.26592859960054116, "brake_pedal_position": 0.0, "acceleration": 0.04174210528538158, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016766335561905984, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137666.19755} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26643991821467666, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6622436536975542, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.328656837774039, "gear": 1, "accelerator_pedal_position": 0.26643991821467666, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137666.19755} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.90999150276184, "x": 17.27460787925969, "y": -0.2919447650343141, "z": null, "yaw": 0.005559710016597531, "pitch": null, "roll": null}, "v": 2.325055877583187, "accelerator_pedal_position": 0.26592859960054116, "brake_pedal_position": 0.0, "acceleration": 0.04174210528538158, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016766335561905984, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137666.21755} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26643991821467666, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6622436536975542, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3295482115378503, "gear": 1, "accelerator_pedal_position": 0.26643991821467666, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137666.21755} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137666.22755, "x": 21.530607034271718, "y": 4.7095708719583955, "z": null, "yaw": 0.006352936936256232, "pitch": null, "roll": null}, "v": 2.3299932528335106, "accelerator_pedal_position": 0.26643991821467666, "brake_pedal_position": 0.0, "acceleration": 0.04446114061755668, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016801939734278834, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137666.23755} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.266911537026171, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6407361110458321, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.330437864239686, "gear": 1, "accelerator_pedal_position": 0.26643991821467666, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137666.23755} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.019991397857666, "x": 17.530607034271718, "y": -0.2904291280416045, "z": null, "yaw": 0.006352936936256232, "pitch": null, "roll": null}, "v": 2.3299932528335106, "accelerator_pedal_position": 0.26643991821467666, "brake_pedal_position": 0.0, "acceleration": 0.04446114061755668, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016801939734278834, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137666.25755} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2667232770033141, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6407361110458321, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3313847227582927, "gear": 1, "accelerator_pedal_position": 0.266911537026171, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137666.25755} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.019991397857666, "x": 17.530607034271718, "y": -0.2904291280416045, "z": null, "yaw": 0.006352936936256232, "pitch": null, "roll": null}, "v": 2.3299932528335106, "accelerator_pedal_position": 0.26643991821467666, "brake_pedal_position": 0.0, "acceleration": 0.04446114061755668, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016801939734278834, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137666.27755} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2667232770033141, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6407361110458321, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.33230623126317, "gear": 1, "accelerator_pedal_position": 0.2667232770033141, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137666.27755} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.019991397857666, "x": 17.530607034271718, "y": -0.2904291280416045, "z": null, "yaw": 0.006352936936256232, "pitch": null, "roll": null}, "v": 2.3299932528335106, "accelerator_pedal_position": 0.26643991821467666, "brake_pedal_position": 0.0, "acceleration": 0.04446114061755668, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016801939734278834, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137666.29755} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2667232770033141, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6407361110458321, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3332259595091402, "gear": 1, "accelerator_pedal_position": 0.2667232770033141, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137666.29755} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.019991397857666, "x": 17.530607034271718, "y": -0.2904291280416045, "z": null, "yaw": 0.006352936936256232, "pitch": null, "roll": null}, "v": 2.3299932528335106, "accelerator_pedal_position": 0.26643991821467666, "brake_pedal_position": 0.0, "acceleration": 0.04446114061755668, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016801939734278834, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137666.31755} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2667232770033141, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6407361110458321, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.334143910597283, "gear": 1, "accelerator_pedal_position": 0.2667232770033141, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137666.31755} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137666.33755, "x": 21.78715427441165, "y": 4.711293262981265, "z": null, "yaw": 0.007146163855914933, "pitch": null, "roll": null}, "v": 2.335060087624645, "accelerator_pedal_position": 0.2667232770033141, "brake_pedal_position": 0.0, "acceleration": 0.04574242076130469, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016838477459313297, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137666.33755} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2679501289397772, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5919334268294086, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.335060087624645, "gear": 1, "accelerator_pedal_position": 0.2667232770033141, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137666.33755} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.129991292953491, "x": 17.78715427441165, "y": -0.2887067370187353, "z": null, "yaw": 0.007146163855914933, "pitch": null, "roll": null}, "v": 2.335060087624645, "accelerator_pedal_position": 0.2667232770033141, "brake_pedal_position": 0.0, "acceleration": 0.04574242076130469, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016838477459313297, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137666.35755} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26740322487094365, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5919334268294086, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.336127776019911, "gear": 1, "accelerator_pedal_position": 0.2679501289397772, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137666.35755} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.129991292953491, "x": 17.78715427441165, "y": -0.2887067370187353, "z": null, "yaw": 0.007146163855914933, "pitch": null, "roll": null}, "v": 2.335060087624645, "accelerator_pedal_position": 0.2667232770033141, "brake_pedal_position": 0.0, "acceleration": 0.04574242076130469, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016838477459313297, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137666.37755} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26740322487094365, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5919334268294086, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.337125070193113, "gear": 1, "accelerator_pedal_position": 0.26740322487094365, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137666.37755} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.129991292953491, "x": 17.78715427441165, "y": -0.2887067370187353, "z": null, "yaw": 0.007146163855914933, "pitch": null, "roll": null}, "v": 2.335060087624645, "accelerator_pedal_position": 0.2667232770033141, "brake_pedal_position": 0.0, "acceleration": 0.04574242076130469, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016838477459313297, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137666.3975499} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26740322487094365, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5919334268294086, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3381204357844463, "gear": 1, "accelerator_pedal_position": 0.26740322487094365, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137666.3975499} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.129991292953491, "x": 17.78715427441165, "y": -0.2887067370187353, "z": null, "yaw": 0.007146163855914933, "pitch": null, "roll": null}, "v": 2.335060087624645, "accelerator_pedal_position": 0.2667232770033141, "brake_pedal_position": 0.0, "acceleration": 0.04574242076130469, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016838477459313297, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137666.4175498} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26740322487094365, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5919334268294086, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3391138761273207, "gear": 1, "accelerator_pedal_position": 0.26740322487094365, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137666.4175498} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.129991292953491, "x": 17.78715427441165, "y": -0.2887067370187353, "z": null, "yaw": 0.007146163855914933, "pitch": null, "roll": null}, "v": 2.335060087624645, "accelerator_pedal_position": 0.2667232770033141, "brake_pedal_position": 0.0, "acceleration": 0.04574242076130469, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016838477459313297, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137666.4375498} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26740322487094365, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5919334268294086, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.340105394550997, "gear": 1, "accelerator_pedal_position": 0.26740322487094365, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137666.4375498} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137666.4475498, "x": 22.044284260111926, "y": 4.713223542266531, "z": null, "yaw": 0.007939390775573634, "pitch": null, "roll": null}, "v": 2.3406004340823947, "accelerator_pedal_position": 0.26740322487094365, "brake_pedal_position": 0.0, "acceleration": 0.04945602981901104, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.01687842974980896, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137666.4575498} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26804515779179183, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5478623066636445, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.341094994380585, "gear": 1, "accelerator_pedal_position": 0.26740322487094365, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137666.4575498} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.239991188049316, "x": 18.044284260111926, "y": -0.2867764577334686, "z": null, "yaw": 0.007939390775573634, "pitch": null, "roll": null}, "v": 2.3406004340823947, "accelerator_pedal_position": 0.26740322487094365, "brake_pedal_position": 0.0, "acceleration": 0.04945602981901104, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.01687842974980896, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137666.4775498} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26778031837261124, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5478623066636445, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3421628817022944, "gear": 1, "accelerator_pedal_position": 0.26804515779179183, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137666.4775498} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.239991188049316, "x": 18.044284260111926, "y": -0.2867764577334686, "z": null, "yaw": 0.007939390775573634, "pitch": null, "roll": null}, "v": 2.3406004340823947, "accelerator_pedal_position": 0.26740322487094365, "brake_pedal_position": 0.0, "acceleration": 0.04945602981901104, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.01687842974980896, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137666.4975498} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26778031837261124, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5478623066636445, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3431956128900624, "gear": 1, "accelerator_pedal_position": 0.26778031837261124, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137666.4975498} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.239991188049316, "x": 18.044284260111926, "y": -0.2867764577334686, "z": null, "yaw": 0.007939390775573634, "pitch": null, "roll": null}, "v": 2.3406004340823947, "accelerator_pedal_position": 0.26740322487094365, "brake_pedal_position": 0.0, "acceleration": 0.04945602981901104, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.01687842974980896, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137666.5175498} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26778031837261124, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5478623066636445, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3442263444657407, "gear": 1, "accelerator_pedal_position": 0.26778031837261124, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137666.5175498} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.239991188049316, "x": 18.044284260111926, "y": -0.2867764577334686, "z": null, "yaw": 0.007939390775573634, "pitch": null, "roll": null}, "v": 2.3406004340823947, "accelerator_pedal_position": 0.26740322487094365, "brake_pedal_position": 0.0, "acceleration": 0.04945602981901104, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.01687842974980896, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137666.5375497} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26778031837261124, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5478623066636445, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.345255079876295, "gear": 1, "accelerator_pedal_position": 0.26778031837261124, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137666.5375497} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137666.5575497, "x": 22.302026024324803, "y": 4.715362875839434, "z": null, "yaw": 0.008732617695232335, "pitch": null, "roll": null}, "v": 2.3462818225644817, "accelerator_pedal_position": 0.26778031837261124, "brake_pedal_position": 0.0, "acceleration": 0.05126251479163102, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016919399116036505, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137666.5575497} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2683051564993931, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5112953838499971, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3462818225644817, "gear": 1, "accelerator_pedal_position": 0.26778031837261124, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137666.5575497} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.349991083145142, "x": 18.302026024324803, "y": -0.2846371241605663, "z": null, "yaw": 0.008732617695232335, "pitch": null, "roll": null}, "v": 2.3462818225644817, "accelerator_pedal_position": 0.26778031837261124, "brake_pedal_position": 0.0, "acceleration": 0.05126251479163102, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016919399116036505, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137666.5775497} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2680971648618096, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5112953838499971, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3473721489373074, "gear": 1, "accelerator_pedal_position": 0.2683051564993931, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137666.5775497} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.349991083145142, "x": 18.302026024324803, "y": -0.2846371241605663, "z": null, "yaw": 0.008732617695232335, "pitch": null, "roll": null}, "v": 2.3462818225644817, "accelerator_pedal_position": 0.26778031837261124, "brake_pedal_position": 0.0, "acceleration": 0.05126251479163102, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016919399116036505, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137666.5975497} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2680971648618096, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5112953838499971, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3484343760160176, "gear": 1, "accelerator_pedal_position": 0.2680971648618096, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137666.5975497} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.349991083145142, "x": 18.302026024324803, "y": -0.2846371241605663, "z": null, "yaw": 0.008732617695232335, "pitch": null, "roll": null}, "v": 2.3462818225644817, "accelerator_pedal_position": 0.26778031837261124, "brake_pedal_position": 0.0, "acceleration": 0.05126251479163102, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016919399116036505, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137666.6175497} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2680971648618096, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5112953838499971, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3494945441509962, "gear": 1, "accelerator_pedal_position": 0.2680971648618096, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137666.6175497} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.349991083145142, "x": 18.302026024324803, "y": -0.2846371241605663, "z": null, "yaw": 0.008732617695232335, "pitch": null, "roll": null}, "v": 2.3462818225644817, "accelerator_pedal_position": 0.26778031837261124, "brake_pedal_position": 0.0, "acceleration": 0.05126251479163102, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016919399116036505, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137666.6375496} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2680971648618096, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5112953838499971, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3505526568837856, "gear": 1, "accelerator_pedal_position": 0.2680971648618096, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137666.6375496} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.349991083145142, "x": 18.302026024324803, "y": -0.2846371241605663, "z": null, "yaw": 0.008732617695232335, "pitch": null, "roll": null}, "v": 2.3462818225644817, "accelerator_pedal_position": 0.26778031837261124, "brake_pedal_position": 0.0, "acceleration": 0.05126251479163102, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016919399116036505, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137666.6575496} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2680971648618096, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5112953838499971, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.351608717751675, "gear": 1, "accelerator_pedal_position": 0.2680971648618096, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137666.6575496} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137666.6675496, "x": 22.5604007804334, "y": 4.717712429750462, "z": null, "yaw": 0.009525844614891036, "pitch": null, "roll": null}, "v": 2.3521359798405217, "accelerator_pedal_position": 0.2680971648618096, "brake_pedal_position": 0.0, "acceleration": 0.05267504471768064, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016961614344611693, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137666.6775496} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2681105163198012, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.46701073695362694, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3526627302876983, "gear": 1, "accelerator_pedal_position": 0.2680971648618096, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137666.6775496} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.459990978240967, "x": 18.5604007804334, "y": -0.28228757024953843, "z": null, "yaw": 0.009525844614891036, "pitch": null, "roll": null}, "v": 2.3521359798405217, "accelerator_pedal_position": 0.2680971648618096, "brake_pedal_position": 0.0, "acceleration": 0.05267504471768064, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016961614344611693, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137666.6975496} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2681474164539672, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.46701073695362694, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.353716366142916, "gear": 1, "accelerator_pedal_position": 0.2681105163198012, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137666.6975496} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.459990978240967, "x": 18.5604007804334, "y": -0.28228757024953843, "z": null, "yaw": 0.009525844614891036, "pitch": null, "roll": null}, "v": 2.3521359798405217, "accelerator_pedal_position": 0.2680971648618096, "brake_pedal_position": 0.0, "acceleration": 0.05267504471768064, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016961614344611693, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137666.7175496} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2681474164539672, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.46701073695362694, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.354772567759885, "gear": 1, "accelerator_pedal_position": 0.2681474164539672, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137666.7175496} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.459990978240967, "x": 18.5604007804334, "y": -0.28228757024953843, "z": null, "yaw": 0.009525844614891036, "pitch": null, "roll": null}, "v": 2.3521359798405217, "accelerator_pedal_position": 0.2680971648618096, "brake_pedal_position": 0.0, "acceleration": 0.05267504471768064, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016961614344611693, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137666.7375495} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2681474164539672, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.46701073695362694, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3558267194366387, "gear": 1, "accelerator_pedal_position": 0.2681474164539672, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137666.7375495} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.459990978240967, "x": 18.5604007804334, "y": -0.28228757024953843, "z": null, "yaw": 0.009525844614891036, "pitch": null, "roll": null}, "v": 2.3521359798405217, "accelerator_pedal_position": 0.2680971648618096, "brake_pedal_position": 0.0, "acceleration": 0.05267504471768064, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.016961614344611693, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137666.7575495} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2681474164539672, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.46701073695362694, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3568788247075463, "gear": 1, "accelerator_pedal_position": 0.2681474164539672, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137666.7575495} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137666.7775495, "x": 22.81941296226048, "y": 4.720273253619227, "z": null, "yaw": 0.010319071534549737, "pitch": null, "roll": null}, "v": 2.3579288871027044, "accelerator_pedal_position": 0.2681474164539672, "brake_pedal_position": 0.0, "acceleration": 0.05242662211582588, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.017003387889915785, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137666.7775495} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2682918380134204, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4295665689118413, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3579288871027044, "gear": 1, "accelerator_pedal_position": 0.2681474164539672, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137666.7775495} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.569990873336792, "x": 18.81941296226048, "y": -0.27972674638077333, "z": null, "yaw": 0.010319071534549737, "pitch": null, "roll": null}, "v": 2.3579288871027044, "accelerator_pedal_position": 0.2681474164539672, "brake_pedal_position": 0.0, "acceleration": 0.05242662211582588, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.017003387889915785, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137666.7975495} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26826592259523696, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4295665689118413, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3589949540720374, "gear": 1, "accelerator_pedal_position": 0.2682918380134204, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137666.7975495} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.569990873336792, "x": 18.81941296226048, "y": -0.27972674638077333, "z": null, "yaw": 0.010319071534549737, "pitch": null, "roll": null}, "v": 2.3579288871027044, "accelerator_pedal_position": 0.2681474164539672, "brake_pedal_position": 0.0, "acceleration": 0.05242662211582588, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.017003387889915785, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137666.8175495} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26826592259523696, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4295665689118413, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.360055712303077, "gear": 1, "accelerator_pedal_position": 0.26826592259523696, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137666.8175495} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.569990873336792, "x": 18.81941296226048, "y": -0.27972674638077333, "z": null, "yaw": 0.010319071534549737, "pitch": null, "roll": null}, "v": 2.3579288871027044, "accelerator_pedal_position": 0.2681474164539672, "brake_pedal_position": 0.0, "acceleration": 0.05242662211582588, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.017003387889915785, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137666.8375494} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26826592259523696, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4295665689118413, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.361114409511153, "gear": 1, "accelerator_pedal_position": 0.26826592259523696, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137666.8375494} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.569990873336792, "x": 18.81941296226048, "y": -0.27972674638077333, "z": null, "yaw": 0.010319071534549737, "pitch": null, "roll": null}, "v": 2.3579288871027044, "accelerator_pedal_position": 0.2681474164539672, "brake_pedal_position": 0.0, "acceleration": 0.05242662211582588, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.017003387889915785, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137666.8575494} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26826592259523696, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4295665689118413, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.362171049252656, "gear": 1, "accelerator_pedal_position": 0.26826592259523696, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137666.8575494} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.569990873336792, "x": 18.81941296226048, "y": -0.27972674638077333, "z": null, "yaw": 0.010319071534549737, "pitch": null, "roll": null}, "v": 2.3579288871027044, "accelerator_pedal_position": 0.2681474164539672, "brake_pedal_position": 0.0, "acceleration": 0.05242662211582588, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.017003387889915785, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137666.8775494} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26826592259523696, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4295665689118413, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3632256350796776, "gear": 1, "accelerator_pedal_position": 0.26826592259523696, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137666.8775494} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137666.8875494, "x": 23.079062200491016, "y": 4.72304635864794, "z": null, "yaw": 0.011112298454208438, "pitch": null, "roll": null}, "v": 2.36375215888411, "accelerator_pedal_position": 0.26826592259523696, "brake_pedal_position": 0.0, "acceleration": 0.05260116558973249, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.017045380398438507, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137666.8975494} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2685749383989311, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.38771386650038464, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3642781705400076, "gear": 1, "accelerator_pedal_position": 0.26826592259523696, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137666.8975494} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.679990768432617, "x": 19.079062200491016, "y": -0.27695364135206013, "z": null, "yaw": 0.011112298454208438, "pitch": null, "roll": null}, "v": 2.36375215888411, "accelerator_pedal_position": 0.26826592259523696, "brake_pedal_position": 0.0, "acceleration": 0.05260116558973249, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.017045380398438507, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137666.9175494} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2684709209097082, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.38771386650038464, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.365367267361291, "gear": 1, "accelerator_pedal_position": 0.2685749383989311, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137666.9175494} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.679990768432617, "x": 19.079062200491016, "y": -0.27695364135206013, "z": null, "yaw": 0.011112298454208438, "pitch": null, "roll": null}, "v": 2.36375215888411, "accelerator_pedal_position": 0.26826592259523696, "brake_pedal_position": 0.0, "acceleration": 0.05260116558973249, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.017045380398438507, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137666.9375494} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2684709209097082, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.38771386650038464, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3664412499305456, "gear": 1, "accelerator_pedal_position": 0.2684709209097082, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137666.9375494} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.679990768432617, "x": 19.079062200491016, "y": -0.27695364135206013, "z": null, "yaw": 0.011112298454208438, "pitch": null, "roll": null}, "v": 2.36375215888411, "accelerator_pedal_position": 0.26826592259523696, "brake_pedal_position": 0.0, "acceleration": 0.05260116558973249, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.017045380398438507, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137666.9575493} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2684709209097082, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.38771386650038464, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3675131430432304, "gear": 1, "accelerator_pedal_position": 0.2684709209097082, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137666.9575493} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.679990768432617, "x": 19.079062200491016, "y": -0.27695364135206013, "z": null, "yaw": 0.011112298454208438, "pitch": null, "roll": null}, "v": 2.36375215888411, "accelerator_pedal_position": 0.26826592259523696, "brake_pedal_position": 0.0, "acceleration": 0.05260116558973249, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.017045380398438507, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137666.9775493} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2684709209097082, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.38771386650038464, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3685829503050697, "gear": 1, "accelerator_pedal_position": 0.2684709209097082, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137666.9775493} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137666.9975493, "x": 23.339353114528738, "y": 4.726032812501335, "z": null, "yaw": 0.011905525373867139, "pitch": null, "roll": null}, "v": 2.369650675317454, "accelerator_pedal_position": 0.2684709209097082, "brake_pedal_position": 0.0, "acceleration": 0.053308278689478794, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.01708791550772012, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137666.9975493} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2687763925247896, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3746842463240388, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.369650675317454, "gear": 1, "accelerator_pedal_position": 0.2684709209097082, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137666.9975493} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.789990663528442, "x": 19.339353114528738, "y": -0.27396718749866533, "z": null, "yaw": 0.011905525373867139, "pitch": null, "roll": null}, "v": 2.369650675317454, "accelerator_pedal_position": 0.2684709209097082, "brake_pedal_position": 0.0, "acceleration": 0.053308278689478794, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.01708791550772012, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137667.0175493} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26867467276132395, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3746842463240388, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3707544870329977, "gear": 1, "accelerator_pedal_position": 0.2687763925247896, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137667.0175493} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.789990663528442, "x": 19.339353114528738, "y": -0.27396718749866533, "z": null, "yaw": 0.011905525373867139, "pitch": null, "roll": null}, "v": 2.369650675317454, "accelerator_pedal_position": 0.2684709209097082, "brake_pedal_position": 0.0, "acceleration": 0.053308278689478794, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.01708791550772012, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137667.0375493} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26867467276132395, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3746842463240388, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.371843440582873, "gear": 1, "accelerator_pedal_position": 0.26867467276132395, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137667.0375493} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.789990663528442, "x": 19.339353114528738, "y": -0.27396718749866533, "z": null, "yaw": 0.011905525373867139, "pitch": null, "roll": null}, "v": 2.369650675317454, "accelerator_pedal_position": 0.2684709209097082, "brake_pedal_position": 0.0, "acceleration": 0.053308278689478794, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.01708791550772012, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137667.0575492} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26867467276132395, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3746842463240388, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3729302732006348, "gear": 1, "accelerator_pedal_position": 0.26867467276132395, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137667.0575492} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.789990663528442, "x": 19.339353114528738, "y": -0.27396718749866533, "z": null, "yaw": 0.011905525373867139, "pitch": null, "roll": null}, "v": 2.369650675317454, "accelerator_pedal_position": 0.2684709209097082, "brake_pedal_position": 0.0, "acceleration": 0.053308278689478794, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.01708791550772012, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137667.0775492} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26867467276132395, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3746842463240388, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.374014988544927, "gear": 1, "accelerator_pedal_position": 0.26867467276132395, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137667.0775492} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.789990663528442, "x": 19.339353114528738, "y": -0.27396718749866533, "z": null, "yaw": 0.011905525373867139, "pitch": null, "roll": null}, "v": 2.369650675317454, "accelerator_pedal_position": 0.2684709209097082, "brake_pedal_position": 0.0, "acceleration": 0.053308278689478794, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.01708791550772012, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137667.0975492} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26867467276132395, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3746842463240388, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.375097590270025, "gear": 1, "accelerator_pedal_position": 0.26867467276132395, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137667.0975492} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137667.1075492, "x": 23.600295576746745, "y": 4.729233758124965, "z": null, "yaw": 0.01269875229352584, "pitch": null, "roll": null}, "v": 2.3756380996661424, "accelerator_pedal_position": 0.26867467276132395, "brake_pedal_position": 0.0, "acceleration": 0.05399823596911385, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.017131091745654664, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137667.1175492} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2694186921877098, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.28848233655900185, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3761780820258336, "gear": 1, "accelerator_pedal_position": 0.26867467276132395, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137667.1175492} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.899990558624268, "x": 19.600295576746745, "y": -0.27076624187503473, "z": null, "yaw": 0.01269875229352584, "pitch": null, "roll": null}, "v": 2.3756380996661424, "accelerator_pedal_position": 0.26867467276132395, "brake_pedal_position": 0.0, "acceleration": 0.05399823596911385, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.017131091745654664, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137667.1375492} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26910885358554537, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.28848233655900185, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3773494245313076, "gear": 1, "accelerator_pedal_position": 0.2694186921877098, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137667.1375492} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.899990558624268, "x": 19.600295576746745, "y": -0.27076624187503473, "z": null, "yaw": 0.01269875229352584, "pitch": null, "roll": null}, "v": 2.3756380996661424, "accelerator_pedal_position": 0.26867467276132395, "brake_pedal_position": 0.0, "acceleration": 0.05399823596911385, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.017131091745654664, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137667.1575491} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26910885358554537, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.28848233655900185, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.378479772136668, "gear": 1, "accelerator_pedal_position": 0.26910885358554537, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137667.1575491} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.899990558624268, "x": 19.600295576746745, "y": -0.27076624187503473, "z": null, "yaw": 0.01269875229352584, "pitch": null, "roll": null}, "v": 2.3756380996661424, "accelerator_pedal_position": 0.26867467276132395, "brake_pedal_position": 0.0, "acceleration": 0.05399823596911385, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.017131091745654664, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137667.1775491} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26910885358554537, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.28848233655900185, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3796079151946343, "gear": 1, "accelerator_pedal_position": 0.26910885358554537, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137667.1775491} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26910885358554537, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.28848233655900185, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.380171161203128, "gear": 1, "accelerator_pedal_position": 0.26910885358554537, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137667.187549} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137667.217549, "x": 23.86190503309309, "y": 4.732650436330151, "z": null, "yaw": 0.01349197921318454, "pitch": null, "roll": null}, "v": 2.381857602826983, "accelerator_pedal_position": 0.26910885358554537, "brake_pedal_position": 0.0, "acceleration": 0.05610499836686228, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.017175941539600857, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137667.217549} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2694525946134753, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.2709509242517805, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3824401366248975, "gear": 1, "accelerator_pedal_position": 0.2694525946134753, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137667.217549} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.009990453720093, "x": 19.86190503309309, "y": -0.26734956366984886, "z": null, "yaw": 0.01349197921318454, "pitch": null, "roll": null}, "v": 2.381857602826983, "accelerator_pedal_position": 0.26910885358554537, "brake_pedal_position": 0.0, "acceleration": 0.05610499836686228, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.017175941539600857, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137667.237549} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2693351458941625, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.2709509242517805, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.383022101619467, "gear": 1, "accelerator_pedal_position": 0.2694525946134753, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137667.237549} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.009990453720093, "x": 19.86190503309309, "y": -0.26734956366984886, "z": null, "yaw": 0.01349197921318454, "pitch": null, "roll": null}, "v": 2.381857602826983, "accelerator_pedal_position": 0.26910885358554537, "brake_pedal_position": 0.0, "acceleration": 0.05610499836686228, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.017175941539600857, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137667.257549} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2693351458941625, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.2709509242517805, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3841696532285446, "gear": 1, "accelerator_pedal_position": 0.2693351458941625, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137667.257549} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.009990453720093, "x": 19.86190503309309, "y": -0.26734956366984886, "z": null, "yaw": 0.01349197921318454, "pitch": null, "roll": null}, "v": 2.381857602826983, "accelerator_pedal_position": 0.26910885358554537, "brake_pedal_position": 0.0, "acceleration": 0.05610499836686228, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.017175941539600857, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137667.277549} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2693351458941625, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.2709509242517805, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.385314964129546, "gear": 1, "accelerator_pedal_position": 0.2693351458941625, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137667.277549} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.009990453720093, "x": 19.86190503309309, "y": -0.26734956366984886, "z": null, "yaw": 0.01349197921318454, "pitch": null, "roll": null}, "v": 2.381857602826983, "accelerator_pedal_position": 0.26910885358554537, "brake_pedal_position": 0.0, "acceleration": 0.05610499836686228, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.017175941539600857, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137667.297549} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2693351458941625, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.2709509242517805, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3864580381732377, "gear": 1, "accelerator_pedal_position": 0.2693351458941625, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137667.297549} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.009990453720093, "x": 19.86190503309309, "y": -0.26734956366984886, "z": null, "yaw": 0.01349197921318454, "pitch": null, "roll": null}, "v": 2.381857602826983, "accelerator_pedal_position": 0.26910885358554537, "brake_pedal_position": 0.0, "acceleration": 0.05610499836686228, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.017175941539600857, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137667.317549} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2693351458941625, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.2709509242517805, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.387598879205936, "gear": 1, "accelerator_pedal_position": 0.2693351458941625, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137667.317549} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137667.327549, "x": 24.124201013679556, "y": 4.7362841790139525, "z": null, "yaw": 0.014285206132843242, "pitch": null, "roll": null}, "v": 2.38816846354392, "accelerator_pedal_position": 0.2693351458941625, "brake_pedal_position": 0.0, "acceleration": 0.05690275255866234, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.017221450126936228, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137667.337549} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2696213176118123, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.2518749425267406, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3887374910695067, "gear": 1, "accelerator_pedal_position": 0.2693351458941625, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137667.337549} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.119990348815918, "x": 20.124201013679556, "y": -0.2637158209860475, "z": null, "yaw": 0.014285206132843242, "pitch": null, "roll": null}, "v": 2.38816846354392, "accelerator_pedal_position": 0.2693351458941625, "brake_pedal_position": 0.0, "acceleration": 0.05690275255866234, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.017221450126936228, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137667.357549} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2695320222911479, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.2518749425267406, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3899096315762676, "gear": 1, "accelerator_pedal_position": 0.2696213176118123, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137667.357549} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.119990348815918, "x": 20.124201013679556, "y": -0.2637158209860475, "z": null, "yaw": 0.014285206132843242, "pitch": null, "roll": null}, "v": 2.38816846354392, "accelerator_pedal_position": 0.2693351458941625, "brake_pedal_position": 0.0, "acceleration": 0.05690275255866234, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.017221450126936228, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137667.377549} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2695320222911479, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.2518749425267406, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.391068324220626, "gear": 1, "accelerator_pedal_position": 0.2695320222911479, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137667.377549} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.119990348815918, "x": 20.124201013679556, "y": -0.2637158209860475, "z": null, "yaw": 0.014285206132843242, "pitch": null, "roll": null}, "v": 2.38816846354392, "accelerator_pedal_position": 0.2693351458941625, "brake_pedal_position": 0.0, "acceleration": 0.05690275255866234, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.017221450126936228, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137667.397549} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2695320222911479, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.2518749425267406, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.392224751209975, "gear": 1, "accelerator_pedal_position": 0.2695320222911479, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137667.397549} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.119990348815918, "x": 20.124201013679556, "y": -0.2637158209860475, "z": null, "yaw": 0.014285206132843242, "pitch": null, "roll": null}, "v": 2.38816846354392, "accelerator_pedal_position": 0.2693351458941625, "brake_pedal_position": 0.0, "acceleration": 0.05690275255866234, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.017221450126936228, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137667.417549} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2695320222911479, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.2518749425267406, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3933789164398047, "gear": 1, "accelerator_pedal_position": 0.2695320222911479, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137667.417549} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137667.4375489, "x": 24.387189846070264, "y": 4.740136172713195, "z": null, "yaw": 0.015078433052501942, "pitch": null, "roll": null}, "v": 2.394530823801125, "accelerator_pedal_position": 0.2695320222911479, "brake_pedal_position": 0.0, "acceleration": 0.05751081946828124, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.017267330085377883, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137667.4375489} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2707797376834944, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.18989227625841182, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.394530823801125, "gear": 1, "accelerator_pedal_position": 0.2695320222911479, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137667.4375489} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.229990243911743, "x": 20.387189846070264, "y": -0.25986382728680457, "z": null, "yaw": 0.015078433052501942, "pitch": null, "roll": null}, "v": 2.394530823801125, "accelerator_pedal_position": 0.2695320222911479, "brake_pedal_position": 0.0, "acceleration": 0.05751081946828124, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.017267330085377883, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137667.4575489} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2702330089813795, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.18989227625841182, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.395836365257656, "gear": 1, "accelerator_pedal_position": 0.2707797376834944, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137667.4575489} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.229990243911743, "x": 20.387189846070264, "y": -0.25986382728680457, "z": null, "yaw": 0.015078433052501942, "pitch": null, "roll": null}, "v": 2.394530823801125, "accelerator_pedal_position": 0.2695320222911479, "brake_pedal_position": 0.0, "acceleration": 0.05751081946828124, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.017267330085377883, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137667.4775488} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2702330089813795, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.18989227625841182, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3970710438245755, "gear": 1, "accelerator_pedal_position": 0.2702330089813795, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137667.4775488} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.229990243911743, "x": 20.387189846070264, "y": -0.25986382728680457, "z": null, "yaw": 0.015078433052501942, "pitch": null, "roll": null}, "v": 2.394530823801125, "accelerator_pedal_position": 0.2695320222911479, "brake_pedal_position": 0.0, "acceleration": 0.05751081946828124, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.017267330085377883, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137667.4975488} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2702330089813795, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.18989227625841182, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.398303305204768, "gear": 1, "accelerator_pedal_position": 0.2702330089813795, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137667.4975488} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.229990243911743, "x": 20.387189846070264, "y": -0.25986382728680457, "z": null, "yaw": 0.015078433052501942, "pitch": null, "roll": null}, "v": 2.394530823801125, "accelerator_pedal_position": 0.2695320222911479, "brake_pedal_position": 0.0, "acceleration": 0.05751081946828124, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.017267330085377883, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137667.5175488} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2702330089813795, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.18989227625841182, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3995331535233806, "gear": 1, "accelerator_pedal_position": 0.2702330089813795, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137667.5175488} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.229990243911743, "x": 20.387189846070264, "y": -0.25986382728680457, "z": null, "yaw": 0.015078433052501942, "pitch": null, "roll": null}, "v": 2.394530823801125, "accelerator_pedal_position": 0.2695320222911479, "brake_pedal_position": 0.0, "acceleration": 0.05751081946828124, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.017267330085377883, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137667.5375488} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2702330089813795, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.18989227625841182, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4007605929010487, "gear": 1, "accelerator_pedal_position": 0.2702330089813795, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137667.5375488} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137667.5475488, "x": 24.650902669584536, "y": 4.744208005304074, "z": null, "yaw": 0.015871659972160643, "pitch": null, "roll": null}, "v": 2.4013734105234916, "accelerator_pedal_position": 0.2702330089813795, "brake_pedal_position": 0.0, "acceleration": 0.061221693039754776, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.01731667303072588, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137667.5575488} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2704784551800145, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.16581743826013076, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.401985627453889, "gear": 1, "accelerator_pedal_position": 0.2702330089813795, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137667.5575488} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.339990139007568, "x": 20.650902669584536, "y": -0.25579199469592595, "z": null, "yaw": 0.015871659972160643, "pitch": null, "roll": null}, "v": 2.4013734105234916, "accelerator_pedal_position": 0.2702330089813795, "brake_pedal_position": 0.0, "acceleration": 0.061221693039754776, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.01731667303072588, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137667.5775487} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27041264596626413, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.16581743826013076, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4032389270267527, "gear": 1, "accelerator_pedal_position": 0.2704784551800145, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137667.5775487} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.339990139007568, "x": 20.650902669584536, "y": -0.25579199469592595, "z": null, "yaw": 0.015871659972160643, "pitch": null, "roll": null}, "v": 2.4013734105234916, "accelerator_pedal_position": 0.2702330089813795, "brake_pedal_position": 0.0, "acceleration": 0.061221693039754776, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.01731667303072588, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137667.5975487} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27041264596626413, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.16581743826013076, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.404481547753248, "gear": 1, "accelerator_pedal_position": 0.27041264596626413, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137667.5975487} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.339990139007568, "x": 20.650902669584536, "y": -0.25579199469592595, "z": null, "yaw": 0.015871659972160643, "pitch": null, "roll": null}, "v": 2.4013734105234916, "accelerator_pedal_position": 0.2702330089813795, "brake_pedal_position": 0.0, "acceleration": 0.061221693039754776, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.01731667303072588, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137667.6175487} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27041264596626413, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.16581743826013076, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4057217320655058, "gear": 1, "accelerator_pedal_position": 0.27041264596626413, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137667.6175487} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.339990139007568, "x": 20.650902669584536, "y": -0.25579199469592595, "z": null, "yaw": 0.015871659972160643, "pitch": null, "roll": null}, "v": 2.4013734105234916, "accelerator_pedal_position": 0.2702330089813795, "brake_pedal_position": 0.0, "acceleration": 0.061221693039754776, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.01731667303072588, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137667.6375487} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27041264596626413, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.16581743826013076, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4069594841256965, "gear": 1, "accelerator_pedal_position": 0.27041264596626413, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137667.6375487} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137667.6575487, "x": 24.91536035939168, "y": 4.748501166415141, "z": null, "yaw": 0.016664886891819344, "pitch": null, "roll": null}, "v": 2.408194808091447, "accelerator_pedal_position": 0.27041264596626413, "brake_pedal_position": 0.0, "acceleration": 0.061675274547392356, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.017365863177822218, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137667.6575487} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.270607581332165, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.14003643164500293, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.408194808091447, "gear": 1, "accelerator_pedal_position": 0.27041264596626413, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137667.6575487} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.449990034103394, "x": 20.91536035939168, "y": -0.2514988335848587, "z": null, "yaw": 0.016664886891819344, "pitch": null, "roll": null}, "v": 2.408194808091447, "accelerator_pedal_position": 0.27041264596626413, "brake_pedal_position": 0.0, "acceleration": 0.061675274547392356, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.017365863177822218, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137667.6775486} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27056573777686316, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.14003643164500293, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4094520630752925, "gear": 1, "accelerator_pedal_position": 0.270607581332165, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137667.6775486} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.449990034103394, "x": 20.91536035939168, "y": -0.2514988335848587, "z": null, "yaw": 0.016664886891819344, "pitch": null, "roll": null}, "v": 2.408194808091447, "accelerator_pedal_position": 0.27041264596626413, "brake_pedal_position": 0.0, "acceleration": 0.061675274547392356, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.017365863177822218, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137667.6975486} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27056573777686316, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.14003643164500293, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4107016225798064, "gear": 1, "accelerator_pedal_position": 0.27056573777686316, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137667.6975486} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.449990034103394, "x": 20.91536035939168, "y": -0.2514988335848587, "z": null, "yaw": 0.016664886891819344, "pitch": null, "roll": null}, "v": 2.408194808091447, "accelerator_pedal_position": 0.27041264596626413, "brake_pedal_position": 0.0, "acceleration": 0.061675274547392356, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.017365863177822218, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137667.7175486} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27056573777686316, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.14003643164500293, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4119487289601538, "gear": 1, "accelerator_pedal_position": 0.27056573777686316, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137667.7175486} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.449990034103394, "x": 20.91536035939168, "y": -0.2514988335848587, "z": null, "yaw": 0.016664886891819344, "pitch": null, "roll": null}, "v": 2.408194808091447, "accelerator_pedal_position": 0.27041264596626413, "brake_pedal_position": 0.0, "acceleration": 0.061675274547392356, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.017365863177822218, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137667.7375486} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27056573777686316, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.14003643164500293, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.413193386410481, "gear": 1, "accelerator_pedal_position": 0.27056573777686316, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137667.7375486} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.449990034103394, "x": 20.91536035939168, "y": -0.2514988335848587, "z": null, "yaw": 0.016664886891819344, "pitch": null, "roll": null}, "v": 2.408194808091447, "accelerator_pedal_position": 0.27041264596626413, "brake_pedal_position": 0.0, "acceleration": 0.061675274547392356, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.017365863177822218, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137667.7575486} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27056573777686316, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.14003643164500293, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4144355991203628, "gear": 1, "accelerator_pedal_position": 0.27056573777686316, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137667.7575486} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137667.7675486, "x": 25.180567297264435, "y": 4.753016918258719, "z": null, "yaw": 0.017458113811478045, "pitch": null, "roll": null}, "v": 2.4150557900056264, "accelerator_pedal_position": 0.27056573777686316, "brake_pedal_position": 0.0, "acceleration": 0.061958126916716316, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.01741533877372784, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137667.7775486} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27186338315188324, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.08399685432185067, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4156753712747934, "gear": 1, "accelerator_pedal_position": 0.27056573777686316, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137667.7775486} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.559989929199219, "x": 21.180567297264435, "y": -0.24698308174128059, "z": null, "yaw": 0.017458113811478045, "pitch": null, "roll": null}, "v": 2.4150557900056264, "accelerator_pedal_position": 0.27056573777686316, "brake_pedal_position": 0.0, "acceleration": 0.061958126916716316, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.01741533877372784, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137667.7975485} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.271296806705276, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.08399685432185067, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4170748329803184, "gear": 1, "accelerator_pedal_position": 0.27186338315188324, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137667.7975485} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.559989929199219, "x": 21.180567297264435, "y": -0.24698308174128059, "z": null, "yaw": 0.017458113811478045, "pitch": null, "roll": null}, "v": 2.4150557900056264, "accelerator_pedal_position": 0.27056573777686316, "brake_pedal_position": 0.0, "acceleration": 0.061958126916716316, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.01741533877372784, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137667.8175485} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.271296806705276, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.08399685432185067, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4184007565045818, "gear": 1, "accelerator_pedal_position": 0.271296806705276, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137667.8175485} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.559989929199219, "x": 21.180567297264435, "y": -0.24698308174128059, "z": null, "yaw": 0.017458113811478045, "pitch": null, "roll": null}, "v": 2.4150557900056264, "accelerator_pedal_position": 0.27056573777686316, "brake_pedal_position": 0.0, "acceleration": 0.061958126916716316, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.01741533877372784, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137667.8375485} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.271296806705276, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.08399685432185067, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.419724072918259, "gear": 1, "accelerator_pedal_position": 0.271296806705276, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137667.8375485} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.559989929199219, "x": 21.180567297264435, "y": -0.24698308174128059, "z": null, "yaw": 0.017458113811478045, "pitch": null, "roll": null}, "v": 2.4150557900056264, "accelerator_pedal_position": 0.27056573777686316, "brake_pedal_position": 0.0, "acceleration": 0.061958126916716316, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.01741533877372784, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137667.8575485} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.271296806705276, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.08399685432185067, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.421044786647485, "gear": 1, "accelerator_pedal_position": 0.271296806705276, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137667.8575485} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137667.8775485, "x": 25.446547467209747, "y": 4.757756886109737, "z": null, "yaw": 0.018251340731136746, "pitch": null, "roll": null}, "v": 2.4223629021138215, "accelerator_pedal_position": 0.271296806705276, "brake_pedal_position": 0.0, "acceleration": 0.0658084765069109, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.01746803148308406, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137667.8775485} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27169223961694444, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.04759453916274747, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4223629021138215, "gear": 1, "accelerator_pedal_position": 0.271296806705276, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137667.8775485} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.669989824295044, "x": 21.446547467209747, "y": -0.24224311389026276, "z": null, "yaw": 0.018251340731136746, "pitch": null, "roll": null}, "v": 2.4223629021138215, "accelerator_pedal_position": 0.271296806705276, "brake_pedal_position": 0.0, "acceleration": 0.0658084765069109, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.01746803148308406, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137667.8975484} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2715587062561021, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.04759453916274747, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.423727828514086, "gear": 1, "accelerator_pedal_position": 0.27169223961694444, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137667.8975484} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.669989824295044, "x": 21.446547467209747, "y": -0.24224311389026276, "z": null, "yaw": 0.018251340731136746, "pitch": null, "roll": null}, "v": 2.4223629021138215, "accelerator_pedal_position": 0.271296806705276, "brake_pedal_position": 0.0, "acceleration": 0.0658084765069109, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.01746803148308406, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137667.9175484} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2715587062561021, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.04759453916274747, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.425073384763272, "gear": 1, "accelerator_pedal_position": 0.2715587062561021, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137667.9175484} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.669989824295044, "x": 21.446547467209747, "y": -0.24224311389026276, "z": null, "yaw": 0.018251340731136746, "pitch": null, "roll": null}, "v": 2.4223629021138215, "accelerator_pedal_position": 0.271296806705276, "brake_pedal_position": 0.0, "acceleration": 0.0658084765069109, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.01746803148308406, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137667.9375484} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2715587062561021, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.04759453916274747, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4264162917136436, "gear": 1, "accelerator_pedal_position": 0.2715587062561021, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137667.9375484} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.669989824295044, "x": 21.446547467209747, "y": -0.24224311389026276, "z": null, "yaw": 0.018251340731136746, "pitch": null, "roll": null}, "v": 2.4223629021138215, "accelerator_pedal_position": 0.271296806705276, "brake_pedal_position": 0.0, "acceleration": 0.0658084765069109, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.01746803148308406, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137667.9575484} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2715587062561021, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.04759453916274747, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.427756553860466, "gear": 1, "accelerator_pedal_position": 0.2715587062561021, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137667.9575484} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.669989824295044, "x": 21.446547467209747, "y": -0.24224311389026276, "z": null, "yaw": 0.018251340731136746, "pitch": null, "roll": null}, "v": 2.4223629021138215, "accelerator_pedal_position": 0.271296806705276, "brake_pedal_position": 0.0, "acceleration": 0.0658084765069109, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.01746803148308406, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137667.9775484} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2715587062561021, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.04759453916274747, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.429094175694411, "gear": 1, "accelerator_pedal_position": 0.2715587062561021, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137667.9775484} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137667.9875484, "x": 25.71333259898481, "y": 4.762722890657683, "z": null, "yaw": 0.019044567650795447, "pitch": null, "roll": null}, "v": 2.429761997896131, "accelerator_pedal_position": 0.2715587062561021, "brake_pedal_position": 0.0, "acceleration": 0.0667163805416296, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.0175213875008628, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137667.9975483} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27248545058620843, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.0006550663850533736, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4304291617015474, "gear": 1, "accelerator_pedal_position": 0.2715587062561021, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137667.9975483} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.77998971939087, "x": 21.71333259898481, "y": -0.23727710934231716, "z": null, "yaw": 0.019044567650795447, "pitch": null, "roll": null}, "v": 2.429761997896131, "accelerator_pedal_position": 0.2715587062561021, "brake_pedal_position": 0.0, "acceleration": 0.0667163805416296, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.0175213875008628, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137668.0175483} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2720996840007225, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.0006550663850533736, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4318773022809483, "gear": 1, "accelerator_pedal_position": 0.27248545058620843, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137668.0175483} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.77998971939087, "x": 21.71333259898481, "y": -0.23727710934231716, "z": null, "yaw": 0.019044567650795447, "pitch": null, "roll": null}, "v": 2.429761997896131, "accelerator_pedal_position": 0.2715587062561021, "brake_pedal_position": 0.0, "acceleration": 0.0667163805416296, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.0175213875008628, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137668.0375483} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2720996840007225, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.0006550663850533736, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.433274390620405, "gear": 1, "accelerator_pedal_position": 0.2720996840007225, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137668.0375483} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.77998971939087, "x": 21.71333259898481, "y": -0.23727710934231716, "z": null, "yaw": 0.019044567650795447, "pitch": null, "roll": null}, "v": 2.429761997896131, "accelerator_pedal_position": 0.2715587062561021, "brake_pedal_position": 0.0, "acceleration": 0.0667163805416296, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.0175213875008628, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137668.0575483} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2720996840007225, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.0006550663850533736, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4346687236269484, "gear": 1, "accelerator_pedal_position": 0.2720996840007225, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137668.0575483} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.77998971939087, "x": 21.71333259898481, "y": -0.23727710934231716, "z": null, "yaw": 0.019044567650795447, "pitch": null, "roll": null}, "v": 2.429761997896131, "accelerator_pedal_position": 0.2715587062561021, "brake_pedal_position": 0.0, "acceleration": 0.0667163805416296, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.0175213875008628, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137668.0775483} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2720996840007225, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.0006550663850533736, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.436060305957355, "gear": 1, "accelerator_pedal_position": 0.2720996840007225, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137668.0775483} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137668.0975482, "x": 25.980941132744682, "y": 4.767916575326636, "z": null, "yaw": 0.019837794570454148, "pitch": null, "roll": null}, "v": 2.4374491422638136, "accelerator_pedal_position": 0.2720996840007225, "brake_pedal_position": 0.0, "acceleration": 0.06933898468009875, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.017576820681296873, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137668.0975482} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26657438968830305, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.051060451086981165, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4374491422638136, "gear": 1, "accelerator_pedal_position": 0.2720996840007225, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137668.0975482} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.889989614486694, "x": 21.980941132744682, "y": -0.2320834246733643, "z": null, "yaw": 0.019837794570454148, "pitch": null, "roll": null}, "v": 2.4374491422638136, "accelerator_pedal_position": 0.2720996840007225, "brake_pedal_position": 0.0, "acceleration": 0.06933898468009875, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.017576820681296873, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137668.1175482} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26926327455289223, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.051060451086981165, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4386603435895418, "gear": 1, "accelerator_pedal_position": 0.26926327455289223, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137668.1175482} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.889989614486694, "x": 21.980941132744682, "y": -0.2320834246733643, "z": null, "yaw": 0.019837794570454148, "pitch": null, "roll": null}, "v": 2.4374491422638136, "accelerator_pedal_position": 0.2720996840007225, "brake_pedal_position": 0.0, "acceleration": 0.06933898468009875, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.017576820681296873, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137668.1375482} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26926327455289223, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.051060451086981165, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.439175261650163, "gear": 1, "accelerator_pedal_position": 0.26926327455289223, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137668.1375482} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.889989614486694, "x": 21.980941132744682, "y": -0.2320834246733643, "z": null, "yaw": 0.019837794570454148, "pitch": null, "roll": null}, "v": 2.4374491422638136, "accelerator_pedal_position": 0.2720996840007225, "brake_pedal_position": 0.0, "acceleration": 0.06933898468009875, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.017576820681296873, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137668.1575482} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26926327455289223, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.051060451086981165, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4407169658640258, "gear": 1, "accelerator_pedal_position": 0.26926327455289223, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137668.1575482} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.889989614486694, "x": 21.980941132744682, "y": -0.2320834246733643, "z": null, "yaw": 0.019837794570454148, "pitch": null, "roll": null}, "v": 2.4374491422638136, "accelerator_pedal_position": 0.2720996840007225, "brake_pedal_position": 0.0, "acceleration": 0.06933898468009875, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.017576820681296873, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137668.1675482} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26926327455289223, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.051060451086981165, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4407169658640258, "gear": 1, "accelerator_pedal_position": 0.26926327455289223, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137668.1675482} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.889989614486694, "x": 21.980941132744682, "y": -0.2320834246733643, "z": null, "yaw": 0.019837794570454148, "pitch": null, "roll": null}, "v": 2.4374491422638136, "accelerator_pedal_position": 0.2720996840007225, "brake_pedal_position": 0.0, "acceleration": 0.06933898468009875, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.017576820681296873, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137668.1975482} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26926327455289223, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.051060451086981165, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.442254104555594, "gear": 1, "accelerator_pedal_position": 0.26926327455289223, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137668.1975482} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137668.2075481, "x": 26.249257015422124, "y": 4.773336890265159, "z": null, "yaw": 0.02063102149011285, "pitch": null, "roll": null}, "v": 2.44276547165175, "accelerator_pedal_position": 0.26926327455289223, "brake_pedal_position": 0.0, "acceleration": 0.0510861608780489, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.01761515755024491, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137668.2175481} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2643849440645222, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.101837727428111, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.443481794173866, "gear": 1, "accelerator_pedal_position": 0.2643849440645222, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137668.2175481} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.99998950958252, "x": 22.249257015422124, "y": -0.22666310973484105, "z": null, "yaw": 0.02063102149011285, "pitch": null, "roll": null}, "v": 2.44276547165175, "accelerator_pedal_position": 0.26926327455289223, "brake_pedal_position": 0.0, "acceleration": 0.0510861608780489, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.01761515755024491, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137668.237548} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26674797993489885, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.101837727428111, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4436870519529656, "gear": 1, "accelerator_pedal_position": 0.2643849440645222, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137668.237548} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.99998950958252, "x": 22.249257015422124, "y": -0.22666310973484105, "z": null, "yaw": 0.02063102149011285, "pitch": null, "roll": null}, "v": 2.44276547165175, "accelerator_pedal_position": 0.26926327455289223, "brake_pedal_position": 0.0, "acceleration": 0.0510861608780489, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.01761515755024491, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137668.257548} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26674797993489885, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.101837727428111, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.444392192327094, "gear": 1, "accelerator_pedal_position": 0.26674797993489885, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137668.257548} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.99998950958252, "x": 22.249257015422124, "y": -0.22666310973484105, "z": null, "yaw": 0.02063102149011285, "pitch": null, "roll": null}, "v": 2.44276547165175, "accelerator_pedal_position": 0.26926327455289223, "brake_pedal_position": 0.0, "acceleration": 0.0510861608780489, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.01761515755024491, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137668.277548} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26674797993489885, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.101837727428111, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4450959388442386, "gear": 1, "accelerator_pedal_position": 0.26674797993489885, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137668.277548} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.99998950958252, "x": 22.249257015422124, "y": -0.22666310973484105, "z": null, "yaw": 0.02063102149011285, "pitch": null, "roll": null}, "v": 2.44276547165175, "accelerator_pedal_position": 0.26926327455289223, "brake_pedal_position": 0.0, "acceleration": 0.0510861608780489, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.01761515755024491, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137668.297548} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26674797993489885, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.101837727428111, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4457982940616434, "gear": 1, "accelerator_pedal_position": 0.26674797993489885, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137668.297548} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137668.317548, "x": 26.51808654115586, "y": 4.778980901837356, "z": null, "yaw": 0.02142424840977155, "pitch": null, "roll": null}, "v": 2.4464992605326694, "accelerator_pedal_position": 0.26674797993489885, "brake_pedal_position": 0.0, "acceleration": 0.03499632524861529, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.017642082476178253, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137668.317548} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2613381374053497, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.16191196838113264, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4464992605326694, "gear": 1, "accelerator_pedal_position": 0.26674797993489885, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137668.317548} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.109989404678345, "x": 22.51808654115586, "y": -0.2210190981626443, "z": null, "yaw": 0.02142424840977155, "pitch": null, "roll": null}, "v": 2.4464992605326694, "accelerator_pedal_position": 0.26674797993489885, "brake_pedal_position": 0.0, "acceleration": 0.03499632524861529, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.017642082476178253, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137668.337548} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26394238709307916, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.16191196838113264, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.446522945000116, "gear": 1, "accelerator_pedal_position": 0.2613381374053497, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137668.337548} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.109989404678345, "x": 22.51808654115586, "y": -0.2210190981626443, "z": null, "yaw": 0.02142424840977155, "pitch": null, "roll": null}, "v": 2.4464992605326694, "accelerator_pedal_position": 0.26674797993489885, "brake_pedal_position": 0.0, "acceleration": 0.03499632524861529, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.017642082476178253, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137668.357548} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26394238709307916, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.16191196838113264, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.446871952811666, "gear": 1, "accelerator_pedal_position": 0.26394238709307916, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137668.357548} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.109989404678345, "x": 22.51808654115586, "y": -0.2210190981626443, "z": null, "yaw": 0.02142424840977155, "pitch": null, "roll": null}, "v": 2.4464992605326694, "accelerator_pedal_position": 0.26674797993489885, "brake_pedal_position": 0.0, "acceleration": 0.03499632524861529, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.017642082476178253, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137668.377548} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26394238709307916, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.16191196838113264, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.447220270378239, "gear": 1, "accelerator_pedal_position": 0.26394238709307916, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137668.377548} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.109989404678345, "x": 22.51808654115586, "y": -0.2210190981626443, "z": null, "yaw": 0.02142424840977155, "pitch": null, "roll": null}, "v": 2.4464992605326694, "accelerator_pedal_position": 0.26674797993489885, "brake_pedal_position": 0.0, "acceleration": 0.03499632524861529, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.017642082476178253, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137668.397548} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26394238709307916, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.16191196838113264, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4475678990164513, "gear": 1, "accelerator_pedal_position": 0.26394238709307916, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137668.397548} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.109989404678345, "x": 22.51808654115586, "y": -0.2210190981626443, "z": null, "yaw": 0.02142424840977155, "pitch": null, "roll": null}, "v": 2.4464992605326694, "accelerator_pedal_position": 0.26674797993489885, "brake_pedal_position": 0.0, "acceleration": 0.03499632524861529, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.017642082476178253, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137668.417548} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26394238709307916, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.16191196838113264, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.447914840040602, "gear": 1, "accelerator_pedal_position": 0.26394238709307916, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137668.417548} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137668.427548, "x": 26.787202539381877, "y": 4.784844481451781, "z": null, "yaw": 0.02221747532943025, "pitch": null, "roll": null}, "v": 2.44808805310749, "accelerator_pedal_position": 0.26394238709307916, "brake_pedal_position": 0.0, "acceleration": 0.01730416551869396, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.017653539503815537, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137668.437548} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2591770227645065, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.22559732881478725, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.448261094762677, "gear": 1, "accelerator_pedal_position": 0.26394238709307916, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137668.437548} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.21998929977417, "x": 22.787202539381877, "y": -0.2151555185482188, "z": null, "yaw": 0.02221747532943025, "pitch": null, "roll": null}, "v": 2.44808805310749, "accelerator_pedal_position": 0.26394238709307916, "brake_pedal_position": 0.0, "acceleration": 0.01730416551869396, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.017653539503815537, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137668.457548} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2614582224962275, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.22559732881478725, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.448011288706044, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137668.457548} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.21998929977417, "x": 22.787202539381877, "y": -0.2151555185482188, "z": null, "yaw": 0.02221747532943025, "pitch": null, "roll": null}, "v": 2.44808805310749, "accelerator_pedal_position": 0.26394238709307916, "brake_pedal_position": 0.0, "acceleration": 0.01730416551869396, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.017653539503815537, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137668.477548} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2614582224962275, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.22559732881478725, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4480469857037495, "gear": 1, "accelerator_pedal_position": 0.2614582224962275, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137668.477548} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.21998929977417, "x": 22.787202539381877, "y": -0.2151555185482188, "z": null, "yaw": 0.02221747532943025, "pitch": null, "roll": null}, "v": 2.44808805310749, "accelerator_pedal_position": 0.26394238709307916, "brake_pedal_position": 0.0, "acceleration": 0.01730416551869396, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.017653539503815537, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137668.4975479} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2614582224962275, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.22559732881478725, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.448082612084373, "gear": 1, "accelerator_pedal_position": 0.2614582224962275, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137668.4975479} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.21998929977417, "x": 22.787202539381877, "y": -0.2151555185482188, "z": null, "yaw": 0.02221747532943025, "pitch": null, "roll": null}, "v": 2.44808805310749, "accelerator_pedal_position": 0.26394238709307916, "brake_pedal_position": 0.0, "acceleration": 0.01730416551869396, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.017653539503815537, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137668.5175478} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2614582224962275, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.22559732881478725, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4481181679871034, "gear": 1, "accelerator_pedal_position": 0.2614582224962275, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137668.5175478} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137668.5375478, "x": 27.056424643500538, "y": 4.790924019905556, "z": null, "yaw": 0.023010702249088952, "pitch": null, "roll": null}, "v": 2.448153653550859, "accelerator_pedal_position": 0.2614582224962275, "brake_pedal_position": 0.0, "acceleration": 0.0017716448099348026, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.017654012558703008, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137668.5375478} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25832836150911587, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.2800871837395303, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.448153653550859, "gear": 1, "accelerator_pedal_position": 0.2614582224962275, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137668.5375478} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.329989194869995, "x": 23.056424643500538, "y": -0.20907598009444417, "z": null, "yaw": 0.023010702249088952, "pitch": null, "roll": null}, "v": 2.448153653550859, "accelerator_pedal_position": 0.2614582224962275, "brake_pedal_position": 0.0, "acceleration": 0.0017716448099348026, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.017654012558703008, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137668.5575478} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25981926687467943, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.2800871837395303, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.447798029875676, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137668.5575478} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.329989194869995, "x": 23.056424643500538, "y": -0.20907598009444417, "z": null, "yaw": 0.023010702249088952, "pitch": null, "roll": null}, "v": 2.448153653550859, "accelerator_pedal_position": 0.2614582224962275, "brake_pedal_position": 0.0, "acceleration": 0.0017716448099348026, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.017654012558703008, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137668.5775478} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25981926687467943, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.2800871837395303, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4476293806509477, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137668.5775478} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.329989194869995, "x": 23.056424643500538, "y": -0.20907598009444417, "z": null, "yaw": 0.023010702249088952, "pitch": null, "roll": null}, "v": 2.448153653550859, "accelerator_pedal_position": 0.2614582224962275, "brake_pedal_position": 0.0, "acceleration": 0.0017716448099348026, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.017654012558703008, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137668.5975478} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25981926687467943, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.2800871837395303, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4474610650294712, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137668.5975478} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.329989194869995, "x": 23.056424643500538, "y": -0.20907598009444417, "z": null, "yaw": 0.023010702249088952, "pitch": null, "roll": null}, "v": 2.448153653550859, "accelerator_pedal_position": 0.2614582224962275, "brake_pedal_position": 0.0, "acceleration": 0.0017716448099348026, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.017654012558703008, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137668.6175478} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25981926687467943, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.2800871837395303, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4472930823400225, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137668.6175478} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.329989194869995, "x": 23.056424643500538, "y": -0.20907598009444417, "z": null, "yaw": 0.023010702249088952, "pitch": null, "roll": null}, "v": 2.448153653550859, "accelerator_pedal_position": 0.2614582224962275, "brake_pedal_position": 0.0, "acceleration": 0.0017716448099348026, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.017654012558703008, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137668.6375477} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25981926687467943, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.2800871837395303, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4471254319127738, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137668.6375477} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137668.6475477, "x": 27.325583925314536, "y": 4.79721574941678, "z": null, "yaw": 0.023803929168747653, "pitch": null, "roll": null}, "v": 2.4470417310885333, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3822322188913143, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.017645994314796735, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137668.6575477} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2544292519087925, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.3576991830146701, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4469581130792877, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137668.6575477} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.43998908996582, "x": 23.325583925314536, "y": -0.20278425058322025, "z": null, "yaw": 0.023803929168747653, "pitch": null, "roll": null}, "v": 2.4470417310885333, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3822322188913143, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.017645994314796735, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137668.6775477} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2569875439781327, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.3576991830146701, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.446117706587032, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137668.6775477} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.43998908996582, "x": 23.325583925314536, "y": -0.20278425058322025, "z": null, "yaw": 0.023803929168747653, "pitch": null, "roll": null}, "v": 2.4470417310885333, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3822322188913143, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.017645994314796735, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137668.6975477} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2569875439781327, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.3576991830146701, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4455985903921094, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137668.6975477} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.43998908996582, "x": 23.325583925314536, "y": -0.20278425058322025, "z": null, "yaw": 0.023803929168747653, "pitch": null, "roll": null}, "v": 2.4470417310885333, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3822322188913143, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.017645994314796735, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137668.7175477} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2569875439781327, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.3576991830146701, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4450805006523684, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137668.7175477} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.43998908996582, "x": 23.325583925314536, "y": -0.20278425058322025, "z": null, "yaw": 0.023803929168747653, "pitch": null, "roll": null}, "v": 2.4470417310885333, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3822322188913143, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.017645994314796735, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137668.7375476} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2569875439781327, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.3576991830146701, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.444563435230873, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137668.7375476} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137668.7575476, "x": 27.594527602052317, "y": 4.803715878240979, "z": null, "yaw": 0.024597156088406354, "pitch": null, "roll": null}, "v": 2.4440473919955474, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.38193604614297977, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.017624401675022713, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137668.7575476} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2558887977019457, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.41257606696239496, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4440473919955474, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137668.7575476} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.549988985061646, "x": 23.594527602052317, "y": -0.196284121759021, "z": null, "yaw": 0.024597156088406354, "pitch": null, "roll": null}, "v": 2.4440473919955474, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.38193604614297977, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.017624401675022713, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137668.7775476} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2563894449217806, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.41257606696239496, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4433950934338022, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137668.7775476} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.549988985061646, "x": 23.594527602052317, "y": -0.196284121759021, "z": null, "yaw": 0.024597156088406354, "pitch": null, "roll": null}, "v": 2.4440473919955474, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.38193604614297977, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.017624401675022713, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137668.7975476} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2563894449217806, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.41257606696239496, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4428066340729835, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137668.7975476} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.549988985061646, "x": 23.594527602052317, "y": -0.196284121759021, "z": null, "yaw": 0.024597156088406354, "pitch": null, "roll": null}, "v": 2.4440473919955474, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.38193604614297977, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.017624401675022713, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137668.8175476} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2563894449217806, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.41257606696239496, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.442219337628035, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137668.8175476} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.549988985061646, "x": 23.594527602052317, "y": -0.196284121759021, "z": null, "yaw": 0.024597156088406354, "pitch": null, "roll": null}, "v": 2.4440473919955474, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.38193604614297977, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.017624401675022713, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137668.8375475} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2563894449217806, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.41257606696239496, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4416332016628988, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137668.8375475} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.549988985061646, "x": 23.594527602052317, "y": -0.196284121759021, "z": null, "yaw": 0.024597156088406354, "pitch": null, "roll": null}, "v": 2.4440473919955474, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.38193604614297977, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.017624401675022713, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137668.8575475} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2563894449217806, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.41257606696239496, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.441048223747148, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137668.8575475} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137668.8675475, "x": 27.863121434228916, "y": 4.810420734797025, "z": null, "yaw": 0.025390383008065055, "pitch": null, "roll": null}, "v": 2.44075616829982, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3816107151459272, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.01760066815471299, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137668.8775475} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2505101667472964, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.488716519967381, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.440464401455972, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3998167721271553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137668.8775475} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.65998888015747, "x": 23.863121434228916, "y": -0.1895792652029753, "z": null, "yaw": 0.025390383008065055, "pitch": null, "roll": null}, "v": 2.44075616829982, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3816107151459272, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.01760066815471299, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137668.8975475} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2532850372834445, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.488716519967381, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4391471856429834, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3597213299473276, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137668.8975475} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.65998888015747, "x": 23.863121434228916, "y": -0.1895792652029753, "z": null, "yaw": 0.025390383008065055, "pitch": null, "roll": null}, "v": 2.44075616829982, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3816107151459272, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.01760066815471299, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137668.9175475} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2532850372834445, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.488716519967381, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.438179258605323, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3597213299473276, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137668.9175475} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.65998888015747, "x": 23.863121434228916, "y": -0.1895792652029753, "z": null, "yaw": 0.025390383008065055, "pitch": null, "roll": null}, "v": 2.44075616829982, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3816107151459272, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.01760066815471299, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137668.9375474} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2532850372834445, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.488716519967381, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.437213242636053, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3597213299473276, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137668.9375474} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.65998888015747, "x": 23.863121434228916, "y": -0.1895792652029753, "z": null, "yaw": 0.025390383008065055, "pitch": null, "roll": null}, "v": 2.44075616829982, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3816107151459272, "steering_wheel_angle": 0.3998167721271553, "front_wheel_angle": 0.018458457125337967, "heading_rate": 0.01760066815471299, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137668.9575474} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2532850372834445, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.488716519967381, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4362491335888827, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3597213299473276, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137668.9575474} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137668.9775474, "x": 28.131239399020192, "y": 4.817320132919483, "z": null, "yaw": 0.026118200938401514, "pitch": null, "roll": null}, "v": 2.435286927327916, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.38107057055053817, "steering_wheel_angle": 0.3597213299473276, "front_wheel_angle": 0.01659850688172302, "heading_rate": 0.015791343543188525, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137668.9775474} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2514700846642527, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5444047482069805, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.435286927327916, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3597213299473276, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137668.9775474} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.769988775253296, "x": 24.131239399020192, "y": -0.18267986708051698, "z": null, "yaw": 0.026118200938401514, "pitch": null, "roll": null}, "v": 2.435286927327916, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.38107057055053817, "steering_wheel_angle": 0.3597213299473276, "front_wheel_angle": 0.01659850688172302, "heading_rate": 0.015791343543188525, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137668.9975474} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2522931943534936, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5444047482069805, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4340998626044343, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3195227158322157, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137668.9975474} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.769988775253296, "x": 24.131239399020192, "y": -0.18267986708051698, "z": null, "yaw": 0.026118200938401514, "pitch": null, "roll": null}, "v": 2.435286927327916, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.38107057055053817, "steering_wheel_angle": 0.3597213299473276, "front_wheel_angle": 0.01659850688172302, "heading_rate": 0.015791343543188525, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137669.0175474} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2522931943534936, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5444047482069805, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.433017977654842, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3195227158322157, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137669.0175474} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.769988775253296, "x": 24.131239399020192, "y": -0.18267986708051698, "z": null, "yaw": 0.026118200938401514, "pitch": null, "roll": null}, "v": 2.435286927327916, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.38107057055053817, "steering_wheel_angle": 0.3597213299473276, "front_wheel_angle": 0.01659850688172302, "heading_rate": 0.015791343543188525, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137669.0375473} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2522931943534936, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5444047482069805, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.431938226552309, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3195227158322157, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137669.0375473} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.769988775253296, "x": 24.131239399020192, "y": -0.18267986708051698, "z": null, "yaw": 0.026118200938401514, "pitch": null, "roll": null}, "v": 2.435286927327916, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.38107057055053817, "steering_wheel_angle": 0.3597213299473276, "front_wheel_angle": 0.01659850688172302, "heading_rate": 0.015791343543188525, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137669.0575473} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2522931943534936, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5444047482069805, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.430860604622045, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3195227158322157, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137669.0575473} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.769988775253296, "x": 24.131239399020192, "y": -0.18267986708051698, "z": null, "yaw": 0.026118200938401514, "pitch": null, "roll": null}, "v": 2.435286927327916, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.38107057055053817, "steering_wheel_angle": 0.3597213299473276, "front_wheel_angle": 0.01659850688172302, "heading_rate": 0.015791343543188525, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137669.0775473} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2522931943534936, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5444047482069805, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4297851072012335, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3195227158322157, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137669.0775473} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137669.0875473, "x": 28.39872046757109, "y": 4.824386624280593, "z": null, "yaw": 0.026758702437660885, "pitch": null, "roll": null}, "v": 2.4292481537280084, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3804748736103098, "steering_wheel_angle": 0.3195227158322157, "front_wheel_angle": 0.01473576855897449, "heading_rate": 0.013984152265703305, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137669.0975473} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.251620388400335, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6012359359954446, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.428711729638999, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3195227158322157, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137669.0975473} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.879988670349121, "x": 24.39872046757109, "y": -0.17561337571940694, "z": null, "yaw": 0.026758702437660885, "pitch": null, "roll": null}, "v": 2.4292481537280084, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3804748736103098, "steering_wheel_angle": 0.3195227158322157, "front_wheel_angle": 0.01473576855897449, "heading_rate": 0.013984152265703305, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137669.1175473} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25189538589138544, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6012359359954446, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4275564079983694, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.23887248914991002, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137669.1175473} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.879988670349121, "x": 24.39872046757109, "y": -0.17561337571940694, "z": null, "yaw": 0.026758702437660885, "pitch": null, "roll": null}, "v": 2.4292481537280084, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3804748736103098, "steering_wheel_angle": 0.3195227158322157, "front_wheel_angle": 0.01473576855897449, "heading_rate": 0.013984152265703305, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137669.1375473} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25189538589138544, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6012359359954446, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4264377202841003, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.23887248914991002, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137669.1375473} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.879988670349121, "x": 24.39872046757109, "y": -0.17561337571940694, "z": null, "yaw": 0.026758702437660885, "pitch": null, "roll": null}, "v": 2.4292481537280084, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3804748736103098, "steering_wheel_angle": 0.3195227158322157, "front_wheel_angle": 0.01473576855897449, "heading_rate": 0.013984152265703305, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137669.1575472} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25189538589138544, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6012359359954446, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4253212360670444, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.23887248914991002, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137669.1575472} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.879988670349121, "x": 24.39872046757109, "y": -0.17561337571940694, "z": null, "yaw": 0.026758702437660885, "pitch": null, "roll": null}, "v": 2.4292481537280084, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3804748736103098, "steering_wheel_angle": 0.3195227158322157, "front_wheel_angle": 0.01473576855897449, "heading_rate": 0.013984152265703305, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137669.1775472} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25189538589138544, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6012359359954446, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.424206950508568, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.23887248914991002, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137669.1775472} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137669.1975472, "x": 28.66553221761235, "y": 4.831593365587048, "z": null, "yaw": 0.02726801771130469, "pitch": null, "roll": null}, "v": 2.423094858782511, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3798686298857079, "steering_wheel_angle": 0.23887248914991002, "front_wheel_angle": 0.011004575376213691, "heading_rate": 0.010416486897571572, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137669.1975472} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.250411703894854, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6542161653849574, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.423094858782511, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.23887248914991002, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137669.1975472} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.989988565444946, "x": 24.66553221761235, "y": -0.16840663441295156, "z": null, "yaw": 0.02726801771130469, "pitch": null, "roll": null}, "v": 2.423094858782511, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3798686298857079, "steering_wheel_angle": 0.23887248914991002, "front_wheel_angle": 0.011004575376213691, "heading_rate": 0.010416486897571572, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137669.2175472} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25107202946309415, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6542161653849574, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4205893644699716, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1984245495952711, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137669.2175472} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.989988565444946, "x": 24.66553221761235, "y": -0.16840663441295156, "z": null, "yaw": 0.02726801771130469, "pitch": null, "roll": null}, "v": 2.423094858782511, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3798686298857079, "steering_wheel_angle": 0.23887248914991002, "front_wheel_angle": 0.011004575376213691, "heading_rate": 0.010416486897571572, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137669.2375472} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25107202946309415, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6542161653849574, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4205893644699716, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1984245495952711, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137669.2375472} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.989988565444946, "x": 24.66553221761235, "y": -0.16840663441295156, "z": null, "yaw": 0.02726801771130469, "pitch": null, "roll": null}, "v": 2.423094858782511, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3798686298857079, "steering_wheel_angle": 0.23887248914991002, "front_wheel_angle": 0.011004575376213691, "heading_rate": 0.010416486897571572, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137669.2675471} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25107202946309415, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6542161653849574, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.41877849318422, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1984245495952711, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137669.2675471} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.989988565444946, "x": 24.66553221761235, "y": -0.16840663441295156, "z": null, "yaw": 0.02726801771130469, "pitch": null, "roll": null}, "v": 2.423094858782511, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3798686298857079, "steering_wheel_angle": 0.23887248914991002, "front_wheel_angle": 0.011004575376213691, "heading_rate": 0.010416486897571572, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137669.287547} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25107202946309415, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6542161653849574, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.417574213107999, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1984245495952711, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137669.287547} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137669.307547, "x": 28.931631841886173, "y": 4.838900437175589, "z": null, "yaw": 0.027667902808585144, "pitch": null, "roll": null}, "v": 2.416372300866493, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37920716600727294, "steering_wheel_angle": 0.1984245495952711, "front_wheel_angle": 0.009136302311530516, "heading_rate": 0.008623953953476782, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137669.307547} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25017372061103643, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6923928457021267, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.416372300866493, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1984245495952711, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137669.307547} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.099988460540771, "x": 24.931631841886173, "y": -0.16109956282441118, "z": null, "yaw": 0.027667902808585144, "pitch": null, "roll": null}, "v": 2.416372300866493, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37920716600727294, "steering_wheel_angle": 0.1984245495952711, "front_wheel_angle": 0.009136302311530516, "heading_rate": 0.008623953953476782, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137669.327547} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2505510896716955, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6923928457021267, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.415060517818252, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.15789127584903512, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137669.327547} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.099988460540771, "x": 24.931631841886173, "y": -0.16109956282441118, "z": null, "yaw": 0.027667902808585144, "pitch": null, "roll": null}, "v": 2.416372300866493, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37920716600727294, "steering_wheel_angle": 0.1984245495952711, "front_wheel_angle": 0.009136302311530516, "heading_rate": 0.008623953953476782, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137669.347547} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2505510896716955, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6923928457021267, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.413798460622357, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.15789127584903512, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137669.347547} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.099988460540771, "x": 24.931631841886173, "y": -0.16109956282441118, "z": null, "yaw": 0.027667902808585144, "pitch": null, "roll": null}, "v": 2.416372300866493, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37920716600727294, "steering_wheel_angle": 0.1984245495952711, "front_wheel_angle": 0.009136302311530516, "heading_rate": 0.008623953953476782, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137669.367547} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2505510896716955, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6923928457021267, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.412538882964629, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.15789127584903512, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137669.367547} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.099988460540771, "x": 24.931631841886173, "y": -0.16109956282441118, "z": null, "yaw": 0.027667902808585144, "pitch": null, "roll": null}, "v": 2.416372300866493, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37920716600727294, "steering_wheel_angle": 0.1984245495952711, "front_wheel_angle": 0.009136302311530516, "heading_rate": 0.008623953953476782, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137669.387547} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2505510896716955, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6923928457021267, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4112817793392676, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.15789127584903512, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137669.387547} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2505510896716955, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6923928457021267, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4106541535721417, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.15789127584903512, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137669.397547} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137669.417547, "x": 29.196978720317748, "y": 4.846283333094959, "z": null, "yaw": 0.02798742925377705, "pitch": null, "roll": null}, "v": 2.409400750703772, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3785221573101076, "steering_wheel_angle": 0.15789127584903512, "front_wheel_angle": 0.0072660934675231595, "heading_rate": 0.006838765297324875, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137669.427547} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2488829705261788, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7203675701378058, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4087749722351517, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.15789127584903512, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137669.427547} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.209988355636597, "x": 25.196978720317748, "y": -0.1537166669050407, "z": null, "yaw": 0.02798742925377705, "pitch": null, "roll": null}, "v": 2.409400750703772, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3785221573101076, "steering_wheel_angle": 0.15789127584903512, "front_wheel_angle": 0.0072660934675231595, "heading_rate": 0.006838765297324875, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137669.447547} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24962512220833039, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7203675701378058, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4073168452653255, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.11728367945048646, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137669.447547} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.209988355636597, "x": 25.196978720317748, "y": -0.1537166669050407, "z": null, "yaw": 0.02798742925377705, "pitch": null, "roll": null}, "v": 2.409400750703772, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3785221573101076, "steering_wheel_angle": 0.15789127584903512, "front_wheel_angle": 0.0072660934675231595, "heading_rate": 0.006838765297324875, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137669.467547} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24962512220833039, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7203675701378058, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4059543027419936, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.11728367945048646, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137669.467547} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.209988355636597, "x": 25.196978720317748, "y": -0.1537166669050407, "z": null, "yaw": 0.02798742925377705, "pitch": null, "roll": null}, "v": 2.409400750703772, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3785221573101076, "steering_wheel_angle": 0.15789127584903512, "front_wheel_angle": 0.0072660934675231595, "heading_rate": 0.006838765297324875, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137669.487547} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24962512220833039, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7203675701378058, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4045944329209963, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.11728367945048646, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137669.487547} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.209988355636597, "x": 25.196978720317748, "y": -0.1537166669050407, "z": null, "yaw": 0.02798742925377705, "pitch": null, "roll": null}, "v": 2.409400750703772, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3785221573101076, "steering_wheel_angle": 0.15789127584903512, "front_wheel_angle": 0.0072660934675231595, "heading_rate": 0.006838765297324875, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137669.507547} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24962512220833039, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7203675701378058, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.403237229820345, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.11728367945048646, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137669.507547} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137669.527547, "x": 29.461531283603623, "y": 4.853720635636852, "z": null, "yaw": 0.028233847513468108, "pitch": null, "roll": null}, "v": 2.401882687474131, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3777845388175861, "steering_wheel_angle": 0.11728367945048646, "front_wheel_angle": 0.005394462316347733, "heading_rate": 0.005061324738239465, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137669.527547} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25114489445052235, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7746592222173737, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.401882687474131, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.11728367945048646, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137669.527547} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.319988250732422, "x": 25.461531283603623, "y": -0.14627936436314837, "z": null, "yaw": 0.028233847513468108, "pitch": null, "roll": null}, "v": 2.401882687474131, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3777845388175861, "steering_wheel_angle": 0.11728367945048646, "front_wheel_angle": 0.005394462316347733, "heading_rate": 0.005061324738239465, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137669.5475469} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2503649934890252, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7746592222173737, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4007206783528776, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.07657238253893192, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137669.5475469} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.319988250732422, "x": 25.461531283603623, "y": -0.14627936436314837, "z": null, "yaw": 0.028233847513468108, "pitch": null, "roll": null}, "v": 2.401882687474131, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3777845388175861, "steering_wheel_angle": 0.11728367945048646, "front_wheel_angle": 0.005394462316347733, "heading_rate": 0.005061324738239465, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137669.5675468} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2503649934890252, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7746592222173737, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3988358441011273, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.07657238253893192, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137669.5675468} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.319988250732422, "x": 25.461531283603623, "y": -0.14627936436314837, "z": null, "yaw": 0.028233847513468108, "pitch": null, "roll": null}, "v": 2.401882687474131, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3777845388175861, "steering_wheel_angle": 0.11728367945048646, "front_wheel_angle": 0.005394462316347733, "heading_rate": 0.005061324738239465, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137669.5775468} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2503649934890252, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7746592222173737, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3988358441011273, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.07657238253893192, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137669.5775468} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.319988250732422, "x": 25.461531283603623, "y": -0.14627936436314837, "z": null, "yaw": 0.028233847513468108, "pitch": null, "roll": null}, "v": 2.401882687474131, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3777845388175861, "steering_wheel_angle": 0.11728367945048646, "front_wheel_angle": 0.005394462316347733, "heading_rate": 0.005061324738239465, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137669.6075468} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2503649934890252, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7746592222173737, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.396331338627269, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.07657238253893192, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137669.6075468} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.319988250732422, "x": 25.461531283603623, "y": -0.14627936436314837, "z": null, "yaw": 0.028233847513468108, "pitch": null, "roll": null}, "v": 2.401882687474131, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3777845388175861, "steering_wheel_angle": 0.11728367945048646, "front_wheel_angle": 0.005394462316347733, "heading_rate": 0.005061324738239465, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137669.6175468} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2503649934890252, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7746592222173737, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.396331338627269, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.07657238253893192, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137669.6175468} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137669.6375468, "x": 29.725296372674535, "y": 4.861189614639845, "z": null, "yaw": 0.028392422808606925, "pitch": null, "roll": null}, "v": 2.395082762302661, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37711835249792647, "steering_wheel_angle": 0.07657238253893192, "front_wheel_angle": 0.0035200615522849115, "heading_rate": 0.003293309987500173, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137669.6475468} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2506585523166073, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8083400410792959, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.394459390870746, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.07657238253893192, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137669.6475468} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.429988145828247, "x": 25.725296372674535, "y": -0.13881038536015478, "z": null, "yaw": 0.028392422808606925, "pitch": null, "roll": null}, "v": 2.395082762302661, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37711835249792647, "steering_wheel_angle": 0.07657238253893192, "front_wheel_angle": 0.0035200615522849115, "heading_rate": 0.003293309987500173, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137669.6675467} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.250468005250598, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8083400410792959, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.393251154983728, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.03577993043371743, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137669.6675467} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.429988145828247, "x": 25.725296372674535, "y": -0.13881038536015478, "z": null, "yaw": 0.028392422808606925, "pitch": null, "roll": null}, "v": 2.395082762302661, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37711835249792647, "steering_wheel_angle": 0.07657238253893192, "front_wheel_angle": 0.0035200615522849115, "heading_rate": 0.003293309987500173, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137669.6875467} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.250468005250598, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8083400410792959, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.392021476236317, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.03577993043371743, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137669.6875467} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.429988145828247, "x": 25.725296372674535, "y": -0.13881038536015478, "z": null, "yaw": 0.028392422808606925, "pitch": null, "roll": null}, "v": 2.395082762302661, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37711835249792647, "steering_wheel_angle": 0.07657238253893192, "front_wheel_angle": 0.0035200615522849115, "heading_rate": 0.003293309987500173, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137669.7075467} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.250468005250598, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8083400410792959, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3907942027088387, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.03577993043371743, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137669.7075467} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.429988145828247, "x": 25.725296372674535, "y": -0.13881038536015478, "z": null, "yaw": 0.028392422808606925, "pitch": null, "roll": null}, "v": 2.395082762302661, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37711835249792647, "steering_wheel_angle": 0.07657238253893192, "front_wheel_angle": 0.0035200615522849115, "heading_rate": 0.003293309987500173, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137669.7275467} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.250468005250598, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8083400410792959, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3895693290945594, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.03577993043371743, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137669.7275467} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137669.7475467, "x": 29.98831215095895, "y": 4.8686710560249535, "z": null, "yaw": 0.028477718094755897, "pitch": null, "roll": null}, "v": 2.3883468501006546, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3764593492688899, "steering_wheel_angle": 0.03577993043371743, "front_wheel_angle": 0.0016439364159330995, "heading_rate": 0.0015337085538015204, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137669.7475467} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24714428761011326, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7981172254787573, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3883468501006546, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.03577993043371743, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137669.7475467} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.539988040924072, "x": 25.98831215095895, "y": -0.13132894397504646, "z": null, "yaw": 0.028477718094755897, "pitch": null, "roll": null}, "v": 2.3883468501006546, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3764593492688899, "steering_wheel_angle": 0.03577993043371743, "front_wheel_angle": 0.0016439364159330995, "heading_rate": 0.0015337085538015204, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137669.7675467} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24867680129178454, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7981172254787573, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3867114988069917, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.03577993043371743, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137669.7675467} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.539988040924072, "x": 25.98831215095895, "y": -0.13132894397504646, "z": null, "yaw": 0.028477718094755897, "pitch": null, "roll": null}, "v": 2.3883468501006546, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3764593492688899, "steering_wheel_angle": 0.03577993043371743, "front_wheel_angle": 0.0016439364159330995, "heading_rate": 0.0015337085538015204, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137669.7875466} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24867680129178454, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7981172254787573, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.385270813427569, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.03577993043371743, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137669.7875466} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.539988040924072, "x": 25.98831215095895, "y": -0.13132894397504646, "z": null, "yaw": 0.028477718094755897, "pitch": null, "roll": null}, "v": 2.3883468501006546, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3764593492688899, "steering_wheel_angle": 0.03577993043371743, "front_wheel_angle": 0.0016439364159330995, "heading_rate": 0.0015337085538015204, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137669.8075466} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24867680129178454, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7981172254787573, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3838329421355677, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.03577993043371743, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137669.8075466} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.539988040924072, "x": 25.98831215095895, "y": -0.13132894397504646, "z": null, "yaw": 0.028477718094755897, "pitch": null, "roll": null}, "v": 2.3883468501006546, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3764593492688899, "steering_wheel_angle": 0.03577993043371743, "front_wheel_angle": 0.0016439364159330995, "heading_rate": 0.0015337085538015204, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137669.8275466} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24867680129178454, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7981172254787573, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3823978786076516, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.03577993043371743, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137669.8275466} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.539988040924072, "x": 25.98831215095895, "y": -0.13132894397504646, "z": null, "yaw": 0.028477718094755897, "pitch": null, "roll": null}, "v": 2.3883468501006546, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3764593492688899, "steering_wheel_angle": 0.03577993043371743, "front_wheel_angle": 0.0016439364159330995, "heading_rate": 0.0015337085538015204, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137669.8475466} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24867680129178454, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7981172254787573, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3809656165376745, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.03577993043371743, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137669.8475466} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137669.8575466, "x": 30.250509488239377, "y": 4.876148277354147, "z": null, "yaw": 0.028548356051261686, "pitch": null, "roll": null}, "v": 2.380250534083429, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37566845275421595, "steering_wheel_angle": 0.03577993043371743, "front_wheel_angle": 0.0016439364159330995, "heading_rate": 0.0015285093972680478, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137669.8675466} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25083728823081103, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8493158080974321, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.379536149636623, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.03577993043371743, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137669.8675466} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.649987936019897, "x": 26.250509488239377, "y": -0.12385172264585265, "z": null, "yaw": 0.028548356051261686, "pitch": null, "roll": null}, "v": 2.380250534083429, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37566845275421595, "steering_wheel_angle": 0.03577993043371743, "front_wheel_angle": 0.0016439364159330995, "heading_rate": 0.0015285093972680478, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137669.8875465} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24974822560040794, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8493158080974321, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.378379400740212, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.005101389278241543, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137669.8875465} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.649987936019897, "x": 26.250509488239377, "y": -0.12385172264585265, "z": null, "yaw": 0.028548356051261686, "pitch": null, "roll": null}, "v": 2.380250534083429, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37566845275421595, "steering_wheel_angle": 0.03577993043371743, "front_wheel_angle": 0.0016439364159330995, "heading_rate": 0.0015285093972680478, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137669.9075465} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24974822560040794, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8493158080974321, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3770888416740115, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.005101389278241543, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137669.9075465} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.649987936019897, "x": 26.250509488239377, "y": -0.12385172264585265, "z": null, "yaw": 0.028548356051261686, "pitch": null, "roll": null}, "v": 2.380250534083429, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37566845275421595, "steering_wheel_angle": 0.03577993043371743, "front_wheel_angle": 0.0016439364159330995, "heading_rate": 0.0015285093972680478, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137669.9275465} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24974822560040794, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8493158080974321, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3758007992148826, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.005101389278241543, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137669.9275465} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.649987936019897, "x": 26.250509488239377, "y": -0.12385172264585265, "z": null, "yaw": 0.028548356051261686, "pitch": null, "roll": null}, "v": 2.380250534083429, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37566845275421595, "steering_wheel_angle": 0.03577993043371743, "front_wheel_angle": 0.0016439364159330995, "heading_rate": 0.0015285093972680478, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137669.9475465} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24974822560040794, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8493158080974321, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3745152677921113, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.005101389278241543, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137669.9475465} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137669.9675465, "x": 30.51188026147817, "y": 4.883614128983556, "z": null, "yaw": 0.02855296245242706, "pitch": null, "roll": null}, "v": 2.3732322418497223, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3749839248300367, "steering_wheel_angle": -0.005101389278241543, "front_wheel_angle": -0.0002342930063118815, "heading_rate": -0.00021719989327866415, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137669.9675465} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2509148678885619, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8895886190804446, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3732322418497223, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.005101389278241543, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137669.9675465} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.759987831115723, "x": 26.51188026147817, "y": -0.11638587101644404, "z": null, "yaw": 0.02855296245242706, "pitch": null, "roll": null}, "v": 2.3732322418497223, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3749839248300367, "steering_wheel_angle": -0.005101389278241543, "front_wheel_angle": -0.0002342930063118815, "heading_rate": -0.00021719989327866415, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137669.9875464} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25030716912974094, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8895886190804446, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.372097475074776, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.046017589187264674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137669.9875464} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.759987831115723, "x": 26.51188026147817, "y": -0.11638587101644404, "z": null, "yaw": 0.02855296245242706, "pitch": null, "roll": null}, "v": 2.3732322418497223, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3749839248300367, "steering_wheel_angle": -0.005101389278241543, "front_wheel_angle": -0.0002342930063118815, "heading_rate": -0.00021719989327866415, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137670.0075464} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25030716912974094, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8895886190804446, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.370888993489113, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.046017589187264674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137670.0075464} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.759987831115723, "x": 26.51188026147817, "y": -0.11638587101644404, "z": null, "yaw": 0.02855296245242706, "pitch": null, "roll": null}, "v": 2.3732322418497223, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3749839248300367, "steering_wheel_angle": -0.005101389278241543, "front_wheel_angle": -0.0002342930063118815, "heading_rate": -0.00021719989327866415, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137670.0275464} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25030716912974094, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8895886190804446, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3696828654544073, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.046017589187264674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137670.0275464} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.759987831115723, "x": 26.51188026147817, "y": -0.11638587101644404, "z": null, "yaw": 0.02855296245242706, "pitch": null, "roll": null}, "v": 2.3732322418497223, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3749839248300367, "steering_wheel_angle": -0.005101389278241543, "front_wheel_angle": -0.0002342930063118815, "heading_rate": -0.00021719989327866415, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137670.0475464} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25030716912974094, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8895886190804446, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.368479085805439, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.046017589187264674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137670.0475464} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.759987831115723, "x": 26.51188026147817, "y": -0.11638587101644404, "z": null, "yaw": 0.02855296245242706, "pitch": null, "roll": null}, "v": 2.3732322418497223, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3749839248300367, "steering_wheel_angle": -0.005101389278241543, "front_wheel_angle": -0.0002342930063118815, "heading_rate": -0.00021719989327866415, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137670.0675464} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25030716912974094, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8895886190804446, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.367277649390443, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.046017589187264674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137670.0675464} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137670.0775464, "x": 30.772504845156956, "y": 4.891048730021315, "z": null, "yaw": 0.028469445656248725, "pitch": null, "roll": null}, "v": 2.366677808289426, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3743455288969677, "steering_wheel_angle": -0.046017589187264674, "front_wheel_angle": -0.002114597529276071, "heading_rate": -0.0019549134786584765, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137670.0875463} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24794957448726146, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8742678788795927, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.366078551071065, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.046017589187264674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137670.0875463} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.869987726211548, "x": 26.772504845156956, "y": -0.10895126997868498, "z": null, "yaw": 0.028469445656248725, "pitch": null, "roll": null}, "v": 2.366677808289426, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3743455288969677, "steering_wheel_angle": -0.046017589187264674, "front_wheel_angle": -0.002114597529276071, "heading_rate": -0.0019549134786584765, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137670.1075463} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24902359944911168, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8742678788795927, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3645872297752066, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.046017589187264674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137670.1075463} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.869987726211548, "x": 26.772504845156956, "y": -0.10895126997868498, "z": null, "yaw": 0.028469445656248725, "pitch": null, "roll": null}, "v": 2.366677808289426, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3743455288969677, "steering_wheel_angle": -0.046017589187264674, "front_wheel_angle": -0.002114597529276071, "heading_rate": -0.0019549134786584765, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137670.1275463} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24902359944911168, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8742678788795927, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.363232996976194, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.046017589187264674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137670.1275463} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.869987726211548, "x": 26.772504845156956, "y": -0.10895126997868498, "z": null, "yaw": 0.028469445656248725, "pitch": null, "roll": null}, "v": 2.366677808289426, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3743455288969677, "steering_wheel_angle": -0.046017589187264674, "front_wheel_angle": -0.002114597529276071, "heading_rate": -0.0019549134786584765, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137670.1475463} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24902359944911168, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8742678788795927, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.36188139745918, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.046017589187264674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137670.1475463} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.869987726211548, "x": 26.772504845156956, "y": -0.10895126997868498, "z": null, "yaw": 0.028469445656248725, "pitch": null, "roll": null}, "v": 2.366677808289426, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3743455288969677, "steering_wheel_angle": -0.046017589187264674, "front_wheel_angle": -0.002114597529276071, "heading_rate": -0.0019549134786584765, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137670.1675463} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24902359944911168, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8742678788795927, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.36053242537342, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.046017589187264674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137670.1675463} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137670.1875463, "x": 31.032358358937405, "y": 4.898437880229017, "z": null, "yaw": 0.028378583908232474, "pitch": null, "roll": null}, "v": 2.359186074883803, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37361689310344665, "steering_wheel_angle": -0.046017589187264674, "front_wheel_angle": -0.002114597529276071, "heading_rate": -0.0019487251878138705, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137670.1875463} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24906299184514152, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8931515731132564, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.359186074883803, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.046017589187264674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137670.1875463} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.979987621307373, "x": 27.032358358937405, "y": -0.10156211977098284, "z": null, "yaw": 0.028378583908232474, "pitch": null, "roll": null}, "v": 2.359186074883803, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37361689310344665, "steering_wheel_angle": -0.046017589187264674, "front_wheel_angle": -0.002114597529276071, "heading_rate": -0.0019487251878138705, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137670.2075462} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24898871841613715, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8931515731132564, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3578472618279465, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.046017589187264674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137670.2075462} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.979987621307373, "x": 27.032358358937405, "y": -0.10156211977098284, "z": null, "yaw": 0.028378583908232474, "pitch": null, "roll": null}, "v": 2.359186074883803, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37361689310344665, "steering_wheel_angle": -0.046017589187264674, "front_wheel_angle": -0.002114597529276071, "heading_rate": -0.0019487251878138705, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137670.2275462} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24898871841613715, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8931515731132564, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.356501769518075, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.046017589187264674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137670.2275462} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.979987621307373, "x": 27.032358358937405, "y": -0.10156211977098284, "z": null, "yaw": 0.028378583908232474, "pitch": null, "roll": null}, "v": 2.359186074883803, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37361689310344665, "steering_wheel_angle": -0.046017589187264674, "front_wheel_angle": -0.002114597529276071, "heading_rate": -0.0019487251878138705, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137670.2475462} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24898871841613715, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8931515731132564, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3551588898740943, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.046017589187264674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137670.2475462} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.979987621307373, "x": 27.032358358937405, "y": -0.10156211977098284, "z": null, "yaw": 0.028378583908232474, "pitch": null, "roll": null}, "v": 2.359186074883803, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37361689310344665, "steering_wheel_angle": -0.046017589187264674, "front_wheel_angle": -0.002114597529276071, "heading_rate": -0.0019487251878138705, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137670.2675462} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24898871841613715, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8931515731132564, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3538186171017697, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.046017589187264674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137670.2675462} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.979987621307373, "x": 27.032358358937405, "y": -0.10156211977098284, "z": null, "yaw": 0.028378583908232474, "pitch": null, "roll": null}, "v": 2.359186074883803, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37361689310344665, "steering_wheel_angle": -0.046017589187264674, "front_wheel_angle": -0.002114597529276071, "heading_rate": -0.0019487251878138705, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137670.2875462} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24898871841613715, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8931515731132564, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3524809454223155, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.046017589187264674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137670.2875462} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137670.2975461, "x": 31.29139583989168, "y": 4.9057802701823645, "z": null, "yaw": 0.028287722160216223, "pitch": null, "roll": null}, "v": 2.3518130831907555, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3729009019422099, "steering_wheel_angle": -0.046017589187264674, "front_wheel_angle": -0.002114597529276071, "heading_rate": -0.001942634979510784, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137670.3075461} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.251453787533726, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9446959574766365, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.351145869072342, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.046017589187264674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137670.3075461} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.089987516403198, "x": 27.29139583989168, "y": -0.09421972981763549, "z": null, "yaw": 0.028287722160216223, "pitch": null, "roll": null}, "v": 2.3518130831907555, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3729009019422099, "steering_wheel_angle": -0.046017589187264674, "front_wheel_angle": -0.002114597529276071, "heading_rate": -0.001942634979510784, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137670.3275461} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2502253927756193, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9446959574766365, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.350121366481546, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.08695180276671388, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137670.3275461} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.089987516403198, "x": 27.29139583989168, "y": -0.09421972981763549, "z": null, "yaw": 0.028287722160216223, "pitch": null, "roll": null}, "v": 2.3518130831907555, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3729009019422099, "steering_wheel_angle": -0.046017589187264674, "front_wheel_angle": -0.002114597529276071, "heading_rate": -0.001942634979510784, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137670.357546} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2502253927756193, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9446959574766365, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.348358235659297, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.08695180276671388, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137670.357546} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.089987516403198, "x": 27.29139583989168, "y": -0.09421972981763549, "z": null, "yaw": 0.028287722160216223, "pitch": null, "roll": null}, "v": 2.3518130831907555, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3729009019422099, "steering_wheel_angle": -0.046017589187264674, "front_wheel_angle": -0.002114597529276071, "heading_rate": -0.001942634979510784, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137670.387546} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2502253927756193, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9446959574766365, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.346600229149902, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.08695180276671388, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137670.387546} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137670.407546, "x": 31.549674178792863, "y": 4.913071436230034, "z": null, "yaw": 0.028130655100465533, "pitch": null, "roll": null}, "v": 2.345431063379066, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3722820218995879, "steering_wheel_angle": -0.08695180276671388, "front_wheel_angle": -0.003997752695129866, "heading_rate": -0.0036626966042031177, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137670.407546} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2525347074848116, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.998094733124442, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.345431063379066, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.08695180276671388, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137670.407546} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.199987411499023, "x": 27.549674178792863, "y": -0.08692856376996616, "z": null, "yaw": 0.028130655100465533, "pitch": null, "roll": null}, "v": 2.345431063379066, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3722820218995879, "steering_wheel_angle": -0.08695180276671388, "front_wheel_angle": -0.003997752695129866, "heading_rate": -0.0036626966042031177, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137670.427546} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2513878804757253, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.998094733124442, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.344552687174821, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.1688083787414252, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137670.427546} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.199987411499023, "x": 27.549674178792863, "y": -0.08692856376996616, "z": null, "yaw": 0.028130655100465533, "pitch": null, "roll": null}, "v": 2.345431063379066, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3722820218995879, "steering_wheel_angle": -0.08695180276671388, "front_wheel_angle": -0.003997752695129866, "heading_rate": -0.0036626966042031177, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137670.447546} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2513878804757253, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.998094733124442, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.343532728424366, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.1688083787414252, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137670.447546} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.199987411499023, "x": 27.549674178792863, "y": -0.08692856376996616, "z": null, "yaw": 0.028130655100465533, "pitch": null, "roll": null}, "v": 2.345431063379066, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3722820218995879, "steering_wheel_angle": -0.08695180276671388, "front_wheel_angle": -0.003997752695129866, "heading_rate": -0.0036626966042031177, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137670.467546} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2513878804757253, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.998094733124442, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3425147449022066, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.1688083787414252, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137670.467546} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.199987411499023, "x": 27.549674178792863, "y": -0.08692856376996616, "z": null, "yaw": 0.028130655100465533, "pitch": null, "roll": null}, "v": 2.345431063379066, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3722820218995879, "steering_wheel_angle": -0.08695180276671388, "front_wheel_angle": -0.003997752695129866, "heading_rate": -0.0036626966042031177, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137670.487546} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2513878804757253, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.998094733124442, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.341498732368846, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.1688083787414252, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137670.487546} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.199987411499023, "x": 27.549674178792863, "y": -0.08692856376996616, "z": null, "yaw": 0.028130655100465533, "pitch": null, "roll": null}, "v": 2.345431063379066, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3722820218995879, "steering_wheel_angle": -0.08695180276671388, "front_wheel_angle": -0.003997752695129866, "heading_rate": -0.0036626966042031177, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137670.507546} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2513878804757253, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.998094733124442, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3404846865954023, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.1688083787414252, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137670.507546} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137670.517546, "x": 31.807303867630367, "y": 4.920286537268356, "z": null, "yaw": 0.027818899464696095, "pitch": null, "roll": null}, "v": 2.3399783999250188, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37175390911740747, "steering_wheel_angle": -0.1688083787414252, "front_wheel_angle": -0.007769612358623842, "heading_rate": -0.007101988649087752, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137670.527546} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2537563502563793, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0499703690048923, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3394726033635775, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.1688083787414252, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137670.527546} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.309987306594849, "x": 27.807303867630367, "y": -0.07971346273164404, "z": null, "yaw": 0.027818899464696095, "pitch": null, "roll": null}, "v": 2.3399783999250188, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37175390911740747, "steering_wheel_angle": -0.1688083787414252, "front_wheel_angle": -0.007769612358623842, "heading_rate": -0.007101988649087752, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137670.547546} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2525882697558231, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0499703690048923, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3387583939241665, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.20972902233439306, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137670.547546} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.309987306594849, "x": 27.807303867630367, "y": -0.07971346273164404, "z": null, "yaw": 0.027818899464696095, "pitch": null, "roll": null}, "v": 2.3399783999250188, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37175390911740747, "steering_wheel_angle": -0.1688083787414252, "front_wheel_angle": -0.007769612358623842, "heading_rate": -0.007101988649087752, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137670.567546} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2525882697558231, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0499703690048923, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.337899626804053, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.20972902233439306, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137670.567546} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.309987306594849, "x": 27.807303867630367, "y": -0.07971346273164404, "z": null, "yaw": 0.027818899464696095, "pitch": null, "roll": null}, "v": 2.3399783999250188, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37175390911740747, "steering_wheel_angle": -0.1688083787414252, "front_wheel_angle": -0.007769612358623842, "heading_rate": -0.007101988649087752, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137670.5875459} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2525882697558231, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0499703690048923, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3370425208053165, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.20972902233439306, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137670.5875459} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.309987306594849, "x": 27.807303867630367, "y": -0.07971346273164404, "z": null, "yaw": 0.027818899464696095, "pitch": null, "roll": null}, "v": 2.3399783999250188, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37175390911740747, "steering_wheel_angle": -0.1688083787414252, "front_wheel_angle": -0.007769612358623842, "heading_rate": -0.007101988649087752, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137670.6075459} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2525882697558231, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0499703690048923, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3361870724211244, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.20972902233439306, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137670.6075459} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137670.6275458, "x": 32.064371898445295, "y": 4.927394496310394, "z": null, "yaw": 0.027418639754756606, "pitch": null, "roll": null}, "v": 2.3353332781531293, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3713044791081509, "steering_wheel_angle": -0.20972902233439306, "front_wheel_angle": -0.00965824949087056, "heading_rate": -0.008810911250641342, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137670.6275458} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2520084291987983, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0401176098638032, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3353332781531293, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.20972902233439306, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137670.6275458} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.419987201690674, "x": 28.064371898445295, "y": -0.07260550368960583, "z": null, "yaw": 0.027418639754756606, "pitch": null, "roll": null}, "v": 2.3353332781531293, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3713044791081509, "steering_wheel_angle": -0.20972902233439306, "front_wheel_angle": -0.00965824949087056, "heading_rate": -0.008810911250641342, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137670.6475458} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2522503015841687, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0401176098638032, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.334408689485126, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.20972902233439306, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137670.6475458} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.419987201690674, "x": 28.064371898445295, "y": -0.07260550368960583, "z": null, "yaw": 0.027418639754756606, "pitch": null, "roll": null}, "v": 2.3353332781531293, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3713044791081509, "steering_wheel_angle": -0.20972902233439306, "front_wheel_angle": -0.00965824949087056, "heading_rate": -0.008810911250641342, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137670.6675458} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2522503015841687, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0401176098638032, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3335161074071733, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.20972902233439306, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137670.6675458} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.419987201690674, "x": 28.064371898445295, "y": -0.07260550368960583, "z": null, "yaw": 0.027418639754756606, "pitch": null, "roll": null}, "v": 2.3353332781531293, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3713044791081509, "steering_wheel_angle": -0.20972902233439306, "front_wheel_angle": -0.00965824949087056, "heading_rate": -0.008810911250641342, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137670.6875458} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2522503015841687, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0401176098638032, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3326252502986606, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.20972902233439306, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137670.6875458} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.419987201690674, "x": 28.064371898445295, "y": -0.07260550368960583, "z": null, "yaw": 0.027418639754756606, "pitch": null, "roll": null}, "v": 2.3353332781531293, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3713044791081509, "steering_wheel_angle": -0.20972902233439306, "front_wheel_angle": -0.00965824949087056, "heading_rate": -0.008810911250641342, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137670.7075458} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2522503015841687, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0401176098638032, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3317361145086823, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.20972902233439306, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137670.7075458} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.419987201690674, "x": 28.064371898445295, "y": -0.07260550368960583, "z": null, "yaw": 0.027418639754756606, "pitch": null, "roll": null}, "v": 2.3353332781531293, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3713044791081509, "steering_wheel_angle": -0.20972902233439306, "front_wheel_angle": -0.00965824949087056, "heading_rate": -0.008810911250641342, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137670.7275457} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2522503015841687, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0401176098638032, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.330848696395226, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.20972902233439306, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137670.7275457} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137670.7375457, "x": 32.320915198803625, "y": 4.934381915052293, "z": null, "yaw": 0.027003623942393834, "pitch": null, "roll": null}, "v": 2.33040563033149, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3708281855353816, "steering_wheel_angle": -0.20972902233439306, "front_wheel_angle": -0.00965824949087056, "heading_rate": -0.00879231987097102, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137670.7475457} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25139213827936613, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0309414637103766, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3299629923251466, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.20972902233439306, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137670.7475457} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.529987096786499, "x": 28.320915198803625, "y": -0.06561808494770727, "z": null, "yaw": 0.027003623942393834, "pitch": null, "roll": null}, "v": 2.33040563033149, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3708281855353816, "steering_wheel_angle": -0.20972902233439306, "front_wheel_angle": -0.00965824949087056, "heading_rate": -0.00879231987097102, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137670.7675457} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2517644986240238, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0309414637103766, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3289717800672225, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.20972902233439306, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137670.7675457} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.529987096786499, "x": 28.320915198803625, "y": -0.06561808494770727, "z": null, "yaw": 0.027003623942393834, "pitch": null, "roll": null}, "v": 2.33040563033149, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3708281855353816, "steering_wheel_angle": -0.20972902233439306, "front_wheel_angle": -0.00965824949087056, "heading_rate": -0.00879231987097102, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137670.7875457} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2517644986240238, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0309414637103766, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3280290041662095, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.20972902233439306, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137670.7875457} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.529987096786499, "x": 28.320915198803625, "y": -0.06561808494770727, "z": null, "yaw": 0.027003623942393834, "pitch": null, "roll": null}, "v": 2.33040563033149, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3708281855353816, "steering_wheel_angle": -0.20972902233439306, "front_wheel_angle": -0.00965824949087056, "heading_rate": -0.00879231987097102, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137670.8075457} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2517644986240238, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0309414637103766, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3270880481747547, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.20972902233439306, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137670.8075457} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.529987096786499, "x": 28.320915198803625, "y": -0.06561808494770727, "z": null, "yaw": 0.027003623942393834, "pitch": null, "roll": null}, "v": 2.33040563033149, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3708281855353816, "steering_wheel_angle": -0.20972902233439306, "front_wheel_angle": -0.00965824949087056, "heading_rate": -0.00879231987097102, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137670.8275456} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2517644986240238, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0309414637103766, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3261489082257647, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.20972902233439306, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137670.8275456} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137670.8475456, "x": 32.57690743656422, "y": 4.941248007313584, "z": null, "yaw": 0.026588608130031062, "pitch": null, "roll": null}, "v": 2.3252115804616595, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37032666796221303, "steering_wheel_angle": -0.20972902233439306, "front_wheel_angle": -0.00965824949087056, "heading_rate": -0.008772723390733017, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137670.8475456} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25415630229292413, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0756618020053885, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3252115804616595, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.20972902233439306, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137670.8475456} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.639986991882324, "x": 28.57690743656422, "y": -0.05875199268641573, "z": null, "yaw": 0.026588608130031062, "pitch": null, "roll": null}, "v": 2.3252115804616595, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37032666796221303, "steering_wheel_angle": -0.20972902233439306, "front_wheel_angle": -0.00965824949087056, "heading_rate": -0.008772723390733017, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137670.8675456} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2529791367141131, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0756618020053885, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.324574892242728, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2506344552091472, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137670.8675456} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.639986991882324, "x": 28.57690743656422, "y": -0.05875199268641573, "z": null, "yaw": 0.026588608130031062, "pitch": null, "roll": null}, "v": 2.3252115804616595, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37032666796221303, "steering_wheel_angle": -0.20972902233439306, "front_wheel_angle": -0.00965824949087056, "heading_rate": -0.008772723390733017, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137670.8875456} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2529791367141131, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0756618020053885, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.32379235746049, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2506344552091472, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137670.8875456} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.639986991882324, "x": 28.57690743656422, "y": -0.05875199268641573, "z": null, "yaw": 0.026588608130031062, "pitch": null, "roll": null}, "v": 2.3252115804616595, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37032666796221303, "steering_wheel_angle": -0.20972902233439306, "front_wheel_angle": -0.00965824949087056, "heading_rate": -0.008772723390733017, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137670.9075456} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2529791367141131, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0756618020053885, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3230113319252284, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2506344552091472, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137670.9075456} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.639986991882324, "x": 28.57690743656422, "y": -0.05875199268641573, "z": null, "yaw": 0.026588608130031062, "pitch": null, "roll": null}, "v": 2.3252115804616595, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37032666796221303, "steering_wheel_angle": -0.20972902233439306, "front_wheel_angle": -0.00965824949087056, "heading_rate": -0.008772723390733017, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137670.9275455} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2529791367141131, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0756618020053885, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.322231812482229, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2506344552091472, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137670.9275455} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.639986991882324, "x": 28.57690743656422, "y": -0.05875199268641573, "z": null, "yaw": 0.026588608130031062, "pitch": null, "roll": null}, "v": 2.3252115804616595, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37032666796221303, "steering_wheel_angle": -0.20972902233439306, "front_wheel_angle": -0.00965824949087056, "heading_rate": -0.008772723390733017, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137670.9475455} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2529791367141131, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0756618020053885, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3214537959842727, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2506344552091472, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137670.9475455} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137670.9575455, "x": 32.832390760247094, "y": 4.94798662178202, "z": null, "yaw": 0.02609975656316524, "pitch": null, "roll": null}, "v": 2.3210653503582237, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36992671112424663, "steering_wheel_angle": -0.2506344552091472, "front_wheel_angle": -0.011548231739108714, "heading_rate": -0.010470856313273012, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137670.9675455} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2525154966003944, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0546632222687364, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3206772792916133, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2506344552091472, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137670.9675455} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.74998688697815, "x": 28.832390760247094, "y": -0.05201337821798013, "z": null, "yaw": 0.02609975656316524, "pitch": null, "roll": null}, "v": 2.3210653503582237, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36992671112424663, "steering_wheel_angle": -0.2506344552091472, "front_wheel_angle": -0.011548231739108714, "heading_rate": -0.010470856313273012, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137670.9875455} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2527058048000541, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0546632222687364, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.319844332193653, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2506344552091472, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137670.9875455} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.74998688697815, "x": 28.832390760247094, "y": -0.05201337821798013, "z": null, "yaw": 0.02609975656316524, "pitch": null, "roll": null}, "v": 2.3210653503582237, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36992671112424663, "steering_wheel_angle": -0.2506344552091472, "front_wheel_angle": -0.011548231739108714, "heading_rate": -0.010470856313273012, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137671.0075455} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2527058048000541, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0546632222687364, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3190367673214087, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2506344552091472, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137671.0075455} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.74998688697815, "x": 28.832390760247094, "y": -0.05201337821798013, "z": null, "yaw": 0.02609975656316524, "pitch": null, "roll": null}, "v": 2.3210653503582237, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36992671112424663, "steering_wheel_angle": -0.2506344552091472, "front_wheel_angle": -0.011548231739108714, "heading_rate": -0.010470856313273012, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137671.0275455} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2527058048000541, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0546632222687364, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3182307584381068, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2506344552091472, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137671.0275455} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.74998688697815, "x": 28.832390760247094, "y": -0.05201337821798013, "z": null, "yaw": 0.02609975656316524, "pitch": null, "roll": null}, "v": 2.3210653503582237, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36992671112424663, "steering_wheel_angle": -0.2506344552091472, "front_wheel_angle": -0.011548231739108714, "heading_rate": -0.010470856313273012, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137671.0475454} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2527058048000541, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0546632222687364, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3174263022859845, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2506344552091472, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137671.0475454} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137671.0675454, "x": 33.087400055374104, "y": 4.954586274970827, "z": null, "yaw": 0.02560352142084911, "pitch": null, "roll": null}, "v": 2.3166233956150566, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3694986093518632, "steering_wheel_angle": -0.2506344552091472, "front_wheel_angle": -0.011548231739108714, "heading_rate": -0.01045081764014449, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137671.0675454} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2550389870091075, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.097351964145819, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.316113542493039, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2506344552091472, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137671.0675454} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.859986782073975, "x": 29.087400055374104, "y": -0.045413725029172625, "z": null, "yaw": 0.02560352142084911, "pitch": null, "roll": null}, "v": 2.3166233956150566, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3694986093518632, "steering_wheel_angle": -0.2506344552091472, "front_wheel_angle": -0.011548231739108714, "heading_rate": -0.01045081764014449, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137671.0875454} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2538953300127367, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.097351964145819, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.316113542493039, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2506344552091472, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137671.0875454} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.859986782073975, "x": 29.087400055374104, "y": -0.045413725029172625, "z": null, "yaw": 0.02560352142084911, "pitch": null, "roll": null}, "v": 2.3166233956150566, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3694986093518632, "steering_wheel_angle": -0.2506344552091472, "front_wheel_angle": -0.011548231739108714, "heading_rate": -0.01045081764014449, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137671.1075454} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2538953300127367, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.097351964145819, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.315461782849252, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2506344552091472, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137671.1075454} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.859986782073975, "x": 29.087400055374104, "y": -0.045413725029172625, "z": null, "yaw": 0.02560352142084911, "pitch": null, "roll": null}, "v": 2.3166233956150566, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3694986093518632, "steering_wheel_angle": -0.2506344552091472, "front_wheel_angle": -0.011548231739108714, "heading_rate": -0.01045081764014449, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137671.1275454} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2538953300127367, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.097351964145819, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3148112780528485, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2506344552091472, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137671.1275454} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.859986782073975, "x": 29.087400055374104, "y": -0.045413725029172625, "z": null, "yaw": 0.02560352142084911, "pitch": null, "roll": null}, "v": 2.3166233956150566, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3694986093518632, "steering_wheel_angle": -0.2506344552091472, "front_wheel_angle": -0.011548231739108714, "heading_rate": -0.01045081764014449, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137671.1475453} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2538953300127367, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.097351964145819, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3141620255186615, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2506344552091472, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137671.1475453} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.859986782073975, "x": 29.087400055374104, "y": -0.045413725029172625, "z": null, "yaw": 0.02560352142084911, "pitch": null, "roll": null}, "v": 2.3166233956150566, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3694986093518632, "steering_wheel_angle": -0.2506344552091472, "front_wheel_angle": -0.011548231739108714, "heading_rate": -0.01045081764014449, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137671.1675453} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2538953300127367, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.097351964145819, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.313190489068633, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2506344552091472, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137671.1675453} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137671.1775453, "x": 33.34198107645306, "y": 4.961048424984262, "z": null, "yaw": 0.02510728627853298, "pitch": null, "roll": null}, "v": 2.313190489068633, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36916802684060745, "steering_wheel_angle": -0.2506344552091472, "front_wheel_angle": -0.011548231739108714, "heading_rate": -0.010435331014066103, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137671.1875453} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.253726324670649, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0832291518790715, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.312867266926023, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2506344552091472, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137671.1875453} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.9699866771698, "x": 29.34198107645306, "y": -0.038951575015738094, "z": null, "yaw": 0.02510728627853298, "pitch": null, "roll": null}, "v": 2.313190489068633, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36916802684060745, "steering_wheel_angle": -0.2506344552091472, "front_wheel_angle": -0.011548231739108714, "heading_rate": -0.010435331014066103, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137671.2075453} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2537816161936442, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0832291518790715, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.311871263737914, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2506344552091472, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137671.2075453} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.9699866771698, "x": 29.34198107645306, "y": -0.038951575015738094, "z": null, "yaw": 0.02510728627853298, "pitch": null, "roll": null}, "v": 2.313190489068633, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36916802684060745, "steering_wheel_angle": -0.2506344552091472, "front_wheel_angle": -0.011548231739108714, "heading_rate": -0.010435331014066103, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137671.2275453} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2537816161936442, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0832291518790715, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3115422042441383, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2506344552091472, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137671.2275453} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.9699866771698, "x": 29.34198107645306, "y": -0.038951575015738094, "z": null, "yaw": 0.02510728627853298, "pitch": null, "roll": null}, "v": 2.313190489068633, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36916802684060745, "steering_wheel_angle": -0.2506344552091472, "front_wheel_angle": -0.011548231739108714, "heading_rate": -0.010435331014066103, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137671.2475452} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2537816161936442, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0832291518790715, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.310885034932889, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2506344552091472, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137671.2475452} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.9699866771698, "x": 29.34198107645306, "y": -0.038951575015738094, "z": null, "yaw": 0.02510728627853298, "pitch": null, "roll": null}, "v": 2.313190489068633, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36916802684060745, "steering_wheel_angle": -0.2506344552091472, "front_wheel_angle": -0.011548231739108714, "heading_rate": -0.010435331014066103, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137671.2675452} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2537816161936442, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0832291518790715, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3102291296828104, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2506344552091472, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137671.2675452} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137671.2875452, "x": 33.596172286818486, "y": 4.967374462617301, "z": null, "yaw": 0.024611051136216852, "pitch": null, "roll": null}, "v": 2.309574485890487, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36882006735328743, "steering_wheel_angle": -0.2506344552091472, "front_wheel_angle": -0.011548231739108714, "heading_rate": -0.010419018397232261, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137671.2875452} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2559575579212805, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1307235355303051, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.309574485890487, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2506344552091472, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137671.2875452} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.079986572265625, "x": 29.596172286818486, "y": -0.03262553738269869, "z": null, "yaw": 0.024611051136216852, "pitch": null, "roll": null}, "v": 2.309574485890487, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36882006735328743, "steering_wheel_angle": -0.2506344552091472, "front_wheel_angle": -0.011548231739108714, "heading_rate": -0.010419018397232261, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137671.3075452} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2548948834639484, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1307235355303051, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.308936059385665, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2915580197087371, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137671.3075452} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.079986572265625, "x": 29.596172286818486, "y": -0.03262553738269869, "z": null, "yaw": 0.024611051136216852, "pitch": null, "roll": null}, "v": 2.309574485890487, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36882006735328743, "steering_wheel_angle": -0.2506344552091472, "front_wheel_angle": -0.011548231739108714, "heading_rate": -0.010419018397232261, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137671.3275452} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2548948834639484, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1307235355303051, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.308679402999836, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2915580197087371, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137671.3275452} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.079986572265625, "x": 29.596172286818486, "y": -0.03262553738269869, "z": null, "yaw": 0.024611051136216852, "pitch": null, "roll": null}, "v": 2.309574485890487, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36882006735328743, "steering_wheel_angle": -0.2506344552091472, "front_wheel_angle": -0.011548231739108714, "heading_rate": -0.010419018397232261, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137671.3475451} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2548948834639484, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1307235355303051, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.308166830504346, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2915580197087371, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137671.3475451} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.079986572265625, "x": 29.596172286818486, "y": -0.03262553738269869, "z": null, "yaw": 0.024611051136216852, "pitch": null, "roll": null}, "v": 2.309574485890487, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36882006735328743, "steering_wheel_angle": -0.2506344552091472, "front_wheel_angle": -0.011548231739108714, "heading_rate": -0.010419018397232261, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137671.3675451} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2548948834639484, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1307235355303051, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3076552433747493, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2915580197087371, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137671.3675451} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.079986572265625, "x": 29.596172286818486, "y": -0.03262553738269869, "z": null, "yaw": 0.024611051136216852, "pitch": null, "roll": null}, "v": 2.309574485890487, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36882006735328743, "steering_wheel_angle": -0.2506344552091472, "front_wheel_angle": -0.011548231739108714, "heading_rate": -0.010419018397232261, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137671.387545} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2548948834639484, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1307235355303051, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.307144639612147, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2915580197087371, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137671.387545} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137671.397545, "x": 33.85002164536537, "y": 4.9735582607848885, "z": null, "yaw": 0.024040864005368916, "pitch": null, "roll": null}, "v": 2.3068897058700286, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3685618864439925, "steering_wheel_angle": -0.2915580197087371, "front_wheel_angle": -0.013441106539759336, "heading_rate": -0.012112897551635898, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137671.407545} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2517748677052801, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0434810672146058, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.306185572434787, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2915580197087371, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137671.407545} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.18998646736145, "x": 29.850021645365374, "y": -0.026441739215111504, "z": null, "yaw": 0.024040864005368916, "pitch": null, "roll": null}, "v": 2.3068897058700286, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3685618864439925, "steering_wheel_angle": -0.2915580197087371, "front_wheel_angle": -0.013441106539759336, "heading_rate": -0.012112897551635898, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137671.427545} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2532409193010565, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0434810672146058, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.305287978534164, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2915580197087371, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137671.427545} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.18998646736145, "x": 29.850021645365374, "y": -0.026441739215111504, "z": null, "yaw": 0.024040864005368916, "pitch": null, "roll": null}, "v": 2.3068897058700286, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3685618864439925, "steering_wheel_angle": -0.2915580197087371, "front_wheel_angle": -0.013441106539759336, "heading_rate": -0.012112897551635898, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137671.447545} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2532409193010565, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0434810672146058, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.304931456734815, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2915580197087371, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137671.447545} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.18998646736145, "x": 29.850021645365374, "y": -0.026441739215111504, "z": null, "yaw": 0.024040864005368916, "pitch": null, "roll": null}, "v": 2.3068897058700286, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3685618864439925, "steering_wheel_angle": -0.2915580197087371, "front_wheel_angle": -0.013441106539759336, "heading_rate": -0.012112897551635898, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137671.467545} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2532409193010565, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0434810672146058, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3038639456701975, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2915580197087371, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137671.467545} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.18998646736145, "x": 29.850021645365374, "y": -0.026441739215111504, "z": null, "yaw": 0.024040864005368916, "pitch": null, "roll": null}, "v": 2.3068897058700286, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3685618864439925, "steering_wheel_angle": -0.2915580197087371, "front_wheel_angle": -0.013441106539759336, "heading_rate": -0.012112897551635898, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137671.487545} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2532409193010565, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0434810672146058, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3035087922456623, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2915580197087371, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137671.487545} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137671.507545, "x": 34.103499842324034, "y": 4.979586706355638, "z": null, "yaw": 0.0234632816756678, "pitch": null, "roll": null}, "v": 2.3027995086709883, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3681688312049029, "steering_wheel_angle": -0.2915580197087371, "front_wheel_angle": -0.013441106539759336, "heading_rate": -0.012091420955025363, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137671.507545} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25566389444219256, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0812824684579871, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.302596813761576, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2915580197087371, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137671.507545} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.299986362457275, "x": 30.103499842324034, "y": -0.02041329364436173, "z": null, "yaw": 0.0234632816756678, "pitch": null, "roll": null}, "v": 2.3027995086709883, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3681688312049029, "steering_wheel_angle": -0.2915580197087371, "front_wheel_angle": -0.013441106539759336, "heading_rate": -0.012091420955025363, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137671.527545} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25448014909876937, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0812824684579871, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3023943135486578, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2915580197087371, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137671.527545} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.299986362457275, "x": 30.103499842324034, "y": -0.02041329364436173, "z": null, "yaw": 0.0234632816756678, "pitch": null, "roll": null}, "v": 2.3027995086709883, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3681688312049029, "steering_wheel_angle": -0.2915580197087371, "front_wheel_angle": -0.013441106539759336, "heading_rate": -0.012091420955025363, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137671.547545} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25448014909876937, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0812824684579871, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.301841999320318, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2915580197087371, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137671.547545} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.299986362457275, "x": 30.103499842324034, "y": -0.02041329364436173, "z": null, "yaw": 0.0234632816756678, "pitch": null, "roll": null}, "v": 2.3027995086709883, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3681688312049029, "steering_wheel_angle": -0.2915580197087371, "front_wheel_angle": -0.013441106539759336, "heading_rate": -0.012091420955025363, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137671.567545} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25448014909876937, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0812824684579871, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3012907454633287, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2915580197087371, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137671.567545} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.299986362457275, "x": 30.103499842324034, "y": -0.02041329364436173, "z": null, "yaw": 0.0234632816756678, "pitch": null, "roll": null}, "v": 2.3027995086709883, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3681688312049029, "steering_wheel_angle": -0.2915580197087371, "front_wheel_angle": -0.013441106539759336, "heading_rate": -0.012091420955025363, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137671.587545} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25448014909876937, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0812824684579871, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3007405498204205, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2915580197087371, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137671.587545} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.299986362457275, "x": 30.103499842324034, "y": -0.02041329364436173, "z": null, "yaw": 0.0234632816756678, "pitch": null, "roll": null}, "v": 2.3027995086709883, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3681688312049029, "steering_wheel_angle": -0.2915580197087371, "front_wheel_angle": -0.013441106539759336, "heading_rate": -0.012091420955025363, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137671.607545} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25448014909876937, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0812824684579871, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2999172358003457, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2915580197087371, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137671.607545} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137671.617545, "x": 34.3566019136785, "y": 4.985459932000051, "z": null, "yaw": 0.02288569934596668, "pitch": null, "roll": null}, "v": 2.2999172358003457, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36789205470533237, "steering_wheel_angle": -0.2915580197087371, "front_wheel_angle": -0.013441106539759336, "heading_rate": -0.01207628686521209, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137671.6275449} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25649288116756835, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1217462858987848, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2996433245719654, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2915580197087371, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137671.6275449} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.4099862575531, "x": 30.356601913678503, "y": -0.014540067999949002, "z": null, "yaw": 0.02288569934596668, "pitch": null, "roll": null}, "v": 2.2999172358003457, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36789205470533237, "steering_wheel_angle": -0.2915580197087371, "front_wheel_angle": -0.013441106539759336, "heading_rate": -0.01207628686521209, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137671.6475449} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25551334910266343, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1217462858987848, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.299200192614441, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2915580197087371, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137671.6475449} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.4099862575531, "x": 30.356601913678503, "y": -0.014540067999949002, "z": null, "yaw": 0.02288569934596668, "pitch": null, "roll": null}, "v": 2.2999172358003457, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36789205470533237, "steering_wheel_angle": -0.2915580197087371, "front_wheel_angle": -0.013441106539759336, "heading_rate": -0.01207628686521209, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137671.6675448} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25551334910266343, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1217462858987848, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2987830970187995, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2915580197087371, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137671.6675448} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.4099862575531, "x": 30.356601913678503, "y": -0.014540067999949002, "z": null, "yaw": 0.02288569934596668, "pitch": null, "roll": null}, "v": 2.2999172358003457, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36789205470533237, "steering_wheel_angle": -0.2915580197087371, "front_wheel_angle": -0.013441106539759336, "heading_rate": -0.01207628686521209, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137671.6875448} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25551334910266343, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1217462858987848, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2985748494164926, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2915580197087371, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137671.6875448} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.4099862575531, "x": 30.356601913678503, "y": -0.014540067999949002, "z": null, "yaw": 0.02288569934596668, "pitch": null, "roll": null}, "v": 2.2999172358003457, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36789205470533237, "steering_wheel_angle": -0.2915580197087371, "front_wheel_angle": -0.013441106539759336, "heading_rate": -0.01207628686521209, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137671.7075448} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25551334910266343, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1217462858987848, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2981589535994367, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2915580197087371, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137671.7075448} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137671.7275448, "x": 34.609421504044604, "y": 4.991180497594774, "z": null, "yaw": 0.022308117016265564, "pitch": null, "roll": null}, "v": 2.2977438556303693, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36768346104238964, "steering_wheel_angle": -0.2915580197087371, "front_wheel_angle": -0.013441106539759336, "heading_rate": -0.012064874992649351, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137671.7275448} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2572730816608134, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1653370859000673, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2977438556303693, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2915580197087371, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137671.7275448} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.519986152648926, "x": 30.609421504044604, "y": -0.008819502405225776, "z": null, "yaw": 0.022308117016265564, "pitch": null, "roll": null}, "v": 2.2977438556303693, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36768346104238964, "steering_wheel_angle": -0.2915580197087371, "front_wheel_angle": -0.013441106539759336, "heading_rate": -0.012064874992649351, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137671.7475448} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25641922049892923, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1653370859000673, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2975494149486138, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.33247647273543735, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137671.7475448} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.519986152648926, "x": 30.609421504044604, "y": -0.008819502405225776, "z": null, "yaw": 0.022308117016265564, "pitch": null, "roll": null}, "v": 2.2977438556303693, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36768346104238964, "steering_wheel_angle": -0.2915580197087371, "front_wheel_angle": -0.013441106539759336, "heading_rate": -0.012064874992649351, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137671.7675447} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25641922049892923, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1653370859000673, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2972486657860927, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.33247647273543735, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137671.7675447} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.519986152648926, "x": 30.609421504044604, "y": -0.008819502405225776, "z": null, "yaw": 0.022308117016265564, "pitch": null, "roll": null}, "v": 2.2977438556303693, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36768346104238964, "steering_wheel_angle": -0.2915580197087371, "front_wheel_angle": -0.013441106539759336, "heading_rate": -0.012064874992649351, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137671.7875447} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25641922049892923, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1653370859000673, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2969484934631668, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.33247647273543735, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137671.7875447} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.519986152648926, "x": 30.609421504044604, "y": -0.008819502405225776, "z": null, "yaw": 0.022308117016265564, "pitch": null, "roll": null}, "v": 2.2977438556303693, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36768346104238964, "steering_wheel_angle": -0.2915580197087371, "front_wheel_angle": -0.013441106539759336, "heading_rate": -0.012064874992649351, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137671.8075447} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25641922049892923, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1653370859000673, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2966488968374286, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.33247647273543735, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137671.8075447} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.519986152648926, "x": 30.609421504044604, "y": -0.008819502405225776, "z": null, "yaw": 0.022308117016265564, "pitch": null, "roll": null}, "v": 2.2977438556303693, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36768346104238964, "steering_wheel_angle": -0.2915580197087371, "front_wheel_angle": -0.013441106539759336, "heading_rate": -0.012064874992649351, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137671.8275447} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25641922049892923, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1653370859000673, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.296349874768869, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.33247647273543735, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137671.8275447} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137671.8375447, "x": 34.862039580407824, "y": 4.996742867336644, "z": null, "yaw": 0.021656507622484257, "pitch": null, "roll": null}, "v": 2.2962005788379325, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36753539992445317, "steering_wheel_angle": -0.33247647273543735, "front_wheel_angle": -0.01533580650344451, "heading_rate": -0.013756581508326824, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137671.8475447} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2531510209273468, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1474806257581882, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2960514261198712, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.33247647273543735, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137671.8475447} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.629986047744751, "x": 30.862039580407824, "y": -0.0032571326633563658, "z": null, "yaw": 0.021656507622484257, "pitch": null, "roll": null}, "v": 2.2962005788379325, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36753539992445317, "steering_wheel_angle": -0.33247647273543735, "front_wheel_angle": -0.01533580650344451, "heading_rate": -0.013756581508326824, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137671.8675447} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.254696026362341, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1474806257581882, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.295089188798213, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.33247647273543735, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137671.8675447} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.629986047744751, "x": 30.862039580407824, "y": -0.0032571326633563658, "z": null, "yaw": 0.021656507622484257, "pitch": null, "roll": null}, "v": 2.2962005788379325, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36753539992445317, "steering_wheel_angle": -0.33247647273543735, "front_wheel_angle": -0.01533580650344451, "heading_rate": -0.013756581508326824, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137671.8875446} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.254696026362341, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1474806257581882, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.294833402413006, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.33247647273543735, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137671.8875446} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.629986047744751, "x": 30.862039580407824, "y": -0.0032571326633563658, "z": null, "yaw": 0.021656507622484257, "pitch": null, "roll": null}, "v": 2.2962005788379325, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36753539992445317, "steering_wheel_angle": -0.33247647273543735, "front_wheel_angle": -0.01533580650344451, "heading_rate": -0.013756581508326824, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137671.9075446} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.254696026362341, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1474806257581882, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.294067514047424, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.33247647273543735, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137671.9075446} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.629986047744751, "x": 30.862039580407824, "y": -0.0032571326633563658, "z": null, "yaw": 0.021656507622484257, "pitch": null, "roll": null}, "v": 2.2962005788379325, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36753539992445317, "steering_wheel_angle": -0.33247647273543735, "front_wheel_angle": -0.01533580650344451, "heading_rate": -0.013756581508326824, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137671.9275446} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.254696026362341, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1474806257581882, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2938127073621457, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.33247647273543735, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137671.9275446} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137671.9475446, "x": 35.11441757492206, "y": 5.002133730624571, "z": null, "yaw": 0.02099749552229493, "pitch": null, "roll": null}, "v": 2.2933038266611785, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36725761574684695, "steering_wheel_angle": -0.33247647273543735, "front_wheel_angle": -0.01533580650344451, "heading_rate": -0.013739227010729271, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137671.9475446} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2568385790266973, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1896676992404505, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2933038266611785, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.33247647273543735, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137671.9475446} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.739985942840576, "x": 31.114417574922058, "y": 0.0021337306245712284, "z": null, "yaw": 0.02099749552229493, "pitch": null, "roll": null}, "v": 2.2933038266611785, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36725761574684695, "steering_wheel_angle": -0.33247647273543735, "front_wheel_angle": -0.01533580650344451, "heading_rate": -0.013739227010729271, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137671.9675446} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2557971508241854, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1896676992404505, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.293063611920575, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.37337806295000836, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137671.9675446} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.739985942840576, "x": 31.114417574922058, "y": 0.0021337306245712284, "z": null, "yaw": 0.02099749552229493, "pitch": null, "roll": null}, "v": 2.2933038266611785, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36725761574684695, "steering_wheel_angle": -0.33247647273543735, "front_wheel_angle": -0.01533580650344451, "heading_rate": -0.013739227010729271, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137671.9875445} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2557971508241854, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1896676992404505, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.292693741378906, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.37337806295000836, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137671.9875445} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.739985942840576, "x": 31.114417574922058, "y": 0.0021337306245712284, "z": null, "yaw": 0.02099749552229493, "pitch": null, "roll": null}, "v": 2.2933038266611785, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36725761574684695, "steering_wheel_angle": -0.33247647273543735, "front_wheel_angle": -0.01533580650344451, "heading_rate": -0.013739227010729271, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137672.0075445} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2557971508241854, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1896676992404505, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.292140264020473, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.37337806295000836, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137672.0075445} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.739985942840576, "x": 31.114417574922058, "y": 0.0021337306245712284, "z": null, "yaw": 0.02099749552229493, "pitch": null, "roll": null}, "v": 2.2933038266611785, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36725761574684695, "steering_wheel_angle": -0.33247647273543735, "front_wheel_angle": -0.01533580650344451, "heading_rate": -0.013739227010729271, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137672.0275445} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2557971508241854, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1896676992404505, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2919561251159797, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.37337806295000836, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137672.0275445} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.739985942840576, "x": 31.114417574922058, "y": 0.0021337306245712284, "z": null, "yaw": 0.02099749552229493, "pitch": null, "roll": null}, "v": 2.2933038266611785, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36725761574684695, "steering_wheel_angle": -0.33247647273543735, "front_wheel_angle": -0.01533580650344451, "heading_rate": -0.013739227010729271, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137672.0475445} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2557971508241854, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1896676992404505, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.291588376572584, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.37337806295000836, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137672.0475445} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137672.0575445, "x": 35.36653785275707, "y": 5.007345216419787, "z": null, "yaw": 0.02026440180195232, "pitch": null, "roll": null}, "v": 2.2914047665820454, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3670755963722515, "steering_wheel_angle": -0.37337806295000836, "front_wheel_angle": -0.01723179257821051, "heading_rate": -0.015425359480890872, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137672.0675445} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2538265062596089, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1802137075418415, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2912213325448345, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.37337806295000836, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137672.0675445} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.849985837936401, "x": 31.36653785275707, "y": 0.007345216419786915, "z": null, "yaw": 0.02026440180195232, "pitch": null, "roll": null}, "v": 2.2914047665820454, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3670755963722515, "steering_wheel_angle": -0.37337806295000836, "front_wheel_angle": -0.01723179257821051, "heading_rate": -0.015425359480890872, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137672.0875444} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2547510407522358, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1802137075418415, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.290608779075014, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.37337806295000836, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137672.0875444} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.849985837936401, "x": 31.36653785275707, "y": 0.007345216419786915, "z": null, "yaw": 0.02026440180195232, "pitch": null, "roll": null}, "v": 2.2914047665820454, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3670755963722515, "steering_wheel_angle": -0.37337806295000836, "front_wheel_angle": -0.01723179257821051, "heading_rate": -0.015425359480890872, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137672.1075444} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2547510407522358, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1802137075418415, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2901129103332285, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.37337806295000836, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137672.1075444} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.849985837936401, "x": 31.36653785275707, "y": 0.007345216419786915, "z": null, "yaw": 0.02026440180195232, "pitch": null, "roll": null}, "v": 2.2914047665820454, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3670755963722515, "steering_wheel_angle": -0.37337806295000836, "front_wheel_angle": -0.01723179257821051, "heading_rate": -0.015425359480890872, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137672.1275444} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2547510407522358, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1802137075418415, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2896179912678125, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.37337806295000836, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137672.1275444} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.849985837936401, "x": 31.36653785275707, "y": 0.007345216419786915, "z": null, "yaw": 0.02026440180195232, "pitch": null, "roll": null}, "v": 2.2914047665820454, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3670755963722515, "steering_wheel_angle": -0.37337806295000836, "front_wheel_angle": -0.01723179257821051, "heading_rate": -0.015425359480890872, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137672.1475444} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2547510407522358, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1802137075418415, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2891240199620366, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.37337806295000836, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137672.1475444} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137672.1675444, "x": 35.618402618860216, "y": 5.012365013075968, "z": null, "yaw": 0.019523899919594377, "pitch": null, "roll": null}, "v": 2.288630994503405, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36680986801518667, "steering_wheel_angle": -0.37337806295000836, "front_wheel_angle": -0.01723179257821051, "heading_rate": -0.015406686904113917, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137672.1675444} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25700863205777463, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2215144072937747, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.288525935326864, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.37337806295000836, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137672.1675444} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.959985733032227, "x": 31.618402618860216, "y": 0.012365013075967823, "z": null, "yaw": 0.019523899919594377, "pitch": null, "roll": null}, "v": 2.288630994503405, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36680986801518667, "steering_wheel_angle": -0.37337806295000836, "front_wheel_angle": -0.01723179257821051, "heading_rate": -0.015406686904113917, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137672.1875443} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2559133420617393, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2215144072937747, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.288420976767145, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.37337806295000836, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137672.1875443} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.959985733032227, "x": 31.618402618860216, "y": 0.012365013075967823, "z": null, "yaw": 0.019523899919594377, "pitch": null, "roll": null}, "v": 2.288630994503405, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36680986801518667, "steering_wheel_angle": -0.37337806295000836, "front_wheel_angle": -0.01723179257821051, "heading_rate": -0.015406686904113917, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137672.2075443} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2559133420617393, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2215144072937747, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2880745154114686, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.37337806295000836, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137672.2075443} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.959985733032227, "x": 31.618402618860216, "y": 0.012365013075967823, "z": null, "yaw": 0.019523899919594377, "pitch": null, "roll": null}, "v": 2.288630994503405, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36680986801518667, "steering_wheel_angle": -0.37337806295000836, "front_wheel_angle": -0.01723179257821051, "heading_rate": -0.015406686904113917, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137672.2275443} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2559133420617393, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2215144072937747, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2877287173031915, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.37337806295000836, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137672.2275443} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.959985733032227, "x": 31.618402618860216, "y": 0.012365013075967823, "z": null, "yaw": 0.019523899919594377, "pitch": null, "roll": null}, "v": 2.288630994503405, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36680986801518667, "steering_wheel_angle": -0.37337806295000836, "front_wheel_angle": -0.01723179257821051, "heading_rate": -0.015406686904113917, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137672.2475443} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2559133420617393, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2215144072937747, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2873835811248195, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.37337806295000836, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137672.2475443} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.959985733032227, "x": 31.618402618860216, "y": 0.012365013075967823, "z": null, "yaw": 0.019523899919594377, "pitch": null, "roll": null}, "v": 2.288630994503405, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36680986801518667, "steering_wheel_angle": -0.37337806295000836, "front_wheel_angle": -0.01723179257821051, "heading_rate": -0.015406686904113917, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137672.2675443} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2559133420617393, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2215144072937747, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.286867115100696, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.37337806295000836, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137672.2675443} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137672.2775443, "x": 35.870023491855115, "y": 5.0171935450226925, "z": null, "yaw": 0.018783398037236436, "pitch": null, "roll": null}, "v": 2.286867115100696, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3666409677763246, "steering_wheel_angle": -0.37337806295000836, "front_wheel_angle": -0.01723179257821051, "heading_rate": -0.015394812758496114, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137672.2875443} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2559661745014786, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2363614943854, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2866952893017913, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.37337806295000836, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137672.2875443} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.069985628128052, "x": 31.870023491855115, "y": 0.017193545022692547, "z": null, "yaw": 0.018783398037236436, "pitch": null, "roll": null}, "v": 2.286867115100696, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3666409677763246, "steering_wheel_angle": -0.37337806295000836, "front_wheel_angle": -0.01723179257821051, "heading_rate": -0.015394812758496114, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137672.3075442} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2559281475882172, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2363614943854, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.286358731930025, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.414288317478876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137672.3075442} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.069985628128052, "x": 31.870023491855115, "y": 0.017193545022692547, "z": null, "yaw": 0.018783398037236436, "pitch": null, "roll": null}, "v": 2.286867115100696, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3666409677763246, "steering_wheel_angle": -0.37337806295000836, "front_wheel_angle": -0.01723179257821051, "heading_rate": -0.015394812758496114, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137672.3275442} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2559281475882172, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2363614943854, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2860180675257875, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.414288317478876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137672.3275442} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.069985628128052, "x": 31.870023491855115, "y": 0.017193545022692547, "z": null, "yaw": 0.018783398037236436, "pitch": null, "roll": null}, "v": 2.286867115100696, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3666409677763246, "steering_wheel_angle": -0.37337806295000836, "front_wheel_angle": -0.01723179257821051, "heading_rate": -0.015394812758496114, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137672.3475442} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2559281475882172, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2363614943854, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2856780549914175, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.414288317478876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137672.3475442} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.069985628128052, "x": 31.870023491855115, "y": 0.017193545022692547, "z": null, "yaw": 0.018783398037236436, "pitch": null, "roll": null}, "v": 2.286867115100696, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3666409677763246, "steering_wheel_angle": -0.37337806295000836, "front_wheel_angle": -0.01723179257821051, "heading_rate": -0.015394812758496114, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137672.3675442} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2559281475882172, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2363614943854, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.285338693033324, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.414288317478876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137672.3675442} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137672.3875442, "x": 36.12144278146346, "y": 5.0218258618045795, "z": null, "yaw": 0.017976131275661486, "pitch": null, "roll": null}, "v": 2.284999980360657, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36646224812051487, "steering_wheel_angle": -0.414288317478876, "front_wheel_angle": -0.019130254230911675, "heading_rate": -0.017077329600505755, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137672.3875442} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25708928078697413, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2602629112530261, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.284999980360657, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.414288317478876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137672.3875442} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.179985523223877, "x": 32.12144278146346, "y": 0.02182586180457946, "z": null, "yaw": 0.017976131275661486, "pitch": null, "roll": null}, "v": 2.284999980360657, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36646224812051487, "steering_wheel_angle": -0.414288317478876, "front_wheel_angle": -0.019130254230911675, "heading_rate": -0.017077329600505755, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137672.4075441} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2565227431974465, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2602629112530261, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2846752215455006, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.414288317478876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137672.4075441} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.179985523223877, "x": 32.12144278146346, "y": 0.02182586180457946, "z": null, "yaw": 0.017976131275661486, "pitch": null, "roll": null}, "v": 2.284999980360657, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36646224812051487, "steering_wheel_angle": -0.414288317478876, "front_wheel_angle": -0.019130254230911675, "heading_rate": -0.017077329600505755, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137672.427544} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2565227431974465, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2602629112530261, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2845435812977737, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.414288317478876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137672.427544} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.179985523223877, "x": 32.12144278146346, "y": 0.02182586180457946, "z": null, "yaw": 0.017976131275661486, "pitch": null, "roll": null}, "v": 2.284999980360657, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36646224812051487, "steering_wheel_angle": -0.414288317478876, "front_wheel_angle": -0.019130254230911675, "heading_rate": -0.017077329600505755, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137672.447544} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2565227431974465, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2602629112530261, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2842806785866165, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.414288317478876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137672.447544} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.179985523223877, "x": 32.12144278146346, "y": 0.02182586180457946, "z": null, "yaw": 0.017976131275661486, "pitch": null, "roll": null}, "v": 2.284999980360657, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36646224812051487, "steering_wheel_angle": -0.414288317478876, "front_wheel_angle": -0.019130254230911675, "heading_rate": -0.017077329600505755, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137672.467544} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2565227431974465, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2602629112530261, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2840182787618057, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.414288317478876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137672.467544} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.179985523223877, "x": 32.12144278146346, "y": 0.02182586180457946, "z": null, "yaw": 0.017976131275661486, "pitch": null, "roll": null}, "v": 2.284999980360657, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36646224812051487, "steering_wheel_angle": -0.414288317478876, "front_wheel_angle": -0.019130254230911675, "heading_rate": -0.017077329600505755, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137672.487544} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2565227431974465, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2602629112530261, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2837563808338803, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.414288317478876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137672.487544} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137672.497544, "x": 36.37268817849604, "y": 5.026248863081192, "z": null, "yaw": 0.017154027874260534, "pitch": null, "roll": null}, "v": 2.2836256197726037, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3663307407014483, "steering_wheel_angle": -0.414288317478876, "front_wheel_angle": -0.019130254230911675, "heading_rate": -0.017067058086740392, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137672.507544} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25584892543237897, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.235908872794151, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2833223592289347, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.414288317478876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137672.507544} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.289985418319702, "x": 32.37268817849604, "y": 0.02624886308119212, "z": null, "yaw": 0.017154027874260534, "pitch": null, "roll": null}, "v": 2.2836256197726037, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3663307407014483, "steering_wheel_angle": -0.414288317478876, "front_wheel_angle": -0.019130254230911675, "heading_rate": -0.017067058086740392, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137672.527544} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25615977157719205, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.235908872794151, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2831498997892283, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.414288317478876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137672.527544} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.289985418319702, "x": 32.37268817849604, "y": 0.02624886308119212, "z": null, "yaw": 0.017154027874260534, "pitch": null, "roll": null}, "v": 2.2836256197726037, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3663307407014483, "steering_wheel_angle": -0.414288317478876, "front_wheel_angle": -0.019130254230911675, "heading_rate": -0.017067058086740392, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137672.547544} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25615977157719205, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.235908872794151, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2828443128780163, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.414288317478876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137672.547544} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.289985418319702, "x": 32.37268817849604, "y": 0.02624886308119212, "z": null, "yaw": 0.017154027874260534, "pitch": null, "roll": null}, "v": 2.2836256197726037, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3663307407014483, "steering_wheel_angle": -0.414288317478876, "front_wheel_angle": -0.019130254230911675, "heading_rate": -0.017067058086740392, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137672.567544} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25615977157719205, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.235908872794151, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2825393103263667, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.414288317478876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137672.567544} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.289985418319702, "x": 32.37268817849604, "y": 0.02624886308119212, "z": null, "yaw": 0.017154027874260534, "pitch": null, "roll": null}, "v": 2.2836256197726037, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3663307407014483, "steering_wheel_angle": -0.414288317478876, "front_wheel_angle": -0.019130254230911675, "heading_rate": -0.017067058086740392, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137672.587544} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25615977157719205, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.235908872794151, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2822348909796437, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.414288317478876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137672.587544} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137672.607544, "x": 36.623766518567194, "y": 5.030462452391881, "z": null, "yaw": 0.016331924472859582, "pitch": null, "roll": null}, "v": 2.281931053685632, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3661686460220298, "steering_wheel_angle": -0.414288317478876, "front_wheel_angle": -0.019130254230911675, "heading_rate": -0.017054393463613135, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137672.607544} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25322009736448114, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1650789398229102, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2815956233106918, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.414288317478876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137672.607544} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.399985313415527, "x": 32.623766518567194, "y": 0.03046245239188128, "z": null, "yaw": 0.016331924472859582, "pitch": null, "roll": null}, "v": 2.281931053685632, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3661686460220298, "steering_wheel_angle": -0.414288317478876, "front_wheel_angle": -0.019130254230911675, "heading_rate": -0.017054393463613135, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137672.627544} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2546075928499786, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1650789398229102, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2812605137254853, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.414288317478876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137672.627544} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.399985313415527, "x": 32.623766518567194, "y": 0.03046245239188128, "z": null, "yaw": 0.016331924472859582, "pitch": null, "roll": null}, "v": 2.281931053685632, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3661686460220298, "steering_wheel_angle": -0.414288317478876, "front_wheel_angle": -0.019130254230911675, "heading_rate": -0.017054393463613135, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137672.647544} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2546075928499786, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1650789398229102, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.280764609623644, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.414288317478876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137672.647544} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.399985313415527, "x": 32.623766518567194, "y": 0.03046245239188128, "z": null, "yaw": 0.016331924472859582, "pitch": null, "roll": null}, "v": 2.281931053685632, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3661686460220298, "steering_wheel_angle": -0.414288317478876, "front_wheel_angle": -0.019130254230911675, "heading_rate": -0.017054393463613135, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137672.667544} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2546075928499786, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1650789398229102, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2800225301705144, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.414288317478876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137672.667544} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.399985313415527, "x": 32.623766518567194, "y": 0.03046245239188128, "z": null, "yaw": 0.016331924472859582, "pitch": null, "roll": null}, "v": 2.281931053685632, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3661686460220298, "steering_wheel_angle": -0.414288317478876, "front_wheel_angle": -0.019130254230911675, "heading_rate": -0.017054393463613135, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137672.6875439} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2546075928499786, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1650789398229102, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2797756431847445, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.414288317478876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137672.6875439} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.399985313415527, "x": 32.623766518567194, "y": 0.03046245239188128, "z": null, "yaw": 0.016331924472859582, "pitch": null, "roll": null}, "v": 2.281931053685632, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3661686460220298, "steering_wheel_angle": -0.414288317478876, "front_wheel_angle": -0.019130254230911675, "heading_rate": -0.017054393463613135, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137672.7075438} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2546075928499786, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1650789398229102, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2792825770323284, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.414288317478876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137672.7075438} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137672.7175438, "x": 36.87459417578815, "y": 5.034465581702617, "z": null, "yaw": 0.01550982107145863, "pitch": null, "roll": null}, "v": 2.2790363973903394, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36589188887581636, "steering_wheel_angle": -0.414288317478876, "front_wheel_angle": -0.019130254230911675, "heading_rate": -0.017032759765556345, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137672.7275438} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2540207815446005, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.150420486102977, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2787904530547047, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.414288317478876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137672.7275438} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.509985208511353, "x": 32.87459417578815, "y": 0.03446558170261671, "z": null, "yaw": 0.01550982107145863, "pitch": null, "roll": null}, "v": 2.2790363973903394, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36589188887581636, "steering_wheel_angle": -0.414288317478876, "front_wheel_angle": -0.019130254230911675, "heading_rate": -0.017032759765556345, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137672.7475438} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2542791293698394, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.150420486102977, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.278225952992687, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.414288317478876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137672.7475438} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.509985208511353, "x": 32.87459417578815, "y": 0.03446558170261671, "z": null, "yaw": 0.01550982107145863, "pitch": null, "roll": null}, "v": 2.2790363973903394, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36589188887581636, "steering_wheel_angle": -0.414288317478876, "front_wheel_angle": -0.019130254230911675, "heading_rate": -0.017032759765556345, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137672.7675438} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2542791293698394, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.150420486102977, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.27769480941901, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.414288317478876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137672.7675438} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.509985208511353, "x": 32.87459417578815, "y": 0.03446558170261671, "z": null, "yaw": 0.01550982107145863, "pitch": null, "roll": null}, "v": 2.2790363973903394, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36589188887581636, "steering_wheel_angle": -0.414288317478876, "front_wheel_angle": -0.019130254230911675, "heading_rate": -0.017032759765556345, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137672.7875438} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2542791293698394, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.150420486102977, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.277164680445326, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.414288317478876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137672.7875438} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.509985208511353, "x": 32.87459417578815, "y": 0.03446558170261671, "z": null, "yaw": 0.01550982107145863, "pitch": null, "roll": null}, "v": 2.2790363973903394, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36589188887581636, "steering_wheel_angle": -0.414288317478876, "front_wheel_angle": -0.019130254230911675, "heading_rate": -0.017032759765556345, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137672.8075438} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2542791293698394, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.150420486102977, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.276635564021166, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.414288317478876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137672.8075438} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137672.8275437, "x": 37.125112640280086, "y": 5.03825777527421, "z": null, "yaw": 0.014687717670057679, "pitch": null, "roll": null}, "v": 2.276107458100623, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3656120245132439, "steering_wheel_angle": -0.414288317478876, "front_wheel_angle": -0.019130254230911675, "heading_rate": -0.017010869847805685, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137672.8275437} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2567762083601464, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.179875150326471, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.276107458100623, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.414288317478876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137672.8275437} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.619985103607178, "x": 33.125112640280086, "y": 0.038257775274209926, "z": null, "yaw": 0.014687717670057679, "pitch": null, "roll": null}, "v": 2.276107458100623, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3656120245132439, "steering_wheel_angle": -0.414288317478876, "front_wheel_angle": -0.019130254230911675, "heading_rate": -0.017010869847805685, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137672.8475437} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25556579952296166, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.179875150326471, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.27589234644295, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.414288317478876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137672.8475437} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.619985103607178, "x": 33.125112640280086, "y": 0.038257775274209926, "z": null, "yaw": 0.014687717670057679, "pitch": null, "roll": null}, "v": 2.276107458100623, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3656120245132439, "steering_wheel_angle": -0.414288317478876, "front_wheel_angle": -0.019130254230911675, "heading_rate": -0.017010869847805685, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137672.8675437} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25556579952296166, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.179875150326471, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.275526416686623, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.414288317478876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137672.8675437} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.619985103607178, "x": 33.125112640280086, "y": 0.038257775274209926, "z": null, "yaw": 0.014687717670057679, "pitch": null, "roll": null}, "v": 2.276107458100623, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3656120245132439, "steering_wheel_angle": -0.414288317478876, "front_wheel_angle": -0.019130254230911675, "heading_rate": -0.017010869847805685, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137672.8875437} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25556579952296166, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.179875150326471, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.275161185612757, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.414288317478876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137672.8875437} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.619985103607178, "x": 33.125112640280086, "y": 0.038257775274209926, "z": null, "yaw": 0.014687717670057679, "pitch": null, "roll": null}, "v": 2.276107458100623, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3656120245132439, "steering_wheel_angle": -0.414288317478876, "front_wheel_angle": -0.019130254230911675, "heading_rate": -0.017010869847805685, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137672.9075437} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25556579952296166, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.179875150326471, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.274796651834, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.414288317478876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137672.9075437} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.619985103607178, "x": 33.125112640280086, "y": 0.038257775274209926, "z": null, "yaw": 0.014687717670057679, "pitch": null, "roll": null}, "v": 2.276107458100623, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3656120245132439, "steering_wheel_angle": -0.414288317478876, "front_wheel_angle": -0.019130254230911675, "heading_rate": -0.017010869847805685, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137672.9275436} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25556579952296166, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.179875150326471, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.274432813965956, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.414288317478876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137672.9275436} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137672.9375436, "x": 37.37537262490823, "y": 5.041840264177661, "z": null, "yaw": 0.013865614268656727, "pitch": null, "roll": null}, "v": 2.2742511555666334, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36543474096429335, "steering_wheel_angle": -0.414288317478876, "front_wheel_angle": -0.019130254230911675, "heading_rate": -0.016996996460285484, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137672.9475436} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.257658498138094, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2115603207262893, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2740696706271755, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.414288317478876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137672.9475436} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.729984998703003, "x": 33.37537262490823, "y": 0.041840264177660735, "z": null, "yaw": 0.013865614268656727, "pitch": null, "roll": null}, "v": 2.2742511555666334, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36543474096429335, "steering_wheel_angle": -0.414288317478876, "front_wheel_angle": -0.019130254230911675, "heading_rate": -0.016996996460285484, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137672.9675436} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2566484671654611, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2115603207262893, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2739686828854606, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.414288317478876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137672.9675436} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.729984998703003, "x": 33.37537262490823, "y": 0.041840264177660735, "z": null, "yaw": 0.013865614268656727, "pitch": null, "roll": null}, "v": 2.2742511555666334, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36543474096429335, "steering_wheel_angle": -0.414288317478876, "front_wheel_angle": -0.019130254230911675, "heading_rate": -0.016996996460285484, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137672.9875436} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2566484671654611, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2115603207262893, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.273741694298217, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.414288317478876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137672.9875436} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.729984998703003, "x": 33.37537262490823, "y": 0.041840264177660735, "z": null, "yaw": 0.013865614268656727, "pitch": null, "roll": null}, "v": 2.2742511555666334, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36543474096429335, "steering_wheel_angle": -0.414288317478876, "front_wheel_angle": -0.019130254230911675, "heading_rate": -0.016996996460285484, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137673.0075436} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2566484671654611, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2115603207262893, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2735151389431665, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.414288317478876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137673.0075436} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.729984998703003, "x": 33.37537262490823, "y": 0.041840264177660735, "z": null, "yaw": 0.013865614268656727, "pitch": null, "roll": null}, "v": 2.2742511555666334, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36543474096429335, "steering_wheel_angle": -0.414288317478876, "front_wheel_angle": -0.019130254230911675, "heading_rate": -0.016996996460285484, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137673.0275435} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2566484671654611, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2115603207262893, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2732890159729173, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.414288317478876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137673.0275435} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137673.0475435, "x": 37.62545901566971, "y": 5.045214625814235, "z": null, "yaw": 0.013043510867255775, "pitch": null, "roll": null}, "v": 2.273063324541813, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36532133500086145, "steering_wheel_angle": -0.414288317478876, "front_wheel_angle": -0.019130254230911675, "heading_rate": -0.016988119006414625, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137673.0475435} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25357583075574497, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1642460575324136, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.273063324541813, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.414288317478876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137673.0475435} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.839984893798828, "x": 33.62545901566971, "y": 0.045214625814234743, "z": null, "yaw": 0.013043510867255775, "pitch": null, "roll": null}, "v": 2.273063324541813, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36532133500086145, "steering_wheel_angle": -0.414288317478876, "front_wheel_angle": -0.019130254230911675, "heading_rate": -0.016988119006414625, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137673.0675435} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2550303512230877, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1642460575324136, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.272454167570299, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.414288317478876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137673.0675435} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.839984893798828, "x": 33.62545901566971, "y": 0.045214625814234743, "z": null, "yaw": 0.013043510867255775, "pitch": null, "roll": null}, "v": 2.273063324541813, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36532133500086145, "steering_wheel_angle": -0.414288317478876, "front_wheel_angle": -0.019130254230911675, "heading_rate": -0.016988119006414625, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137673.0875435} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2550303512230877, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1642460575324136, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2720279012431095, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.414288317478876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137673.0875435} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.839984893798828, "x": 33.62545901566971, "y": 0.045214625814234743, "z": null, "yaw": 0.013043510867255775, "pitch": null, "roll": null}, "v": 2.273063324541813, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36532133500086145, "steering_wheel_angle": -0.414288317478876, "front_wheel_angle": -0.019130254230911675, "heading_rate": -0.016988119006414625, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137673.1075435} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2550303512230877, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1642460575324136, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.271602448207722, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.414288317478876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137673.1075435} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.839984893798828, "x": 33.62545901566971, "y": 0.045214625814234743, "z": null, "yaw": 0.013043510867255775, "pitch": null, "roll": null}, "v": 2.273063324541813, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36532133500086145, "steering_wheel_angle": -0.414288317478876, "front_wheel_angle": -0.019130254230911675, "heading_rate": -0.016988119006414625, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137673.1275434} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2550303512230877, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1642460575324136, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.271177806840053, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.414288317478876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137673.1275434} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.839984893798828, "x": 33.62545901566971, "y": 0.045214625814234743, "z": null, "yaw": 0.013043510867255775, "pitch": null, "roll": null}, "v": 2.273063324541813, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36532133500086145, "steering_wheel_angle": -0.414288317478876, "front_wheel_angle": -0.019130254230911675, "heading_rate": -0.016988119006414625, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137673.1475434} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2550303512230877, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1642460575324136, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.270753975519532, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.414288317478876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137673.1475434} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137673.1575434, "x": 37.87534145145042, "y": 5.048380781029875, "z": null, "yaw": 0.012221407465854824, "pitch": null, "roll": null}, "v": 2.270542363121481, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3650807443833669, "steering_wheel_angle": -0.414288317478876, "front_wheel_angle": -0.019130254230911675, "heading_rate": -0.016969278179519577, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137673.1675434} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25764074611299964, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.201060451347094, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2703309526290907, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.414288317478876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137673.1675434} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.949984788894653, "x": 33.87534145145042, "y": 0.04838078102987531, "z": null, "yaw": 0.012221407465854824, "pitch": null, "roll": null}, "v": 2.270542363121481, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3650807443833669, "steering_wheel_angle": -0.414288317478876, "front_wheel_angle": -0.019130254230911675, "heading_rate": -0.016969278179519577, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137673.1875434} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2563793695835007, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.201060451347094, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2702348802650323, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.414288317478876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137673.1875434} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.949984788894653, "x": 33.87534145145042, "y": 0.04838078102987531, "z": null, "yaw": 0.012221407465854824, "pitch": null, "roll": null}, "v": 2.270542363121481, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3650807443833669, "steering_wheel_angle": -0.414288317478876, "front_wheel_angle": -0.019130254230911675, "heading_rate": -0.016969278179519577, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137673.2075434} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2563793695835007, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.201060451347094, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2699813942752614, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.414288317478876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137673.2075434} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.949984788894653, "x": 33.87534145145042, "y": 0.04838078102987531, "z": null, "yaw": 0.012221407465854824, "pitch": null, "roll": null}, "v": 2.270542363121481, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3650807443833669, "steering_wheel_angle": -0.414288317478876, "front_wheel_angle": -0.019130254230911675, "heading_rate": -0.016969278179519577, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137673.2275434} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2563793695835007, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.201060451347094, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.269728391710595, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.414288317478876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137673.2275434} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.949984788894653, "x": 33.87534145145042, "y": 0.04838078102987531, "z": null, "yaw": 0.012221407465854824, "pitch": null, "roll": null}, "v": 2.270542363121481, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3650807443833669, "steering_wheel_angle": -0.414288317478876, "front_wheel_angle": -0.019130254230911675, "heading_rate": -0.016969278179519577, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137673.2475433} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2563793695835007, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.201060451347094, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2694758716234973, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.414288317478876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137673.2475433} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137673.2675433, "x": 38.12501883511332, "y": 5.0513390376883285, "z": null, "yaw": 0.011399304064453872, "pitch": null, "roll": null}, "v": 2.269223833068386, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3649549596990751, "steering_wheel_angle": -0.414288317478876, "front_wheel_angle": -0.019130254230911675, "heading_rate": -0.01695942392459686, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137673.2675433} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2585552972314356, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2407269077628142, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.269223833068386, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.414288317478876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137673.2675433} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.05998468399048, "x": 34.12501883511332, "y": 0.05133903768832848, "z": null, "yaw": 0.011399304064453872, "pitch": null, "roll": null}, "v": 2.269223833068386, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3649549596990751, "steering_wheel_angle": -0.414288317478876, "front_wheel_angle": -0.019130254230911675, "heading_rate": -0.01695942392459686, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137673.2875433} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2575095570912229, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2407269077628142, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2692441363406184, "gear": 1, "accelerator_pedal_position": 0.2585552972314356, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.414288317478876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137673.2875433} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.05998468399048, "x": 34.12501883511332, "y": 0.05133903768832848, "z": null, "yaw": 0.011399304064453872, "pitch": null, "roll": null}, "v": 2.269223833068386, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3649549596990751, "steering_wheel_angle": -0.414288317478876, "front_wheel_angle": -0.019130254230911675, "heading_rate": -0.01695942392459686, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137673.3075433} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2575095570912229, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2407269077628142, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2691337457234138, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.414288317478876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137673.3075433} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.05998468399048, "x": 34.12501883511332, "y": 0.05133903768832848, "z": null, "yaw": 0.011399304064453872, "pitch": null, "roll": null}, "v": 2.269223833068386, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3649549596990751, "steering_wheel_angle": -0.414288317478876, "front_wheel_angle": -0.019130254230911675, "heading_rate": -0.01695942392459686, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137673.3275433} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2575095570912229, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2407269077628142, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2690235655940425, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.414288317478876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137673.3275433} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.05998468399048, "x": 34.12501883511332, "y": 0.05133903768832848, "z": null, "yaw": 0.011399304064453872, "pitch": null, "roll": null}, "v": 2.269223833068386, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3649549596990751, "steering_wheel_angle": -0.414288317478876, "front_wheel_angle": -0.019130254230911675, "heading_rate": -0.01695942392459686, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137673.3475432} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2575095570912229, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2407269077628142, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2689135955463025, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.414288317478876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137673.3475432} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.05998468399048, "x": 34.12501883511332, "y": 0.05133903768832848, "z": null, "yaw": 0.011399304064453872, "pitch": null, "roll": null}, "v": 2.269223833068386, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3649549596990751, "steering_wheel_angle": -0.414288317478876, "front_wheel_angle": -0.019130254230911675, "heading_rate": -0.01695942392459686, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137673.3675432} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2575095570912229, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2407269077628142, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2688038351747934, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.414288317478876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137673.3675432} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137673.3775432, "x": 38.37460037211374, "y": 5.0540909444055, "z": null, "yaw": 0.01057720066305292, "pitch": null, "roll": null}, "v": 2.268749033491157, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3649096734442285, "steering_wheel_angle": -0.414288317478876, "front_wheel_angle": -0.019130254230911675, "heading_rate": -0.01695587543052937, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137673.3875432} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2593672742247595, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2836913025977872, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.268694284074916, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.414288317478876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137673.3875432} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.169984579086304, "x": 34.37460037211374, "y": 0.0540909444055, "z": null, "yaw": 0.01057720066305292, "pitch": null, "roll": null}, "v": 2.268749033491157, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3649096734442285, "steering_wheel_angle": -0.414288317478876, "front_wheel_angle": -0.019130254230911675, "heading_rate": -0.01695587543052937, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137673.4075432} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2584791961933581, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2836913025977872, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.268817045748421, "gear": 1, "accelerator_pedal_position": 0.2593672742247595, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137673.4075432} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.169984579086304, "x": 34.37460037211374, "y": 0.0540909444055, "z": null, "yaw": 0.01057720066305292, "pitch": null, "roll": null}, "v": 2.268749033491157, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3649096734442285, "steering_wheel_angle": -0.414288317478876, "front_wheel_angle": -0.019130254230911675, "heading_rate": -0.01695587543052937, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137673.4275432} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2584791961933581, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2836913025977872, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2688286165488876, "gear": 1, "accelerator_pedal_position": 0.2584791961933581, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137673.4275432} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.169984579086304, "x": 34.37460037211374, "y": 0.0540909444055, "z": null, "yaw": 0.01057720066305292, "pitch": null, "roll": null}, "v": 2.268749033491157, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3649096734442285, "steering_wheel_angle": -0.414288317478876, "front_wheel_angle": -0.019130254230911675, "heading_rate": -0.01695587543052937, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137673.4475431} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2584791961933581, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2836913025977872, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2688401652882275, "gear": 1, "accelerator_pedal_position": 0.2584791961933581, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137673.4475431} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.169984579086304, "x": 34.37460037211374, "y": 0.0540909444055, "z": null, "yaw": 0.01057720066305292, "pitch": null, "roll": null}, "v": 2.268749033491157, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3649096734442285, "steering_wheel_angle": -0.414288317478876, "front_wheel_angle": -0.019130254230911675, "heading_rate": -0.01695587543052937, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137673.4675431} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2584791961933581, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2836913025977872, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2688574471244976, "gear": 1, "accelerator_pedal_position": 0.2584791961933581, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137673.4675431} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137673.487543, "x": 38.62415640568322, "y": 5.056631313000822, "z": null, "yaw": 0.00968823892661494, "pitch": null, "roll": null}, "v": 2.2688631967514827, "accelerator_pedal_position": 0.2584791961933581, "brake_pedal_position": 0.0, "acceleration": 0.0005744143151801828, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.01864219993499275, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137673.487543} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25660950292713747, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.237123286467579, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2688631967514827, "gear": 1, "accelerator_pedal_position": 0.2584791961933581, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137673.487543} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.27998447418213, "x": 34.62415640568322, "y": 0.056631313000822026, "z": null, "yaw": 0.00968823892661494, "pitch": null, "roll": null}, "v": 2.2688631967514827, "accelerator_pedal_position": 0.2584791961933581, "brake_pedal_position": 0.0, "acceleration": 0.0005744143151801828, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.01864219993499275, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137673.507543} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.257500663095203, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.237123286467579, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2686410793535603, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137673.507543} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.27998447418213, "x": 34.62415640568322, "y": 0.056631313000822026, "z": null, "yaw": 0.00968823892661494, "pitch": null, "roll": null}, "v": 2.2688631967514827, "accelerator_pedal_position": 0.2584791961933581, "brake_pedal_position": 0.0, "acceleration": 0.0005744143151801828, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.01864219993499275, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137673.527543} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.257500663095203, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.237123286467579, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.268530727339437, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137673.527543} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.27998447418213, "x": 34.62415640568322, "y": 0.056631313000822026, "z": null, "yaw": 0.00968823892661494, "pitch": null, "roll": null}, "v": 2.2688631967514827, "accelerator_pedal_position": 0.2584791961933581, "brake_pedal_position": 0.0, "acceleration": 0.0005744143151801828, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.01864219993499275, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137673.547543} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.257500663095203, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.237123286467579, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2684205857129474, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137673.547543} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.27998447418213, "x": 34.62415640568322, "y": 0.056631313000822026, "z": null, "yaw": 0.00968823892661494, "pitch": null, "roll": null}, "v": 2.2688631967514827, "accelerator_pedal_position": 0.2584791961933581, "brake_pedal_position": 0.0, "acceleration": 0.0005744143151801828, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.01864219993499275, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137673.567543} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.257500663095203, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.237123286467579, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.268310654068135, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137673.567543} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.27998447418213, "x": 34.62415640568322, "y": 0.056631313000822026, "z": null, "yaw": 0.00968823892661494, "pitch": null, "roll": null}, "v": 2.2688631967514827, "accelerator_pedal_position": 0.2584791961933581, "brake_pedal_position": 0.0, "acceleration": 0.0005744143151801828, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.01864219993499275, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137673.587543} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.257500663095203, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.237123286467579, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2682009319998437, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137673.587543} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137673.597543, "x": 38.87367967982288, "y": 5.058946315266415, "z": null, "yaw": 0.008784419782390952, "pitch": null, "roll": null}, "v": 2.2681461494305015, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3648521770232892, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.01863630828866532, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137673.607543} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2579060183033471, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2373507406311408, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2680367409690763, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137673.607543} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.389984369277954, "x": 34.87367967982288, "y": 0.05894631526641536, "z": null, "yaw": 0.008784419782390952, "pitch": null, "roll": null}, "v": 2.2681461494305015, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3648521770232892, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.01863630828866532, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137673.627543} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25770778163891583, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2373507406311408, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.267978186316654, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137673.627543} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.389984369277954, "x": 34.87367967982288, "y": 0.05894631526641536, "z": null, "yaw": 0.008784419782390952, "pitch": null, "roll": null}, "v": 2.2681461494305015, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3648521770232892, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.01863630828866532, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137673.647543} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25770778163891583, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2373507406311408, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.267936561070567, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137673.647543} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.389984369277954, "x": 34.87367967982288, "y": 0.05894631526641536, "z": null, "yaw": 0.008784419782390952, "pitch": null, "roll": null}, "v": 2.2681461494305015, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3648521770232892, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.01863630828866532, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137673.667543} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25770778163891583, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2373507406311408, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.267853429620635, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137673.667543} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.389984369277954, "x": 34.87367967982288, "y": 0.05894631526641536, "z": null, "yaw": 0.008784419782390952, "pitch": null, "roll": null}, "v": 2.2681461494305015, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3648521770232892, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.01863630828866532, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137673.687543} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25770778163891583, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2373507406311408, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2677704566392305, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137673.687543} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137673.707543, "x": 39.12314348849318, "y": 5.0610352761115305, "z": null, "yaw": 0.007880600638166965, "pitch": null, "roll": null}, "v": 2.2676876418215213, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3648084544997766, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.01863254094362197, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137673.707543} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.258923439274396, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2526226735815476, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2676876418215213, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137673.707543} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.49998426437378, "x": 35.12314348849318, "y": 0.06103527611153048, "z": null, "yaw": 0.007880600638166965, "pitch": null, "roll": null}, "v": 2.2676876418215213, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3648084544997766, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.01863254094362197, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137673.7275429} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.258341223155343, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2526226735815476, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2677568696193102, "gear": 1, "accelerator_pedal_position": 0.258923439274396, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137673.7275429} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.49998426437378, "x": 35.12314348849318, "y": 0.06103527611153048, "z": null, "yaw": 0.007880600638166965, "pitch": null, "roll": null}, "v": 2.2676876418215213, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3648084544997766, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.01863254094362197, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137673.7475429} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.258341223155343, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2526226735815476, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2677532231395494, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137673.7475429} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.49998426437378, "x": 35.12314348849318, "y": 0.06103527611153048, "z": null, "yaw": 0.007880600638166965, "pitch": null, "roll": null}, "v": 2.2676876418215213, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3648084544997766, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.01863254094362197, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137673.7675428} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.258341223155343, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2526226735815476, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2677495836106805, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137673.7675428} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.49998426437378, "x": 35.12314348849318, "y": 0.06103527611153048, "z": null, "yaw": 0.007880600638166965, "pitch": null, "roll": null}, "v": 2.2676876418215213, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3648084544997766, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.01863254094362197, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137673.7875428} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.258341223155343, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2526226735815476, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.267745951019449, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137673.7875428} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.49998426437378, "x": 35.12314348849318, "y": 0.06103527611153048, "z": null, "yaw": 0.007880600638166965, "pitch": null, "roll": null}, "v": 2.2676876418215213, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3648084544997766, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.01863254094362197, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137673.8075428} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.258341223155343, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2526226735815476, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2677423253526245, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137673.8075428} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137673.8175428, "x": 39.372588082903846, "y": 5.0628986051979, "z": null, "yaw": 0.006976781493942978, "pitch": null, "roll": null}, "v": 2.2677405151117376, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3648134961943794, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.01863297537900302, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137673.8275428} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2589749019351658, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.242446142214539, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2677387065970027, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137673.8275428} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.609984159469604, "x": 35.372588082903846, "y": 0.06289860519790036, "z": null, "yaw": 0.006976781493942978, "pitch": null, "roll": null}, "v": 2.2677405151117376, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3648134961943794, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.01863297537900302, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137673.8475428} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25867353411381644, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.242446142214539, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2678142668215537, "gear": 1, "accelerator_pedal_position": 0.2589749019351658, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137673.8475428} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.609984159469604, "x": 35.372588082903846, "y": 0.06289860519790036, "z": null, "yaw": 0.006976781493942978, "pitch": null, "roll": null}, "v": 2.2677405151117376, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3648134961943794, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.01863297537900302, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137673.8675427} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25867353411381644, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.242446142214539, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.267852029995795, "gear": 1, "accelerator_pedal_position": 0.25867353411381644, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137673.8675427} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.609984159469604, "x": 35.372588082903846, "y": 0.06289860519790036, "z": null, "yaw": 0.006976781493942978, "pitch": null, "roll": null}, "v": 2.2677405151117376, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3648134961943794, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.01863297537900302, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137673.8875427} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25867353411381644, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.242446142214539, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2678897211848263, "gear": 1, "accelerator_pedal_position": 0.25867353411381644, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137673.8875427} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.609984159469604, "x": 35.372588082903846, "y": 0.06289860519790036, "z": null, "yaw": 0.006976781493942978, "pitch": null, "roll": null}, "v": 2.2677405151117376, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3648134961943794, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.01863297537900302, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137673.9075427} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25867353411381644, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.242446142214539, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2679273405252993, "gear": 1, "accelerator_pedal_position": 0.25867353411381644, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137673.9075427} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137673.9275427, "x": 39.62204567502217, "y": 5.064536554018143, "z": null, "yaw": 0.006072962349718991, "pitch": null, "roll": null}, "v": 2.267964888153609, "accelerator_pedal_position": 0.25867353411381644, "brake_pedal_position": 0.0, "acceleration": 0.0018746964646960684, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.018634818948554756, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137673.9275427} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.256674708885044, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1540820299968584, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.267964888153609, "gear": 1, "accelerator_pedal_position": 0.25867353411381644, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137673.9275427} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.71998405456543, "x": 35.62204567502217, "y": 0.06453655401814284, "z": null, "yaw": 0.006072962349718991, "pitch": null, "roll": null}, "v": 2.267964888153609, "accelerator_pedal_position": 0.25867353411381644, "brake_pedal_position": 0.0, "acceleration": 0.0018746964646960684, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.018634818948554756, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137673.9475427} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25762816103616204, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1540820299968584, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2677526301803113, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137673.9475427} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.71998405456543, "x": 35.62204567502217, "y": 0.06453655401814284, "z": null, "yaw": 0.006072962349718991, "pitch": null, "roll": null}, "v": 2.267964888153609, "accelerator_pedal_position": 0.25867353411381644, "brake_pedal_position": 0.0, "acceleration": 0.0018746964646960684, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.018634818948554756, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137673.9675426} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25762816103616204, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1540820299968584, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2676136034840324, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137673.9675426} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.71998405456543, "x": 35.62204567502217, "y": 0.06453655401814284, "z": null, "yaw": 0.006072962349718991, "pitch": null, "roll": null}, "v": 2.267964888153609, "accelerator_pedal_position": 0.25867353411381644, "brake_pedal_position": 0.0, "acceleration": 0.0018746964646960684, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.018634818948554756, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137673.9875426} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25762816103616204, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1540820299968584, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.26756734960158, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137673.9875426} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.71998405456543, "x": 35.62204567502217, "y": 0.06453655401814284, "z": null, "yaw": 0.006072962349718991, "pitch": null, "roll": null}, "v": 2.267964888153609, "accelerator_pedal_position": 0.25867353411381644, "brake_pedal_position": 0.0, "acceleration": 0.0018746964646960684, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.018634818948554756, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137674.0075426} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25762816103616204, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1540820299968584, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.267474974105935, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137674.0075426} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.71998405456543, "x": 35.62204567502217, "y": 0.06453655401814284, "z": null, "yaw": 0.006072962349718991, "pitch": null, "roll": null}, "v": 2.267964888153609, "accelerator_pedal_position": 0.25867353411381644, "brake_pedal_position": 0.0, "acceleration": 0.0018746964646960684, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.018634818948554756, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137674.0275426} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25762816103616204, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1540820299968584, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2673827746863053, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137674.0275426} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137674.0375426, "x": 39.87148097876314, "y": 5.065948910460149, "z": null, "yaw": 0.005169143205495004, "pitch": null, "roll": null}, "v": 2.2673367408990277, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3647749960112576, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.018629657752972192, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137674.0475426} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2597224761261208, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1806599903670407, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2672907510036753, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137674.0475426} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.829983949661255, "x": 35.87148097876314, "y": 0.06594891046014872, "z": null, "yaw": 0.005169143205495004, "pitch": null, "roll": null}, "v": 2.2673367408990277, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3647749960112576, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.018629657752972192, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137674.0675426} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2587206192410673, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1806599903670407, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2674605673028174, "gear": 1, "accelerator_pedal_position": 0.2597224761261208, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137674.0675426} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.829983949661255, "x": 35.87148097876314, "y": 0.06594891046014872, "z": null, "yaw": 0.005169143205495004, "pitch": null, "roll": null}, "v": 2.2673367408990277, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3647749960112576, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.018629657752972192, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137674.0875425} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2587206192410673, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1806599903670407, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.267504887516179, "gear": 1, "accelerator_pedal_position": 0.2587206192410673, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137674.0875425} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.829983949661255, "x": 35.87148097876314, "y": 0.06594891046014872, "z": null, "yaw": 0.005169143205495004, "pitch": null, "roll": null}, "v": 2.2673367408990277, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3647749960112576, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.018629657752972192, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137674.1075425} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2587206192410673, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1806599903670407, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2675712094896032, "gear": 1, "accelerator_pedal_position": 0.2587206192410673, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137674.1075425} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.829983949661255, "x": 35.87148097876314, "y": 0.06594891046014872, "z": null, "yaw": 0.005169143205495004, "pitch": null, "roll": null}, "v": 2.2673367408990277, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3647749960112576, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.018629657752972192, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137674.1275425} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2587206192410673, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1806599903670407, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2675932746684144, "gear": 1, "accelerator_pedal_position": 0.2587206192410673, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137674.1275425} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137674.1475425, "x": 40.12090121996201, "y": 5.06713573701945, "z": null, "yaw": 0.004265324061271017, "pitch": null, "roll": null}, "v": 2.2676373419274682, "accelerator_pedal_position": 0.2587206192410673, "brake_pedal_position": 0.0, "acceleration": 0.002200212015258496, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.018632127652647445, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137674.1475425} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26049437460661423, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.208667174551491, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2676373419274682, "gear": 1, "accelerator_pedal_position": 0.2587206192410673, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137674.1475425} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.93998384475708, "x": 36.12090121996201, "y": 0.0671357370194503, "z": null, "yaw": 0.004265324061271017, "pitch": null, "roll": null}, "v": 2.2676373419274682, "accelerator_pedal_position": 0.2587206192410673, "brake_pedal_position": 0.0, "acceleration": 0.002200212015258496, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.018632127652647445, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137674.1675425} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2596519125625666, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.208667174551491, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2679029388992964, "gear": 1, "accelerator_pedal_position": 0.26049437460661423, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137674.1675425} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.93998384475708, "x": 36.12090121996201, "y": 0.0671357370194503, "z": null, "yaw": 0.004265324061271017, "pitch": null, "roll": null}, "v": 2.2676373419274682, "accelerator_pedal_position": 0.2587206192410673, "brake_pedal_position": 0.0, "acceleration": 0.002200212015258496, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.018632127652647445, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137674.1875424} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2596519125625666, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.208667174551491, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.268062772038783, "gear": 1, "accelerator_pedal_position": 0.2596519125625666, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137674.1875424} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.93998384475708, "x": 36.12090121996201, "y": 0.0671357370194503, "z": null, "yaw": 0.004265324061271017, "pitch": null, "roll": null}, "v": 2.2676373419274682, "accelerator_pedal_position": 0.2587206192410673, "brake_pedal_position": 0.0, "acceleration": 0.002200212015258496, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.018632127652647445, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137674.2075424} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2596519125625666, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.208667174551491, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.268222300488395, "gear": 1, "accelerator_pedal_position": 0.2596519125625666, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137674.2075424} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.93998384475708, "x": 36.12090121996201, "y": 0.0671357370194503, "z": null, "yaw": 0.004265324061271017, "pitch": null, "roll": null}, "v": 2.2676373419274682, "accelerator_pedal_position": 0.2587206192410673, "brake_pedal_position": 0.0, "acceleration": 0.002200212015258496, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.018632127652647445, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137674.2275424} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2596519125625666, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.208667174551491, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2683815248187873, "gear": 1, "accelerator_pedal_position": 0.2596519125625666, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137674.2275424} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.93998384475708, "x": 36.12090121996201, "y": 0.0671357370194503, "z": null, "yaw": 0.004265324061271017, "pitch": null, "roll": null}, "v": 2.2676373419274682, "accelerator_pedal_position": 0.2587206192410673, "brake_pedal_position": 0.0, "acceleration": 0.002200212015258496, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.018632127652647445, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137674.2475424} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2596519125625666, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.208667174551491, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.268540445599586, "gear": 1, "accelerator_pedal_position": 0.2596519125625666, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137674.2475424} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137674.2575424, "x": 40.370393417879406, "y": 5.068097400938922, "z": null, "yaw": 0.003361504917047033, "pitch": null, "roll": null}, "v": 2.2686197923366143, "accelerator_pedal_position": 0.2596519125625666, "brake_pedal_position": 0.0, "acceleration": 0.007927106277396123, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.018640199993447782, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137674.2675424} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.260115171341836, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1930392710596966, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.268699063399388, "gear": 1, "accelerator_pedal_position": 0.2596519125625666, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137674.2675424} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.049983739852905, "x": 36.370393417879406, "y": 0.06809740093892191, "z": null, "yaw": 0.003361504917047033, "pitch": null, "roll": null}, "v": 2.2686197923366143, "accelerator_pedal_position": 0.2596519125625666, "brake_pedal_position": 0.0, "acceleration": 0.007927106277396123, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.018640199993447782, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137674.2875423} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25990171002581597, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1930392710596966, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.268915258518361, "gear": 1, "accelerator_pedal_position": 0.260115171341836, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137674.2875423} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.049983739852905, "x": 36.370393417879406, "y": 0.06809740093892191, "z": null, "yaw": 0.003361504917047033, "pitch": null, "roll": null}, "v": 2.2686197923366143, "accelerator_pedal_position": 0.2596519125625666, "brake_pedal_position": 0.0, "acceleration": 0.007927106277396123, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.018640199993447782, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137674.3075423} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25990171002581597, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1930392710596966, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2691043714927024, "gear": 1, "accelerator_pedal_position": 0.25990171002581597, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137674.3075423} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.049983739852905, "x": 36.370393417879406, "y": 0.06809740093892191, "z": null, "yaw": 0.003361504917047033, "pitch": null, "roll": null}, "v": 2.2686197923366143, "accelerator_pedal_position": 0.2596519125625666, "brake_pedal_position": 0.0, "acceleration": 0.007927106277396123, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.018640199993447782, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137674.3275423} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25990171002581597, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1930392710596966, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2692931238828633, "gear": 1, "accelerator_pedal_position": 0.25990171002581597, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137674.3275423} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.049983739852905, "x": 36.370393417879406, "y": 0.06809740093892191, "z": null, "yaw": 0.003361504917047033, "pitch": null, "roll": null}, "v": 2.2686197923366143, "accelerator_pedal_position": 0.2596519125625666, "brake_pedal_position": 0.0, "acceleration": 0.007927106277396123, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.018640199993447782, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137674.3475423} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25990171002581597, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1930392710596966, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2694815163621302, "gear": 1, "accelerator_pedal_position": 0.25990171002581597, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137674.3475423} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137674.3675423, "x": 40.61999324224795, "y": 5.068833883090701, "z": null, "yaw": 0.0024576857728230506, "pitch": null, "roll": null}, "v": 2.2696695496025874, "accelerator_pedal_position": 0.25990171002581597, "brake_pedal_position": 0.0, "acceleration": 0.009388211537288194, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.018648825363573006, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137674.3675423} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2601076292567455, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0579673506494705, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2696695496025874, "gear": 1, "accelerator_pedal_position": 0.25990171002581597, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137674.3675423} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.15998363494873, "x": 36.61999324224795, "y": 0.06883388309070071, "z": null, "yaw": 0.0024576857728230506, "pitch": null, "roll": null}, "v": 2.2696695496025874, "accelerator_pedal_position": 0.25990171002581597, "brake_pedal_position": 0.0, "acceleration": 0.009388211537288194, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.018648825363573006, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137674.3875422} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2600172013024, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0579673506494705, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.269882951901643, "gear": 1, "accelerator_pedal_position": 0.2601076292567455, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137674.3875422} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.15998363494873, "x": 36.61999324224795, "y": 0.06883388309070071, "z": null, "yaw": 0.0024576857728230506, "pitch": null, "roll": null}, "v": 2.2696695496025874, "accelerator_pedal_position": 0.25990171002581597, "brake_pedal_position": 0.0, "acceleration": 0.009388211537288194, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.018648825363573006, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137674.4075422} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2600172013024, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0579673506494705, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.270084649135325, "gear": 1, "accelerator_pedal_position": 0.2600172013024, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137674.4075422} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.15998363494873, "x": 36.61999324224795, "y": 0.06883388309070071, "z": null, "yaw": 0.0024576857728230506, "pitch": null, "roll": null}, "v": 2.2696695496025874, "accelerator_pedal_position": 0.25990171002581597, "brake_pedal_position": 0.0, "acceleration": 0.009388211537288194, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.018648825363573006, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137674.4275422} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2600172013024, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0579673506494705, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.270285961711496, "gear": 1, "accelerator_pedal_position": 0.2600172013024, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137674.4275422} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.15998363494873, "x": 36.61999324224795, "y": 0.06883388309070071, "z": null, "yaw": 0.0024576857728230506, "pitch": null, "roll": null}, "v": 2.2696695496025874, "accelerator_pedal_position": 0.25990171002581597, "brake_pedal_position": 0.0, "acceleration": 0.009388211537288194, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.018648825363573006, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137674.4475422} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2600172013024, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0579673506494705, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2704868903475357, "gear": 1, "accelerator_pedal_position": 0.2600172013024, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137674.4475422} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.15998363494873, "x": 36.61999324224795, "y": 0.06883388309070071, "z": null, "yaw": 0.0024576857728230506, "pitch": null, "roll": null}, "v": 2.2696695496025874, "accelerator_pedal_position": 0.25990171002581597, "brake_pedal_position": 0.0, "acceleration": 0.009388211537288194, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.018648825363573006, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137674.4675422} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2600172013024, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0579673506494705, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.270687435759547, "gear": 1, "accelerator_pedal_position": 0.2600172013024, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137674.4675422} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137674.4775422, "x": 40.869712876990945, "y": 5.0693450154960376, "z": null, "yaw": 0.0015538666285990672, "pitch": null, "roll": null}, "v": 2.2707875649799756, "accelerator_pedal_position": 0.2600172013024, "brake_pedal_position": 0.0, "acceleration": 0.010003368238324428, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.01865801157904228, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137674.4875422} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2619492513301376, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0739428048029809, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.270887598662359, "gear": 1, "accelerator_pedal_position": 0.2600172013024, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137674.4875422} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.269983530044556, "x": 36.869712876990945, "y": 0.06934501549603755, "z": null, "yaw": 0.0015538666285990672, "pitch": null, "roll": null}, "v": 2.2707875649799756, "accelerator_pedal_position": 0.2600172013024, "brake_pedal_position": 0.0, "acceleration": 0.010003368238324428, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.01865801157904228, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137674.5075421} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26103735381588145, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0739428048029809, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2713287707992067, "gear": 1, "accelerator_pedal_position": 0.2619492513301376, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137674.5075421} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.269983530044556, "x": 36.869712876990945, "y": 0.06934501549603755, "z": null, "yaw": 0.0015538666285990672, "pitch": null, "roll": null}, "v": 2.2707875649799756, "accelerator_pedal_position": 0.2600172013024, "brake_pedal_position": 0.0, "acceleration": 0.010003368238324428, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.01865801157904228, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137674.527542} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26103735381588145, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0739428048029809, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.271655168566266, "gear": 1, "accelerator_pedal_position": 0.26103735381588145, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137674.527542} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.269983530044556, "x": 36.869712876990945, "y": 0.06934501549603755, "z": null, "yaw": 0.0015538666285990672, "pitch": null, "roll": null}, "v": 2.2707875649799756, "accelerator_pedal_position": 0.2600172013024, "brake_pedal_position": 0.0, "acceleration": 0.010003368238324428, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.01865801157904228, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137674.547542} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26103735381588145, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0739428048029809, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.271980943658203, "gear": 1, "accelerator_pedal_position": 0.26103735381588145, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137674.547542} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.269983530044556, "x": 36.869712876990945, "y": 0.06934501549603755, "z": null, "yaw": 0.0015538666285990672, "pitch": null, "roll": null}, "v": 2.2707875649799756, "accelerator_pedal_position": 0.2600172013024, "brake_pedal_position": 0.0, "acceleration": 0.010003368238324428, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.01865801157904228, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137674.567542} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26103735381588145, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0739428048029809, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2723060972204747, "gear": 1, "accelerator_pedal_position": 0.26103735381588145, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137674.567542} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137674.587542, "x": 41.119592471882044, "y": 5.069630622469616, "z": null, "yaw": 0.000650047484375083, "pitch": null, "roll": null}, "v": 2.2726306303965966, "accelerator_pedal_position": 0.26103735381588145, "brake_pedal_position": 0.0, "acceleration": 0.016203430007260766, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.018673155195475, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137674.587542} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2626883598878142, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0910129424873736, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2726306303965966, "gear": 1, "accelerator_pedal_position": 0.26103735381588145, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137674.587542} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.37998342514038, "x": 37.119592471882044, "y": 0.06963062246961638, "z": null, "yaw": 0.000650047484375083, "pitch": null, "roll": null}, "v": 2.2726306303965966, "accelerator_pedal_position": 0.26103735381588145, "brake_pedal_position": 0.0, "acceleration": 0.016203430007260766, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.018673155195475, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137674.607542} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26191556738677957, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0910129424873736, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.273377238126, "gear": 1, "accelerator_pedal_position": 0.26191556738677957, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137674.607542} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.37998342514038, "x": 37.119592471882044, "y": 0.06963062246961638, "z": null, "yaw": 0.000650047484375083, "pitch": null, "roll": null}, "v": 2.2726306303965966, "accelerator_pedal_position": 0.26103735381588145, "brake_pedal_position": 0.0, "acceleration": 0.016203430007260766, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.018673155195475, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137674.627542} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26191556738677957, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0910129424873736, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2735934480619275, "gear": 1, "accelerator_pedal_position": 0.26191556738677957, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137674.627542} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.37998342514038, "x": 37.119592471882044, "y": 0.06963062246961638, "z": null, "yaw": 0.000650047484375083, "pitch": null, "roll": null}, "v": 2.2726306303965966, "accelerator_pedal_position": 0.26103735381588145, "brake_pedal_position": 0.0, "acceleration": 0.016203430007260766, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.018673155195475, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137674.647542} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26191556738677957, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0910129424873736, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2740252488765345, "gear": 1, "accelerator_pedal_position": 0.26191556738677957, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137674.647542} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.37998342514038, "x": 37.119592471882044, "y": 0.06963062246961638, "z": null, "yaw": 0.000650047484375083, "pitch": null, "roll": null}, "v": 2.2726306303965966, "accelerator_pedal_position": 0.26103735381588145, "brake_pedal_position": 0.0, "acceleration": 0.016203430007260766, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.018673155195475, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137674.667542} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26191556738677957, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0910129424873736, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.274671405268955, "gear": 1, "accelerator_pedal_position": 0.26191556738677957, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137674.667542} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.37998342514038, "x": 37.119592471882044, "y": 0.06963062246961638, "z": null, "yaw": 0.000650047484375083, "pitch": null, "roll": null}, "v": 2.2726306303965966, "accelerator_pedal_position": 0.26103735381588145, "brake_pedal_position": 0.0, "acceleration": 0.016203430007260766, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.018673155195475, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137674.687542} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26191556738677957, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0910129424873736, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2748863795277994, "gear": 1, "accelerator_pedal_position": 0.26191556738677957, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137674.687542} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137674.697542, "x": 41.36970993170401, "y": 5.069690435649868, "z": null, "yaw": -0.00025377165984890075, "pitch": null, "roll": null}, "v": 2.2751011484957333, "accelerator_pedal_position": 0.26191556738677957, "brake_pedal_position": 0.0, "acceleration": 0.02145638638371944, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.018693454300512745, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137674.707542} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2673139636322235, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9237964854580601, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2753157123595704, "gear": 1, "accelerator_pedal_position": 0.26191556738677957, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137674.707542} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.489983320236206, "x": 37.36970993170401, "y": 0.06969043564986777, "z": null, "yaw": 6.2829315355197375, "pitch": null, "roll": null}, "v": 2.2751011484957333, "accelerator_pedal_position": 0.26191556738677957, "brake_pedal_position": 0.0, "acceleration": 0.02145638638371944, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.018693454300512745, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137674.727542} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26476126916905096, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9237964854580601, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2764187027882037, "gear": 1, "accelerator_pedal_position": 0.2673139636322235, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137674.727542} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.489983320236206, "x": 37.36970993170401, "y": 0.06969043564986777, "z": null, "yaw": 6.2829315355197375, "pitch": null, "roll": null}, "v": 2.2751011484957333, "accelerator_pedal_position": 0.26191556738677957, "brake_pedal_position": 0.0, "acceleration": 0.02145638638371944, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.018693454300512745, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137674.747542} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26476126916905096, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9237964854580601, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.277200652623695, "gear": 1, "accelerator_pedal_position": 0.26476126916905096, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137674.747542} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.489983320236206, "x": 37.36970993170401, "y": 0.06969043564986777, "z": null, "yaw": 6.2829315355197375, "pitch": null, "roll": null}, "v": 2.2751011484957333, "accelerator_pedal_position": 0.26191556738677957, "brake_pedal_position": 0.0, "acceleration": 0.02145638638371944, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.018693454300512745, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137674.767542} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26476126916905096, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9237964854580601, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2779811090216118, "gear": 1, "accelerator_pedal_position": 0.26476126916905096, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137674.767542} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.489983320236206, "x": 37.36970993170401, "y": 0.06969043564986777, "z": null, "yaw": 6.2829315355197375, "pitch": null, "roll": null}, "v": 2.2751011484957333, "accelerator_pedal_position": 0.26191556738677957, "brake_pedal_position": 0.0, "acceleration": 0.02145638638371944, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.018693454300512745, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137674.7875419} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26476126916905096, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9237964854580601, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.278760074590725, "gear": 1, "accelerator_pedal_position": 0.26476126916905096, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137674.7875419} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137674.8075418, "x": 41.62019552370499, "y": 5.069523925935819, "z": null, "yaw": -0.0011575908040728845, "pitch": null, "roll": null}, "v": 2.279537551936219, "accelerator_pedal_position": 0.26476126916905096, "brake_pedal_position": 0.0, "acceleration": 0.038818140202883766, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.018729906176521944, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137674.8075418} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26625055747479937, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9215368475432554, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.279537551936219, "gear": 1, "accelerator_pedal_position": 0.26476126916905096, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137674.8075418} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.59998321533203, "x": 37.62019552370499, "y": 0.06952392593581891, "z": null, "yaw": 6.282027716375513, "pitch": null, "roll": null}, "v": 2.279537551936219, "accelerator_pedal_position": 0.26476126916905096, "brake_pedal_position": 0.0, "acceleration": 0.038818140202883766, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.018729906176521944, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137674.8275418} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26557366802497623, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9215368475432554, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.280499615713449, "gear": 1, "accelerator_pedal_position": 0.26625055747479937, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137674.8275418} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.59998321533203, "x": 37.62019552370499, "y": 0.06952392593581891, "z": null, "yaw": 6.282027716375513, "pitch": null, "roll": null}, "v": 2.279537551936219, "accelerator_pedal_position": 0.26476126916905096, "brake_pedal_position": 0.0, "acceleration": 0.038818140202883766, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.018729906176521944, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137674.8475418} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26557366802497623, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9215368475432554, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2813752700754626, "gear": 1, "accelerator_pedal_position": 0.26557366802497623, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137674.8475418} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.59998321533203, "x": 37.62019552370499, "y": 0.06952392593581891, "z": null, "yaw": 6.282027716375513, "pitch": null, "roll": null}, "v": 2.279537551936219, "accelerator_pedal_position": 0.26476126916905096, "brake_pedal_position": 0.0, "acceleration": 0.038818140202883766, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.018729906176521944, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137674.8675418} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26557366802497623, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9215368475432554, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.282249250582024, "gear": 1, "accelerator_pedal_position": 0.26557366802497623, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137674.8675418} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.59998321533203, "x": 37.62019552370499, "y": 0.06952392593581891, "z": null, "yaw": 6.282027716375513, "pitch": null, "roll": null}, "v": 2.279537551936219, "accelerator_pedal_position": 0.26476126916905096, "brake_pedal_position": 0.0, "acceleration": 0.038818140202883766, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.018729906176521944, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137674.8875418} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26557366802497623, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9215368475432554, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.283121560127398, "gear": 1, "accelerator_pedal_position": 0.26557366802497623, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137674.8875418} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.59998321533203, "x": 37.62019552370499, "y": 0.06952392593581891, "z": null, "yaw": 6.282027716375513, "pitch": null, "roll": null}, "v": 2.279537551936219, "accelerator_pedal_position": 0.26476126916905096, "brake_pedal_position": 0.0, "acceleration": 0.038818140202883766, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.018729906176521944, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137674.9075418} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26557366802497623, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9215368475432554, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.283992201602068, "gear": 1, "accelerator_pedal_position": 0.26557366802497623, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137674.9075418} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137674.9175417, "x": 41.87119307733888, "y": 5.069130216626866, "z": null, "yaw": -0.0020614099482968687, "pitch": null, "roll": null}, "v": 2.28442689771513, "accelerator_pedal_position": 0.26557366802497623, "brake_pedal_position": 0.0, "acceleration": 0.04342801776030114, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.018770079670319312, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137674.9275417} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26841283589077614, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8652062148700219, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2848611778927332, "gear": 1, "accelerator_pedal_position": 0.26557366802497623, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137674.9275417} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.709983110427856, "x": 37.87119307733888, "y": 0.06913021662686614, "z": null, "yaw": 6.281123897231289, "pitch": null, "roll": null}, "v": 2.28442689771513, "accelerator_pedal_position": 0.26557366802497623, "brake_pedal_position": 0.0, "acceleration": 0.04342801776030114, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.018770079670319312, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137674.9475417} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26709647836697836, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8652062148700219, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.286083218034189, "gear": 1, "accelerator_pedal_position": 0.26841283589077614, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137674.9475417} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.709983110427856, "x": 37.87119307733888, "y": 0.06913021662686614, "z": null, "yaw": 6.281123897231289, "pitch": null, "roll": null}, "v": 2.28442689771513, "accelerator_pedal_position": 0.26557366802497623, "brake_pedal_position": 0.0, "acceleration": 0.04342801776030114, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.018770079670319312, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137674.9675417} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26709647836697836, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8652062148700219, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.287138454001644, "gear": 1, "accelerator_pedal_position": 0.26709647836697836, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137674.9675417} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.709983110427856, "x": 37.87119307733888, "y": 0.06913021662686614, "z": null, "yaw": 6.281123897231289, "pitch": null, "roll": null}, "v": 2.28442689771513, "accelerator_pedal_position": 0.26557366802497623, "brake_pedal_position": 0.0, "acceleration": 0.04342801776030114, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.018770079670319312, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137674.9875417} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26709647836697836, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8652062148700219, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2881916704234273, "gear": 1, "accelerator_pedal_position": 0.26709647836697836, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137674.9875417} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.709983110427856, "x": 37.87119307733888, "y": 0.06913021662686614, "z": null, "yaw": 6.281123897231289, "pitch": null, "roll": null}, "v": 2.28442689771513, "accelerator_pedal_position": 0.26557366802497623, "brake_pedal_position": 0.0, "acceleration": 0.04342801776030114, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.018770079670319312, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137675.0075417} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26709647836697836, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8652062148700219, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2897677158915797, "gear": 1, "accelerator_pedal_position": 0.26709647836697836, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137675.0075417} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137675.0275416, "x": 42.12277408410502, "y": 5.068508198856024, "z": null, "yaw": -0.002965229092520851, "pitch": null, "roll": null}, "v": 2.2902920583122963, "accelerator_pedal_position": 0.26709647836697836, "brake_pedal_position": 0.0, "acceleration": 0.05238400975431612, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.018818270983334467, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137675.0275416} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27631165238666433, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6129336434691632, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2902920583122963, "gear": 1, "accelerator_pedal_position": 0.26709647836697836, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137675.0275416} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.81998300552368, "x": 38.12277408410502, "y": 0.06850819885602366, "z": null, "yaw": 6.280220078087066, "pitch": null, "roll": null}, "v": 2.2902920583122963, "accelerator_pedal_position": 0.26709647836697836, "brake_pedal_position": 0.0, "acceleration": 0.05238400975431612, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.018818270983334467, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137675.0475416} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2719662585984616, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6129336434691632, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2924905814772916, "gear": 1, "accelerator_pedal_position": 0.27631165238666433, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137675.0475416} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.81998300552368, "x": 38.12277408410502, "y": 0.06850819885602366, "z": null, "yaw": 6.280220078087066, "pitch": null, "roll": null}, "v": 2.2902920583122963, "accelerator_pedal_position": 0.26709647836697836, "brake_pedal_position": 0.0, "acceleration": 0.05238400975431612, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.018818270983334467, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137675.0675416} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2719662585984616, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6129336434691632, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2949664901602445, "gear": 1, "accelerator_pedal_position": 0.2719662585984616, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137675.0675416} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.81998300552368, "x": 38.12277408410502, "y": 0.06850819885602366, "z": null, "yaw": 6.280220078087066, "pitch": null, "roll": null}, "v": 2.2902920583122963, "accelerator_pedal_position": 0.26709647836697836, "brake_pedal_position": 0.0, "acceleration": 0.05238400975431612, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.018818270983334467, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137675.0875416} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2719662585984616, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6129336434691632, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2957902109584722, "gear": 1, "accelerator_pedal_position": 0.2719662585984616, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137675.0875416} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.81998300552368, "x": 38.12277408410502, "y": 0.06850819885602366, "z": null, "yaw": 6.280220078087066, "pitch": null, "roll": null}, "v": 2.2902920583122963, "accelerator_pedal_position": 0.26709647836697836, "brake_pedal_position": 0.0, "acceleration": 0.05238400975431612, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.018818270983334467, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137675.1075416} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2719662585984616, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6129336434691632, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2974352831453704, "gear": 1, "accelerator_pedal_position": 0.2719662585984616, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137675.1075416} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.81998300552368, "x": 38.12277408410502, "y": 0.06850819885602366, "z": null, "yaw": 6.280220078087066, "pitch": null, "roll": null}, "v": 2.2902920583122963, "accelerator_pedal_position": 0.26709647836697836, "brake_pedal_position": 0.0, "acceleration": 0.05238400975431612, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.018818270983334467, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137675.1275415} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2719662585984616, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6129336434691632, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2990772002663022, "gear": 1, "accelerator_pedal_position": 0.2719662585984616, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137675.1275415} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137675.1375415, "x": 42.37521035774602, "y": 5.0676558790139214, "z": null, "yaw": -0.0038690482367448333, "pitch": null, "roll": null}, "v": 2.2998969772312945, "accelerator_pedal_position": 0.2719662585984616, "brake_pedal_position": 0.0, "acceleration": 0.08189900632004354, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.018897190161495464, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137675.1475415} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27253241689086577, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.585021240135142, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.300715967294495, "gear": 1, "accelerator_pedal_position": 0.2719662585984616, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137675.1475415} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.929982900619507, "x": 38.37521035774602, "y": 0.06765587901392145, "z": null, "yaw": 6.279316258942841, "pitch": null, "roll": null}, "v": 2.2998969772312945, "accelerator_pedal_position": 0.2719662585984616, "brake_pedal_position": 0.0, "acceleration": 0.08189900632004354, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.018897190161495464, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137675.1675415} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2723329989286586, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.585021240135142, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3024223250059075, "gear": 1, "accelerator_pedal_position": 0.27253241689086577, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137675.1675415} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.929982900619507, "x": 38.37521035774602, "y": 0.06765587901392145, "z": null, "yaw": 6.279316258942841, "pitch": null, "roll": null}, "v": 2.2998969772312945, "accelerator_pedal_position": 0.2719662585984616, "brake_pedal_position": 0.0, "acceleration": 0.08189900632004354, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.018897190161495464, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137675.1875415} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2723329989286586, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.585021240135142, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.304100491450314, "gear": 1, "accelerator_pedal_position": 0.2723329989286586, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137675.1875415} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.929982900619507, "x": 38.37521035774602, "y": 0.06765587901392145, "z": null, "yaw": 6.279316258942841, "pitch": null, "roll": null}, "v": 2.2998969772312945, "accelerator_pedal_position": 0.2719662585984616, "brake_pedal_position": 0.0, "acceleration": 0.08189900632004354, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.018897190161495464, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137675.2075415} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2723329989286586, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.585021240135142, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3057754348933543, "gear": 1, "accelerator_pedal_position": 0.2723329989286586, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137675.2075415} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.929982900619507, "x": 38.37521035774602, "y": 0.06765587901392145, "z": null, "yaw": 6.279316258942841, "pitch": null, "roll": null}, "v": 2.2998969772312945, "accelerator_pedal_position": 0.2719662585984616, "brake_pedal_position": 0.0, "acceleration": 0.08189900632004354, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.018897190161495464, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137675.2275414} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2723329989286586, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.585021240135142, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.307447160403327, "gear": 1, "accelerator_pedal_position": 0.2723329989286586, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137675.2275414} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137675.2475414, "x": 42.628658243673605, "y": 5.06657107120232, "z": null, "yaw": -0.00477286738096882, "pitch": null, "roll": null}, "v": 2.3091156730452553, "accelerator_pedal_position": 0.2723329989286586, "brake_pedal_position": 0.0, "acceleration": 0.08330530773682088, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.018972935922963056, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137675.2475414} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2781524856474237, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.438878772729365, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3091156730452553, "gear": 1, "accelerator_pedal_position": 0.2723329989286586, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137675.2475414} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.039982795715332, "x": 38.628658243673605, "y": 0.0665710712023202, "z": null, "yaw": 6.278412439798617, "pitch": null, "roll": null}, "v": 2.3091156730452553, "accelerator_pedal_position": 0.2723329989286586, "brake_pedal_position": 0.0, "acceleration": 0.08330530773682088, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.018972935922963056, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137675.2675414} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27544879162288066, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.438878772729365, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3115080638145793, "gear": 1, "accelerator_pedal_position": 0.2781524856474237, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137675.2675414} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.039982795715332, "x": 38.628658243673605, "y": 0.0665710712023202, "z": null, "yaw": 6.278412439798617, "pitch": null, "roll": null}, "v": 2.3091156730452553, "accelerator_pedal_position": 0.2723329989286586, "brake_pedal_position": 0.0, "acceleration": 0.08330530773682088, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.018972935922963056, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137675.2875414} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27544879162288066, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.438878772729365, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.313558053863417, "gear": 1, "accelerator_pedal_position": 0.27544879162288066, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137675.2875414} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.039982795715332, "x": 38.628658243673605, "y": 0.0665710712023202, "z": null, "yaw": 6.278412439798617, "pitch": null, "roll": null}, "v": 2.3091156730452553, "accelerator_pedal_position": 0.2723329989286586, "brake_pedal_position": 0.0, "acceleration": 0.08330530773682088, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.018972935922963056, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137675.3075414} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27544879162288066, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.438878772729365, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3156040991338127, "gear": 1, "accelerator_pedal_position": 0.27544879162288066, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137675.3075414} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.039982795715332, "x": 38.628658243673605, "y": 0.0665710712023202, "z": null, "yaw": 6.278412439798617, "pitch": null, "roll": null}, "v": 2.3091156730452553, "accelerator_pedal_position": 0.2723329989286586, "brake_pedal_position": 0.0, "acceleration": 0.08330530773682088, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.018972935922963056, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137675.3275414} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27544879162288066, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.438878772729365, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.318665783523207, "gear": 1, "accelerator_pedal_position": 0.27544879162288066, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137675.3275414} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.039982795715332, "x": 38.628658243673605, "y": 0.0665710712023202, "z": null, "yaw": 6.278412439798617, "pitch": null, "roll": null}, "v": 2.3091156730452553, "accelerator_pedal_position": 0.2723329989286586, "brake_pedal_position": 0.0, "acceleration": 0.08330530773682088, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.018972935922963056, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137675.3475413} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27544879162288066, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.438878772729365, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3196843790063073, "gear": 1, "accelerator_pedal_position": 0.27544879162288066, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137675.3475413} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137675.3575413, "x": 42.88325316866012, "y": 5.065251222718372, "z": null, "yaw": -0.005676686525192807, "pitch": null, "roll": null}, "v": 2.3207019927314136, "accelerator_pedal_position": 0.27544879162288066, "brake_pedal_position": 0.0, "acceleration": 0.10166327061575786, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.01906813535517623, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137675.3675413} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2917939909674382, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.109276511923929, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.323755852822747, "gear": 1, "accelerator_pedal_position": 0.2917939909674382, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137675.3675413} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.149982690811157, "x": 38.88325316866012, "y": 0.0652512227183717, "z": null, "yaw": 6.277508620654394, "pitch": null, "roll": null}, "v": 2.3207019927314136, "accelerator_pedal_position": 0.27544879162288066, "brake_pedal_position": 0.0, "acceleration": 0.10166327061575786, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.01906813535517623, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137675.3875413} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2840955677355655, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.109276511923929, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3257911152054476, "gear": 1, "accelerator_pedal_position": 0.2917939909674382, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137675.3875413} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.149982690811157, "x": 38.88325316866012, "y": 0.0652512227183717, "z": null, "yaw": 6.277508620654394, "pitch": null, "roll": null}, "v": 2.3207019927314136, "accelerator_pedal_position": 0.27544879162288066, "brake_pedal_position": 0.0, "acceleration": 0.10166327061575786, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.01906813535517623, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137675.4075413} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2840955677355655, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.109276511923929, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3288939108865225, "gear": 1, "accelerator_pedal_position": 0.2840955677355655, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137675.4075413} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.149982690811157, "x": 38.88325316866012, "y": 0.0652512227183717, "z": null, "yaw": 6.277508620654394, "pitch": null, "roll": null}, "v": 2.3207019927314136, "accelerator_pedal_position": 0.27544879162288066, "brake_pedal_position": 0.0, "acceleration": 0.10166327061575786, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.01906813535517623, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137675.4275413} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2840955677355655, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.109276511923929, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.331990717195464, "gear": 1, "accelerator_pedal_position": 0.2840955677355655, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137675.4275413} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.149982690811157, "x": 38.88325316866012, "y": 0.0652512227183717, "z": null, "yaw": 6.277508620654394, "pitch": null, "roll": null}, "v": 2.3207019927314136, "accelerator_pedal_position": 0.27544879162288066, "brake_pedal_position": 0.0, "acceleration": 0.10166327061575786, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.01906813535517623, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137675.4475412} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2840955677355655, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.109276511923929, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3350815418594135, "gear": 1, "accelerator_pedal_position": 0.2840955677355655, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137675.4475412} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137675.4675412, "x": 43.13940722950316, "y": 5.063691715995076, "z": null, "yaw": -0.006580505669416794, "pitch": null, "roll": null}, "v": 2.3381663926128007, "accelerator_pedal_position": 0.2840955677355655, "brake_pedal_position": 0.0, "acceleration": 0.15401875792120467, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.01921163225476878, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137675.4675412} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2848339459224081, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.022102394860958836, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3381663926128007, "gear": 1, "accelerator_pedal_position": 0.2840955677355655, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137675.4675412} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.259982585906982, "x": 39.13940722950316, "y": 0.06369171599507606, "z": null, "yaw": 6.276604801510169, "pitch": null, "roll": null}, "v": 2.3381663926128007, "accelerator_pedal_position": 0.2840955677355655, "brake_pedal_position": 0.0, "acceleration": 0.15401875792120467, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.01921163225476878, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137675.4875412} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28461086007619113, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.022102394860958836, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3413375298012205, "gear": 1, "accelerator_pedal_position": 0.2848339459224081, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137675.4875412} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.259982585906982, "x": 39.13940722950316, "y": 0.06369171599507606, "z": null, "yaw": 6.276604801510169, "pitch": null, "roll": null}, "v": 2.3381663926128007, "accelerator_pedal_position": 0.2840955677355655, "brake_pedal_position": 0.0, "acceleration": 0.15401875792120467, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.01921163225476878, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137675.5075412} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28461086007619113, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.022102394860958836, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.344474657723687, "gear": 1, "accelerator_pedal_position": 0.28461086007619113, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137675.5075412} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.259982585906982, "x": 39.13940722950316, "y": 0.06369171599507606, "z": null, "yaw": 6.276604801510169, "pitch": null, "roll": null}, "v": 2.3381663926128007, "accelerator_pedal_position": 0.2840955677355655, "brake_pedal_position": 0.0, "acceleration": 0.15401875792120467, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.01921163225476878, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137675.5275412} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28461086007619113, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.022102394860958836, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3476057104801478, "gear": 1, "accelerator_pedal_position": 0.28461086007619113, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137675.5275412} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.259982585906982, "x": 39.13940722950316, "y": 0.06369171599507606, "z": null, "yaw": 6.276604801510169, "pitch": null, "roll": null}, "v": 2.3381663926128007, "accelerator_pedal_position": 0.2840955677355655, "brake_pedal_position": 0.0, "acceleration": 0.15401875792120467, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.01921163225476878, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137675.5475411} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28461086007619113, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.022102394860958836, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3507306959158925, "gear": 1, "accelerator_pedal_position": 0.28461086007619113, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137675.5475411} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.259982585906982, "x": 39.13940722950316, "y": 0.06369171599507606, "z": null, "yaw": 6.276604801510169, "pitch": null, "roll": null}, "v": 2.3381663926128007, "accelerator_pedal_position": 0.2840955677355655, "brake_pedal_position": 0.0, "acceleration": 0.15401875792120467, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.01921163225476878, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137675.5675411} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28461086007619113, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.022102394860958836, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3538496218837897, "gear": 1, "accelerator_pedal_position": 0.28461086007619113, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137675.5675411} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137675.577541, "x": 43.397464163034236, "y": 5.061887383099914, "z": null, "yaw": -0.007484324813640781, "pitch": null, "roll": null}, "v": 2.3554068150233656, "accelerator_pedal_position": 0.28461086007619113, "brake_pedal_position": 0.0, "acceleration": 0.15556812208244108, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.019353288835034024, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137675.587541} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27518546445142467, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0954746633228176, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.35696249624419, "gear": 1, "accelerator_pedal_position": 0.28461086007619113, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137675.587541} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.369982481002808, "x": 39.397464163034236, "y": 0.06188738309991404, "z": null, "yaw": 6.2757009823659455, "pitch": null, "roll": null}, "v": 2.3554068150233656, "accelerator_pedal_position": 0.28461086007619113, "brake_pedal_position": 0.0, "acceleration": 0.15556812208244108, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.019353288835034024, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137675.607541} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2798010808997907, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0954746633228176, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.35889172479505, "gear": 1, "accelerator_pedal_position": 0.27518546445142467, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137675.607541} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.369982481002808, "x": 39.397464163034236, "y": 0.06188738309991404, "z": null, "yaw": 6.2757009823659455, "pitch": null, "roll": null}, "v": 2.3554068150233656, "accelerator_pedal_position": 0.28461086007619113, "brake_pedal_position": 0.0, "acceleration": 0.15556812208244108, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.019353288835034024, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137675.627541} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2798010808997907, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0954746633228176, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3613938776321324, "gear": 1, "accelerator_pedal_position": 0.2798010808997907, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137675.627541} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.369982481002808, "x": 39.397464163034236, "y": 0.06188738309991404, "z": null, "yaw": 6.2757009823659455, "pitch": null, "roll": null}, "v": 2.3554068150233656, "accelerator_pedal_position": 0.28461086007619113, "brake_pedal_position": 0.0, "acceleration": 0.15556812208244108, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.019353288835034024, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137675.647541} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2798010808997907, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0954746633228176, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3638911678801433, "gear": 1, "accelerator_pedal_position": 0.2798010808997907, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137675.647541} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.369982481002808, "x": 39.397464163034236, "y": 0.06188738309991404, "z": null, "yaw": 6.2757009823659455, "pitch": null, "roll": null}, "v": 2.3554068150233656, "accelerator_pedal_position": 0.28461086007619113, "brake_pedal_position": 0.0, "acceleration": 0.15556812208244108, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.019353288835034024, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137675.667541} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2798010808997907, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0954746633228176, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.367628001115057, "gear": 1, "accelerator_pedal_position": 0.2798010808997907, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137675.667541} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137675.687541, "x": 43.65722015541133, "y": 5.059836418305551, "z": null, "yaw": -0.008388143957864767, "pitch": null, "roll": null}, "v": 2.3688711884355698, "accelerator_pedal_position": 0.2798010808997907, "brake_pedal_position": 0.0, "acceleration": 0.12419768912791196, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.01946391936644248, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137675.687541} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23420733549869235, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7168475015139134, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3688711884355698, "gear": 1, "accelerator_pedal_position": 0.2798010808997907, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45520800008604273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137675.687541} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.479982376098633, "x": 39.65722015541133, "y": 0.059836418305550865, "z": null, "yaw": 6.274797163221722, "pitch": null, "roll": null}, "v": 2.3688711884355698, "accelerator_pedal_position": 0.2798010808997907, "brake_pedal_position": 0.0, "acceleration": 0.12419768912791196, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.01946391936644248, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137675.707541} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2560184109168596, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7168475015139134, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.365657489255359, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.37450915464583634, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137675.707541} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.479982376098633, "x": 39.65722015541133, "y": 0.059836418305550865, "z": null, "yaw": 6.274797163221722, "pitch": null, "roll": null}, "v": 2.3688711884355698, "accelerator_pedal_position": 0.2798010808997907, "brake_pedal_position": 0.0, "acceleration": 0.12419768912791196, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.01946391936644248, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137675.727541} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2560184109168596, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7168475015139134, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.365175100881511, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.29363590979341125, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137675.727541} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.479982376098633, "x": 39.65722015541133, "y": 0.059836418305550865, "z": null, "yaw": 6.274797163221722, "pitch": null, "roll": null}, "v": 2.3688711884355698, "accelerator_pedal_position": 0.2798010808997907, "brake_pedal_position": 0.0, "acceleration": 0.12419768912791196, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.01946391936644248, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137675.747541} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2560184109168596, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7168475015139134, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3646936508357594, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2125882655287676, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137675.747541} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.479982376098633, "x": 39.65722015541133, "y": 0.059836418305550865, "z": null, "yaw": 6.274797163221722, "pitch": null, "roll": null}, "v": 2.3688711884355698, "accelerator_pedal_position": 0.2798010808997907, "brake_pedal_position": 0.0, "acceleration": 0.12419768912791196, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.01946391936644248, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137675.767541} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2560184109168596, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7168475015139134, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.364213137200223, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.13136622185190516, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137675.767541} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.479982376098633, "x": 39.65722015541133, "y": 0.059836418305550865, "z": null, "yaw": 6.274797163221722, "pitch": null, "roll": null}, "v": 2.3688711884355698, "accelerator_pedal_position": 0.2798010808997907, "brake_pedal_position": 0.0, "acceleration": 0.12419768912791196, "steering_wheel_angle": -0.45520800008604273, "front_wheel_angle": -0.021031235103508454, "heading_rate": -0.01946391936644248, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137675.787541} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2560184109168596, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7168475015139134, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3637335580612913, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.13136622185190516, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137675.787541} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137675.797541, "x": 43.91739417496299, "y": 5.0575755176117365, "z": null, "yaw": -0.00891131781706915, "pitch": null, "roll": null}, "v": 2.363494118331214, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37403575039042314, "steering_wheel_angle": -0.13136622185190516, "front_wheel_angle": -0.0060433089498307955, "heading_rate": -0.00557949181403871, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137675.807541} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3142814908646008, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3632549115096135, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.13136622185190516, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137675.807541} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.589982271194458, "x": 39.91739417496299, "y": 0.057575517611736515, "z": null, "yaw": 6.274273989362517, "pitch": null, "roll": null}, "v": 2.363494118331214, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37403575039042314, "steering_wheel_angle": -0.13136622185190516, "front_wheel_angle": -0.0060433089498307955, "heading_rate": -0.00557949181403871, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137675.8275409} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2343040342501041, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3142814908646008, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.355778298279989, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.04860989930754923, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137675.8275409} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.589982271194458, "x": 39.91739417496299, "y": 0.057575517611736515, "z": null, "yaw": 6.274273989362517, "pitch": null, "roll": null}, "v": 2.363494118331214, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37403575039042314, "steering_wheel_angle": -0.13136622185190516, "front_wheel_angle": -0.0060433089498307955, "heading_rate": -0.00557949181403871, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137675.8475409} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2343040342501041, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3142814908646008, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3526021287590364, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.034295850452941305, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137675.8475409} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.589982271194458, "x": 39.91739417496299, "y": 0.057575517611736515, "z": null, "yaw": 6.274273989362517, "pitch": null, "roll": null}, "v": 2.363494118331214, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37403575039042314, "steering_wheel_angle": -0.13136622185190516, "front_wheel_angle": -0.0060433089498307955, "heading_rate": -0.00557949181403871, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137675.8675408} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2343040342501041, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3142814908646008, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.349432122329525, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.11708331366648247, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137675.8675408} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.589982271194458, "x": 39.91739417496299, "y": 0.057575517611736515, "z": null, "yaw": 6.274273989362517, "pitch": null, "roll": null}, "v": 2.363494118331214, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37403575039042314, "steering_wheel_angle": -0.13136622185190516, "front_wheel_angle": -0.0060433089498307955, "heading_rate": -0.00557949181403871, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137675.8875408} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2343040342501041, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3142814908646008, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3462682630148617, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1996905079003298, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137675.8875408} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137675.9075408, "x": 44.1762646954286, "y": 5.055259031637545, "z": null, "yaw": -0.008836167825256256, "pitch": null, "roll": null}, "v": 2.3431105348928116, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3720571965318974, "steering_wheel_angle": 0.28211743315448323, "front_wheel_angle": 0.013004259789237508, "heading_rate": 0.011903178067249073, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137675.9075408} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24511035128173878, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.330138043380238, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3431105348928116, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.28211743315448323, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137675.9075408} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.699982166290283, "x": 40.1762646954286, "y": 0.05525903163754542, "z": null, "yaw": 6.27434913935433, "pitch": null, "roll": null}, "v": 2.3431105348928116, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3720571965318974, "steering_wheel_angle": 0.28211743315448323, "front_wheel_angle": 0.013004259789237508, "heading_rate": 0.011903178067249073, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137675.9275408} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2398137364220393, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.330138043380238, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.340409627305119, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.405474833744177, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137675.9275408} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.699982166290283, "x": 40.1762646954286, "y": 0.05525903163754542, "z": null, "yaw": 6.27434913935433, "pitch": null, "roll": null}, "v": 2.3431105348928116, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3720571965318974, "steering_wheel_angle": 0.28211743315448323, "front_wheel_angle": 0.013004259789237508, "heading_rate": 0.011903178067249073, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137675.9475408} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2398137364220393, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.330138043380238, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.339180029295486, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.44650375219833005, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137675.9475408} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.699982166290283, "x": 40.1762646954286, "y": 0.05525903163754542, "z": null, "yaw": 6.27434913935433, "pitch": null, "roll": null}, "v": 2.3431105348928116, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3720571965318974, "steering_wheel_angle": 0.28211743315448323, "front_wheel_angle": 0.013004259789237508, "heading_rate": 0.011903178067249073, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137675.9675407} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2398137364220393, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.330138043380238, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3367244024234632, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4874875631146109, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137675.9675407} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.699982166290283, "x": 40.1762646954286, "y": 0.05525903163754542, "z": null, "yaw": 6.27434913935433, "pitch": null, "roll": null}, "v": 2.3431105348928116, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3720571965318974, "steering_wheel_angle": 0.28211743315448323, "front_wheel_angle": 0.013004259789237508, "heading_rate": 0.011903178067249073, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137675.9875407} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2398137364220393, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.330138043380238, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3342735247324575, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4874875631146109, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137675.9875407} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.699982166290283, "x": 40.1762646954286, "y": 0.05525903163754542, "z": null, "yaw": 6.27434913935433, "pitch": null, "roll": null}, "v": 2.3431105348928116, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3720571965318974, "steering_wheel_angle": 0.28211743315448323, "front_wheel_angle": 0.013004259789237508, "heading_rate": 0.011903178067249073, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137676.0075407} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2398137364220393, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.330138043380238, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3318273846359947, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4874875631146109, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137676.0075407} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137676.0175407, "x": 44.4334108695864, "y": 5.0530772479841035, "z": null, "yaw": -0.007979517024608081, "pitch": null, "roll": null}, "v": 2.33060608757488, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3708475517331549, "steering_wheel_angle": 0.4874875631146109, "front_wheel_angle": 0.02253230063843416, "heading_rate": 0.020516721103694263, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137676.0275407} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24810758101924876, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3415568105580045, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.329385970583926, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4874875631146109, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137676.0275407} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.80998206138611, "x": 40.4334108695864, "y": 0.053077247984103515, "z": null, "yaw": 6.2752057901549785, "pitch": null, "roll": null}, "v": 2.33060608757488, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3708475517331549, "steering_wheel_angle": 0.4874875631146109, "front_wheel_angle": 0.02253230063843416, "heading_rate": 0.020516721103694263, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137676.0475407} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24406596577885287, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3415568105580045, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.32798550105923, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5284394445976445, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137676.0475407} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.80998206138611, "x": 40.4334108695864, "y": 0.053077247984103515, "z": null, "yaw": 6.2752057901549785, "pitch": null, "roll": null}, "v": 2.33060608757488, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3708475517331549, "steering_wheel_angle": 0.4874875631146109, "front_wheel_angle": 0.02253230063843416, "heading_rate": 0.020516721103694263, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137676.0675406} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24406596577885287, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3415568105580045, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.32608277696742, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5284394445976445, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137676.0675406} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.80998206138611, "x": 40.4334108695864, "y": 0.053077247984103515, "z": null, "yaw": 6.2752057901549785, "pitch": null, "roll": null}, "v": 2.33060608757488, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3708475517331549, "steering_wheel_angle": 0.4874875631146109, "front_wheel_angle": 0.02253230063843416, "heading_rate": 0.020516721103694263, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137676.0875406} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24406596577885287, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3415568105580045, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3241837245463994, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5284394445976445, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137676.0875406} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.80998206138611, "x": 40.4334108695864, "y": 0.053077247984103515, "z": null, "yaw": 6.2752057901549785, "pitch": null, "roll": null}, "v": 2.33060608757488, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3708475517331549, "steering_wheel_angle": 0.4874875631146109, "front_wheel_angle": 0.02253230063843416, "heading_rate": 0.020516721103694263, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137676.1075406} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24406596577885287, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3415568105580045, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.32228833526911, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5284394445976445, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137676.1075406} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137676.1275406, "x": 44.689263251149995, "y": 5.051154392256024, "z": null, "yaw": -0.006944115735893908, "pitch": null, "roll": null}, "v": 2.320396600633288, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36986223387396966, "steering_wheel_angle": 0.5284394445976445, "front_wheel_angle": 0.02443852255879827, "heading_rate": 0.022155608061002526, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137676.1275406} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2513648493526582, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3553342621850055, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.320396600633288, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5284394445976445, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137676.1275406} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.919981956481934, "x": 40.689263251149995, "y": 0.051154392256023584, "z": null, "yaw": 6.276241191443693, "pitch": null, "roll": null}, "v": 2.320396600633288, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36986223387396966, "steering_wheel_angle": 0.5284394445976445, "front_wheel_angle": 0.02443852255879827, "heading_rate": 0.022155608061002526, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137676.1475406} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2478141168973527, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3553342621850055, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3194204328795403, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5284394445976445, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137676.1475406} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.919981956481934, "x": 40.689263251149995, "y": 0.051154392256023584, "z": null, "yaw": 6.276241191443693, "pitch": null, "roll": null}, "v": 2.320396600633288, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36986223387396966, "steering_wheel_angle": 0.5284394445976445, "front_wheel_angle": 0.02443852255879827, "heading_rate": 0.022155608061002526, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137676.1675406} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2478141168973527, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3553342621850055, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3180025184616704, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5284394445976445, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137676.1675406} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.919981956481934, "x": 40.689263251149995, "y": 0.051154392256023584, "z": null, "yaw": 6.276241191443693, "pitch": null, "roll": null}, "v": 2.320396600633288, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36986223387396966, "steering_wheel_angle": 0.5284394445976445, "front_wheel_angle": 0.02443852255879827, "heading_rate": 0.022155608061002526, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137676.1875405} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2478141168973527, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3553342621850055, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3165873355342756, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5284394445976445, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137676.1875405} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.919981956481934, "x": 40.689263251149995, "y": 0.051154392256023584, "z": null, "yaw": 6.276241191443693, "pitch": null, "roll": null}, "v": 2.320396600633288, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36986223387396966, "steering_wheel_angle": 0.5284394445976445, "front_wheel_angle": 0.02443852255879827, "heading_rate": 0.022155608061002526, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137676.2075405} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2478141168973527, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3553342621850055, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3151748780346626, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5284394445976445, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137676.2075405} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.919981956481934, "x": 40.689263251149995, "y": 0.051154392256023584, "z": null, "yaw": 6.276241191443693, "pitch": null, "roll": null}, "v": 2.320396600633288, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36986223387396966, "steering_wheel_angle": 0.5284394445976445, "front_wheel_angle": 0.02443852255879827, "heading_rate": 0.022155608061002526, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137676.2275405} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2478141168973527, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3553342621850055, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.31376513991644, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5284394445976445, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137676.2275405} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137676.2375405, "x": 44.944154022855066, "y": 5.049505994298883, "z": null, "yaw": -0.005893813866788804, "pitch": null, "roll": null}, "v": 2.313061288740297, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3691555896917041, "steering_wheel_angle": 0.5284394445976445, "front_wheel_angle": 0.02443852255879827, "heading_rate": 0.022085569044714547, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137676.2475405} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.01072673007215, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3123581151494643, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5284394445976445, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137676.2475405} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.02998185157776, "x": 40.944154022855066, "y": 0.04950599429888314, "z": null, "yaw": 6.277291493312798, "pitch": null, "roll": null}, "v": 2.313061288740297, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3691555896917041, "steering_wheel_angle": 0.5284394445976445, "front_wheel_angle": 0.02443852255879827, "heading_rate": 0.022085569044714547, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137676.2675405} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22808571413864054, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.01072673007215, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3049799080278786, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.6117947259472962, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137676.2675405} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.02998185157776, "x": 40.944154022855066, "y": 0.04950599429888314, "z": null, "yaw": 6.277291493312798, "pitch": null, "roll": null}, "v": 2.313061288740297, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3691555896917041, "steering_wheel_angle": 0.5284394445976445, "front_wheel_angle": 0.02443852255879827, "heading_rate": 0.022085569044714547, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137676.2875404} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22808571413864054, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.01072673007215, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.301124908749708, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.694962376901723, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137676.2875404} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.02998185157776, "x": 40.944154022855066, "y": 0.04950599429888314, "z": null, "yaw": 6.277291493312798, "pitch": null, "roll": null}, "v": 2.313061288740297, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3691555896917041, "steering_wheel_angle": 0.5284394445976445, "front_wheel_angle": 0.02443852255879827, "heading_rate": 0.022085569044714547, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137676.3075404} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22808571413864054, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.01072673007215, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2972773107357156, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.7779423974609245, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137676.3075404} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.02998185157776, "x": 40.944154022855066, "y": 0.04950599429888314, "z": null, "yaw": 6.277291493312798, "pitch": null, "roll": null}, "v": 2.313061288740297, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3691555896917041, "steering_wheel_angle": 0.5284394445976445, "front_wheel_angle": 0.02443852255879827, "heading_rate": 0.022085569044714547, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137676.3275404} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22808571413864054, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.01072673007215, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2934370938573494, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.8607347876249009, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137676.3275404} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137676.3475404, "x": 45.197350736431034, "y": 5.048155255600236, "z": null, "yaw": -0.004501597209453399, "pitch": null, "roll": null}, "v": 2.2896042380587427, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3669030875723027, "steering_wheel_angle": 0.9433395473936518, "front_wheel_angle": 0.043871110684453075, "heading_rate": 0.039262489648272454, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137676.3475404} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21676322273884827, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.3797373195190055, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2896042380587427, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.9433395473936518, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137676.3475404} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.139981746673584, "x": 41.197350736431034, "y": 0.04815525560023559, "z": null, "yaw": 6.2786837099701325, "pitch": null, "roll": null}, "v": 2.2896042380587427, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3669030875723027, "steering_wheel_angle": 0.9433395473936518, "front_wheel_angle": 0.043871110684453075, "heading_rate": 0.039262489648272454, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137676.3675404} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2219832687087217, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.3797373195190055, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.284364089488649, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.0266619882213002, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137676.3675404} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.139981746673584, "x": 41.197350736431034, "y": 0.04815525560023559, "z": null, "yaw": 6.2786837099701325, "pitch": null, "roll": null}, "v": 2.2896042380587427, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3669030875723027, "steering_wheel_angle": 0.9433395473936518, "front_wheel_angle": 0.043871110684453075, "heading_rate": 0.039262489648272454, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137676.3875403} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2219832687087217, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.3797373195190055, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2797861609005032, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.109792649158557, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137676.3875403} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.139981746673584, "x": 41.197350736431034, "y": 0.04815525560023559, "z": null, "yaw": 6.2786837099701325, "pitch": null, "roll": null}, "v": 2.2896042380587427, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3669030875723027, "steering_wheel_angle": 0.9433395473936518, "front_wheel_angle": 0.043871110684453075, "heading_rate": 0.039262489648272454, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137676.4075403} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2219832687087217, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.3797373195190055, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2729356674024053, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.23412905326996, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137676.4075403} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.139981746673584, "x": 41.197350736431034, "y": 0.04815525560023559, "z": null, "yaw": 6.2786837099701325, "pitch": null, "roll": null}, "v": 2.2896042380587427, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3669030875723027, "steering_wheel_angle": 0.9433395473936518, "front_wheel_angle": 0.043871110684453075, "heading_rate": 0.039262489648272454, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137676.4275403} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2219832687087217, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.3797373195190055, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2706565302081843, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.2754786313618987, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137676.4275403} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.139981746673584, "x": 41.197350736431034, "y": 0.04815525560023559, "z": null, "yaw": 6.2786837099701325, "pitch": null, "roll": null}, "v": 2.2896042380587427, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3669030875723027, "steering_wheel_angle": 0.9433395473936518, "front_wheel_angle": 0.043871110684453075, "heading_rate": 0.039262489648272454, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137676.4475403} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2219832687087217, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.3797373195190055, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2661047780532773, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.358033952627983, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137676.4475403} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137676.4575403, "x": 45.44788517567234, "y": 5.047270639512362, "z": null, "yaw": -0.0021921129191883886, "pitch": null, "roll": null}, "v": 2.2638321568720343, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3644409681884806, "steering_wheel_angle": 1.3992396958021287, "front_wheel_angle": 0.06548203126850684, "heading_rate": 0.05798928587737144, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137676.4675403} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.017236750120920366, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.2246807517135836, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2615617014844447, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.4403974940036763, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137676.4675403} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.24998164176941, "x": 41.44788517567234, "y": 0.04727063951236232, "z": null, "yaw": 6.280993194260398, "pitch": null, "roll": null}, "v": 2.2638321568720343, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3644409681884806, "steering_wheel_angle": 1.3992396958021287, "front_wheel_angle": 0.06548203126850684, "heading_rate": 0.05798928587737144, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137676.4875402} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.2246807517135836, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2515241067147937, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.017236750120920366, "steering_wheel_angle": 1.5247296978279787, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137676.4875402} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.24998164176941, "x": 41.44788517567234, "y": 0.04727063951236232, "z": null, "yaw": 6.280993194260398, "pitch": null, "roll": null}, "v": 2.2638321568720343, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3644409681884806, "steering_wheel_angle": 1.3992396958021287, "front_wheel_angle": 0.06548203126850684, "heading_rate": 0.05798928587737144, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137676.5075402} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.2246807517135836, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.240636358952844, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.650849236048724, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137676.5075402} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.24998164176941, "x": 41.44788517567234, "y": 0.04727063951236232, "z": null, "yaw": 6.280993194260398, "pitch": null, "roll": null}, "v": 2.2638321568720343, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3644409681884806, "steering_wheel_angle": 1.3992396958021287, "front_wheel_angle": 0.06548203126850684, "heading_rate": 0.05798928587737144, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137676.5275402} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.2246807517135836, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2370139956440616, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.69278807745145, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137676.5275402} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.24998164176941, "x": 41.44788517567234, "y": 0.04727063951236232, "z": null, "yaw": 6.280993194260398, "pitch": null, "roll": null}, "v": 2.2638321568720343, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3644409681884806, "steering_wheel_angle": 1.3992396958021287, "front_wheel_angle": 0.06548203126850684, "heading_rate": 0.05798928587737144, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137676.5475402} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.2246807517135836, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2297795625999735, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.7765142532506188, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137676.5475402} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137676.5675402, "x": 45.694811037007334, "y": 5.047073494473995, "z": null, "yaw": 0.0010590620118554502, "pitch": null, "roll": null}, "v": 2.2225588152229268, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36052561763239777, "steering_wheel_angle": 1.860038419708076, "front_wheel_angle": 0.08761010731382117, "heading_rate": 0.07625716414578922, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137676.5675402} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23003113729137137, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.1049076669481086, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2225588152229268, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.860038419708076, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137676.5675402} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.359981536865234, "x": 41.694811037007334, "y": 0.047073494473995225, "z": null, "yaw": 0.0010590620118554502, "pitch": null, "roll": null}, "v": 2.2225588152229268, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36052561763239777, "steering_wheel_angle": 1.860038419708076, "front_wheel_angle": 0.08761010731382117, "heading_rate": 0.07625716414578922, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137676.5875401} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.1049076669481086, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2191038271422103, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.9430477296022084, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137676.5875401} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.359981536865234, "x": 41.694811037007334, "y": 0.047073494473995225, "z": null, "yaw": 0.0010590620118554502, "pitch": null, "roll": null}, "v": 2.2225588152229268, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36052561763239777, "steering_wheel_angle": 1.860038419708076, "front_wheel_angle": 0.08761010731382117, "heading_rate": 0.07625716414578922, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137676.6075401} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.1049076669481086, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.211903237295327, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.025856546091005, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137676.6075401} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.359981536865234, "x": 41.694811037007334, "y": 0.047073494473995225, "z": null, "yaw": 0.0010590620118554502, "pitch": null, "roll": null}, "v": 2.2225588152229268, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36052561763239777, "steering_wheel_angle": 1.860038419708076, "front_wheel_angle": 0.08761010731382117, "heading_rate": 0.07625716414578922, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137676.62754} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.1049076669481086, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.204716217629182, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.1084648691744654, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137676.62754} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.359981536865234, "x": 41.694811037007334, "y": 0.047073494473995225, "z": null, "yaw": 0.0010590620118554502, "pitch": null, "roll": null}, "v": 2.2225588152229268, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36052561763239777, "steering_wheel_angle": 1.860038419708076, "front_wheel_angle": 0.08761010731382117, "heading_rate": 0.07625716414578922, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137676.64754} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.1049076669481086, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1975427219179196, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.1908726988525906, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137676.64754} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.359981536865234, "x": 41.694811037007334, "y": 0.047073494473995225, "z": null, "yaw": 0.0010590620118554502, "pitch": null, "roll": null}, "v": 2.2225588152229268, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36052561763239777, "steering_wheel_angle": 1.860038419708076, "front_wheel_angle": 0.08761010731382117, "heading_rate": 0.07625716414578922, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137676.66754} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.1049076669481086, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.190382704139295, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.27308003512538, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137676.66754} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137676.67754, "x": 45.93766921740288, "y": 5.047774759662985, "z": null, "yaw": 0.00526869025645286, "pitch": null, "roll": null}, "v": 2.186807735148166, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3571616674624468, "steering_wheel_angle": 2.3141085182347734, "front_wheel_angle": 0.10970652040937603, "heading_rate": 0.09409148142760798, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137676.68754} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24441602117613617, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.9517460668285236, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.183236118473541, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.3141085182347734, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137676.68754} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.46998143196106, "x": 41.93766921740288, "y": 0.04777475966298539, "z": null, "yaw": 0.00526869025645286, "pitch": null, "roll": null}, "v": 2.186807735148166, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3571616674624468, "steering_wheel_angle": 2.3141085182347734, "front_wheel_angle": 0.10970652040937603, "heading_rate": 0.09409148142760798, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137676.70754} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23006854467226323, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.9517460668285236, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1816523230258213, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.3141085182347734, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137676.70754} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.46998143196106, "x": 41.93766921740288, "y": 0.04777475966298539, "z": null, "yaw": 0.00526869025645286, "pitch": null, "roll": null}, "v": 2.186807735148166, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3571616674624468, "steering_wheel_angle": 2.3141085182347734, "front_wheel_angle": 0.10970652040937603, "heading_rate": 0.09409148142760798, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137676.72754} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23006854467226323, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.9517460668285236, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.178278897190635, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.3141085182347734, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137676.72754} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.46998143196106, "x": 41.93766921740288, "y": 0.04777475966298539, "z": null, "yaw": 0.00526869025645286, "pitch": null, "roll": null}, "v": 2.186807735148166, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3571616674624468, "steering_wheel_angle": 2.3141085182347734, "front_wheel_angle": 0.10970652040937603, "heading_rate": 0.09409148142760798, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137676.74754} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23006854467226323, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.9517460668285236, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1749117822704025, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.3141085182347734, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137676.74754} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.46998143196106, "x": 41.93766921740288, "y": 0.04777475966298539, "z": null, "yaw": 0.00526869025645286, "pitch": null, "roll": null}, "v": 2.186807735148166, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3571616674624468, "steering_wheel_angle": 2.3141085182347734, "front_wheel_angle": 0.10970652040937603, "heading_rate": 0.09409148142760798, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137676.76754} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23006854467226323, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.9517460668285236, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.171550961925966, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.3141085182347734, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137676.76754} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137676.78754, "x": 46.17724785120647, "y": 5.049551716891354, "z": null, "yaw": 0.010001645417842773, "pitch": null, "roll": null}, "v": 2.168196419874138, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3554205781452572, "steering_wheel_angle": 2.3141085182347734, "front_wheel_angle": 0.10970652040937603, "heading_rate": 0.09329069487591285, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137676.78754} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21943868446425038, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.335433605389176, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.168196419874138, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.3141085182347734, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137676.78754} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.579981327056885, "x": 42.17724785120647, "y": 0.0495517168913544, "z": null, "yaw": 0.010001645417842773, "pitch": null, "roll": null}, "v": 2.168196419874138, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3554205781452572, "steering_wheel_angle": 2.3141085182347734, "front_wheel_angle": 0.10970652040937603, "heading_rate": 0.09329069487591285, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137676.80754} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22436787069671926, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.335433605389176, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1635200273732127, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.396612368546682, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137676.80754} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.579981327056885, "x": 42.17724785120647, "y": 0.0495517168913544, "z": null, "yaw": 0.010001645417842773, "pitch": null, "roll": null}, "v": 2.168196419874138, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3554205781452572, "steering_wheel_angle": 2.3141085182347734, "front_wheel_angle": 0.10970652040937603, "heading_rate": 0.09329069487591285, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137676.82754} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22436787069671926, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.335433605389176, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.159468217441449, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.478912787204121, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137676.82754} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.579981327056885, "x": 42.17724785120647, "y": 0.0495517168913544, "z": null, "yaw": 0.010001645417842773, "pitch": null, "roll": null}, "v": 2.168196419874138, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3554205781452572, "steering_wheel_angle": 2.3141085182347734, "front_wheel_angle": 0.10970652040937603, "heading_rate": 0.09329069487591285, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137676.84754} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22436787069671926, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.335433605389176, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1554239573437792, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.5610097742070908, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137676.84754} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.579981327056885, "x": 42.17724785120647, "y": 0.0495517168913544, "z": null, "yaw": 0.010001645417842773, "pitch": null, "roll": null}, "v": 2.168196419874138, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3554205781452572, "steering_wheel_angle": 2.3141085182347734, "front_wheel_angle": 0.10970652040937603, "heading_rate": 0.09329069487591285, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137676.86754} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22436787069671926, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.335433605389176, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.151387226473045, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.5610097742070908, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137676.86754} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.579981327056885, "x": 42.17724785120647, "y": 0.0495517168913544, "z": null, "yaw": 0.010001645417842773, "pitch": null, "roll": null}, "v": 2.168196419874138, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3554205781452572, "steering_wheel_angle": 2.3141085182347734, "front_wheel_angle": 0.10970652040937603, "heading_rate": 0.09329069487591285, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137676.8875399} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22436787069671926, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.335433605389176, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1473580042969833, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.5610097742070908, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137676.8875399} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137676.8975399, "x": 46.41455901304133, "y": 5.052461631479333, "z": null, "yaw": 0.015095030943694023, "pitch": null, "roll": null}, "v": 2.145346202573518, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35329241341764206, "steering_wheel_angle": 2.5610097742070908, "front_wheel_angle": 0.12184710404570112, "heading_rate": 0.10261938120759333, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137676.9075398} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.014566348742402382, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.246257524499409, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1433362703578864, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.5610097742070908, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137676.9075398} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.68998122215271, "x": 42.41455901304133, "y": 0.052461631479332915, "z": null, "yaw": 0.015095030943694023, "pitch": null, "roll": null}, "v": 2.145346202573518, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35329241341764206, "steering_wheel_angle": 2.5610097742070908, "front_wheel_angle": 0.12184710404570112, "heading_rate": 0.10261938120759333, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137676.9275398} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.246257524499409, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1339478993700483, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.014566348742402382, "steering_wheel_angle": 2.645379308194374, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137676.9275398} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.68998122215271, "x": 42.41455901304133, "y": 0.052461631479332915, "z": null, "yaw": 0.015095030943694023, "pitch": null, "roll": null}, "v": 2.145346202573518, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35329241341764206, "steering_wheel_angle": 2.5610097742070908, "front_wheel_angle": 0.12184710404570112, "heading_rate": 0.10261938120759333, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137676.9475398} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.246257524499409, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1269064679773266, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.7295329071824477, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137676.9475398} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.68998122215271, "x": 42.41455901304133, "y": 0.052461631479332915, "z": null, "yaw": 0.015095030943694023, "pitch": null, "roll": null}, "v": 2.145346202573518, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35329241341764206, "steering_wheel_angle": 2.5610097742070908, "front_wheel_angle": 0.12184710404570112, "heading_rate": 0.10261938120759333, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137676.9675398} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.246257524499409, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.119878067528474, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.813470571171313, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137676.9675398} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.68998122215271, "x": 42.41455901304133, "y": 0.052461631479332915, "z": null, "yaw": 0.015095030943694023, "pitch": null, "roll": null}, "v": 2.145346202573518, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35329241341764206, "steering_wheel_angle": 2.5610097742070908, "front_wheel_angle": 0.12184710404570112, "heading_rate": 0.10261938120759333, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137676.9875398} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.246257524499409, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.112862654158048, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.897192300160968, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137676.9875398} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137677.0075397, "x": 46.6485272225161, "y": 5.056572460322919, "z": null, "yaw": 0.020729284365117923, "pitch": null, "roll": null}, "v": 2.1058601841911884, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3496394803631769, "steering_wheel_angle": 2.980698094151414, "front_wheel_angle": 0.14269396016075742, "heading_rate": 0.1181835096042839, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137677.0075397} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2369254270249699, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.048871859430062, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1058601841911884, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.980698094151414, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137677.0075397} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.799981117248535, "x": 42.6485272225161, "y": 0.056572460322919405, "z": null, "yaw": 0.020729284365117923, "pitch": null, "roll": null}, "v": 2.1058601841911884, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3496394803631769, "steering_wheel_angle": 2.980698094151414, "front_wheel_angle": 0.14269396016075742, "heading_rate": 0.1181835096042839, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137677.0275397} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2198612879721031, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.048871859430062, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.103484167684976, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.063439449907992, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137677.0275397} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.799981117248535, "x": 42.6485272225161, "y": 0.056572460322919405, "z": null, "yaw": 0.020729284365117923, "pitch": null, "roll": null}, "v": 2.1058601841911884, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3496394803631769, "steering_wheel_angle": 2.980698094151414, "front_wheel_angle": 0.14269396016075742, "heading_rate": 0.1181835096042839, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137677.0475397} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2198612879721031, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.048871859430062, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0989804890934565, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.1459677090123845, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137677.0475397} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.799981117248535, "x": 42.6485272225161, "y": 0.056572460322919405, "z": null, "yaw": 0.020729284365117923, "pitch": null, "roll": null}, "v": 2.1058601841911884, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3496394803631769, "steering_wheel_angle": 2.980698094151414, "front_wheel_angle": 0.14269396016075742, "heading_rate": 0.1181835096042839, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137677.0675397} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2198612879721031, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.048871859430062, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0944850936510795, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.228282871464592, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137677.0675397} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.799981117248535, "x": 42.6485272225161, "y": 0.056572460322919405, "z": null, "yaw": 0.020729284365117923, "pitch": null, "roll": null}, "v": 2.1058601841911884, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3496394803631769, "steering_wheel_angle": 2.980698094151414, "front_wheel_angle": 0.14269396016075742, "heading_rate": 0.1181835096042839, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137677.0975397} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2198612879721031, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.048871859430062, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.087757480416558, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.269360541446126, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137677.0975397} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137677.1175396, "x": 46.87907191624414, "y": 5.062025939499272, "z": null, "yaw": 0.02730792261202259, "pitch": null, "roll": null}, "v": 2.0832826910390723, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3475648022597836, "steering_wheel_angle": 3.269360541446126, "front_wheel_angle": 0.15719053502322783, "heading_rate": 0.12898297029680938, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137677.1175396} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24539310574387682, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.8891490808738376, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0832826910390723, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.269360541446126, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137677.1175396} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.90998101234436, "x": 42.87907191624414, "y": 0.062025939499272376, "z": null, "yaw": 0.02730792261202259, "pitch": null, "roll": null}, "v": 2.0832826910390723, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3475648022597836, "steering_wheel_angle": 3.269360541446126, "front_wheel_angle": 0.15719053502322783, "heading_rate": 0.12898297029680938, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137677.1275396} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23307702041606526, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.8891490808738376, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.082644112125467, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.269360541446126, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137677.1275396} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.90998101234436, "x": 42.87907191624414, "y": 0.062025939499272376, "z": null, "yaw": 0.02730792261202259, "pitch": null, "roll": null}, "v": 2.0832826910390723, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3475648022597836, "steering_wheel_angle": 3.269360541446126, "front_wheel_angle": 0.15719053502322783, "heading_rate": 0.12898297029680938, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137677.1475396} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23307702041606526, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.8891490808738376, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0798299043100883, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.269360541446126, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137677.1475396} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.90998101234436, "x": 42.87907191624414, "y": 0.062025939499272376, "z": null, "yaw": 0.02730792261202259, "pitch": null, "roll": null}, "v": 2.0832826910390723, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3475648022597836, "steering_wheel_angle": 3.269360541446126, "front_wheel_angle": 0.15719053502322783, "heading_rate": 0.12898297029680938, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137677.1675396} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23307702041606526, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.8891490808738376, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.077020850362465, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.269360541446126, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137677.1675396} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.90998101234436, "x": 42.87907191624414, "y": 0.062025939499272376, "z": null, "yaw": 0.02730792261202259, "pitch": null, "roll": null}, "v": 2.0832826910390723, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3475648022597836, "steering_wheel_angle": 3.269360541446126, "front_wheel_angle": 0.15719053502322783, "heading_rate": 0.12898297029680938, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137677.1875396} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23307702041606526, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.8891490808738376, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.074216937689065, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.269360541446126, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137677.1875396} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.90998101234436, "x": 42.87907191624414, "y": 0.062025939499272376, "z": null, "yaw": 0.02730792261202259, "pitch": null, "roll": null}, "v": 2.0832826910390723, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3475648022597836, "steering_wheel_angle": 3.269360541446126, "front_wheel_angle": 0.15719053502322783, "heading_rate": 0.12898297029680938, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137677.2075396} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23307702041606526, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.8891490808738376, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0714181537367327, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.269360541446126, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137677.2075396} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137677.2275395, "x": 47.107431216721594, "y": 5.06897008968802, "z": null, "yaw": 0.03411838899456257, "pitch": null, "roll": null}, "v": 2.068624485992524, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34622329694010456, "steering_wheel_angle": 3.269360541446126, "front_wheel_angle": 0.15719053502322783, "heading_rate": 0.1280754319995558, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137677.2275395} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21706069357718022, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.396707679441787, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.068624485992524, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.269360541446126, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137677.2275395} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.019980907440186, "x": 43.107431216721594, "y": 0.06897008968801988, "z": null, "yaw": 0.03411838899456257, "pitch": null, "roll": null}, "v": 2.068624485992524, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34622329694010456, "steering_wheel_angle": 3.269360541446126, "front_wheel_angle": 0.15719053502322783, "heading_rate": 0.1280754319995558, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137677.2475395} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2245853097111673, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.396707679441787, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0638347954065, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.352321255956857, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137677.2475395} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.019980907440186, "x": 43.107431216721594, "y": 0.06897008968801988, "z": null, "yaw": 0.03411838899456257, "pitch": null, "roll": null}, "v": 2.068624485992524, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34622329694010456, "steering_wheel_angle": 3.269360541446126, "front_wheel_angle": 0.15719053502322783, "heading_rate": 0.1280754319995558, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137677.2675395} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2245853097111673, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.396707679441787, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0599939948214296, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.435063820739461, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137677.2675395} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.019980907440186, "x": 43.107431216721594, "y": 0.06897008968801988, "z": null, "yaw": 0.03411838899456257, "pitch": null, "roll": null}, "v": 2.068624485992524, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34622329694010456, "steering_wheel_angle": 3.269360541446126, "front_wheel_angle": 0.15719053502322783, "heading_rate": 0.1280754319995558, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137677.2875395} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2245853097111673, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.396707679441787, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.056160198127347, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.5175882357939368, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137677.2875395} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.019980907440186, "x": 43.107431216721594, "y": 0.06897008968801988, "z": null, "yaw": 0.03411838899456257, "pitch": null, "roll": null}, "v": 2.068624485992524, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34622329694010456, "steering_wheel_angle": 3.269360541446126, "front_wheel_angle": 0.15719053502322783, "heading_rate": 0.1280754319995558, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137677.3075395} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2245853097111673, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.396707679441787, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0523333866757865, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.599894501120286, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137677.3075395} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.019980907440186, "x": 43.107431216721594, "y": 0.06897008968801988, "z": null, "yaw": 0.03411838899456257, "pitch": null, "roll": null}, "v": 2.068624485992524, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34622329694010456, "steering_wheel_angle": 3.269360541446126, "front_wheel_angle": 0.15719053502322783, "heading_rate": 0.1280754319995558, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137677.3275394} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2245853097111673, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.396707679441787, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.048513541884388, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.6409658276354127, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137677.3275394} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137677.3375394, "x": 47.33367643651347, "y": 5.077420615066451, "z": null, "yaw": 0.04138300298503857, "pitch": null, "roll": null}, "v": 2.046606226197265, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34421628176095737, "steering_wheel_angle": 3.6409658276354127, "front_wheel_angle": 0.17604867680900138, "heading_rate": 0.14221537120440134, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137677.3475394} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.034950925162837716, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.846632967066795, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0447006452366034, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.6409658276354127, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137677.3475394} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.12998080253601, "x": 43.33367643651347, "y": 0.07742061506645115, "z": null, "yaw": 0.04138300298503857, "pitch": null, "roll": null}, "v": 2.046606226197265, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34421628176095737, "steering_wheel_angle": 3.6409658276354127, "front_wheel_angle": 0.17604867680900138, "heading_rate": 0.14221537120440134, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137677.3675394} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.846632967066795, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.03223330113931, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.034950925162837716, "steering_wheel_angle": 3.7273177457000783, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137677.3675394} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.12998080253601, "x": 43.33367643651347, "y": 0.07742061506645115, "z": null, "yaw": 0.04138300298503857, "pitch": null, "roll": null}, "v": 2.046606226197265, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34421628176095737, "steering_wheel_angle": 3.6409658276354127, "front_wheel_angle": 0.17604867680900138, "heading_rate": 0.14221537120440134, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137677.3875394} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.846632967066795, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0219552757653667, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.856391727173664, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137677.3875394} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.12998080253601, "x": 43.33367643651347, "y": 0.07742061506645115, "z": null, "yaw": 0.04138300298503857, "pitch": null, "roll": null}, "v": 2.046606226197265, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34421628176095737, "steering_wheel_angle": 3.6409658276354127, "front_wheel_angle": 0.17604867680900138, "heading_rate": 0.14221537120440134, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137677.4075394} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.846632967066795, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0185354678137646, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.89929534883195, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137677.4075394} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.12998080253601, "x": 43.33367643651347, "y": 0.07742061506645115, "z": null, "yaw": 0.04138300298503857, "pitch": null, "roll": null}, "v": 2.046606226197265, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34421628176095737, "steering_wheel_angle": 3.6409658276354127, "front_wheel_angle": 0.17604867680900138, "heading_rate": 0.14221537120440134, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137677.4275393} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.846632967066795, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.011705121802328, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.9849210338991554, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137677.4275393} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137677.4475393, "x": 47.5563687350976, "y": 5.087435308169203, "z": null, "yaw": 0.04942802917577054, "pitch": null, "roll": null}, "v": 2.0048871014955805, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34044007797221254, "steering_wheel_angle": 4.070304641300542, "front_wheel_angle": 0.19812142509804856, "heading_rate": 0.15722309738403548, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137677.4475393} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22852679886158894, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.586492641926419, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0048871014955805, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.070304641300542, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137677.4475393} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.239980697631836, "x": 43.5563687350976, "y": 0.0874353081692032, "z": null, "yaw": 0.04942802917577054, "pitch": null, "roll": null}, "v": 2.0048871014955805, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34044007797221254, "steering_wheel_angle": 4.070304641300542, "front_wheel_angle": 0.19812142509804856, "heading_rate": 0.15722309738403548, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137677.4675393} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.586492641926419, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0016456104440454, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.154621730428444, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137677.4675393} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.239980697631836, "x": 43.5563687350976, "y": 0.0874353081692032, "z": null, "yaw": 0.04942802917577054, "pitch": null, "roll": null}, "v": 2.0048871014955805, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34044007797221254, "steering_wheel_angle": 4.070304641300542, "front_wheel_angle": 0.19812142509804856, "heading_rate": 0.15722309738403548, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137677.4875393} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.586492641926419, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9948457090993228, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.238701413900153, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137677.4875393} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.239980697631836, "x": 43.5563687350976, "y": 0.0874353081692032, "z": null, "yaw": 0.04942802917577054, "pitch": null, "roll": null}, "v": 2.0048871014955805, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34044007797221254, "steering_wheel_angle": 4.070304641300542, "front_wheel_angle": 0.19812142509804856, "heading_rate": 0.15722309738403548, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137677.5075393} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.586492641926419, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9880580326840283, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.32254369171567, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137677.5075393} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.239980697631836, "x": 43.5563687350976, "y": 0.0874353081692032, "z": null, "yaw": 0.04942802917577054, "pitch": null, "roll": null}, "v": 2.0048871014955805, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34044007797221254, "steering_wheel_angle": 4.070304641300542, "front_wheel_angle": 0.19812142509804856, "heading_rate": 0.15722309738403548, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137677.5275393} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.586492641926419, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.981282540799307, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.4061485638749955, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137677.5275393} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.239980697631836, "x": 43.5563687350976, "y": 0.0874353081692032, "z": null, "yaw": 0.04942802917577054, "pitch": null, "roll": null}, "v": 2.0048871014955805, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34044007797221254, "steering_wheel_angle": 4.070304641300542, "front_wheel_angle": 0.19812142509804856, "heading_rate": 0.15722309738403548, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137677.5475392} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.586492641926419, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.974519193218063, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.489516030378131, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137677.5475392} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137677.5575392, "x": 47.77506266155175, "y": 5.09913990695152, "z": null, "yaw": 0.05854431771771553, "pitch": null, "roll": null}, "v": 1.9711420610170154, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.33741111329795487, "steering_wheel_angle": 4.531110736508625, "front_wheel_angle": 0.22216600896520836, "heading_rate": 0.17393392106770908, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137677.5675392} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2458154756118563, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.295449470195221, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9672603220643758, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.572646091225072, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137677.5675392} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.34998059272766, "x": 43.77506266155175, "y": 0.0991399069515202, "z": null, "yaw": 0.05854431771771553, "pitch": null, "roll": null}, "v": 1.9711420610170154, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.33741111329795487, "steering_wheel_angle": 4.531110736508625, "front_wheel_angle": 0.22216600896520836, "heading_rate": 0.17393392106770908, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137677.5875392} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22805257850567112, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.295449470195221, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9667531478116078, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.572646091225072, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137677.5875392} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.34998059272766, "x": 43.77506266155175, "y": 0.0991399069515202, "z": null, "yaw": 0.05854431771771553, "pitch": null, "roll": null}, "v": 1.9711420610170154, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.33741111329795487, "steering_wheel_angle": 4.531110736508625, "front_wheel_angle": 0.22216600896520836, "heading_rate": 0.17393392106770908, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137677.6075392} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22805257850567112, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.295449470195221, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9635207875872913, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.572646091225072, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137677.6075392} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.34998059272766, "x": 43.77506266155175, "y": 0.0991399069515202, "z": null, "yaw": 0.05854431771771553, "pitch": null, "roll": null}, "v": 1.9711420610170154, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.33741111329795487, "steering_wheel_angle": 4.531110736508625, "front_wheel_angle": 0.22216600896520836, "heading_rate": 0.17393392106770908, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137677.6275392} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22805257850567112, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.295449470195221, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.96029419691421, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.572646091225072, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137677.6275392} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.34998059272766, "x": 43.77506266155175, "y": 0.0991399069515202, "z": null, "yaw": 0.05854431771771553, "pitch": null, "roll": null}, "v": 1.9711420610170154, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.33741111329795487, "steering_wheel_angle": 4.531110736508625, "front_wheel_angle": 0.22216600896520836, "heading_rate": 0.17393392106770908, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137677.6475391} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22805257850567112, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.295449470195221, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9570733613315936, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.572646091225072, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137677.6475391} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137677.6675391, "x": 47.99058361092546, "y": 5.112732761098784, "z": null, "yaw": 0.06834052417557988, "pitch": null, "roll": null}, "v": 1.9538582664267425, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3358685345741783, "steering_wheel_angle": 4.572646091225072, "front_wheel_angle": 0.22435188022585922, "heading_rate": 0.1741631100729463, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137677.6675391} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21710518249252617, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.7777880476768475, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9538582664267425, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.572646091225072, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137677.6675391} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.459980487823486, "x": 43.99058361092546, "y": 0.11273276109878427, "z": null, "yaw": 0.06834052417557988, "pitch": null, "roll": null}, "v": 1.9538582664267425, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3358685345741783, "steering_wheel_angle": 4.572646091225072, "front_wheel_angle": 0.22435188022585922, "heading_rate": 0.1741631100729463, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137677.687539} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22220070095097966, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.7777880476768475, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9492810825435605, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.656132434173949, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137677.687539} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.459980487823486, "x": 43.99058361092546, "y": 0.11273276109878427, "z": null, "yaw": 0.06834052417557988, "pitch": null, "roll": null}, "v": 1.9538582664267425, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3358685345741783, "steering_wheel_angle": 4.572646091225072, "front_wheel_angle": 0.22435188022585922, "heading_rate": 0.1741631100729463, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137677.707539} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22220070095097966, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.7777880476768475, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9453486997514713, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.739377953682559, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137677.707539} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.459980487823486, "x": 43.99058361092546, "y": 0.11273276109878427, "z": null, "yaw": 0.06834052417557988, "pitch": null, "roll": null}, "v": 1.9538582664267425, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3358685345741783, "steering_wheel_angle": 4.572646091225072, "front_wheel_angle": 0.22435188022585922, "heading_rate": 0.1741631100729463, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137677.727539} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22220070095097966, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.7777880476768475, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9414233077218177, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.8223826497508995, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137677.727539} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.459980487823486, "x": 43.99058361092546, "y": 0.11273276109878427, "z": null, "yaw": 0.06834052417557988, "pitch": null, "roll": null}, "v": 1.9538582664267425, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3358685345741783, "steering_wheel_angle": 4.572646091225072, "front_wheel_angle": 0.22435188022585922, "heading_rate": 0.1741631100729463, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137677.747539} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22220070095097966, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.7777880476768475, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9375048878660812, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.905146522378972, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137677.747539} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.459980487823486, "x": 43.99058361092546, "y": 0.11273276109878427, "z": null, "yaw": 0.06834052417557988, "pitch": null, "roll": null}, "v": 1.9538582664267425, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3358685345741783, "steering_wheel_angle": 4.572646091225072, "front_wheel_angle": 0.22435188022585922, "heading_rate": 0.1741631100729463, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137677.767539} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22220070095097966, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.7777880476768475, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9335934216615944, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.987669571566775, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137677.767539} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137677.777539, "x": 48.203797388793866, "y": 5.128308757899076, "z": null, "yaw": 0.07864512955614293, "pitch": null, "roll": null}, "v": 1.9316402904081706, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.33389435663569017, "steering_wheel_angle": 5.028840787370575, "front_wheel_angle": 0.24856892320019233, "heading_rate": 0.1915176789836527, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137677.787539} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2371594146374994, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.811320990024539, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.92968889065125, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.069951797314309, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137677.787539} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.56998038291931, "x": 44.203797388793866, "y": 0.1283087578990756, "z": null, "yaw": 0.07864512955614293, "pitch": null, "roll": null}, "v": 1.9316402904081706, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.33389435663569017, "steering_wheel_angle": 5.028840787370575, "front_wheel_angle": 0.24856892320019233, "heading_rate": 0.1915176789836527, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137677.807539} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22988580045321236, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.811320990024539, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9276602876505773, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.111054459463159, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137677.807539} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.56998038291931, "x": 44.203797388793866, "y": 0.1283087578990756, "z": null, "yaw": 0.07864512955614293, "pitch": null, "roll": null}, "v": 1.9316402904081706, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.33389435663569017, "steering_wheel_angle": 5.028840787370575, "front_wheel_angle": 0.24856892320019233, "heading_rate": 0.1915176789836527, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137677.827539} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22988580045321236, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.811320990024539, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9247264769343182, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.111054459463159, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137677.827539} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.56998038291931, "x": 44.203797388793866, "y": 0.1283087578990756, "z": null, "yaw": 0.07864512955614293, "pitch": null, "roll": null}, "v": 1.9316402904081706, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.33389435663569017, "steering_wheel_angle": 5.028840787370575, "front_wheel_angle": 0.24856892320019233, "heading_rate": 0.1915176789836527, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137677.847539} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22988580045321236, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.811320990024539, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9217978573048342, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.111054459463159, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137677.847539} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.56998038291931, "x": 44.203797388793866, "y": 0.1283087578990756, "z": null, "yaw": 0.07864512955614293, "pitch": null, "roll": null}, "v": 1.9316402904081706, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.33389435663569017, "steering_wheel_angle": 5.028840787370575, "front_wheel_angle": 0.24856892320019233, "heading_rate": 0.1915176789836527, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137677.867539} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22988580045321236, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.811320990024539, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9188744161478035, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.111054459463159, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137677.867539} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137677.887539, "x": 48.414758515309224, "y": 5.145999628382496, "z": null, "yaw": 0.08972559356835688, "pitch": null, "roll": null}, "v": 1.9159561408894026, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3325066863825883, "steering_wheel_angle": 5.111054459463159, "front_wheel_angle": 0.25297480510770237, "heading_rate": 0.19347646952619715, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137677.887539} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.026140701980069472, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.324778150738802, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9159561408894026, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.111054459463159, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137677.887539} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.679980278015137, "x": 44.414758515309224, "y": 0.14599962838249603, "z": null, "yaw": 0.08972559356835688, "pitch": null, "roll": null}, "v": 1.9159561408894026, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3325066863825883, "steering_wheel_angle": 5.111054459463159, "front_wheel_angle": 0.25297480510770237, "heading_rate": 0.19347646952619715, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137677.907539} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.324778150738802, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9051282755602663, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.026140701980069472, "steering_wheel_angle": 5.198197214495666, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137677.907539} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.679980278015137, "x": 44.414758515309224, "y": 0.14599962838249603, "z": null, "yaw": 0.08972559356835688, "pitch": null, "roll": null}, "v": 1.9159561408894026, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3325066863825883, "steering_wheel_angle": 5.111054459463159, "front_wheel_angle": 0.25297480510770237, "heading_rate": 0.19347646952619715, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137677.9275389} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.324778150738802, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8985001644904003, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.285067414583975, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137677.9275389} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.679980278015137, "x": 44.414758515309224, "y": 0.14599962838249603, "z": null, "yaw": 0.08972559356835688, "pitch": null, "roll": null}, "v": 1.9159561408894026, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3325066863825883, "steering_wheel_angle": 5.111054459463159, "front_wheel_angle": 0.25297480510770237, "heading_rate": 0.19347646952619715, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137677.9475389} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.324778150738802, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8918837141815277, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.371665059728086, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137677.9475389} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.679980278015137, "x": 44.414758515309224, "y": 0.14599962838249603, "z": null, "yaw": 0.08972559356835688, "pitch": null, "roll": null}, "v": 1.9159561408894026, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3325066863825883, "steering_wheel_angle": 5.111054459463159, "front_wheel_angle": 0.25297480510770237, "heading_rate": 0.19347646952619715, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137677.9675388} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.324778150738802, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.885278886615721, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.457990149928002, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137677.9675388} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.679980278015137, "x": 44.414758515309224, "y": 0.14599962838249603, "z": null, "yaw": 0.08972559356835688, "pitch": null, "roll": null}, "v": 1.9159561408894026, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3325066863825883, "steering_wheel_angle": 5.111054459463159, "front_wheel_angle": 0.25297480510770237, "heading_rate": 0.19347646952619715, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137677.9875388} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.324778150738802, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8786856439341133, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.544042685183723, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137677.9875388} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137677.9975388, "x": 48.62235436313886, "y": 5.165760181982512, "z": null, "yaw": 0.10137273266786412, "pitch": null, "roll": null}, "v": 1.875393355137274, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3289406701217941, "steering_wheel_angle": 5.586966744707508, "front_wheel_angle": 0.2787379435139352, "heading_rate": 0.20965462444961117, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137678.0075388} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24114739893682322, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.924228390996427, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8713891315760145, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.671899286146307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137678.0075388} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.789980173110962, "x": 44.62235436313886, "y": 0.1657601819825123, "z": null, "yaw": 0.10137273266786412, "pitch": null, "roll": null}, "v": 1.875393355137274, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3289406701217941, "steering_wheel_angle": 5.586966744707508, "front_wheel_angle": 0.2787379435139352, "heading_rate": 0.20965462444961117, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137678.0275388} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2196621222463857, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.924228390996427, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8706749397156, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.713910016005856, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137678.0275388} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.789980173110962, "x": 44.62235436313886, "y": 0.1657601819825123, "z": null, "yaw": 0.10137273266786412, "pitch": null, "roll": null}, "v": 1.875393355137274, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3289406701217941, "steering_wheel_angle": 5.586966744707508, "front_wheel_angle": 0.2787379435139352, "heading_rate": 0.20965462444961117, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137678.0475388} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2196621222463857, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.924228390996427, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8665639422566207, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.797733803350402, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137678.0475388} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.789980173110962, "x": 44.62235436313886, "y": 0.1657601819825123, "z": null, "yaw": 0.10137273266786412, "pitch": null, "roll": null}, "v": 1.875393355137274, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3289406701217941, "steering_wheel_angle": 5.586966744707508, "front_wheel_angle": 0.2787379435139352, "heading_rate": 0.20965462444961117, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137678.0675387} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2196621222463857, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.924228390996427, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8624601237248852, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.881294027528885, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137678.0675387} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.789980173110962, "x": 44.62235436313886, "y": 0.1657601819825123, "z": null, "yaw": 0.10137273266786412, "pitch": null, "roll": null}, "v": 1.875393355137274, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3289406701217941, "steering_wheel_angle": 5.586966744707508, "front_wheel_angle": 0.2787379435139352, "heading_rate": 0.20965462444961117, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137678.0875387} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2196621222463857, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.924228390996427, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8583634648504266, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.964590688541306, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137678.0875387} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137678.1075387, "x": 48.82644497314867, "y": 5.187701827021449, "z": null, "yaw": 0.11420942899017357, "pitch": null, "roll": null}, "v": 1.8542739464321478, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3270970160057779, "steering_wheel_angle": 6.047623786387665, "front_wheel_angle": 0.3041115037016963, "heading_rate": 0.22732742410942938, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137678.1075387} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2520780588839995, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.590996970431567, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8542739464321478, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.047623786387665, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137678.1075387} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.899980068206787, "x": 44.82644497314867, "y": 0.18770182702144922, "z": null, "yaw": 0.11420942899017357, "pitch": null, "roll": null}, "v": 1.8542739464321478, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3270970160057779, "steering_wheel_angle": 6.047623786387665, "front_wheel_angle": 0.3041115037016963, "heading_rate": 0.22732742410942938, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137678.1275387} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23650142191413337, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.590996970431567, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8542417774858486, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.047623786387665, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137678.1275387} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.899980068206787, "x": 44.82644497314867, "y": 0.18770182702144922, "z": null, "yaw": 0.11420942899017357, "pitch": null, "roll": null}, "v": 1.8542739464321478, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3270970160057779, "steering_wheel_angle": 6.047623786387665, "front_wheel_angle": 0.3041115037016963, "heading_rate": 0.22732742410942938, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137678.1475387} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23650142191413337, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.590996970431567, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8522634326302088, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.047623786387665, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137678.1475387} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.899980068206787, "x": 44.82644497314867, "y": 0.18770182702144922, "z": null, "yaw": 0.11420942899017357, "pitch": null, "roll": null}, "v": 1.8542739464321478, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3270970160057779, "steering_wheel_angle": 6.047623786387665, "front_wheel_angle": 0.3041115037016963, "heading_rate": 0.22732742410942938, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137678.1675386} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23650142191413337, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.590996970431567, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8483170643778026, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.047623786387665, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137678.1675386} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.899980068206787, "x": 44.82644497314867, "y": 0.18770182702144922, "z": null, "yaw": 0.11420942899017357, "pitch": null, "roll": null}, "v": 1.8542739464321478, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3270970160057779, "steering_wheel_angle": 6.047623786387665, "front_wheel_angle": 0.3041115037016963, "heading_rate": 0.22732742410942938, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137678.1875386} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23650142191413337, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.590996970431567, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8483170643778026, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.047623786387665, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137678.1875386} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.899980068206787, "x": 44.82644497314867, "y": 0.18770182702144922, "z": null, "yaw": 0.11420942899017357, "pitch": null, "roll": null}, "v": 1.8542739464321478, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3270970160057779, "steering_wheel_angle": 6.047623786387665, "front_wheel_angle": 0.3041115037016963, "heading_rate": 0.22732742410942938, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137678.2075386} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23650142191413337, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.590996970431567, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.843403379115312, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.047623786387665, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137678.2075386} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137678.2175386, "x": 49.028582611986245, "y": 5.212143852215622, "z": null, "yaw": 0.12769503973293997, "pitch": null, "roll": null}, "v": 1.8453662897835872, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3263220819238758, "steering_wheel_angle": 6.047623786387665, "front_wheel_angle": 0.3041115037016963, "heading_rate": 0.22623537692585938, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137678.2375386} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.07245679462829706, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.457045188134867, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8424232026935743, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.047623786387665, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137678.2375386} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.009979963302612, "x": 45.028582611986245, "y": 0.21214385221562182, "z": null, "yaw": 0.12769503973293997, "pitch": null, "roll": null}, "v": 1.8453662897835872, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3263220819238758, "steering_wheel_angle": 6.047623786387665, "front_wheel_angle": 0.3041115037016963, "heading_rate": 0.22623537692585938, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137678.2575386} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.02442026408981994, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.457045188134867, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8243166455410853, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.07245679462829706, "steering_wheel_angle": 6.140646694248491, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137678.2575386} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.009979963302612, "x": 45.028582611986245, "y": 0.21214385221562182, "z": null, "yaw": 0.12769503973293997, "pitch": null, "roll": null}, "v": 1.8453662897835872, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3263220819238758, "steering_wheel_angle": 6.047623786387665, "front_wheel_angle": 0.3041115037016963, "heading_rate": 0.22623537692585938, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137678.2775385} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.02442026408981994, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.457045188134867, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8191180529688094, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.02442026408981994, "steering_wheel_angle": 6.187033258537763, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137678.2775385} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.009979963302612, "x": 45.028582611986245, "y": 0.21214385221562182, "z": null, "yaw": 0.12769503973293997, "pitch": null, "roll": null}, "v": 1.8453662897835872, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3263220819238758, "steering_wheel_angle": 6.047623786387665, "front_wheel_angle": 0.3041115037016963, "heading_rate": 0.22623537692585938, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137678.2975385} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.02442026408981994, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.457045188134867, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8087343386510024, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.02442026408981994, "steering_wheel_angle": 6.279556607834024, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137678.2975385} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.009979963302612, "x": 45.028582611986245, "y": 0.21214385221562182, "z": null, "yaw": 0.12769503973293997, "pitch": null, "roll": null}, "v": 1.8453662897835872, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3263220819238758, "steering_wheel_angle": 6.047623786387665, "front_wheel_angle": 0.3041115037016963, "heading_rate": 0.22623537692585938, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137678.3175385} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.02442026408981994, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.457045188134867, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7983685236662506, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.02442026408981994, "steering_wheel_angle": 6.371746918087242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137678.3175385} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137678.3275385, "x": 49.22755492263093, "y": 5.238935666037308, "z": null, "yaw": 0.14149300004055962, "pitch": null, "roll": null}, "v": 1.7931923053425405, "accelerator_pedal_position": 0, "brake_pedal_position": 0.02442026408981994, "acceleration": -0.5171771144250835, "steering_wheel_angle": 6.417717183572709, "front_wheel_angle": 0.3248232449193218, "heading_rate": 0.2358825013882092, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137678.3375385} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21635547510522365, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.107072621874812, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7880205341982895, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.02442026408981994, "steering_wheel_angle": 6.463604189297415, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137678.3375385} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.119979858398438, "x": 45.22755492263093, "y": 0.23893566603730765, "z": null, "yaw": 0.14149300004055962, "pitch": null, "roll": null}, "v": 1.7931923053425405, "accelerator_pedal_position": 0, "brake_pedal_position": 0.02442026408981994, "acceleration": -0.5171771144250835, "steering_wheel_angle": 6.417717183572709, "front_wheel_angle": 0.3248232449193218, "heading_rate": 0.2358825013882092, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137678.3575385} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.107072621874812, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7836394235207906, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.553508706374488, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137678.3575385} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.119979858398438, "x": 45.22755492263093, "y": 0.23893566603730765, "z": null, "yaw": 0.14149300004055962, "pitch": null, "roll": null}, "v": 1.7931923053425405, "accelerator_pedal_position": 0, "brake_pedal_position": 0.02442026408981994, "acceleration": -0.5171771144250835, "steering_wheel_angle": 6.417717183572709, "front_wheel_angle": 0.3248232449193218, "heading_rate": 0.2358825013882092, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137678.3775384} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.107072621874812, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.777222259207649, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.643091888497039, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137678.3775384} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.119979858398438, "x": 45.22755492263093, "y": 0.23893566603730765, "z": null, "yaw": 0.14149300004055962, "pitch": null, "roll": null}, "v": 1.7931923053425405, "accelerator_pedal_position": 0, "brake_pedal_position": 0.02442026408981994, "acceleration": -0.5171771144250835, "steering_wheel_angle": 6.417717183572709, "front_wheel_angle": 0.3248232449193218, "heading_rate": 0.2358825013882092, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137678.3975384} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.107072621874812, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7708160733699747, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.732353735665072, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137678.3975384} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.119979858398438, "x": 45.22755492263093, "y": 0.23893566603730765, "z": null, "yaw": 0.14149300004055962, "pitch": null, "roll": null}, "v": 1.7931923053425405, "accelerator_pedal_position": 0, "brake_pedal_position": 0.02442026408981994, "acceleration": -0.5171771144250835, "steering_wheel_angle": 6.417717183572709, "front_wheel_angle": 0.3248232449193218, "heading_rate": 0.2358825013882092, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137678.4175384} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.107072621874812, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7580364965026956, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.909913425137573, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137678.4175384} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137678.4375384, "x": 49.42087445393377, "y": 5.267799955021461, "z": null, "yaw": 0.15657684805527367, "pitch": null, "roll": null}, "v": 1.7580364965026956, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.31880874805548953, "steering_wheel_angle": 6.909913425137573, "front_wheel_angle": 0.35284289615809367, "heading_rate": 0.25289186781355355, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137678.4375384} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.443585704315645, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7548484090221406, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.954102513159124, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137678.4375384} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.229979753494263, "x": 45.42087445393377, "y": 0.26779995502146114, "z": null, "yaw": 0.15657684805527367, "pitch": null, "roll": null}, "v": 1.7580364965026956, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.31880874805548953, "steering_wheel_angle": 6.909913425137573, "front_wheel_angle": 0.35284289615809367, "heading_rate": 0.25289186781355355, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137678.4675384} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.443585704315645, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7453004131201568, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.088471294457887, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137678.4675384} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.443585704315645, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7453004131201568, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.088471294457887, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137678.4775383} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.229979753494263, "x": 45.42087445393377, "y": 0.26779995502146114, "z": null, "yaw": 0.15657684805527367, "pitch": null, "roll": null}, "v": 1.7580364965026956, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.31880874805548953, "steering_wheel_angle": 6.909913425137573, "front_wheel_angle": 0.35284289615809367, "heading_rate": 0.25289186781355355, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137678.5075383} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.443585704315645, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7357767261548702, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.222091786108905, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137678.5075383} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.229979753494263, "x": 45.42087445393377, "y": 0.26779995502146114, "z": null, "yaw": 0.15657684805527367, "pitch": null, "roll": null}, "v": 1.7580364965026956, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.31880874805548953, "steering_wheel_angle": 6.909913425137573, "front_wheel_angle": 0.35284289615809367, "heading_rate": 0.25289186781355355, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137678.5275383} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.443585704315645, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7294410490438887, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.310756397405279, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137678.5275383} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137678.5475383, "x": 49.609938728229956, "y": 5.299070859585872, "z": null, "yaw": 0.1730337974156024, "pitch": null, "roll": null}, "v": 1.7231160899610798, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3158470950928816, "steering_wheel_angle": 7.399088435524877, "front_wheel_angle": 0.38125752702475585, "heading_rate": 0.2698235535062546, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137678.5475383} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.554213875564297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7231160899610798, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.399088435524877, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137678.5475383} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.339979648590088, "x": 45.609938728229956, "y": 0.2990708595858722, "z": null, "yaw": 0.1730337974156024, "pitch": null, "roll": null}, "v": 1.7231160899610798, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3158470950928816, "steering_wheel_angle": 7.399088435524877, "front_wheel_angle": 0.38125752702475585, "heading_rate": 0.2698235535062546, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137678.5675383} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.554213875564297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7168018147795268, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.487597222120505, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137678.5675383} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.339979648590088, "x": 45.609938728229956, "y": 0.2990708595858722, "z": null, "yaw": 0.1730337974156024, "pitch": null, "roll": null}, "v": 1.7231160899610798, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3158470950928816, "steering_wheel_angle": 7.399088435524877, "front_wheel_angle": 0.38125752702475585, "heading_rate": 0.2698235535062546, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137678.5875382} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.554213875564297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7104981895110454, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.575769567303953, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137678.5875382} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.339979648590088, "x": 45.609938728229956, "y": 0.2990708595858722, "z": null, "yaw": 0.1730337974156024, "pitch": null, "roll": null}, "v": 1.7231160899610798, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3158470950928816, "steering_wheel_angle": 7.399088435524877, "front_wheel_angle": 0.38125752702475585, "heading_rate": 0.2698235535062546, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137678.6075382} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.554213875564297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7010626461856588, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.7073972574312855, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137678.6075382} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.339979648590088, "x": 45.609938728229956, "y": 0.2990708595858722, "z": null, "yaw": 0.1730337974156024, "pitch": null, "roll": null}, "v": 1.7231160899610798, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3158470950928816, "steering_wheel_angle": 7.399088435524877, "front_wheel_angle": 0.38125752702475585, "heading_rate": 0.2698235535062546, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137678.6275382} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.554213875564297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6979227534499413, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.751104933434305, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137678.6275382} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.339979648590088, "x": 45.609938728229956, "y": 0.2990708595858722, "z": null, "yaw": 0.1730337974156024, "pitch": null, "roll": null}, "v": 1.7231160899610798, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3158470950928816, "steering_wheel_angle": 7.399088435524877, "front_wheel_angle": 0.38125752702475585, "heading_rate": 0.2698235535062546, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137678.6475382} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.554213875564297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.691650875368204, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.838267954381208, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137678.6475382} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137678.6575382, "x": 49.79467788610662, "y": 5.332880823089819, "z": null, "yaw": 0.1909125051420368, "pitch": null, "roll": null}, "v": 1.6885188816621066, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3129369042203999, "steering_wheel_angle": 7.881723299325091, "front_wheel_angle": 0.40988127226985677, "heading_rate": 0.2865799466444195, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137678.6675382} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2501530040973103, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.027026387822861, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6853895126199026, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.92509453391593, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137678.6675382} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.449979543685913, "x": 45.79467788610662, "y": 0.3328808230898188, "z": null, "yaw": 0.1909125051420368, "pitch": null, "roll": null}, "v": 1.6885188816621066, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3129369042203999, "steering_wheel_angle": 7.881723299325091, "front_wheel_angle": 0.40988127226985677, "heading_rate": 0.2865799466444195, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137678.6875381} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2283074060282395, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.027026387822861, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6854051345164807, "gear": 1, "accelerator_pedal_position": 0.2501530040973103, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.009287318493154, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137678.6875381} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.449979543685913, "x": 45.79467788610662, "y": 0.3328808230898188, "z": null, "yaw": 0.1909125051420368, "pitch": null, "roll": null}, "v": 1.6885188816621066, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3129369042203999, "steering_wheel_angle": 7.881723299325091, "front_wheel_angle": 0.40988127226985677, "heading_rate": 0.2865799466444195, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137678.7075381} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2283074060282395, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.027026387822861, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6826911732360004, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.093161330418274, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137678.7075381} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.449979543685913, "x": 45.79467788610662, "y": 0.3328808230898188, "z": null, "yaw": 0.1909125051420368, "pitch": null, "roll": null}, "v": 1.6885188816621066, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3129369042203999, "steering_wheel_angle": 7.881723299325091, "front_wheel_angle": 0.40988127226985677, "heading_rate": 0.2865799466444195, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137678.727538} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2283074060282395, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.027026387822861, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6799817514573074, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.176716569691292, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137678.727538} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.449979543685913, "x": 45.79467788610662, "y": 0.3328808230898188, "z": null, "yaw": 0.1909125051420368, "pitch": null, "roll": null}, "v": 1.6885188816621066, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3129369042203999, "steering_wheel_angle": 7.881723299325091, "front_wheel_angle": 0.40988127226985677, "heading_rate": 0.2865799466444195, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137678.747538} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2283074060282395, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.027026387822861, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.677276858652253, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.259953036312211, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137678.747538} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137678.767538, "x": 49.976048465912804, "y": 5.369564355755975, "z": null, "yaw": 0.2102372711394895, "pitch": null, "roll": null}, "v": 1.6745764843250088, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3117708882347935, "steering_wheel_angle": 8.342870730281026, "front_wheel_angle": 0.43781252033874196, "heading_rate": 0.3062061038102929, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137678.767538} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2608578504243556, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.578101979117445, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6745764843250088, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.342870730281026, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137678.767538} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.55997943878174, "x": 45.976048465912804, "y": 0.36956435575597535, "z": null, "yaw": 0.2102372711394895, "pitch": null, "roll": null}, "v": 1.6745764843250088, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3117708882347935, "steering_wheel_angle": 8.342870730281026, "front_wheel_angle": 0.43781252033874196, "heading_rate": 0.3062061038102929, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137678.787538} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2452687917065525, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.578101979117445, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6759477251422568, "gear": 1, "accelerator_pedal_position": 0.2608578504243556, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.342870730281026, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137678.787538} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.55997943878174, "x": 45.976048465912804, "y": 0.36956435575597535, "z": null, "yaw": 0.2102372711394895, "pitch": null, "roll": null}, "v": 1.6745764843250088, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3117708882347935, "steering_wheel_angle": 8.342870730281026, "front_wheel_angle": 0.43781252033874196, "heading_rate": 0.3062061038102929, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137678.807538} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2452687917065525, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.578101979117445, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6753688580494241, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.342870730281026, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137678.807538} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.55997943878174, "x": 45.976048465912804, "y": 0.36956435575597535, "z": null, "yaw": 0.2102372711394895, "pitch": null, "roll": null}, "v": 1.6745764843250088, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3117708882347935, "steering_wheel_angle": 8.342870730281026, "front_wheel_angle": 0.43781252033874196, "heading_rate": 0.3062061038102929, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137678.827538} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2452687917065525, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.578101979117445, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6747909573798672, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.342870730281026, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137678.827538} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.55997943878174, "x": 45.976048465912804, "y": 0.36956435575597535, "z": null, "yaw": 0.2102372711394895, "pitch": null, "roll": null}, "v": 1.6745764843250088, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3117708882347935, "steering_wheel_angle": 8.342870730281026, "front_wheel_angle": 0.43781252033874196, "heading_rate": 0.3062061038102929, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137678.847538} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2452687917065525, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.578101979117445, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6742140213866026, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.342870730281026, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137678.847538} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.55997943878174, "x": 45.976048465912804, "y": 0.36956435575597535, "z": null, "yaw": 0.2102372711394895, "pitch": null, "roll": null}, "v": 1.6745764843250088, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3117708882347935, "steering_wheel_angle": 8.342870730281026, "front_wheel_angle": 0.43781252033874196, "heading_rate": 0.3062061038102929, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137678.867538} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2452687917065525, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.578101979117445, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6733504223520477, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.342870730281026, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137678.867538} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137678.877538, "x": 50.15585966494635, "y": 5.409656262924431, "z": null, "yaw": 0.23035141446732255, "pitch": null, "roll": null}, "v": 1.6733504223520477, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.31166853747746015, "steering_wheel_angle": 8.342870730281026, "front_wheel_angle": 0.43781252033874196, "heading_rate": 0.3059819112079934, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137678.887538} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2694753652314753, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.18679511797799, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.672775890429966, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.342870730281026, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137678.887538} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.669979333877563, "x": 46.15585966494635, "y": 0.4096562629244307, "z": null, "yaw": 0.23035141446732255, "pitch": null, "roll": null}, "v": 1.6733504223520477, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.31166853747746015, "steering_wheel_angle": 8.342870730281026, "front_wheel_angle": 0.43781252033874196, "heading_rate": 0.3059819112079934, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137678.907538} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2579406215426544, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.18679511797799, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.674001894893758, "gear": 1, "accelerator_pedal_position": 0.2694753652314753, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.342870730281026, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137678.907538} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.669979333877563, "x": 46.15585966494635, "y": 0.4096562629244307, "z": null, "yaw": 0.23035141446732255, "pitch": null, "roll": null}, "v": 1.6733504223520477, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.31166853747746015, "steering_wheel_angle": 8.342870730281026, "front_wheel_angle": 0.43781252033874196, "heading_rate": 0.3059819112079934, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137678.927538} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2579406215426544, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.18679511797799, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6750095934082678, "gear": 1, "accelerator_pedal_position": 0.2579406215426544, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.342870730281026, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137678.927538} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.669979333877563, "x": 46.15585966494635, "y": 0.4096562629244307, "z": null, "yaw": 0.23035141446732255, "pitch": null, "roll": null}, "v": 1.6733504223520477, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.31166853747746015, "steering_wheel_angle": 8.342870730281026, "front_wheel_angle": 0.43781252033874196, "heading_rate": 0.3059819112079934, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137678.947538} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2579406215426544, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.18679511797799, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6760156098664907, "gear": 1, "accelerator_pedal_position": 0.2579406215426544, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.342870730281026, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137678.947538} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.669979333877563, "x": 46.15585966494635, "y": 0.4096562629244307, "z": null, "yaw": 0.23035141446732255, "pitch": null, "roll": null}, "v": 1.6733504223520477, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.31166853747746015, "steering_wheel_angle": 8.342870730281026, "front_wheel_angle": 0.43781252033874196, "heading_rate": 0.3059819112079934, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137678.9675379} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2579406215426544, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.18679511797799, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6770199466714657, "gear": 1, "accelerator_pedal_position": 0.2579406215426544, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.342870730281026, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137678.9675379} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137678.9875379, "x": 50.33485045594347, "y": 5.4533633535674015, "z": null, "yaw": 0.2504655577951556, "pitch": null, "roll": null}, "v": 1.6780226062242474, "accelerator_pedal_position": 0.2579406215426544, "brake_pedal_position": 0.0, "acceleration": 0.050070155660381366, "steering_wheel_angle": 8.342870730281026, "front_wheel_angle": 0.43781252033874196, "heading_rate": 0.30683624735398807, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137678.9875379} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27777933598190807, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.82761626048386, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6780226062242474, "gear": 1, "accelerator_pedal_position": 0.2579406215426544, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.342870730281026, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137678.9875379} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.77997922897339, "x": 46.33485045594347, "y": 0.45336335356740154, "z": null, "yaw": 0.2504655577951556, "pitch": null, "roll": null}, "v": 1.6780226062242474, "accelerator_pedal_position": 0.2579406215426544, "brake_pedal_position": 0.0, "acceleration": 0.050070155660381366, "steering_wheel_angle": 8.342870730281026, "front_wheel_angle": 0.43781252033874196, "heading_rate": 0.30683624735398807, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137679.0075378} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2683620532782049, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.82761626048386, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6815023938684335, "gear": 1, "accelerator_pedal_position": 0.27777933598190807, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.342870730281026, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137679.0075378} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.77997922897339, "x": 46.33485045594347, "y": 0.45336335356740154, "z": null, "yaw": 0.2504655577951556, "pitch": null, "roll": null}, "v": 1.6780226062242474, "accelerator_pedal_position": 0.2579406215426544, "brake_pedal_position": 0.0, "acceleration": 0.050070155660381366, "steering_wheel_angle": 8.342870730281026, "front_wheel_angle": 0.43781252033874196, "heading_rate": 0.30683624735398807, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137679.0275378} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2683620532782049, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.82761626048386, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6837996969224454, "gear": 1, "accelerator_pedal_position": 0.2683620532782049, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.342870730281026, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137679.0275378} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.77997922897339, "x": 46.33485045594347, "y": 0.45336335356740154, "z": null, "yaw": 0.2504655577951556, "pitch": null, "roll": null}, "v": 1.6780226062242474, "accelerator_pedal_position": 0.2579406215426544, "brake_pedal_position": 0.0, "acceleration": 0.050070155660381366, "steering_wheel_angle": 8.342870730281026, "front_wheel_angle": 0.43781252033874196, "heading_rate": 0.30683624735398807, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137679.0475378} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2683620532782049, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.82761626048386, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.686093157530164, "gear": 1, "accelerator_pedal_position": 0.2683620532782049, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.342870730281026, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137679.0475378} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.77997922897339, "x": 46.33485045594347, "y": 0.45336335356740154, "z": null, "yaw": 0.2504655577951556, "pitch": null, "roll": null}, "v": 1.6780226062242474, "accelerator_pedal_position": 0.2579406215426544, "brake_pedal_position": 0.0, "acceleration": 0.050070155660381366, "steering_wheel_angle": 8.342870730281026, "front_wheel_angle": 0.43781252033874196, "heading_rate": 0.30683624735398807, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137679.0675378} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2683620532782049, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.82761626048386, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6883827800153226, "gear": 1, "accelerator_pedal_position": 0.2683620532782049, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.342870730281026, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137679.0675378} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.77997922897339, "x": 46.33485045594347, "y": 0.45336335356740154, "z": null, "yaw": 0.2504655577951556, "pitch": null, "roll": null}, "v": 1.6780226062242474, "accelerator_pedal_position": 0.2579406215426544, "brake_pedal_position": 0.0, "acceleration": 0.050070155660381366, "steering_wheel_angle": 8.342870730281026, "front_wheel_angle": 0.43781252033874196, "heading_rate": 0.30683624735398807, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137679.0875378} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2683620532782049, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.82761626048386, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6906685687049752, "gear": 1, "accelerator_pedal_position": 0.2683620532782049, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.342870730281026, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137679.0875378} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137679.0975378, "x": 50.51396262218837, "y": 5.5009384850450935, "z": null, "yaw": 0.27057970112298896, "pitch": null, "roll": null}, "v": 1.6918100267295897, "accelerator_pedal_position": 0.2683620532782049, "brake_pedal_position": 0.0, "acceleration": 0.11405011998687331, "steering_wheel_angle": 8.342870730281026, "front_wheel_angle": 0.43781252033874196, "heading_rate": 0.3093573578282205, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137679.1075377} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23489333119353178, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.8125887796454, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6929505279294583, "gear": 1, "accelerator_pedal_position": 0.2683620532782049, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.342870730281026, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137679.1075377} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.889979124069214, "x": 46.51396262218837, "y": 0.5009384850450935, "z": null, "yaw": 0.27057970112298896, "pitch": null, "roll": null}, "v": 1.6918100267295897, "accelerator_pedal_position": 0.2683620532782049, "brake_pedal_position": 0.0, "acceleration": 0.11405011998687331, "steering_wheel_angle": 8.342870730281026, "front_wheel_angle": 0.43781252033874196, "heading_rate": 0.3093573578282205, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137679.1275377} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2509187484979683, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.8125887796454, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6910468259596458, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.342870730281026, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137679.1275377} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.889979124069214, "x": 46.51396262218837, "y": 0.5009384850450935, "z": null, "yaw": 0.27057970112298896, "pitch": null, "roll": null}, "v": 1.6918100267295897, "accelerator_pedal_position": 0.2683620532782049, "brake_pedal_position": 0.0, "acceleration": 0.11405011998687331, "steering_wheel_angle": 8.342870730281026, "front_wheel_angle": 0.43781252033874196, "heading_rate": 0.3093573578282205, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137679.1475377} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2509187484979683, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.8125887796454, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6911486521284378, "gear": 1, "accelerator_pedal_position": 0.2509187484979683, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.342870730281026, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137679.1475377} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.889979124069214, "x": 46.51396262218837, "y": 0.5009384850450935, "z": null, "yaw": 0.27057970112298896, "pitch": null, "roll": null}, "v": 1.6918100267295897, "accelerator_pedal_position": 0.2683620532782049, "brake_pedal_position": 0.0, "acceleration": 0.11405011998687331, "steering_wheel_angle": 8.342870730281026, "front_wheel_angle": 0.43781252033874196, "heading_rate": 0.3093573578282205, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137679.1675377} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2509187484979683, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.8125887796454, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6912503076623682, "gear": 1, "accelerator_pedal_position": 0.2509187484979683, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.342870730281026, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137679.1675377} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.889979124069214, "x": 46.51396262218837, "y": 0.5009384850450935, "z": null, "yaw": 0.27057970112298896, "pitch": null, "roll": null}, "v": 1.6918100267295897, "accelerator_pedal_position": 0.2683620532782049, "brake_pedal_position": 0.0, "acceleration": 0.11405011998687331, "steering_wheel_angle": 8.342870730281026, "front_wheel_angle": 0.43781252033874196, "heading_rate": 0.3093573578282205, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137679.1875377} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2509187484979683, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.8125887796454, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.691351792843246, "gear": 1, "accelerator_pedal_position": 0.2509187484979683, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.342870730281026, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137679.1875377} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137679.2075377, "x": 50.69279327518093, "y": 5.55230809646355, "z": null, "yaw": 0.2906938444508223, "pitch": null, "roll": null}, "v": 1.6914531079524286, "accelerator_pedal_position": 0.2509187484979683, "brake_pedal_position": 0.0, "acceleration": 0.005059386550661071, "steering_wheel_angle": 8.342870730281026, "front_wheel_angle": 0.43781252033874196, "heading_rate": 0.3092920931424003, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137679.2075377} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24056489061666933, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.328389976609126, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6914531079524286, "gear": 1, "accelerator_pedal_position": 0.2509187484979683, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.342870730281026, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137679.2075377} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.99997901916504, "x": 46.69279327518093, "y": 0.5523080964635501, "z": null, "yaw": 0.2906938444508223, "pitch": null, "roll": null}, "v": 1.6914531079524286, "accelerator_pedal_position": 0.2509187484979683, "brake_pedal_position": 0.0, "acceleration": 0.005059386550661071, "steering_wheel_angle": 8.342870730281026, "front_wheel_angle": 0.43781252033874196, "heading_rate": 0.3092920931424003, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137679.2275376} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24549302186460825, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.328389976609126, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6902605634717052, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.426735642309898, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137679.2275376} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.99997901916504, "x": 46.69279327518093, "y": 0.5523080964635501, "z": null, "yaw": 0.2906938444508223, "pitch": null, "roll": null}, "v": 1.6914531079524286, "accelerator_pedal_position": 0.2509187484979683, "brake_pedal_position": 0.0, "acceleration": 0.005059386550661071, "steering_wheel_angle": 8.342870730281026, "front_wheel_angle": 0.43781252033874196, "heading_rate": 0.3092920931424003, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137679.2475376} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24549302186460825, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.328389976609126, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6896857754306853, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.510271915690643, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137679.2475376} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.99997901916504, "x": 46.69279327518093, "y": 0.5523080964635501, "z": null, "yaw": 0.2906938444508223, "pitch": null, "roll": null}, "v": 1.6914531079524286, "accelerator_pedal_position": 0.2509187484979683, "brake_pedal_position": 0.0, "acceleration": 0.005059386550661071, "steering_wheel_angle": 8.342870730281026, "front_wheel_angle": 0.43781252033874196, "heading_rate": 0.3092920931424003, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137679.2675376} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24549302186460825, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.328389976609126, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6891119502916205, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.593479550423263, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137679.2675376} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.99997901916504, "x": 46.69279327518093, "y": 0.5523080964635501, "z": null, "yaw": 0.2906938444508223, "pitch": null, "roll": null}, "v": 1.6914531079524286, "accelerator_pedal_position": 0.2509187484979683, "brake_pedal_position": 0.0, "acceleration": 0.005059386550661071, "steering_wheel_angle": 8.342870730281026, "front_wheel_angle": 0.43781252033874196, "heading_rate": 0.3092920931424003, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137679.2875376} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24549302186460825, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.328389976609126, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.688539086309774, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.676358546507757, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137679.2875376} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.99997901916504, "x": 46.69279327518093, "y": 0.5523080964635501, "z": null, "yaw": 0.2906938444508223, "pitch": null, "roll": null}, "v": 1.6914531079524286, "accelerator_pedal_position": 0.2509187484979683, "brake_pedal_position": 0.0, "acceleration": 0.005059386550661071, "steering_wheel_angle": 8.342870730281026, "front_wheel_angle": 0.43781252033874196, "heading_rate": 0.3092920931424003, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137679.3075376} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24549302186460825, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.328389976609126, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6879671817439927, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.717674805056955, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137679.3075376} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137679.3175375, "x": 50.87033197657631, "y": 5.607230723129945, "z": null, "yaw": 0.3114748748379626, "pitch": null, "roll": null}, "v": 1.6876815886989942, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3128667708832853, "steering_wheel_angle": 8.717674805056955, "front_wheel_angle": 0.46095878295783316, "heading_rate": 0.3274125170712715, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137679.3275375} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.06737175962492531, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6873962348566993, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.717674805056955, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137679.3275375} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.109978914260864, "x": 46.87033197657631, "y": 0.6072307231299447, "z": null, "yaw": 0.3114748748379626, "pitch": null, "roll": null}, "v": 1.6876815886989942, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3128667708832853, "steering_wheel_angle": 8.717674805056955, "front_wheel_angle": 0.46095878295783316, "heading_rate": 0.3274125170712715, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137679.3475375} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.018384268309792173, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6703670224054241, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.06737175962492531, "steering_wheel_angle": 8.808083940407785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137679.3475375} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.109978914260864, "x": 46.87033197657631, "y": 0.6072307231299447, "z": null, "yaw": 0.3114748748379626, "pitch": null, "roll": null}, "v": 1.6876815886989942, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3128667708832853, "steering_wheel_angle": 8.717674805056955, "front_wheel_angle": 0.46095878295783316, "heading_rate": 0.3274125170712715, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137679.3675375} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.018384268309792173, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6612009693278713, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.018384268309792173, "steering_wheel_angle": 8.898097157869305, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137679.3675375} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.109978914260864, "x": 46.87033197657631, "y": 0.6072307231299447, "z": null, "yaw": 0.3114748748379626, "pitch": null, "roll": null}, "v": 1.6876815886989942, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3128667708832853, "steering_wheel_angle": 8.717674805056955, "front_wheel_angle": 0.46095878295783316, "heading_rate": 0.3274125170712715, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137679.3875375} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.018384268309792173, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6520501750154275, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.018384268309792173, "steering_wheel_angle": 8.98771445744151, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137679.3875375} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.109978914260864, "x": 46.87033197657631, "y": 0.6072307231299447, "z": null, "yaw": 0.3114748748379626, "pitch": null, "roll": null}, "v": 1.6876815886989942, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3128667708832853, "steering_wheel_angle": 8.717674805056955, "front_wheel_angle": 0.46095878295783316, "heading_rate": 0.3274125170712715, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137679.4075375} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.018384268309792173, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6429145805858463, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.018384268309792173, "steering_wheel_angle": 9.076935839124406, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137679.4075375} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137679.4275374, "x": 51.04385873409026, "y": 5.664979275886195, "z": null, "yaw": 0.33343923360450983, "pitch": null, "roll": null}, "v": 1.6337941274216203, "accelerator_pedal_position": 0, "brake_pedal_position": 0.018384268309792173, "acceleration": -0.45545668535739214, "steering_wheel_angle": 9.165761302917991, "front_wheel_angle": 0.48918688066215016, "heading_rate": 0.3397424757550071, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137679.4275374} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23508799145800754, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6337941274216203, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.018384268309792173, "steering_wheel_angle": 9.165761302917991, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137679.4275374} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.21997880935669, "x": 47.04385873409026, "y": 0.6649792758861954, "z": null, "yaw": 0.33343923360450983, "pitch": null, "roll": null}, "v": 1.6337941274216203, "accelerator_pedal_position": 0, "brake_pedal_position": 0.018384268309792173, "acceleration": -0.45545668535739214, "steering_wheel_angle": 9.165761302917991, "front_wheel_angle": 0.48918688066215016, "heading_rate": 0.3397424757550071, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137679.4475374} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6320132119951267, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.254190848822264, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137679.4475374} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.21997880935669, "x": 47.04385873409026, "y": 0.6649792758861954, "z": null, "yaw": 0.33343923360450983, "pitch": null, "roll": null}, "v": 1.6337941274216203, "accelerator_pedal_position": 0, "brake_pedal_position": 0.018384268309792173, "acceleration": -0.45545668535739214, "steering_wheel_angle": 9.165761302917991, "front_wheel_angle": 0.48918688066215016, "heading_rate": 0.3397424757550071, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137679.4675374} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.625851051673143, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.342224476837224, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137679.4675374} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.21997880935669, "x": 47.04385873409026, "y": 0.6649792758861954, "z": null, "yaw": 0.33343923360450983, "pitch": null, "roll": null}, "v": 1.6337941274216203, "accelerator_pedal_position": 0, "brake_pedal_position": 0.018384268309792173, "acceleration": -0.45545668535739214, "steering_wheel_angle": 9.165761302917991, "front_wheel_angle": 0.48918688066215016, "heading_rate": 0.3397424757550071, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137679.4875374} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6196990606132204, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.42986218696287, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137679.4875374} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.21997880935669, "x": 47.04385873409026, "y": 0.6649792758861954, "z": null, "yaw": 0.33343923360450983, "pitch": null, "roll": null}, "v": 1.6337941274216203, "accelerator_pedal_position": 0, "brake_pedal_position": 0.018384268309792173, "acceleration": -0.45545668535739214, "steering_wheel_angle": 9.165761302917991, "front_wheel_angle": 0.48918688066215016, "heading_rate": 0.3397424757550071, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137679.5075374} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6135572069007087, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.51710397919921, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137679.5075374} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.21997880935669, "x": 47.04385873409026, "y": 0.6649792758861954, "z": null, "yaw": 0.33343923360450983, "pitch": null, "roll": null}, "v": 1.6337941274216203, "accelerator_pedal_position": 0, "brake_pedal_position": 0.018384268309792173, "acceleration": -0.45545668535739214, "steering_wheel_angle": 9.165761302917991, "front_wheel_angle": 0.48918688066215016, "heading_rate": 0.3397424757550071, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137679.5275373} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6074254587483827, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.60394985354623, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137679.5275373} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137679.5375373, "x": 51.21184044381579, "y": 5.7251602382258655, "z": null, "yaw": 0.35710012660206103, "pitch": null, "roll": null}, "v": 1.6043633643584654, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3059579862668794, "steering_wheel_angle": 9.647224321511251, "front_wheel_angle": 0.5202377881368989, "heading_rate": 0.3590249442969882, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137679.5475373} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2512528072654215, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6013037844957967, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.690399810003942, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137679.5475373} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.329978704452515, "x": 47.21184044381579, "y": 0.7251602382258655, "z": null, "yaw": 0.35710012660206103, "pitch": null, "roll": null}, "v": 1.6043633643584654, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3059579862668794, "steering_wheel_angle": 9.647224321511251, "front_wheel_angle": 0.5202377881368989, "heading_rate": 0.3590249442969882, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137679.5675373} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22991535340233055, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6015961269075931, "gear": 1, "accelerator_pedal_position": 0.2512528072654215, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.776453848572343, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137679.5675373} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.329978704452515, "x": 47.21184044381579, "y": 0.7251602382258655, "z": null, "yaw": 0.35710012660206103, "pitch": null, "roll": null}, "v": 1.6043633643584654, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3059579862668794, "steering_wheel_angle": 9.647224321511251, "front_wheel_angle": 0.5202377881368989, "heading_rate": 0.3590249442969882, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137679.5875373} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22991535340233055, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.599221901994887, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.862111969251432, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137679.5875373} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.329978704452515, "x": 47.21184044381579, "y": 0.7251602382258655, "z": null, "yaw": 0.35710012660206103, "pitch": null, "roll": null}, "v": 1.6043633643584654, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3059579862668794, "steering_wheel_angle": 9.647224321511251, "front_wheel_angle": 0.5202377881368989, "heading_rate": 0.3590249442969882, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137679.6075373} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22991535340233055, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5968515690397262, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.947374172041208, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137679.6075373} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.329978704452515, "x": 47.21184044381579, "y": 0.7251602382258655, "z": null, "yaw": 0.35710012660206103, "pitch": null, "roll": null}, "v": 1.6043633643584654, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3059579862668794, "steering_wheel_angle": 9.647224321511251, "front_wheel_angle": 0.5202377881368989, "heading_rate": 0.3590249442969882, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137679.6275373} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22991535340233055, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5944851194157323, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.032240456941674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137679.6275373} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137679.6475372, "x": 51.37589705339015, "y": 5.788508053831402, "z": null, "yaw": 0.3825308155297683, "pitch": null, "roll": null}, "v": 1.5921225445217029, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30495466919382774, "steering_wheel_angle": 10.116710823952825, "front_wheel_angle": 0.5512886956116477, "heading_rate": 0.3824077657709808, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137679.6475372} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5921225445217029, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.116710823952825, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137679.6475372} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.43997859954834, "x": 47.37589705339015, "y": 0.7885080538314018, "z": null, "yaw": 0.3825308155297683, "pitch": null, "roll": null}, "v": 1.5921225445217029, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30495466919382774, "steering_wheel_angle": 10.116710823952825, "front_wheel_angle": 0.5512886956116477, "heading_rate": 0.3824077657709808, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137679.6675372} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.57993931152923, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.284463804307196, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137679.6675372} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.43997859954834, "x": 47.37589705339015, "y": 0.7885080538314018, "z": null, "yaw": 0.3825308155297683, "pitch": null, "roll": null}, "v": 1.5921225445217029, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30495466919382774, "steering_wheel_angle": 10.116710823952825, "front_wheel_angle": 0.5512886956116477, "heading_rate": 0.3824077657709808, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137679.6875372} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.57993931152923, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.284463804307196, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137679.6875372} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.43997859954834, "x": 47.37589705339015, "y": 0.7885080538314018, "z": null, "yaw": 0.3825308155297683, "pitch": null, "roll": null}, "v": 1.5921225445217029, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30495466919382774, "steering_wheel_angle": 10.116710823952825, "front_wheel_angle": 0.5512886956116477, "heading_rate": 0.3824077657709808, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137679.7075372} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5647661139456879, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137679.7075372} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.43997859954834, "x": 47.37589705339015, "y": 0.7885080538314018, "z": null, "yaw": 0.3825308155297683, "pitch": null, "roll": null}, "v": 1.5921225445217029, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30495466919382774, "steering_wheel_angle": 10.116710823952825, "front_wheel_angle": 0.5512886956116477, "heading_rate": 0.3824077657709808, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137679.7375371} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5617388815895799, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137679.7375371} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137679.7575371, "x": 51.53601435803696, "y": 5.855209649954801, "z": null, "yaw": 0.40970373706576446, "pitch": null, "roll": null}, "v": 1.5587141093153583, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30223160221155565, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.39116942605126315, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137679.767537} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22070587915839257, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5539660471484236, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137679.767537} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.549978494644165, "x": 47.53601435803696, "y": 0.8552096499548014, "z": null, "yaw": 0.40970373706576446, "pitch": null, "roll": null}, "v": 1.5587141093153583, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30223160221155565, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.39116942605126315, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137679.787537} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21772518716776362, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5522417005246798, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137679.787537} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.549978494644165, "x": 47.53601435803696, "y": 0.8552096499548014, "z": null, "yaw": 0.40970373706576446, "pitch": null, "roll": null}, "v": 1.5587141093153583, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30223160221155565, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.39116942605126315, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137679.807537} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21772518716776362, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5484247633383117, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137679.807537} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.549978494644165, "x": 47.53601435803696, "y": 0.8552096499548014, "z": null, "yaw": 0.40970373706576446, "pitch": null, "roll": null}, "v": 1.5587141093153583, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30223160221155565, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.39116942605126315, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137679.827537} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21772518716776362, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5446140061391196, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137679.827537} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.549978494644165, "x": 47.53601435803696, "y": 0.8552096499548014, "z": null, "yaw": 0.40970373706576446, "pitch": null, "roll": null}, "v": 1.5587141093153583, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30223160221155565, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.39116942605126315, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137679.847537} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21772518716776362, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.540809413114711, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137679.847537} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137679.867537, "x": 51.691380696091834, "y": 5.925006178408665, "z": null, "yaw": 0.43730895126667974, "pitch": null, "roll": null}, "v": 1.5370109685064548, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3004745755984143, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3857228819525141, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137679.867537} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24294865926028095, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5370109685064548, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137679.867537} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.65997838973999, "x": 47.691380696091834, "y": 0.9250061784086654, "z": null, "yaw": 0.43730895126667974, "pitch": null, "roll": null}, "v": 1.5370109685064548, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3004745755984143, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3857228819525141, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137679.887537} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2308036073120493, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5363703181274608, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137679.887537} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.65997838973999, "x": 47.691380696091834, "y": 0.9250061784086654, "z": null, "yaw": 0.43730895126667974, "pitch": null, "roll": null}, "v": 1.5370109685064548, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3004745755984143, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3857228819525141, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137679.907537} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2308036073120493, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5342131829072292, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137679.907537} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.65997838973999, "x": 47.691380696091834, "y": 0.9250061784086654, "z": null, "yaw": 0.43730895126667974, "pitch": null, "roll": null}, "v": 1.5370109685064548, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3004745755984143, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3857228819525141, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137679.927537} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2308036073120493, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5320595276851856, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137679.927537} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.65997838973999, "x": 47.691380696091834, "y": 0.9250061784086654, "z": null, "yaw": 0.43730895126667974, "pitch": null, "roll": null}, "v": 1.5370109685064548, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3004745755984143, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3857228819525141, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137679.947537} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2308036073120493, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5299093449926784, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137679.947537} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.65997838973999, "x": 47.691380696091834, "y": 0.9250061784086654, "z": null, "yaw": 0.43730895126667974, "pitch": null, "roll": null}, "v": 1.5370109685064548, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3004745755984143, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3857228819525141, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137679.967537} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2308036073120493, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5256193674266647, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137679.967537} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137679.977537, "x": 51.84322335608759, "y": 5.998324719706704, "z": null, "yaw": 0.464914165467595, "pitch": null, "roll": null}, "v": 1.5266905656608198, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29964236911581854, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3831329098507551, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137679.987537} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23517115116879067, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5245490317545278, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137679.987537} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.769978284835815, "x": 47.84322335608759, "y": 0.9983247197067042, "z": null, "yaw": 0.464914165467595, "pitch": null, "roll": null}, "v": 1.5266905656608198, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29964236911581854, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3831329098507551, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137680.0175369} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23302796110105137, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.521099074301826, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137680.0175369} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.769978284835815, "x": 47.84322335608759, "y": 0.9983247197067042, "z": null, "yaw": 0.464914165467595, "pitch": null, "roll": null}, "v": 1.5266905656608198, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29964236911581854, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3831329098507551, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137680.0375369} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23302796110105137, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5201713980941065, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137680.0375369} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.769978284835815, "x": 47.84322335608759, "y": 0.9983247197067042, "z": null, "yaw": 0.464914165467595, "pitch": null, "roll": null}, "v": 1.5266905656608198, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29964236911581854, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3831329098507551, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137680.0675368} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23302796110105137, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5164681452460662, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137680.0675368} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137680.0875368, "x": 51.99191467854332, "y": 6.075253159829464, "z": null, "yaw": 0.4925193796685103, "pitch": null, "roll": null}, "v": 1.5164681452460662, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29882016361776376, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.38056752707619984, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137680.0875368} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2657943027814408, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5164681452460662, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137680.0875368} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.87997817993164, "x": 47.99191467854332, "y": 1.0752531598294643, "z": null, "yaw": 0.4925193796685103, "pitch": null, "roll": null}, "v": 1.5164681452460662, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29882016361776376, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.38056752707619984, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137680.1075368} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2501286308795255, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5198372636361586, "gear": 1, "accelerator_pedal_position": 0.2657943027814408, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137680.1075368} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.87997817993164, "x": 47.99191467854332, "y": 1.0752531598294643, "z": null, "yaw": 0.4925193796685103, "pitch": null, "roll": null}, "v": 1.5164681452460662, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29882016361776376, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.38056752707619984, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137680.1275368} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2501286308795255, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.519979393903517, "gear": 1, "accelerator_pedal_position": 0.2501286308795255, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137680.1275368} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.87997817993164, "x": 47.99191467854332, "y": 1.0752531598294643, "z": null, "yaw": 0.4925193796685103, "pitch": null, "roll": null}, "v": 1.5164681452460662, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29882016361776376, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.38056752707619984, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137680.1475368} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2501286308795255, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5202633117156825, "gear": 1, "accelerator_pedal_position": 0.2501286308795255, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137680.1475368} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.87997817993164, "x": 47.99191467854332, "y": 1.0752531598294643, "z": null, "yaw": 0.4925193796685103, "pitch": null, "roll": null}, "v": 1.5164681452460662, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29882016361776376, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.38056752707619984, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137680.1675367} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2501286308795255, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5206883329441752, "gear": 1, "accelerator_pedal_position": 0.2501286308795255, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137680.1675367} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.87997817993164, "x": 47.99191467854332, "y": 1.0752531598294643, "z": null, "yaw": 0.4925193796685103, "pitch": null, "roll": null}, "v": 1.5164681452460662, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29882016361776376, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.38056752707619984, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137680.1875367} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2501286308795255, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5208297789070782, "gear": 1, "accelerator_pedal_position": 0.2501286308795255, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137680.1875367} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137680.1975367, "x": 52.13819346235161, "y": 6.156131922619576, "z": null, "yaw": 0.5201245938694251, "pitch": null, "roll": null}, "v": 1.5209711111259538, "accelerator_pedal_position": 0.2501286308795255, "brake_pedal_position": 0.0, "acceleration": 0.014121856231939567, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3816975756003245, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137680.2075367} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27198790032117764, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5226196390215496, "gear": 1, "accelerator_pedal_position": 0.27198790032117764, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137680.2075367} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.989978075027466, "x": 48.13819346235161, "y": 1.1561319226195756, "z": null, "yaw": 0.5201245938694251, "pitch": null, "roll": null}, "v": 1.5209711111259538, "accelerator_pedal_position": 0.2501286308795255, "brake_pedal_position": 0.0, "acceleration": 0.014121856231939567, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3816975756003245, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137680.2275367} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26160629430745513, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.524125735915599, "gear": 1, "accelerator_pedal_position": 0.27198790032117764, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137680.2275367} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.989978075027466, "x": 48.13819346235161, "y": 1.1561319226195756, "z": null, "yaw": 0.5201245938694251, "pitch": null, "roll": null}, "v": 1.5209711111259538, "accelerator_pedal_position": 0.2501286308795255, "brake_pedal_position": 0.0, "acceleration": 0.014121856231939567, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3816975756003245, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137680.2475367} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26160629430745513, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5258371160848865, "gear": 1, "accelerator_pedal_position": 0.26160629430745513, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137680.2475367} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.989978075027466, "x": 48.13819346235161, "y": 1.1561319226195756, "z": null, "yaw": 0.5201245938694251, "pitch": null, "roll": null}, "v": 1.5209711111259538, "accelerator_pedal_position": 0.2501286308795255, "brake_pedal_position": 0.0, "acceleration": 0.014121856231939567, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3816975756003245, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137680.2675366} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26160629430745513, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5283990226853126, "gear": 1, "accelerator_pedal_position": 0.26160629430745513, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137680.2675366} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.989978075027466, "x": 48.13819346235161, "y": 1.1561319226195756, "z": null, "yaw": 0.5201245938694251, "pitch": null, "roll": null}, "v": 1.5209711111259538, "accelerator_pedal_position": 0.2501286308795255, "brake_pedal_position": 0.0, "acceleration": 0.014121856231939567, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3816975756003245, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137680.2875366} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26160629430745513, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5292516162109313, "gear": 1, "accelerator_pedal_position": 0.26160629430745513, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137680.2875366} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137680.3075366, "x": 52.2827535186882, "y": 6.241354916685374, "z": null, "yaw": 0.5477298080703398, "pitch": null, "roll": null}, "v": 1.530954742700284, "accelerator_pedal_position": 0.26160629430745513, "brake_pedal_position": 0.0, "acceleration": 0.08505337804461538, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3842030327649827, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137680.3075366} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.02547866012126434, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5259165902768133, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.02547866012126434, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137680.3075366} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.09997797012329, "x": 48.2827535186882, "y": 1.2413549166853741, "z": null, "yaw": 0.5477298080703398, "pitch": null, "roll": null}, "v": 1.530954742700284, "accelerator_pedal_position": 0.26160629430745513, "brake_pedal_position": 0.0, "acceleration": 0.08505337804461538, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3842030327649827, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137680.3275366} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5208824970279256, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.02547866012126434, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137680.3275366} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.09997797012329, "x": 48.2827535186882, "y": 1.2413549166853741, "z": null, "yaw": 0.5477298080703398, "pitch": null, "roll": null}, "v": 1.530954742700284, "accelerator_pedal_position": 0.26160629430745513, "brake_pedal_position": 0.0, "acceleration": 0.08505337804461538, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3842030327649827, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137680.3475366} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5149014028166128, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137680.3475366} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.09997797012329, "x": 48.2827535186882, "y": 1.2413549166853741, "z": null, "yaw": 0.5477298080703398, "pitch": null, "roll": null}, "v": 1.530954742700284, "accelerator_pedal_position": 0.26160629430745513, "brake_pedal_position": 0.0, "acceleration": 0.08505337804461538, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3842030327649827, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137680.3675365} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5089299137261531, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137680.3675365} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.09997797012329, "x": 48.2827535186882, "y": 1.2413549166853741, "z": null, "yaw": 0.5477298080703398, "pitch": null, "roll": null}, "v": 1.530954742700284, "accelerator_pedal_position": 0.26160629430745513, "brake_pedal_position": 0.0, "acceleration": 0.08505337804461538, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3842030327649827, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137680.3875365} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5029680000737926, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137680.3875365} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.09997797012329, "x": 48.2827535186882, "y": 1.2413549166853741, "z": null, "yaw": 0.5477298080703398, "pitch": null, "roll": null}, "v": 1.530954742700284, "accelerator_pedal_position": 0.26160629430745513, "brake_pedal_position": 0.0, "acceleration": 0.08505337804461538, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3842030327649827, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137680.4075365} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4970156322929882, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137680.4075365} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137680.4175365, "x": 52.42368977788374, "y": 6.329758780973569, "z": null, "yaw": 0.5753350222712544, "pitch": null, "roll": null}, "v": 1.4940430188965088, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2970237963679594, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3749397960183624, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137680.4275365} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23304782504036106, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4910727809328292, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137680.4275365} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.209977865219116, "x": 48.42368977788374, "y": 1.3297587809735694, "z": null, "yaw": 0.5753350222712544, "pitch": null, "roll": null}, "v": 1.4940430188965088, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2970237963679594, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3749397960183624, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137680.4475365} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22294924582279949, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.489268746883465, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137680.4475365} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.209977865219116, "x": 48.42368977788374, "y": 1.3297587809735694, "z": null, "yaw": 0.5753350222712544, "pitch": null, "roll": null}, "v": 1.4940430188965088, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2970237963679594, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3749397960183624, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137680.4675364} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22294924582279949, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4862057717402621, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137680.4675364} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.209977865219116, "x": 48.42368977788374, "y": 1.3297587809735694, "z": null, "yaw": 0.5753350222712544, "pitch": null, "roll": null}, "v": 1.4940430188965088, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2970237963679594, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3749397960183624, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137680.4875364} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22294924582279949, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4831476794477374, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137680.4875364} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.209977865219116, "x": 48.42368977788374, "y": 1.3297587809735694, "z": null, "yaw": 0.5753350222712544, "pitch": null, "roll": null}, "v": 1.4940430188965088, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2970237963679594, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3749397960183624, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137680.5075364} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22294924582279949, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4785696711566783, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137680.5075364} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137680.5275364, "x": 52.55971059186856, "y": 6.420410903734078, "z": null, "yaw": 0.6029402364721691, "pitch": null, "roll": null}, "v": 1.4770460973577784, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29566895660508735, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3706743082017006, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137680.5275364} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21797278795715933, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4770460973577784, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137680.5275364} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.31997776031494, "x": 48.55971059186856, "y": 1.4204109037340782, "z": null, "yaw": 0.6029402364721691, "pitch": null, "roll": null}, "v": 1.4770460973577784, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29566895660508735, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3706743082017006, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137680.5475364} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22023930504346964, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.473380774679752, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137680.5475364} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.31997776031494, "x": 48.55971059186856, "y": 1.4204109037340782, "z": null, "yaw": 0.6029402364721691, "pitch": null, "roll": null}, "v": 1.4770460973577784, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29566895660508735, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3706743082017006, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137680.5675364} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22023930504346964, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.470004478632976, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137680.5675364} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.31997776031494, "x": 48.55971059186856, "y": 1.4204109037340782, "z": null, "yaw": 0.6029402364721691, "pitch": null, "roll": null}, "v": 1.4770460973577784, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29566895660508735, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3706743082017006, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137680.5875363} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22023930504346964, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4666335431613118, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137680.5875363} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.31997776031494, "x": 48.55971059186856, "y": 1.4204109037340782, "z": null, "yaw": 0.6029402364721691, "pitch": null, "roll": null}, "v": 1.4770460973577784, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29566895660508735, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3706743082017006, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137680.6075363} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22023930504346964, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.463267955210246, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137680.6075363} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.31997776031494, "x": 48.55971059186856, "y": 1.4204109037340782, "z": null, "yaw": 0.6029402364721691, "pitch": null, "roll": null}, "v": 1.4770460973577784, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29566895660508735, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3706743082017006, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137680.6275363} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22023930504346964, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.459907701767602, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137680.6275363} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137680.6375363, "x": 52.69158890933314, "y": 6.51365884915424, "z": null, "yaw": 0.6305454506730838, "pitch": null, "roll": null}, "v": 1.4582295714321671, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2941758134016008, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.36595217884994086, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137680.6475363} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22788182099463639, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.456552769863368, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137680.6475363} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.429977655410767, "x": 48.69158890933314, "y": 1.5136588491542398, "z": null, "yaw": 0.6305454506730838, "pitch": null, "roll": null}, "v": 1.4582295714321671, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2941758134016008, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.36595217884994086, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137680.6675363} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2241287625180461, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4541580832254466, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137680.6675363} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.429977655410767, "x": 48.69158890933314, "y": 1.5136588491542398, "z": null, "yaw": 0.6305454506730838, "pitch": null, "roll": null}, "v": 1.4582295714321671, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2941758134016008, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.36595217884994086, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137680.6875362} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2241287625180461, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.45129823638204, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137680.6875362} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.429977655410767, "x": 48.69158890933314, "y": 1.5136588491542398, "z": null, "yaw": 0.6305454506730838, "pitch": null, "roll": null}, "v": 1.4582295714321671, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2941758134016008, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.36595217884994086, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137680.7075362} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2241287625180461, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4484429086132937, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137680.7075362} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.429977655410767, "x": 48.69158890933314, "y": 1.5136588491542398, "z": null, "yaw": 0.6305454506730838, "pitch": null, "roll": null}, "v": 1.4582295714321671, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2941758134016008, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.36595217884994086, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137680.7275362} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2241287625180461, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4455920895183816, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137680.7275362} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137680.7475362, "x": 52.81933354010169, "y": 6.609381131032223, "z": null, "yaw": 0.6581506648739984, "pitch": null, "roll": null}, "v": 1.4427457687283458, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29295244196825276, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.36206641802918, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137680.7475362} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22642885988695882, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4427457687283458, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137680.7475362} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.539977550506592, "x": 48.81933354010169, "y": 1.6093811310322232, "z": null, "yaw": 0.6581506648739984, "pitch": null, "roll": null}, "v": 1.4427457687283458, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29295244196825276, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.36206641802918, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137680.7675362} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22524036557980237, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.440191334757152, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137680.7675362} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.539977550506592, "x": 48.81933354010169, "y": 1.6093811310322232, "z": null, "yaw": 0.6581506648739984, "pitch": null, "roll": null}, "v": 1.4427457687283458, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29295244196825276, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.36206641802918, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137680.7875361} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22524036557980237, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4374924225636276, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137680.7875361} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.539977550506592, "x": 48.81933354010169, "y": 1.6093811310322232, "z": null, "yaw": 0.6581506648739984, "pitch": null, "roll": null}, "v": 1.4427457687283458, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29295244196825276, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.36206641802918, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137680.8075361} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22524036557980237, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4334520197103802, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137680.8075361} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.539977550506592, "x": 48.81933354010169, "y": 1.6093811310322232, "z": null, "yaw": 0.6581506648739984, "pitch": null, "roll": null}, "v": 1.4427457687283458, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29295244196825276, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.36206641802918, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137680.827536} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22524036557980237, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4321073380799814, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137680.827536} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.539977550506592, "x": 48.81933354010169, "y": 1.6093811310322232, "z": null, "yaw": 0.6581506648739984, "pitch": null, "roll": null}, "v": 1.4427457687283458, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29295244196825276, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.36206641802918, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137680.847536} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22524036557980237, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4294211466280167, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137680.847536} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137680.857536, "x": 52.94308703014309, "y": 6.707561410090992, "z": null, "yaw": 0.6857558790749131, "pitch": null, "roll": null}, "v": 1.4280796344219975, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2917980961436085, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3583858564016697, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137680.867536} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21705717604395872, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4248883217561703, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137680.867536} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.649977445602417, "x": 48.94308703014309, "y": 1.7075614100909924, "z": null, "yaw": 0.6857558790749131, "pitch": null, "roll": null}, "v": 1.4280796344219975, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2917980961436085, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3583858564016697, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137680.887536} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22086598471038724, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.423038920425092, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137680.887536} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.649977445602417, "x": 48.94308703014309, "y": 1.7075614100909924, "z": null, "yaw": 0.6857558790749131, "pitch": null, "roll": null}, "v": 1.4280796344219975, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2917980961436085, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3583858564016697, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137680.907536} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22086598471038724, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4198203845200739, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137680.907536} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.649977445602417, "x": 48.94308703014309, "y": 1.7075614100909924, "z": null, "yaw": 0.6857558790749131, "pitch": null, "roll": null}, "v": 1.4280796344219975, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2917980961436085, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3583858564016697, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137680.927536} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22086598471038724, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.416606894105495, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137680.927536} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.649977445602417, "x": 48.94308703014309, "y": 1.7075614100909924, "z": null, "yaw": 0.6857558790749131, "pitch": null, "roll": null}, "v": 1.4280796344219975, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2917980961436085, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3583858564016697, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137680.947536} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22086598471038724, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.413398437142875, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137680.947536} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137680.967536, "x": 53.062717478015095, "y": 6.807972429924498, "z": null, "yaw": 0.7133610932758278, "pitch": null, "roll": null}, "v": 1.410195001631996, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29039624950787846, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.353897591682827, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137680.967536} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23697581554270453, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4096020276083363, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137680.967536} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.759977340698242, "x": 49.062717478015095, "y": 1.8079724299244981, "z": null, "yaw": 0.7133610932758278, "pitch": null, "roll": null}, "v": 1.410195001631996, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29039624950787846, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.353897591682827, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137680.987536} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22919765627906266, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4090095172783275, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137680.987536} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.759977340698242, "x": 49.062717478015095, "y": 1.8079724299244981, "z": null, "yaw": 0.7133610932758278, "pitch": null, "roll": null}, "v": 1.410195001631996, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29039624950787846, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.353897591682827, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137681.007536} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22919765627906266, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4068539960404862, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137681.007536} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.759977340698242, "x": 49.062717478015095, "y": 1.8079724299244981, "z": null, "yaw": 0.7133610932758278, "pitch": null, "roll": null}, "v": 1.410195001631996, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29039624950787846, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.353897591682827, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137681.027536} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22919765627906266, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4047018424737623, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137681.027536} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.759977340698242, "x": 49.062717478015095, "y": 1.8079724299244981, "z": null, "yaw": 0.7133610932758278, "pitch": null, "roll": null}, "v": 1.410195001631996, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29039624950787846, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.353897591682827, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137681.047536} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22919765627906266, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4025530494647036, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137681.047536} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.759977340698242, "x": 49.062717478015095, "y": 1.8079724299244981, "z": null, "yaw": 0.7133610932758278, "pitch": null, "roll": null}, "v": 1.410195001631996, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29039624950787846, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.353897591682827, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137681.0675359} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22919765627906266, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4004076099196419, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137681.0675359} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137681.0775359, "x": 53.178356471369334, "y": 6.910607177514269, "z": null, "yaw": 0.7409663074767424, "pitch": null, "roll": null}, "v": 1.3993361454847313, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.28954822375483724, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.35117249122898914, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137681.0875359} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21704615184495882, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3982655167646243, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137681.0875359} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.869977235794067, "x": 49.178356471369334, "y": 1.9106071775142688, "z": null, "yaw": 0.7409663074767424, "pitch": null, "roll": null}, "v": 1.3993361454847313, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.28954822375483724, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.35117249122898914, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137681.1075358} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22276797390021952, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3946084167932922, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137681.1075358} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.869977235794067, "x": 49.178356471369334, "y": 1.9106071775142688, "z": null, "yaw": 0.7409663074767424, "pitch": null, "roll": null}, "v": 1.3993361454847313, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.28954822375483724, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.35117249122898914, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137681.1275358} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22276797390021952, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3916719624505212, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137681.1275358} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.869977235794067, "x": 49.178356471369334, "y": 1.9106071775142688, "z": null, "yaw": 0.7409663074767424, "pitch": null, "roll": null}, "v": 1.3993361454847313, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.28954822375483724, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.35117249122898914, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137681.1475358} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22276797390021952, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.387275846706711, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137681.1475358} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.869977235794067, "x": 49.178356471369334, "y": 1.9106071775142688, "z": null, "yaw": 0.7409663074767424, "pitch": null, "roll": null}, "v": 1.3993361454847313, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.28954822375483724, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.35117249122898914, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137681.1675358} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22276797390021952, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3858127537246359, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137681.1675358} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137681.1875358, "x": 53.29000881863023, "y": 7.015351656690597, "z": null, "yaw": 0.7685715216776571, "pitch": null, "roll": null}, "v": 1.3828899782742565, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.28826834583382654, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3470452187869053, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137681.1875358} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23573161111609323, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.382240520510674, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137681.1875358} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.979977130889893, "x": 49.29000881863023, "y": 2.015351656690597, "z": null, "yaw": 0.7685715216776571, "pitch": null, "roll": null}, "v": 1.3828899782742565, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.28826834583382654, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3470452187869053, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137681.2075357} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22946093289636052, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3805512000561961, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137681.2075357} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.979977130889893, "x": 49.29000881863023, "y": 2.015351656690597, "z": null, "yaw": 0.7685715216776571, "pitch": null, "roll": null}, "v": 1.3828899782742565, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.28826834583382654, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3470452187869053, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137681.2275357} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22946093289636052, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.379511640600593, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137681.2275357} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.979977130889893, "x": 49.29000881863023, "y": 2.015351656690597, "z": null, "yaw": 0.7685715216776571, "pitch": null, "roll": null}, "v": 1.3828899782742565, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.28826834583382654, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3470452187869053, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137681.2475357} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22946093289636052, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3774349409615039, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137681.2475357} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.979977130889893, "x": 49.29000881863023, "y": 2.015351656690597, "z": null, "yaw": 0.7685715216776571, "pitch": null, "roll": null}, "v": 1.3828899782742565, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.28826834583382654, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3470452187869053, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137681.2675357} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22946093289636052, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.373291195239194, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137681.2675357} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.979977130889893, "x": 49.29000881863023, "y": 2.015351656690597, "z": null, "yaw": 0.7685715216776571, "pitch": null, "roll": null}, "v": 1.3828899782742565, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.28826834583382654, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3470452187869053, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137681.2875357} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22946093289636052, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.373291195239194, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137681.2875357} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137681.2975357, "x": 53.39767712625177, "y": 7.122098656114739, "z": null, "yaw": 0.7961767358785717, "pitch": null, "roll": null}, "v": 1.3722572650769047, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.28744376326940874, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.34437687037463444, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137681.3075356} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2178042740008104, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3684317350885324, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137681.3075356} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.089977025985718, "x": 49.39767712625177, "y": 2.122098656114739, "z": null, "yaw": 0.7961767358785717, "pitch": null, "roll": null}, "v": 1.3722572650769047, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.28744376326940874, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.34437687037463444, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137681.3275356} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22329224135431047, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.366673025804679, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137681.3275356} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.089977025985718, "x": 49.39767712625177, "y": 2.122098656114739, "z": null, "yaw": 0.7961767358785717, "pitch": null, "roll": null}, "v": 1.3722572650769047, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.28744376326940874, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.34437687037463444, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137681.3475356} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22329224135431047, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.365258674860475, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137681.3475356} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.089977025985718, "x": 49.39767712625177, "y": 2.122098656114739, "z": null, "yaw": 0.7961767358785717, "pitch": null, "roll": null}, "v": 1.3722572650769047, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.28744376326940874, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.34437687037463444, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137681.3675356} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22329224135431047, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3624332524263851, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137681.3675356} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.089977025985718, "x": 49.39767712625177, "y": 2.122098656114739, "z": null, "yaw": 0.7961767358785717, "pitch": null, "roll": null}, "v": 1.3722572650769047, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.28744376326940874, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.34437687037463444, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137681.3875356} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22329224135431047, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3596121943064823, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137681.3875356} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137681.4075356, "x": 53.50137223321509, "y": 7.230742108953027, "z": null, "yaw": 0.8237819500794864, "pitch": null, "roll": null}, "v": 1.3567954905772692, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2862487145613716, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3404966376747373, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137681.4075356} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22947007698950173, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3557748832434993, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137681.4075356} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.199976921081543, "x": 49.50137223321509, "y": 2.2307421089530273, "z": null, "yaw": 0.8237819500794864, "pitch": null, "roll": null}, "v": 1.3567954905772692, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2862487145613716, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3404966376747373, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137681.4275355} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2264371976513616, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.354755063060318, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137681.4275355} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.199976921081543, "x": 49.50137223321509, "y": 2.2307421089530273, "z": null, "yaw": 0.8237819500794864, "pitch": null, "roll": null}, "v": 1.3567954905772692, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2862487145613716, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3404966376747373, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137681.4475355} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2264371976513616, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.352338817064196, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137681.4475355} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.199976921081543, "x": 49.50137223321509, "y": 2.2307421089530273, "z": null, "yaw": 0.8237819500794864, "pitch": null, "roll": null}, "v": 1.3567954905772692, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2862487145613716, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3404966376747373, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137681.4675355} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2264371976513616, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3499262934966367, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137681.4675355} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.199976921081543, "x": 49.50137223321509, "y": 2.2307421089530273, "z": null, "yaw": 0.8237819500794864, "pitch": null, "roll": null}, "v": 1.3567954905772692, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2862487145613716, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3404966376747373, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137681.4875355} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2264371976513616, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3475174842957163, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137681.4875355} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.199976921081543, "x": 49.50137223321509, "y": 2.2307421089530273, "z": null, "yaw": 0.8237819500794864, "pitch": null, "roll": null}, "v": 1.3567954905772692, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2862487145613716, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3404966376747373, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137681.5075355} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2264371976513616, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3451123814226735, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137681.5075355} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137681.5175354, "x": 53.60097491812516, "y": 7.341040001118232, "z": null, "yaw": 0.8513871642804011, "pitch": null, "roll": null}, "v": 1.3439112173533065, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2852565344689458, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.33726324565500454, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137681.5275354} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21912015890392797, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3427109768618273, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137681.5275354} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.309976816177368, "x": 49.60097491812516, "y": 2.341040001118232, "z": null, "yaw": 0.8513871642804011, "pitch": null, "roll": null}, "v": 1.3439112173533065, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2852565344689458, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.33726324565500454, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137681.5475354} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2225288700984641, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.339398984112271, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137681.5475354} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.309976816177368, "x": 49.60097491812516, "y": 2.341040001118232, "z": null, "yaw": 0.8513871642804011, "pitch": null, "roll": null}, "v": 1.3439112173533065, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2852565344689458, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.33726324565500454, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137681.5675354} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2225288700984641, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.335079169646663, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137681.5675354} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.309976816177368, "x": 49.60097491812516, "y": 2.341040001118232, "z": null, "yaw": 0.8513871642804011, "pitch": null, "roll": null}, "v": 1.3439112173533065, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2852565344689458, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.33726324565500454, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137681.5875354} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2225288700984641, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3336414408040713, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137681.5875354} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.309976816177368, "x": 49.60097491812516, "y": 2.341040001118232, "z": null, "yaw": 0.8513871642804011, "pitch": null, "roll": null}, "v": 1.3439112173533065, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2852565344689458, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.33726324565500454, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137681.6075354} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2225288700984641, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3307692895226746, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137681.6075354} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137681.6275353, "x": 53.69646095479642, "y": 7.452832864665663, "z": null, "yaw": 0.8789923784813157, "pitch": null, "roll": null}, "v": 1.3279015383995274, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2840283018768147, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.33324551277494135, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137681.6275353} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.219791043245946, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3279015383995274, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137681.6275353} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.419976711273193, "x": 49.69646095479642, "y": 2.4528328646656634, "z": null, "yaw": 0.8789923784813157, "pitch": null, "roll": null}, "v": 1.3279015383995274, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2840283018768147, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.33324551277494135, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137681.6475353} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22100119129702836, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.323095190190786, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137681.6475353} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.419976711273193, "x": 49.69646095479642, "y": 2.4528328646656634, "z": null, "yaw": 0.8789923784813157, "pitch": null, "roll": null}, "v": 1.3279015383995274, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2840283018768147, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.33324551277494135, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137681.6675353} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22100119129702836, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3185265903674126, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137681.6675353} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.419976711273193, "x": 49.69646095479642, "y": 2.4528328646656634, "z": null, "yaw": 0.8789923784813157, "pitch": null, "roll": null}, "v": 1.3279015383995274, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2840283018768147, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.33324551277494135, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137681.6875353} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22100119129702836, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3170060502913425, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137681.6875353} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.419976711273193, "x": 49.69646095479642, "y": 2.4528328646656634, "z": null, "yaw": 0.8789923784813157, "pitch": null, "roll": null}, "v": 1.3279015383995274, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2840283018768147, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.33324551277494135, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137681.7075353} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22100119129702836, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3109354866471308, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137681.7075353} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137681.7375352, "x": 53.78768471945053, "y": 7.565806246331558, "z": null, "yaw": 0.9065975926822304, "pitch": null, "roll": null}, "v": 1.3109354866471308, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.28273229283386403, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3289877719315894, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137681.7375352} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3109354866471308, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137681.7375352} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.52997660636902, "x": 49.78768471945053, "y": 2.565806246331558, "z": null, "yaw": 0.9065975926822304, "pitch": null, "roll": null}, "v": 1.3109354866471308, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.28273229283386403, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3289877719315894, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137681.7575352} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2996391068852517, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137681.7575352} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.52997660636902, "x": 49.78768471945053, "y": 2.565806246331558, "z": null, "yaw": 0.9065975926822304, "pitch": null, "roll": null}, "v": 1.3109354866471308, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.28273229283386403, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3289877719315894, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137681.7775352} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2996391068852517, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137681.7775352} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.52997660636902, "x": 49.78768471945053, "y": 2.565806246331558, "z": null, "yaw": 0.9065975926822304, "pitch": null, "roll": null}, "v": 1.3109354866471308, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.28273229283386403, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3289877719315894, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137681.7975352} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2940037966503222, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137681.7975352} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.52997660636902, "x": 49.78768471945053, "y": 2.565806246331558, "z": null, "yaw": 0.9065975926822304, "pitch": null, "roll": null}, "v": 1.3109354866471308, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.28273229283386403, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3289877719315894, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137681.8175352} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2855668584419548, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137681.8175352} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.52997660636902, "x": 49.78768471945053, "y": 2.565806246331558, "z": null, "yaw": 0.9065975926822304, "pitch": null, "roll": null}, "v": 1.3109354866471308, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.28273229283386403, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3289877719315894, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137681.8375351} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2827588067979814, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137681.8375351} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137681.8475351, "x": 53.8742062428176, "y": 7.6792177625256395, "z": null, "yaw": 0.934202806883145, "pitch": null, "roll": null}, "v": 1.2799528803789406, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2803804377788505, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3212124857267166, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137681.8575351} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2188624959616542, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.275526296484522, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137681.8575351} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.639976501464844, "x": 49.8742062428176, "y": 2.6792177625256395, "z": null, "yaw": 0.934202806883145, "pitch": null, "roll": null}, "v": 1.2799528803789406, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2803804377788505, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3212124857267166, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137681.877535} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2165599655235195, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2739047426005807, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137681.877535} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.639976501464844, "x": 49.8742062428176, "y": 2.6792177625256395, "z": null, "yaw": 0.934202806883145, "pitch": null, "roll": null}, "v": 1.2799528803789406, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2803804377788505, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3212124857267166, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137681.897535} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2165599655235195, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2703775981916443, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137681.897535} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.639976501464844, "x": 49.8742062428176, "y": 2.6792177625256395, "z": null, "yaw": 0.934202806883145, "pitch": null, "roll": null}, "v": 1.2799528803789406, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2803804377788505, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3212124857267166, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137681.917535} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2165599655235195, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2650968500913276, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137681.917535} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.639976501464844, "x": 49.8742062428176, "y": 2.6792177625256395, "z": null, "yaw": 0.934202806883145, "pitch": null, "roll": null}, "v": 1.2799528803789406, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2803804377788505, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3212124857267166, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137681.947535} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2165599655235195, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2615829781197643, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137681.947535} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137681.957535, "x": 53.955864139873455, "y": 7.792617675412232, "z": null, "yaw": 0.9618080210840597, "pitch": null, "roll": null}, "v": 1.2598280253148562, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2788630677994301, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.31616202268302185, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137681.957535} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2282470128949103, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2588048329427937, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137681.957535} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.74997639656067, "x": 49.955864139873455, "y": 2.792617675412232, "z": null, "yaw": 0.9618080210840597, "pitch": null, "roll": null}, "v": 1.2598280253148562, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2788630677994301, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.31616202268302185, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137681.977535} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22256614026273383, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2577824098715102, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137681.977535} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.74997639656067, "x": 49.955864139873455, "y": 2.792617675412232, "z": null, "yaw": 0.9618080210840597, "pitch": null, "roll": null}, "v": 1.2598280253148562, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2788630677994301, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.31616202268302185, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137681.997535} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22256614026273383, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2550300261614773, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137681.997535} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.74997639656067, "x": 49.955864139873455, "y": 2.792617675412232, "z": null, "yaw": 0.9618080210840597, "pitch": null, "roll": null}, "v": 1.2598280253148562, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2788630677994301, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.31616202268302185, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137682.017535} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22256614026273383, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2509091976836826, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137682.017535} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.74997639656067, "x": 49.955864139873455, "y": 2.792617675412232, "z": null, "yaw": 0.9618080210840597, "pitch": null, "roll": null}, "v": 1.2598280253148562, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2788630677994301, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.31616202268302185, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137682.037535} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22256614026273383, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2495376494691766, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137682.037535} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.74997639656067, "x": 49.955864139873455, "y": 2.792617675412232, "z": null, "yaw": 0.9618080210840597, "pitch": null, "roll": null}, "v": 1.2598280253148562, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2788630677994301, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.31616202268302185, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137682.057535} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22256614026273383, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.244061732370224, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137682.057535} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137682.067535, "x": 54.033318823565445, "y": 7.906695620951988, "z": null, "yaw": 0.9894132352849744, "pitch": null, "roll": null}, "v": 1.2454291725724789, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27778239686756967, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.31254853709937863, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137682.077535} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.244061732370224, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137682.077535} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.859976291656494, "x": 50.033318823565445, "y": 2.9066956209519876, "z": null, "yaw": 0.9894132352849744, "pitch": null, "roll": null}, "v": 1.2454291725724789, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27778239686756967, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.31254853709937863, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137682.097535} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21696170980454588, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2385102112499957, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137682.097535} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.859976291656494, "x": 50.033318823565445, "y": 2.9066956209519876, "z": null, "yaw": 0.9894132352849744, "pitch": null, "roll": null}, "v": 1.2454291725724789, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27778239686756967, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.31254853709937863, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137682.1175349} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21696170980454588, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2350864134312665, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137682.1175349} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.859976291656494, "x": 50.033318823565445, "y": 2.9066956209519876, "z": null, "yaw": 0.9894132352849744, "pitch": null, "roll": null}, "v": 1.2454291725724789, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27778239686756967, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.31254853709937863, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137682.1375349} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21696170980454588, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2316677301460257, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137682.1375349} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.859976291656494, "x": 50.033318823565445, "y": 2.9066956209519876, "z": null, "yaw": 0.9894132352849744, "pitch": null, "roll": null}, "v": 1.2454291725724789, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27778239686756967, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.31254853709937863, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137682.1575348} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21696170980454588, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2265492680436427, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137682.1575348} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137682.1775348, "x": 54.106528882117765, "y": 8.02119711474481, "z": null, "yaw": 1.0170184494858892, "pitch": null, "roll": null}, "v": 1.224845657961711, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27624475175636215, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.30738297046448854, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137682.1775348} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22357768074456125, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.224845657961711, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137682.1775348} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.96997618675232, "x": 50.106528882117765, "y": 3.02119711474481, "z": null, "yaw": 1.0170184494858892, "pitch": null, "roll": null}, "v": 1.224845657961711, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27624475175636215, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.30738297046448854, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137682.1975348} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2203100628466202, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.222268933001399, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137682.1975348} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.96997618675232, "x": 50.106528882117765, "y": 3.02119711474481, "z": null, "yaw": 1.0170184494858892, "pitch": null, "roll": null}, "v": 1.224845657961711, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27624475175636215, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.30738297046448854, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137682.2175348} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2203100628466202, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2192877435249767, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137682.2175348} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.96997618675232, "x": 50.106528882117765, "y": 3.02119711474481, "z": null, "yaw": 1.0170184494858892, "pitch": null, "roll": null}, "v": 1.224845657961711, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27624475175636215, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.30738297046448854, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137682.2375348} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2203100628466202, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.216310988448001, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137682.2375348} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.96997618675232, "x": 50.106528882117765, "y": 3.02119711474481, "z": null, "yaw": 1.0170184494858892, "pitch": null, "roll": null}, "v": 1.224845657961711, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27624475175636215, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.30738297046448854, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137682.2575347} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2203100628466202, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2133386576313692, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137682.2575347} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.96997618675232, "x": 50.106528882117765, "y": 3.02119711474481, "z": null, "yaw": 1.0170184494858892, "pitch": null, "roll": null}, "v": 1.224845657961711, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27624475175636215, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.30738297046448854, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137682.2775347} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2203100628466202, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2103707409668492, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137682.2775347} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137682.2875347, "x": 54.17554116215263, "y": 8.13599870936084, "z": null, "yaw": 1.0446236636868038, "pitch": null, "roll": null}, "v": 1.2088884347912205, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2750585342172807, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.30337840170382313, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137682.2975347} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22387582345172358, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.205927120469173, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137682.2975347} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.079976081848145, "x": 50.17554116215263, "y": 3.1359987093608392, "z": null, "yaw": 1.0446236636868038, "pitch": null, "roll": null}, "v": 1.2088884347912205, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2750585342172807, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.30337840170382313, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137682.3175347} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22208746283866582, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.200684636962901, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137682.3175347} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.079976081848145, "x": 50.17554116215263, "y": 3.1359987093608392, "z": null, "yaw": 1.0446236636868038, "pitch": null, "roll": null}, "v": 1.2088884347912205, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2750585342172807, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.30337840170382313, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137682.3475347} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22208746283866582, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1993205967120923, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137682.3475347} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.079976081848145, "x": 50.17554116215263, "y": 3.1359987093608392, "z": null, "yaw": 1.0446236636868038, "pitch": null, "roll": null}, "v": 1.2088884347912205, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2750585342172807, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.30337840170382313, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137682.3675346} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22208746283866582, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1965955432633157, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137682.3675346} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.079976081848145, "x": 50.17554116215263, "y": 3.1359987093608392, "z": null, "yaw": 1.0446236636868038, "pitch": null, "roll": null}, "v": 1.2088884347912205, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2750585342172807, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.30337840170382313, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137682.3875346} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22208746283866582, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.193874518435535, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137682.3875346} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137682.3975346, "x": 54.24050777338204, "y": 8.251154121485314, "z": null, "yaw": 1.0722288778877185, "pitch": null, "roll": null}, "v": 1.193874518435535, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27394708957947356, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.29961056191297475, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137682.4075346} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1911575133124845, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137682.4075346} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.18997597694397, "x": 50.24050777338204, "y": 3.251154121485314, "z": null, "yaw": 1.0722288778877185, "pitch": null, "roll": null}, "v": 1.193874518435535, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27394708957947356, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.29961056191297475, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137682.4275346} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1884200489336763, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137682.4275346} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.18997597694397, "x": 50.24050777338204, "y": 3.251154121485314, "z": null, "yaw": 1.0722288778877185, "pitch": null, "roll": null}, "v": 1.193874518435535, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27394708957947356, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.29961056191297475, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137682.4475346} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1829511775874153, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137682.4475346} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.18997597694397, "x": 50.24050777338204, "y": 3.251154121485314, "z": null, "yaw": 1.0722288778877185, "pitch": null, "roll": null}, "v": 1.193874518435535, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27394708957947356, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.29961056191297475, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137682.4675345} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1774903628981541, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137682.4675345} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.18997597694397, "x": 50.24050777338204, "y": 3.251154121485314, "z": null, "yaw": 1.0722288778877185, "pitch": null, "roll": null}, "v": 1.193874518435535, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27394708957947356, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.29961056191297475, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137682.4875345} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1720375810731343, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137682.4875345} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137682.5075345, "x": 54.301275789854685, "y": 8.366167614068232, "z": null, "yaw": 1.0998340920886331, "pitch": null, "roll": null}, "v": 1.1665928084072361, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2719390282266366, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.29276403964844344, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137682.5075345} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2448650948823572, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.166677486555117, "gear": 1, "accelerator_pedal_position": 0.2448650948823572, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137682.5075345} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.299975872039795, "x": 50.301275789854685, "y": 3.3661676140682317, "z": null, "yaw": 1.0998340920886331, "pitch": null, "roll": null}, "v": 1.1665928084072361, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2719390282266366, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.29276403964844344, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137682.5275345} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22970304476413417, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1667621026062234, "gear": 1, "accelerator_pedal_position": 0.2448650948823572, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137682.5275345} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.299975872039795, "x": 50.301275789854685, "y": 3.3661676140682317, "z": null, "yaw": 1.0998340920886331, "pitch": null, "roll": null}, "v": 1.1665928084072361, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2719390282266366, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.29276403964844344, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137682.5475345} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22970304476413417, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1650365872013337, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137682.5475345} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.299975872039795, "x": 50.301275789854685, "y": 3.3661676140682317, "z": null, "yaw": 1.0998340920886331, "pitch": null, "roll": null}, "v": 1.1665928084072361, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2719390282266366, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.29276403964844344, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137682.5675344} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22970304476413417, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1633136007977924, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137682.5675344} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.299975872039795, "x": 50.301275789854685, "y": 3.3661676140682317, "z": null, "yaw": 1.0998340920886331, "pitch": null, "roll": null}, "v": 1.1665928084072361, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2719390282266366, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.29276403964844344, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137682.5875344} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22970304476413417, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1615931385019311, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137682.5875344} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.299975872039795, "x": 50.301275789854685, "y": 3.3661676140682317, "z": null, "yaw": 1.0998340920886331, "pitch": null, "roll": null}, "v": 1.1665928084072361, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2719390282266366, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.29276403964844344, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137682.6075344} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22970304476413417, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1598751954324678, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137682.6075344} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137682.6175344, "x": 54.3579330373304, "y": 8.480975675666793, "z": null, "yaw": 1.1274393062895478, "pitch": null, "roll": null}, "v": 1.159017167085612, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2713840662902722, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2908628832721458, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137682.6275344} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.157302993730341, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137682.6275344} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.40997576713562, "x": 50.3579330373304, "y": 3.4809756756667927, "z": null, "yaw": 1.1274393062895478, "pitch": null, "roll": null}, "v": 1.159017167085612, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2713840662902722, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2908628832721458, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137682.6475344} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1518798041070977, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137682.6475344} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.40997576713562, "x": 50.3579330373304, "y": 3.4809756756667927, "z": null, "yaw": 1.1274393062895478, "pitch": null, "roll": null}, "v": 1.159017167085612, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2713840662902722, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2908628832721458, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137682.6675344} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1491711814967331, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137682.6675344} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.40997576713562, "x": 50.3579330373304, "y": 3.4809756756667927, "z": null, "yaw": 1.1274393062895478, "pitch": null, "roll": null}, "v": 1.159017167085612, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2713840662902722, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2908628832721458, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137682.6875343} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1410571675077934, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137682.6875343} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.40997576713562, "x": 50.3579330373304, "y": 3.4809756756667927, "z": null, "yaw": 1.1274393062895478, "pitch": null, "roll": null}, "v": 1.159017167085612, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2713840662902722, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2908628832721458, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137682.7075343} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1356576740212554, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137682.7075343} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137682.7275343, "x": 54.410703859267464, "y": 8.595778165820356, "z": null, "yaw": 1.1550445204904625, "pitch": null, "roll": null}, "v": 1.1329608733489884, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26948404707284646, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.28432388718231444, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137682.7275343} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22627723865877294, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1329608733489884, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137682.7275343} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.519975662231445, "x": 50.410703859267464, "y": 3.595778165820356, "z": null, "yaw": 1.1550445204904625, "pitch": null, "roll": null}, "v": 1.1329608733489884, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26948404707284646, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.28432388718231444, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137682.7475343} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22081157373633736, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1298056273194215, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137682.7475343} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.519975662231445, "x": 50.410703859267464, "y": 3.595778165820356, "z": null, "yaw": 1.1550445204904625, "pitch": null, "roll": null}, "v": 1.1329608733489884, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26948404707284646, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.28432388718231444, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137682.7675343} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22081157373633736, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1270229864755505, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137682.7675343} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.519975662231445, "x": 50.410703859267464, "y": 3.595778165820356, "z": null, "yaw": 1.1550445204904625, "pitch": null, "roll": null}, "v": 1.1329608733489884, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26948404707284646, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.28432388718231444, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137682.7875342} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22081157373633736, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1256331802596293, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137682.7875342} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.519975662231445, "x": 50.410703859267464, "y": 3.595778165820356, "z": null, "yaw": 1.1550445204904625, "pitch": null, "roll": null}, "v": 1.1329608733489884, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26948404707284646, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.28432388718231444, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137682.8075342} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22081157373633736, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1228565906468295, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137682.8075342} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.519975662231445, "x": 50.410703859267464, "y": 3.595778165820356, "z": null, "yaw": 1.1550445204904625, "pitch": null, "roll": null}, "v": 1.1329608733489884, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26948404707284646, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.28432388718231444, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137682.8275342} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22081157373633736, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1200840240213668, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137682.8275342} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137682.8375342, "x": 54.45934059766865, "y": 8.709785788230123, "z": null, "yaw": 1.1826497346913771, "pitch": null, "roll": null}, "v": 1.1186992465457903, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2684498423695107, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.28074483933907995, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137682.8475342} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22434440213361323, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1159326977171162, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137682.8475342} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.62997555732727, "x": 50.45934059766865, "y": 3.709785788230123, "z": null, "yaw": 1.1826497346913771, "pitch": null, "roll": null}, "v": 1.1186992465457903, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2684498423695107, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.28074483933907995, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137682.8675342} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2225833054682449, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.114771725923025, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137682.8675342} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.62997555732727, "x": 50.45934059766865, "y": 3.709785788230123, "z": null, "yaw": 1.1826497346913771, "pitch": null, "roll": null}, "v": 1.1186992465457903, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2684498423695107, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.28074483933907995, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137682.8875341} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2225833054682449, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1122322423163473, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137682.8875341} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.62997555732727, "x": 50.45934059766865, "y": 3.709785788230123, "z": null, "yaw": 1.1826497346913771, "pitch": null, "roll": null}, "v": 1.1186992465457903, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2684498423695107, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.28074483933907995, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137682.9075341} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2225833054682449, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1096964273107295, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137682.9075341} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.62997555732727, "x": 50.45934059766865, "y": 3.709785788230123, "z": null, "yaw": 1.1826497346913771, "pitch": null, "roll": null}, "v": 1.1186992465457903, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2684498423695107, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.28074483933907995, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137682.927534} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2225833054682449, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.107164273035204, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137682.927534} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137682.947534, "x": 54.50422261043049, "y": 8.823598014959376, "z": null, "yaw": 1.2102549488922918, "pitch": null, "roll": null}, "v": 1.1046357716413036, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.267433990461961, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.277215519001375, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137682.947534} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2175777487101144, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1046357716413036, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137682.947534} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.739975452423096, "x": 50.50422261043049, "y": 3.8235980149593765, "z": null, "yaw": 1.2102549488922918, "pitch": null, "roll": null}, "v": 1.1046357716413036, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.267433990461961, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.277215519001375, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137682.967534} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21988395007784015, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1014854461595207, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137682.967534} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.739975452423096, "x": 50.50422261043049, "y": 3.8235980149593765, "z": null, "yaw": 1.2102549488922918, "pitch": null, "roll": null}, "v": 1.1046357716413036, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.267433990461961, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.277215519001375, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137682.987534} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21988395007784015, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0972005644224183, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137682.987534} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.739975452423096, "x": 50.50422261043049, "y": 3.8235980149593765, "z": null, "yaw": 1.2102549488922918, "pitch": null, "roll": null}, "v": 1.1046357716413036, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.267433990461961, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.277215519001375, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137683.007534} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21988395007784015, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.092924926016403, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137683.007534} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.739975452423096, "x": 50.50422261043049, "y": 3.8235980149593765, "z": null, "yaw": 1.2102549488922918, "pitch": null, "roll": null}, "v": 1.1046357716413036, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.267433990461961, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.277215519001375, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137683.027534} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21988395007784015, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.092924926016403, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137683.027534} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.739975452423096, "x": 50.50422261043049, "y": 3.8235980149593765, "z": null, "yaw": 1.2102549488922918, "pitch": null, "roll": null}, "v": 1.1046357716413036, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.267433990461961, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.277215519001375, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137683.047534} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21988395007784015, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0900796203331293, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137683.047534} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137683.057534, "x": 54.54538421276898, "y": 8.937055319833284, "z": null, "yaw": 1.2378601630932065, "pitch": null, "roll": null}, "v": 1.0886585000449611, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2662846982994495, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2732059189580729, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137683.067534} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22411967142940498, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0872383999418316, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137683.067534} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.84997534751892, "x": 50.54538421276898, "y": 3.9370553198332843, "z": null, "yaw": 1.2378601630932065, "pitch": null, "roll": null}, "v": 1.0886585000449611, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2662846982994495, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2732059189580729, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137683.087534} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22201509509352158, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0849305310542832, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137683.087534} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.84997534751892, "x": 50.54538421276898, "y": 3.9370553198332843, "z": null, "yaw": 1.2378601630932065, "pitch": null, "roll": null}, "v": 1.0886585000449611, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2662846982994495, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2732059189580729, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137683.107534} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22201509509352158, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0823629931680798, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137683.107534} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.84997534751892, "x": 50.54538421276898, "y": 3.9370553198332843, "z": null, "yaw": 1.2378601630932065, "pitch": null, "roll": null}, "v": 1.0886585000449611, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2662846982994495, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2732059189580729, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137683.127534} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22201509509352158, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0797991337639463, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137683.127534} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.84997534751892, "x": 50.54538421276898, "y": 3.9370553198332843, "z": null, "yaw": 1.2378601630932065, "pitch": null, "roll": null}, "v": 1.0886585000449611, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2662846982994495, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2732059189580729, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137683.147534} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22201509509352158, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0772389449433537, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137683.147534} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137683.1675339, "x": 54.58288100642708, "y": 9.050047507019993, "z": null, "yaw": 1.2654653772941211, "pitch": null, "roll": null}, "v": 1.0746824188303727, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2652835439549497, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.269698530634272, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137683.1675339} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22477210139335557, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0746824188303727, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137683.1675339} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.959975242614746, "x": 50.58288100642708, "y": 4.050047507019993, "z": null, "yaw": 1.2654653772941211, "pitch": null, "roll": null}, "v": 1.0746824188303727, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2652835439549497, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.269698530634272, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137683.1875339} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22338296213039413, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.072474050207333, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137683.1875339} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.959975242614746, "x": 50.58288100642708, "y": 4.050047507019993, "z": null, "yaw": 1.2654653772941211, "pitch": null, "roll": null}, "v": 1.0746824188303727, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2652835439549497, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.269698530634272, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137683.2075338} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22338296213039413, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0677198587255092, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137683.2075338} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.959975242614746, "x": 50.58288100642708, "y": 4.050047507019993, "z": null, "yaw": 1.2654653772941211, "pitch": null, "roll": null}, "v": 1.0746824188303727, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2652835439549497, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.269698530634272, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137683.2275338} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22338296213039413, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0677198587255092, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137683.2275338} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.959975242614746, "x": 50.58288100642708, "y": 4.050047507019993, "z": null, "yaw": 1.2654653772941211, "pitch": null, "roll": null}, "v": 1.0746824188303727, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2652835439549497, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.269698530634272, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137683.2475338} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22338296213039413, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0653478504210734, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137683.2475338} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.959975242614746, "x": 50.58288100642708, "y": 4.050047507019993, "z": null, "yaw": 1.2654653772941211, "pitch": null, "roll": null}, "v": 1.0746824188303727, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2652835439549497, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.269698530634272, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137683.2675338} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22338296213039413, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.062979224286872, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137683.2675338} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137683.2775338, "x": 54.61681807531633, "y": 9.162617072784697, "z": null, "yaw": 1.2930705914950358, "pitch": null, "roll": null}, "v": 1.0617961773247517, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26436392008805215, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.26646464466147757, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137683.2875338} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2257064965994222, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0606139732570208, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137683.2875338} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.06997513771057, "x": 50.61681807531633, "y": 4.1626170727846965, "z": null, "yaw": 1.2930705914950358, "pitch": null, "roll": null}, "v": 1.0617961773247517, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26436392008805215, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.26646464466147757, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137683.3075337} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22452998444611647, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.05854242871101, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137683.3075337} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.06997513771057, "x": 50.61681807531633, "y": 4.1626170727846965, "z": null, "yaw": 1.2930705914950358, "pitch": null, "roll": null}, "v": 1.0617961773247517, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26436392008805215, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.26646464466147757, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137683.3275337} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22452998444611647, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0563268205147776, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137683.3275337} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.06997513771057, "x": 50.61681807531633, "y": 4.1626170727846965, "z": null, "yaw": 1.2930705914950358, "pitch": null, "roll": null}, "v": 1.0617961773247517, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26436392008805215, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.26646464466147757, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137683.3475337} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22452998444611647, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0541143634591306, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137683.3475337} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.06997513771057, "x": 50.61681807531633, "y": 4.1626170727846965, "z": null, "yaw": 1.2930705914950358, "pitch": null, "roll": null}, "v": 1.0617961773247517, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26436392008805215, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.26646464466147757, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137683.3675337} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22452998444611647, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0519050511050796, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137683.3675337} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137683.3875337, "x": 54.647272120182734, "y": 9.274744730749342, "z": null, "yaw": 1.3206758056959504, "pitch": null, "roll": null}, "v": 1.0496988770311353, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26350362117596104, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.26342874860822235, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137683.3875337} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22409619521681412, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0496988770311353, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137683.3875337} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.179975032806396, "x": 50.647272120182734, "y": 4.274744730749342, "z": null, "yaw": 1.3206758056959504, "pitch": null, "roll": null}, "v": 1.0496988770311353, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26350362117596104, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.26342874860822235, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137683.4075336} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22423721500314908, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.045205207386829, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137683.4075336} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.179975032806396, "x": 50.647272120182734, "y": 4.274744730749342, "z": null, "yaw": 1.3206758056959504, "pitch": null, "roll": null}, "v": 1.0496988770311353, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26350362117596104, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.26342874860822235, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137683.4275336} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22423721500314908, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0440881853282775, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137683.4275336} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.179975032806396, "x": 50.647272120182734, "y": 4.274744730749342, "z": null, "yaw": 1.3206758056959504, "pitch": null, "roll": null}, "v": 1.0496988770311353, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26350362117596104, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.26342874860822235, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137683.4575336} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22423721500314908, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.03962800788993, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137683.4575336} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.179975032806396, "x": 50.647272120182734, "y": 4.274744730749342, "z": null, "yaw": 1.3206758056959504, "pitch": null, "roll": null}, "v": 1.0496988770311353, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26350362117596104, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.26342874860822235, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137683.4775336} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22423721500314908, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.03962800788993, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137683.4775336} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137683.4975336, "x": 54.67430364312668, "y": 9.386364982381933, "z": null, "yaw": 1.348281019896865, "pitch": null, "roll": null}, "v": 1.0374026543258323, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26263217538831446, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.26034293168420375, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137683.4975336} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22802823835200522, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0374026543258323, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137683.4975336} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.28997492790222, "x": 50.67430364312668, "y": 4.386364982381933, "z": null, "yaw": 1.348281019896865, "pitch": null, "roll": null}, "v": 1.0374026543258323, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26263217538831446, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.26034293168420375, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137683.5175335} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2261565923337603, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.035654159267531, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137683.5175335} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.28997492790222, "x": 50.67430364312668, "y": 4.386364982381933, "z": null, "yaw": 1.348281019896865, "pitch": null, "roll": null}, "v": 1.0374026543258323, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26263217538831446, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.26034293168420375, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137683.5375335} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2261565923337603, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0336742634146503, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137683.5375335} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.28997492790222, "x": 50.67430364312668, "y": 4.386364982381933, "z": null, "yaw": 1.348281019896865, "pitch": null, "roll": null}, "v": 1.0374026543258323, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26263217538831446, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.26034293168420375, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137683.5575335} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2261565923337603, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0307096640215194, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137683.5575335} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.28997492790222, "x": 50.67430364312668, "y": 4.386364982381933, "z": null, "yaw": 1.348281019896865, "pitch": null, "roll": null}, "v": 1.0374026543258323, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26263217538831446, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.26034293168420375, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137683.5775335} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2261565923337603, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0297228599692179, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137683.5775335} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.28997492790222, "x": 50.67430364312668, "y": 4.386364982381933, "z": null, "yaw": 1.348281019896865, "pitch": null, "roll": null}, "v": 1.0374026543258323, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26263217538831446, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.26034293168420375, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137683.5975335} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2261565923337603, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0277513413571735, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137683.5975335} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137683.6075335, "x": 54.697981345216164, "y": 9.497458437621557, "z": null, "yaw": 1.3758862340977798, "pitch": null, "roll": null}, "v": 1.0267666254253889, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2618808283021439, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2576737511747141, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137683.6175334} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2261179704718132, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0247992768869054, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137683.6175334} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.399974822998047, "x": 50.697981345216164, "y": 4.497458437621557, "z": null, "yaw": 1.3758862340977798, "pitch": null, "roll": null}, "v": 1.0267666254253889, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2618808283021439, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2576737511747141, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137683.6375334} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22607911632295613, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0238142290471595, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137683.6375334} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.399974822998047, "x": 50.697981345216164, "y": 4.497458437621557, "z": null, "yaw": 1.3758862340977798, "pitch": null, "roll": null}, "v": 1.0267666254253889, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2618808283021439, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2576737511747141, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137683.6575334} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22607911632295613, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0218413605932095, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137683.6575334} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.399974822998047, "x": 50.697981345216164, "y": 4.497458437621557, "z": null, "yaw": 1.3758862340977798, "pitch": null, "roll": null}, "v": 1.0267666254253889, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2618808283021439, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2576737511747141, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137683.6775334} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22607911632295613, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.019871270801423, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137683.6775334} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.399974822998047, "x": 50.697981345216164, "y": 4.497458437621557, "z": null, "yaw": 1.3758862340977798, "pitch": null, "roll": null}, "v": 1.0267666254253889, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2618808283021439, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2576737511747141, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137683.6975334} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22607911632295613, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0179039542062722, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137683.6975334} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137683.7175333, "x": 54.718367965779514, "y": 9.607993318996042, "z": null, "yaw": 1.4034914482986944, "pitch": null, "roll": null}, "v": 1.0159394053564774, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2611182990213846, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.25495659000014365, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137683.7175333} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22571141418344223, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0159394053564774, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137683.7175333} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.509974718093872, "x": 50.718367965779514, "y": 4.6079933189960425, "z": null, "yaw": 1.4034914482986944, "pitch": null, "roll": null}, "v": 1.0159394053564774, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2611182990213846, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.25495659000014365, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137683.7375333} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2258284130297894, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0139316722031895, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137683.7375333} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.509974718093872, "x": 50.718367965779514, "y": 4.6079933189960425, "z": null, "yaw": 1.4034914482986944, "pitch": null, "roll": null}, "v": 1.0159394053564774, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2611182990213846, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.25495659000014365, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137683.7575333} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2258284130297894, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0119413801942492, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137683.7575333} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.509974718093872, "x": 50.718367965779514, "y": 4.6079933189960425, "z": null, "yaw": 1.4034914482986944, "pitch": null, "roll": null}, "v": 1.0159394053564774, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2611182990213846, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.25495659000014365, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137683.7775333} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2258284130297894, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0099538835149329, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137683.7775333} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.509974718093872, "x": 50.718367965779514, "y": 4.6079933189960425, "z": null, "yaw": 1.4034914482986944, "pitch": null, "roll": null}, "v": 1.0159394053564774, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2611182990213846, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.25495659000014365, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137683.7975333} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2258284130297894, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0079691766597467, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137683.7975333} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.509974718093872, "x": 50.718367965779514, "y": 4.6079933189960425, "z": null, "yaw": 1.4034914482986944, "pitch": null, "roll": null}, "v": 1.0159394053564774, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2611182990213846, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.25495659000014365, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137683.8175333} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2258284130297894, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0059872541375774, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137683.8175333} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137683.8275332, "x": 54.73551125438063, "y": 9.717865232728295, "z": null, "yaw": 1.431096662499609, "pitch": null, "roll": null}, "v": 1.0049973352893218, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26035006320385246, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2522106064728232, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137683.8375332} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2254777651793245, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0040081104716452, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137683.8375332} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.619974613189697, "x": 50.73551125438063, "y": 4.717865232728295, "z": null, "yaw": 1.431096662499609, "pitch": null, "roll": null}, "v": 1.0049973352893218, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26035006320385246, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2522106064728232, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137683.8575332} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2255862081476202, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.001987924572179, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137683.8575332} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.619974613189697, "x": 50.73551125438063, "y": 4.717865232728295, "z": null, "yaw": 1.431096662499609, "pitch": null, "roll": null}, "v": 1.0049973352893218, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26035006320385246, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2522106064728232, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137683.8775332} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2255862081476202, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9999841185816446, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137683.8775332} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.619974613189697, "x": 50.73551125438063, "y": 4.717865232728295, "z": null, "yaw": 1.431096662499609, "pitch": null, "roll": null}, "v": 1.0049973352893218, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26035006320385246, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2522106064728232, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137683.8975332} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2255862081476202, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9979831173262949, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137683.8975332} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.619974613189697, "x": 50.73551125438063, "y": 4.717865232728295, "z": null, "yaw": 1.431096662499609, "pitch": null, "roll": null}, "v": 1.0049973352893218, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26035006320385246, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2522106064728232, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137683.9175332} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2255862081476202, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9959849152792881, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137683.9175332} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137683.9375331, "x": 54.74946245374451, "y": 9.826972262133442, "z": null, "yaw": 1.4587018767005238, "pitch": null, "roll": null}, "v": 0.9939895069282345, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2595796267452461, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2494481204746893, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137683.9375331} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23377489275994073, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9939895069282345, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137683.9375331} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.729974508285522, "x": 50.74946245374451, "y": 4.826972262133442, "z": null, "yaw": 1.4587018767005238, "pitch": null, "roll": null}, "v": 0.9939895069282345, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2595796267452461, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2494481204746893, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137683.9575331} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22981681723713882, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9918046969904895, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137683.9575331} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.729974508285522, "x": 50.74946245374451, "y": 4.826972262133442, "z": null, "yaw": 1.4587018767005238, "pitch": null, "roll": null}, "v": 0.9939895069282345, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2595796267452461, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2494481204746893, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137683.977533} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22981681723713882, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9918046969904895, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137683.977533} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.729974508285522, "x": 50.74946245374451, "y": 4.826972262133442, "z": null, "yaw": 1.4587018767005238, "pitch": null, "roll": null}, "v": 0.9939895069282345, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2595796267452461, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2494481204746893, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137684.007533} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22981681723713882, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9881562002506666, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137684.007533} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.729974508285522, "x": 50.74946245374451, "y": 4.826972262133442, "z": null, "yaw": 1.4587018767005238, "pitch": null, "roll": null}, "v": 0.9939895069282345, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2595796267452461, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2494481204746893, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137684.027533} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22981681723713882, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9881562002506666, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137684.027533} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137684.047533, "x": 54.76029698227533, "y": 9.935432579716261, "z": null, "yaw": 1.4863070909014384, "pitch": null, "roll": null}, "v": 0.986700363612554, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2590707942561592, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24761886263313906, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137684.057533} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23320974865546412, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9859732067473136, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137684.057533} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.839974403381348, "x": 50.76029698227533, "y": 4.935432579716261, "z": null, "yaw": 1.4863070909014384, "pitch": null, "roll": null}, "v": 0.986700363612554, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2590707942561592, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24761886263313906, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137684.077533} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23155529801157507, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9849443822336602, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137684.077533} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.839974403381348, "x": 50.76029698227533, "y": 4.935432579716261, "z": null, "yaw": 1.4863070909014384, "pitch": null, "roll": null}, "v": 0.986700363612554, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2590707942561592, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24761886263313906, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137684.097533} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23155529801157507, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9837102572131787, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137684.097533} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.839974403381348, "x": 50.76029698227533, "y": 4.935432579716261, "z": null, "yaw": 1.4863070909014384, "pitch": null, "roll": null}, "v": 0.986700363612554, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2590707942561592, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24761886263313906, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137684.117533} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23155529801157507, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9824778514794422, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137684.117533} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.839974403381348, "x": 50.76029698227533, "y": 4.935432579716261, "z": null, "yaw": 1.4863070909014384, "pitch": null, "roll": null}, "v": 0.986700363612554, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2590707942561592, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24761886263313906, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137684.137533} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23155529801157507, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9812471620299563, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137684.137533} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137684.157533, "x": 54.768076049603806, "y": 10.043353448796593, "z": null, "yaw": 1.513912305102353, "pitch": null, "roll": null}, "v": 0.9800181858689456, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2586052657397859, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2459419267427673, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137684.157533} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2227116511042459, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9800181858689456, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137684.157533} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.949974298477173, "x": 50.768076049603806, "y": 5.0433534487965925, "z": null, "yaw": 1.513912305102353, "pitch": null, "roll": null}, "v": 0.9800181858689456, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2586052657397859, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2459419267427673, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137684.177533} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22688744478295605, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9776858487461606, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137684.177533} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.949974298477173, "x": 50.768076049603806, "y": 5.0433534487965925, "z": null, "yaw": 1.513912305102353, "pitch": null, "roll": null}, "v": 0.9800181858689456, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2586052657397859, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2459419267427673, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137684.197533} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22688744478295605, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9758785482307716, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137684.197533} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.949974298477173, "x": 50.768076049603806, "y": 5.0433534487965925, "z": null, "yaw": 1.513912305102353, "pitch": null, "roll": null}, "v": 0.9800181858689456, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2586052657397859, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2459419267427673, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137684.2175329} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22688744478295605, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9740737599513264, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137684.2175329} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.949974298477173, "x": 50.768076049603806, "y": 5.0433534487965925, "z": null, "yaw": 1.513912305102353, "pitch": null, "roll": null}, "v": 0.9800181858689456, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2586052657397859, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2459419267427673, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137684.2375329} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22688744478295605, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9722714791132424, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137684.2375329} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.949974298477173, "x": 50.768076049603806, "y": 5.0433534487965925, "z": null, "yaw": 1.513912305102353, "pitch": null, "roll": null}, "v": 0.9800181858689456, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2586052657397859, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2459419267427673, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137684.2575328} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22688744478295605, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9704717009340276, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137684.2575328} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137684.2675328, "x": 54.77283222448061, "y": 10.150500085625293, "z": null, "yaw": 1.5415175193032677, "pitch": null, "roll": null}, "v": 0.9695727488502639, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25787935059564376, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24332057650346844, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137684.2775328} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2359408905799099, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9686744206432422, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137684.2775328} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.059974193572998, "x": 50.77283222448061, "y": 5.150500085625293, "z": null, "yaw": 1.5415175193032677, "pitch": null, "roll": null}, "v": 0.9695727488502639, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25787935059564376, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24332057650346844, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137684.2975328} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23157441591294287, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9680109217334563, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137684.2975328} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.059974193572998, "x": 50.77283222448061, "y": 5.150500085625293, "z": null, "yaw": 1.5415175193032677, "pitch": null, "roll": null}, "v": 0.9695727488502639, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25787935059564376, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24332057650346844, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137684.3175328} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23157441591294287, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.96619925176805, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137684.3175328} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.059974193572998, "x": 50.77283222448061, "y": 5.150500085625293, "z": null, "yaw": 1.5415175193032677, "pitch": null, "roll": null}, "v": 0.9695727488502639, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25787935059564376, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24332057650346844, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137684.3275328} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23157441591294287, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.96619925176805, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137684.3275328} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.059974193572998, "x": 50.77283222448061, "y": 5.150500085625293, "z": null, "yaw": 1.5415175193032677, "pitch": null, "roll": null}, "v": 0.9695727488502639, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25787935059564376, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24332057650346844, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137684.3575327} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23157441591294287, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9643913472848678, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137684.3575327} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137684.3775327, "x": 54.77461278034805, "y": 10.256819627645475, "z": null, "yaw": 1.5691227335041824, "pitch": null, "roll": null}, "v": 0.9631881647303075, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25743672264328077, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2417183236651488, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137684.3775327} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22693944193528523, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9631881647303075, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137684.3775327} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.169974088668823, "x": 50.77461278034805, "y": 5.256819627645475, "z": null, "yaw": 1.5691227335041824, "pitch": null, "roll": null}, "v": 0.9631881647303075, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25743672264328077, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2417183236651488, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137684.3975327} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22911284945208274, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9614074773391926, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137684.3975327} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.169974088668823, "x": 50.77461278034805, "y": 5.256819627645475, "z": null, "yaw": 1.5691227335041824, "pitch": null, "roll": null}, "v": 0.9631881647303075, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25743672264328077, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2417183236651488, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137684.4175327} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22911284945208274, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9599008368093168, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137684.4175327} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.169974088668823, "x": 50.77461278034805, "y": 5.256819627645475, "z": null, "yaw": 1.5691227335041824, "pitch": null, "roll": null}, "v": 0.9631881647303075, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25743672264328077, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2417183236651488, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137684.4375327} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22911284945208274, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9583962809156563, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137684.4375327} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.169974088668823, "x": 50.77461278034805, "y": 5.256819627645475, "z": null, "yaw": 1.5691227335041824, "pitch": null, "roll": null}, "v": 0.9631881647303075, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25743672264328077, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2417183236651488, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137684.4575326} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22911284945208274, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9568938058686792, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137684.4575326} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.169974088668823, "x": 50.77461278034805, "y": 5.256819627645475, "z": null, "yaw": 1.5691227335041824, "pitch": null, "roll": null}, "v": 0.9631881647303075, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25743672264328077, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2417183236651488, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137684.4775326} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22911284945208274, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9553934078878507, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137684.4775326} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137684.4875326, "x": 54.773467615854464, "y": 10.362320768245528, "z": null, "yaw": 1.596727947705097, "pitch": null, "roll": null}, "v": 0.9546439866182783, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2568456507427783, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2395741066928458, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137684.4975326} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22902669167305573, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9538950832016057, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137684.4975326} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.27997398376465, "x": 50.773467615854464, "y": 5.362320768245528, "z": null, "yaw": 1.596727947705097, "pitch": null, "roll": null}, "v": 0.9546439866182783, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2568456507427783, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2395741066928458, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137684.5175326} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2290226851353146, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9523880620438854, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137684.5175326} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.27997398376465, "x": 50.773467615854464, "y": 5.362320768245528, "z": null, "yaw": 1.596727947705097, "pitch": null, "roll": null}, "v": 0.9546439866182783, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2568456507427783, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2395741066928458, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137684.5375326} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2290226851353146, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9508826208790994, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137684.5375326} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.27997398376465, "x": 50.773467615854464, "y": 5.362320768245528, "z": null, "yaw": 1.596727947705097, "pitch": null, "roll": null}, "v": 0.9546439866182783, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2568456507427783, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2395741066928458, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137684.5575325} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2290226851353146, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9493792572640639, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137684.5575325} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.27997398376465, "x": 50.773467615854464, "y": 5.362320768245528, "z": null, "yaw": 1.596727947705097, "pitch": null, "roll": null}, "v": 0.9546439866182783, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2568456507427783, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2395741066928458, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137684.5775325} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2290226851353146, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9478779674279748, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137684.5775325} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137684.5975325, "x": 54.7694459634849, "y": 10.466837434492836, "z": null, "yaw": 1.6243331619060117, "pitch": null, "roll": null}, "v": 0.9463787476089692, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2562752647197077, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.23749989129944818, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137684.5975325} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23356899123305275, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9463787476089692, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137684.5975325} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.389973878860474, "x": 50.7694459634849, "y": 5.466837434492836, "z": null, "yaw": 1.6243331619060117, "pitch": null, "roll": null}, "v": 0.9463787476089692, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2562752647197077, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.23749989129944818, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137684.6175325} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23136062448157732, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.94544968649714, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137684.6175325} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.389973878860474, "x": 50.7694459634849, "y": 5.466837434492836, "z": null, "yaw": 1.6243331619060117, "pitch": null, "roll": null}, "v": 0.9463787476089692, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2562752647197077, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.23749989129944818, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137684.6375325} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23136062448157732, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9442459546953205, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137684.6375325} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.389973878860474, "x": 50.7694459634849, "y": 5.466837434492836, "z": null, "yaw": 1.6243331619060117, "pitch": null, "roll": null}, "v": 0.9463787476089692, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2562752647197077, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.23749989129944818, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137684.6575325} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23136062448157732, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9430438808465169, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137684.6575325} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.389973878860474, "x": 50.7694459634849, "y": 5.466837434492836, "z": null, "yaw": 1.6243331619060117, "pitch": null, "roll": null}, "v": 0.9463787476089692, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2562752647197077, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.23749989129944818, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137684.6775324} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23136062448157732, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9418434620893636, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137684.6775324} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.389973878860474, "x": 50.7694459634849, "y": 5.466837434492836, "z": null, "yaw": 1.6243331619060117, "pitch": null, "roll": null}, "v": 0.9463787476089692, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2562752647197077, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.23749989129944818, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137684.6975324} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23136062448157732, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9406446955688215, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137684.6975324} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137684.7075324, "x": 54.76259338849607, "y": 10.57040471335884, "z": null, "yaw": 1.6519383761069264, "pitch": null, "roll": null}, "v": 0.9400459310068054, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2558391600743648, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2359106298558314, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137684.7175324} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23695705843574688, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9394475784361603, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137684.7175324} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.4999737739563, "x": 50.76259338849607, "y": 5.57040471335884, "z": null, "yaw": 1.6519383761069264, "pitch": null, "roll": null}, "v": 0.9400459310068054, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2558391600743648, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2359106298558314, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137684.7375324} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23425886151767755, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9389514215147927, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137684.7375324} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.4999737739563, "x": 50.76259338849607, "y": 5.57040471335884, "z": null, "yaw": 1.6519383761069264, "pitch": null, "roll": null}, "v": 0.9400459310068054, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2558391600743648, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2359106298558314, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137684.7575324} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23425886151767755, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9377029010129289, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137684.7575324} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.4999737739563, "x": 50.76259338849607, "y": 5.57040471335884, "z": null, "yaw": 1.6519383761069264, "pitch": null, "roll": null}, "v": 0.9400459310068054, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2558391600743648, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2359106298558314, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137684.7775323} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23425886151767755, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9372872997342204, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137684.7775323} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.4999737739563, "x": 50.76259338849607, "y": 5.57040471335884, "z": null, "yaw": 1.6519383761069264, "pitch": null, "roll": null}, "v": 0.9400459310068054, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2558391600743648, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2359106298558314, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137684.7975323} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23425886151767755, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9364569541222738, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137684.7975323} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137684.8175323, "x": 54.752941367956645, "y": 10.67313563006347, "z": null, "yaw": 1.679543590307841, "pitch": null, "roll": null}, "v": 0.9356277495658021, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25553538033586576, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.23480185853712773, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137684.8175323} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24685440657739507, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9360007961735306, "gear": 1, "accelerator_pedal_position": 0.24685440657739507, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137684.8175323} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.609973669052124, "x": 50.752941367956645, "y": 5.67313563006347, "z": null, "yaw": 1.679543590307841, "pitch": null, "roll": null}, "v": 0.9356277495658021, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25553538033586576, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.23480185853712773, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137684.8375323} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2408333798468304, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9363735864374872, "gear": 1, "accelerator_pedal_position": 0.24685440657739507, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137684.8375323} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.609973669052124, "x": 50.752941367956645, "y": 5.67313563006347, "z": null, "yaw": 1.679543590307841, "pitch": null, "roll": null}, "v": 0.9356277495658021, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25553538033586576, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.23480185853712773, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137684.8575323} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2408333798468304, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9363660288311951, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137684.8575323} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.609973669052124, "x": 50.752941367956645, "y": 5.67313563006347, "z": null, "yaw": 1.679543590307841, "pitch": null, "roll": null}, "v": 0.9356277495658021, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25553538033586576, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.23480185853712773, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137684.8775322} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2408333798468304, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9363584816096195, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137684.8775322} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.609973669052124, "x": 50.752941367956645, "y": 5.67313563006347, "z": null, "yaw": 1.679543590307841, "pitch": null, "roll": null}, "v": 0.9356277495658021, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25553538033586576, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.23480185853712773, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137684.8975322} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2408333798468304, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9363509447584684, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137684.8975322} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.609973669052124, "x": 50.752941367956645, "y": 5.67313563006347, "z": null, "yaw": 1.679543590307841, "pitch": null, "roll": null}, "v": 0.9356277495658021, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25553538033586576, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.23480185853712773, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137684.9175322} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2408333798468304, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9363434182634691, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137684.9175322} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137684.9275322, "x": 54.74048024299335, "y": 10.775364265076322, "z": null, "yaw": 1.7071488045087557, "pitch": null, "roll": null}, "v": 0.9363396588950718, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.255584302512951, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.23498051680554702, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137684.9375322} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.217459509079747, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9363359021103691, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137684.9375322} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.71997356414795, "x": 50.74048024299335, "y": 5.7753642650763215, "z": null, "yaw": 1.7071488045087557, "pitch": null, "roll": null}, "v": 0.9363396588950718, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.255584302512951, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.23498051680554702, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137684.9575322} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22859365669670068, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9334076662304309, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137684.9575322} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.71997356414795, "x": 50.74048024299335, "y": 5.7753642650763215, "z": null, "yaw": 1.7071488045087557, "pitch": null, "roll": null}, "v": 0.9363396588950718, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.255584302512951, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.23498051680554702, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137684.9775321} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22859365669670068, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9318747421143143, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137684.9775321} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.71997356414795, "x": 50.74048024299335, "y": 5.7753642650763215, "z": null, "yaw": 1.7071488045087557, "pitch": null, "roll": null}, "v": 0.9363396588950718, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.255584302512951, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.23498051680554702, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137684.9975321} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22859365669670068, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9303439218323482, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137684.9975321} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.71997356414795, "x": 50.74048024299335, "y": 5.7753642650763215, "z": null, "yaw": 1.7071488045087557, "pitch": null, "roll": null}, "v": 0.9363396588950718, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.255584302512951, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.23498051680554702, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137685.017532} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22859365669670068, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.928051627735019, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137685.017532} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.71997356414795, "x": 50.74048024299335, "y": 5.7753642650763215, "z": null, "yaw": 1.7071488045087557, "pitch": null, "roll": null}, "v": 0.9363396588950718, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.255584302512951, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.23498051680554702, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137685.027532} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22859365669670068, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.928051627735019, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137685.027532} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137685.037532, "x": 54.72527213672508, "y": 10.876760564452901, "z": null, "yaw": 1.7347540187096704, "pitch": null, "roll": null}, "v": 0.9272885774823212, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25496306993340795, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2327090891587388, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137685.057532} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23323921670997472, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9257640457927181, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137685.057532} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.829973459243774, "x": 50.72527213672508, "y": 5.876760564452901, "z": null, "yaw": 1.7347540187096704, "pitch": null, "roll": null}, "v": 0.9272885774823212, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25496306993340795, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2327090891587388, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137685.077532} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23097971214030064, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9248220987991691, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137685.077532} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.829973459243774, "x": 50.72527213672508, "y": 5.876760564452901, "z": null, "yaw": 1.7347540187096704, "pitch": null, "roll": null}, "v": 0.9272885774823212, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25496306993340795, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2327090891587388, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137685.097532} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23097971214030064, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9235991004962516, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137685.097532} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.829973459243774, "x": 50.72527213672508, "y": 5.876760564452901, "z": null, "yaw": 1.7347540187096704, "pitch": null, "roll": null}, "v": 0.9272885774823212, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25496306993340795, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2327090891587388, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137685.117532} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23097971214030064, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9223777765918192, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137685.117532} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.829973459243774, "x": 50.72527213672508, "y": 5.876760564452901, "z": null, "yaw": 1.7347540187096704, "pitch": null, "roll": null}, "v": 0.9272885774823212, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25496306993340795, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2327090891587388, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137685.137532} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23097971214030064, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9211581241970157, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137685.137532} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137685.147532, "x": 54.70742415490982, "y": 10.976836223845178, "z": null, "yaw": 1.762359232910585, "pitch": null, "roll": null}, "v": 0.9205489239147086, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2545015494089407, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.23101772933715783, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137685.157532} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2357219080626298, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.919940140429388, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137685.157532} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.9399733543396, "x": 50.70742415490982, "y": 5.9768362238451775, "z": null, "yaw": 1.762359232910585, "pitch": null, "roll": null}, "v": 0.9205489239147086, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2545015494089407, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.23101772933715783, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137685.177532} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23342855491402642, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9193163942051095, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137685.177532} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.9399733543396, "x": 50.70742415490982, "y": 5.9768362238451775, "z": null, "yaw": 1.762359232910585, "pitch": null, "roll": null}, "v": 0.9205489239147086, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2545015494089407, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.23101772933715783, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137685.197532} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23342855491402642, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9184069297089821, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137685.197532} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.9399733543396, "x": 50.70742415490982, "y": 5.9768362238451775, "z": null, "yaw": 1.762359232910585, "pitch": null, "roll": null}, "v": 0.9205489239147086, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2545015494089407, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.23101772933715783, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137685.217532} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23342855491402642, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9174987084383311, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137685.217532} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.9399733543396, "x": 50.70742415490982, "y": 5.9768362238451775, "z": null, "yaw": 1.762359232910585, "pitch": null, "roll": null}, "v": 0.9205489239147086, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2545015494089407, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.23101772933715783, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137685.237532} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23342855491402642, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9165917283638508, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137685.237532} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137685.257532, "x": 54.68694972344385, "y": 11.075755644563404, "z": null, "yaw": 1.7899644471114997, "pitch": null, "roll": null}, "v": 0.9156859874603611, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25416910764933065, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.22979734386017878, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137685.257532} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22913325247327376, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9156859874603611, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137685.257532} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.049973249435425, "x": 50.68694972344385, "y": 6.0757556445634044, "z": null, "yaw": 1.7899644471114997, "pitch": null, "roll": null}, "v": 0.9156859874603611, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25416910764933065, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.22979734386017878, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137685.2775319} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23115330670105294, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9142447542627602, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137685.2775319} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.049973249435425, "x": 50.68694972344385, "y": 6.0757556445634044, "z": null, "yaw": 1.7899644471114997, "pitch": null, "roll": null}, "v": 0.9156859874603611, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25416910764933065, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.22979734386017878, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137685.2975318} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23115330670105294, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9130579094729968, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137685.2975318} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.049973249435425, "x": 50.68694972344385, "y": 6.0757556445634044, "z": null, "yaw": 1.7899644471114997, "pitch": null, "roll": null}, "v": 0.9156859874603611, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25416910764933065, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.22979734386017878, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137685.3175318} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23115330670105294, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9112806787262618, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137685.3175318} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.049973249435425, "x": 50.68694972344385, "y": 6.0757556445634044, "z": null, "yaw": 1.7899644471114997, "pitch": null, "roll": null}, "v": 0.9156859874603611, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25416910764933065, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.22979734386017878, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137685.3375318} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23115330670105294, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9106890768081726, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137685.3375318} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.049973249435425, "x": 50.68694972344385, "y": 6.0757556445634044, "z": null, "yaw": 1.7899644471114997, "pitch": null, "roll": null}, "v": 0.9156859874603611, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25416910764933065, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.22979734386017878, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137685.3475318} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23115330670105294, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9100978784791225, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137685.3475318} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137685.3675318, "x": 54.6639011322738, "y": 11.173445477539664, "z": null, "yaw": 1.8175696613124144, "pitch": null, "roll": null}, "v": 0.9089166912075021, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25370713007593104, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.22809854501427304, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137685.3675318} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23590452398977702, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9080381747405936, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137685.3675318} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.15997314453125, "x": 50.6639011322738, "y": 6.173445477539664, "z": null, "yaw": 1.8175696613124144, "pitch": null, "roll": null}, "v": 0.9089166912075021, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25370713007593104, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.22809854501427304, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137685.3975317} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23360684012747496, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9077457350699057, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137685.3975317} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.15997314453125, "x": 50.6639011322738, "y": 6.173445477539664, "z": null, "yaw": 1.8175696613124144, "pitch": null, "roll": null}, "v": 0.9089166912075021, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25370713007593104, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.22809854501427304, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137685.4175317} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23360684012747496, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9060041339297035, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137685.4175317} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.15997314453125, "x": 50.6639011322738, "y": 6.173445477539664, "z": null, "yaw": 1.8175696613124144, "pitch": null, "roll": null}, "v": 0.9089166912075021, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25370713007593104, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.22809854501427304, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137685.4475317} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23360684012747496, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9051351121846832, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137685.4475317} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137685.4775317, "x": 54.63831439636545, "y": 11.26989603610667, "z": null, "yaw": 1.845174875513329, "pitch": null, "roll": null}, "v": 0.9047010451794271, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25341989207045884, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.22704060127245262, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137685.4775317} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23449977951759138, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.904323082478572, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137685.4775317} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.269973039627075, "x": 50.63831439636545, "y": 6.269896036106671, "z": null, "yaw": 1.845174875513329, "pitch": null, "roll": null}, "v": 0.9047010451794271, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25341989207045884, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.22704060127245262, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137685.4975317} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23405268526044257, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9039453771334318, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137685.4975317} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.269973039627075, "x": 50.63831439636545, "y": 6.269896036106671, "z": null, "yaw": 1.845174875513329, "pitch": null, "roll": null}, "v": 0.9047010451794271, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25341989207045884, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.22704060127245262, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137685.5175316} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23405268526044257, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9031348699346131, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137685.5175316} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.269973039627075, "x": 50.63831439636545, "y": 6.269896036106671, "z": null, "yaw": 1.845174875513329, "pitch": null, "roll": null}, "v": 0.9047010451794271, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25341989207045884, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.22704060127245262, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137685.5375316} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23405268526044257, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9023254657321185, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137685.5375316} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.269973039627075, "x": 50.63831439636545, "y": 6.269896036106671, "z": null, "yaw": 1.845174875513329, "pitch": null, "roll": null}, "v": 0.9047010451794271, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25341989207045884, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.22704060127245262, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137685.5575316} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23405268526044257, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9015171627629466, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137685.5575316} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.269973039627075, "x": 50.63831439636545, "y": 6.269896036106671, "z": null, "yaw": 1.845174875513329, "pitch": null, "roll": null}, "v": 0.9047010451794271, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25341989207045884, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.22704060127245262, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137685.5775316} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23405268526044257, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9007099592675637, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137685.5775316} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137685.5875316, "x": 54.61021399649361, "y": 11.365133425003426, "z": null, "yaw": 1.8727800897142437, "pitch": null, "roll": null}, "v": 0.9003067692736352, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2531208612516811, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.22593782920302258, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137685.5975316} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23103672324680924, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.899903853489896, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137685.5975316} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.3799729347229, "x": 50.61021399649361, "y": 6.365133425003426, "z": null, "yaw": 1.8727800897142437, "pitch": null, "roll": null}, "v": 0.9003067692736352, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2531208612516811, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.22593782920302258, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137685.6175315} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23245011303982532, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8987219765816448, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137685.6175315} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.3799729347229, "x": 50.61021399649361, "y": 6.365133425003426, "z": null, "yaw": 1.8727800897142437, "pitch": null, "roll": null}, "v": 0.9003067692736352, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2531208612516811, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.22593782920302258, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137685.6375315} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23245011303982532, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8977183197026383, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137685.6375315} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.3799729347229, "x": 50.61021399649361, "y": 6.365133425003426, "z": null, "yaw": 1.8727800897142437, "pitch": null, "roll": null}, "v": 0.9003067692736352, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2531208612516811, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.22593782920302258, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137685.6575315} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23245011303982532, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8967160265182078, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137685.6575315} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.3799729347229, "x": 50.61021399649361, "y": 6.365133425003426, "z": null, "yaw": 1.8727800897142437, "pitch": null, "roll": null}, "v": 0.9003067692736352, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2531208612516811, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.22593782920302258, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137685.6775315} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23245011303982532, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.895715094773766, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137685.6775315} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137685.6975315, "x": 54.579665102579334, "y": 11.459038863528107, "z": null, "yaw": 1.9003853039151584, "pitch": null, "roll": null}, "v": 0.894715522219425, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25274093476797505, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2245346694522798, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137685.6975315} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2361985844062649, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.894715522219425, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137685.6975315} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.489972829818726, "x": 50.579665102579334, "y": 6.459038863528107, "z": null, "yaw": 1.9003853039151584, "pitch": null, "roll": null}, "v": 0.894715522219425, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25274093476797505, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2245346694522798, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137685.7175314} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23438465035544342, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8941857064862704, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137685.7175314} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.489972829818726, "x": 50.579665102579334, "y": 6.459038863528107, "z": null, "yaw": 1.9003853039151584, "pitch": null, "roll": null}, "v": 0.894715522219425, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25274093476797505, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2245346694522798, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137685.7375314} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23438465035544342, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8934299450509469, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137685.7375314} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.489972829818726, "x": 50.579665102579334, "y": 6.459038863528107, "z": null, "yaw": 1.9003853039151584, "pitch": null, "roll": null}, "v": 0.894715522219425, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25274093476797505, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2245346694522798, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137685.7575314} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23438465035544342, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8922982253137218, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137685.7575314} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.489972829818726, "x": 50.579665102579334, "y": 6.459038863528107, "z": null, "yaw": 1.9003853039151584, "pitch": null, "roll": null}, "v": 0.894715522219425, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25274093476797505, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2245346694522798, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137685.7775314} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23438465035544342, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8919214972359903, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137685.7775314} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.489972829818726, "x": 50.579665102579334, "y": 6.459038863528107, "z": null, "yaw": 1.9003853039151584, "pitch": null, "roll": null}, "v": 0.894715522219425, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25274093476797505, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2245346694522798, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137685.7975314} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23438465035544342, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8911688076205966, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137685.7975314} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137685.8075314, "x": 54.54670999884047, "y": 11.551575227760157, "z": null, "yaw": 1.927990518116073, "pitch": null, "roll": null}, "v": 0.8907928456796339, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2524747612231219, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.22355024830571765, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137685.8175313} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23715168862250757, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8902146264160756, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137685.8175313} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.59997272491455, "x": 50.54670999884047, "y": 6.551575227760157, "z": null, "yaw": 1.927990518116073, "pitch": null, "roll": null}, "v": 0.8907928456796339, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2524747612231219, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.22355024830571765, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137685.8375313} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23581377079499694, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8900122514336658, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137685.8375313} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.59997272491455, "x": 50.54670999884047, "y": 6.551575227760157, "z": null, "yaw": 1.927990518116073, "pitch": null, "roll": null}, "v": 0.8907928456796339, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2524747612231219, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.22355024830571765, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137685.8575313} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23581377079499694, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8888699831397389, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137685.8575313} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.59997272491455, "x": 50.54670999884047, "y": 6.551575227760157, "z": null, "yaw": 1.927990518116073, "pitch": null, "roll": null}, "v": 0.8907928456796339, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2524747612231219, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.22355024830571765, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137685.8775313} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23581377079499694, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8885848998381636, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137685.8775313} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.59997272491455, "x": 50.54670999884047, "y": 6.551575227760157, "z": null, "yaw": 1.927990518116073, "pitch": null, "roll": null}, "v": 0.8907928456796339, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2524747612231219, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.22355024830571765, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137685.9075313} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23581377079499694, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8874464972998621, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137685.9075313} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137685.9175313, "x": 54.51135659725123, "y": 11.642796272788658, "z": null, "yaw": 1.9555957323169877, "pitch": null, "roll": null}, "v": 0.8877308086283477, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2522672003172968, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2227818102267004, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137685.9275312} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23040542879537199, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8871623785973425, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137685.9275312} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.709972620010376, "x": 50.51135659725123, "y": 6.642796272788658, "z": null, "yaw": 1.9555957323169877, "pitch": null, "roll": null}, "v": 0.8877308086283477, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2522672003172968, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2227818102267004, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137685.9575312} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2329650168619471, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8859189046897863, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137685.9575312} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.709972620010376, "x": 50.51135659725123, "y": 6.642796272788658, "z": null, "yaw": 1.9555957323169877, "pitch": null, "roll": null}, "v": 0.8877308086283477, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2522672003172968, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2227818102267004, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137685.9775312} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2329650168619471, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8849969546809598, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137685.9775312} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.709972620010376, "x": 50.51135659725123, "y": 6.642796272788658, "z": null, "yaw": 1.9555957323169877, "pitch": null, "roll": null}, "v": 0.8877308086283477, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2522672003172968, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2227818102267004, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137685.9975312} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2329650168619471, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.884076252653737, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137685.9975312} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.709972620010376, "x": 50.51135659725123, "y": 6.642796272788658, "z": null, "yaw": 1.9555957323169877, "pitch": null, "roll": null}, "v": 0.8877308086283477, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2522672003172968, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2227818102267004, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137686.0175312} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2329650168619471, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.883156796579847, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137686.0175312} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137686.0275311, "x": 54.47366529127613, "y": 11.732611493875972, "z": null, "yaw": 1.9832009465179024, "pitch": null, "roll": null}, "v": 0.8826975351426942, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25192642614260463, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2215186775657618, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137686.0375311} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23663757897353613, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8822385844351399, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137686.0375311} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.8199725151062, "x": 50.47366529127613, "y": 6.732611493875972, "z": null, "yaw": 1.9832009465179024, "pitch": null, "roll": null}, "v": 0.8826975351426942, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25192642614260463, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2215186775657618, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137686.057531} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2348627752395442, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8817805292107954, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137686.057531} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.8199725151062, "x": 50.47366529127613, "y": 6.732611493875972, "z": null, "yaw": 1.9832009465179024, "pitch": null, "roll": null}, "v": 0.8826975351426942, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25192642614260463, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2215186775657618, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137686.077531} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2348627752395442, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8811013179666836, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137686.077531} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.8199725151062, "x": 50.47366529127613, "y": 6.732611493875972, "z": null, "yaw": 1.9832009465179024, "pitch": null, "roll": null}, "v": 0.8826975351426942, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25192642614260463, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2215186775657618, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137686.097531} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2348627752395442, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8804230250509164, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137686.097531} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.8199725151062, "x": 50.47366529127613, "y": 6.732611493875972, "z": null, "yaw": 1.9832009465179024, "pitch": null, "roll": null}, "v": 0.8826975351426942, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25192642614260463, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2215186775657618, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137686.117531} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2348627752395442, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8794073044251492, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137686.117531} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2348627752395442, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8794073044251492, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137686.127531} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137686.137531, "x": 54.433710708090885, "y": 11.820906036502532, "z": null, "yaw": 2.010806160718817, "pitch": null, "roll": null}, "v": 0.8790691885047005, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25168108580701815, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.22060812041906191, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137686.157531} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23773971655484438, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8783936420310706, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137686.157531} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.929972410202026, "x": 50.433710708090885, "y": 6.820906036502532, "z": null, "yaw": 2.010806160718817, "pitch": null, "roll": null}, "v": 0.8790691885047005, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25168108580701815, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.22060812041906191, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137686.177531} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23635105120924346, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8780785043797219, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137686.177531} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.929972410202026, "x": 50.433710708090885, "y": 6.820906036502532, "z": null, "yaw": 2.010806160718817, "pitch": null, "roll": null}, "v": 0.8790691885047005, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25168108580701815, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.22060812041906191, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137686.197531} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23635105120924346, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8775902678844159, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137686.197531} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.929972410202026, "x": 50.433710708090885, "y": 6.820906036502532, "z": null, "yaw": 2.010806160718817, "pitch": null, "roll": null}, "v": 0.8790691885047005, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25168108580701815, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.22060812041906191, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137686.217531} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23635105120924346, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8771026908152789, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137686.217531} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.929972410202026, "x": 50.433710708090885, "y": 6.820906036502532, "z": null, "yaw": 2.010806160718817, "pitch": null, "roll": null}, "v": 0.8790691885047005, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25168108580701815, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.22060812041906191, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137686.237531} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23635105120924346, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8766157721866108, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137686.237531} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137686.247531, "x": 54.39149073079984, "y": 11.907741767844222, "z": null, "yaw": 2.0384113749197317, "pitch": null, "roll": null}, "v": 0.8763725594798906, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2514989166040879, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21993138385678662, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137686.257531} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23863521970783447, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8761295110144274, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137686.257531} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.03997230529785, "x": 50.39149073079984, "y": 6.907741767844222, "z": null, "yaw": 2.0384113749197317, "pitch": null, "roll": null}, "v": 0.8763725594798906, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2514989166040879, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21993138385678662, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137686.277531} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2375336403141856, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8759293309880695, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137686.277531} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.03997230529785, "x": 50.39149073079984, "y": 6.907741767844222, "z": null, "yaw": 2.0384113749197317, "pitch": null, "roll": null}, "v": 0.8763725594798906, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2514989166040879, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21993138385678662, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137686.297531} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2375336403141856, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8755917702515296, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137686.297531} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.03997230529785, "x": 50.39149073079984, "y": 6.907741767844222, "z": null, "yaw": 2.0384113749197317, "pitch": null, "roll": null}, "v": 0.8763725594798906, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2514989166040879, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21993138385678662, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137686.3175309} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2375336403141856, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8752546651594232, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137686.3175309} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.03997230529785, "x": 50.39149073079984, "y": 6.907741767844222, "z": null, "yaw": 2.0384113749197317, "pitch": null, "roll": null}, "v": 0.8763725594798906, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2514989166040879, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21993138385678662, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137686.3375309} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2375336403141856, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8749180150512742, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137686.3375309} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137686.3575308, "x": 54.34700352332246, "y": 11.993160690176007, "z": null, "yaw": 2.0660165891206463, "pitch": null, "roll": null}, "v": 0.8745818192676819, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2513780245493198, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21948198597373011, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137686.3575308} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23746027816827037, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8745818192676819, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137686.3575308} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.149972200393677, "x": 50.34700352332246, "y": 6.993160690176007, "z": null, "yaw": 2.0660165891206463, "pitch": null, "roll": null}, "v": 0.8745818192676819, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2513780245493198, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21948198597373011, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137686.3775308} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2374860017130977, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8742369099765054, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137686.3775308} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.149972200393677, "x": 50.34700352332246, "y": 6.993160690176007, "z": null, "yaw": 2.0660165891206463, "pitch": null, "roll": null}, "v": 0.8745818192676819, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2513780245493198, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21948198597373011, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137686.3975308} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2374860017130977, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8738956804205992, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137686.3975308} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.149972200393677, "x": 50.34700352332246, "y": 6.993160690176007, "z": null, "yaw": 2.0660165891206463, "pitch": null, "roll": null}, "v": 0.8745818192676819, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2513780245493198, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21948198597373011, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137686.4175308} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2374860017130977, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8735549112301316, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137686.4175308} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.149972200393677, "x": 50.34700352332246, "y": 6.993160690176007, "z": null, "yaw": 2.0660165891206463, "pitch": null, "roll": null}, "v": 0.8745818192676819, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2513780245493198, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21948198597373011, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137686.4375308} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2374860017130977, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8732146017375729, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137686.4375308} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.149972200393677, "x": 50.34700352332246, "y": 6.993160690176007, "z": null, "yaw": 2.0660165891206463, "pitch": null, "roll": null}, "v": 0.8745818192676819, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2513780245493198, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21948198597373011, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137686.4575307} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2374860017130977, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8725353591815026, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137686.4575307} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137686.4675307, "x": 54.30027407413696, "y": 12.077142160571775, "z": null, "yaw": 2.093621803321561, "pitch": null, "roll": null}, "v": 0.8727049979747704, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25125139003364, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2190109854845696, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137686.4775307} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.233986654832711, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8723658348136782, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137686.4775307} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.259972095489502, "x": 50.30027407413696, "y": 7.077142160571775, "z": null, "yaw": 2.093621803321561, "pitch": null, "roll": null}, "v": 0.8727049979747704, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25125139003364, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2190109854845696, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137686.5075307} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2356433629735843, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8715898581639293, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137686.5075307} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.259972095489502, "x": 50.30027407413696, "y": 7.077142160571775, "z": null, "yaw": 2.093621803321561, "pitch": null, "roll": null}, "v": 0.8727049979747704, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25125139003364, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2190109854845696, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137686.5275307} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2356433629735843, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8710219464343438, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137686.5275307} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.259972095489502, "x": 50.30027407413696, "y": 7.077142160571775, "z": null, "yaw": 2.093621803321561, "pitch": null, "roll": null}, "v": 0.8727049979747704, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25125139003364, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2190109854845696, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137686.5475307} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2356433629735843, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8704548002560164, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137686.5475307} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.259972095489502, "x": 50.30027407413696, "y": 7.077142160571775, "z": null, "yaw": 2.093621803321561, "pitch": null, "roll": null}, "v": 0.8727049979747704, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25125139003364, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2190109854845696, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137686.5675306} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2356433629735843, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8698884184683567, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137686.5675306} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137686.5775306, "x": 54.25137852231089, "y": 12.159576367029505, "z": null, "yaw": 2.1212270175224757, "pitch": null, "roll": null}, "v": 0.869605513858913, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2510424131902839, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21823314982156436, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137686.5875306} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23970575734286914, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8693227999128592, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137686.5875306} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.369971990585327, "x": 50.25137852231089, "y": 7.159576367029505, "z": null, "yaw": 2.1212270175224757, "pitch": null, "roll": null}, "v": 0.869605513858913, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2510424131902839, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21823314982156436, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137686.6075306} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23775536081416954, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8692655716431836, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137686.6075306} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.369971990585327, "x": 50.25137852231089, "y": 7.159576367029505, "z": null, "yaw": 2.1212270175224757, "pitch": null, "roll": null}, "v": 0.869605513858913, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2510424131902839, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21823314982156436, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137686.6275306} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23775536081416954, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8689647030490231, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137686.6275306} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.369971990585327, "x": 50.25137852231089, "y": 7.159576367029505, "z": null, "yaw": 2.1212270175224757, "pitch": null, "roll": null}, "v": 0.869605513858913, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2510424131902839, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21823314982156436, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137686.6475306} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23775536081416954, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8686642397735878, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137686.6475306} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.369971990585327, "x": 50.25137852231089, "y": 7.159576367029505, "z": null, "yaw": 2.1212270175224757, "pitch": null, "roll": null}, "v": 0.869605513858913, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2510424131902839, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21823314982156436, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137686.6675305} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23775536081416954, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8683641812347487, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137686.6675305} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137686.6875305, "x": 54.20036794315919, "y": 12.240404257608981, "z": null, "yaw": 2.1488322317233903, "pitch": null, "roll": null}, "v": 0.8680645268513068, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2509385865703412, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21784642912678437, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137686.6875305} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23816210529257173, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8680645268513068, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137686.6875305} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.479971885681152, "x": 50.20036794315919, "y": 7.240404257608981, "z": null, "yaw": 2.1488322317233903, "pitch": null, "roll": null}, "v": 0.8680645268513068, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2509385865703412, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21784642912678437, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137686.7075305} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23796050674539157, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8678161019792173, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137686.7075305} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.479971885681152, "x": 50.20036794315919, "y": 7.240404257608981, "z": null, "yaw": 2.1488322317233903, "pitch": null, "roll": null}, "v": 0.8680645268513068, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2509385865703412, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21784642912678437, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137686.7275305} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23796050674539157, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8675428203284131, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137686.7275305} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.479971885681152, "x": 50.20036794315919, "y": 7.240404257608981, "z": null, "yaw": 2.1488322317233903, "pitch": null, "roll": null}, "v": 0.8680645268513068, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2509385865703412, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21784642912678437, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137686.7475305} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23796050674539157, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8672699066761749, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137686.7475305} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.479971885681152, "x": 50.20036794315919, "y": 7.240404257608981, "z": null, "yaw": 2.1488322317233903, "pitch": null, "roll": null}, "v": 0.8680645268513068, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2509385865703412, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21784642912678437, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137686.7675304} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23796050674539157, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8669973604971762, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137686.7675304} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.479971885681152, "x": 50.20036794315919, "y": 7.240404257608981, "z": null, "yaw": 2.1488322317233903, "pitch": null, "roll": null}, "v": 0.8680645268513068, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2509385865703412, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21784642912678437, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137686.7875304} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23796050674539157, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8667251812669187, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137686.7875304} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137686.7975304, "x": 54.14723881932111, "y": 12.31965464764477, "z": null, "yaw": 2.176437445924305, "pitch": null, "roll": null}, "v": 0.8665892290938879, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2508392303745098, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21747619357584186, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137686.8075304} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23338882110511272, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8664533684617298, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137686.8075304} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.589971780776978, "x": 50.14723881932111, "y": 7.31965464764477, "z": null, "yaw": 2.176437445924305, "pitch": null, "roll": null}, "v": 0.8665892290938879, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2508392303745098, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21747619357584186, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137686.8275304} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23555824535499958, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8656106532173857, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137686.8275304} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.589971780776978, "x": 50.14723881932111, "y": 7.31965464764477, "z": null, "yaw": 2.176437445924305, "pitch": null, "roll": null}, "v": 0.8665892290938879, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2508392303745098, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21747619357584186, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137686.8475304} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23555824535499958, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8650401589356126, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137686.8475304} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.589971780776978, "x": 50.14723881932111, "y": 7.31965464764477, "z": null, "yaw": 2.176437445924305, "pitch": null, "roll": null}, "v": 0.8665892290938879, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2508392303745098, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21747619357584186, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137686.8675303} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23555824535499958, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8644704323224428, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137686.8675303} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.589971780776978, "x": 50.14723881932111, "y": 7.31965464764477, "z": null, "yaw": 2.176437445924305, "pitch": null, "roll": null}, "v": 0.8665892290938879, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2508392303745098, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21747619357584186, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137686.8875303} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23555824535499958, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8639014722150942, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137686.8875303} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137686.9075303, "x": 54.092090399979035, "y": 12.397201218498916, "z": null, "yaw": 2.2040426601252197, "pitch": null, "roll": null}, "v": 0.863333277452873, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25062010735221885, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21665909137149603, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137686.9075303} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2366782609049587, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.863333277452873, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137686.9075303} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.699971675872803, "x": 50.092090399979035, "y": 7.397201218498916, "z": null, "yaw": 2.2040426601252197, "pitch": null, "roll": null}, "v": 0.863333277452873, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25062010735221885, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21665909137149603, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137686.9275303} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23612822480470322, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8629058017370779, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137686.9275303} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.699971675872803, "x": 50.092090399979035, "y": 7.397201218498916, "z": null, "yaw": 2.2040426601252197, "pitch": null, "roll": null}, "v": 0.863333277452873, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25062010735221885, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21665909137149603, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137686.9475303} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23612822480470322, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8624101694777775, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137686.9475303} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.699971675872803, "x": 50.092090399979035, "y": 7.397201218498916, "z": null, "yaw": 2.2040426601252197, "pitch": null, "roll": null}, "v": 0.863333277452873, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25062010735221885, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21665909137149603, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137686.9675303} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23612822480470322, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8619152036264728, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137686.9675303} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.699971675872803, "x": 50.092090399979035, "y": 7.397201218498916, "z": null, "yaw": 2.2040426601252197, "pitch": null, "roll": null}, "v": 0.863333277452873, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25062010735221885, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21665909137149603, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137686.9875302} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23612822480470322, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8614209031891737, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137686.9875302} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.699971675872803, "x": 50.092090399979035, "y": 7.397201218498916, "z": null, "yaw": 2.2040426601252197, "pitch": null, "roll": null}, "v": 0.863333277452873, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25062010735221885, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21665909137149603, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137687.0075302} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23612822480470322, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8609272671736218, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137687.0075302} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137687.0175302, "x": 54.0350167428955, "y": 12.472938115173475, "z": null, "yaw": 2.2316478743261343, "pitch": null, "roll": null}, "v": 0.8606806980143926, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2504417475400651, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21599340933891245, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137687.0275302} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23840579413393023, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8604342945892859, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137687.0275302} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.809971570968628, "x": 50.0350167428955, "y": 7.472938115173475, "z": null, "yaw": 2.2316478743261343, "pitch": null, "roll": null}, "v": 0.8606806980143926, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2504417475400651, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21599340933891245, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137687.0475302} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23730764744289531, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8602265849482207, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137687.0475302} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.809971570968628, "x": 50.0350167428955, "y": 7.472938115173475, "z": null, "yaw": 2.2316478743261343, "pitch": null, "roll": null}, "v": 0.8606806980143926, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2504417475400651, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21599340933891245, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137687.0675302} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23730764744289531, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8597097794905958, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137687.0675302} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.809971570968628, "x": 50.0350167428955, "y": 7.472938115173475, "z": null, "yaw": 2.2316478743261343, "pitch": null, "roll": null}, "v": 0.8606806980143926, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2504417475400651, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21599340933891245, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137687.0875301} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23730764744289531, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8595377424755363, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137687.0875301} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.809971570968628, "x": 50.0350167428955, "y": 7.472938115173475, "z": null, "yaw": 2.2316478743261343, "pitch": null, "roll": null}, "v": 0.8606806980143926, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2504417475400651, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21599340933891245, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137687.10753} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23730764744289531, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8591940151496182, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137687.10753} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137687.12753, "x": 53.97603169717384, "y": 12.546873259313521, "z": null, "yaw": 2.259253088527049, "pitch": null, "roll": null}, "v": 0.8588507495390743, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25031878357679205, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21553417188765975, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137687.12753} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2389953076059649, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8588507495390743, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137687.12753} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.919971466064453, "x": 49.97603169717384, "y": 7.5468732593135215, "z": null, "yaw": 2.259253088527049, "pitch": null, "roll": null}, "v": 0.8588507495390743, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25031878357679205, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21553417188765975, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137687.14753} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23818229082021164, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.858718831641989, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137687.14753} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.919971466064453, "x": 49.97603169717384, "y": 7.5468732593135215, "z": null, "yaw": 2.259253088527049, "pitch": null, "roll": null}, "v": 0.8588507495390743, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25031878357679205, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21553417188765975, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137687.16753} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23818229082021164, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8584854979517049, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137687.16753} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.919971466064453, "x": 49.97603169717384, "y": 7.5468732593135215, "z": null, "yaw": 2.259253088527049, "pitch": null, "roll": null}, "v": 0.8588507495390743, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25031878357679205, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21553417188765975, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137687.18753} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23818229082021164, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8582524776207145, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137687.18753} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.919971466064453, "x": 49.97603169717384, "y": 7.5468732593135215, "z": null, "yaw": 2.259253088527049, "pitch": null, "roll": null}, "v": 0.8588507495390743, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25031878357679205, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21553417188765975, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137687.20753} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23818229082021164, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8580197702064749, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137687.20753} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.919971466064453, "x": 49.97603169717384, "y": 7.5468732593135215, "z": null, "yaw": 2.259253088527049, "pitch": null, "roll": null}, "v": 0.8588507495390743, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25031878357679205, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21553417188765975, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137687.22753} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23818229082021164, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8577873752671247, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137687.22753} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137687.23753, "x": 53.91513487542911, "y": 12.619025753536224, "z": null, "yaw": 2.2868583027279636, "pitch": null, "roll": null}, "v": 0.8576712948376376, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2502395652417666, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2152381800724467, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137687.24753} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23988979598957932, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8575552923614832, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137687.24753} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.02997136116028, "x": 49.91513487542911, "y": 7.619025753536224, "z": null, "yaw": 2.2868583027279636, "pitch": null, "roll": null}, "v": 0.8576712948376376, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2502395652417666, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2152381800724467, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137687.26753} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2390706621980187, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8575368875335174, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137687.26753} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.02997136116028, "x": 49.91513487542911, "y": 7.619025753536224, "z": null, "yaw": 2.2868583027279636, "pitch": null, "roll": null}, "v": 0.8576712948376376, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2502395652417666, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2152381800724467, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137687.28753} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2390706621980187, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8574161500693397, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137687.28753} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.02997136116028, "x": 49.91513487542911, "y": 7.619025753536224, "z": null, "yaw": 2.2868583027279636, "pitch": null, "roll": null}, "v": 0.8576712948376376, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2502395652417666, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2152381800724467, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137687.30753} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2390706621980187, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8572955746985447, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137687.30753} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.02997136116028, "x": 49.91513487542911, "y": 7.619025753536224, "z": null, "yaw": 2.2868583027279636, "pitch": null, "roll": null}, "v": 0.8576712948376376, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2502395652417666, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2152381800724467, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137687.32753} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2390706621980187, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8571751611977043, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137687.32753} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137687.34753, "x": 53.85233972269201, "y": 12.689391227157039, "z": null, "yaw": 2.3144635169288783, "pitch": null, "roll": null}, "v": 0.8570549093437136, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2501981766434873, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21508349413071845, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137687.34753} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24876566918458726, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8570549093437136, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137687.34753} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.139971256256104, "x": 49.85233972269201, "y": 7.689391227157039, "z": null, "yaw": 2.3144635169288783, "pitch": null, "roll": null}, "v": 0.8570549093437136, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2501981766434873, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21508349413071845, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137687.3675299} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24414584346616666, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8581462879242898, "gear": 1, "accelerator_pedal_position": 0.24876566918458726, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137687.3675299} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.139971256256104, "x": 49.85233972269201, "y": 7.689391227157039, "z": null, "yaw": 2.3144635169288783, "pitch": null, "roll": null}, "v": 0.8570549093437136, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2501981766434873, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21508349413071845, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137687.3875299} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24414584346616666, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8586589168466437, "gear": 1, "accelerator_pedal_position": 0.24414584346616666, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137687.3875299} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.139971256256104, "x": 49.85233972269201, "y": 7.689391227157039, "z": null, "yaw": 2.3144635169288783, "pitch": null, "roll": null}, "v": 0.8570549093437136, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2501981766434873, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21508349413071845, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137687.4075298} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24414584346616666, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8594265696600606, "gear": 1, "accelerator_pedal_position": 0.24414584346616666, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137687.4075298} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24414584346616666, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8594265696600606, "gear": 1, "accelerator_pedal_position": 0.24414584346616666, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137687.4175298} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.139971256256104, "x": 49.85233972269201, "y": 7.689391227157039, "z": null, "yaw": 2.3144635169288783, "pitch": null, "roll": null}, "v": 0.8570549093437136, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2501981766434873, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21508349413071845, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137687.4475298} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24414584346616666, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8601926762478299, "gear": 1, "accelerator_pedal_position": 0.24414584346616666, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137687.4475298} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137687.4575298, "x": 53.78751711862978, "y": 12.75811098106986, "z": null, "yaw": 2.342068731129793, "pitch": null, "roll": null}, "v": 0.8604477019823144, "accelerator_pedal_position": 0.24414584346616666, "brake_pedal_position": 0.0, "acceleration": 0.02548543408595938, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2159349374718808, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137687.4675298} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22867366877469444, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8599902284543847, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137687.4675298} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.24997115135193, "x": 49.78751711862978, "y": 7.75811098106986, "z": null, "yaw": 2.342068731129793, "pitch": null, "roll": null}, "v": 0.8604477019823144, "accelerator_pedal_position": 0.24414584346616666, "brake_pedal_position": 0.0, "acceleration": 0.02548543408595938, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2159349374718808, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137687.4875298} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23605873934049193, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8592783793192722, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137687.4875298} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.24997115135193, "x": 49.78751711862978, "y": 7.75811098106986, "z": null, "yaw": 2.342068731129793, "pitch": null, "roll": null}, "v": 0.8604477019823144, "accelerator_pedal_position": 0.24414584346616666, "brake_pedal_position": 0.0, "acceleration": 0.02548543408595938, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2159349374718808, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137687.5075297} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23605873934049193, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8585294709292797, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137687.5075297} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.24997115135193, "x": 49.78751711862978, "y": 7.75811098106986, "z": null, "yaw": 2.342068731129793, "pitch": null, "roll": null}, "v": 0.8604477019823144, "accelerator_pedal_position": 0.24414584346616666, "brake_pedal_position": 0.0, "acceleration": 0.02548543408595938, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2159349374718808, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137687.5275297} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23605873934049193, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8582801701173504, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137687.5275297} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.24997115135193, "x": 49.78751711862978, "y": 7.75811098106986, "z": null, "yaw": 2.342068731129793, "pitch": null, "roll": null}, "v": 0.8604477019823144, "accelerator_pedal_position": 0.24414584346616666, "brake_pedal_position": 0.0, "acceleration": 0.02548543408595938, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2159349374718808, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137687.5475297} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23605873934049193, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8577820707204298, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137687.5475297} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137687.5675297, "x": 53.7208151872925, "y": 12.825024978674989, "z": null, "yaw": 2.3696739453307076, "pitch": null, "roll": null}, "v": 0.857284640127364, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25021360154835126, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21514114656245673, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137687.5675297} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2461890616251412, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.857284640127364, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137687.5675297} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.359971046447754, "x": 49.7208151872925, "y": 7.825024978674989, "z": null, "yaw": 2.3696739453307076, "pitch": null, "roll": null}, "v": 0.857284640127364, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25021360154835126, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21514114656245673, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137687.5875297} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24134890680283133, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8580537424884651, "gear": 1, "accelerator_pedal_position": 0.2461890616251412, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137687.5875297} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.359971046447754, "x": 49.7208151872925, "y": 7.825024978674989, "z": null, "yaw": 2.3696739453307076, "pitch": null, "roll": null}, "v": 0.857284640127364, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25021360154835126, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21514114656245673, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137687.6075296} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24134890680283133, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8582985405467856, "gear": 1, "accelerator_pedal_position": 0.24134890680283133, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137687.6075296} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.359971046447754, "x": 49.7208151872925, "y": 7.825024978674989, "z": null, "yaw": 2.3696739453307076, "pitch": null, "roll": null}, "v": 0.857284640127364, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25021360154835126, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21514114656245673, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137687.6275296} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24134890680283133, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8583800303132186, "gear": 1, "accelerator_pedal_position": 0.24134890680283133, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137687.6275296} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.359971046447754, "x": 49.7208151872925, "y": 7.825024978674989, "z": null, "yaw": 2.3696739453307076, "pitch": null, "roll": null}, "v": 0.857284640127364, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25021360154835126, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21514114656245673, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137687.6475296} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24134890680283133, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8585428456793508, "gear": 1, "accelerator_pedal_position": 0.24134890680283133, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137687.6475296} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.359971046447754, "x": 49.7208151872925, "y": 7.825024978674989, "z": null, "yaw": 2.3696739453307076, "pitch": null, "roll": null}, "v": 0.857284640127364, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25021360154835126, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21514114656245673, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137687.6675296} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24134890680283133, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8587866588429418, "gear": 1, "accelerator_pedal_position": 0.24134890680283133, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137687.6675296} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137687.6775296, "x": 53.65234899266343, "y": 12.890016381677933, "z": null, "yaw": 2.3972791595316223, "pitch": null, "roll": null}, "v": 0.8587866588429418, "accelerator_pedal_position": 0.24134890680283133, "brake_pedal_position": 0.0, "acceleration": 0.008116189321482392, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21551808791134136, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137687.6875296} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23823619795328596, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8588678207361566, "gear": 1, "accelerator_pedal_position": 0.24134890680283133, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137687.6875296} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.46997094154358, "x": 49.65234899266343, "y": 7.890016381677933, "z": null, "yaw": 2.3972791595316223, "pitch": null, "roll": null}, "v": 0.8587866588429418, "accelerator_pedal_position": 0.24134890680283133, "brake_pedal_position": 0.0, "acceleration": 0.008116189321482392, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21551808791134136, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137687.7075295} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23972612684671496, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8585277384954189, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137687.7075295} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.46997094154358, "x": 49.65234899266343, "y": 7.890016381677933, "z": null, "yaw": 2.3972791595316223, "pitch": null, "roll": null}, "v": 0.8587866588429418, "accelerator_pedal_position": 0.24134890680283133, "brake_pedal_position": 0.0, "acceleration": 0.008116189321482392, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21551808791134136, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137687.7275295} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23972612684671496, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8585076505663142, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137687.7275295} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.46997094154358, "x": 49.65234899266343, "y": 7.890016381677933, "z": null, "yaw": 2.3972791595316223, "pitch": null, "roll": null}, "v": 0.8587866588429418, "accelerator_pedal_position": 0.24134890680283133, "brake_pedal_position": 0.0, "acceleration": 0.008116189321482392, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21551808791134136, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137687.7475295} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23972612684671496, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8584675151783602, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137687.7475295} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.46997094154358, "x": 49.65234899266343, "y": 7.890016381677933, "z": null, "yaw": 2.3972791595316223, "pitch": null, "roll": null}, "v": 0.8587866588429418, "accelerator_pedal_position": 0.24134890680283133, "brake_pedal_position": 0.0, "acceleration": 0.008116189321482392, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21551808791134136, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137687.7675295} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23972612684671496, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8584274336898179, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137687.7675295} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137687.7875295, "x": 53.58208592736001, "y": 12.953119971065927, "z": null, "yaw": 2.424884373732537, "pitch": null, "roll": null}, "v": 0.8583874060276613, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25028765968965205, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21541789282510374, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137687.7875295} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23278524350838126, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8583874060276613, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137687.7875295} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.579970836639404, "x": 49.58208592736001, "y": 7.953119971065927, "z": null, "yaw": 2.424884373732537, "pitch": null, "roll": null}, "v": 0.8583874060276613, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25028765968965205, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21541789282510374, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137687.8075294} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2360883843857225, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8574801130583097, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137687.8075294} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.579970836639404, "x": 49.58208592736001, "y": 7.953119971065927, "z": null, "yaw": 2.424884373732537, "pitch": null, "roll": null}, "v": 0.8583874060276613, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25028765968965205, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21541789282510374, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137687.8275294} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2360883843857225, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8569867922456292, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137687.8275294} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.579970836639404, "x": 49.58208592736001, "y": 7.953119971065927, "z": null, "yaw": 2.424884373732537, "pitch": null, "roll": null}, "v": 0.8583874060276613, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25028765968965205, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21541789282510374, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137687.8475294} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2360883843857225, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8564941336634817, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137687.8475294} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.579970836639404, "x": 49.58208592736001, "y": 7.953119971065927, "z": null, "yaw": 2.424884373732537, "pitch": null, "roll": null}, "v": 0.8583874060276613, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25028765968965205, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21541789282510374, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137687.8675294} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2360883843857225, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8560021363258409, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137687.8675294} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.579970836639404, "x": 49.58208592736001, "y": 7.953119971065927, "z": null, "yaw": 2.424884373732537, "pitch": null, "roll": null}, "v": 0.8583874060276613, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25028765968965205, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21541789282510374, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137687.8875294} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2360883843857225, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8555107992483949, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137687.8875294} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137687.8975294, "x": 53.510257264947896, "y": 13.014134057522634, "z": null, "yaw": 2.4524895879334516, "pitch": null, "roll": null}, "v": 0.8552653780001153, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25007805756806256, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21463439962108857, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137687.9075294} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2387078623559446, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8550201214485423, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137687.9075294} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.68997073173523, "x": 49.510257264947896, "y": 8.014134057522634, "z": null, "yaw": 2.4524895879334516, "pitch": null, "roll": null}, "v": 0.8552653780001153, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25007805756806256, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21463439962108857, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137687.9275293} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23744452157738571, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8548574268419953, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137687.9275293} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.68997073173523, "x": 49.510257264947896, "y": 8.014134057522634, "z": null, "yaw": 2.4524895879334516, "pitch": null, "roll": null}, "v": 0.8552653780001153, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25007805756806256, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21463439962108857, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137687.9475293} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23744452157738571, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.854537085871608, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137687.9475293} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.68997073173523, "x": 49.510257264947896, "y": 8.014134057522634, "z": null, "yaw": 2.4524895879334516, "pitch": null, "roll": null}, "v": 0.8552653780001153, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25007805756806256, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21463439962108857, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137687.9675293} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23744452157738571, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8542171746055546, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137687.9675293} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.68997073173523, "x": 49.510257264947896, "y": 8.014134057522634, "z": null, "yaw": 2.4524895879334516, "pitch": null, "roll": null}, "v": 0.8552653780001153, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25007805756806256, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21463439962108857, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137687.9875293} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23744452157738571, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8538976924265073, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137687.9875293} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137688.0075293, "x": 53.43696791318969, "y": 13.072984451827974, "z": null, "yaw": 2.4800948021343663, "pitch": null, "roll": null}, "v": 0.8535786387181311, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24996489686066553, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21421110144672245, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137688.0075293} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23919103990390658, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8535786387181311, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137688.0075293} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.799970626831055, "x": 49.43696791318969, "y": 8.072984451827974, "z": null, "yaw": 2.4800948021343663, "pitch": null, "roll": null}, "v": 0.8535786387181311, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24996489686066553, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21421110144672245, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137688.0275292} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23835074232237724, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.853478254444603, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137688.0275292} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.799970626831055, "x": 49.43696791318969, "y": 8.072984451827974, "z": null, "yaw": 2.4800948021343663, "pitch": null, "roll": null}, "v": 0.8535786387181311, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24996489686066553, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21421110144672245, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137688.0475292} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23835074232237724, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8532730028070197, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137688.0475292} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.799970626831055, "x": 49.43696791318969, "y": 8.072984451827974, "z": null, "yaw": 2.4800948021343663, "pitch": null, "roll": null}, "v": 0.8535786387181311, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24996489686066553, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21421110144672245, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137688.0675292} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23835074232237724, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8530680263872402, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137688.0675292} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.799970626831055, "x": 49.43696791318969, "y": 8.072984451827974, "z": null, "yaw": 2.4800948021343663, "pitch": null, "roll": null}, "v": 0.8535786387181311, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24996489686066553, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21421110144672245, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137688.0875292} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23835074232237724, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8528633247994301, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137688.0875292} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.799970626831055, "x": 49.43696791318969, "y": 8.072984451827974, "z": null, "yaw": 2.4800948021343663, "pitch": null, "roll": null}, "v": 0.8535786387181311, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24996489686066553, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21421110144672245, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137688.1075292} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23835074232237724, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8526588976583396, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137688.1075292} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137688.1175292, "x": 53.36220058897294, "y": 13.129699459472342, "z": null, "yaw": 2.507700016335281, "pitch": null, "roll": null}, "v": 0.8525567868850834, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24989637009289237, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2139546610946054, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137688.1275291} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2397005982379117, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.852454744579303, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137688.1275291} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.90997052192688, "x": 49.36220058897294, "y": 8.129699459472342, "z": null, "yaw": 2.507700016335281, "pitch": null, "roll": null}, "v": 0.8525567868850834, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24989637009289237, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2139546610946054, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137688.1475291} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2390525882959271, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8524195406020524, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137688.1475291} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.90997052192688, "x": 49.36220058897294, "y": 8.129699459472342, "z": null, "yaw": 2.507700016335281, "pitch": null, "roll": null}, "v": 0.8525567868850834, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24989637009289237, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2139546610946054, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137688.167529} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2390525882959271, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8523034097284606, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137688.167529} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.90997052192688, "x": 49.36220058897294, "y": 8.129699459472342, "z": null, "yaw": 2.507700016335281, "pitch": null, "roll": null}, "v": 0.8525567868850834, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24989637009289237, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2139546610946054, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137688.187529} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2390525882959271, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8521874345263836, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137688.187529} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.90997052192688, "x": 49.36220058897294, "y": 8.129699459472342, "z": null, "yaw": 2.507700016335281, "pitch": null, "roll": null}, "v": 0.8525567868850834, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24989637009289237, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2139546610946054, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137688.207529} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2390525882959271, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8520716147817678, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137688.207529} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137688.227529, "x": 53.28597382168696, "y": 13.184273518445135, "z": null, "yaw": 2.5353052305361956, "pitch": null, "roll": null}, "v": 0.8519559502808687, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24985608692623323, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2138038772477045, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137688.227529} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24046497084737375, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8519559502808687, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137688.227529} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.019970417022705, "x": 49.28597382168696, "y": 8.184273518445135, "z": null, "yaw": 2.5353052305361956, "pitch": null, "roll": null}, "v": 0.8519559502808687, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24985608692623323, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2138038772477045, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137688.247529} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23978933819647902, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8520169294513696, "gear": 1, "accelerator_pedal_position": 0.24046497084737375, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137688.247529} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.019970417022705, "x": 49.28597382168696, "y": 8.184273518445135, "z": null, "yaw": 2.5353052305361956, "pitch": null, "roll": null}, "v": 0.8519559502808687, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24985608692623323, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2138038772477045, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137688.267529} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23978933819647902, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8519934011162322, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137688.267529} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.019970417022705, "x": 49.28597382168696, "y": 8.184273518445135, "z": null, "yaw": 2.5353052305361956, "pitch": null, "roll": null}, "v": 0.8519559502808687, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24985608692623323, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2138038772477045, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137688.287529} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23978933819647902, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8519699043173053, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137688.287529} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.019970417022705, "x": 49.28597382168696, "y": 8.184273518445135, "z": null, "yaw": 2.5353052305361956, "pitch": null, "roll": null}, "v": 0.8519559502808687, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24985608692623323, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2138038772477045, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137688.307529} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23978933819647902, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8519464390120987, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137688.307529} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.019970417022705, "x": 49.28597382168696, "y": 8.184273518445135, "z": null, "yaw": 2.5353052305361956, "pitch": null, "roll": null}, "v": 0.8519559502808687, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24985608692623323, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2138038772477045, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137688.327529} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23978933819647902, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8519230051581798, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137688.327529} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137688.337529, "x": 53.20829877234723, "y": 13.236703059590432, "z": null, "yaw": 2.5629104447371103, "pitch": null, "roll": null}, "v": 0.8519113000122088, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24985309363149538, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2137926719728819, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137688.347529} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2493727503905004, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8518996027131738, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137688.347529} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.12997031211853, "x": 49.20829877234723, "y": 8.236703059590432, "z": null, "yaw": 2.5629104447371103, "pitch": null, "roll": null}, "v": 0.8519113000122088, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24985309363149538, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2137926719728819, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137688.367529} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2448089904339508, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8533750081320046, "gear": 1, "accelerator_pedal_position": 0.2448089904339508, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137688.367529} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.12997031211853, "x": 49.20829877234723, "y": 8.236703059590432, "z": null, "yaw": 2.5629104447371103, "pitch": null, "roll": null}, "v": 0.8519113000122088, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24985309363149538, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2137926719728819, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137688.387529} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2448089904339508, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8536760576396101, "gear": 1, "accelerator_pedal_position": 0.2448089904339508, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137688.387529} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.12997031211853, "x": 49.20829877234723, "y": 8.236703059590432, "z": null, "yaw": 2.5629104447371103, "pitch": null, "roll": null}, "v": 0.8519113000122088, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24985309363149538, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2137926719728819, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137688.4075289} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2448089904339508, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8542775510258126, "gear": 1, "accelerator_pedal_position": 0.2448089904339508, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137688.4075289} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.12997031211853, "x": 49.20829877234723, "y": 8.236703059590432, "z": null, "yaw": 2.5629104447371103, "pitch": null, "roll": null}, "v": 0.8519113000122088, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24985309363149538, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2137926719728819, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137688.4275289} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2448089904339508, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8548782376885777, "gear": 1, "accelerator_pedal_position": 0.2448089904339508, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137688.4275289} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137688.4475288, "x": 53.12905678573655, "y": 13.287062463583563, "z": null, "yaw": 2.590515658938025, "pitch": null, "roll": null}, "v": 0.8554781185656024, "accelerator_pedal_position": 0.2448089904339508, "brake_pedal_position": 0.0, "acceleration": 0.029963856170466818, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2146877882472658, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137688.4475288} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25249253929742926, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8554781185656024, "gear": 1, "accelerator_pedal_position": 0.2448089904339508, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137688.4475288} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.239970207214355, "x": 49.12905678573655, "y": 8.287062463583563, "z": null, "yaw": 2.590515658938025, "pitch": null, "roll": null}, "v": 0.8554781185656024, "accelerator_pedal_position": 0.2448089904339508, "brake_pedal_position": 0.0, "acceleration": 0.029963856170466818, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2146877882472658, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137688.4675288} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24885193252743396, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8570373158752499, "gear": 1, "accelerator_pedal_position": 0.25249253929742926, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137688.4675288} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.239970207214355, "x": 49.12905678573655, "y": 8.287062463583563, "z": null, "yaw": 2.590515658938025, "pitch": null, "roll": null}, "v": 0.8554781185656024, "accelerator_pedal_position": 0.2448089904339508, "brake_pedal_position": 0.0, "acceleration": 0.029963856170466818, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2146877882472658, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137688.4875288} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24885193252743396, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8581394973720471, "gear": 1, "accelerator_pedal_position": 0.24885193252743396, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137688.4875288} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.239970207214355, "x": 49.12905678573655, "y": 8.287062463583563, "z": null, "yaw": 2.590515658938025, "pitch": null, "roll": null}, "v": 0.8554781185656024, "accelerator_pedal_position": 0.2448089904339508, "brake_pedal_position": 0.0, "acceleration": 0.029963856170466818, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2146877882472658, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137688.5075288} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24885193252743396, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8592401989757732, "gear": 1, "accelerator_pedal_position": 0.24885193252743396, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137688.5075288} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.239970207214355, "x": 49.12905678573655, "y": 8.287062463583563, "z": null, "yaw": 2.590515658938025, "pitch": null, "roll": null}, "v": 0.8554781185656024, "accelerator_pedal_position": 0.2448089904339508, "brake_pedal_position": 0.0, "acceleration": 0.029963856170466818, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2146877882472658, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137688.5275288} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24885193252743396, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8603394221890177, "gear": 1, "accelerator_pedal_position": 0.24885193252743396, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137688.5275288} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.239970207214355, "x": 49.12905678573655, "y": 8.287062463583563, "z": null, "yaw": 2.590515658938025, "pitch": null, "roll": null}, "v": 0.8554781185656024, "accelerator_pedal_position": 0.2448089904339508, "brake_pedal_position": 0.0, "acceleration": 0.029963856170466818, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2146877882472658, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137688.5475287} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24885193252743396, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8619854883134814, "gear": 1, "accelerator_pedal_position": 0.24885193252743396, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137688.5475287} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137688.5575287, "x": 53.047977569241674, "y": 13.335499924034043, "z": null, "yaw": 2.6181208731389396, "pitch": null, "roll": null}, "v": 0.8619854883134814, "accelerator_pedal_position": 0.24885193252743396, "brake_pedal_position": 0.0, "acceleration": 0.054795114060157746, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21632085493612724, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137688.5675287} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22864033054480093, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.862533439454083, "gear": 1, "accelerator_pedal_position": 0.24885193252743396, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137688.5675287} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.34997010231018, "x": 49.047977569241674, "y": 8.335499924034043, "z": null, "yaw": 2.6181208731389396, "pitch": null, "roll": null}, "v": 0.8619854883134814, "accelerator_pedal_position": 0.24885193252743396, "brake_pedal_position": 0.0, "acceleration": 0.054795114060157746, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21632085493612724, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137688.5875287} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2382982128996997, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8611026357690159, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137688.5875287} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.34997010231018, "x": 49.047977569241674, "y": 8.335499924034043, "z": null, "yaw": 2.6181208731389396, "pitch": null, "roll": null}, "v": 0.8619854883134814, "accelerator_pedal_position": 0.24885193252743396, "brake_pedal_position": 0.0, "acceleration": 0.054795114060157746, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21632085493612724, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137688.6075287} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2382982128996997, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8608805848532951, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137688.6075287} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.34997010231018, "x": 49.047977569241674, "y": 8.335499924034043, "z": null, "yaw": 2.6181208731389396, "pitch": null, "roll": null}, "v": 0.8619854883134814, "accelerator_pedal_position": 0.24885193252743396, "brake_pedal_position": 0.0, "acceleration": 0.054795114060157746, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21632085493612724, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137688.6275287} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2382982128996997, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8606588323568207, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137688.6275287} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.34997010231018, "x": 49.047977569241674, "y": 8.335499924034043, "z": null, "yaw": 2.6181208731389396, "pitch": null, "roll": null}, "v": 0.8619854883134814, "accelerator_pedal_position": 0.24885193252743396, "brake_pedal_position": 0.0, "acceleration": 0.054795114060157746, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21632085493612724, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137688.6475286} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2382982128996997, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8604373778588773, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137688.6475286} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137688.6675286, "x": 52.965356380209364, "y": 13.381815702615507, "z": null, "yaw": 2.6457260873398543, "pitch": null, "roll": null}, "v": 0.8602162209393941, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25041053051464224, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21587684580121475, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137688.6675286} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2684979554980777, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8602162209393941, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137688.6675286} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.459969997406006, "x": 48.965356380209364, "y": 8.381815702615507, "z": null, "yaw": 2.6457260873398543, "pitch": null, "roll": null}, "v": 0.8602162209393941, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25041053051464224, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21587684580121475, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137688.6875286} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2541080568840547, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8637690602183705, "gear": 1, "accelerator_pedal_position": 0.2684979554980777, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137688.6875286} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.459969997406006, "x": 48.965356380209364, "y": 8.381815702615507, "z": null, "yaw": 2.6457260873398543, "pitch": null, "roll": null}, "v": 0.8602162209393941, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25041053051464224, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21587684580121475, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137688.7075286} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2541080568840547, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8655189899601247, "gear": 1, "accelerator_pedal_position": 0.2541080568840547, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137688.7075286} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.459969997406006, "x": 48.965356380209364, "y": 8.381815702615507, "z": null, "yaw": 2.6457260873398543, "pitch": null, "roll": null}, "v": 0.8602162209393941, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25041053051464224, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21587684580121475, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137688.7275286} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2541080568840547, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8672665650321288, "gear": 1, "accelerator_pedal_position": 0.2541080568840547, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137688.7275286} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.459969997406006, "x": 48.965356380209364, "y": 8.381815702615507, "z": null, "yaw": 2.6457260873398543, "pitch": null, "roll": null}, "v": 0.8602162209393941, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25041053051464224, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21587684580121475, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137688.7475286} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2541080568840547, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.869011787381582, "gear": 1, "accelerator_pedal_position": 0.2541080568840547, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137688.7475286} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.459969997406006, "x": 48.965356380209364, "y": 8.381815702615507, "z": null, "yaw": 2.6457260873398543, "pitch": null, "roll": null}, "v": 0.8602162209393941, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25041053051464224, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21587684580121475, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137688.7675285} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2541080568840547, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8707546589579935, "gear": 1, "accelerator_pedal_position": 0.2541080568840547, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137688.7675285} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137688.7775285, "x": 52.88099499828842, "y": 13.426088545285841, "z": null, "yaw": 2.673331301540769, "pitch": null, "roll": null}, "v": 0.8716252138161582, "accelerator_pedal_position": 0.2541080568840547, "brake_pedal_position": 0.0, "acceleration": 0.08699678970093316, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21874000663921284, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137688.7875285} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25607812337199, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8724951817131675, "gear": 1, "accelerator_pedal_position": 0.2541080568840547, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137688.7875285} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.56996989250183, "x": 48.88099499828842, "y": 8.426088545285841, "z": null, "yaw": 2.673331301540769, "pitch": null, "roll": null}, "v": 0.8716252138161582, "accelerator_pedal_position": 0.2541080568840547, "brake_pedal_position": 0.0, "acceleration": 0.08699678970093316, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21874000663921284, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137688.8075285} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25519851300955154, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8744795328387579, "gear": 1, "accelerator_pedal_position": 0.25607812337199, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137688.8075285} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.56996989250183, "x": 48.88099499828842, "y": 8.426088545285841, "z": null, "yaw": 2.673331301540769, "pitch": null, "roll": null}, "v": 0.8716252138161582, "accelerator_pedal_position": 0.2541080568840547, "brake_pedal_position": 0.0, "acceleration": 0.08699678970093316, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21874000663921284, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137688.8275285} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25519851300955154, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8763512926190482, "gear": 1, "accelerator_pedal_position": 0.25519851300955154, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137688.8275285} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.56996989250183, "x": 48.88099499828842, "y": 8.426088545285841, "z": null, "yaw": 2.673331301540769, "pitch": null, "roll": null}, "v": 0.8716252138161582, "accelerator_pedal_position": 0.2541080568840547, "brake_pedal_position": 0.0, "acceleration": 0.08699678970093316, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21874000663921284, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137688.8475285} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25519851300955154, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8782205257156507, "gear": 1, "accelerator_pedal_position": 0.25519851300955154, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137688.8475285} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.56996989250183, "x": 48.88099499828842, "y": 8.426088545285841, "z": null, "yaw": 2.673331301540769, "pitch": null, "roll": null}, "v": 0.8716252138161582, "accelerator_pedal_position": 0.2541080568840547, "brake_pedal_position": 0.0, "acceleration": 0.08699678970093316, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.21874000663921284, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137688.8775284} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25519851300955154, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8828825674376538, "gear": 1, "accelerator_pedal_position": 0.25519851300955154, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137688.8775284} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137688.8875284, "x": 52.794437855683384, "y": 13.468509153516514, "z": null, "yaw": 2.7009365157416836, "pitch": null, "roll": null}, "v": 0.8819514199152235, "accelerator_pedal_position": 0.25519851300955154, "brake_pedal_position": 0.0, "acceleration": 0.09311475224303112, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.22133143510509912, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137688.8975284} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27286551662806524, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8828825674376538, "gear": 1, "accelerator_pedal_position": 0.25519851300955154, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137688.8975284} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.679969787597656, "x": 48.794437855683384, "y": 8.468509153516514, "z": null, "yaw": 2.7009365157416836, "pitch": null, "roll": null}, "v": 0.8819514199152235, "accelerator_pedal_position": 0.25519851300955154, "brake_pedal_position": 0.0, "acceleration": 0.09311475224303112, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.22133143510509912, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137688.9275284} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26450578792832385, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8889825524271395, "gear": 1, "accelerator_pedal_position": 0.27286551662806524, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137688.9275284} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.679969787597656, "x": 48.794437855683384, "y": 8.468509153516514, "z": null, "yaw": 2.7009365157416836, "pitch": null, "roll": null}, "v": 0.8819514199152235, "accelerator_pedal_position": 0.25519851300955154, "brake_pedal_position": 0.0, "acceleration": 0.09311475224303112, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.22133143510509912, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137688.9475284} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26450578792832385, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8919977129634781, "gear": 1, "accelerator_pedal_position": 0.26450578792832385, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137688.9475284} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.679969787597656, "x": 48.794437855683384, "y": 8.468509153516514, "z": null, "yaw": 2.7009365157416836, "pitch": null, "roll": null}, "v": 0.8819514199152235, "accelerator_pedal_position": 0.25519851300955154, "brake_pedal_position": 0.0, "acceleration": 0.09311475224303112, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.22133143510509912, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137688.9675283} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26450578792832385, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8950087848292249, "gear": 1, "accelerator_pedal_position": 0.26450578792832385, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137688.9675283} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.679969787597656, "x": 48.794437855683384, "y": 8.468509153516514, "z": null, "yaw": 2.7009365157416836, "pitch": null, "roll": null}, "v": 0.8819514199152235, "accelerator_pedal_position": 0.25519851300955154, "brake_pedal_position": 0.0, "acceleration": 0.09311475224303112, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.22133143510509912, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137688.9875283} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26450578792832385, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8980157699433793, "gear": 1, "accelerator_pedal_position": 0.26450578792832385, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137688.9875283} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137688.9975283, "x": 52.705362938102006, "y": 13.509152017139451, "z": null, "yaw": 2.7285417299425982, "pitch": null, "roll": null}, "v": 0.8995177305716211, "accelerator_pedal_position": 0.26450578792832385, "brake_pedal_position": 0.0, "acceleration": 0.15009396654731577, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.22573981481773248, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137689.0075283} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24787694222237175, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9010186702370943, "gear": 1, "accelerator_pedal_position": 0.26450578792832385, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137689.0075283} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.78996968269348, "x": 48.705362938102006, "y": 8.509152017139451, "z": null, "yaw": 2.7285417299425982, "pitch": null, "roll": null}, "v": 0.8995177305716211, "accelerator_pedal_position": 0.26450578792832385, "brake_pedal_position": 0.0, "acceleration": 0.15009396654731577, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.22573981481773248, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137689.0275283} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2558862063833676, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9019395890818298, "gear": 1, "accelerator_pedal_position": 0.24787694222237175, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137689.0275283} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.78996968269348, "x": 48.705362938102006, "y": 8.509152017139451, "z": null, "yaw": 2.7285417299425982, "pitch": null, "roll": null}, "v": 0.8995177305716211, "accelerator_pedal_position": 0.26450578792832385, "brake_pedal_position": 0.0, "acceleration": 0.15009396654731577, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.22573981481773248, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137689.0475283} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2558862063833676, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.903860072634658, "gear": 1, "accelerator_pedal_position": 0.2558862063833676, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137689.0475283} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.78996968269348, "x": 48.705362938102006, "y": 8.509152017139451, "z": null, "yaw": 2.7285417299425982, "pitch": null, "roll": null}, "v": 0.8995177305716211, "accelerator_pedal_position": 0.26450578792832385, "brake_pedal_position": 0.0, "acceleration": 0.15009396654731577, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.22573981481773248, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137689.0675282} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2558862063833676, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.905777942623321, "gear": 1, "accelerator_pedal_position": 0.2558862063833676, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137689.0675282} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.78996968269348, "x": 48.705362938102006, "y": 8.509152017139451, "z": null, "yaw": 2.7285417299425982, "pitch": null, "roll": null}, "v": 0.8995177305716211, "accelerator_pedal_position": 0.26450578792832385, "brake_pedal_position": 0.0, "acceleration": 0.15009396654731577, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.22573981481773248, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137689.0875282} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2558862063833676, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9076932011337993, "gear": 1, "accelerator_pedal_position": 0.2558862063833676, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137689.0875282} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137689.1075282, "x": 52.61379044680492, "y": 13.547919899115684, "z": null, "yaw": 2.756146944143513, "pitch": null, "roll": null}, "v": 0.9096058502552399, "accelerator_pedal_position": 0.2558862063833676, "brake_pedal_position": 0.0, "acceleration": 0.09553466935509997, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.22827149395183033, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137689.1075282} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2589006453031608, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9096058502552399, "gear": 1, "accelerator_pedal_position": 0.2558862063833676, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137689.1075282} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.899969577789307, "x": 48.61379044680492, "y": 8.547919899115684, "z": null, "yaw": 2.756146944143513, "pitch": null, "roll": null}, "v": 0.9096058502552399, "accelerator_pedal_position": 0.2558862063833676, "brake_pedal_position": 0.0, "acceleration": 0.09553466935509997, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.22827149395183033, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137689.1275282} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25751753370081, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9118925684297575, "gear": 1, "accelerator_pedal_position": 0.2589006453031608, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137689.1275282} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.899969577789307, "x": 48.61379044680492, "y": 8.547919899115684, "z": null, "yaw": 2.756146944143513, "pitch": null, "roll": null}, "v": 0.9096058502552399, "accelerator_pedal_position": 0.2558862063833676, "brake_pedal_position": 0.0, "acceleration": 0.09553466935509997, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.22827149395183033, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137689.1475282} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25751753370081, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9140033374336533, "gear": 1, "accelerator_pedal_position": 0.25751753370081, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137689.1475282} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.899969577789307, "x": 48.61379044680492, "y": 8.547919899115684, "z": null, "yaw": 2.756146944143513, "pitch": null, "roll": null}, "v": 0.9096058502552399, "accelerator_pedal_position": 0.2558862063833676, "brake_pedal_position": 0.0, "acceleration": 0.09553466935509997, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.22827149395183033, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137689.1675282} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25751753370081, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9161112253980377, "gear": 1, "accelerator_pedal_position": 0.25751753370081, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137689.1675282} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.899969577789307, "x": 48.61379044680492, "y": 8.547919899115684, "z": null, "yaw": 2.756146944143513, "pitch": null, "roll": null}, "v": 0.9096058502552399, "accelerator_pedal_position": 0.2558862063833676, "brake_pedal_position": 0.0, "acceleration": 0.09553466935509997, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.22827149395183033, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137689.1875281} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25751753370081, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9182162344786411, "gear": 1, "accelerator_pedal_position": 0.25751753370081, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137689.1875281} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.899969577789307, "x": 48.61379044680492, "y": 8.547919899115684, "z": null, "yaw": 2.756146944143513, "pitch": null, "roll": null}, "v": 0.9096058502552399, "accelerator_pedal_position": 0.2558862063833676, "brake_pedal_position": 0.0, "acceleration": 0.09553466935509997, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.22827149395183033, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137689.207528} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25751753370081, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9203183668355279, "gear": 1, "accelerator_pedal_position": 0.25751753370081, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137689.207528} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137689.217528, "x": 52.520056328326916, "y": 13.584585600656304, "z": null, "yaw": 2.7837521583444276, "pitch": null, "roll": null}, "v": 0.9213683549187773, "accelerator_pedal_position": 0.25751753370081, "brake_pedal_position": 0.0, "acceleration": 0.10492697142966612, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.23122337086797776, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137689.227528} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2595024166679404, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.922417624633074, "gear": 1, "accelerator_pedal_position": 0.25751753370081, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137689.227528} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.00996947288513, "x": 48.520056328326916, "y": 8.584585600656304, "z": null, "yaw": 2.7837521583444276, "pitch": null, "roll": null}, "v": 0.9213683549187773, "accelerator_pedal_position": 0.25751753370081, "brake_pedal_position": 0.0, "acceleration": 0.10492697142966612, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.23122337086797776, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137689.247528} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25861845242559084, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9247620354695488, "gear": 1, "accelerator_pedal_position": 0.2595024166679404, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137689.247528} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.00996947288513, "x": 48.520056328326916, "y": 8.584585600656304, "z": null, "yaw": 2.7837521583444276, "pitch": null, "roll": null}, "v": 0.9213683549187773, "accelerator_pedal_position": 0.25751753370081, "brake_pedal_position": 0.0, "acceleration": 0.10492697142966612, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.23122337086797776, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137689.267528} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25861845242559084, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9269927786601033, "gear": 1, "accelerator_pedal_position": 0.25861845242559084, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137689.267528} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.00996947288513, "x": 48.520056328326916, "y": 8.584585600656304, "z": null, "yaw": 2.7837521583444276, "pitch": null, "roll": null}, "v": 0.9213683549187773, "accelerator_pedal_position": 0.25751753370081, "brake_pedal_position": 0.0, "acceleration": 0.10492697142966612, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.23122337086797776, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137689.287528} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25861845242559084, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9292204654997255, "gear": 1, "accelerator_pedal_position": 0.25861845242559084, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137689.287528} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.00996947288513, "x": 48.520056328326916, "y": 8.584585600656304, "z": null, "yaw": 2.7837521583444276, "pitch": null, "roll": null}, "v": 0.9213683549187773, "accelerator_pedal_position": 0.25751753370081, "brake_pedal_position": 0.0, "acceleration": 0.10492697142966612, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.23122337086797776, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137689.307528} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25861845242559084, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9314450981915797, "gear": 1, "accelerator_pedal_position": 0.25861845242559084, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137689.307528} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137689.327528, "x": 52.42411003202487, "y": 13.619094483951542, "z": null, "yaw": 2.8113573725453422, "pitch": null, "roll": null}, "v": 0.9336666789439702, "accelerator_pedal_position": 0.25861845242559084, "brake_pedal_position": 0.0, "acceleration": 0.11096465903904151, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.234309715131866, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137689.327528} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27787818839882567, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9336666789439702, "gear": 1, "accelerator_pedal_position": 0.25861845242559084, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137689.327528} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.11996936798096, "x": 48.42411003202487, "y": 8.619094483951542, "z": null, "yaw": 2.8113573725453422, "pitch": null, "roll": null}, "v": 0.9336666789439702, "accelerator_pedal_position": 0.25861845242559084, "brake_pedal_position": 0.0, "acceleration": 0.11096465903904151, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.234309715131866, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137689.347528} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2687711137227992, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9382918499110073, "gear": 1, "accelerator_pedal_position": 0.27787818839882567, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137689.347528} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.11996936798096, "x": 48.42411003202487, "y": 8.619094483951542, "z": null, "yaw": 2.8113573725453422, "pitch": null, "roll": null}, "v": 0.9336666789439702, "accelerator_pedal_position": 0.25861845242559084, "brake_pedal_position": 0.0, "acceleration": 0.11096465903904151, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.234309715131866, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137689.367528} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2687711137227992, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9417726714344421, "gear": 1, "accelerator_pedal_position": 0.2687711137227992, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137689.367528} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.11996936798096, "x": 48.42411003202487, "y": 8.619094483951542, "z": null, "yaw": 2.8113573725453422, "pitch": null, "roll": null}, "v": 0.9336666789439702, "accelerator_pedal_position": 0.25861845242559084, "brake_pedal_position": 0.0, "acceleration": 0.11096465903904151, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.234309715131866, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137689.387528} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2687711137227992, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9452487037398383, "gear": 1, "accelerator_pedal_position": 0.2687711137227992, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137689.387528} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.11996936798096, "x": 48.42411003202487, "y": 8.619094483951542, "z": null, "yaw": 2.8113573725453422, "pitch": null, "roll": null}, "v": 0.9336666789439702, "accelerator_pedal_position": 0.25861845242559084, "brake_pedal_position": 0.0, "acceleration": 0.11096465903904151, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.234309715131866, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137689.407528} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2687711137227992, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9487199485851638, "gear": 1, "accelerator_pedal_position": 0.2687711137227992, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137689.407528} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.11996936798096, "x": 48.42411003202487, "y": 8.619094483951542, "z": null, "yaw": 2.8113573725453422, "pitch": null, "roll": null}, "v": 0.9336666789439702, "accelerator_pedal_position": 0.25861845242559084, "brake_pedal_position": 0.0, "acceleration": 0.11096465903904151, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.234309715131866, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137689.427528} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2687711137227992, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.952186407745923, "gear": 1, "accelerator_pedal_position": 0.2687711137227992, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137689.427528} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137689.437528, "x": 52.32553562389986, "y": 13.65150293886177, "z": null, "yaw": 2.838962586746257, "pitch": null, "roll": null}, "v": 0.9539178432542154, "accelerator_pedal_position": 0.2687711137227992, "brake_pedal_position": 0.0, "acceleration": 0.17302397608799647, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2393918763009773, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137689.447528} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2405681706377288, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9556480830150953, "gear": 1, "accelerator_pedal_position": 0.2687711137227992, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137689.447528} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.22996926307678, "x": 48.32553562389986, "y": 8.65150293886177, "z": null, "yaw": 2.838962586746257, "pitch": null, "roll": null}, "v": 0.9539178432542154, "accelerator_pedal_position": 0.2687711137227992, "brake_pedal_position": 0.0, "acceleration": 0.17302397608799647, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2393918763009773, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137689.4675279} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.254104421997033, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9555808268593637, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137689.4675279} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.22996926307678, "x": 48.32553562389986, "y": 8.65150293886177, "z": null, "yaw": 2.838962586746257, "pitch": null, "roll": null}, "v": 0.9539178432542154, "accelerator_pedal_position": 0.2687711137227992, "brake_pedal_position": 0.0, "acceleration": 0.17302397608799647, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2393918763009773, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137689.4875278} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.254104421997033, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9572051102944825, "gear": 1, "accelerator_pedal_position": 0.254104421997033, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137689.4875278} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.22996926307678, "x": 48.32553562389986, "y": 8.65150293886177, "z": null, "yaw": 2.838962586746257, "pitch": null, "roll": null}, "v": 0.9539178432542154, "accelerator_pedal_position": 0.2687711137227992, "brake_pedal_position": 0.0, "acceleration": 0.17302397608799647, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2393918763009773, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137689.5075278} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.254104421997033, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9588271485774974, "gear": 1, "accelerator_pedal_position": 0.254104421997033, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137689.5075278} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.22996926307678, "x": 48.32553562389986, "y": 8.65150293886177, "z": null, "yaw": 2.838962586746257, "pitch": null, "roll": null}, "v": 0.9539178432542154, "accelerator_pedal_position": 0.2687711137227992, "brake_pedal_position": 0.0, "acceleration": 0.17302397608799647, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2393918763009773, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137689.5275278} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.254104421997033, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9604469437597115, "gear": 1, "accelerator_pedal_position": 0.254104421997033, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137689.5275278} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137689.5475278, "x": 52.2246132819328, "y": 13.681626503334064, "z": null, "yaw": 2.8665678009471716, "pitch": null, "roll": null}, "v": 0.9620644978939552, "accelerator_pedal_position": 0.254104421997033, "brake_pedal_position": 0.0, "acceleration": 0.08079373160567882, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24143633217689453, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137689.5475278} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2506205955142271, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9620644978939552, "gear": 1, "accelerator_pedal_position": 0.254104421997033, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137689.5475278} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.33996915817261, "x": 48.2246132819328, "y": 8.681626503334064, "z": null, "yaw": 2.8665678009471716, "pitch": null, "roll": null}, "v": 0.9620644978939552, "accelerator_pedal_position": 0.254104421997033, "brake_pedal_position": 0.0, "acceleration": 0.08079373160567882, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24143633217689453, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137689.5675278} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2523224886854497, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9632444855200648, "gear": 1, "accelerator_pedal_position": 0.2506205955142271, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137689.5675278} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.33996915817261, "x": 48.2246132819328, "y": 8.681626503334064, "z": null, "yaw": 2.8665678009471716, "pitch": null, "roll": null}, "v": 0.9620644978939552, "accelerator_pedal_position": 0.254104421997033, "brake_pedal_position": 0.0, "acceleration": 0.08079373160567882, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24143633217689453, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137689.5875278} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2523224886854497, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9646355021740527, "gear": 1, "accelerator_pedal_position": 0.2523224886854497, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137689.5875278} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.33996915817261, "x": 48.2246132819328, "y": 8.681626503334064, "z": null, "yaw": 2.8665678009471716, "pitch": null, "roll": null}, "v": 0.9620644978939552, "accelerator_pedal_position": 0.254104421997033, "brake_pedal_position": 0.0, "acceleration": 0.08079373160567882, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24143633217689453, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137689.6075277} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2523224886854497, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9660245919430867, "gear": 1, "accelerator_pedal_position": 0.2523224886854497, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137689.6075277} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.33996915817261, "x": 48.2246132819328, "y": 8.681626503334064, "z": null, "yaw": 2.8665678009471716, "pitch": null, "roll": null}, "v": 0.9620644978939552, "accelerator_pedal_position": 0.254104421997033, "brake_pedal_position": 0.0, "acceleration": 0.08079373160567882, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24143633217689453, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137689.6275277} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2523224886854497, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9674117567247943, "gear": 1, "accelerator_pedal_position": 0.2523224886854497, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137689.6275277} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.33996915817261, "x": 48.2246132819328, "y": 8.681626503334064, "z": null, "yaw": 2.8665678009471716, "pitch": null, "roll": null}, "v": 0.9620644978939552, "accelerator_pedal_position": 0.254104421997033, "brake_pedal_position": 0.0, "acceleration": 0.08079373160567882, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24143633217689453, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137689.6475277} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2523224886854497, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9687969984173809, "gear": 1, "accelerator_pedal_position": 0.2523224886854497, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137689.6475277} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137689.6575277, "x": 52.122063721724764, "y": 13.709177123163895, "z": null, "yaw": 2.8941730151480862, "pitch": null, "roll": null}, "v": 0.9694888986985986, "accelerator_pedal_position": 0.2523224886854497, "brake_pedal_position": 0.0, "acceleration": 0.06914202210213244, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24329953376349117, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137689.6675277} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2493615213120772, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9701803189196199, "gear": 1, "accelerator_pedal_position": 0.2523224886854497, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137689.6675277} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.44996905326843, "x": 48.122063721724764, "y": 8.709177123163895, "z": null, "yaw": 2.8941730151480862, "pitch": null, "roll": null}, "v": 0.9694888986985986, "accelerator_pedal_position": 0.2523224886854497, "brake_pedal_position": 0.0, "acceleration": 0.06914202210213244, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24329953376349117, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137689.6875277} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25081071612284983, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9711917276699541, "gear": 1, "accelerator_pedal_position": 0.2493615213120772, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137689.6875277} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.44996905326843, "x": 48.122063721724764, "y": 8.709177123163895, "z": null, "yaw": 2.8941730151480862, "pitch": null, "roll": null}, "v": 0.9694888986985986, "accelerator_pedal_position": 0.2523224886854497, "brake_pedal_position": 0.0, "acceleration": 0.06914202210213244, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24329953376349117, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137689.7075276} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25081071612284983, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9723828191535001, "gear": 1, "accelerator_pedal_position": 0.25081071612284983, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137689.7075276} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.44996905326843, "x": 48.122063721724764, "y": 8.709177123163895, "z": null, "yaw": 2.8941730151480862, "pitch": null, "roll": null}, "v": 0.9694888986985986, "accelerator_pedal_position": 0.2523224886854497, "brake_pedal_position": 0.0, "acceleration": 0.06914202210213244, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24329953376349117, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137689.7275276} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25081071612284983, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9735722569830859, "gear": 1, "accelerator_pedal_position": 0.25081071612284983, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137689.7275276} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.44996905326843, "x": 48.122063721724764, "y": 8.709177123163895, "z": null, "yaw": 2.8941730151480862, "pitch": null, "roll": null}, "v": 0.9694888986985986, "accelerator_pedal_position": 0.2523224886854497, "brake_pedal_position": 0.0, "acceleration": 0.06914202210213244, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24329953376349117, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137689.7475276} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25081071612284983, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9747600428888564, "gear": 1, "accelerator_pedal_position": 0.25081071612284983, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137689.7475276} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137689.7675276, "x": 52.018037976677114, "y": 13.734067601421195, "z": null, "yaw": 2.921778229349001, "pitch": null, "roll": null}, "v": 0.9759461786009105, "accelerator_pedal_position": 0.25081071612284983, "brake_pedal_position": 0.0, "acceleration": 0.05924495740250857, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24492003008038735, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137689.7675276} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24861605777047657, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9759461786009105, "gear": 1, "accelerator_pedal_position": 0.25081071612284983, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137689.7675276} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.55996894836426, "x": 48.018037976677114, "y": 8.734067601421195, "z": null, "yaw": 2.921778229349001, "pitch": null, "roll": null}, "v": 0.9759461786009105, "accelerator_pedal_position": 0.25081071612284983, "brake_pedal_position": 0.0, "acceleration": 0.05924495740250857, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24492003008038735, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137689.7875276} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24969530409137547, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9768564289260481, "gear": 1, "accelerator_pedal_position": 0.24861605777047657, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137689.7875276} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.55996894836426, "x": 48.018037976677114, "y": 8.734067601421195, "z": null, "yaw": 2.921778229349001, "pitch": null, "roll": null}, "v": 0.9759461786009105, "accelerator_pedal_position": 0.25081071612284983, "brake_pedal_position": 0.0, "acceleration": 0.05924495740250857, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24492003008038735, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137689.8075275} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24969530409137547, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9779002727289955, "gear": 1, "accelerator_pedal_position": 0.24969530409137547, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137689.8075275} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.55996894836426, "x": 48.018037976677114, "y": 8.734067601421195, "z": null, "yaw": 2.921778229349001, "pitch": null, "roll": null}, "v": 0.9759461786009105, "accelerator_pedal_position": 0.25081071612284983, "brake_pedal_position": 0.0, "acceleration": 0.05924495740250857, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24492003008038735, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137689.8275275} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24969530409137547, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9789426649920518, "gear": 1, "accelerator_pedal_position": 0.24969530409137547, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137689.8275275} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.55996894836426, "x": 48.018037976677114, "y": 8.734067601421195, "z": null, "yaw": 2.921778229349001, "pitch": null, "roll": null}, "v": 0.9759461786009105, "accelerator_pedal_position": 0.25081071612284983, "brake_pedal_position": 0.0, "acceleration": 0.05924495740250857, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24492003008038735, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137689.8475275} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24969530409137547, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9799836072992061, "gear": 1, "accelerator_pedal_position": 0.24969530409137547, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137689.8475275} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.55996894836426, "x": 48.018037976677114, "y": 8.734067601421195, "z": null, "yaw": 2.921778229349001, "pitch": null, "roll": null}, "v": 0.9759461786009105, "accelerator_pedal_position": 0.25081071612284983, "brake_pedal_position": 0.0, "acceleration": 0.05924495740250857, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24492003008038735, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137689.8675275} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24969530409137547, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9810231012340571, "gear": 1, "accelerator_pedal_position": 0.24969530409137547, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137689.8675275} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137689.8775275, "x": 51.91271635420337, "y": 13.756213873251665, "z": null, "yaw": 2.9493834435499156, "pitch": null, "roll": null}, "v": 0.9815423055566356, "accelerator_pedal_position": 0.24969530409137547, "brake_pedal_position": 0.0, "acceleration": 0.051884282317290475, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24632441447409925, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137689.8875275} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2398255791604665, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9820611483798085, "gear": 1, "accelerator_pedal_position": 0.24969530409137547, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137689.8875275} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.66996884346008, "x": 47.91271635420337, "y": 8.756213873251665, "z": null, "yaw": 2.9493834435499156, "pitch": null, "roll": null}, "v": 0.9815423055566356, "accelerator_pedal_position": 0.24969530409137547, "brake_pedal_position": 0.0, "acceleration": 0.051884282317290475, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24632441447409925, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137689.9075274} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24455511529120477, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9818644643161368, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137689.9075274} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.66996884346008, "x": 47.91271635420337, "y": 8.756213873251665, "z": null, "yaw": 2.9493834435499156, "pitch": null, "roll": null}, "v": 0.9815423055566356, "accelerator_pedal_position": 0.24969530409137547, "brake_pedal_position": 0.0, "acceleration": 0.051884282317290475, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24632441447409925, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137689.9275274} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24455511529120477, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9822590402602193, "gear": 1, "accelerator_pedal_position": 0.24455511529120477, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137689.9275274} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.66996884346008, "x": 47.91271635420337, "y": 8.756213873251665, "z": null, "yaw": 2.9493834435499156, "pitch": null, "roll": null}, "v": 0.9815423055566356, "accelerator_pedal_position": 0.24969530409137547, "brake_pedal_position": 0.0, "acceleration": 0.051884282317290475, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24632441447409925, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137689.9475274} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24455511529120477, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.982653066804993, "gear": 1, "accelerator_pedal_position": 0.24455511529120477, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137689.9475274} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.66996884346008, "x": 47.91271635420337, "y": 8.756213873251665, "z": null, "yaw": 2.9493834435499156, "pitch": null, "roll": null}, "v": 0.9815423055566356, "accelerator_pedal_position": 0.24969530409137547, "brake_pedal_position": 0.0, "acceleration": 0.051884282317290475, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24632441447409925, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137689.9675274} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24455511529120477, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9830465446533491, "gear": 1, "accelerator_pedal_position": 0.24455511529120477, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137689.9675274} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137689.9875274, "x": 51.80639892930404, "y": 13.775522778968732, "z": null, "yaw": 2.97698865775083, "pitch": null, "roll": null}, "v": 0.983439474507459, "accelerator_pedal_position": 0.24455511529120477, "brake_pedal_position": 0.0, "acceleration": 0.01962596484446172, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24680052134012476, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137689.9875274} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24541096732381598, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.983439474507459, "gear": 1, "accelerator_pedal_position": 0.24455511529120477, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137689.9875274} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.77996873855591, "x": 47.80639892930404, "y": 8.775522778968732, "z": null, "yaw": 2.97698865775083, "pitch": null, "roll": null}, "v": 0.983439474507459, "accelerator_pedal_position": 0.24455511529120477, "brake_pedal_position": 0.0, "acceleration": 0.01962596484446172, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24680052134012476, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137690.0075274} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2450134861551952, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9839388013041064, "gear": 1, "accelerator_pedal_position": 0.24541096732381598, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137690.0075274} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.77996873855591, "x": 47.80639892930404, "y": 8.775522778968732, "z": null, "yaw": 2.97698865775083, "pitch": null, "roll": null}, "v": 0.983439474507459, "accelerator_pedal_position": 0.24455511529120477, "brake_pedal_position": 0.0, "acceleration": 0.01962596484446172, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24680052134012476, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137690.0275273} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2450134861551952, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9843877646836076, "gear": 1, "accelerator_pedal_position": 0.2450134861551952, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137690.0275273} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.77996873855591, "x": 47.80639892930404, "y": 8.775522778968732, "z": null, "yaw": 2.97698865775083, "pitch": null, "roll": null}, "v": 0.983439474507459, "accelerator_pedal_position": 0.24455511529120477, "brake_pedal_position": 0.0, "acceleration": 0.01962596484446172, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24680052134012476, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137690.0475273} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2450134861551952, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.98483610255629, "gear": 1, "accelerator_pedal_position": 0.2450134861551952, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137690.0475273} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.77996873855591, "x": 47.80639892930404, "y": 8.775522778968732, "z": null, "yaw": 2.97698865775083, "pitch": null, "roll": null}, "v": 0.983439474507459, "accelerator_pedal_position": 0.24455511529120477, "brake_pedal_position": 0.0, "acceleration": 0.01962596484446172, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24680052134012476, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137690.0675273} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2450134861551952, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9852838157132501, "gear": 1, "accelerator_pedal_position": 0.2450134861551952, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137690.0675273} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.77996873855591, "x": 47.80639892930404, "y": 8.775522778968732, "z": null, "yaw": 2.97698865775083, "pitch": null, "roll": null}, "v": 0.983439474507459, "accelerator_pedal_position": 0.24455511529120477, "brake_pedal_position": 0.0, "acceleration": 0.01962596484446172, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24680052134012476, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137690.0875273} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2450134861551952, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9857309049448184, "gear": 1, "accelerator_pedal_position": 0.2450134861551952, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137690.0875273} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137690.0975273, "x": 51.69934538685268, "y": 13.791926923252829, "z": null, "yaw": 3.004593871951745, "pitch": null, "roll": null}, "v": 0.9859542158353494, "accelerator_pedal_position": 0.2450134861551952, "brake_pedal_position": 0.0, "acceleration": 0.022315520520967413, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24743161200390934, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137690.1075273} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24544711974330846, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.986177371040559, "gear": 1, "accelerator_pedal_position": 0.2450134861551952, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137690.1075273} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.88996863365173, "x": 47.69934538685268, "y": 8.791926923252829, "z": null, "yaw": 3.004593871951745, "pitch": null, "roll": null}, "v": 0.9859542158353494, "accelerator_pedal_position": 0.2450134861551952, "brake_pedal_position": 0.0, "acceleration": 0.022315520520967413, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24743161200390934, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137690.1275272} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24525398077427293, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9866774000899566, "gear": 1, "accelerator_pedal_position": 0.24544711974330846, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137690.1275272} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.88996863365173, "x": 47.69934538685268, "y": 8.791926923252829, "z": null, "yaw": 3.004593871951745, "pitch": null, "roll": null}, "v": 0.9859542158353494, "accelerator_pedal_position": 0.2450134861551952, "brake_pedal_position": 0.0, "acceleration": 0.022315520520967413, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24743161200390934, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137690.1475272} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24525398077427293, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9871525980786315, "gear": 1, "accelerator_pedal_position": 0.24525398077427293, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137690.1475272} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.88996863365173, "x": 47.69934538685268, "y": 8.791926923252829, "z": null, "yaw": 3.004593871951745, "pitch": null, "roll": null}, "v": 0.9859542158353494, "accelerator_pedal_position": 0.2450134861551952, "brake_pedal_position": 0.0, "acceleration": 0.022315520520967413, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24743161200390934, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137690.1675272} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24525398077427293, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9876271334858603, "gear": 1, "accelerator_pedal_position": 0.24525398077427293, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137690.1675272} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.88996863365173, "x": 47.69934538685268, "y": 8.791926923252829, "z": null, "yaw": 3.004593871951745, "pitch": null, "roll": null}, "v": 0.9859542158353494, "accelerator_pedal_position": 0.2450134861551952, "brake_pedal_position": 0.0, "acceleration": 0.022315520520967413, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24743161200390934, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137690.1875272} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24525398077427293, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.988101007145456, "gear": 1, "accelerator_pedal_position": 0.24525398077427293, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137690.1875272} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137690.2075272, "x": 51.59160226630709, "y": 13.805404649238355, "z": null, "yaw": 3.0321990861526595, "pitch": null, "roll": null}, "v": 0.9885742198904457, "accelerator_pedal_position": 0.24525398077427293, "brake_pedal_position": 0.0, "acceleration": 0.02363587896236341, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24808911903252934, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137690.2075272} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25284380581937915, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9885742198904457, "gear": 1, "accelerator_pedal_position": 0.24525398077427293, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137690.2075272} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.99996852874756, "x": 47.59160226630709, "y": 8.805404649238355, "z": null, "yaw": 3.0321990861526595, "pitch": null, "roll": null}, "v": 0.9885742198904457, "accelerator_pedal_position": 0.24525398077427293, "brake_pedal_position": 0.0, "acceleration": 0.02363587896236341, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24808911903252934, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137690.2275271} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2492435241272374, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9899951696679327, "gear": 1, "accelerator_pedal_position": 0.25284380581937915, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137690.2275271} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.99996852874756, "x": 47.59160226630709, "y": 8.805404649238355, "z": null, "yaw": 3.0321990861526595, "pitch": null, "roll": null}, "v": 0.9885742198904457, "accelerator_pedal_position": 0.24525398077427293, "brake_pedal_position": 0.0, "acceleration": 0.02363587896236341, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24808911903252934, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137690.2475271} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2492435241272374, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9909642585738363, "gear": 1, "accelerator_pedal_position": 0.2492435241272374, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137690.2475271} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.99996852874756, "x": 47.59160226630709, "y": 8.805404649238355, "z": null, "yaw": 3.0321990861526595, "pitch": null, "roll": null}, "v": 0.9885742198904457, "accelerator_pedal_position": 0.24525398077427293, "brake_pedal_position": 0.0, "acceleration": 0.02363587896236341, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24808911903252934, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137690.267527} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2492435241272374, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9919319948241319, "gear": 1, "accelerator_pedal_position": 0.2492435241272374, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137690.267527} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.99996852874756, "x": 47.59160226630709, "y": 8.805404649238355, "z": null, "yaw": 3.0321990861526595, "pitch": null, "roll": null}, "v": 0.9885742198904457, "accelerator_pedal_position": 0.24525398077427293, "brake_pedal_position": 0.0, "acceleration": 0.02363587896236341, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24808911903252934, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137690.287527} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2492435241272374, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9928983799323832, "gear": 1, "accelerator_pedal_position": 0.2492435241272374, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137690.287527} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.99996852874756, "x": 47.59160226630709, "y": 8.805404649238355, "z": null, "yaw": 3.0321990861526595, "pitch": null, "roll": null}, "v": 0.9885742198904457, "accelerator_pedal_position": 0.24525398077427293, "brake_pedal_position": 0.0, "acceleration": 0.02363587896236341, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24808911903252934, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137690.307527} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2492435241272374, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9938634154116093, "gear": 1, "accelerator_pedal_position": 0.2492435241272374, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137690.307527} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137690.317527, "x": 51.483064184147274, "y": 13.815947665332754, "z": null, "yaw": 3.059804300353574, "pitch": null, "roll": null}, "v": 0.9943454275130065, "accelerator_pedal_position": 0.2492435241272374, "brake_pedal_position": 0.0, "acceleration": 0.048167526127423144, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24953744105633613, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137690.327527} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23284309913765952, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9948271027742807, "gear": 1, "accelerator_pedal_position": 0.2492435241272374, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137690.327527} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.109968423843384, "x": 47.483064184147274, "y": 8.815947665332754, "z": null, "yaw": 3.059804300353574, "pitch": null, "roll": null}, "v": 0.9943454275130065, "accelerator_pedal_position": 0.2492435241272374, "brake_pedal_position": 0.0, "acceleration": 0.048167526127423144, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24953744105633613, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137690.347527} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24068353390960057, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9937401068603491, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137690.347527} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.109968423843384, "x": 47.483064184147274, "y": 8.815947665332754, "z": null, "yaw": 3.059804300353574, "pitch": null, "roll": null}, "v": 0.9943454275130065, "accelerator_pedal_position": 0.2492435241272374, "brake_pedal_position": 0.0, "acceleration": 0.048167526127423144, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24953744105633613, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137690.367527} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24068353390960057, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9936343415764681, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137690.367527} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.109968423843384, "x": 47.483064184147274, "y": 8.815947665332754, "z": null, "yaw": 3.059804300353574, "pitch": null, "roll": null}, "v": 0.9943454275130065, "accelerator_pedal_position": 0.2492435241272374, "brake_pedal_position": 0.0, "acceleration": 0.048167526127423144, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24953744105633613, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137690.387527} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24068353390960057, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9935287240441599, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137690.387527} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.109968423843384, "x": 47.483064184147274, "y": 8.815947665332754, "z": null, "yaw": 3.059804300353574, "pitch": null, "roll": null}, "v": 0.9943454275130065, "accelerator_pedal_position": 0.2492435241272374, "brake_pedal_position": 0.0, "acceleration": 0.048167526127423144, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24953744105633613, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137690.407527} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24068353390960057, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9934232540525586, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137690.407527} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137690.427527, "x": 51.37401061224123, "y": 13.82351102059642, "z": null, "yaw": 3.087409514554489, "pitch": null, "roll": null}, "v": 0.9933179313911116, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25953270169778675, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24927958423328594, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137690.427527} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24354451126464677, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9933179313911116, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137690.427527} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.21996831893921, "x": 47.37401061224123, "y": 8.82351102059642, "z": null, "yaw": 3.087409514554489, "pitch": null, "roll": null}, "v": 0.9933179313911116, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25953270169778675, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24927958423328594, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137690.447527} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2421766700907551, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9935702530888499, "gear": 1, "accelerator_pedal_position": 0.24354451126464677, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137690.447527} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.21996831893921, "x": 47.37401061224123, "y": 8.82351102059642, "z": null, "yaw": 3.087409514554489, "pitch": null, "roll": null}, "v": 0.9933179313911116, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25953270169778675, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24927958423328594, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137690.467527} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2421766700907551, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9936513019025086, "gear": 1, "accelerator_pedal_position": 0.2421766700907551, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137690.467527} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.21996831893921, "x": 47.37401061224123, "y": 8.82351102059642, "z": null, "yaw": 3.087409514554489, "pitch": null, "roll": null}, "v": 0.9933179313911116, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25953270169778675, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24927958423328594, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137690.487527} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2421766700907551, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9937322374938765, "gear": 1, "accelerator_pedal_position": 0.2421766700907551, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137690.487527} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.21996831893921, "x": 47.37401061224123, "y": 8.82351102059642, "z": null, "yaw": 3.087409514554489, "pitch": null, "roll": null}, "v": 0.9933179313911116, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25953270169778675, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24927958423328594, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137690.5075269} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2421766700907551, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9938130600185019, "gear": 1, "accelerator_pedal_position": 0.2421766700907551, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137690.5075269} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.21996831893921, "x": 47.37401061224123, "y": 8.82351102059642, "z": null, "yaw": 3.087409514554489, "pitch": null, "roll": null}, "v": 0.9933179313911116, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25953270169778675, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24927958423328594, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137690.5275269} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2421766700907551, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9938937696317265, "gear": 1, "accelerator_pedal_position": 0.2421766700907551, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137690.5275269} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137690.5375268, "x": 51.264805256680866, "y": 13.828060307126469, "z": null, "yaw": 3.1150147287554035, "pitch": null, "roll": null}, "v": 0.9939340821450515, "accelerator_pedal_position": 0.2421766700907551, "brake_pedal_position": 0.0, "acceleration": 0.0040284343634715, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24943421126549112, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137690.5475268} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24754344146794088, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9939743664886862, "gear": 1, "accelerator_pedal_position": 0.2421766700907551, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137690.5475268} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.329968214035034, "x": 47.264805256680866, "y": 8.828060307126469, "z": null, "yaw": 3.1150147287554035, "pitch": null, "roll": null}, "v": 0.9939340821450515, "accelerator_pedal_position": 0.2421766700907551, "brake_pedal_position": 0.0, "acceleration": 0.0040284343634715, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24943421126549112, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137690.5675268} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24499111492806988, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9947254627604876, "gear": 1, "accelerator_pedal_position": 0.24754344146794088, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137690.5675268} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.329968214035034, "x": 47.264805256680866, "y": 8.828060307126469, "z": null, "yaw": 3.1150147287554035, "pitch": null, "roll": null}, "v": 0.9939340821450515, "accelerator_pedal_position": 0.2421766700907551, "brake_pedal_position": 0.0, "acceleration": 0.0040284343634715, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24943421126549112, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137690.5875268} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24499111492806988, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9951565801934533, "gear": 1, "accelerator_pedal_position": 0.24499111492806988, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137690.5875268} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.329968214035034, "x": 47.264805256680866, "y": 8.828060307126469, "z": null, "yaw": 3.1150147287554035, "pitch": null, "roll": null}, "v": 0.9939340821450515, "accelerator_pedal_position": 0.2421766700907551, "brake_pedal_position": 0.0, "acceleration": 0.0040284343634715, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24943421126549112, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137690.6075268} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24499111492806988, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9955870951264889, "gear": 1, "accelerator_pedal_position": 0.24499111492806988, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137690.6075268} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.329968214035034, "x": 47.264805256680866, "y": 8.828060307126469, "z": null, "yaw": 3.1150147287554035, "pitch": null, "roll": null}, "v": 0.9939340821450515, "accelerator_pedal_position": 0.2421766700907551, "brake_pedal_position": 0.0, "acceleration": 0.0040284343634715, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24943421126549112, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137690.6275268} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24499111492806988, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9960170083274955, "gear": 1, "accelerator_pedal_position": 0.24499111492806988, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137690.6275268} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137690.6475267, "x": 51.1553585518476, "y": 13.829595299338928, "z": null, "yaw": 3.142619942956318, "pitch": null, "roll": null}, "v": 0.9964463205636113, "accelerator_pedal_position": 0.24499111492806988, "brake_pedal_position": 0.0, "acceleration": 0.02144309957460855, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.25006467380792846, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137690.6475267} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2344687520226343, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9964463205636113, "gear": 1, "accelerator_pedal_position": 0.24499111492806988, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137690.6475267} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.43996810913086, "x": 47.1553585518476, "y": 8.829595299338928, "z": null, "yaw": 3.142619942956318, "pitch": null, "roll": null}, "v": 0.9964463205636113, "accelerator_pedal_position": 0.24499111492806988, "brake_pedal_position": 0.0, "acceleration": 0.02144309957460855, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.25006467380792846, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137690.6675267} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23949278372710453, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9955601971089499, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137690.6675267} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.43996810913086, "x": 47.1553585518476, "y": 8.829595299338928, "z": null, "yaw": 3.142619942956318, "pitch": null, "roll": null}, "v": 0.9964463205636113, "accelerator_pedal_position": 0.24499111492806988, "brake_pedal_position": 0.0, "acceleration": 0.02144309957460855, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.25006467380792846, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137690.6875267} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23949278372710453, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9953030967572628, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137690.6875267} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.43996810913086, "x": 47.1553585518476, "y": 8.829595299338928, "z": null, "yaw": 3.142619942956318, "pitch": null, "roll": null}, "v": 0.9964463205636113, "accelerator_pedal_position": 0.24499111492806988, "brake_pedal_position": 0.0, "acceleration": 0.02144309957460855, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.25006467380792846, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137690.7075267} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23949278372710453, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9950463557440044, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137690.7075267} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.43996810913086, "x": 47.1553585518476, "y": 8.829595299338928, "z": null, "yaw": 3.142619942956318, "pitch": null, "roll": null}, "v": 0.9964463205636113, "accelerator_pedal_position": 0.24499111492806988, "brake_pedal_position": 0.0, "acceleration": 0.02144309957460855, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.25006467380792846, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137690.7275267} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23949278372710453, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.994789973540585, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137690.7275267} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.43996810913086, "x": 47.1553585518476, "y": 8.829595299338928, "z": null, "yaw": 3.142619942956318, "pitch": null, "roll": null}, "v": 0.9964463205636113, "accelerator_pedal_position": 0.24499111492806988, "brake_pedal_position": 0.0, "acceleration": 0.02144309957460855, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.25006467380792846, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137690.7475266} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23949278372710453, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9945339496192644, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137690.7475266} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137690.7575266, "x": 51.045893387227416, "y": 13.828109670790692, "z": null, "yaw": 3.170225157157233, "pitch": null, "roll": null}, "v": 0.9944060718497043, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2596087379498008, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24955266014637809, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137690.7675266} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2431906254281161, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9942782834531503, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137690.7675266} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.549968004226685, "x": 47.045893387227416, "y": 8.828109670790692, "z": null, "yaw": 3.170225157157233, "pitch": null, "roll": null}, "v": 0.9944060718497043, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2596087379498008, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24955266014637809, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137690.7875266} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24141888043582543, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9944850432132843, "gear": 1, "accelerator_pedal_position": 0.2431906254281161, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137690.7875266} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.549968004226685, "x": 47.045893387227416, "y": 8.828109670790692, "z": null, "yaw": 3.170225157157233, "pitch": null, "roll": null}, "v": 0.9944060718497043, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2596087379498008, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24955266014637809, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137690.8075266} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24141888043582543, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9944701233398587, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137690.8075266} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.549968004226685, "x": 47.045893387227416, "y": 8.828109670790692, "z": null, "yaw": 3.170225157157233, "pitch": null, "roll": null}, "v": 0.9944060718497043, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2596087379498008, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24955266014637809, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137690.8275266} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24141888043582543, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9944552243139885, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137690.8275266} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.549968004226685, "x": 47.045893387227416, "y": 8.828109670790692, "z": null, "yaw": 3.170225157157233, "pitch": null, "roll": null}, "v": 0.9944060718497043, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2596087379498008, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24955266014637809, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137690.8475266} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24141888043582543, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9944403461064546, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137690.8475266} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137690.8675265, "x": 50.93660218979064, "y": 13.823606454828651, "z": null, "yaw": 3.1978303713581475, "pitch": null, "roll": null}, "v": 0.994425488688079, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2596100949599292, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24955753292803662, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137690.8675265} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24395105898920483, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.994425488688079, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137690.8675265} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.65996789932251, "x": 46.93660218979064, "y": 8.823606454828651, "z": null, "yaw": 3.1978303713581475, "pitch": null, "roll": null}, "v": 0.994425488688079, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2596100949599292, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24955753292803662, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137690.8875265} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24274536246702158, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9947270637402618, "gear": 1, "accelerator_pedal_position": 0.24395105898920483, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137690.8875265} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.65996789932251, "x": 46.93660218979064, "y": 8.823606454828651, "z": null, "yaw": 3.1978303713581475, "pitch": null, "roll": null}, "v": 0.994425488688079, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2596100949599292, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24955753292803662, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137690.9075265} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24274536246702158, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9948775579860472, "gear": 1, "accelerator_pedal_position": 0.24274536246702158, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137690.9075265} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.65996789932251, "x": 46.93660218979064, "y": 8.823606454828651, "z": null, "yaw": 3.1978303713581475, "pitch": null, "roll": null}, "v": 0.994425488688079, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2596100949599292, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24955753292803662, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137690.9275265} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24274536246702158, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9950278419240381, "gear": 1, "accelerator_pedal_position": 0.24274536246702158, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137690.9275265} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.65996789932251, "x": 46.93660218979064, "y": 8.823606454828651, "z": null, "yaw": 3.1978303713581475, "pitch": null, "roll": null}, "v": 0.994425488688079, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2596100949599292, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24955753292803662, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137690.9475265} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24274536246702158, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.995177915839098, "gear": 1, "accelerator_pedal_position": 0.24274536246702158, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137690.9475265} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.65996789932251, "x": 46.93660218979064, "y": 8.823606454828651, "z": null, "yaw": 3.1978303713581475, "pitch": null, "roll": null}, "v": 0.994425488688079, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2596100949599292, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24955753292803662, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137690.9675264} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24274536246702158, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9953277800157294, "gear": 1, "accelerator_pedal_position": 0.24274536246702158, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137690.9675264} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137690.9775264, "x": 50.82742194455661, "y": 13.81608433106488, "z": null, "yaw": 3.225435585559062, "pitch": null, "roll": null}, "v": 0.9954026335409433, "accelerator_pedal_position": 0.24274536246702158, "brake_pedal_position": 0.0, "acceleration": 0.007480119713235145, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24980275377320604, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137690.9875264} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24316117103393425, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9954774347380756, "gear": 1, "accelerator_pedal_position": 0.24274536246702158, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137690.9875264} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.769967794418335, "x": 46.82742194455661, "y": 8.81608433106488, "z": null, "yaw": 3.225435585559062, "pitch": null, "roll": null}, "v": 0.9954026335409433, "accelerator_pedal_position": 0.24274536246702158, "brake_pedal_position": 0.0, "acceleration": 0.007480119713235145, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24980275377320604, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137691.0075264} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24296837072448046, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9956788381922099, "gear": 1, "accelerator_pedal_position": 0.24316117103393425, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137691.0075264} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.769967794418335, "x": 46.82742194455661, "y": 8.81608433106488, "z": null, "yaw": 3.225435585559062, "pitch": null, "roll": null}, "v": 0.9954026335409433, "accelerator_pedal_position": 0.24274536246702158, "brake_pedal_position": 0.0, "acceleration": 0.007480119713235145, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24980275377320604, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137691.0275264} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24296837072448046, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9958558685182719, "gear": 1, "accelerator_pedal_position": 0.24296837072448046, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137691.0275264} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.769967794418335, "x": 46.82742194455661, "y": 8.81608433106488, "z": null, "yaw": 3.225435585559062, "pitch": null, "roll": null}, "v": 0.9954026335409433, "accelerator_pedal_position": 0.24274536246702158, "brake_pedal_position": 0.0, "acceleration": 0.007480119713235145, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24980275377320604, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137691.0475264} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24296837072448046, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9960326513850047, "gear": 1, "accelerator_pedal_position": 0.24296837072448046, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137691.0475264} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.769967794418335, "x": 46.82742194455661, "y": 8.81608433106488, "z": null, "yaw": 3.225435585559062, "pitch": null, "roll": null}, "v": 0.9954026335409433, "accelerator_pedal_position": 0.24274536246702158, "brake_pedal_position": 0.0, "acceleration": 0.007480119713235145, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24980275377320604, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137691.0675263} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24296837072448046, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9962091871258193, "gear": 1, "accelerator_pedal_position": 0.24296837072448046, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137691.0675263} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137691.0875263, "x": 50.71839025506525, "y": 13.805541763654523, "z": null, "yaw": 3.253040799759977, "pitch": null, "roll": null}, "v": 0.9963854760737129, "accelerator_pedal_position": 0.24296837072448046, "brake_pedal_position": 0.0, "acceleration": 0.008805203055010813, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2500494044881413, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137691.0875263} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23150914439074183, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9963854760737129, "gear": 1, "accelerator_pedal_position": 0.24296837072448046, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137691.0875263} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.87996768951416, "x": 46.71839025506525, "y": 8.805541763654523, "z": null, "yaw": 3.253040799759977, "pitch": null, "roll": null}, "v": 0.9963854760737129, "accelerator_pedal_position": 0.24296837072448046, "brake_pedal_position": 0.0, "acceleration": 0.008805203055010813, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2500494044881413, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137691.1075263} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2369711572414051, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.995129616054277, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137691.1075263} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.87996768951416, "x": 46.71839025506525, "y": 8.805541763654523, "z": null, "yaw": 3.253040799759977, "pitch": null, "roll": null}, "v": 0.9963854760737129, "accelerator_pedal_position": 0.24296837072448046, "brake_pedal_position": 0.0, "acceleration": 0.008805203055010813, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2500494044881413, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137691.1275263} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2369711572414051, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9945580243432336, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137691.1275263} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.87996768951416, "x": 46.71839025506525, "y": 8.805541763654523, "z": null, "yaw": 3.253040799759977, "pitch": null, "roll": null}, "v": 0.9963854760737129, "accelerator_pedal_position": 0.24296837072448046, "brake_pedal_position": 0.0, "acceleration": 0.008805203055010813, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2500494044881413, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137691.1475263} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2369711572414051, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.993987231369801, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137691.1475263} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.87996768951416, "x": 46.71839025506525, "y": 8.805541763654523, "z": null, "yaw": 3.253040799759977, "pitch": null, "roll": null}, "v": 0.9963854760737129, "accelerator_pedal_position": 0.24296837072448046, "brake_pedal_position": 0.0, "acceleration": 0.008805203055010813, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2500494044881413, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137691.1675262} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2369711572414051, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9934172358875535, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137691.1675262} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.87996768951416, "x": 46.71839025506525, "y": 8.805541763654523, "z": null, "yaw": 3.253040799759977, "pitch": null, "roll": null}, "v": 0.9963854760737129, "accelerator_pedal_position": 0.24296837072448046, "brake_pedal_position": 0.0, "acceleration": 0.008805203055010813, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2500494044881413, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137691.1875262} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2369711572414051, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9928480366523527, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137691.1875262} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137691.1975262, "x": 50.6098530069655, "y": 13.792015097086498, "z": null, "yaw": 3.2806460139608915, "pitch": null, "roll": null}, "v": 0.9925637352392258, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25948001444708174, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24909031381217403, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137691.2075262} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24966276946133575, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9922796324223428, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137691.2075262} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.989967584609985, "x": 46.6098530069655, "y": 8.792015097086498, "z": null, "yaw": 3.2806460139608915, "pitch": null, "roll": null}, "v": 0.9925637352392258, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25948001444708174, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24909031381217403, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137691.2275262} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24359879112541064, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9932979194343206, "gear": 1, "accelerator_pedal_position": 0.24966276946133575, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137691.2275262} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.989967584609985, "x": 46.6098530069655, "y": 8.792015097086498, "z": null, "yaw": 3.2806460139608915, "pitch": null, "roll": null}, "v": 0.9925637352392258, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25948001444708174, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24909031381217403, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137691.2475262} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24359879112541064, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9935570516982783, "gear": 1, "accelerator_pedal_position": 0.24359879112541064, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137691.2475262} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.989967584609985, "x": 46.6098530069655, "y": 8.792015097086498, "z": null, "yaw": 3.2806460139608915, "pitch": null, "roll": null}, "v": 0.9925637352392258, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25948001444708174, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24909031381217403, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137691.2675261} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24359879112541064, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9938158219781174, "gear": 1, "accelerator_pedal_position": 0.24359879112541064, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137691.2675261} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.989967584609985, "x": 46.6098530069655, "y": 8.792015097086498, "z": null, "yaw": 3.2806460139608915, "pitch": null, "roll": null}, "v": 0.9925637352392258, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25948001444708174, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24909031381217403, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137691.2875261} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24359879112541064, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9940742307527208, "gear": 1, "accelerator_pedal_position": 0.24359879112541064, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137691.2875261} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137691.307526, "x": 50.50183342936755, "y": 13.775512070394658, "z": null, "yaw": 3.308251228161806, "pitch": null, "roll": null}, "v": 0.9943322785004152, "accelerator_pedal_position": 0.24359879112541064, "brake_pedal_position": 0.0, "acceleration": 0.012888863808117323, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24953414122625325, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137691.307526} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24546872085933308, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9943322785004152, "gear": 1, "accelerator_pedal_position": 0.24359879112541064, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137691.307526} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.09996747970581, "x": 46.50183342936755, "y": 8.775512070394658, "z": null, "yaw": 3.308251228161806, "pitch": null, "roll": null}, "v": 0.9943322785004152, "accelerator_pedal_position": 0.24359879112541064, "brake_pedal_position": 0.0, "acceleration": 0.012888863808117323, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24953414122625325, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137691.327526} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2445876922623905, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9948236252343845, "gear": 1, "accelerator_pedal_position": 0.24546872085933308, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137691.327526} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.09996747970581, "x": 46.50183342936755, "y": 8.775512070394658, "z": null, "yaw": 3.308251228161806, "pitch": null, "roll": null}, "v": 0.9943322785004152, "accelerator_pedal_position": 0.24359879112541064, "brake_pedal_position": 0.0, "acceleration": 0.012888863808117323, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24953414122625325, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137691.347526} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2445876922623905, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9952041952802424, "gear": 1, "accelerator_pedal_position": 0.2445876922623905, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137691.347526} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.09996747970581, "x": 46.50183342936755, "y": 8.775512070394658, "z": null, "yaw": 3.308251228161806, "pitch": null, "roll": null}, "v": 0.9943322785004152, "accelerator_pedal_position": 0.24359879112541064, "brake_pedal_position": 0.0, "acceleration": 0.012888863808117323, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24953414122625325, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137691.367526} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2445876922623905, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9955842334585389, "gear": 1, "accelerator_pedal_position": 0.2445876922623905, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137691.367526} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.09996747970581, "x": 46.50183342936755, "y": 8.775512070394658, "z": null, "yaw": 3.308251228161806, "pitch": null, "roll": null}, "v": 0.9943322785004152, "accelerator_pedal_position": 0.24359879112541064, "brake_pedal_position": 0.0, "acceleration": 0.012888863808117323, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24953414122625325, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137691.387526} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2445876922623905, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9959637404548366, "gear": 1, "accelerator_pedal_position": 0.2445876922623905, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137691.387526} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.09996747970581, "x": 46.50183342936755, "y": 8.775512070394658, "z": null, "yaw": 3.308251228161806, "pitch": null, "roll": null}, "v": 0.9943322785004152, "accelerator_pedal_position": 0.24359879112541064, "brake_pedal_position": 0.0, "acceleration": 0.012888863808117323, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.24953414122625325, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137691.407526} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2445876922623905, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9963427169539822, "gear": 1, "accelerator_pedal_position": 0.2445876922623905, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137691.407526} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137691.417526, "x": 50.394098732730086, "y": 13.755995402331223, "z": null, "yaw": 3.335856442362721, "pitch": null, "roll": null}, "v": 0.996532006480942, "accelerator_pedal_position": 0.2445876922623905, "brake_pedal_position": 0.0, "acceleration": 0.018915715916484055, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2500861772452186, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137691.427526} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23868456545159253, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9967211636401068, "gear": 1, "accelerator_pedal_position": 0.2445876922623905, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137691.427526} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.209967374801636, "x": 46.394098732730086, "y": 8.755995402331223, "z": null, "yaw": 3.335856442362721, "pitch": null, "roll": null}, "v": 0.996532006480942, "accelerator_pedal_position": 0.2445876922623905, "brake_pedal_position": 0.0, "acceleration": 0.018915715916484055, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2500861772452186, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137691.447526} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24150729619997421, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9963614483654671, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137691.447526} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.209967374801636, "x": 46.394098732730086, "y": 8.755995402331223, "z": null, "yaw": 3.335856442362721, "pitch": null, "roll": null}, "v": 0.996532006480942, "accelerator_pedal_position": 0.2445876922623905, "brake_pedal_position": 0.0, "acceleration": 0.018915715916484055, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2500861772452186, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137691.467526} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24150729619997421, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9963549539864035, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137691.467526} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.209967374801636, "x": 46.394098732730086, "y": 8.755995402331223, "z": null, "yaw": 3.335856442362721, "pitch": null, "roll": null}, "v": 0.996532006480942, "accelerator_pedal_position": 0.2445876922623905, "brake_pedal_position": 0.0, "acceleration": 0.018915715916484055, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2500861772452186, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137691.487526} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24150729619997421, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9963484686868301, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137691.487526} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.209967374801636, "x": 46.394098732730086, "y": 8.755995402331223, "z": null, "yaw": 3.335856442362721, "pitch": null, "roll": null}, "v": 0.996532006480942, "accelerator_pedal_position": 0.2445876922623905, "brake_pedal_position": 0.0, "acceleration": 0.018915715916484055, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2500861772452186, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137691.507526} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24150729619997421, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9963419924540367, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137691.507526} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137691.527526, "x": 50.28683178081947, "y": 13.73348964582555, "z": null, "yaw": 3.3634616565636355, "pitch": null, "roll": null}, "v": 0.9963355252753305, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25974362105302323, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2500368690109699, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137691.527526} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24471294990052536, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9963355252753305, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137691.527526} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.31996726989746, "x": 46.28683178081947, "y": 8.73348964582555, "z": null, "yaw": 3.3634616565636355, "pitch": null, "roll": null}, "v": 0.9963355252753305, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25974362105302323, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2500368690109699, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137691.547526} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2431854005432475, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9967296337462098, "gear": 1, "accelerator_pedal_position": 0.24471294990052536, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137691.547526} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.31996726989746, "x": 46.28683178081947, "y": 8.73348964582555, "z": null, "yaw": 3.3634616565636355, "pitch": null, "roll": null}, "v": 0.9963355252753305, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25974362105302323, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2500368690109699, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137691.5675259} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2431854005432475, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9969323142900868, "gear": 1, "accelerator_pedal_position": 0.2431854005432475, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137691.5675259} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.31996726989746, "x": 46.28683178081947, "y": 8.73348964582555, "z": null, "yaw": 3.3634616565636355, "pitch": null, "roll": null}, "v": 0.9963355252753305, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25974362105302323, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2500368690109699, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137691.5875258} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2431854005432475, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9971347114331524, "gear": 1, "accelerator_pedal_position": 0.2431854005432475, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137691.5875258} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.31996726989746, "x": 46.28683178081947, "y": 8.73348964582555, "z": null, "yaw": 3.3634616565636355, "pitch": null, "roll": null}, "v": 0.9963355252753305, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25974362105302323, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2500368690109699, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137691.6075258} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2431854005432475, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9973368255552956, "gear": 1, "accelerator_pedal_position": 0.2431854005432475, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137691.6075258} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.31996726989746, "x": 46.28683178081947, "y": 8.73348964582555, "z": null, "yaw": 3.3634616565636355, "pitch": null, "roll": null}, "v": 0.9963355252753305, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25974362105302323, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2500368690109699, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137691.6275258} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2431854005432475, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9975386570359426, "gear": 1, "accelerator_pedal_position": 0.2431854005432475, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137691.6275258} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137691.6375258, "x": 50.1801639278166, "y": 13.708016274099773, "z": null, "yaw": 3.39106687076455, "pitch": null, "roll": null}, "v": 0.9976394669041495, "accelerator_pedal_position": 0.2431854005432475, "brake_pedal_position": 0.0, "acceleration": 0.01007393499084136, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.25036410162887024, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137691.6475258} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2455430267704438, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9977402062540579, "gear": 1, "accelerator_pedal_position": 0.2431854005432475, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137691.6475258} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.429967164993286, "x": 46.1801639278166, "y": 8.708016274099773, "z": null, "yaw": 3.39106687076455, "pitch": null, "roll": null}, "v": 0.9976394669041495, "accelerator_pedal_position": 0.2431854005432475, "brake_pedal_position": 0.0, "acceleration": 0.01007393499084136, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.25036410162887024, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137691.6675258} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2444272954269124, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9982360737818551, "gear": 1, "accelerator_pedal_position": 0.2455430267704438, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137691.6675258} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.429967164993286, "x": 46.1801639278166, "y": 8.708016274099773, "z": null, "yaw": 3.39106687076455, "pitch": null, "roll": null}, "v": 0.9976394669041495, "accelerator_pedal_position": 0.2431854005432475, "brake_pedal_position": 0.0, "acceleration": 0.01007393499084136, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.25036410162887024, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137691.6875257} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2444272954269124, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.998591830085965, "gear": 1, "accelerator_pedal_position": 0.2444272954269124, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137691.6875257} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.429967164993286, "x": 46.1801639278166, "y": 8.708016274099773, "z": null, "yaw": 3.39106687076455, "pitch": null, "roll": null}, "v": 0.9976394669041495, "accelerator_pedal_position": 0.2431854005432475, "brake_pedal_position": 0.0, "acceleration": 0.01007393499084136, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.25036410162887024, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137691.7075257} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2444272954269124, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9989470887184674, "gear": 1, "accelerator_pedal_position": 0.2444272954269124, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137691.7075257} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.429967164993286, "x": 46.1801639278166, "y": 8.708016274099773, "z": null, "yaw": 3.39106687076455, "pitch": null, "roll": null}, "v": 0.9976394669041495, "accelerator_pedal_position": 0.2431854005432475, "brake_pedal_position": 0.0, "acceleration": 0.01007393499084136, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.25036410162887024, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137691.7275257} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2444272954269124, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.999301850325095, "gear": 1, "accelerator_pedal_position": 0.2444272954269124, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137691.7275257} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137691.7475257, "x": 50.07407420288958, "y": 13.679563763200838, "z": null, "yaw": 3.418672084965465, "pitch": null, "roll": null}, "v": 0.9996561155508891, "accelerator_pedal_position": 0.2444272954269124, "brake_pedal_position": 0.0, "acceleration": 0.017694667147075127, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.250870192700336, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137691.7475257} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2388744300495082, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9996561155508891, "gear": 1, "accelerator_pedal_position": 0.2444272954269124, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137691.7475257} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.53996706008911, "x": 46.07407420288958, "y": 8.679563763200838, "z": null, "yaw": 3.418672084965465, "pitch": null, "roll": null}, "v": 0.9996561155508891, "accelerator_pedal_position": 0.2444272954269124, "brake_pedal_position": 0.0, "acceleration": 0.017694667147075127, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.250870192700336, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137691.7675257} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24152940428819894, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9993160197822522, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137691.7675257} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.53996706008911, "x": 46.07407420288958, "y": 8.679563763200838, "z": null, "yaw": 3.418672084965465, "pitch": null, "roll": null}, "v": 0.9996561155508891, "accelerator_pedal_position": 0.2444272954269124, "brake_pedal_position": 0.0, "acceleration": 0.017694667147075127, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.250870192700336, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137691.7875257} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24152940428819894, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9993081555499213, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137691.7875257} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.53996706008911, "x": 46.07407420288958, "y": 8.679563763200838, "z": null, "yaw": 3.418672084965465, "pitch": null, "roll": null}, "v": 0.9996561155508891, "accelerator_pedal_position": 0.2444272954269124, "brake_pedal_position": 0.0, "acceleration": 0.017694667147075127, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.250870192700336, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137691.8075256} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24152940428819894, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9993003023214936, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137691.8075256} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.53996706008911, "x": 46.07407420288958, "y": 8.679563763200838, "z": null, "yaw": 3.418672084965465, "pitch": null, "roll": null}, "v": 0.9996561155508891, "accelerator_pedal_position": 0.2444272954269124, "brake_pedal_position": 0.0, "acceleration": 0.017694667147075127, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.250870192700336, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137691.8275256} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24152940428819894, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9992924600815474, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137691.8275256} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.53996706008911, "x": 46.07407420288958, "y": 8.679563763200838, "z": null, "yaw": 3.418672084965465, "pitch": null, "roll": null}, "v": 0.9996561155508891, "accelerator_pedal_position": 0.2444272954269124, "brake_pedal_position": 0.0, "acceleration": 0.017694667147075127, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.250870192700336, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137691.8475256} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24152940428819894, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9992846288146825, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137691.8475256} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137691.8575256, "x": 49.9687275278242, "y": 13.648169799888635, "z": null, "yaw": 3.4462772991663795, "pitch": null, "roll": null}, "v": 0.999280717291349, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2599496553840706, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2507759840697428, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137691.8675256} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2371440846887745, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9992768085055208, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137691.8675256} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.64996695518494, "x": 45.9687275278242, "y": 8.648169799888635, "z": null, "yaw": 3.4462772991663795, "pitch": null, "roll": null}, "v": 0.999280717291349, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2599496553840706, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2507759840697428, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137691.8875256} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23923033133927696, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9987210259991407, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137691.8875256} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.64996695518494, "x": 45.9687275278242, "y": 8.648169799888635, "z": null, "yaw": 3.4462772991663795, "pitch": null, "roll": null}, "v": 0.999280717291349, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2599496553840706, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2507759840697428, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137691.9075255} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23923033133927696, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9984267106595953, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137691.9075255} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.64996695518494, "x": 45.9687275278242, "y": 8.648169799888635, "z": null, "yaw": 3.4462772991663795, "pitch": null, "roll": null}, "v": 0.999280717291349, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2599496553840706, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2507759840697428, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137691.9275255} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23923033133927696, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9981328070408824, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137691.9275255} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.64996695518494, "x": 45.9687275278242, "y": 8.648169799888635, "z": null, "yaw": 3.4462772991663795, "pitch": null, "roll": null}, "v": 0.999280717291349, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2599496553840706, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2507759840697428, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137691.9475255} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23923033133927696, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9978393145325014, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137691.9475255} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137691.9675255, "x": 49.86437894928507, "y": 13.613910476513986, "z": null, "yaw": 3.473882513367294, "pitch": null, "roll": null}, "v": 0.9975462325249511, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2598282964864948, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2503407038560643, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137691.9675255} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24374912731118234, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9975462325249511, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137691.9675255} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.75996685028076, "x": 45.86437894928507, "y": 8.613910476513986, "z": null, "yaw": 3.473882513367294, "pitch": null, "roll": null}, "v": 0.9975462325249511, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2598282964864948, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2503407038560643, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137691.9875255} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24158807223377543, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9978182123477848, "gear": 1, "accelerator_pedal_position": 0.24374912731118234, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137691.9875255} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.75996685028076, "x": 45.86437894928507, "y": 8.613910476513986, "z": null, "yaw": 3.473882513367294, "pitch": null, "roll": null}, "v": 0.9975462325249511, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2598282964864948, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2503407038560643, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137692.0075254} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24158807223377543, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9978197743811182, "gear": 1, "accelerator_pedal_position": 0.24158807223377543, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137692.0075254} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.75996685028076, "x": 45.86437894928507, "y": 8.613910476513986, "z": null, "yaw": 3.473882513367294, "pitch": null, "roll": null}, "v": 0.9975462325249511, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2598282964864948, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2503407038560643, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137692.0275254} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24158807223377543, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.997821334229732, "gear": 1, "accelerator_pedal_position": 0.24158807223377543, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137692.0275254} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.75996685028076, "x": 45.86437894928507, "y": 8.613910476513986, "z": null, "yaw": 3.473882513367294, "pitch": null, "roll": null}, "v": 0.9975462325249511, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2598282964864948, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2503407038560643, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137692.0475254} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24158807223377543, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9978228918966806, "gear": 1, "accelerator_pedal_position": 0.24158807223377543, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137692.0475254} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.75996685028076, "x": 45.86437894928507, "y": 8.613910476513986, "z": null, "yaw": 3.473882513367294, "pitch": null, "roll": null}, "v": 0.9975462325249511, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2598282964864948, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2503407038560643, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137692.0675254} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24158807223377543, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9978244473850145, "gear": 1, "accelerator_pedal_position": 0.24158807223377543, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137692.0675254} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137692.0775254, "x": 49.761087324703496, "y": 13.576809180126396, "z": null, "yaw": 3.501487727568209, "pitch": null, "roll": null}, "v": 0.997825224313153, "accelerator_pedal_position": 0.24158807223377543, "brake_pedal_position": 0.0, "acceleration": 7.763846268271646e-05, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2504107186567334, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137692.0875254} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24620885759277633, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9978260006977798, "gear": 1, "accelerator_pedal_position": 0.24158807223377543, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137692.0875254} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.86996674537659, "x": 45.761087324703496, "y": 8.576809180126396, "z": null, "yaw": 3.501487727568209, "pitch": null, "roll": null}, "v": 0.997825224313153, "accelerator_pedal_position": 0.24158807223377543, "brake_pedal_position": 0.0, "acceleration": 7.763846268271646e-05, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2504107186567334, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137692.1075253} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24400996948619572, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9984049479657187, "gear": 1, "accelerator_pedal_position": 0.24620885759277633, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137692.1075253} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.86996674537659, "x": 45.761087324703496, "y": 8.576809180126396, "z": null, "yaw": 3.501487727568209, "pitch": null, "roll": null}, "v": 0.997825224313153, "accelerator_pedal_position": 0.24158807223377543, "brake_pedal_position": 0.0, "acceleration": 7.763846268271646e-05, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2504107186567334, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137692.1275253} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24400996948619572, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9987083205440445, "gear": 1, "accelerator_pedal_position": 0.24400996948619572, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137692.1275253} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.86996674537659, "x": 45.761087324703496, "y": 8.576809180126396, "z": null, "yaw": 3.501487727568209, "pitch": null, "roll": null}, "v": 0.997825224313153, "accelerator_pedal_position": 0.24158807223377543, "brake_pedal_position": 0.0, "acceleration": 7.763846268271646e-05, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2504107186567334, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137692.1475253} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24400996948619572, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9990112687152477, "gear": 1, "accelerator_pedal_position": 0.24400996948619572, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137692.1475253} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.86996674537659, "x": 45.761087324703496, "y": 8.576809180126396, "z": null, "yaw": 3.501487727568209, "pitch": null, "roll": null}, "v": 0.997825224313153, "accelerator_pedal_position": 0.24158807223377543, "brake_pedal_position": 0.0, "acceleration": 7.763846268271646e-05, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2504107186567334, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137692.1675253} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24400996948619572, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9993137930363604, "gear": 1, "accelerator_pedal_position": 0.24400996948619572, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137692.1675253} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137692.1875253, "x": 49.658769584670914, "y": 13.536835563922896, "z": null, "yaw": 3.5290929417691235, "pitch": null, "roll": null}, "v": 0.9996158940637889, "accelerator_pedal_position": 0.24400996948619572, "brake_pedal_position": 0.0, "acceleration": 0.015089195228884245, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2508600988570007, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137692.1875253} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2446628072182186, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9996158940637889, "gear": 1, "accelerator_pedal_position": 0.24400996948619572, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137692.1875253} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.97996664047241, "x": 45.658769584670914, "y": 8.536835563922896, "z": null, "yaw": 3.5290929417691235, "pitch": null, "roll": null}, "v": 0.9996158940637889, "accelerator_pedal_position": 0.24400996948619572, "brake_pedal_position": 0.0, "acceleration": 0.015089195228884245, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2508600988570007, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137692.2075253} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24436147870474192, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9999991485099036, "gear": 1, "accelerator_pedal_position": 0.2446628072182186, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137692.2075253} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.97996664047241, "x": 45.658769584670914, "y": 8.536835563922896, "z": null, "yaw": 3.5290929417691235, "pitch": null, "roll": null}, "v": 0.9996158940637889, "accelerator_pedal_position": 0.24400996948619572, "brake_pedal_position": 0.0, "acceleration": 0.015089195228884245, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2508600988570007, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137692.2275252} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24436147870474192, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0003442137220222, "gear": 1, "accelerator_pedal_position": 0.24436147870474192, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137692.2275252} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.97996664047241, "x": 45.658769584670914, "y": 8.536835563922896, "z": null, "yaw": 3.5290929417691235, "pitch": null, "roll": null}, "v": 0.9996158940637889, "accelerator_pedal_position": 0.24400996948619572, "brake_pedal_position": 0.0, "acceleration": 0.015089195228884245, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2508600988570007, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137692.2475252} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24436147870474192, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0006887959763515, "gear": 1, "accelerator_pedal_position": 0.24436147870474192, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137692.2475252} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.97996664047241, "x": 45.658769584670914, "y": 8.536835563922896, "z": null, "yaw": 3.5290929417691235, "pitch": null, "roll": null}, "v": 0.9996158940637889, "accelerator_pedal_position": 0.24400996948619572, "brake_pedal_position": 0.0, "acceleration": 0.015089195228884245, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2508600988570007, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137692.2675252} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24436147870474192, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0010328959013675, "gear": 1, "accelerator_pedal_position": 0.24436147870474192, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137692.2675252} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.97996664047241, "x": 45.658769584670914, "y": 8.536835563922896, "z": null, "yaw": 3.5290929417691235, "pitch": null, "roll": null}, "v": 0.9996158940637889, "accelerator_pedal_position": 0.24400996948619572, "brake_pedal_position": 0.0, "acceleration": 0.015089195228884245, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2508600988570007, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137692.2875252} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24436147870474192, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0013765141248652, "gear": 1, "accelerator_pedal_position": 0.24436147870474192, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137692.2875252} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137692.2975252, "x": 49.557406562524314, "y": 13.493973693224582, "z": null, "yaw": 3.556698155970038, "pitch": null, "roll": null}, "v": 1.001548142794545, "accelerator_pedal_position": 0.24436147870474192, "brake_pedal_position": 0.0, "acceleration": 0.01715084794155769, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.25134500922156405, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137692.3075252} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2466862455667554, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0017196512739606, "gear": 1, "accelerator_pedal_position": 0.24436147870474192, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137692.3075252} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.08996653556824, "x": 45.557406562524314, "y": 8.493973693224582, "z": null, "yaw": 3.556698155970038, "pitch": null, "roll": null}, "v": 1.001548142794545, "accelerator_pedal_position": 0.24436147870474192, "brake_pedal_position": 0.0, "acceleration": 0.01715084794155769, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.25134500922156405, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137692.3275251} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.245589520220086, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.002352802067227, "gear": 1, "accelerator_pedal_position": 0.2466862455667554, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137692.3275251} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.08996653556824, "x": 45.557406562524314, "y": 8.493973693224582, "z": null, "yaw": 3.556698155970038, "pitch": null, "roll": null}, "v": 1.001548142794545, "accelerator_pedal_position": 0.24436147870474192, "brake_pedal_position": 0.0, "acceleration": 0.01715084794155769, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.25134500922156405, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137692.3475251} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.245589520220086, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0028480235537671, "gear": 1, "accelerator_pedal_position": 0.245589520220086, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137692.3475251} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.08996653556824, "x": 45.557406562524314, "y": 8.493973693224582, "z": null, "yaw": 3.556698155970038, "pitch": null, "roll": null}, "v": 1.001548142794545, "accelerator_pedal_position": 0.24436147870474192, "brake_pedal_position": 0.0, "acceleration": 0.01715084794155769, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.25134500922156405, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137692.367525} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.245589520220086, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0033425514336345, "gear": 1, "accelerator_pedal_position": 0.245589520220086, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137692.367525} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.08996653556824, "x": 45.557406562524314, "y": 8.493973693224582, "z": null, "yaw": 3.556698155970038, "pitch": null, "roll": null}, "v": 1.001548142794545, "accelerator_pedal_position": 0.24436147870474192, "brake_pedal_position": 0.0, "acceleration": 0.01715084794155769, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.25134500922156405, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137692.387525} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.245589520220086, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.003836386580505, "gear": 1, "accelerator_pedal_position": 0.245589520220086, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137692.387525} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137692.407525, "x": 49.45703389354035, "y": 13.448224675381354, "z": null, "yaw": 3.584303370170953, "pitch": null, "roll": null}, "v": 1.0043295298672414, "accelerator_pedal_position": 0.245589520220086, "brake_pedal_position": 0.0, "acceleration": 0.024631246836541887, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2520430163662681, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137692.407525} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24002820814569387, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0043295298672414, "gear": 1, "accelerator_pedal_position": 0.245589520220086, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137692.407525} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.19996643066406, "x": 45.45703389354035, "y": 8.448224675381354, "z": null, "yaw": 3.584303370170953, "pitch": null, "roll": null}, "v": 1.0043295298672414, "accelerator_pedal_position": 0.245589520220086, "brake_pedal_position": 0.0, "acceleration": 0.024631246836541887, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2520430163662681, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137692.427525} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24269129984104298, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.004127061770013, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137692.427525} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.19996643066406, "x": 45.45703389354035, "y": 8.448224675381354, "z": null, "yaw": 3.584303370170953, "pitch": null, "roll": null}, "v": 1.0043295298672414, "accelerator_pedal_position": 0.245589520220086, "brake_pedal_position": 0.0, "acceleration": 0.024631246836541887, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2520430163662681, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137692.447525} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24269129984104298, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0042576471818834, "gear": 1, "accelerator_pedal_position": 0.24269129984104298, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137692.447525} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.19996643066406, "x": 45.45703389354035, "y": 8.448224675381354, "z": null, "yaw": 3.584303370170953, "pitch": null, "roll": null}, "v": 1.0043295298672414, "accelerator_pedal_position": 0.245589520220086, "brake_pedal_position": 0.0, "acceleration": 0.024631246836541887, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2520430163662681, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137692.467525} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24269129984104298, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0043880496176296, "gear": 1, "accelerator_pedal_position": 0.24269129984104298, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137692.467525} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.19996643066406, "x": 45.45703389354035, "y": 8.448224675381354, "z": null, "yaw": 3.584303370170953, "pitch": null, "roll": null}, "v": 1.0043295298672414, "accelerator_pedal_position": 0.245589520220086, "brake_pedal_position": 0.0, "acceleration": 0.024631246836541887, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2520430163662681, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137692.487525} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24269129984104298, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0045182693268382, "gear": 1, "accelerator_pedal_position": 0.24269129984104298, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137692.487525} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.19996643066406, "x": 45.45703389354035, "y": 8.448224675381354, "z": null, "yaw": 3.584303370170953, "pitch": null, "roll": null}, "v": 1.0043295298672414, "accelerator_pedal_position": 0.245589520220086, "brake_pedal_position": 0.0, "acceleration": 0.024631246836541887, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2520430163662681, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137692.507525} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24269129984104298, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0046483065587746, "gear": 1, "accelerator_pedal_position": 0.24269129984104298, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137692.507525} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137692.517525, "x": 49.35780931039604, "y": 13.399648428788865, "z": null, "yaw": 3.6119085843718675, "pitch": null, "roll": null}, "v": 1.0047132568235733, "accelerator_pedal_position": 0.24269129984104298, "brake_pedal_position": 0.0, "acceleration": 0.006490473880969572, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.25213931513739724, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137692.527525} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24615062152570066, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.004778161562383, "gear": 1, "accelerator_pedal_position": 0.24269129984104298, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137692.527525} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.30996632575989, "x": 45.35780931039604, "y": 8.399648428788865, "z": null, "yaw": 3.6119085843718675, "pitch": null, "roll": null}, "v": 1.0047132568235733, "accelerator_pedal_position": 0.24269129984104298, "brake_pedal_position": 0.0, "acceleration": 0.006490473880969572, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.25213931513739724, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137692.547525} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2445053738510613, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0053400982374516, "gear": 1, "accelerator_pedal_position": 0.24615062152570066, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137692.547525} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.30996632575989, "x": 45.35780931039604, "y": 8.399648428788865, "z": null, "yaw": 3.6119085843718675, "pitch": null, "roll": null}, "v": 1.0047132568235733, "accelerator_pedal_position": 0.24269129984104298, "brake_pedal_position": 0.0, "acceleration": 0.006490473880969572, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.25213931513739724, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137692.567525} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2445053738510613, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0056956634434056, "gear": 1, "accelerator_pedal_position": 0.2445053738510613, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137692.567525} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.30996632575989, "x": 45.35780931039604, "y": 8.399648428788865, "z": null, "yaw": 3.6119085843718675, "pitch": null, "roll": null}, "v": 1.0047132568235733, "accelerator_pedal_position": 0.24269129984104298, "brake_pedal_position": 0.0, "acceleration": 0.006490473880969572, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.25213931513739724, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137692.587525} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2445053738510613, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.006050730235432, "gear": 1, "accelerator_pedal_position": 0.2445053738510613, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137692.587525} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.30996632575989, "x": 45.35780931039604, "y": 8.399648428788865, "z": null, "yaw": 3.6119085843718675, "pitch": null, "roll": null}, "v": 1.0047132568235733, "accelerator_pedal_position": 0.24269129984104298, "brake_pedal_position": 0.0, "acceleration": 0.006490473880969572, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.25213931513739724, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137692.6075249} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2445053738510613, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.006405299261772, "gear": 1, "accelerator_pedal_position": 0.2445053738510613, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137692.6075249} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137692.6275249, "x": 49.25983778990668, "y": 13.348285650446918, "z": null, "yaw": 3.639513798572782, "pitch": null, "roll": null}, "v": 1.0067593711699694, "accelerator_pedal_position": 0.2445053738510613, "brake_pedal_position": 0.0, "acceleration": 0.01768497369624905, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.25265280081750474, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137692.6275249} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24722268485279686, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0067593711699694, "gear": 1, "accelerator_pedal_position": 0.2445053738510613, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137692.6275249} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.41996622085571, "x": 45.25983778990668, "y": 8.348285650446918, "z": null, "yaw": 3.639513798572782, "pitch": null, "roll": null}, "v": 1.0067593711699694, "accelerator_pedal_position": 0.2445053738510613, "brake_pedal_position": 0.0, "acceleration": 0.01768497369624905, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.25265280081750474, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137692.6475248} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24593965708702942, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0074524913612504, "gear": 1, "accelerator_pedal_position": 0.24722268485279686, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137692.6475248} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.41996622085571, "x": 45.25983778990668, "y": 8.348285650446918, "z": null, "yaw": 3.639513798572782, "pitch": null, "roll": null}, "v": 1.0067593711699694, "accelerator_pedal_position": 0.2445053738510613, "brake_pedal_position": 0.0, "acceleration": 0.01768497369624905, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.25265280081750474, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137692.6675248} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24593965708702942, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.007984317293351, "gear": 1, "accelerator_pedal_position": 0.24593965708702942, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137692.6675248} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.41996622085571, "x": 45.25983778990668, "y": 8.348285650446918, "z": null, "yaw": 3.639513798572782, "pitch": null, "roll": null}, "v": 1.0067593711699694, "accelerator_pedal_position": 0.2445053738510613, "brake_pedal_position": 0.0, "acceleration": 0.01768497369624905, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.25265280081750474, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137692.6875248} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24593965708702942, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0085153972606986, "gear": 1, "accelerator_pedal_position": 0.24593965708702942, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137692.6875248} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.41996622085571, "x": 45.25983778990668, "y": 8.348285650446918, "z": null, "yaw": 3.639513798572782, "pitch": null, "roll": null}, "v": 1.0067593711699694, "accelerator_pedal_position": 0.2445053738510613, "brake_pedal_position": 0.0, "acceleration": 0.01768497369624905, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.25265280081750474, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137692.7075248} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24593965708702942, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.009045732196841, "gear": 1, "accelerator_pedal_position": 0.24593965708702942, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137692.7075248} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.41996622085571, "x": 45.25983778990668, "y": 8.348285650446918, "z": null, "yaw": 3.639513798572782, "pitch": null, "roll": null}, "v": 1.0067593711699694, "accelerator_pedal_position": 0.2445053738510613, "brake_pedal_position": 0.0, "acceleration": 0.01768497369624905, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.25265280081750474, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137692.7275248} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24593965708702942, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0095753230344904, "gear": 1, "accelerator_pedal_position": 0.24593965708702942, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137692.7275248} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137692.7375247, "x": 49.16307489435204, "y": 13.294100016298206, "z": null, "yaw": 3.667119012773697, "pitch": null, "roll": null}, "v": 1.0098398397076245, "accelerator_pedal_position": 0.24593965708702942, "brake_pedal_position": 0.0, "acceleration": 0.026433099789945347, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.25342586439769704, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137692.7475247} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24051442118684416, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0101041707055238, "gear": 1, "accelerator_pedal_position": 0.24593965708702942, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137692.7475247} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.52996611595154, "x": 45.16307489435204, "y": 8.294100016298206, "z": null, "yaw": 3.667119012773697, "pitch": null, "roll": null}, "v": 1.0098398397076245, "accelerator_pedal_position": 0.24593965708702942, "brake_pedal_position": 0.0, "acceleration": 0.026433099789945347, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.25342586439769704, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137692.7675247} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24311433627664486, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0099543596991651, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137692.7675247} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.52996611595154, "x": 45.16307489435204, "y": 8.294100016298206, "z": null, "yaw": 3.667119012773697, "pitch": null, "roll": null}, "v": 1.0098398397076245, "accelerator_pedal_position": 0.24593965708702942, "brake_pedal_position": 0.0, "acceleration": 0.026433099789945347, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.25342586439769704, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137692.7875247} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24311433627664486, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0101296342693673, "gear": 1, "accelerator_pedal_position": 0.24311433627664486, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137692.7875247} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.52996611595154, "x": 45.16307489435204, "y": 8.294100016298206, "z": null, "yaw": 3.667119012773697, "pitch": null, "roll": null}, "v": 1.0098398397076245, "accelerator_pedal_position": 0.24593965708702942, "brake_pedal_position": 0.0, "acceleration": 0.026433099789945347, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.25342586439769704, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137692.8075247} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24311433627664486, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0103046628344379, "gear": 1, "accelerator_pedal_position": 0.24311433627664486, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137692.8075247} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.52996611595154, "x": 45.16307489435204, "y": 8.294100016298206, "z": null, "yaw": 3.667119012773697, "pitch": null, "roll": null}, "v": 1.0098398397076245, "accelerator_pedal_position": 0.24593965708702942, "brake_pedal_position": 0.0, "acceleration": 0.026433099789945347, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.25342586439769704, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137692.8275247} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24311433627664486, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0104794457274053, "gear": 1, "accelerator_pedal_position": 0.24311433627664486, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137692.8275247} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137692.8475246, "x": 49.067659045205104, "y": 13.237154213499519, "z": null, "yaw": 3.6947242269746114, "pitch": null, "roll": null}, "v": 1.0106539832808827, "accelerator_pedal_position": 0.24311433627664486, "brake_pedal_position": 0.0, "acceleration": 0.008717687825770981, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2536301790134251, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137692.8475246} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2518786569879519, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0106539832808827, "gear": 1, "accelerator_pedal_position": 0.24311433627664486, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137692.8475246} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.63996601104736, "x": 45.067659045205104, "y": 8.237154213499519, "z": null, "yaw": 3.6947242269746114, "pitch": null, "roll": null}, "v": 1.0106539832808827, "accelerator_pedal_position": 0.24311433627664486, "brake_pedal_position": 0.0, "acceleration": 0.008717687825770981, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2536301790134251, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137692.8675246} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24770952366365734, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0119234312702072, "gear": 1, "accelerator_pedal_position": 0.2518786569879519, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137692.8675246} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.63996601104736, "x": 45.067659045205104, "y": 8.237154213499519, "z": null, "yaw": 3.6947242269746114, "pitch": null, "roll": null}, "v": 1.0106539832808827, "accelerator_pedal_position": 0.24311433627664486, "brake_pedal_position": 0.0, "acceleration": 0.008717687825770981, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2536301790134251, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137692.8875246} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24770952366365734, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0126701381469236, "gear": 1, "accelerator_pedal_position": 0.24770952366365734, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137692.8875246} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.63996601104736, "x": 45.067659045205104, "y": 8.237154213499519, "z": null, "yaw": 3.6947242269746114, "pitch": null, "roll": null}, "v": 1.0106539832808827, "accelerator_pedal_position": 0.24311433627664486, "brake_pedal_position": 0.0, "acceleration": 0.008717687825770981, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2536301790134251, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137692.9075246} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24770952366365734, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0134157962739385, "gear": 1, "accelerator_pedal_position": 0.24770952366365734, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137692.9075246} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.63996601104736, "x": 45.067659045205104, "y": 8.237154213499519, "z": null, "yaw": 3.6947242269746114, "pitch": null, "roll": null}, "v": 1.0106539832808827, "accelerator_pedal_position": 0.24311433627664486, "brake_pedal_position": 0.0, "acceleration": 0.008717687825770981, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2536301790134251, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137692.9275246} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24770952366365734, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0141604069018966, "gear": 1, "accelerator_pedal_position": 0.24770952366365734, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137692.9275246} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.63996601104736, "x": 45.067659045205104, "y": 8.237154213499519, "z": null, "yaw": 3.6947242269746114, "pitch": null, "roll": null}, "v": 1.0106539832808827, "accelerator_pedal_position": 0.24311433627664486, "brake_pedal_position": 0.0, "acceleration": 0.008717687825770981, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2536301790134251, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137692.9475245} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24770952366365734, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.014903971280622, "gear": 1, "accelerator_pedal_position": 0.24770952366365734, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137692.9475245} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137692.9575245, "x": 48.97359338062784, "y": 13.177431567361067, "z": null, "yaw": 3.722329441175526, "pitch": null, "roll": null}, "v": 1.0152753615168681, "accelerator_pedal_position": 0.24770952366365734, "brake_pedal_position": 0.0, "acceleration": 0.03711291422498281, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2547899438871326, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137692.9675245} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23810418156372648, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.015646490659118, "gear": 1, "accelerator_pedal_position": 0.24770952366365734, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137692.9675245} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.74996590614319, "x": 44.97359338062784, "y": 8.177431567361067, "z": null, "yaw": 3.722329441175526, "pitch": null, "roll": null}, "v": 1.0152753615168681, "accelerator_pedal_position": 0.24770952366365734, "brake_pedal_position": 0.0, "acceleration": 0.03711291422498281, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2547899438871326, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137692.9875245} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24270289493863684, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0151877206439022, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137692.9875245} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.74996590614319, "x": 44.97359338062784, "y": 8.177431567361067, "z": null, "yaw": 3.722329441175526, "pitch": null, "roll": null}, "v": 1.0152753615168681, "accelerator_pedal_position": 0.24770952366365734, "brake_pedal_position": 0.0, "acceleration": 0.03711291422498281, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2547899438871326, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137693.0075245} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24270289493863684, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0153042325980781, "gear": 1, "accelerator_pedal_position": 0.24270289493863684, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137693.0075245} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.74996590614319, "x": 44.97359338062784, "y": 8.177431567361067, "z": null, "yaw": 3.722329441175526, "pitch": null, "roll": null}, "v": 1.0152753615168681, "accelerator_pedal_position": 0.24770952366365734, "brake_pedal_position": 0.0, "acceleration": 0.03711291422498281, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2547899438871326, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137693.0275245} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24270289493863684, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.015420580781216, "gear": 1, "accelerator_pedal_position": 0.24270289493863684, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137693.0275245} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.74996590614319, "x": 44.97359338062784, "y": 8.177431567361067, "z": null, "yaw": 3.722329441175526, "pitch": null, "roll": null}, "v": 1.0152753615168681, "accelerator_pedal_position": 0.24770952366365734, "brake_pedal_position": 0.0, "acceleration": 0.03711291422498281, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2547899438871326, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137693.0475245} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24270289493863684, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.015536765418102, "gear": 1, "accelerator_pedal_position": 0.24270289493863684, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137693.0475245} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137693.0675244, "x": 48.88098926789418, "y": 13.114986401205387, "z": null, "yaw": 3.7499346553764408, "pitch": null, "roll": null}, "v": 1.0156527867332295, "accelerator_pedal_position": 0.24270289493863684, "brake_pedal_position": 0.0, "acceleration": 0.005794948197828886, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.25488466119570063, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137693.0675244} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25435424201905593, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0156527867332295, "gear": 1, "accelerator_pedal_position": 0.24270289493863684, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137693.0675244} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.859965801239014, "x": 44.88098926789418, "y": 8.114986401205387, "z": null, "yaw": 3.7499346553764408, "pitch": null, "roll": null}, "v": 1.0156527867332295, "accelerator_pedal_position": 0.24270289493863684, "brake_pedal_position": 0.0, "acceleration": 0.005794948197828886, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.25488466119570063, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137693.0875244} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2488080005622303, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0172245512482467, "gear": 1, "accelerator_pedal_position": 0.25435424201905593, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137693.0875244} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.859965801239014, "x": 44.88098926789418, "y": 8.114986401205387, "z": null, "yaw": 3.7499346553764408, "pitch": null, "roll": null}, "v": 1.0156527867332295, "accelerator_pedal_position": 0.24270289493863684, "brake_pedal_position": 0.0, "acceleration": 0.005794948197828886, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.25488466119570063, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137693.1075244} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2488080005622303, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0181010691910037, "gear": 1, "accelerator_pedal_position": 0.2488080005622303, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137693.1075244} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.859965801239014, "x": 44.88098926789418, "y": 8.114986401205387, "z": null, "yaw": 3.7499346553764408, "pitch": null, "roll": null}, "v": 1.0156527867332295, "accelerator_pedal_position": 0.24270289493863684, "brake_pedal_position": 0.0, "acceleration": 0.005794948197828886, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.25488466119570063, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137693.1275244} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2488080005622303, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0189763541730252, "gear": 1, "accelerator_pedal_position": 0.2488080005622303, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137693.1275244} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.859965801239014, "x": 44.88098926789418, "y": 8.114986401205387, "z": null, "yaw": 3.7499346553764408, "pitch": null, "roll": null}, "v": 1.0156527867332295, "accelerator_pedal_position": 0.24270289493863684, "brake_pedal_position": 0.0, "acceleration": 0.005794948197828886, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.25488466119570063, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137693.1475244} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2488080005622303, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.019850407622323, "gear": 1, "accelerator_pedal_position": 0.2488080005622303, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137693.1475244} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.859965801239014, "x": 44.88098926789418, "y": 8.114986401205387, "z": null, "yaw": 3.7499346553764408, "pitch": null, "roll": null}, "v": 1.0156527867332295, "accelerator_pedal_position": 0.24270289493863684, "brake_pedal_position": 0.0, "acceleration": 0.005794948197828886, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.25488466119570063, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137693.1675243} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2488080005622303, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0207232309661929, "gear": 1, "accelerator_pedal_position": 0.2488080005622303, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137693.1675243} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137693.1775243, "x": 48.789873124944336, "y": 13.049813653043303, "z": null, "yaw": 3.7775398695773554, "pitch": null, "roll": null}, "v": 1.0211591817944257, "accelerator_pedal_position": 0.2488080005622303, "brake_pedal_position": 0.0, "acceleration": 0.04356438367858734, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.256266526787875, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137693.1875243} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24415992964557529, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0215948256312115, "gear": 1, "accelerator_pedal_position": 0.2488080005622303, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137693.1875243} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.96996569633484, "x": 44.789873124944336, "y": 8.049813653043303, "z": null, "yaw": 3.7775398695773554, "pitch": null, "roll": null}, "v": 1.0211591817944257, "accelerator_pedal_position": 0.2488080005622303, "brake_pedal_position": 0.0, "acceleration": 0.04356438367858734, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.256266526787875, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137693.2075243} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2464028197485336, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0218843888032874, "gear": 1, "accelerator_pedal_position": 0.24415992964557529, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137693.2075243} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.96996569633484, "x": 44.789873124944336, "y": 8.049813653043303, "z": null, "yaw": 3.7775398695773554, "pitch": null, "roll": null}, "v": 1.0211591817944257, "accelerator_pedal_position": 0.2488080005622303, "brake_pedal_position": 0.0, "acceleration": 0.04356438367858734, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.256266526787875, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137693.2275243} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2464028197485336, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0224538067210593, "gear": 1, "accelerator_pedal_position": 0.2464028197485336, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137693.2275243} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.96996569633484, "x": 44.789873124944336, "y": 8.049813653043303, "z": null, "yaw": 3.7775398695773554, "pitch": null, "roll": null}, "v": 1.0211591817944257, "accelerator_pedal_position": 0.2488080005622303, "brake_pedal_position": 0.0, "acceleration": 0.04356438367858734, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.256266526787875, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137693.2475243} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2464028197485336, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0230224226545248, "gear": 1, "accelerator_pedal_position": 0.2464028197485336, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137693.2475243} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.96996569633484, "x": 44.789873124944336, "y": 8.049813653043303, "z": null, "yaw": 3.7775398695773554, "pitch": null, "roll": null}, "v": 1.0211591817944257, "accelerator_pedal_position": 0.2488080005622303, "brake_pedal_position": 0.0, "acceleration": 0.04356438367858734, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.256266526787875, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137693.2675242} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2464028197485336, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0235902376039372, "gear": 1, "accelerator_pedal_position": 0.2464028197485336, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137693.2675242} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137693.2875242, "x": 48.7002342682755, "y": 12.981881505118608, "z": null, "yaw": 3.80514508377827, "pitch": null, "roll": null}, "v": 1.024157252568687, "accelerator_pedal_position": 0.2464028197485336, "brake_pedal_position": 0.0, "acceleration": 0.028320780020010095, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.25701891211435673, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137693.2875242} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25030827826916413, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.024157252568687, "gear": 1, "accelerator_pedal_position": 0.2464028197485336, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137693.2875242} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.079965591430664, "x": 44.7002342682755, "y": 7.981881505118608, "z": null, "yaw": 3.80514508377827, "pitch": null, "roll": null}, "v": 1.024157252568687, "accelerator_pedal_position": 0.2464028197485336, "brake_pedal_position": 0.0, "acceleration": 0.028320780020010095, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.25701891211435673, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137693.3075242} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24846462842010672, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0252114787994726, "gear": 1, "accelerator_pedal_position": 0.25030827826916413, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137693.3075242} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.079965591430664, "x": 44.7002342682755, "y": 7.981881505118608, "z": null, "yaw": 3.80514508377827, "pitch": null, "roll": null}, "v": 1.024157252568687, "accelerator_pedal_position": 0.2464028197485336, "brake_pedal_position": 0.0, "acceleration": 0.028320780020010095, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.25701891211435673, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137693.3275242} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24846462842010672, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0260338441376038, "gear": 1, "accelerator_pedal_position": 0.24846462842010672, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137693.3275242} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.079965591430664, "x": 44.7002342682755, "y": 7.981881505118608, "z": null, "yaw": 3.80514508377827, "pitch": null, "roll": null}, "v": 1.024157252568687, "accelerator_pedal_position": 0.2464028197485336, "brake_pedal_position": 0.0, "acceleration": 0.028320780020010095, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.25701891211435673, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137693.3475242} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24846462842010672, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0268550500771096, "gear": 1, "accelerator_pedal_position": 0.24846462842010672, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137693.3475242} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.079965591430664, "x": 44.7002342682755, "y": 7.981881505118608, "z": null, "yaw": 3.80514508377827, "pitch": null, "roll": null}, "v": 1.024157252568687, "accelerator_pedal_position": 0.2464028197485336, "brake_pedal_position": 0.0, "acceleration": 0.028320780020010095, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.25701891211435673, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137693.3675241} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24846462842010672, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0276750979828932, "gear": 1, "accelerator_pedal_position": 0.24846462842010672, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137693.3675241} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.079965591430664, "x": 44.7002342682755, "y": 7.981881505118608, "z": null, "yaw": 3.80514508377827, "pitch": null, "roll": null}, "v": 1.024157252568687, "accelerator_pedal_position": 0.2464028197485336, "brake_pedal_position": 0.0, "acceleration": 0.028320780020010095, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.25701891211435673, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137693.3875241} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24846462842010672, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0284939892190734, "gear": 1, "accelerator_pedal_position": 0.24846462842010672, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137693.3875241} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137693.397524, "x": 48.612169515587766, "y": 12.91123166371365, "z": null, "yaw": 3.8327502979791848, "pitch": null, "roll": null}, "v": 1.0289030015121345, "accelerator_pedal_position": 0.24846462842010672, "brake_pedal_position": 0.0, "acceleration": 0.04087236368485342, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.258209888624608, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137693.407524} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2520405714529488, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0293117251489832, "gear": 1, "accelerator_pedal_position": 0.24846462842010672, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137693.407524} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.18996548652649, "x": 44.612169515587766, "y": 7.91123166371365, "z": null, "yaw": 3.8327502979791848, "pitch": null, "roll": null}, "v": 1.0289030015121345, "accelerator_pedal_position": 0.24846462842010672, "brake_pedal_position": 0.0, "acceleration": 0.04087236368485342, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.258209888624608, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137693.427524} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.250363243116172, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.030575142233299, "gear": 1, "accelerator_pedal_position": 0.2520405714529488, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137693.427524} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.18996548652649, "x": 44.612169515587766, "y": 7.91123166371365, "z": null, "yaw": 3.8327502979791848, "pitch": null, "roll": null}, "v": 1.0289030015121345, "accelerator_pedal_position": 0.24846462842010672, "brake_pedal_position": 0.0, "acceleration": 0.04087236368485342, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.258209888624608, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137693.447524} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.250363243116172, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0316271838657438, "gear": 1, "accelerator_pedal_position": 0.250363243116172, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137693.447524} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.18996548652649, "x": 44.612169515587766, "y": 7.91123166371365, "z": null, "yaw": 3.8327502979791848, "pitch": null, "roll": null}, "v": 1.0289030015121345, "accelerator_pedal_position": 0.24846462842010672, "brake_pedal_position": 0.0, "acceleration": 0.04087236368485342, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.258209888624608, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137693.467524} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.250363243116172, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0326777399661564, "gear": 1, "accelerator_pedal_position": 0.250363243116172, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137693.467524} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.18996548652649, "x": 44.612169515587766, "y": 7.91123166371365, "z": null, "yaw": 3.8327502979791848, "pitch": null, "roll": null}, "v": 1.0289030015121345, "accelerator_pedal_position": 0.24846462842010672, "brake_pedal_position": 0.0, "acceleration": 0.04087236368485342, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.258209888624608, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137693.487524} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.250363243116172, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0337268121908663, "gear": 1, "accelerator_pedal_position": 0.250363243116172, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137693.487524} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137693.507524, "x": 48.52565442201144, "y": 12.837809317565512, "z": null, "yaw": 3.8603555121800994, "pitch": null, "roll": null}, "v": 1.0347744021957332, "accelerator_pedal_position": 0.250363243116172, "brake_pedal_position": 0.0, "acceleration": 0.05232396873189271, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.25968335474760923, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137693.507524} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25382838114350953, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0347744021957332, "gear": 1, "accelerator_pedal_position": 0.250363243116172, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137693.507524} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.299965381622314, "x": 44.52565442201144, "y": 7.837809317565512, "z": null, "yaw": 3.8603555121800994, "pitch": null, "roll": null}, "v": 1.0347744021957332, "accelerator_pedal_position": 0.250363243116172, "brake_pedal_position": 0.0, "acceleration": 0.05232396873189271, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.25968335474760923, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137693.527524} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25220991360225303, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0362535007561906, "gear": 1, "accelerator_pedal_position": 0.25382838114350953, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137693.527524} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.299965381622314, "x": 44.52565442201144, "y": 7.837809317565512, "z": null, "yaw": 3.8603555121800994, "pitch": null, "roll": null}, "v": 1.0347744021957332, "accelerator_pedal_position": 0.250363243116172, "brake_pedal_position": 0.0, "acceleration": 0.05232396873189271, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.25968335474760923, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137693.547524} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25220991360225303, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0375282712008687, "gear": 1, "accelerator_pedal_position": 0.25220991360225303, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137693.547524} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.299965381622314, "x": 44.52565442201144, "y": 7.837809317565512, "z": null, "yaw": 3.8603555121800994, "pitch": null, "roll": null}, "v": 1.0347744021957332, "accelerator_pedal_position": 0.250363243116172, "brake_pedal_position": 0.0, "acceleration": 0.05232396873189271, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.25968335474760923, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137693.567524} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25220991360225303, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0388012386315026, "gear": 1, "accelerator_pedal_position": 0.25220991360225303, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137693.567524} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.299965381622314, "x": 44.52565442201144, "y": 7.837809317565512, "z": null, "yaw": 3.8603555121800994, "pitch": null, "roll": null}, "v": 1.0347744021957332, "accelerator_pedal_position": 0.250363243116172, "brake_pedal_position": 0.0, "acceleration": 0.05232396873189271, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.25968335474760923, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137693.587524} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25220991360225303, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0400724049502965, "gear": 1, "accelerator_pedal_position": 0.25220991360225303, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137693.587524} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.299965381622314, "x": 44.52565442201144, "y": 7.837809317565512, "z": null, "yaw": 3.8603555121800994, "pitch": null, "roll": null}, "v": 1.0347744021957332, "accelerator_pedal_position": 0.250363243116172, "brake_pedal_position": 0.0, "acceleration": 0.05232396873189271, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.25968335474760923, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137693.607524} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25220991360225303, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0413417720595124, "gear": 1, "accelerator_pedal_position": 0.25220991360225303, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137693.607524} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137693.617524, "x": 48.44066309270728, "y": 12.76154583122593, "z": null, "yaw": 3.887960726381014, "pitch": null, "roll": null}, "v": 1.041975781505, "accelerator_pedal_position": 0.25220991360225303, "brake_pedal_position": 0.0, "acceleration": 0.0633560356464018, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.26149058764192146, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137693.627524} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2490481439389501, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.042609341861464, "gear": 1, "accelerator_pedal_position": 0.25220991360225303, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137693.627524} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.40996527671814, "x": 44.44066309270728, "y": 7.761545831225931, "z": null, "yaw": 3.887960726381014, "pitch": null, "roll": null}, "v": 1.041975781505, "accelerator_pedal_position": 0.25220991360225303, "brake_pedal_position": 0.0, "acceleration": 0.0633560356464018, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.26149058764192146, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137693.6475239} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2505925777785873, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0434800350831455, "gear": 1, "accelerator_pedal_position": 0.2490481439389501, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137693.6475239} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.40996527671814, "x": 44.44066309270728, "y": 7.761545831225931, "z": null, "yaw": 3.887960726381014, "pitch": null, "roll": null}, "v": 1.041975781505, "accelerator_pedal_position": 0.25220991360225303, "brake_pedal_position": 0.0, "acceleration": 0.0633560356464018, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.26149058764192146, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137693.6675239} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2505925777785873, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0445424805165437, "gear": 1, "accelerator_pedal_position": 0.2505925777785873, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137693.6675239} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.40996527671814, "x": 44.44066309270728, "y": 7.761545831225931, "z": null, "yaw": 3.887960726381014, "pitch": null, "roll": null}, "v": 1.041975781505, "accelerator_pedal_position": 0.25220991360225303, "brake_pedal_position": 0.0, "acceleration": 0.0633560356464018, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.26149058764192146, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137693.6775239} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2505925777785873, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.045073138488087, "gear": 1, "accelerator_pedal_position": 0.2505925777785873, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137693.6775239} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.40996527671814, "x": 44.44066309270728, "y": 7.761545831225931, "z": null, "yaw": 3.887960726381014, "pitch": null, "roll": null}, "v": 1.041975781505, "accelerator_pedal_position": 0.25220991360225303, "brake_pedal_position": 0.0, "acceleration": 0.0633560356464018, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.26149058764192146, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137693.7075238} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2505925777785873, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0466628559479125, "gear": 1, "accelerator_pedal_position": 0.2505925777785873, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137693.7075238} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137693.7275238, "x": 48.35729489224389, "y": 12.682478284321117, "z": null, "yaw": 3.9155659405819287, "pitch": null, "roll": null}, "v": 1.0477207893130538, "accelerator_pedal_position": 0.2505925777785873, "brake_pedal_position": 0.0, "acceleration": 0.05284038312693007, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2629323346521692, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137693.7275238} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25722132052182267, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0477207893130538, "gear": 1, "accelerator_pedal_position": 0.2505925777785873, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137693.7275238} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.519965171813965, "x": 44.35729489224389, "y": 7.6824782843211175, "z": null, "yaw": 3.9155659405819287, "pitch": null, "roll": null}, "v": 1.0477207893130538, "accelerator_pedal_position": 0.2505925777785873, "brake_pedal_position": 0.0, "acceleration": 0.05284038312693007, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2629323346521692, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137693.7475238} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25409580745392774, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0496055208421715, "gear": 1, "accelerator_pedal_position": 0.25722132052182267, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137693.7475238} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.519965171813965, "x": 44.35729489224389, "y": 7.6824782843211175, "z": null, "yaw": 3.9155659405819287, "pitch": null, "roll": null}, "v": 1.0477207893130538, "accelerator_pedal_position": 0.2505925777785873, "brake_pedal_position": 0.0, "acceleration": 0.05284038312693007, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2629323346521692, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137693.7675238} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25409580745392774, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0510970272335955, "gear": 1, "accelerator_pedal_position": 0.25409580745392774, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137693.7675238} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.519965171813965, "x": 44.35729489224389, "y": 7.6824782843211175, "z": null, "yaw": 3.9155659405819287, "pitch": null, "roll": null}, "v": 1.0477207893130538, "accelerator_pedal_position": 0.2505925777785873, "brake_pedal_position": 0.0, "acceleration": 0.05284038312693007, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2629323346521692, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137693.7875237} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25409580745392774, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0525864160061675, "gear": 1, "accelerator_pedal_position": 0.25409580745392774, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137693.7875237} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.519965171813965, "x": 44.35729489224389, "y": 7.6824782843211175, "z": null, "yaw": 3.9155659405819287, "pitch": null, "roll": null}, "v": 1.0477207893130538, "accelerator_pedal_position": 0.2505925777785873, "brake_pedal_position": 0.0, "acceleration": 0.05284038312693007, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2629323346521692, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137693.8075237} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25409580745392774, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0540736892794553, "gear": 1, "accelerator_pedal_position": 0.25409580745392774, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137693.8075237} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.519965171813965, "x": 44.35729489224389, "y": 7.6824782843211175, "z": null, "yaw": 3.9155659405819287, "pitch": null, "roll": null}, "v": 1.0477207893130538, "accelerator_pedal_position": 0.2505925777785873, "brake_pedal_position": 0.0, "acceleration": 0.05284038312693007, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2629323346521692, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137693.8275237} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25409580745392774, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.055558849173795, "gear": 1, "accelerator_pedal_position": 0.25409580745392774, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137693.8275237} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137693.8375237, "x": 48.275581136331674, "y": 12.60057779363833, "z": null, "yaw": 3.9431711547828434, "pitch": null, "roll": null}, "v": 1.0563006372666717, "accelerator_pedal_position": 0.25409580745392774, "brake_pedal_position": 0.0, "acceleration": 0.07412605436081493, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2650855032028138, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137693.8475237} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25738362010561056, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0570418978102798, "gear": 1, "accelerator_pedal_position": 0.25409580745392774, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137693.8475237} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.62996506690979, "x": 44.275581136331674, "y": 7.60057779363833, "z": null, "yaw": 3.9431711547828434, "pitch": null, "roll": null}, "v": 1.0563006372666717, "accelerator_pedal_position": 0.25409580745392774, "brake_pedal_position": 0.0, "acceleration": 0.07412605436081493, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2650855032028138, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137693.8675237} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25586443345444193, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0589336676714523, "gear": 1, "accelerator_pedal_position": 0.25738362010561056, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137693.8675237} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.62996506690979, "x": 44.275581136331674, "y": 7.60057779363833, "z": null, "yaw": 3.9431711547828434, "pitch": null, "roll": null}, "v": 1.0563006372666717, "accelerator_pedal_position": 0.25409580745392774, "brake_pedal_position": 0.0, "acceleration": 0.07412605436081493, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2650855032028138, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137693.8875237} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25586443345444193, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0606329150446452, "gear": 1, "accelerator_pedal_position": 0.25586443345444193, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137693.8875237} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.62996506690979, "x": 44.275581136331674, "y": 7.60057779363833, "z": null, "yaw": 3.9431711547828434, "pitch": null, "roll": null}, "v": 1.0563006372666717, "accelerator_pedal_position": 0.25409580745392774, "brake_pedal_position": 0.0, "acceleration": 0.07412605436081493, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2650855032028138, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137693.9075236} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25586443345444193, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0623297434097578, "gear": 1, "accelerator_pedal_position": 0.25586443345444193, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137693.9075236} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.62996506690979, "x": 44.275581136331674, "y": 7.60057779363833, "z": null, "yaw": 3.9431711547828434, "pitch": null, "roll": null}, "v": 1.0563006372666717, "accelerator_pedal_position": 0.25409580745392774, "brake_pedal_position": 0.0, "acceleration": 0.07412605436081493, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2650855032028138, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137693.9275236} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25586443345444193, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0640241550591518, "gear": 1, "accelerator_pedal_position": 0.25586443345444193, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137693.9275236} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137693.9475236, "x": 48.19549396836992, "y": 12.515748199237823, "z": null, "yaw": 3.970776368983758, "pitch": null, "roll": null}, "v": 1.0657161522868424, "accelerator_pedal_position": 0.25586443345444193, "brake_pedal_position": 0.0, "acceleration": 0.0845093923034691, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.26744838782957514, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137693.9475236} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.260883161490311, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0657161522868424, "gear": 1, "accelerator_pedal_position": 0.25586443345444193, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137693.9475236} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.739964962005615, "x": 44.19549396836992, "y": 7.515748199237823, "z": null, "yaw": 3.970776368983758, "pitch": null, "roll": null}, "v": 1.0657161522868424, "accelerator_pedal_position": 0.25586443345444193, "brake_pedal_position": 0.0, "acceleration": 0.0845093923034691, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.26744838782957514, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137693.9675236} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2585443812238073, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0680328546381161, "gear": 1, "accelerator_pedal_position": 0.260883161490311, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137693.9675236} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.739964962005615, "x": 44.19549396836992, "y": 7.515748199237823, "z": null, "yaw": 3.970776368983758, "pitch": null, "roll": null}, "v": 1.0657161522868424, "accelerator_pedal_position": 0.25586443345444193, "brake_pedal_position": 0.0, "acceleration": 0.0845093923034691, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.26744838782957514, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137693.9875236} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2585443812238073, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.070054009086551, "gear": 1, "accelerator_pedal_position": 0.2585443812238073, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137693.9875236} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.739964962005615, "x": 44.19549396836992, "y": 7.515748199237823, "z": null, "yaw": 3.970776368983758, "pitch": null, "roll": null}, "v": 1.0657161522868424, "accelerator_pedal_position": 0.25586443345444193, "brake_pedal_position": 0.0, "acceleration": 0.0845093923034691, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.26744838782957514, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137694.0075235} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2585443812238073, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.072072278721537, "gear": 1, "accelerator_pedal_position": 0.2585443812238073, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137694.0075235} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.739964962005615, "x": 44.19549396836992, "y": 7.515748199237823, "z": null, "yaw": 3.970776368983758, "pitch": null, "roll": null}, "v": 1.0657161522868424, "accelerator_pedal_position": 0.25586443345444193, "brake_pedal_position": 0.0, "acceleration": 0.0845093923034691, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.26744838782957514, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137694.0275235} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2585443812238073, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0740876660318137, "gear": 1, "accelerator_pedal_position": 0.2585443812238073, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137694.0275235} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.739964962005615, "x": 44.19549396836992, "y": 7.515748199237823, "z": null, "yaw": 3.970776368983758, "pitch": null, "roll": null}, "v": 1.0657161522868424, "accelerator_pedal_position": 0.25586443345444193, "brake_pedal_position": 0.0, "acceleration": 0.0845093923034691, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.26744838782957514, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137694.0475235} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2585443812238073, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.076100173509543, "gear": 1, "accelerator_pedal_position": 0.2585443812238073, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137694.0475235} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137694.0575235, "x": 48.1170153142955, "y": 12.427885003484494, "z": null, "yaw": 3.9983815831846727, "pitch": null, "roll": null}, "v": 1.0771053480909334, "accelerator_pedal_position": 0.2585443812238073, "brake_pedal_position": 0.0, "acceleration": 0.10044555593538795, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.27030658046364875, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137694.0675235} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2590418601922733, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0781098036502872, "gear": 1, "accelerator_pedal_position": 0.2585443812238073, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137694.0675235} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.84996485710144, "x": 44.1170153142955, "y": 7.427885003484494, "z": null, "yaw": 3.9983815831846727, "pitch": null, "roll": null}, "v": 1.0771053480909334, "accelerator_pedal_position": 0.2585443812238073, "brake_pedal_position": 0.0, "acceleration": 0.10044555593538795, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.27030658046364875, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137694.0875235} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25886694706670244, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0801787215672765, "gear": 1, "accelerator_pedal_position": 0.2590418601922733, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137694.0875235} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.84996485710144, "x": 44.1170153142955, "y": 7.427885003484494, "z": null, "yaw": 3.9983815831846727, "pitch": null, "roll": null}, "v": 1.0771053480909334, "accelerator_pedal_position": 0.2585443812238073, "brake_pedal_position": 0.0, "acceleration": 0.10044555593538795, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.27030658046364875, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137694.1075234} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25886694706670244, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0822228218238463, "gear": 1, "accelerator_pedal_position": 0.25886694706670244, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137694.1075234} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.84996485710144, "x": 44.1170153142955, "y": 7.427885003484494, "z": null, "yaw": 3.9983815831846727, "pitch": null, "roll": null}, "v": 1.0771053480909334, "accelerator_pedal_position": 0.2585443812238073, "brake_pedal_position": 0.0, "acceleration": 0.10044555593538795, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.27030658046364875, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137694.1275234} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25886694706670244, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0842639945782873, "gear": 1, "accelerator_pedal_position": 0.25886694706670244, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137694.1275234} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.84996485710144, "x": 44.1170153142955, "y": 7.427885003484494, "z": null, "yaw": 3.9983815831846727, "pitch": null, "roll": null}, "v": 1.0771053480909334, "accelerator_pedal_position": 0.2585443812238073, "brake_pedal_position": 0.0, "acceleration": 0.10044555593538795, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.27030658046364875, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137694.1475234} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25886694706670244, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0863022423573268, "gear": 1, "accelerator_pedal_position": 0.25886694706670244, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137694.1475234} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137694.1675234, "x": 48.040196980409064, "y": 12.336948385703899, "z": null, "yaw": 4.025986797385592, "pitch": null, "roll": null}, "v": 1.0883375676912326, "accelerator_pedal_position": 0.25886694706670244, "brake_pedal_position": 0.0, "acceleration": 0.10165675416984787, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2731253789001758, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137694.1675234} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2562084248723454, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0883375676912326, "gear": 1, "accelerator_pedal_position": 0.25886694706670244, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137694.1675234} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.959964752197266, "x": 44.040196980409064, "y": 7.336948385703899, "z": null, "yaw": 4.025986797385592, "pitch": null, "roll": null}, "v": 1.0883375676912326, "accelerator_pedal_position": 0.25886694706670244, "brake_pedal_position": 0.0, "acceleration": 0.10165675416984787, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2731253789001758, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137694.1875234} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2575357094971623, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0900377771164536, "gear": 1, "accelerator_pedal_position": 0.2562084248723454, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137694.1875234} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.959964752197266, "x": 44.040196980409064, "y": 7.336948385703899, "z": null, "yaw": 4.025986797385592, "pitch": null, "roll": null}, "v": 1.0883375676912326, "accelerator_pedal_position": 0.25886694706670244, "brake_pedal_position": 0.0, "acceleration": 0.10165675416984787, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2731253789001758, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137694.2075233} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2575357094971623, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0919013971815335, "gear": 1, "accelerator_pedal_position": 0.2575357094971623, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137694.2075233} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.959964752197266, "x": 44.040196980409064, "y": 7.336948385703899, "z": null, "yaw": 4.025986797385592, "pitch": null, "roll": null}, "v": 1.0883375676912326, "accelerator_pedal_position": 0.25886694706670244, "brake_pedal_position": 0.0, "acceleration": 0.10165675416984787, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2731253789001758, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137694.2275233} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2575357094971623, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.093762340979749, "gear": 1, "accelerator_pedal_position": 0.2575357094971623, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137694.2275233} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.959964752197266, "x": 44.040196980409064, "y": 7.336948385703899, "z": null, "yaw": 4.025986797385592, "pitch": null, "roll": null}, "v": 1.0883375676912326, "accelerator_pedal_position": 0.25886694706670244, "brake_pedal_position": 0.0, "acceleration": 0.10165675416984787, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2731253789001758, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137694.2475233} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2575357094971623, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0956206109696278, "gear": 1, "accelerator_pedal_position": 0.2575357094971623, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137694.2475233} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.959964752197266, "x": 44.040196980409064, "y": 7.336948385703899, "z": null, "yaw": 4.025986797385592, "pitch": null, "roll": null}, "v": 1.0883375676912326, "accelerator_pedal_position": 0.25886694706670244, "brake_pedal_position": 0.0, "acceleration": 0.10165675416984787, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2731253789001758, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137694.2675233} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2575357094971623, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0974762096121335, "gear": 1, "accelerator_pedal_position": 0.2575357094971623, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137694.2675233} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137694.2775233, "x": 47.96518769946258, "y": 12.243012114505504, "z": null, "yaw": 4.053592011586511, "pitch": null, "roll": null}, "v": 1.0984030079478337, "accelerator_pedal_position": 0.2575357094971623, "brake_pedal_position": 0.0, "acceleration": 0.09261314228118417, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.27565136648481203, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137694.2875233} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2703251701485669, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0993291393706457, "gear": 1, "accelerator_pedal_position": 0.2575357094971623, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137694.2875233} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.06996464729309, "x": 43.96518769946258, "y": 7.243012114505504, "z": null, "yaw": 4.053592011586511, "pitch": null, "roll": null}, "v": 1.0984030079478337, "accelerator_pedal_position": 0.2575357094971623, "brake_pedal_position": 0.0, "acceleration": 0.09261314228118417, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.27565136648481203, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137694.3075233} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2642900622200723, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.102777509662039, "gear": 1, "accelerator_pedal_position": 0.2703251701485669, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137694.3075233} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.06996464729309, "x": 43.96518769946258, "y": 7.243012114505504, "z": null, "yaw": 4.053592011586511, "pitch": null, "roll": null}, "v": 1.0984030079478337, "accelerator_pedal_position": 0.2575357094971623, "brake_pedal_position": 0.0, "acceleration": 0.09261314228118417, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.27565136648481203, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137694.3275232} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2642900622200723, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1054667968621807, "gear": 1, "accelerator_pedal_position": 0.2642900622200723, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137694.3275232} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.06996464729309, "x": 43.96518769946258, "y": 7.243012114505504, "z": null, "yaw": 4.053592011586511, "pitch": null, "roll": null}, "v": 1.0984030079478337, "accelerator_pedal_position": 0.2575357094971623, "brake_pedal_position": 0.0, "acceleration": 0.09261314228118417, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.27565136648481203, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137694.3475232} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2642900622200723, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1081522077293688, "gear": 1, "accelerator_pedal_position": 0.2642900622200723, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137694.3475232} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.06996464729309, "x": 43.96518769946258, "y": 7.243012114505504, "z": null, "yaw": 4.053592011586511, "pitch": null, "roll": null}, "v": 1.0984030079478337, "accelerator_pedal_position": 0.2575357094971623, "brake_pedal_position": 0.0, "acceleration": 0.09261314228118417, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.27565136648481203, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137694.3675232} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2642900622200723, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.110833744967409, "gear": 1, "accelerator_pedal_position": 0.2642900622200723, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137694.3675232} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137694.3875232, "x": 47.89197436704963, "y": 12.145944766131791, "z": null, "yaw": 4.081197225787431, "pitch": null, "roll": null}, "v": 1.1135114112886828, "accelerator_pedal_position": 0.2642900622200723, "brake_pedal_position": 0.0, "acceleration": 0.13373824168031645, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2794429183980662, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137694.3875232} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2754901659032317, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1135114112886828, "gear": 1, "accelerator_pedal_position": 0.2642900622200723, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137694.3875232} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.179964542388916, "x": 43.89197436704963, "y": 7.145944766131791, "z": null, "yaw": 4.081197225787431, "pitch": null, "roll": null}, "v": 1.1135114112886828, "accelerator_pedal_position": 0.2642900622200723, "brake_pedal_position": 0.0, "acceleration": 0.13373824168031645, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2794429183980662, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137694.4075232} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2702397981070576, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.117584716241983, "gear": 1, "accelerator_pedal_position": 0.2754901659032317, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137694.4075232} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.179964542388916, "x": 43.89197436704963, "y": 7.145944766131791, "z": null, "yaw": 4.081197225787431, "pitch": null, "roll": null}, "v": 1.1135114112886828, "accelerator_pedal_position": 0.2642900622200723, "brake_pedal_position": 0.0, "acceleration": 0.13373824168031645, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2794429183980662, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137694.4275231} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2702397981070576, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.120996072344705, "gear": 1, "accelerator_pedal_position": 0.2702397981070576, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137694.4275231} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.179964542388916, "x": 43.89197436704963, "y": 7.145944766131791, "z": null, "yaw": 4.081197225787431, "pitch": null, "roll": null}, "v": 1.1135114112886828, "accelerator_pedal_position": 0.2642900622200723, "brake_pedal_position": 0.0, "acceleration": 0.13373824168031645, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2794429183980662, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137694.447523} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2702397981070576, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1244024903970555, "gear": 1, "accelerator_pedal_position": 0.2702397981070576, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137694.447523} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.179964542388916, "x": 43.89197436704963, "y": 7.145944766131791, "z": null, "yaw": 4.081197225787431, "pitch": null, "roll": null}, "v": 1.1135114112886828, "accelerator_pedal_position": 0.2642900622200723, "brake_pedal_position": 0.0, "acceleration": 0.13373824168031645, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2794429183980662, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137694.467523} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2702397981070576, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1278039729072327, "gear": 1, "accelerator_pedal_position": 0.2702397981070576, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137694.467523} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.179964542388916, "x": 43.89197436704963, "y": 7.145944766131791, "z": null, "yaw": 4.081197225787431, "pitch": null, "roll": null}, "v": 1.1135114112886828, "accelerator_pedal_position": 0.2642900622200723, "brake_pedal_position": 0.0, "acceleration": 0.13373824168031645, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2794429183980662, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137694.487523} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2702397981070576, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1312005223999635, "gear": 1, "accelerator_pedal_position": 0.2702397981070576, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137694.487523} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137694.497523, "x": 47.82036692833563, "y": 12.045344968232405, "z": null, "yaw": 4.1088024399883505, "pitch": null, "roll": null}, "v": 1.132896948058267, "accelerator_pedal_position": 0.2702397981070576, "brake_pedal_position": 0.0, "acceleration": 0.16951933581699935, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.28430784471555787, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137694.507523} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2737101464633732, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1345921414164368, "gear": 1, "accelerator_pedal_position": 0.2702397981070576, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137694.507523} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.28996443748474, "x": 43.82036692833563, "y": 7.0453449682324045, "z": null, "yaw": 4.1088024399883505, "pitch": null, "roll": null}, "v": 1.132896948058267, "accelerator_pedal_position": 0.2702397981070576, "brake_pedal_position": 0.0, "acceleration": 0.16951933581699935, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.28430784471555787, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137694.527523} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2721646278193194, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.138412468314328, "gear": 1, "accelerator_pedal_position": 0.2737101464633732, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137694.527523} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.28996443748474, "x": 43.82036692833563, "y": 7.0453449682324045, "z": null, "yaw": 4.1088024399883505, "pitch": null, "roll": null}, "v": 1.132896948058267, "accelerator_pedal_position": 0.2702397981070576, "brake_pedal_position": 0.0, "acceleration": 0.16951933581699935, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.28430784471555787, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137694.547523} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2721646278193194, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1420341192199674, "gear": 1, "accelerator_pedal_position": 0.2721646278193194, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137694.547523} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.28996443748474, "x": 43.82036692833563, "y": 7.0453449682324045, "z": null, "yaw": 4.1088024399883505, "pitch": null, "roll": null}, "v": 1.132896948058267, "accelerator_pedal_position": 0.2702397981070576, "brake_pedal_position": 0.0, "acceleration": 0.16951933581699935, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.28430784471555787, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137694.567523} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2721646278193194, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1456504972878605, "gear": 1, "accelerator_pedal_position": 0.2721646278193194, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137694.567523} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.28996443748474, "x": 43.82036692833563, "y": 7.0453449682324045, "z": null, "yaw": 4.1088024399883505, "pitch": null, "roll": null}, "v": 1.132896948058267, "accelerator_pedal_position": 0.2702397981070576, "brake_pedal_position": 0.0, "acceleration": 0.16951933581699935, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.28430784471555787, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137694.587523} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2721646278193194, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.149261604965472, "gear": 1, "accelerator_pedal_position": 0.2721646278193194, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137694.587523} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137694.607523, "x": 47.75037518860606, "y": 11.941035835137775, "z": null, "yaw": 4.13640765418927, "pitch": null, "roll": null}, "v": 1.1528674447195582, "accelerator_pedal_position": 0.2721646278193194, "brake_pedal_position": 0.0, "acceleration": 0.1800945181838261, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2893195705158634, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137694.607523} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2811862313989465, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1528674447195582, "gear": 1, "accelerator_pedal_position": 0.2721646278193194, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137694.607523} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.399964332580566, "x": 43.75037518860606, "y": 6.941035835137775, "z": null, "yaw": 4.13640765418927, "pitch": null, "roll": null}, "v": 1.1528674447195582, "accelerator_pedal_position": 0.2721646278193194, "brake_pedal_position": 0.0, "acceleration": 0.1800945181838261, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2893195705158634, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137694.627523} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27700108500063647, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1575953073146323, "gear": 1, "accelerator_pedal_position": 0.2811862313989465, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137694.627523} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.399964332580566, "x": 43.75037518860606, "y": 6.941035835137775, "z": null, "yaw": 4.13640765418927, "pitch": null, "roll": null}, "v": 1.1528674447195582, "accelerator_pedal_position": 0.2721646278193194, "brake_pedal_position": 0.0, "acceleration": 0.1800945181838261, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2893195705158634, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137694.647523} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27700108500063647, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1617933057924632, "gear": 1, "accelerator_pedal_position": 0.27700108500063647, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137694.647523} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.399964332580566, "x": 43.75037518860606, "y": 6.941035835137775, "z": null, "yaw": 4.13640765418927, "pitch": null, "roll": null}, "v": 1.1528674447195582, "accelerator_pedal_position": 0.2721646278193194, "brake_pedal_position": 0.0, "acceleration": 0.1800945181838261, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2893195705158634, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137694.667523} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27700108500063647, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1659851594024706, "gear": 1, "accelerator_pedal_position": 0.27700108500063647, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137694.667523} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.399964332580566, "x": 43.75037518860606, "y": 6.941035835137775, "z": null, "yaw": 4.13640765418927, "pitch": null, "roll": null}, "v": 1.1528674447195582, "accelerator_pedal_position": 0.2721646278193194, "brake_pedal_position": 0.0, "acceleration": 0.1800945181838261, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2893195705158634, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137694.687523} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27700108500063647, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1701708701131945, "gear": 1, "accelerator_pedal_position": 0.27700108500063647, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137694.687523} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.399964332580566, "x": 43.75037518860606, "y": 6.941035835137775, "z": null, "yaw": 4.13640765418927, "pitch": null, "roll": null}, "v": 1.1528674447195582, "accelerator_pedal_position": 0.2721646278193194, "brake_pedal_position": 0.0, "acceleration": 0.1800945181838261, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.2893195705158634, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137694.7075229} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27700108500063647, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1743504399211702, "gear": 1, "accelerator_pedal_position": 0.27700108500063647, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137694.7075229} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137694.7175229, "x": 47.68200826540329, "y": 11.832805305783586, "z": null, "yaw": 4.16401286839019, "pitch": null, "roll": null}, "v": 1.1764379226181751, "accelerator_pedal_position": 0.27700108500063647, "brake_pedal_position": 0.0, "acceleration": 0.2085948232653274, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.295234734981402, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137694.7275229} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2883249421903739, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1785238708508283, "gear": 1, "accelerator_pedal_position": 0.27700108500063647, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137694.7275229} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.50996422767639, "x": 43.68200826540329, "y": 6.832805305783586, "z": null, "yaw": 4.16401286839019, "pitch": null, "roll": null}, "v": 1.1764379226181751, "accelerator_pedal_position": 0.27700108500063647, "brake_pedal_position": 0.0, "acceleration": 0.2085948232653274, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.295234734981402, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137694.7475228} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2830642496474469, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.184106126069491, "gear": 1, "accelerator_pedal_position": 0.2883249421903739, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137694.7475228} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.50996422767639, "x": 43.68200826540329, "y": 6.832805305783586, "z": null, "yaw": 4.16401286839019, "pitch": null, "roll": null}, "v": 1.1764379226181751, "accelerator_pedal_position": 0.27700108500063647, "brake_pedal_position": 0.0, "acceleration": 0.2085948232653274, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.295234734981402, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137694.7675228} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2830642496474469, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.189022817052071, "gear": 1, "accelerator_pedal_position": 0.2830642496474469, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137694.7675228} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.50996422767639, "x": 43.68200826540329, "y": 6.832805305783586, "z": null, "yaw": 4.16401286839019, "pitch": null, "roll": null}, "v": 1.1764379226181751, "accelerator_pedal_position": 0.27700108500063647, "brake_pedal_position": 0.0, "acceleration": 0.2085948232653274, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.295234734981402, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137694.7875228} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2830642496474469, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1939322580134832, "gear": 1, "accelerator_pedal_position": 0.2830642496474469, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137694.7875228} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.50996422767639, "x": 43.68200826540329, "y": 6.832805305783586, "z": null, "yaw": 4.16401286839019, "pitch": null, "roll": null}, "v": 1.1764379226181751, "accelerator_pedal_position": 0.27700108500063647, "brake_pedal_position": 0.0, "acceleration": 0.2085948232653274, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.295234734981402, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137694.8075228} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2830642496474469, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1988344500069301, "gear": 1, "accelerator_pedal_position": 0.2830642496474469, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137694.8075228} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137694.8275228, "x": 47.61524672165738, "y": 11.720355649185233, "z": null, "yaw": 4.191618082591109, "pitch": null, "roll": null}, "v": 1.2037293941267344, "accelerator_pedal_position": 0.2830642496474469, "brake_pedal_position": 0.0, "acceleration": 0.24447544604735932, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3020837069527834, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137694.8275228} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2961740028050299, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2037293941267344, "gear": 1, "accelerator_pedal_position": 0.2830642496474469, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137694.8275228} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.61996412277222, "x": 43.61524672165738, "y": 6.720355649185233, "z": null, "yaw": 4.191618082591109, "pitch": null, "roll": null}, "v": 1.2037293941267344, "accelerator_pedal_position": 0.2830642496474469, "brake_pedal_position": 0.0, "acceleration": 0.24447544604735932, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3020837069527834, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137694.8475227} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29008471968893, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2102552032479175, "gear": 1, "accelerator_pedal_position": 0.2961740028050299, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137694.8475227} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.61996412277222, "x": 43.61524672165738, "y": 6.720355649185233, "z": null, "yaw": 4.191618082591109, "pitch": null, "roll": null}, "v": 1.2037293941267344, "accelerator_pedal_position": 0.2830642496474469, "brake_pedal_position": 0.0, "acceleration": 0.24447544604735932, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3020837069527834, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137694.8675227} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29008471968893, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2160104575066237, "gear": 1, "accelerator_pedal_position": 0.29008471968893, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137694.8675227} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.61996412277222, "x": 43.61524672165738, "y": 6.720355649185233, "z": null, "yaw": 4.191618082591109, "pitch": null, "roll": null}, "v": 1.2037293941267344, "accelerator_pedal_position": 0.2830642496474469, "brake_pedal_position": 0.0, "acceleration": 0.24447544604735932, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3020837069527834, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137694.8875227} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29008471968893, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2217571636212992, "gear": 1, "accelerator_pedal_position": 0.29008471968893, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137694.8875227} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.61996412277222, "x": 43.61524672165738, "y": 6.720355649185233, "z": null, "yaw": 4.191618082591109, "pitch": null, "roll": null}, "v": 1.2037293941267344, "accelerator_pedal_position": 0.2830642496474469, "brake_pedal_position": 0.0, "acceleration": 0.24447544604735932, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3020837069527834, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137694.9075227} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29008471968893, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2274953210833612, "gear": 1, "accelerator_pedal_position": 0.29008471968893, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137694.9075227} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.61996412277222, "x": 43.61524672165738, "y": 6.720355649185233, "z": null, "yaw": 4.191618082591109, "pitch": null, "roll": null}, "v": 1.2037293941267344, "accelerator_pedal_position": 0.2830642496474469, "brake_pedal_position": 0.0, "acceleration": 0.24447544604735932, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3020837069527834, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137694.9275227} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29008471968893, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.233224929443892, "gear": 1, "accelerator_pedal_position": 0.29008471968893, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137694.9275227} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137694.9375226, "x": 47.55001648116723, "y": 11.603235042445094, "z": null, "yaw": 4.219223296792029, "pitch": null, "roll": null}, "v": 1.2360865275870678, "accelerator_pedal_position": 0.29008471968893, "brake_pedal_position": 0.0, "acceleration": 0.2859460726396365, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3102039396809661, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137694.9475226} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3074642602768547, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2389459883134641, "gear": 1, "accelerator_pedal_position": 0.29008471968893, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137694.9475226} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.72996401786804, "x": 43.55001648116723, "y": 6.603235042445094, "z": null, "yaw": 4.219223296792029, "pitch": null, "roll": null}, "v": 1.2360865275870678, "accelerator_pedal_position": 0.29008471968893, "brake_pedal_position": 0.0, "acceleration": 0.2859460726396365, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3102039396809661, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137694.9675226} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2993716987098829, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2468301269321913, "gear": 1, "accelerator_pedal_position": 0.3074642602768547, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137694.9675226} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.72996401786804, "x": 43.55001648116723, "y": 6.603235042445094, "z": null, "yaw": 4.219223296792029, "pitch": null, "roll": null}, "v": 1.2360865275870678, "accelerator_pedal_position": 0.29008471968893, "brake_pedal_position": 0.0, "acceleration": 0.2859460726396365, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3102039396809661, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137694.9875226} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2993716987098829, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2536912691756783, "gear": 1, "accelerator_pedal_position": 0.2993716987098829, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137694.9875226} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.72996401786804, "x": 43.55001648116723, "y": 6.603235042445094, "z": null, "yaw": 4.219223296792029, "pitch": null, "roll": null}, "v": 1.2360865275870678, "accelerator_pedal_position": 0.29008471968893, "brake_pedal_position": 0.0, "acceleration": 0.2859460726396365, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3102039396809661, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137695.0075226} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2993716987098829, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2605421181480225, "gear": 1, "accelerator_pedal_position": 0.2993716987098829, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137695.0075226} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.72996401786804, "x": 43.55001648116723, "y": 6.603235042445094, "z": null, "yaw": 4.219223296792029, "pitch": null, "roll": null}, "v": 1.2360865275870678, "accelerator_pedal_position": 0.29008471968893, "brake_pedal_position": 0.0, "acceleration": 0.2859460726396365, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3102039396809661, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137695.0275226} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2993716987098829, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2673826705248694, "gear": 1, "accelerator_pedal_position": 0.2993716987098829, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137695.0275226} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137695.0475225, "x": 47.4862790249021, "y": 11.480970399191964, "z": null, "yaw": 4.246828510992948, "pitch": null, "roll": null}, "v": 1.2742129230714396, "accelerator_pedal_position": 0.2993716987098829, "brake_pedal_position": 0.0, "acceleration": 0.3411262850499734, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3197720061723741, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137695.0475225} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.31948676919794583, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.877922738620885, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2742129230714396, "gear": 1, "accelerator_pedal_position": 0.2993716987098829, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137695.0475225} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.83996391296387, "x": 43.4862790249021, "y": 6.480970399191964, "z": null, "yaw": 4.246828510992948, "pitch": null, "roll": null}, "v": 1.2742129230714396, "accelerator_pedal_position": 0.2993716987098829, "brake_pedal_position": 0.0, "acceleration": 0.3411262850499734, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3197720061723741, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137695.0675225} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.310126323830202, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.877922738620885, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2835463064555457, "gear": 1, "accelerator_pedal_position": 0.31948676919794583, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137695.0675225} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.83996391296387, "x": 43.4862790249021, "y": 6.480970399191964, "z": null, "yaw": 4.246828510992948, "pitch": null, "roll": null}, "v": 1.2742129230714396, "accelerator_pedal_position": 0.2993716987098829, "brake_pedal_position": 0.0, "acceleration": 0.3411262850499734, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3197720061723741, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137695.0875225} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.310126323830202, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.877922738620885, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2916959661128387, "gear": 1, "accelerator_pedal_position": 0.310126323830202, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137695.0875225} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.83996391296387, "x": 43.4862790249021, "y": 6.480970399191964, "z": null, "yaw": 4.246828510992948, "pitch": null, "roll": null}, "v": 1.2742129230714396, "accelerator_pedal_position": 0.2993716987098829, "brake_pedal_position": 0.0, "acceleration": 0.3411262850499734, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3197720061723741, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137695.1075225} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.310126323830202, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.877922738620885, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.299833276683338, "gear": 1, "accelerator_pedal_position": 0.310126323830202, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137695.1075225} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.83996391296387, "x": 43.4862790249021, "y": 6.480970399191964, "z": null, "yaw": 4.246828510992948, "pitch": null, "roll": null}, "v": 1.2742129230714396, "accelerator_pedal_position": 0.2993716987098829, "brake_pedal_position": 0.0, "acceleration": 0.3411262850499734, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3197720061723741, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137695.1275225} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.310126323830202, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.877922738620885, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.307958230403202, "gear": 1, "accelerator_pedal_position": 0.310126323830202, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137695.1275225} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.83996391296387, "x": 43.4862790249021, "y": 6.480970399191964, "z": null, "yaw": 4.246828510992948, "pitch": null, "roll": null}, "v": 1.2742129230714396, "accelerator_pedal_position": 0.2993716987098829, "brake_pedal_position": 0.0, "acceleration": 0.3411262850499734, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.3197720061723741, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137695.1475224} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.310126323830202, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.877922738620885, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3160708196409303, "gear": 1, "accelerator_pedal_position": 0.310126323830202, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137695.1475224} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137695.1575224, "x": 47.423915831855034, "y": 11.352829532254258, "z": null, "yaw": 4.274433725193868, "pitch": null, "roll": null}, "v": 1.3201224752302665, "accelerator_pedal_position": 0.310126323830202, "brake_pedal_position": 0.0, "acceleration": 0.4048561666811681, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.331293306365215, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137695.1675224} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3427639694360336, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.420171563274748, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3241710368970783, "gear": 1, "accelerator_pedal_position": 0.310126323830202, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.409239255113528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137695.1675224} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.94996380805969, "x": 43.423915831855034, "y": 6.352829532254258, "z": null, "yaw": 4.274433725193868, "pitch": null, "roll": null}, "v": 1.3201224752302665, "accelerator_pedal_position": 0.310126323830202, "brake_pedal_position": 0.0, "acceleration": 0.4048561666811681, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.331293306365215, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137695.1875224} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3274878658304269, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.420171563274748, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.33633701828893, "gear": 1, "accelerator_pedal_position": 0.3427639694360336, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.33686568904556, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137695.1875224} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.94996380805969, "x": 43.423915831855034, "y": 6.352829532254258, "z": null, "yaw": 4.274433725193868, "pitch": null, "roll": null}, "v": 1.3201224752302665, "accelerator_pedal_position": 0.310126323830202, "brake_pedal_position": 0.0, "acceleration": 0.4048561666811681, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.331293306365215, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137695.2075224} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3274878658304269, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.420171563274748, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3465755731882814, "gear": 1, "accelerator_pedal_position": 0.3274878658304269, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.264191522462921, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137695.2075224} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.94996380805969, "x": 43.423915831855034, "y": 6.352829532254258, "z": null, "yaw": 4.274433725193868, "pitch": null, "roll": null}, "v": 1.3201224752302665, "accelerator_pedal_position": 0.310126323830202, "brake_pedal_position": 0.0, "acceleration": 0.4048561666811681, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.331293306365215, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137695.2275224} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3274878658304269, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.420171563274748, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3567983912759667, "gear": 1, "accelerator_pedal_position": 0.3274878658304269, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.191216755365609, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137695.2275224} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.94996380805969, "x": 43.423915831855034, "y": 6.352829532254258, "z": null, "yaw": 4.274433725193868, "pitch": null, "roll": null}, "v": 1.3201224752302665, "accelerator_pedal_position": 0.310126323830202, "brake_pedal_position": 0.0, "acceleration": 0.4048561666811681, "steering_wheel_angle": 10.409239255113528, "front_wheel_angle": 0.5710483640046695, "heading_rate": 0.331293306365215, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137695.2475224} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3274878658304269, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.420171563274748, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3670054549534063, "gear": 1, "accelerator_pedal_position": 0.3274878658304269, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.117941387753621, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137695.2475224} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137695.2675223, "x": 47.36279764121877, "y": 11.217951179359467, "z": null, "yaw": 4.3014341167196015, "pitch": null, "roll": null}, "v": 1.3771967468422046, "accelerator_pedal_position": 0.3274878658304269, "brake_pedal_position": 0.0, "acceleration": 0.5089726153029301, "steering_wheel_angle": 10.044365419626962, "front_wheel_angle": 0.5464518302345291, "heading_rate": 0.3272100419793581, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137695.2675223} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.36292694078220183, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.1108777076563126, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3771967468422046, "gear": 1, "accelerator_pedal_position": 0.3274878658304269, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.044365419626962, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137695.2675223} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.05996370315552, "x": 43.36279764121877, "y": 6.217951179359467, "z": null, "yaw": 4.3014341167196015, "pitch": null, "roll": null}, "v": 1.3771967468422046, "accelerator_pedal_position": 0.3274878658304269, "brake_pedal_position": 0.0, "acceleration": 0.5089726153029301, "steering_wheel_angle": 10.044365419626962, "front_wheel_angle": 0.5464518302345291, "heading_rate": 0.3272100419793581, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137695.2875223} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3463859016949292, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.1108777076563126, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3918004138541542, "gear": 1, "accelerator_pedal_position": 0.36292694078220183, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.97740913809922, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137695.2875223} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.05996370315552, "x": 43.36279764121877, "y": 6.217951179359467, "z": null, "yaw": 4.3014341167196015, "pitch": null, "roll": null}, "v": 1.3771967468422046, "accelerator_pedal_position": 0.3274878658304269, "brake_pedal_position": 0.0, "acceleration": 0.5089726153029301, "steering_wheel_angle": 10.044365419626962, "front_wheel_angle": 0.5464518302345291, "heading_rate": 0.3272100419793581, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137695.3075223} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3463859016949292, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.1108777076563126, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4043145534046046, "gear": 1, "accelerator_pedal_position": 0.3463859016949292, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.910205841082448, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137695.3075223} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.05996370315552, "x": 43.36279764121877, "y": 6.217951179359467, "z": null, "yaw": 4.3014341167196015, "pitch": null, "roll": null}, "v": 1.3771967468422046, "accelerator_pedal_position": 0.3274878658304269, "brake_pedal_position": 0.0, "acceleration": 0.5089726153029301, "steering_wheel_angle": 10.044365419626962, "front_wheel_angle": 0.5464518302345291, "heading_rate": 0.3272100419793581, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137695.3275223} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3463859016949292, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.1108777076563126, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.416809172584887, "gear": 1, "accelerator_pedal_position": 0.3463859016949292, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.842755528576642, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137695.3275223} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.05996370315552, "x": 43.36279764121877, "y": 6.217951179359467, "z": null, "yaw": 4.3014341167196015, "pitch": null, "roll": null}, "v": 1.3771967468422046, "accelerator_pedal_position": 0.3274878658304269, "brake_pedal_position": 0.0, "acceleration": 0.5089726153029301, "steering_wheel_angle": 10.044365419626962, "front_wheel_angle": 0.5464518302345291, "heading_rate": 0.3272100419793581, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137695.3475223} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3463859016949292, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.1108777076563126, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4292842394223833, "gear": 1, "accelerator_pedal_position": 0.3463859016949292, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.775058200581809, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137695.3475223} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.05996370315552, "x": 43.36279764121877, "y": 6.217951179359467, "z": null, "yaw": 4.3014341167196015, "pitch": null, "roll": null}, "v": 1.3771967468422046, "accelerator_pedal_position": 0.3274878658304269, "brake_pedal_position": 0.0, "acceleration": 0.5089726153029301, "steering_wheel_angle": 10.044365419626962, "front_wheel_angle": 0.5464518302345291, "heading_rate": 0.3272100419793581, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137695.3675222} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3463859016949292, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.1108777076563126, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.441739722287317, "gear": 1, "accelerator_pedal_position": 0.3463859016949292, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.707113857097942, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137695.3675222} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137695.3775222, "x": 47.30251120300159, "y": 11.075020951453027, "z": null, "yaw": 4.326919023418368, "pitch": null, "roll": null}, "v": 1.4479601099394241, "accelerator_pedal_position": 0.3463859016949292, "brake_pedal_position": 0.0, "acceleration": 0.6215479952965783, "steering_wheel_angle": 9.67304905454762, "front_wheel_angle": 0.5219254290660298, "heading_rate": 0.3252940191199493, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137695.3875222} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.39357265311631623, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.2317531941787876, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4541755898923898, "gear": 1, "accelerator_pedal_position": 0.3463859016949292, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.63892249812504, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137695.3875222} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.16996359825134, "x": 43.30251120300159, "y": 6.075020951453027, "z": null, "yaw": 4.326919023418368, "pitch": null, "roll": null}, "v": 1.4479601099394241, "accelerator_pedal_position": 0.3463859016949292, "brake_pedal_position": 0.0, "acceleration": 0.6215479952965783, "steering_wheel_angle": 9.67304905454762, "front_wheel_angle": 0.5219254290660298, "heading_rate": 0.3252940191199493, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137695.4075222} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3715246533614873, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.2317531941787876, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4724878183783565, "gear": 1, "accelerator_pedal_position": 0.39357265311631623, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.577028939273266, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137695.4075222} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.16996359825134, "x": 43.30251120300159, "y": 6.075020951453027, "z": null, "yaw": 4.326919023418368, "pitch": null, "roll": null}, "v": 1.4479601099394241, "accelerator_pedal_position": 0.3463859016949292, "brake_pedal_position": 0.0, "acceleration": 0.6215479952965783, "steering_wheel_angle": 9.67304905454762, "front_wheel_angle": 0.5219254290660298, "heading_rate": 0.3252940191199493, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137695.4275222} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3715246533614873, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.2317531941787876, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4880160910808808, "gear": 1, "accelerator_pedal_position": 0.3715246533614873, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.514933280848629, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137695.4275222} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.16996359825134, "x": 43.30251120300159, "y": 6.075020951453027, "z": null, "yaw": 4.326919023418368, "pitch": null, "roll": null}, "v": 1.4479601099394241, "accelerator_pedal_position": 0.3463859016949292, "brake_pedal_position": 0.0, "acceleration": 0.6215479952965783, "steering_wheel_angle": 9.67304905454762, "front_wheel_angle": 0.5219254290660298, "heading_rate": 0.3252940191199493, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137695.4475222} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3715246533614873, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.2317531941787876, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.503519626964567, "gear": 1, "accelerator_pedal_position": 0.3715246533614873, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.452635522851137, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137695.4475222} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.16996359825134, "x": 43.30251120300159, "y": 6.075020951453027, "z": null, "yaw": 4.326919023418368, "pitch": null, "roll": null}, "v": 1.4479601099394241, "accelerator_pedal_position": 0.3463859016949292, "brake_pedal_position": 0.0, "acceleration": 0.6215479952965783, "steering_wheel_angle": 9.67304905454762, "front_wheel_angle": 0.5219254290660298, "heading_rate": 0.3252940191199493, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137695.4675221} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3715246533614873, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.2317531941787876, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5189983693302247, "gear": 1, "accelerator_pedal_position": 0.3715246533614873, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.390135665280793, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137695.4675221} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137695.4875221, "x": 47.24269084143972, "y": 10.92272714803379, "z": null, "yaw": 4.351048322121599, "pitch": null, "roll": null}, "v": 1.5344522620299696, "accelerator_pedal_position": 0.3715246533614873, "brake_pedal_position": 0.0, "acceleration": 0.7717610329633082, "steering_wheel_angle": 9.327433708137589, "front_wheel_angle": 0.49952780664891583, "heading_rate": 0.3270838023100318, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137695.4875221} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.40349230779397965, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9326502344129631, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5344522620299696, "gear": 1, "accelerator_pedal_position": 0.3715246533614873, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.327433708137589, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137695.4875221} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.27996349334717, "x": 43.24269084143972, "y": 5.92272714803379, "z": null, "yaw": 4.351048322121599, "pitch": null, "roll": null}, "v": 1.5344522620299696, "accelerator_pedal_position": 0.3715246533614873, "brake_pedal_position": 0.0, "acceleration": 0.7717610329633082, "steering_wheel_angle": 9.327433708137589, "front_wheel_angle": 0.49952780664891583, "heading_rate": 0.3270838023100318, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137695.507522} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.38879563912253684, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9326502344129631, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5538755906382438, "gear": 1, "accelerator_pedal_position": 0.40349230779397965, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.268723640065229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137695.507522} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.27996349334717, "x": 43.24269084143972, "y": 5.92272714803379, "z": null, "yaw": 4.351048322121599, "pitch": null, "roll": null}, "v": 1.5344522620299696, "accelerator_pedal_position": 0.3715246533614873, "brake_pedal_position": 0.0, "acceleration": 0.7717610329633082, "steering_wheel_angle": 9.327433708137589, "front_wheel_angle": 0.49952780664891583, "heading_rate": 0.3270838023100318, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137695.527522} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.38879563912253684, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9326502344129631, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5714311366671867, "gear": 1, "accelerator_pedal_position": 0.38879563912253684, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.209837485456893, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137695.527522} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.27996349334717, "x": 43.24269084143972, "y": 5.92272714803379, "z": null, "yaw": 4.351048322121599, "pitch": null, "roll": null}, "v": 1.5344522620299696, "accelerator_pedal_position": 0.3715246533614873, "brake_pedal_position": 0.0, "acceleration": 0.7717610329633082, "steering_wheel_angle": 9.327433708137589, "front_wheel_angle": 0.49952780664891583, "heading_rate": 0.3270838023100318, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137695.547522} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.38879563912253684, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9326502344129631, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5889581346649997, "gear": 1, "accelerator_pedal_position": 0.38879563912253684, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.150775244312582, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137695.547522} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.27996349334717, "x": 43.24269084143972, "y": 5.92272714803379, "z": null, "yaw": 4.351048322121599, "pitch": null, "roll": null}, "v": 1.5344522620299696, "accelerator_pedal_position": 0.3715246533614873, "brake_pedal_position": 0.0, "acceleration": 0.7717610329633082, "steering_wheel_angle": 9.327433708137589, "front_wheel_angle": 0.49952780664891583, "heading_rate": 0.3270838023100318, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137695.567522} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.38879563912253684, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9326502344129631, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6064565082271336, "gear": 1, "accelerator_pedal_position": 0.38879563912253684, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.091536916632297, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137695.567522} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.27996349334717, "x": 43.24269084143972, "y": 5.92272714803379, "z": null, "yaw": 4.351048322121599, "pitch": null, "roll": null}, "v": 1.5344522620299696, "accelerator_pedal_position": 0.3715246533614873, "brake_pedal_position": 0.0, "acceleration": 0.7717610329633082, "steering_wheel_angle": 9.327433708137589, "front_wheel_angle": 0.49952780664891583, "heading_rate": 0.3270838023100318, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137695.587522} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.38879563912253684, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9326502344129631, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6239261816749662, "gear": 1, "accelerator_pedal_position": 0.38879563912253684, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.032122502416037, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137695.587522} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137695.597522, "x": 47.18298432213589, "y": 10.759519065475581, "z": null, "yaw": 4.373974743868513, "pitch": null, "roll": null}, "v": 1.6326502324049343, "accelerator_pedal_position": 0.38879563912253684, "brake_pedal_position": 0.0, "acceleration": 0.8716847650818896, "steering_wheel_angle": 9.002349262856914, "front_wheel_angle": 0.47881996623809686, "heading_rate": 0.33106568873322756, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137695.607522} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24516016387426479, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.826174153521088, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6413670800557532, "gear": 1, "accelerator_pedal_position": 0.38879563912253684, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.972532001663799, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137695.607522} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.38996338844299, "x": 43.18298432213589, "y": 5.7595190654755815, "z": null, "yaw": 4.373974743868513, "pitch": null, "roll": null}, "v": 1.6326502324049343, "accelerator_pedal_position": 0.38879563912253684, "brake_pedal_position": 0.0, "acceleration": 0.8716847650818896, "steering_wheel_angle": 9.002349262856914, "front_wheel_angle": 0.47881996623809686, "heading_rate": 0.33106568873322756, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137695.627522} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3141690859045452, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.826174153521088, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.640832137905486, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.905095038932691, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137695.627522} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.38996338844299, "x": 43.18298432213589, "y": 5.7595190654755815, "z": null, "yaw": 4.373974743868513, "pitch": null, "roll": null}, "v": 1.6326502324049343, "accelerator_pedal_position": 0.38879563912253684, "brake_pedal_position": 0.0, "acceleration": 0.8716847650818896, "steering_wheel_angle": 9.002349262856914, "front_wheel_angle": 0.47881996623809686, "heading_rate": 0.33106568873322756, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137695.647522} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3141690859045452, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.826174153521088, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6489206231536357, "gear": 1, "accelerator_pedal_position": 0.3141690859045452, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.837433976482636, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137695.647522} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.38996338844299, "x": 43.18298432213589, "y": 5.7595190654755815, "z": null, "yaw": 4.373974743868513, "pitch": null, "roll": null}, "v": 1.6326502324049343, "accelerator_pedal_position": 0.38879563912253684, "brake_pedal_position": 0.0, "acceleration": 0.8716847650818896, "steering_wheel_angle": 9.002349262856914, "front_wheel_angle": 0.47881996623809686, "heading_rate": 0.33106568873322756, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137695.667522} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3141690859045452, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.826174153521088, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6569956971173827, "gear": 1, "accelerator_pedal_position": 0.3141690859045452, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.76954881431363, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137695.667522} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.38996338844299, "x": 43.18298432213589, "y": 5.7595190654755815, "z": null, "yaw": 4.373974743868513, "pitch": null, "roll": null}, "v": 1.6326502324049343, "accelerator_pedal_position": 0.38879563912253684, "brake_pedal_position": 0.0, "acceleration": 0.8716847650818896, "steering_wheel_angle": 9.002349262856914, "front_wheel_angle": 0.47881996623809686, "heading_rate": 0.33106568873322756, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137695.687522} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3141690859045452, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.826174153521088, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.665057355961697, "gear": 1, "accelerator_pedal_position": 0.3141690859045452, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.701439552425674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137695.687522} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137695.707522, "x": 47.12443308377723, "y": 10.58767496579038, "z": null, "yaw": 4.395717313837462, "pitch": null, "roll": null}, "v": 1.6731055959877963, "accelerator_pedal_position": 0.3141690859045452, "brake_pedal_position": 0.0, "acceleration": 0.40190868375076055, "steering_wheel_angle": 8.63310619081877, "front_wheel_angle": 0.45570011557686374, "heading_rate": 0.32031132552543634, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137695.707522} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22070116896401049, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.604658685182286, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6731055959877963, "gear": 1, "accelerator_pedal_position": 0.3141690859045452, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.63310619081877, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137695.707522} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.49996328353882, "x": 43.12443308377723, "y": 5.587674965790381, "z": null, "yaw": 4.395717313837462, "pitch": null, "roll": null}, "v": 1.6731055959877963, "accelerator_pedal_position": 0.3141690859045452, "brake_pedal_position": 0.0, "acceleration": 0.40190868375076055, "steering_wheel_angle": 8.63310619081877, "front_wheel_angle": 0.45570011557686374, "heading_rate": 0.32031132552543634, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137695.727522} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2654657326284961, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.604658685182286, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6694618009418722, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.55670066146331, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137695.727522} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.49996328353882, "x": 43.12443308377723, "y": 5.587674965790381, "z": null, "yaw": 4.395717313837462, "pitch": null, "roll": null}, "v": 1.6731055959877963, "accelerator_pedal_position": 0.3141690859045452, "brake_pedal_position": 0.0, "acceleration": 0.40190868375076055, "steering_wheel_angle": 8.63310619081877, "front_wheel_angle": 0.45570011557686374, "heading_rate": 0.32031132552543634, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137695.7475219} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2654657326284961, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.604658685182286, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6714173193967636, "gear": 1, "accelerator_pedal_position": 0.2654657326284961, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.480016892318341, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137695.7475219} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.49996328353882, "x": 43.12443308377723, "y": 5.587674965790381, "z": null, "yaw": 4.395717313837462, "pitch": null, "roll": null}, "v": 1.6731055959877963, "accelerator_pedal_position": 0.3141690859045452, "brake_pedal_position": 0.0, "acceleration": 0.40190868375076055, "steering_wheel_angle": 8.63310619081877, "front_wheel_angle": 0.45570011557686374, "heading_rate": 0.32031132552543634, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137695.7675219} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2654657326284961, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.604658685182286, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6733695766815773, "gear": 1, "accelerator_pedal_position": 0.2654657326284961, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.403054883383865, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137695.7675219} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.49996328353882, "x": 43.12443308377723, "y": 5.587674965790381, "z": null, "yaw": 4.395717313837462, "pitch": null, "roll": null}, "v": 1.6731055959877963, "accelerator_pedal_position": 0.3141690859045452, "brake_pedal_position": 0.0, "acceleration": 0.40190868375076055, "steering_wheel_angle": 8.63310619081877, "front_wheel_angle": 0.45570011557686374, "heading_rate": 0.32031132552543634, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137695.7875218} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2654657326284961, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.604658685182286, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6753185767109988, "gear": 1, "accelerator_pedal_position": 0.2654657326284961, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.325814634659876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137695.7875218} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.49996328353882, "x": 43.12443308377723, "y": 5.587674965790381, "z": null, "yaw": 4.395717313837462, "pitch": null, "roll": null}, "v": 1.6731055959877963, "accelerator_pedal_position": 0.3141690859045452, "brake_pedal_position": 0.0, "acceleration": 0.40190868375076055, "steering_wheel_angle": 8.63310619081877, "front_wheel_angle": 0.45570011557686374, "heading_rate": 0.32031132552543634, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137695.8075218} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2654657326284961, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.604658685182286, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.677264323400809, "gear": 1, "accelerator_pedal_position": 0.2654657326284961, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.24829614614638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137695.8075218} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137695.8175218, "x": 47.06876881456238, "y": 10.412250979470711, "z": null, "yaw": 4.4161509838541955, "pitch": null, "roll": null}, "v": 1.6782359779673344, "accelerator_pedal_position": 0.2654657326284961, "brake_pedal_position": 0.0, "acceleration": 0.09708427005229409, "steering_wheel_angle": 8.209432561968567, "front_wheel_angle": 0.42966968497285823, "heading_rate": 0.30039197632571185, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137695.8275218} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -9.695744701487301, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6792068206678572, "gear": 1, "accelerator_pedal_position": 0.2654657326284961, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.170499417843375, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137695.8275218} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.609963178634644, "x": 43.06876881456238, "y": 5.412250979470711, "z": null, "yaw": 4.4161509838541955, "pitch": null, "roll": null}, "v": 1.6782359779673344, "accelerator_pedal_position": 0.2654657326284961, "brake_pedal_position": 0.0, "acceleration": 0.09708427005229409, "steering_wheel_angle": 8.209432561968567, "front_wheel_angle": 0.42966968497285823, "heading_rate": 0.30039197632571185, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137695.8475218} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2348505584742349, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -9.695744701487301, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.672966274906598, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.084167966377098, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137695.8475218} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.609963178634644, "x": 43.06876881456238, "y": 5.412250979470711, "z": null, "yaw": 4.4161509838541955, "pitch": null, "roll": null}, "v": 1.6782359779673344, "accelerator_pedal_position": 0.2654657326284961, "brake_pedal_position": 0.0, "acceleration": 0.09708427005229409, "steering_wheel_angle": 8.209432561968567, "front_wheel_angle": 0.42966968497285823, "heading_rate": 0.30039197632571185, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137695.8675218} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2348505584742349, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -9.695744701487301, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6710906481409913, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.997496443318061, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137695.8675218} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.609963178634644, "x": 43.06876881456238, "y": 5.412250979470711, "z": null, "yaw": 4.4161509838541955, "pitch": null, "roll": null}, "v": 1.6782359779673344, "accelerator_pedal_position": 0.2654657326284961, "brake_pedal_position": 0.0, "acceleration": 0.09708427005229409, "steering_wheel_angle": 8.209432561968567, "front_wheel_angle": 0.42966968497285823, "heading_rate": 0.30039197632571185, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137695.8875217} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2348505584742349, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -9.695744701487301, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.669218149785454, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.910484848666267, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137695.8875217} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.609963178634644, "x": 43.06876881456238, "y": 5.412250979470711, "z": null, "yaw": 4.4161509838541955, "pitch": null, "roll": null}, "v": 1.6782359779673344, "accelerator_pedal_position": 0.2654657326284961, "brake_pedal_position": 0.0, "acceleration": 0.09708427005229409, "steering_wheel_angle": 8.209432561968567, "front_wheel_angle": 0.42966968497285823, "heading_rate": 0.30039197632571185, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137695.9075217} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2348505584742349, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -9.695744701487301, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6673487732201078, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.823133182421717, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137695.9075217} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137695.9275217, "x": 47.016624104128695, "y": 10.23589078972233, "z": null, "yaw": 4.435177324587149, "pitch": null, "roll": null}, "v": 1.6654825118431238, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.311012445564709, "steering_wheel_angle": 7.735441444584407, "front_wheel_angle": 0.4011416866639745, "heading_rate": 0.2759363859897202, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137695.9275217} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6654825118431238, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.735441444584407, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137695.9275217} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.71996307373047, "x": 43.016624104128695, "y": 5.23589078972233, "z": null, "yaw": 4.435177324587149, "pitch": null, "roll": null}, "v": 1.6654825118431238, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.311012445564709, "steering_wheel_angle": 7.735441444584407, "front_wheel_angle": 0.4011416866639745, "heading_rate": 0.2759363859897202, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137695.9475217} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6592648529983482, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.640676212371447, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137695.9475217} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.71996307373047, "x": 43.016624104128695, "y": 5.23589078972233, "z": null, "yaw": 4.435177324587149, "pitch": null, "roll": null}, "v": 1.6654825118431238, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.311012445564709, "steering_wheel_angle": 7.735441444584407, "front_wheel_angle": 0.4011416866639745, "heading_rate": 0.2759363859897202, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137695.9675217} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6530575380713601, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.545517012010114, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137695.9675217} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.71996307373047, "x": 43.016624104128695, "y": 5.23589078972233, "z": null, "yaw": 4.435177324587149, "pitch": null, "roll": null}, "v": 1.6654825118431238, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.311012445564709, "steering_wheel_angle": 7.735441444584407, "front_wheel_angle": 0.4011416866639745, "heading_rate": 0.2759363859897202, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137695.9875216} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6468605344477432, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.449963843500413, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137695.9875216} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.71996307373047, "x": 43.016624104128695, "y": 5.23589078972233, "z": null, "yaw": 4.435177324587149, "pitch": null, "roll": null}, "v": 1.6654825118431238, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.311012445564709, "steering_wheel_angle": 7.735441444584407, "front_wheel_angle": 0.4011416866639745, "heading_rate": 0.2759363859897202, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137696.0075216} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.640673809644062, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.35401670684234, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137696.0075216} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.71996307373047, "x": 43.016624104128695, "y": 5.23589078972233, "z": null, "yaw": 4.435177324587149, "pitch": null, "roll": null}, "v": 1.6654825118431238, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.311012445564709, "steering_wheel_angle": 7.735441444584407, "front_wheel_angle": 0.4011416866639745, "heading_rate": 0.2759363859897202, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137696.0275216} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6344973313071955, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.2576756020358975, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137696.0275216} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137696.0375216, "x": 46.9683623118163, "y": 10.0609306970971, "z": null, "yaw": 4.4526940866737945, "pitch": null, "roll": null}, "v": 1.6314129244889368, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3081857275263423, "steering_wheel_angle": 7.209357311577038, "front_wheel_angle": 0.3701673303464107, "heading_rate": 0.24729650288670427, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137696.0475216} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21712085398398862, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6283310672136735, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.160940529081084, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137696.0475216} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.829962968826294, "x": 42.9683623118163, "y": 5.060930697097101, "z": null, "yaw": 4.4526940866737945, "pitch": null, "roll": null}, "v": 1.6314129244889368, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3081857275263423, "steering_wheel_angle": 7.209357311577038, "front_wheel_angle": 0.3701673303464107, "heading_rate": 0.24729650288670427, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137696.0675216} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6243142090546028, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.063811487977904, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137696.0675216} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.829962968826294, "x": 42.9683623118163, "y": 5.060930697097101, "z": null, "yaw": 4.4526940866737945, "pitch": null, "roll": null}, "v": 1.6314129244889368, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3081857275263423, "steering_wheel_angle": 7.209357311577038, "front_wheel_angle": 0.3701673303464107, "heading_rate": 0.24729650288670427, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137696.0875216} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.618164751844862, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.96628847872635, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137696.0875216} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.829962968826294, "x": 42.9683623118163, "y": 5.060930697097101, "z": null, "yaw": 4.4526940866737945, "pitch": null, "roll": null}, "v": 1.6314129244889368, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3081857275263423, "steering_wheel_angle": 7.209357311577038, "front_wheel_angle": 0.3701673303464107, "heading_rate": 0.24729650288670427, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137696.1075215} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6120254240346996, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.868371501326427, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137696.1075215} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.829962968826294, "x": 42.9683623118163, "y": 5.060930697097101, "z": null, "yaw": 4.4526940866737945, "pitch": null, "roll": null}, "v": 1.6314129244889368, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3081857275263423, "steering_wheel_angle": 7.209357311577038, "front_wheel_angle": 0.3701673303464107, "heading_rate": 0.24729650288670427, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137696.1275215} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.605896193868602, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.770060555778136, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137696.1275215} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137696.1475215, "x": 46.923936590572545, "y": 9.888621567393878, "z": null, "yaw": 4.468677465246748, "pitch": null, "roll": null}, "v": 1.5997770297176748, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3055817169340068, "steering_wheel_angle": 6.6713556420814735, "front_wheel_angle": 0.3391929740288469, "heading_rate": 0.22048747438933738, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137696.1475215} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5997770297176748, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.6713556420814735, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137696.1475215} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.93996286392212, "x": 42.923936590572545, "y": 4.888621567393878, "z": null, "yaw": 4.468677465246748, "pitch": null, "roll": null}, "v": 1.5997770297176748, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3055817169340068, "steering_wheel_angle": 6.6713556420814735, "front_wheel_angle": 0.3391929740288469, "heading_rate": 0.22048747438933738, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137696.1675215} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5936679000790004, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.572256760236441, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137696.1675215} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.93996286392212, "x": 42.923936590572545, "y": 4.888621567393878, "z": null, "yaw": 4.468677465246748, "pitch": null, "roll": null}, "v": 1.5997770297176748, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3055817169340068, "steering_wheel_angle": 6.6713556420814735, "front_wheel_angle": 0.3391929740288469, "heading_rate": 0.22048747438933738, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137696.1875215} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5875687735750026, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.472763910243039, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137696.1875215} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.93996286392212, "x": 42.923936590572545, "y": 4.888621567393878, "z": null, "yaw": 4.468677465246748, "pitch": null, "roll": null}, "v": 1.5997770297176748, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3055817169340068, "steering_wheel_angle": 6.6713556420814735, "front_wheel_angle": 0.3391929740288469, "heading_rate": 0.22048747438933738, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137696.1975214} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.584522951727132, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.4228697471907, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137696.1975214} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.93996286392212, "x": 42.923936590572545, "y": 4.888621567393878, "z": null, "yaw": 4.468677465246748, "pitch": null, "roll": null}, "v": 1.5997770297176748, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3055817169340068, "steering_wheel_angle": 6.6713556420814735, "front_wheel_angle": 0.3391929740288469, "heading_rate": 0.22048747438933738, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137696.2175214} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5723645162374678, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.222308174610416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137696.2175214} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.93996286392212, "x": 42.923936590572545, "y": 4.888621567393878, "z": null, "yaw": 4.468677465246748, "pitch": null, "roll": null}, "v": 1.5997770297176748, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3055817169340068, "steering_wheel_angle": 6.6713556420814735, "front_wheel_angle": 0.3391929740288469, "heading_rate": 0.22048747438933738, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137696.2375214} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5663001554012308, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.121436436097718, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137696.2375214} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137696.2575214, "x": 46.883008593805556, "y": 9.719197626899792, "z": null, "yaw": 4.483162409619532, "pitch": null, "roll": null}, "v": 1.5663001554012308, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3028479695381608, "steering_wheel_angle": 6.121436436097718, "front_wheel_angle": 0.3082186177112831, "heading_rate": 0.19478683335843378, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137696.2675214} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.554200993438731, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.918511054627214, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137696.2675214} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.049962759017944, "x": 42.883008593805556, "y": 4.719197626899792, "z": null, "yaw": 4.483162409619532, "pitch": null, "roll": null}, "v": 1.5663001554012308, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3028479695381608, "steering_wheel_angle": 6.121436436097718, "front_wheel_angle": 0.3082186177112831, "heading_rate": 0.19478683335843378, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137696.2975214} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5511823388692112, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.867533479166857, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137696.2975214} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.049962759017944, "x": 42.883008593805556, "y": 4.719197626899792, "z": null, "yaw": 4.483162409619532, "pitch": null, "roll": null}, "v": 1.5663001554012308, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3028479695381608, "steering_wheel_angle": 6.121436436097718, "front_wheel_angle": 0.3082186177112831, "heading_rate": 0.19478683335843378, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137696.3275213} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.542141040365966, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.71400980056323, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137696.3275213} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.542141040365966, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.71400980056323, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137696.3375213} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137696.3675213, "x": 46.84523727433375, "y": 9.552800538235392, "z": null, "yaw": 4.496179903710137, "pitch": null, "roll": null}, "v": 1.5331216600350404, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.300160703246438, "steering_wheel_angle": 5.559599693625772, "front_wheel_angle": 0.2772442613937193, "heading_rate": 0.1704238859570711, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137696.3675213} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.012540336321067734, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5331216600350404, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.559599693625772, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137696.3675213} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.15996265411377, "x": 42.84523727433375, "y": 4.552800538235392, "z": null, "yaw": 4.496179903710137, "pitch": null, "roll": null}, "v": 1.5331216600350404, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.300160703246438, "steering_wheel_angle": 5.559599693625772, "front_wheel_angle": 0.2772442613937193, "heading_rate": 0.1704238859570711, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137696.3875213} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5251152209513714, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.012540336321067734, "steering_wheel_angle": 5.456167162148669, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137696.3875213} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.15996265411377, "x": 42.84523727433375, "y": 4.552800538235392, "z": null, "yaw": 4.496179903710137, "pitch": null, "roll": null}, "v": 1.5331216600350404, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.300160703246438, "steering_wheel_angle": 5.559599693625772, "front_wheel_angle": 0.2772442613937193, "heading_rate": 0.1704238859570711, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137696.4075212} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5191273207148897, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.352340662523198, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137696.4075212} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.15996265411377, "x": 42.84523727433375, "y": 4.552800538235392, "z": null, "yaw": 4.496179903710137, "pitch": null, "roll": null}, "v": 1.5331216600350404, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.300160703246438, "steering_wheel_angle": 5.559599693625772, "front_wheel_angle": 0.2772442613937193, "heading_rate": 0.1704238859570711, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137696.4275212} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.51314904664684, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.248120194749356, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137696.4275212} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.15996265411377, "x": 42.84523727433375, "y": 4.552800538235392, "z": null, "yaw": 4.496179903710137, "pitch": null, "roll": null}, "v": 1.5331216600350404, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.300160703246438, "steering_wheel_angle": 5.559599693625772, "front_wheel_angle": 0.2772442613937193, "heading_rate": 0.1704238859570711, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137696.4475212} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.50718036898199, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.1435057588271444, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137696.4475212} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.15996265411377, "x": 42.84523727433375, "y": 4.552800538235392, "z": null, "yaw": 4.496179903710137, "pitch": null, "roll": null}, "v": 1.5331216600350404, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.300160703246438, "steering_wheel_angle": 5.559599693625772, "front_wheel_angle": 0.2772442613937193, "heading_rate": 0.1704238859570711, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137696.4675212} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5012212580717292, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.038497354756564, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137696.4675212} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137696.4775212, "x": 46.81032627138867, "y": 9.389689150728572, "z": null, "yaw": 4.507757245229959, "pitch": null, "roll": null}, "v": 1.4982452809161246, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29735965326368063, "steering_wheel_angle": 4.985845414665634, "front_wheel_angle": 0.2462699050761553, "heading_rate": 0.1471162088303917, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137696.4875212} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.01500596155481431, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.495271684383488, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.933094982537612, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137696.4875212} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.269962549209595, "x": 42.81032627138867, "y": 4.389689150728572, "z": null, "yaw": 4.507757245229959, "pitch": null, "roll": null}, "v": 1.4982452809161246, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29735965326368063, "steering_wheel_angle": 4.985845414665634, "front_wheel_angle": 0.2462699050761553, "heading_rate": 0.1471162088303917, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137696.5075212} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4869316230401917, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.01500596155481431, "steering_wheel_angle": 4.827298642170289, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137696.5075212} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.269962549209595, "x": 42.81032627138867, "y": 4.389689150728572, "z": null, "yaw": 4.507757245229959, "pitch": null, "roll": null}, "v": 1.4982452809161246, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29735965326368063, "steering_wheel_angle": 4.985845414665634, "front_wheel_angle": 0.2462699050761553, "heading_rate": 0.1471162088303917, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137696.5275211} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4810048613094666, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.721108333654597, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137696.5275211} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.269962549209595, "x": 42.81032627138867, "y": 4.389689150728572, "z": null, "yaw": 4.507757245229959, "pitch": null, "roll": null}, "v": 1.4982452809161246, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29735965326368063, "steering_wheel_angle": 4.985845414665634, "front_wheel_angle": 0.2462699050761553, "heading_rate": 0.1471162088303917, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137696.547521} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4750875371197096, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.614524056990536, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137696.547521} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.269962549209595, "x": 42.81032627138867, "y": 4.389689150728572, "z": null, "yaw": 4.507757245229959, "pitch": null, "roll": null}, "v": 1.4982452809161246, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29735965326368063, "steering_wheel_angle": 4.985845414665634, "front_wheel_angle": 0.2462699050761553, "heading_rate": 0.1471162088303917, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137696.567521} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4691796214426267, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.507545812178105, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137696.567521} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137696.587521, "x": 46.77796214722567, "y": 9.229963799235493, "z": null, "yaw": 4.5179182847403965, "pitch": null, "roll": null}, "v": 1.4632810853628846, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29457596961595206, "steering_wheel_angle": 4.400173599217304, "front_wheel_angle": 0.2152955487585915, "heading_rate": 0.12499900101497913, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137696.587521} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4632810853628846, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.400173599217304, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137696.587521} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.37996244430542, "x": 42.77796214722567, "y": 4.2299637992354935, "z": null, "yaw": 4.5179182847403965, "pitch": null, "roll": null}, "v": 1.4632810853628846, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29457596961595206, "steering_wheel_angle": 4.400173599217304, "front_wheel_angle": 0.2152955487585915, "heading_rate": 0.12499900101497913, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137696.607521} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4515120368955465, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.18424726885059, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137696.607521} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.37996244430542, "x": 42.77796214722567, "y": 4.2299637992354935, "z": null, "yaw": 4.5179182847403965, "pitch": null, "roll": null}, "v": 1.4632810853628846, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29457596961595206, "steering_wheel_angle": 4.400173599217304, "front_wheel_angle": 0.2152955487585915, "heading_rate": 0.12499900101497913, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137696.627521} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4515120368955465, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.18424726885059, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137696.627521} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.37996244430542, "x": 42.77796214722567, "y": 4.2299637992354935, "z": null, "yaw": 4.5179182847403965, "pitch": null, "roll": null}, "v": 1.4632810853628846, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29457596961595206, "steering_wheel_angle": 4.400173599217304, "front_wheel_angle": 0.2152955487585915, "heading_rate": 0.12499900101497913, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137696.647521} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4427096585782768, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.021268354686083, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137696.647521} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.37996244430542, "x": 42.77796214722567, "y": 4.2299637992354935, "z": null, "yaw": 4.5179182847403965, "pitch": null, "roll": null}, "v": 1.4632810853628846, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29457596961595206, "steering_wheel_angle": 4.400173599217304, "front_wheel_angle": 0.2152955487585915, "heading_rate": 0.12499900101497913, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137696.677521} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4339280947247506, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.857403012187745, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137696.677521} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4339280947247506, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.857403012187745, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137696.687521} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137696.697521, "x": 46.74780786921732, "y": 9.073498932325611, "z": null, "yaw": 4.5266836292184855, "pitch": null, "roll": null}, "v": 1.431005515699304, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2920280436445835, "steering_wheel_angle": 3.8025842472807807, "front_wheel_angle": 0.1843211924410277, "heading_rate": 0.1042159670937872, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137696.707521} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.03622835862897366, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.425167249901309, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.6926512413555743, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137696.707521} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.489962339401245, "x": 42.74780786921732, "y": 4.073498932325611, "z": null, "yaw": 4.5266836292184855, "pitch": null, "roll": null}, "v": 1.431005515699304, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2920280436445835, "steering_wheel_angle": 3.8025842472807807, "front_wheel_angle": 0.1843211924410277, "heading_rate": 0.1042159670937872, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137696.727521} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.02349626141197051, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4193532874170214, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.03622835862897366, "steering_wheel_angle": 3.637537000337332, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137696.727521} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.489962339401245, "x": 42.74780786921732, "y": 4.073498932325611, "z": null, "yaw": 4.5266836292184855, "pitch": null, "roll": null}, "v": 1.431005515699304, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2920280436445835, "steering_wheel_angle": 3.8025842472807807, "front_wheel_angle": 0.1843211924410277, "heading_rate": 0.1042159670937872, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137696.747521} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.02349626141197051, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4097753726517241, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.02349626141197051, "steering_wheel_angle": 3.5270130421895707, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137696.747521} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.489962339401245, "x": 42.74780786921732, "y": 4.073498932325611, "z": null, "yaw": 4.5266836292184855, "pitch": null, "roll": null}, "v": 1.431005515699304, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2920280436445835, "steering_wheel_angle": 3.8025842472807807, "front_wheel_angle": 0.1843211924410277, "heading_rate": 0.1042159670937872, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137696.767521} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.02349626141197051, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4002124401981397, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.02349626141197051, "steering_wheel_angle": 3.4160951158934396, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137696.767521} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.489962339401245, "x": 42.74780786921732, "y": 4.073498932325611, "z": null, "yaw": 4.5266836292184855, "pitch": null, "roll": null}, "v": 1.431005515699304, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2920280436445835, "steering_wheel_angle": 3.8025842472807807, "front_wheel_angle": 0.1843211924410277, "heading_rate": 0.1042159670937872, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137696.787521} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.02349626141197051, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3858960021707936, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.02349626141197051, "steering_wheel_angle": 3.2489795361710483, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137696.787521} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137696.8075209, "x": 46.71970495624484, "y": 8.921015866137788, "z": null, "yaw": 4.534070813956478, "pitch": null, "roll": null}, "v": 1.3811312824838673, "accelerator_pedal_position": 0, "brake_pedal_position": 0.02349626141197051, "acceleration": -0.4761018916145128, "steering_wheel_angle": 3.193077358856067, "front_wheel_angle": 0.15334683612346395, "heading_rate": 0.08338593464115694, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137696.8075209} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3706172444033138, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.0247798746885652, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137696.8075209} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.59996223449707, "x": 42.71970495624484, "y": 3.921015866137788, "z": null, "yaw": 4.534070813956478, "pitch": null, "roll": null}, "v": 1.3811312824838673, "accelerator_pedal_position": 0, "brake_pedal_position": 0.02349626141197051, "acceleration": -0.4761018916145128, "steering_wheel_angle": 3.193077358856067, "front_wheel_angle": 0.15334683612346395, "heading_rate": 0.08338593464115694, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137696.8375208} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.012698434240284266, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3677440766180466, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.968483729225214, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137696.8375208} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.59996223449707, "x": 42.71970495624484, "y": 3.921015866137788, "z": null, "yaw": 4.534070813956478, "pitch": null, "roll": null}, "v": 1.3811312824838673, "accelerator_pedal_position": 0, "brake_pedal_position": 0.02349626141197051, "acceleration": -0.4761018916145128, "steering_wheel_angle": 3.193077358856067, "front_wheel_angle": 0.15334683612346395, "heading_rate": 0.08338593464115694, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137696.8575208} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.012698434240284266, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.356092629187164, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.012698434240284266, "steering_wheel_angle": 2.7990043406126026, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137696.8575208} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.59996223449707, "x": 42.71970495624484, "y": 3.921015866137788, "z": null, "yaw": 4.534070813956478, "pitch": null, "roll": null}, "v": 1.3811312824838673, "accelerator_pedal_position": 0, "brake_pedal_position": 0.02349626141197051, "acceleration": -0.4761018916145128, "steering_wheel_angle": 3.193077358856067, "front_wheel_angle": 0.15334683612346395, "heading_rate": 0.08338593464115694, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137696.8775208} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.012698434240284266, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.356092629187164, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.012698434240284266, "steering_wheel_angle": 2.7990043406126026, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137696.8775208} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.59996223449707, "x": 42.71970495624484, "y": 3.921015866137788, "z": null, "yaw": 4.534070813956478, "pitch": null, "roll": null}, "v": 1.3811312824838673, "accelerator_pedal_position": 0, "brake_pedal_position": 0.02349626141197051, "acceleration": -0.4761018916145128, "steering_wheel_angle": 3.193077358856067, "front_wheel_angle": 0.15334683612346395, "heading_rate": 0.08338593464115694, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137696.8975208} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.012698434240284266, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3483399787784465, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.012698434240284266, "steering_wheel_angle": 2.6855256213520664, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137696.8975208} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137696.9175208, "x": 46.6935274442852, "y": 8.77337583931503, "z": null, "yaw": 4.54009444593122, "pitch": null, "roll": null}, "v": 1.3405992637189936, "accelerator_pedal_position": 0, "brake_pedal_position": 0.012698434240284266, "acceleration": -0.3865895009670629, "steering_wheel_angle": 2.57165293394316, "front_wheel_angle": 0.12237247980589985, "heading_rate": 0.06440479996817959, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137696.9175208} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.05885036400571076, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.336733368709323, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.012698434240284266, "steering_wheel_angle": 2.5145688521830682, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137696.9175208} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.709962129592896, "x": 42.6935274442852, "y": 3.7733758393150296, "z": null, "yaw": 4.54009444593122, "pitch": null, "roll": null}, "v": 1.3405992637189936, "accelerator_pedal_position": 0, "brake_pedal_position": 0.012698434240284266, "acceleration": -0.3865895009670629, "steering_wheel_angle": 2.57165293394316, "front_wheel_angle": 0.12237247980589985, "heading_rate": 0.06440479996817959, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137696.9375207} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.03705953973634605, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3216289975385638, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.05885036400571076, "steering_wheel_angle": 2.4001052125516074, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137696.9375207} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.709962129592896, "x": 42.6935274442852, "y": 3.7733758393150296, "z": null, "yaw": 4.54009444593122, "pitch": null, "roll": null}, "v": 1.3405992637189936, "accelerator_pedal_position": 0, "brake_pedal_position": 0.012698434240284266, "acceleration": -0.3865895009670629, "steering_wheel_angle": 2.57165293394316, "front_wheel_angle": 0.12237247980589985, "heading_rate": 0.06440479996817959, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137696.9575207} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.03705953973634605, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3042415331838977, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.03705953973634605, "steering_wheel_angle": 2.2276710628262215, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137696.9575207} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.709962129592896, "x": 42.6935274442852, "y": 3.7733758393150296, "z": null, "yaw": 4.54009444593122, "pitch": null, "roll": null}, "v": 1.3405992637189936, "accelerator_pedal_position": 0, "brake_pedal_position": 0.012698434240284266, "acceleration": -0.3865895009670629, "steering_wheel_angle": 2.57165293394316, "front_wheel_angle": 0.12237247980589985, "heading_rate": 0.06440479996817959, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137696.9875207} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.03705953973634605, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2984545446407099, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.03705953973634605, "steering_wheel_angle": 2.169996028843575, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137696.9875207} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.709962129592896, "x": 42.6935274442852, "y": 3.7733758393150296, "z": null, "yaw": 4.54009444593122, "pitch": null, "roll": null}, "v": 1.3405992637189936, "accelerator_pedal_position": 0, "brake_pedal_position": 0.012698434240284266, "acceleration": -0.3865895009670629, "steering_wheel_angle": 2.57165293394316, "front_wheel_angle": 0.12237247980589985, "heading_rate": 0.06440479996817959, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137697.0075207} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.03705953973634605, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2868937565337166, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.03705953973634605, "steering_wheel_angle": 2.0543504847670038, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137697.0075207} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137697.0275207, "x": 46.669124503389234, "y": 8.631282376764275, "z": null, "yaw": 4.544766321191235, "pitch": null, "roll": null}, "v": 1.2753504869458345, "accelerator_pedal_position": 0, "brake_pedal_position": 0.03705953973634605, "acceleration": -0.5765090308835898, "steering_wheel_angle": 1.9383109725420626, "front_wheel_angle": 0.09139812348833609, "heading_rate": 0.04566027669061346, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137697.0275207} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2753504869458345, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.03705953973634605, "steering_wheel_angle": 1.9383109725420626, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137697.0275207} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.81996202468872, "x": 42.669124503389234, "y": 3.6312823767642755, "z": null, "yaw": 4.544766321191235, "pitch": null, "roll": null}, "v": 1.2753504869458345, "accelerator_pedal_position": 0, "brake_pedal_position": 0.03705953973634605, "acceleration": -0.5765090308835898, "steering_wheel_angle": 1.9383109725420626, "front_wheel_angle": 0.09139812348833609, "heading_rate": 0.04566027669061346, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137697.0475206} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.02312106675267317, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2697519463450737, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.8218774921687513, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137697.0475206} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.81996202468872, "x": 42.669124503389234, "y": 3.6312823767642755, "z": null, "yaw": 4.544766321191235, "pitch": null, "roll": null}, "v": 1.2753504869458345, "accelerator_pedal_position": 0, "brake_pedal_position": 0.03705953973634605, "acceleration": -0.5765090308835898, "steering_wheel_angle": 1.9383109725420626, "front_wheel_angle": 0.09139812348833609, "heading_rate": 0.04566027669061346, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137697.0675206} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.02312106675267317, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2604638702528244, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.02312106675267317, "steering_wheel_angle": 1.7050500436470701, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137697.0675206} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.81996202468872, "x": 42.669124503389234, "y": 3.6312823767642755, "z": null, "yaw": 4.544766321191235, "pitch": null, "roll": null}, "v": 1.2753504869458345, "accelerator_pedal_position": 0, "brake_pedal_position": 0.03705953973634605, "acceleration": -0.5765090308835898, "steering_wheel_angle": 1.9383109725420626, "front_wheel_angle": 0.09139812348833609, "heading_rate": 0.04566027669061346, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137697.0875206} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.02312106675267317, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2511897685202524, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.02312106675267317, "steering_wheel_angle": 1.587828626977019, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137697.0875206} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.81996202468872, "x": 42.669124503389234, "y": 3.6312823767642755, "z": null, "yaw": 4.544766321191235, "pitch": null, "roll": null}, "v": 1.2753504869458345, "accelerator_pedal_position": 0, "brake_pedal_position": 0.03705953973634605, "acceleration": -0.5765090308835898, "steering_wheel_angle": 1.9383109725420626, "front_wheel_angle": 0.09139812348833609, "heading_rate": 0.04566027669061346, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137697.1075206} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.02312106675267317, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2419295857315684, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.02312106675267317, "steering_wheel_angle": 1.4702132421585983, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137697.1075206} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.81996202468872, "x": 42.669124503389234, "y": 3.6312823767642755, "z": null, "yaw": 4.544766321191235, "pitch": null, "roll": null}, "v": 1.2753504869458345, "accelerator_pedal_position": 0, "brake_pedal_position": 0.03705953973634605, "acceleration": -0.5765090308835898, "steering_wheel_angle": 1.9383109725420626, "front_wheel_angle": 0.09139812348833609, "heading_rate": 0.04566027669061346, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137697.1275206} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.02312106675267317, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2326832667090941, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.02312106675267317, "steering_wheel_angle": 1.352203889191807, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137697.1275206} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137697.1375206, "x": 46.64630588625796, "y": 8.495093728558123, "z": null, "yaw": 4.548095518300795, "pitch": null, "roll": null}, "v": 1.2280652889319232, "accelerator_pedal_position": 0, "brake_pedal_position": 0.02312106675267317, "acceleration": -0.461453242006776, "steering_wheel_angle": 1.293051474652773, "front_wheel_angle": 0.060423767170772295, "heading_rate": 0.029021394774917653, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137697.1475205} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.03267387223242559, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2234507565118555, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.02312106675267317, "steering_wheel_angle": 1.233800568076646, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137697.1475205} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.929961919784546, "x": 42.64630588625796, "y": 3.495093728558123, "z": null, "yaw": 4.548095518300795, "pitch": null, "roll": null}, "v": 1.2280652889319232, "accelerator_pedal_position": 0, "brake_pedal_position": 0.02312106675267317, "acceleration": -0.461453242006776, "steering_wheel_angle": 1.293051474652773, "front_wheel_angle": 0.060423767170772295, "heading_rate": 0.029021394774917653, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137697.1675205} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.02833610584941531, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2076838142485022, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.02833610584941531, "steering_wheel_angle": 1.0554568961257107, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137697.1675205} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.929961919784546, "x": 42.64630588625796, "y": 3.495093728558123, "z": null, "yaw": 4.548095518300795, "pitch": null, "roll": null}, "v": 1.2280652889319232, "accelerator_pedal_position": 0, "brake_pedal_position": 0.02312106675267317, "acceleration": -0.461453242006776, "steering_wheel_angle": 1.293051474652773, "front_wheel_angle": 0.060423767170772295, "heading_rate": 0.029021394774917653, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137697.1875205} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.02833610584941531, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1976543709214864, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.02833610584941531, "steering_wheel_angle": 0.9360686546396249, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137697.1875205} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.929961919784546, "x": 42.64630588625796, "y": 3.495093728558123, "z": null, "yaw": 4.548095518300795, "pitch": null, "roll": null}, "v": 1.2280652889319232, "accelerator_pedal_position": 0, "brake_pedal_position": 0.02312106675267317, "acceleration": -0.461453242006776, "steering_wheel_angle": 1.293051474652773, "front_wheel_angle": 0.060423767170772295, "heading_rate": 0.029021394774917653, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137697.2075205} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.02833610584941531, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1876397663305434, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.02833610584941531, "steering_wheel_angle": 0.8162864450051688, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137697.2075205} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.929961919784546, "x": 42.64630588625796, "y": 3.495093728558123, "z": null, "yaw": 4.548095518300795, "pitch": null, "roll": null}, "v": 1.2280652889319232, "accelerator_pedal_position": 0, "brake_pedal_position": 0.02312106675267317, "acceleration": -0.461453242006776, "steering_wheel_angle": 1.293051474652773, "front_wheel_angle": 0.060423767170772295, "heading_rate": 0.029021394774917653, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137697.2275205} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.02833610584941531, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1826380091579678, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.02833610584941531, "steering_wheel_angle": 0.7562476021323021, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137697.2275205} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137697.2475204, "x": 46.62479772084397, "y": 8.364545006755497, "z": null, "yaw": 4.550088469433626, "pitch": null, "roll": null}, "v": 1.172645546399746, "accelerator_pedal_position": 0, "brake_pedal_position": 0.02833610584941531, "acceleration": -0.4990720998902214, "steering_wheel_angle": 0.6358744402752912, "front_wheel_angle": 0.02944941085320852, "heading_rate": 0.013493635653726401, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137697.2475204} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.172645546399746, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.02833610584941531, "steering_wheel_angle": 0.6358744402752912, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137697.2475204} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.03996181488037, "x": 42.62479772084397, "y": 3.364545006755497, "z": null, "yaw": 4.550088469433626, "pitch": null, "roll": null}, "v": 1.172645546399746, "accelerator_pedal_position": 0, "brake_pedal_position": 0.02833610584941531, "acceleration": -0.4990720998902214, "steering_wheel_angle": 0.6358744402752912, "front_wheel_angle": 0.02944941085320852, "heading_rate": 0.013493635653726401, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137697.2675204} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.016702549089694797, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.163143841906066, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.016702549089694797, "steering_wheel_angle": 0.45457600721158115, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137697.2675204} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.03996181488037, "x": 42.62479772084397, "y": 3.364545006755497, "z": null, "yaw": 4.550088469433626, "pitch": null, "roll": null}, "v": 1.172645546399746, "accelerator_pedal_position": 0, "brake_pedal_position": 0.02833610584941531, "acceleration": -0.4990720998902214, "steering_wheel_angle": 0.6358744402752912, "front_wheel_angle": 0.02944941085320852, "heading_rate": 0.013493635653726401, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137697.2875204} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.016702549089694797, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.159090775698241, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.016702549089694797, "steering_wheel_angle": 0.39394621211615943, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137697.2875204} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.03996181488037, "x": 42.62479772084397, "y": 3.364545006755497, "z": null, "yaw": 4.550088469433626, "pitch": null, "roll": null}, "v": 1.172645546399746, "accelerator_pedal_position": 0, "brake_pedal_position": 0.02833610584941531, "acceleration": -0.4990720998902214, "steering_wheel_angle": 0.6358744402752912, "front_wheel_angle": 0.02944941085320852, "heading_rate": 0.013493635653726401, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137697.3075204} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.016702549089694797, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1509935410781815, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.016702549089694797, "steering_wheel_angle": 0.2723911458140386, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137697.3075204} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.03996181488037, "x": 42.62479772084397, "y": 3.364545006755497, "z": null, "yaw": 4.550088469433626, "pitch": null, "roll": null}, "v": 1.172645546399746, "accelerator_pedal_position": 0, "brake_pedal_position": 0.02833610584941531, "acceleration": -0.4990720998902214, "steering_wheel_angle": 0.6358744402752912, "front_wheel_angle": 0.02944941085320852, "heading_rate": 0.013493635653726401, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137697.3275204} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.016702549089694797, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1429081338754015, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.016702549089694797, "steering_wheel_angle": 0.1504421113635478, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137697.3275204} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.03996181488037, "x": 42.62479772084397, "y": 3.364545006755497, "z": null, "yaw": 4.550088469433626, "pitch": null, "roll": null}, "v": 1.172645546399746, "accelerator_pedal_position": 0, "brake_pedal_position": 0.02833610584941531, "acceleration": -0.4990720998902214, "steering_wheel_angle": 0.6358744402752912, "front_wheel_angle": 0.02944941085320852, "heading_rate": 0.013493635653726401, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137697.3475204} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.016702549089694797, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.134834510673899, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.016702549089694797, "steering_wheel_angle": 0.028099108764687002, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137697.3475204} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137697.3575203, "x": 46.60432450223199, "y": 8.239189889811396, "z": null, "yaw": 4.550749010309403, "pitch": null, "roll": null}, "v": 1.130802104554725, "accelerator_pedal_position": 0, "brake_pedal_position": 0.016702549089694797, "acceleration": -0.4029476319419486, "steering_wheel_angle": -0.03319124438229738, "front_wheel_angle": -0.0015249454643555507, "heading_rate": -0.0006735987801204183, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137697.3675203} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.014994249641988137, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1228827402942547, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.014994249641988137, "steering_wheel_angle": -0.15551787458450078, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137697.3675203} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.149961709976196, "x": 42.60432450223199, "y": 3.2391898898113958, "z": null, "yaw": 4.550749010309403, "pitch": null, "roll": null}, "v": 1.130802104554725, "accelerator_pedal_position": 0, "brake_pedal_position": 0.016702549089694797, "acceleration": -0.4029476319419486, "steering_wheel_angle": -0.03319124438229738, "front_wheel_angle": -0.0015249454643555507, "heading_rate": -0.0006735987801204183, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137697.3875203} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.01598963165423458, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1189956723879035, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.014994249641988137, "steering_wheel_angle": -0.21653345162996374, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137697.3875203} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.149961709976196, "x": 42.60432450223199, "y": 3.2391898898113958, "z": null, "yaw": 4.550749010309403, "pitch": null, "roll": null}, "v": 1.130802104554725, "accelerator_pedal_position": 0, "brake_pedal_position": 0.016702549089694797, "acceleration": -0.4029476319419486, "steering_wheel_angle": -0.03319124438229738, "front_wheel_angle": -0.0015249454643555507, "heading_rate": -0.0006735987801204183, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137697.4075203} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.01598963165423458, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1110707728720828, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.01598963165423458, "steering_wheel_angle": -0.3382691296096121, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137697.4075203} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.149961709976196, "x": 42.60432450223199, "y": 3.2391898898113958, "z": null, "yaw": 4.550749010309403, "pitch": null, "roll": null}, "v": 1.130802104554725, "accelerator_pedal_position": 0, "brake_pedal_position": 0.016702549089694797, "acceleration": -0.4029476319419486, "steering_wheel_angle": -0.03319124438229738, "front_wheel_angle": -0.0015249454643555507, "heading_rate": -0.0006735987801204183, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137697.4275203} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.01598963165423458, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1031573224500295, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.01598963165423458, "steering_wheel_angle": -0.45961083944089065, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137697.4275203} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.149961709976196, "x": 42.60432450223199, "y": 3.2391898898113958, "z": null, "yaw": 4.550749010309403, "pitch": null, "roll": null}, "v": 1.130802104554725, "accelerator_pedal_position": 0, "brake_pedal_position": 0.016702549089694797, "acceleration": -0.4029476319419486, "steering_wheel_angle": -0.03319124438229738, "front_wheel_angle": -0.0015249454643555507, "heading_rate": -0.0006735987801204183, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137697.4475203} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.01598963165423458, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0952552795411905, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.01598963165423458, "steering_wheel_angle": -0.580558581123799, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137697.4475203} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137697.4675202, "x": 46.5846321751648, "y": 8.118570867444555, "z": null, "yaw": 4.550078409801442, "pitch": null, "roll": null}, "v": 1.0873646027333002, "accelerator_pedal_position": 0, "brake_pedal_position": 0.01598963165423458, "acceleration": -0.39410890116331515, "steering_wheel_angle": -0.7011123546583377, "front_wheel_angle": -0.03249930178191933, "heading_rate": -0.013808998915584682, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137697.4675202} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0873646027333002, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.01598963165423458, "steering_wheel_angle": -0.7011123546583377, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137697.4675202} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.25996160507202, "x": 42.5846321751648, "y": 3.1185708674445554, "z": null, "yaw": 4.550078409801442, "pitch": null, "roll": null}, "v": 1.0873646027333002, "accelerator_pedal_position": 0, "brake_pedal_position": 0.01598963165423458, "acceleration": -0.39410890116331515, "steering_wheel_angle": -0.7011123546583377, "front_wheel_angle": -0.03249930178191933, "heading_rate": -0.013808998915584682, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137697.4875202} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0820426749205558, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.8212721600445061, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137697.4875202} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.25996160507202, "x": 42.5846321751648, "y": 3.1185708674445554, "z": null, "yaw": 4.550078409801442, "pitch": null, "roll": null}, "v": 1.0873646027333002, "accelerator_pedal_position": 0, "brake_pedal_position": 0.01598963165423458, "acceleration": -0.39410890116331515, "steering_wheel_angle": -0.7011123546583377, "front_wheel_angle": -0.03249930178191933, "heading_rate": -0.013808998915584682, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137697.5075202} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0767283725566705, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.9410379972823044, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137697.5075202} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.25996160507202, "x": 42.5846321751648, "y": 3.1185708674445554, "z": null, "yaw": 4.550078409801442, "pitch": null, "roll": null}, "v": 1.0873646027333002, "accelerator_pedal_position": 0, "brake_pedal_position": 0.01598963165423458, "acceleration": -0.39410890116331515, "steering_wheel_angle": -0.7011123546583377, "front_wheel_angle": -0.03249930178191933, "heading_rate": -0.013808998915584682, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137697.5275202} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0714216734229418, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.0604098663717332, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137697.5275202} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.25996160507202, "x": 42.5846321751648, "y": 3.1185708674445554, "z": null, "yaw": 4.550078409801442, "pitch": null, "roll": null}, "v": 1.0873646027333002, "accelerator_pedal_position": 0, "brake_pedal_position": 0.01598963165423458, "acceleration": -0.39410890116331515, "steering_wheel_angle": -0.7011123546583377, "front_wheel_angle": -0.03249930178191933, "heading_rate": -0.013808998915584682, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137697.5475202} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0661225553809432, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1793877673127917, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137697.5475202} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.25996160507202, "x": 42.5846321751648, "y": 3.1185708674445554, "z": null, "yaw": 4.550078409801442, "pitch": null, "roll": null}, "v": 1.0873646027333002, "accelerator_pedal_position": 0, "brake_pedal_position": 0.01598963165423458, "acceleration": -0.39410890116331515, "steering_wheel_angle": -0.7011123546583377, "front_wheel_angle": -0.03249930178191933, "heading_rate": -0.013808998915584682, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137697.5675201} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0581880446336804, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.3571159284461858, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137697.5675201} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137697.5775201, "x": 46.56544661683969, "y": 8.0019898159979, "z": null, "yaw": 4.5480753797029125, "pitch": null, "roll": null}, "v": 1.0581880446336804, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26410702160974053, "steering_wheel_angle": -1.3571159284461858, "front_wheel_angle": -0.06347365809948312, "heading_rate": -0.026272427736174785, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137697.5875201} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.055546974417583, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.4161616647497988, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137697.5875201} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.36996150016785, "x": 42.56544661683969, "y": 3.0019898159979004, "z": null, "yaw": 4.5480753797029125, "pitch": null, "roll": null}, "v": 1.0581880446336804, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26410702160974053, "steering_wheel_angle": -1.3571159284461858, "front_wheel_angle": -0.06347365809948312, "heading_rate": -0.026272427736174785, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137697.60752} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0476350255780882, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.5927079214380833, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137697.60752} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.36996150016785, "x": 42.56544661683969, "y": 3.0019898159979004, "z": null, "yaw": 4.5480753797029125, "pitch": null, "roll": null}, "v": 1.0581880446336804, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26410702160974053, "steering_wheel_angle": -1.3571159284461858, "front_wheel_angle": -0.06347365809948312, "heading_rate": -0.026272427736174785, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137697.62752} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0450014541506174, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.6513596895933265, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137697.62752} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.36996150016785, "x": 42.56544661683969, "y": 3.0019898159979004, "z": null, "yaw": 4.5480753797029125, "pitch": null, "roll": null}, "v": 1.0581880446336804, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26410702160974053, "steering_wheel_angle": -1.3571159284461858, "front_wheel_angle": -0.06347365809948312, "heading_rate": -0.026272427736174785, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137697.64752} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0397399122746138, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.7683677497925347, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137697.64752} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.36996150016785, "x": 42.56544661683969, "y": 3.0019898159979004, "z": null, "yaw": 4.5480753797029125, "pitch": null, "roll": null}, "v": 1.0581880446336804, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26410702160974053, "steering_wheel_angle": -1.3571159284461858, "front_wheel_angle": -0.06347365809948312, "heading_rate": -0.026272427736174785, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137697.66752} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0318615613234816, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.9431411498131541, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137697.66752} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137697.68752, "x": 46.54648474860735, "y": 7.888613401976077, "z": null, "yaw": 4.544736064811713, "pitch": null, "roll": null}, "v": 1.0292391567146462, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2620552902528791, "steering_wheel_angle": -2.0012019657458424, "front_wheel_angle": -0.0944480144170469, "heading_rate": -0.038085812581600806, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137697.68752} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0292391567146462, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.0012019657458424, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137697.68752} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.47996139526367, "x": 42.54648474860735, "y": 2.8886134019760767, "z": null, "yaw": 4.544736064811713, "pitch": null, "roll": null}, "v": 1.0292391567146462, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2620552902528791, "steering_wheel_angle": -2.0012019657458424, "front_wheel_angle": -0.0944480144170469, "heading_rate": -0.038085812581600806, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137697.70752} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0239998999344422, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.1170281214999407, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137697.70752} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.47996139526367, "x": 42.54648474860735, "y": 2.8886134019760767, "z": null, "yaw": 4.544736064811713, "pitch": null, "roll": null}, "v": 1.0292391567146462, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2620552902528791, "steering_wheel_angle": -2.0012019657458424, "front_wheel_angle": -0.0944480144170469, "heading_rate": -0.038085812581600806, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137697.72752} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0161548557079587, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.2900286648528954, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137697.72752} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.47996139526367, "x": 42.54648474860735, "y": 2.8886134019760767, "z": null, "yaw": 4.544736064811713, "pitch": null, "roll": null}, "v": 1.0292391567146462, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2620552902528791, "steering_wheel_angle": -2.0012019657458424, "front_wheel_angle": -0.0944480144170469, "heading_rate": -0.038085812581600806, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137697.74752} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0135435212110269, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.347498528563029, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137697.74752} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.47996139526367, "x": 42.54648474860735, "y": 2.8886134019760767, "z": null, "yaw": 4.544736064811713, "pitch": null, "roll": null}, "v": 1.0292391567146462, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2620552902528791, "steering_wheel_angle": -2.0012019657458424, "front_wheel_angle": -0.0944480144170469, "heading_rate": -0.038085812581600806, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137697.76752} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0083263566325154, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.4621427798720172, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137697.76752} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.47996139526367, "x": 42.54648474860735, "y": 2.8886134019760767, "z": null, "yaw": 4.544736064811713, "pitch": null, "roll": null}, "v": 1.0292391567146462, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2620552902528791, "steering_wheel_angle": -2.0012019657458424, "front_wheel_angle": -0.0944480144170469, "heading_rate": -0.038085812581600806, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137697.78752} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0031165136127398, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.576393063032636, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137697.78752} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137697.79752, "x": 46.52761145905976, "y": 7.778440318731171, "z": null, "yaw": 4.540054013171417, "pitch": null, "roll": null}, "v": 1.000514331081945, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26003600582110076, "steering_wheel_angle": -2.633370466557307, "front_wheel_angle": -0.12542237073461096, "heading_rate": -0.049276971887125876, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137697.80752} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9953154308088659, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.747029797495371, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137697.80752} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.5899612903595, "x": 42.52761145905976, "y": 2.778440318731171, "z": null, "yaw": 4.540054013171417, "pitch": null, "roll": null}, "v": 1.000514331081945, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26003600582110076, "steering_wheel_angle": -2.633370466557307, "front_wheel_angle": -0.12542237073461096, "heading_rate": -0.049276971887125876, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137697.82752} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9927187078127808, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.803711724908764, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137697.82752} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.5899612903595, "x": 42.52761145905976, "y": 2.778440318731171, "z": null, "yaw": 4.540054013171417, "pitch": null, "roll": null}, "v": 1.000514331081945, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26003600582110076, "steering_wheel_angle": -2.633370466557307, "front_wheel_angle": -0.12542237073461096, "heading_rate": -0.049276971887125876, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137697.8475199} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9875307030020656, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.9167801036242733, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137697.8475199} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.5899612903595, "x": 42.52761145905976, "y": 2.778440318731171, "z": null, "yaw": 4.540054013171417, "pitch": null, "roll": null}, "v": 1.000514331081945, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26003600582110076, "steering_wheel_angle": -2.633370466557307, "front_wheel_angle": -0.12542237073461096, "heading_rate": -0.049276971887125876, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137697.8675199} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9823499356883351, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.029454514191412, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137697.8675199} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.5899612903595, "x": 42.52761145905976, "y": 2.778440318731171, "z": null, "yaw": 4.540054013171417, "pitch": null, "roll": null}, "v": 1.000514331081945, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26003600582110076, "steering_wheel_angle": -2.633370466557307, "front_wheel_angle": -0.12542237073461096, "heading_rate": -0.049276971887125876, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137697.8875198} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9771763850425559, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.1417349566101804, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137697.8875198} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137697.9075198, "x": 46.50870344677576, "y": 7.671469328059858, "z": null, "yaw": 4.53402012597847, "pitch": null, "roll": null}, "v": 0.9720100303095756, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25804853650570303, "steering_wheel_angle": -3.25362143088058, "front_wheel_angle": -0.15639672705217475, "heading_rate": -0.05987144351013614, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137697.9075198} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9694295449445185, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.3094169299601406, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137697.9075198} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.69996118545532, "x": 42.50870344677576, "y": 2.6714693280598576, "z": null, "yaw": 4.53402012597847, "pitch": null, "roll": null}, "v": 0.9720100303095756, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25804853650570303, "steering_wheel_angle": -3.25362143088058, "front_wheel_angle": -0.15639672705217475, "heading_rate": -0.05987144351013614, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137697.9275198} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9668508508077851, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.365113937002609, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137697.9275198} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.69996118545532, "x": 42.50870344677576, "y": 2.6714693280598576, "z": null, "yaw": 4.53402012597847, "pitch": null, "roll": null}, "v": 0.9720100303095756, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25804853650570303, "steering_wheel_angle": -3.25362143088058, "front_wheel_angle": -0.15639672705217475, "heading_rate": -0.05987144351013614, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137697.9475198} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9616988259287842, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.4762124749762675, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137697.9475198} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.69996118545532, "x": 42.50870344677576, "y": 2.6714693280598576, "z": null, "yaw": 4.53402012597847, "pitch": null, "roll": null}, "v": 0.9720100303095756, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25804853650570303, "steering_wheel_angle": -3.25362143088058, "front_wheel_angle": -0.15639672705217475, "heading_rate": -0.05987144351013614, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137697.9675198} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9565539351370472, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.586917044801557, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137697.9675198} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.69996118545532, "x": 42.50870344677576, "y": 2.6714693280598576, "z": null, "yaw": 4.53402012597847, "pitch": null, "roll": null}, "v": 0.9720100303095756, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25804853650570303, "steering_wheel_angle": -3.25362143088058, "front_wheel_angle": -0.15639672705217475, "heading_rate": -0.05987144351013614, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137697.9875197} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9514161579695919, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.697227646478476, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137697.9875197} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.69996118545532, "x": 42.50870344677576, "y": 2.6714693280598576, "z": null, "yaw": 4.53402012597847, "pitch": null, "roll": null}, "v": 0.9720100303095756, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25804853650570303, "steering_wheel_angle": -3.25362143088058, "front_wheel_angle": -0.15639672705217475, "heading_rate": -0.05987144351013614, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137698.0075197} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9462854740356488, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.807144280007025, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137698.0075197} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137698.0175197, "x": 46.489648932945585, "y": 7.567699701824379, "z": null, "yaw": 4.526622586324551, "pitch": null, "roll": null}, "v": 0.9437227856787939, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2560922662460331, "steering_wheel_angle": -3.8619548587156607, "front_wheel_angle": -0.1873710833697385, "heading_rate": -0.06989264652572073, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137698.0275197} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9411618630163335, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.9166669453872043, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137698.0275197} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.80996108055115, "x": 42.489648932945585, "y": 2.5676997018243792, "z": null, "yaw": 4.526622586324551, "pitch": null, "roll": null}, "v": 0.9437227856787939, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2560922662460331, "steering_wheel_angle": -3.8619548587156607, "front_wheel_angle": -0.1873710833697385, "heading_rate": -0.06989264652572073, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137698.0475197} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9360453046643206, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.025795642619014, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137698.0475197} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.80996108055115, "x": 42.489648932945585, "y": 2.5676997018243792, "z": null, "yaw": 4.526622586324551, "pitch": null, "roll": null}, "v": 0.9437227856787939, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2560922662460331, "steering_wheel_angle": -3.8619548587156607, "front_wheel_angle": -0.1873710833697385, "heading_rate": -0.06989264652572073, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137698.0675197} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.930935778803518, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.134530371702453, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137698.0675197} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.80996108055115, "x": 42.489648932945585, "y": 2.5676997018243792, "z": null, "yaw": 4.526622586324551, "pitch": null, "roll": null}, "v": 0.9437227856787939, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2560922662460331, "steering_wheel_angle": -3.8619548587156607, "front_wheel_angle": -0.1873710833697385, "heading_rate": -0.06989264652572073, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137698.0875196} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9258332653287454, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.2428711326375215, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137698.0875196} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.80996108055115, "x": 42.489648932945585, "y": 2.5676997018243792, "z": null, "yaw": 4.526622586324551, "pitch": null, "roll": null}, "v": 0.9437227856787939, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2560922662460331, "steering_wheel_angle": -3.8619548587156607, "front_wheel_angle": -0.1873710833697385, "heading_rate": -0.06989264652572073, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137698.1075196} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9207377442054122, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.350817925424221, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137698.1075196} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137698.1275196, "x": 46.470347411726195, "y": 7.4671315945534875, "z": null, "yaw": 4.517846765578092, "pitch": null, "roll": null}, "v": 0.9156491954691982, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2541665942650938, "steering_wheel_angle": -4.45837075006255, "front_wheel_angle": -0.2183454396873023, "heading_rate": -0.07936202151943367, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137698.1275196} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9156491954691982, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.45837075006255, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137698.1275196} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.91996097564697, "x": 42.470347411726195, "y": 2.4671315945534875, "z": null, "yaw": 4.517846765578092, "pitch": null, "roll": null}, "v": 0.9156491954691982, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2541665942650938, "steering_wheel_angle": -4.45837075006255, "front_wheel_angle": -0.2183454396873023, "heading_rate": -0.07936202151943367, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137698.1475196} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9105675992257362, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.565529606552509, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137698.1475196} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.91996097564697, "x": 42.470347411726195, "y": 2.4671315945534875, "z": null, "yaw": 4.517846765578092, "pitch": null, "roll": null}, "v": 0.9156491954691982, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2541665942650938, "steering_wheel_angle": -4.45837075006255, "front_wheel_angle": -0.2183454396873023, "heading_rate": -0.07936202151943367, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137698.1675196} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9029581974368194, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.725529201009254, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137698.1675196} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.91996097564697, "x": 42.470347411726195, "y": 2.4671315945534875, "z": null, "yaw": 4.517846765578092, "pitch": null, "roll": null}, "v": 0.9156491954691982, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2541665942650938, "steering_wheel_angle": -4.45837075006255, "front_wheel_angle": -0.2183454396873023, "heading_rate": -0.07936202151943367, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137698.1875196} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9004251849874692, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.778665415087318, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137698.1875196} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.91996097564697, "x": 42.470347411726195, "y": 2.4671315945534875, "z": null, "yaw": 4.517846765578092, "pitch": null, "roll": null}, "v": 0.9156491954691982, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2541665942650938, "steering_wheel_angle": -4.45837075006255, "front_wheel_angle": -0.2183454396873023, "heading_rate": -0.07936202151943367, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137698.2075195} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8953643275508584, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.884642367132168, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137698.2075195} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.91996097564697, "x": 42.470347411726195, "y": 2.4671315945534875, "z": null, "yaw": 4.517846765578092, "pitch": null, "roll": null}, "v": 0.9156491954691982, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2541665942650938, "steering_wheel_angle": -4.45837075006255, "front_wheel_angle": -0.2183454396873023, "heading_rate": -0.07936202151943367, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137698.2275195} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8903103437227644, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.990225351028647, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137698.2275195} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137698.2375195, "x": 46.45070943894125, "y": 7.369766350686043, "z": null, "yaw": 4.507675105809126, "pitch": null, "roll": null}, "v": 0.8877859233000891, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2522709346211024, "steering_wheel_angle": -5.042869104921248, "front_wheel_angle": -0.24931979600486637, "heading_rate": -0.08829915116386687, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137698.2475195} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2194101398691606, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8852632139538781, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.0954143667767555, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137698.2475195} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.0299608707428, "x": 42.45070943894125, "y": 2.369766350686043, "z": null, "yaw": 4.507675105809126, "pitch": null, "roll": null}, "v": 0.8877859233000891, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2522709346211024, "steering_wheel_angle": -5.042869104921248, "front_wheel_angle": -0.24931979600486637, "heading_rate": -0.08829915116386687, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137698.2675195} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8801291343593397, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.252459200120726, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137698.2675195} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.0299608707428, "x": 42.45070943894125, "y": 2.369766350686043, "z": null, "yaw": 4.507675105809126, "pitch": null, "roll": null}, "v": 0.8877859233000891, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2522709346211024, "steering_wheel_angle": -5.042869104921248, "front_wheel_angle": -0.24931979600486637, "heading_rate": -0.08829915116386687, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137698.2875195} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8776116070628452, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.304610493827865, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137698.2875195} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.0299608707428, "x": 42.45070943894125, "y": 2.369766350686043, "z": null, "yaw": 4.507675105809126, "pitch": null, "roll": null}, "v": 0.8877859233000891, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2522709346211024, "steering_wheel_angle": -5.042869104921248, "front_wheel_angle": -0.24931979600486637, "heading_rate": -0.08829915116386687, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137698.3075194} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8725816538929052, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.408617605130864, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137698.3075194} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.0299608707428, "x": 42.45070943894125, "y": 2.369766350686043, "z": null, "yaw": 4.507675105809126, "pitch": null, "roll": null}, "v": 0.8877859233000891, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2522709346211024, "steering_wheel_angle": -5.042869104921248, "front_wheel_angle": -0.24931979600486637, "heading_rate": -0.08829915116386687, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137698.3275194} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8675584865347773, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.512230748285493, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137698.3275194} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137698.3475194, "x": 46.43061334851039, "y": 7.275405609072647, "z": null, "yaw": 4.496086976214561, "pitch": null, "roll": null}, "v": 0.8625420857443675, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25056689278402083, "steering_wheel_angle": -5.615449923291753, "front_wheel_angle": -0.2802941523224302, "heading_rate": -0.09699313642987858, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137698.3475194} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2210102742295586, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8625420857443675, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.615449923291753, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137698.3475194} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.13996076583862, "x": 42.43061334851039, "y": 2.2754056090726467, "z": null, "yaw": 4.496086976214561, "pitch": null, "roll": null}, "v": 0.8625420857443675, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25056689278402083, "steering_wheel_angle": -5.615449923291753, "front_wheel_angle": -0.2802941523224302, "heading_rate": -0.09699313642987858, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137698.3675194} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2175991297553559, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8601578340094729, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.7182751301496415, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137698.3675194} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.13996076583862, "x": 42.43061334851039, "y": 2.2754056090726467, "z": null, "yaw": 4.496086976214561, "pitch": null, "roll": null}, "v": 0.8625420857443675, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25056689278402083, "steering_wheel_angle": -5.615449923291753, "front_wheel_angle": -0.2802941523224302, "heading_rate": -0.09699313642987858, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137698.3875194} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2175991297553559, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8573505365111167, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.820706368859162, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137698.3875194} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.13996076583862, "x": 42.43061334851039, "y": 2.2754056090726467, "z": null, "yaw": 4.496086976214561, "pitch": null, "roll": null}, "v": 0.8625420857443675, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25056689278402083, "steering_wheel_angle": -5.615449923291753, "front_wheel_angle": -0.2802941523224302, "heading_rate": -0.09699313642987858, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137698.4075193} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2175991297553559, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8545470085675604, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.922743639420312, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137698.4075193} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.13996076583862, "x": 42.43061334851039, "y": 2.2754056090726467, "z": null, "yaw": 4.496086976214561, "pitch": null, "roll": null}, "v": 0.8625420857443675, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25056689278402083, "steering_wheel_angle": -5.615449923291753, "front_wheel_angle": -0.2802941523224302, "heading_rate": -0.09699313642987858, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137698.4275193} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2175991297553559, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8517472419743054, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.02438694183309, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137698.4275193} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.13996076583862, "x": 42.43061334851039, "y": 2.2754056090726467, "z": null, "yaw": 4.496086976214561, "pitch": null, "roll": null}, "v": 0.8625420857443675, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25056689278402083, "steering_wheel_angle": -5.615449923291753, "front_wheel_angle": -0.2802941523224302, "heading_rate": -0.09699313642987858, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137698.4475193} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2175991297553559, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.848951228550513, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.1256362760975005, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137698.4475193} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137698.4575193, "x": 46.40987599321172, "y": 7.183570072574907, "z": null, "yaw": 4.483058500991902, "pitch": null, "roll": null}, "v": 0.8475546267271017, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24956121978922027, "steering_wheel_angle": -6.176113205174067, "front_wheel_angle": -0.3112685086399939, "heading_rate": -0.10651601199405591, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137698.4675193} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22347528063984212, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8461589601389192, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.22649164221354, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137698.4675193} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.24996066093445, "x": 42.40987599321172, "y": 2.1835700725749074, "z": null, "yaw": 4.483058500991902, "pitch": null, "roll": null}, "v": 0.8475546267271017, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24956121978922027, "steering_wheel_angle": -6.176113205174067, "front_wheel_angle": -0.3112685086399939, "heading_rate": -0.10651601199405591, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137698.4875193} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22060048941154195, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8430786031879295, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.377036001109405, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137698.4875193} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.24996066093445, "x": 42.40987599321172, "y": 2.1835700725749074, "z": null, "yaw": 4.483058500991902, "pitch": null, "roll": null}, "v": 0.8475546267271017, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24956121978922027, "steering_wheel_angle": -6.176113205174067, "front_wheel_angle": -0.3112685086399939, "heading_rate": -0.10651601199405591, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137698.5075192} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22060048941154195, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8418735163214416, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.427020470000509, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137698.5075192} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.24996066093445, "x": 42.40987599321172, "y": 2.1835700725749074, "z": null, "yaw": 4.483058500991902, "pitch": null, "roll": null}, "v": 0.8475546267271017, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24956121978922027, "steering_wheel_angle": -6.176113205174067, "front_wheel_angle": -0.3112685086399939, "heading_rate": -0.10651601199405591, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137698.5275192} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22060048941154195, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8394657585441745, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.526693931671439, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137698.5275192} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.24996066093445, "x": 42.40987599321172, "y": 2.1835700725749074, "z": null, "yaw": 4.483058500991902, "pitch": null, "roll": null}, "v": 0.8475546267271017, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24956121978922027, "steering_wheel_angle": -6.176113205174067, "front_wheel_angle": -0.3112685086399939, "heading_rate": -0.10651601199405591, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137698.5475192} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22060048941154195, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8370612165222485, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.625973425193999, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137698.5475192} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137698.5675192, "x": 46.38824658260408, "y": 7.093540415877626, "z": null, "yaw": 4.4685623555207235, "pitch": null, "roll": null}, "v": 0.8346598836488046, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24869956539616658, "steering_wheel_angle": -6.724858950568188, "front_wheel_angle": -0.3422428649575577, "heading_rate": -0.11615544275254443, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137698.5675192} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23120387107001167, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8346598836488046, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.724858950568188, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137698.5675192} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.35996055603027, "x": 42.38824658260408, "y": 2.0935404158776256, "z": null, "yaw": 4.4685623555207235, "pitch": null, "roll": null}, "v": 0.8346598836488046, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24869956539616658, "steering_wheel_angle": -6.724858950568188, "front_wheel_angle": -0.3422428649575577, "heading_rate": -0.11615544275254443, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137698.5875192} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22608898929521032, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8335867341740365, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.823350507794008, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137698.5875192} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.35996055603027, "x": 42.38824658260408, "y": 2.0935404158776256, "z": null, "yaw": 4.4685623555207235, "pitch": null, "roll": null}, "v": 0.8346598836488046, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24869956539616658, "steering_wheel_angle": -6.724858950568188, "front_wheel_angle": -0.3422428649575577, "heading_rate": -0.11615544275254443, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137698.6075191} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22608898929521032, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8318758681820417, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.921448096871457, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137698.6075191} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.35996055603027, "x": 42.38824658260408, "y": 2.0935404158776256, "z": null, "yaw": 4.4685623555207235, "pitch": null, "roll": null}, "v": 0.8346598836488046, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24869956539616658, "steering_wheel_angle": -6.724858950568188, "front_wheel_angle": -0.3422428649575577, "heading_rate": -0.11615544275254443, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137698.6275191} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22608898929521032, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8301672818801805, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.019151717800537, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137698.6275191} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.35996055603027, "x": 42.38824658260408, "y": 2.0935404158776256, "z": null, "yaw": 4.4685623555207235, "pitch": null, "roll": null}, "v": 0.8346598836488046, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24869956539616658, "steering_wheel_angle": -6.724858950568188, "front_wheel_angle": -0.3422428649575577, "heading_rate": -0.11615544275254443, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137698.647519} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22608898929521032, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8284609710634991, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.116461370581248, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137698.647519} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.35996055603027, "x": 42.38824658260408, "y": 2.0935404158776256, "z": null, "yaw": 4.4685623555207235, "pitch": null, "roll": null}, "v": 0.8346598836488046, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24869956539616658, "steering_wheel_angle": -6.724858950568188, "front_wheel_angle": -0.3422428649575577, "heading_rate": -0.11615544275254443, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137698.667519} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22608898929521032, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8267569315373087, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.213377055213587, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137698.667519} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137698.677519, "x": 46.365548548356436, "y": 7.005001481976307, "z": null, "yaw": 4.452567527021365, "pitch": null, "roll": null}, "v": 0.8259057622001061, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24811649139035868, "steering_wheel_angle": -7.261687159474118, "front_wheel_angle": -0.37321722127512147, "heading_rate": -0.12632777467396458, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137698.687519} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2348868893559265, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8250551591171532, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.309898771697557, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137698.687519} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.4699604511261, "x": 42.365548548356436, "y": 2.005001481976307, "z": null, "yaw": 4.452567527021365, "pitch": null, "roll": null}, "v": 0.8259057622001061, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24811649139035868, "steering_wheel_angle": -7.261687159474118, "front_wheel_angle": -0.37321722127512147, "heading_rate": -0.12632777467396458, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137698.707519} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23065298633536152, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8244550215308276, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.406026520033156, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137698.707519} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.4699604511261, "x": 42.365548548356436, "y": 2.005001481976307, "z": null, "yaw": 4.452567527021365, "pitch": null, "roll": null}, "v": 0.8259057622001061, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24811649139035868, "steering_wheel_angle": -7.261687159474118, "front_wheel_angle": -0.37321722127512147, "heading_rate": -0.12632777467396458, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137698.727519} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23065298633536152, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8233266198096767, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.501760300220387, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137698.727519} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.4699604511261, "x": 42.365548548356436, "y": 2.005001481976307, "z": null, "yaw": 4.452567527021365, "pitch": null, "roll": null}, "v": 0.8259057622001061, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24811649139035868, "steering_wheel_angle": -7.261687159474118, "front_wheel_angle": -0.37321722127512147, "heading_rate": -0.12632777467396458, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137698.747519} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23065298633536152, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8221997177362983, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.597100112259246, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137698.747519} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.4699604511261, "x": 42.365548548356436, "y": 2.005001481976307, "z": null, "yaw": 4.452567527021365, "pitch": null, "roll": null}, "v": 0.8259057622001061, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24811649139035868, "steering_wheel_angle": -7.261687159474118, "front_wheel_angle": -0.37321722127512147, "heading_rate": -0.12632777467396458, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137698.767519} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23065298633536152, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8210743128098633, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.6920459561497365, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137698.767519} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137698.787519, "x": 46.34159990621618, "y": 6.917671084028021, "z": null, "yaw": 4.4350390350427125, "pitch": null, "roll": null}, "v": 0.8199504025348892, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24772070675291574, "steering_wheel_angle": -7.786597831891856, "front_wheel_angle": -0.40419157759268526, "heading_rate": -0.13700309731022373, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137698.787519} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2166989764316257, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8199504025348892, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.786597831891856, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137698.787519} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.579960346221924, "x": 42.34159990621618, "y": 1.9176710840280213, "z": null, "yaw": 4.4350390350427125, "pitch": null, "roll": null}, "v": 0.8199504025348892, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24772070675291574, "steering_wheel_angle": -7.786597831891856, "front_wheel_angle": -0.40419157759268526, "heading_rate": -0.13700309731022373, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137698.807519} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22331359133674578, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8160661067172309, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.927686955226842, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137698.807519} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.579960346221924, "x": 42.34159990621618, "y": 1.9176710840280213, "z": null, "yaw": 4.4350390350427125, "pitch": null, "roll": null}, "v": 0.8199504025348892, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24772070675291574, "steering_wheel_angle": -7.786597831891856, "front_wheel_angle": -0.40419157759268526, "heading_rate": -0.13700309731022373, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137698.827519} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22331359133674578, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8150485767333656, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.974519678930987, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137698.827519} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.579960346221924, "x": 42.34159990621618, "y": 1.9176710840280213, "z": null, "yaw": 4.4350390350427125, "pitch": null, "roll": null}, "v": 0.8199504025348892, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24772070675291574, "steering_wheel_angle": -7.786597831891856, "front_wheel_angle": -0.40419157759268526, "heading_rate": -0.13700309731022373, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137698.847519} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22331359133674578, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8130155403187476, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.067889650227997, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137698.847519} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.579960346221924, "x": 42.34159990621618, "y": 1.9176710840280213, "z": null, "yaw": 4.4350390350427125, "pitch": null, "roll": null}, "v": 0.8199504025348892, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24772070675291574, "steering_wheel_angle": -7.786597831891856, "front_wheel_angle": -0.40419157759268526, "heading_rate": -0.13700309731022373, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137698.867519} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22331359133674578, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8109851976172202, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.160865653376636, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137698.867519} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.579960346221924, "x": 42.34159990621618, "y": 1.9176710840280213, "z": null, "yaw": 4.4350390350427125, "pitch": null, "roll": null}, "v": 0.8199504025348892, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24772070675291574, "steering_wheel_angle": -7.786597831891856, "front_wheel_angle": -0.40419157759268526, "heading_rate": -0.13700309731022373, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137698.887519} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22331359133674578, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8089575434113225, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.253447688376907, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137698.887519} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137698.8975189, "x": 46.3163454243036, "y": 6.831750788241922, "z": null, "yaw": 4.415937606152277, "pitch": null, "roll": null}, "v": 0.8079447228674592, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24692498289546672, "steering_wheel_angle": -8.299590967821402, "front_wheel_angle": -0.4351659339102494, "heading_rate": -0.14672037241519725, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137698.9075189} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26146097580904853, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8083053031812125, "gear": 1, "accelerator_pedal_position": 0.26146097580904853, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.391582050599117, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137698.9075189} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.68996024131775, "x": 42.3163454243036, "y": 1.831750788241922, "z": null, "yaw": 4.415937606152277, "pitch": null, "roll": null}, "v": 0.8079447228674592, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24692498289546672, "steering_wheel_angle": -8.299590967821402, "front_wheel_angle": -0.4351659339102494, "heading_rate": -0.14672037241519725, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137698.9275188} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24323491894743465, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8096771257713724, "gear": 1, "accelerator_pedal_position": 0.26146097580904853, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.437429853932336, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137698.9275188} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.68996024131775, "x": 42.3163454243036, "y": 1.831750788241922, "z": null, "yaw": 4.415937606152277, "pitch": null, "roll": null}, "v": 0.8079447228674592, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24692498289546672, "steering_wheel_angle": -8.299590967821402, "front_wheel_angle": -0.4351659339102494, "heading_rate": -0.14672037241519725, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137698.9475188} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24323491894743465, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8101405446715837, "gear": 1, "accelerator_pedal_position": 0.24323491894743465, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.528829984487498, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137698.9475188} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.68996024131775, "x": 42.3163454243036, "y": 1.831750788241922, "z": null, "yaw": 4.415937606152277, "pitch": null, "roll": null}, "v": 0.8079447228674592, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24692498289546672, "steering_wheel_angle": -8.299590967821402, "front_wheel_angle": -0.4351659339102494, "heading_rate": -0.14672037241519725, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137698.9675188} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24323491894743465, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.811065543093896, "gear": 1, "accelerator_pedal_position": 0.24323491894743465, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.710448341152707, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137698.9675188} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.68996024131775, "x": 42.3163454243036, "y": 1.831750788241922, "z": null, "yaw": 4.415937606152277, "pitch": null, "roll": null}, "v": 0.8079447228674592, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24692498289546672, "steering_wheel_angle": -8.299590967821402, "front_wheel_angle": -0.4351659339102494, "heading_rate": -0.14672037241519725, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137698.9875188} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24323491894743465, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.811065543093896, "gear": 1, "accelerator_pedal_position": 0.24323491894743465, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.710448341152707, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137698.9875188} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137699.0075188, "x": 46.289535482027006, "y": 6.746812240452367, "z": null, "yaw": 4.395219296019919, "pitch": null, "roll": null}, "v": 0.8115271240677545, "accelerator_pedal_position": 0.24323491894743465, "brake_pedal_position": 0.0, "acceleration": 0.023056124487101953, "steering_wheel_angle": -8.800666567262756, "front_wheel_angle": -0.466140290227813, "heading_rate": -0.15949035966619482, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137699.0075188} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2537197689742582, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.813298266019595, "gear": 1, "accelerator_pedal_position": 0.2537197689742582, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.890490825224438, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137699.0075188} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.799960136413574, "x": 42.289535482027006, "y": 1.7468122404523667, "z": null, "yaw": 4.395219296019919, "pitch": null, "roll": null}, "v": 0.8115271240677545, "accelerator_pedal_position": 0.24323491894743465, "brake_pedal_position": 0.0, "acceleration": 0.023056124487101953, "steering_wheel_angle": -8.800666567262756, "front_wheel_angle": -0.466140290227813, "heading_rate": -0.15949035966619482, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137699.0275187} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2487450482698346, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8141829570405252, "gear": 1, "accelerator_pedal_position": 0.2537197689742582, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.935255216149638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137699.0275187} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.799960136413574, "x": 42.289535482027006, "y": 1.7468122404523667, "z": null, "yaw": 4.395219296019919, "pitch": null, "roll": null}, "v": 0.8115271240677545, "accelerator_pedal_position": 0.24323491894743465, "brake_pedal_position": 0.0, "acceleration": 0.023056124487101953, "steering_wheel_angle": -8.800666567262756, "front_wheel_angle": -0.466140290227813, "heading_rate": -0.15949035966619482, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137699.0475187} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2487450482698346, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8147561416901161, "gear": 1, "accelerator_pedal_position": 0.2487450482698346, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.979921115037747, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137699.0475187} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.799960136413574, "x": 42.289535482027006, "y": 1.7468122404523667, "z": null, "yaw": 4.395219296019919, "pitch": null, "roll": null}, "v": 0.8115271240677545, "accelerator_pedal_position": 0.24323491894743465, "brake_pedal_position": 0.0, "acceleration": 0.023056124487101953, "steering_wheel_angle": -8.800666567262756, "front_wheel_angle": -0.466140290227813, "heading_rate": -0.15949035966619482, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137699.0775187} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2487450482698346, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8170450825446881, "gear": 1, "accelerator_pedal_position": 0.2487450482698346, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.15759979021926, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137699.0775187} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.799960136413574, "x": 42.289535482027006, "y": 1.7468122404523667, "z": null, "yaw": 4.395219296019919, "pitch": null, "roll": null}, "v": 0.8115271240677545, "accelerator_pedal_position": 0.24323491894743465, "brake_pedal_position": 0.0, "acceleration": 0.023056124487101953, "steering_wheel_angle": -8.800666567262756, "front_wheel_angle": -0.466140290227813, "heading_rate": -0.15949035966619482, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137699.0875187} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2487450482698346, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8176163692535894, "gear": 1, "accelerator_pedal_position": 0.2487450482698346, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.201773228921905, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137699.0875187} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.799960136413574, "x": 42.289535482027006, "y": 1.7468122404523667, "z": null, "yaw": 4.395219296019919, "pitch": null, "roll": null}, "v": 0.8115271240677545, "accelerator_pedal_position": 0.24323491894743465, "brake_pedal_position": 0.0, "acceleration": 0.023056124487101953, "steering_wheel_angle": -8.800666567262756, "front_wheel_angle": -0.466140290227813, "heading_rate": -0.15949035966619482, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137699.1075187} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2487450482698346, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8181872769331001, "gear": 1, "accelerator_pedal_position": 0.2487450482698346, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.245848175587458, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137699.1075187} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137699.1175187, "x": 46.26071590125308, "y": 6.661904492028798, "z": null, "yaw": 4.37283505064759, "pitch": null, "roll": null}, "v": 0.8187578057694848, "accelerator_pedal_position": 0.2487450482698346, "brake_pedal_position": 0.0, "acceleration": 0.05701501795290728, "steering_wheel_angle": -9.289824630215918, "front_wheel_angle": -0.4971146465453769, "heading_rate": -0.17352608975800926, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137699.1275187} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2612498849360164, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8193279559490139, "gear": 1, "accelerator_pedal_position": 0.2487450482698346, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.333702592807288, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137699.1275187} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.9099600315094, "x": 42.26071590125308, "y": 1.661904492028798, "z": null, "yaw": 4.37283505064759, "pitch": null, "roll": null}, "v": 0.8187578057694848, "accelerator_pedal_position": 0.2487450482698346, "brake_pedal_position": 0.0, "acceleration": 0.05701501795290728, "steering_wheel_angle": -9.289824630215918, "front_wheel_angle": -0.4971146465453769, "heading_rate": -0.17352608975800926, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137699.1475186} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.255331724694727, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8220297066700728, "gear": 1, "accelerator_pedal_position": 0.2612498849360164, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.42116304187875, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137699.1475186} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.9099600315094, "x": 42.26071590125308, "y": 1.661904492028798, "z": null, "yaw": 4.37283505064759, "pitch": null, "roll": null}, "v": 0.8187578057694848, "accelerator_pedal_position": 0.2487450482698346, "brake_pedal_position": 0.0, "acceleration": 0.05701501795290728, "steering_wheel_angle": -9.289824630215918, "front_wheel_angle": -0.4971146465453769, "heading_rate": -0.17352608975800926, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137699.1675186} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.255331724694727, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8239883450048137, "gear": 1, "accelerator_pedal_position": 0.255331724694727, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.50822952280184, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137699.1675186} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.9099600315094, "x": 42.26071590125308, "y": 1.661904492028798, "z": null, "yaw": 4.37283505064759, "pitch": null, "roll": null}, "v": 0.8187578057694848, "accelerator_pedal_position": 0.2487450482698346, "brake_pedal_position": 0.0, "acceleration": 0.05701501795290728, "steering_wheel_angle": -9.289824630215918, "front_wheel_angle": -0.4971146465453769, "heading_rate": -0.17352608975800926, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137699.1875186} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.255331724694727, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8259443803922863, "gear": 1, "accelerator_pedal_position": 0.255331724694727, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.59490203557656, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137699.1875186} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.9099600315094, "x": 42.26071590125308, "y": 1.661904492028798, "z": null, "yaw": 4.37283505064759, "pitch": null, "roll": null}, "v": 0.8187578057694848, "accelerator_pedal_position": 0.2487450482698346, "brake_pedal_position": 0.0, "acceleration": 0.05701501795290728, "steering_wheel_angle": -9.289824630215918, "front_wheel_angle": -0.4971146465453769, "heading_rate": -0.17352608975800926, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137699.2075186} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.255331724694727, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8278978147617764, "gear": 1, "accelerator_pedal_position": 0.255331724694727, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.681180580202911, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137699.2075186} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137699.2275186, "x": 46.229608399090054, "y": 6.576789074842652, "z": null, "yaw": 4.348730196732282, "pitch": null, "roll": null}, "v": 0.829848650046106, "accelerator_pedal_position": 0.255331724694727, "brake_pedal_position": 0.0, "acceleration": 0.09744435901990478, "steering_wheel_angle": -9.767065156680891, "front_wheel_angle": -0.5280890028629409, "heading_rate": -0.18909944030413692, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137699.2275186} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2551688528615251, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.829848650046106, "gear": 1, "accelerator_pedal_position": 0.255331724694727, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.767065156680891, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137699.2275186} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.019959926605225, "x": 42.229608399090054, "y": 1.5767890748426518, "z": null, "yaw": 4.348730196732282, "pitch": null, "roll": null}, "v": 0.829848650046106, "accelerator_pedal_position": 0.255331724694727, "brake_pedal_position": 0.0, "acceleration": 0.09744435901990478, "steering_wheel_angle": -9.767065156680891, "front_wheel_angle": -0.5280890028629409, "heading_rate": -0.18909944030413692, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137699.2475185} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2553025927794648, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8317765359836705, "gear": 1, "accelerator_pedal_position": 0.2551688528615251, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.852555765010502, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137699.2475185} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.019959926605225, "x": 42.229608399090054, "y": 1.5767890748426518, "z": null, "yaw": 4.348730196732282, "pitch": null, "roll": null}, "v": 0.829848650046106, "accelerator_pedal_position": 0.255331724694727, "brake_pedal_position": 0.0, "acceleration": 0.09744435901990478, "steering_wheel_angle": -9.767065156680891, "front_wheel_angle": -0.5280890028629409, "heading_rate": -0.18909944030413692, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137699.2675185} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2553025927794648, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8346886098541548, "gear": 1, "accelerator_pedal_position": 0.2553025927794648, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.980052987226722, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137699.2675185} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.019959926605225, "x": 42.229608399090054, "y": 1.5767890748426518, "z": null, "yaw": 4.348730196732282, "pitch": null, "roll": null}, "v": 0.829848650046106, "accelerator_pedal_position": 0.255331724694727, "brake_pedal_position": 0.0, "acceleration": 0.09744435901990478, "steering_wheel_angle": -9.767065156680891, "front_wheel_angle": -0.5280890028629409, "heading_rate": -0.18909944030413692, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137699.2875185} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2553025927794648, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8356580070904023, "gear": 1, "accelerator_pedal_position": 0.2553025927794648, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.022355077224612, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137699.2875185} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.019959926605225, "x": 42.229608399090054, "y": 1.5767890748426518, "z": null, "yaw": 4.348730196732282, "pitch": null, "roll": null}, "v": 0.829848650046106, "accelerator_pedal_position": 0.255331724694727, "brake_pedal_position": 0.0, "acceleration": 0.09744435901990478, "steering_wheel_angle": -9.767065156680891, "front_wheel_angle": -0.5280890028629409, "heading_rate": -0.18909944030413692, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137699.3075185} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2553025927794648, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8375948619417855, "gear": 1, "accelerator_pedal_position": 0.2553025927794648, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.106663781109113, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137699.3075185} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.019959926605225, "x": 42.229608399090054, "y": 1.5767890748426518, "z": null, "yaw": 4.348730196732282, "pitch": null, "roll": null}, "v": 0.829848650046106, "accelerator_pedal_position": 0.255331724694727, "brake_pedal_position": 0.0, "acceleration": 0.09744435901990478, "steering_wheel_angle": -9.767065156680891, "front_wheel_angle": -0.5280890028629409, "heading_rate": -0.18909944030413692, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137699.3275185} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2553025927794648, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8395291322564906, "gear": 1, "accelerator_pedal_position": 0.2553025927794648, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.190578516845243, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137699.3275185} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137699.3375185, "x": 46.19595392608917, "y": 6.491366450701468, "z": null, "yaw": 4.3228438489678895, "pitch": null, "roll": null}, "v": 0.8404952988226881, "accelerator_pedal_position": 0.2553025927794648, "brake_pedal_position": 0.0, "acceleration": 0.09655211645709025, "steering_wheel_angle": -10.232388146657668, "front_wheel_angle": -0.5590633591805046, "heading_rate": -0.2054109765558039, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137699.3475184} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2548753746614392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8414608199872591, "gear": 1, "accelerator_pedal_position": 0.2553025927794648, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.274099284433003, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137699.3475184} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.12995982170105, "x": 42.19595392608917, "y": 1.4913664507014683, "z": null, "yaw": 4.3228438489678895, "pitch": null, "roll": null}, "v": 0.8404952988226881, "accelerator_pedal_position": 0.2553025927794648, "brake_pedal_position": 0.0, "acceleration": 0.09655211645709025, "steering_wheel_angle": -10.232388146657668, "front_wheel_angle": -0.5590633591805046, "heading_rate": -0.2054109765558039, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137699.3675184} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25513292003429144, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8433365426747023, "gear": 1, "accelerator_pedal_position": 0.2548753746614392, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.357226083872394, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137699.3675184} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.12995982170105, "x": 42.19595392608917, "y": 1.4913664507014683, "z": null, "yaw": 4.3228438489678895, "pitch": null, "roll": null}, "v": 0.8404952988226881, "accelerator_pedal_position": 0.2553025927794648, "brake_pedal_position": 0.0, "acceleration": 0.09655211645709025, "steering_wheel_angle": -10.232388146657668, "front_wheel_angle": -0.5590633591805046, "heading_rate": -0.2054109765558039, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137699.3875184} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25513292003429144, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8452419404889485, "gear": 1, "accelerator_pedal_position": 0.25513292003429144, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137699.3875184} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.12995982170105, "x": 42.19595392608917, "y": 1.4913664507014683, "z": null, "yaw": 4.3228438489678895, "pitch": null, "roll": null}, "v": 0.8404952988226881, "accelerator_pedal_position": 0.2553025927794648, "brake_pedal_position": 0.0, "acceleration": 0.09655211645709025, "steering_wheel_angle": -10.232388146657668, "front_wheel_angle": -0.5590633591805046, "heading_rate": -0.2054109765558039, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137699.4075184} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25513292003429144, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8480952595900392, "gear": 1, "accelerator_pedal_position": 0.25513292003429144, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137699.4075184} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.12995982170105, "x": 42.19595392608917, "y": 1.4913664507014683, "z": null, "yaw": 4.3228438489678895, "pitch": null, "roll": null}, "v": 0.8404952988226881, "accelerator_pedal_position": 0.2553025927794648, "brake_pedal_position": 0.0, "acceleration": 0.09655211645709025, "steering_wheel_angle": -10.232388146657668, "front_wheel_angle": -0.5590633591805046, "heading_rate": -0.2054109765558039, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137699.4275184} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25513292003429144, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8490450929054535, "gear": 1, "accelerator_pedal_position": 0.25513292003429144, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137699.4275184} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137699.4475183, "x": 46.159577265579216, "y": 6.4058041152584835, "z": null, "yaw": 4.295343517188419, "pitch": null, "roll": null}, "v": 0.8509428514319355, "accelerator_pedal_position": 0.25513292003429144, "brake_pedal_position": 0.0, "acceleration": 0.0947925702786935, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.21453440668959067, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137699.4475183} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23924671575265335, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8509428514319355, "gear": 1, "accelerator_pedal_position": 0.25513292003429144, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137699.4475183} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.239959716796875, "x": 42.159577265579216, "y": 1.4058041152584835, "z": null, "yaw": 4.295343517188419, "pitch": null, "roll": null}, "v": 0.8509428514319355, "accelerator_pedal_position": 0.25513292003429144, "brake_pedal_position": 0.0, "acceleration": 0.0947925702786935, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.21453440668959067, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137699.4675183} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2468648428558636, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8508529574351644, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137699.4675183} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.239959716796875, "x": 42.159577265579216, "y": 1.4058041152584835, "z": null, "yaw": 4.295343517188419, "pitch": null, "roll": null}, "v": 0.8509428514319355, "accelerator_pedal_position": 0.25513292003429144, "brake_pedal_position": 0.0, "acceleration": 0.0947925702786935, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.21453440668959067, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137699.4875183} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2468648428558636, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8517151306666633, "gear": 1, "accelerator_pedal_position": 0.2468648428558636, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137699.4875183} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.239959716796875, "x": 42.159577265579216, "y": 1.4058041152584835, "z": null, "yaw": 4.295343517188419, "pitch": null, "roll": null}, "v": 0.8509428514319355, "accelerator_pedal_position": 0.25513292003429144, "brake_pedal_position": 0.0, "acceleration": 0.0947925702786935, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.21453440668959067, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137699.5075183} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2468648428558636, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8525761484562714, "gear": 1, "accelerator_pedal_position": 0.2468648428558636, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137699.5075183} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.239959716796875, "x": 42.159577265579216, "y": 1.4058041152584835, "z": null, "yaw": 4.295343517188419, "pitch": null, "roll": null}, "v": 0.8509428514319355, "accelerator_pedal_position": 0.25513292003429144, "brake_pedal_position": 0.0, "acceleration": 0.0947925702786935, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.21453440668959067, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137699.5275183} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2468648428558636, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8534360120560134, "gear": 1, "accelerator_pedal_position": 0.2468648428558636, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137699.5275183} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.239959716796875, "x": 42.159577265579216, "y": 1.4058041152584835, "z": null, "yaw": 4.295343517188419, "pitch": null, "roll": null}, "v": 0.8509428514319355, "accelerator_pedal_position": 0.25513292003429144, "brake_pedal_position": 0.0, "acceleration": 0.0947925702786935, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.21453440668959067, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137699.5475183} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2468648428558636, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8542947227174278, "gear": 1, "accelerator_pedal_position": 0.2468648428558636, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137699.5475183} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137699.5575182, "x": 46.12052559382945, "y": 6.320577925833397, "z": null, "yaw": 4.267611002958886, "pitch": null, "roll": null}, "v": 0.8547236460872343, "accelerator_pedal_position": 0.2468648428558636, "brake_pedal_position": 0.0, "acceleration": 0.042863560432979175, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.21548759706756349, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137699.5675182} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2522207875888088, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8551522816915641, "gear": 1, "accelerator_pedal_position": 0.2468648428558636, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137699.5675182} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.3499596118927, "x": 42.12052559382945, "y": 1.3205779258333967, "z": null, "yaw": 4.267611002958886, "pitch": null, "roll": null}, "v": 0.8547236460872343, "accelerator_pedal_position": 0.2468648428558636, "brake_pedal_position": 0.0, "acceleration": 0.042863560432979175, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.21548759706756349, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137699.5875182} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24968965283103509, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8566779586555878, "gear": 1, "accelerator_pedal_position": 0.2522207875888088, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137699.5875182} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.3499596118927, "x": 42.12052559382945, "y": 1.3205779258333967, "z": null, "yaw": 4.267611002958886, "pitch": null, "roll": null}, "v": 0.8547236460872343, "accelerator_pedal_position": 0.2468648428558636, "brake_pedal_position": 0.0, "acceleration": 0.042863560432979175, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.21548759706756349, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137699.6075182} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24968965283103509, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8578853024368571, "gear": 1, "accelerator_pedal_position": 0.24968965283103509, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137699.6075182} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.3499596118927, "x": 42.12052559382945, "y": 1.3205779258333967, "z": null, "yaw": 4.267611002958886, "pitch": null, "roll": null}, "v": 0.8547236460872343, "accelerator_pedal_position": 0.2468648428558636, "brake_pedal_position": 0.0, "acceleration": 0.042863560432979175, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.21548759706756349, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137699.6275182} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24968965283103509, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8590910252596012, "gear": 1, "accelerator_pedal_position": 0.24968965283103509, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137699.6275182} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.3499596118927, "x": 42.12052559382945, "y": 1.3205779258333967, "z": null, "yaw": 4.267611002958886, "pitch": null, "roll": null}, "v": 0.8547236460872343, "accelerator_pedal_position": 0.2468648428558636, "brake_pedal_position": 0.0, "acceleration": 0.042863560432979175, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.21548759706756349, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137699.6475182} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24968965283103509, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8602951287187787, "gear": 1, "accelerator_pedal_position": 0.24968965283103509, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137699.6475182} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137699.6675181, "x": 46.078855331551054, "y": 6.235919653288823, "z": null, "yaw": 4.239878488729353, "pitch": null, "roll": null}, "v": 0.8614976144095478, "accelerator_pedal_position": 0.24968965283103509, "brake_pedal_position": 0.0, "acceleration": 0.060063668077158405, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.21719540773019042, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137699.6675181} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2416751573757323, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8614976144095478, "gear": 1, "accelerator_pedal_position": 0.24968965283103509, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137699.6675181} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.459959506988525, "x": 42.078855331551054, "y": 1.235919653288823, "z": null, "yaw": 4.239878488729353, "pitch": null, "roll": null}, "v": 0.8614976144095478, "accelerator_pedal_position": 0.24968965283103509, "brake_pedal_position": 0.0, "acceleration": 0.060063668077158405, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.21719540773019042, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137699.6875181} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24552624892209488, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8616970087892715, "gear": 1, "accelerator_pedal_position": 0.2416751573757323, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137699.6875181} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.459959506988525, "x": 42.078855331551054, "y": 1.235919653288823, "z": null, "yaw": 4.239878488729353, "pitch": null, "roll": null}, "v": 0.8614976144095478, "accelerator_pedal_position": 0.24968965283103509, "brake_pedal_position": 0.0, "acceleration": 0.060063668077158405, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.21719540773019042, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137699.707518} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24552624892209488, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8623773597468789, "gear": 1, "accelerator_pedal_position": 0.24552624892209488, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137699.707518} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.459959506988525, "x": 42.078855331551054, "y": 1.235919653288823, "z": null, "yaw": 4.239878488729353, "pitch": null, "roll": null}, "v": 0.8614976144095478, "accelerator_pedal_position": 0.24968965283103509, "brake_pedal_position": 0.0, "acceleration": 0.060063668077158405, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.21719540773019042, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137699.727518} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24552624892209488, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8630567960197664, "gear": 1, "accelerator_pedal_position": 0.24552624892209488, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137699.727518} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.459959506988525, "x": 42.078855331551054, "y": 1.235919653288823, "z": null, "yaw": 4.239878488729353, "pitch": null, "roll": null}, "v": 0.8614976144095478, "accelerator_pedal_position": 0.24968965283103509, "brake_pedal_position": 0.0, "acceleration": 0.060063668077158405, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.21719540773019042, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137699.747518} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24552624892209488, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8637353186530727, "gear": 1, "accelerator_pedal_position": 0.24552624892209488, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137699.747518} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.459959506988525, "x": 42.078855331551054, "y": 1.235919653288823, "z": null, "yaw": 4.239878488729353, "pitch": null, "roll": null}, "v": 0.8614976144095478, "accelerator_pedal_position": 0.24968965283103509, "brake_pedal_position": 0.0, "acceleration": 0.060063668077158405, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.21719540773019042, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137699.767518} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24552624892209488, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8644129286912762, "gear": 1, "accelerator_pedal_position": 0.24552624892209488, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137699.767518} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137699.777518, "x": 46.034600258508604, "y": 6.151966908127587, "z": null, "yaw": 4.21214597449982, "pitch": null, "roll": null}, "v": 0.8647513918134326, "accelerator_pedal_position": 0.24552624892209488, "brake_pedal_position": 0.0, "acceleration": 0.03382353647598857, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.2180157298043083, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137699.787518} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24583879604907435, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8650896271781925, "gear": 1, "accelerator_pedal_position": 0.24552624892209488, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137699.787518} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.56995940208435, "x": 42.034600258508604, "y": 1.1519669081275872, "z": null, "yaw": 4.21214597449982, "pitch": null, "roll": null}, "v": 0.8647513918134326, "accelerator_pedal_position": 0.24552624892209488, "brake_pedal_position": 0.0, "acceleration": 0.03382353647598857, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.2180157298043083, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137699.807518} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24570663884985008, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8658044703996246, "gear": 1, "accelerator_pedal_position": 0.24583879604907435, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137699.807518} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.56995940208435, "x": 42.034600258508604, "y": 1.1519669081275872, "z": null, "yaw": 4.21214597449982, "pitch": null, "roll": null}, "v": 0.8647513918134326, "accelerator_pedal_position": 0.24552624892209488, "brake_pedal_position": 0.0, "acceleration": 0.03382353647598857, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.2180157298043083, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137699.827518} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24570663884985008, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8665018374979346, "gear": 1, "accelerator_pedal_position": 0.24570663884985008, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137699.827518} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.56995940208435, "x": 42.034600258508604, "y": 1.1519669081275872, "z": null, "yaw": 4.21214597449982, "pitch": null, "roll": null}, "v": 0.8647513918134326, "accelerator_pedal_position": 0.24552624892209488, "brake_pedal_position": 0.0, "acceleration": 0.03382353647598857, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.2180157298043083, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137699.847518} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24570663884985008, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8671982658859531, "gear": 1, "accelerator_pedal_position": 0.24570663884985008, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137699.847518} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.56995940208435, "x": 42.034600258508604, "y": 1.1519669081275872, "z": null, "yaw": 4.21214597449982, "pitch": null, "roll": null}, "v": 0.8647513918134326, "accelerator_pedal_position": 0.24552624892209488, "brake_pedal_position": 0.0, "acceleration": 0.03382353647598857, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.2180157298043083, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137699.867518} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24570663884985008, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.867893756633317, "gear": 1, "accelerator_pedal_position": 0.24570663884985008, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137699.867518} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137699.887518, "x": 45.98783361626981, "y": 6.0689174675767985, "z": null, "yaw": 4.184413460270287, "pitch": null, "roll": null}, "v": 0.8685883108090071, "accelerator_pedal_position": 0.24570663884985008, "brake_pedal_position": 0.0, "acceleration": 0.03469262073437218, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.2189830699010568, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137699.887518} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24048155882846772, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8685883108090071, "gear": 1, "accelerator_pedal_position": 0.24570663884985008, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137699.887518} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.679959297180176, "x": 41.98783361626981, "y": 1.0689174675767985, "z": null, "yaw": 4.184413460270287, "pitch": null, "roll": null}, "v": 0.8685883108090071, "accelerator_pedal_position": 0.24570663884985008, "brake_pedal_position": 0.0, "acceleration": 0.03469262073437218, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.2189830699010568, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137699.907518} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24298937744684992, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8688264020369437, "gear": 1, "accelerator_pedal_position": 0.24298937744684992, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137699.907518} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.679959297180176, "x": 41.98783361626981, "y": 1.0689174675767985, "z": null, "yaw": 4.184413460270287, "pitch": null, "roll": null}, "v": 0.8685883108090071, "accelerator_pedal_position": 0.24570663884985008, "brake_pedal_position": 0.0, "acceleration": 0.03469262073437218, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.2189830699010568, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137699.927518} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24298937744684992, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8688264020369437, "gear": 1, "accelerator_pedal_position": 0.24298937744684992, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137699.927518} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.679959297180176, "x": 41.98783361626981, "y": 1.0689174675767985, "z": null, "yaw": 4.184413460270287, "pitch": null, "roll": null}, "v": 0.8685883108090071, "accelerator_pedal_position": 0.24570663884985008, "brake_pedal_position": 0.0, "acceleration": 0.03469262073437218, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.2189830699010568, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137699.9575179} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24298937744684992, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8693568553328525, "gear": 1, "accelerator_pedal_position": 0.24298937744684992, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137699.9575179} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.679959297180176, "x": 41.98783361626981, "y": 1.0689174675767985, "z": null, "yaw": 4.184413460270287, "pitch": null, "roll": null}, "v": 0.8685883108090071, "accelerator_pedal_position": 0.24570663884985008, "brake_pedal_position": 0.0, "acceleration": 0.03469262073437218, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.2189830699010568, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137699.9775178} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24298937744684992, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.869709895394986, "gear": 1, "accelerator_pedal_position": 0.24298937744684992, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137699.9775178} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137699.9975178, "x": 45.93863594361971, "y": 5.986952146392572, "z": null, "yaw": 4.156680946040754, "pitch": null, "roll": null}, "v": 0.8700624597728926, "accelerator_pedal_position": 0.24298937744684992, "brake_pedal_position": 0.0, "acceleration": 0.017610399215106765, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.21935472314757865, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137699.9975178} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23807452718621167, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8700624597728926, "gear": 1, "accelerator_pedal_position": 0.24298937744684992, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137699.9975178} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.789959192276, "x": 41.93863594361971, "y": 0.9869521463925723, "z": null, "yaw": 4.156680946040754, "pitch": null, "roll": null}, "v": 0.8700624597728926, "accelerator_pedal_position": 0.24298937744684992, "brake_pedal_position": 0.0, "acceleration": 0.017610399215106765, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.21935472314757865, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137700.0175178} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2404225018356612, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8698003998185109, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137700.0175178} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.789959192276, "x": 41.93863594361971, "y": 0.9869521463925723, "z": null, "yaw": 4.156680946040754, "pitch": null, "roll": null}, "v": 0.8700624597728926, "accelerator_pedal_position": 0.24298937744684992, "brake_pedal_position": 0.0, "acceleration": 0.017610399215106765, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.21935472314757865, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137700.0275178} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2404225018356612, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8698320909181521, "gear": 1, "accelerator_pedal_position": 0.2404225018356612, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137700.0275178} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.789959192276, "x": 41.93863594361971, "y": 0.9869521463925723, "z": null, "yaw": 4.156680946040754, "pitch": null, "roll": null}, "v": 0.8700624597728926, "accelerator_pedal_position": 0.24298937744684992, "brake_pedal_position": 0.0, "acceleration": 0.017610399215106765, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.21935472314757865, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137700.0575178} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2404225018356612, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8698637393148149, "gear": 1, "accelerator_pedal_position": 0.2404225018356612, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137700.0575178} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.789959192276, "x": 41.93863594361971, "y": 0.9869521463925723, "z": null, "yaw": 4.156680946040754, "pitch": null, "roll": null}, "v": 0.8700624597728926, "accelerator_pedal_position": 0.24298937744684992, "brake_pedal_position": 0.0, "acceleration": 0.017610399215106765, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.21935472314757865, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137700.0775177} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2404225018356612, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.86989534506564, "gear": 1, "accelerator_pedal_position": 0.2404225018356612, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137700.0775177} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.789959192276, "x": 41.93863594361971, "y": 0.9869521463925723, "z": null, "yaw": 4.156680946040754, "pitch": null, "roll": null}, "v": 0.8700624597728926, "accelerator_pedal_position": 0.24298937744684992, "brake_pedal_position": 0.0, "acceleration": 0.017610399215106765, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.21935472314757865, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137700.0875177} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2404225018356612, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8699269082276928, "gear": 1, "accelerator_pedal_position": 0.2404225018356612, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137700.0875177} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137700.1075177, "x": 45.88713737183162, "y": 5.906308202765701, "z": null, "yaw": 4.128948431811221, "pitch": null, "roll": null}, "v": 0.869942673855742, "accelerator_pedal_position": 0.2404225018356612, "brake_pedal_position": 0.0, "acceleration": 0.0015755002221424785, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.21932452346892523, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137700.1175177} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24887859675492174, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8699584288579634, "gear": 1, "accelerator_pedal_position": 0.2404225018356612, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137700.1175177} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.899959087371826, "x": 41.88713737183162, "y": 0.9063082027657012, "z": null, "yaw": 4.128948431811221, "pitch": null, "roll": null}, "v": 0.869942673855742, "accelerator_pedal_position": 0.2404225018356612, "brake_pedal_position": 0.0, "acceleration": 0.0015755002221424785, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.21932452346892523, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137700.1275177} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24485126774710686, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8705026791739229, "gear": 1, "accelerator_pedal_position": 0.24887859675492174, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137700.1275177} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.899959087371826, "x": 41.88713737183162, "y": 0.9063082027657012, "z": null, "yaw": 4.128948431811221, "pitch": null, "roll": null}, "v": 0.869942673855742, "accelerator_pedal_position": 0.2404225018356612, "brake_pedal_position": 0.0, "acceleration": 0.0015755002221424785, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.21932452346892523, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137700.1575177} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24485126774710686, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8716299833742783, "gear": 1, "accelerator_pedal_position": 0.24485126774710686, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137700.1575177} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.899959087371826, "x": 41.88713737183162, "y": 0.9063082027657012, "z": null, "yaw": 4.128948431811221, "pitch": null, "roll": null}, "v": 0.869942673855742, "accelerator_pedal_position": 0.2404225018356612, "brake_pedal_position": 0.0, "acceleration": 0.0015755002221424785, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.21932452346892523, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137700.1775177} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24485126774710686, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8722126175762638, "gear": 1, "accelerator_pedal_position": 0.24485126774710686, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137700.1775177} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.899959087371826, "x": 41.88713737183162, "y": 0.9063082027657012, "z": null, "yaw": 4.128948431811221, "pitch": null, "roll": null}, "v": 0.869942673855742, "accelerator_pedal_position": 0.2404225018356612, "brake_pedal_position": 0.0, "acceleration": 0.0015755002221424785, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.21932452346892523, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137700.1975176} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24485126774710686, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8727944661706456, "gear": 1, "accelerator_pedal_position": 0.24485126774710686, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137700.1975176} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137700.2175176, "x": 45.83331968086326, "y": 5.826973430856412, "z": null, "yaw": 4.101215917581688, "pitch": null, "roll": null}, "v": 0.8733755300813414, "accelerator_pedal_position": 0.24485126774710686, "brake_pedal_position": 0.0, "acceleration": 0.029023798749902074, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.2201899937791468, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137700.2175176} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23679741296610735, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8733755300813414, "gear": 1, "accelerator_pedal_position": 0.24485126774710686, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137700.2175176} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.00995898246765, "x": 41.83331968086326, "y": 0.8269734308564116, "z": null, "yaw": 4.101215917581688, "pitch": null, "roll": null}, "v": 0.8733755300813414, "accelerator_pedal_position": 0.24485126774710686, "brake_pedal_position": 0.0, "acceleration": 0.029023798749902074, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.2201899937791468, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137700.2375176} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24065022104694553, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8729494179962851, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137700.2375176} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.00995898246765, "x": 41.83331968086326, "y": 0.8269734308564116, "z": null, "yaw": 4.101215917581688, "pitch": null, "roll": null}, "v": 0.8733755300813414, "accelerator_pedal_position": 0.24485126774710686, "brake_pedal_position": 0.0, "acceleration": 0.029023798749902074, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.2201899937791468, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137700.2575176} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24065022104694553, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8730053192102442, "gear": 1, "accelerator_pedal_position": 0.24065022104694553, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137700.2575176} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.00995898246765, "x": 41.83331968086326, "y": 0.8269734308564116, "z": null, "yaw": 4.101215917581688, "pitch": null, "roll": null}, "v": 0.8733755300813414, "accelerator_pedal_position": 0.24485126774710686, "brake_pedal_position": 0.0, "acceleration": 0.029023798749902074, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.2201899937791468, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137700.2675176} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24065022104694553, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8730611450279187, "gear": 1, "accelerator_pedal_position": 0.24065022104694553, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137700.2675176} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.00995898246765, "x": 41.83331968086326, "y": 0.8269734308564116, "z": null, "yaw": 4.101215917581688, "pitch": null, "roll": null}, "v": 0.8733755300813414, "accelerator_pedal_position": 0.24485126774710686, "brake_pedal_position": 0.0, "acceleration": 0.029023798749902074, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.2201899937791468, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137700.2875175} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24065022104694553, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8731168955497526, "gear": 1, "accelerator_pedal_position": 0.24065022104694553, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137700.2875175} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.00995898246765, "x": 41.83331968086326, "y": 0.8269734308564116, "z": null, "yaw": 4.101215917581688, "pitch": null, "roll": null}, "v": 0.8733755300813414, "accelerator_pedal_position": 0.24485126774710686, "brake_pedal_position": 0.0, "acceleration": 0.029023798749902074, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.2201899937791468, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137700.3175175} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24065022104694553, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8731725708760593, "gear": 1, "accelerator_pedal_position": 0.24065022104694553, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137700.3175175} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137700.3275175, "x": 45.77722337459264, "y": 5.749021727174222, "z": null, "yaw": 4.073483403352155, "pitch": null, "roll": null}, "v": 0.8732003803722023, "accelerator_pedal_position": 0.24065022104694553, "brake_pedal_position": 0.0, "acceleration": 0.0027790734819777563, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.22014583612641045, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137700.3375175} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24897343833448485, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.873228171107022, "gear": 1, "accelerator_pedal_position": 0.24065022104694553, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137700.3375175} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.11995887756348, "x": 41.77722337459264, "y": 0.7490217271742221, "z": null, "yaw": 4.073483403352155, "pitch": null, "roll": null}, "v": 0.8732003803722023, "accelerator_pedal_position": 0.24065022104694553, "brake_pedal_position": 0.0, "acceleration": 0.0027790734819777563, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.22014583612641045, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137700.3575175} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24500909923753725, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8743237475222981, "gear": 1, "accelerator_pedal_position": 0.24897343833448485, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137700.3575175} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.11995887756348, "x": 41.77722337459264, "y": 0.7490217271742221, "z": null, "yaw": 4.073483403352155, "pitch": null, "roll": null}, "v": 0.8732003803722023, "accelerator_pedal_position": 0.24065022104694553, "brake_pedal_position": 0.0, "acceleration": 0.0027790734819777563, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.22014583612641045, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137700.3775175} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24500909923753725, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8749224706706332, "gear": 1, "accelerator_pedal_position": 0.24500909923753725, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137700.3775175} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.11995887756348, "x": 41.77722337459264, "y": 0.7490217271742221, "z": null, "yaw": 4.073483403352155, "pitch": null, "roll": null}, "v": 0.8732003803722023, "accelerator_pedal_position": 0.24065022104694553, "brake_pedal_position": 0.0, "acceleration": 0.0027790734819777563, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.22014583612641045, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137700.3875175} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24500909923753725, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8752215292046756, "gear": 1, "accelerator_pedal_position": 0.24500909923753725, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137700.3875175} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.11995887756348, "x": 41.77722337459264, "y": 0.7490217271742221, "z": null, "yaw": 4.073483403352155, "pitch": null, "roll": null}, "v": 0.8732003803722023, "accelerator_pedal_position": 0.24065022104694553, "brake_pedal_position": 0.0, "acceleration": 0.0027790734819777563, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.22014583612641045, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137700.4075174} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24500909923753725, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8761174940674383, "gear": 1, "accelerator_pedal_position": 0.24500909923753725, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137700.4075174} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137700.4375174, "x": 45.71887067650024, "y": 5.67250433753203, "z": null, "yaw": 4.045750889122622, "pitch": null, "roll": null}, "v": 0.8767137962098824, "accelerator_pedal_position": 0.24500909923753725, "brake_pedal_position": 0.0, "acceleration": 0.02978490961946617, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.2210316166237989, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137700.4375174} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24165095141491222, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8767137962098824, "gear": 1, "accelerator_pedal_position": 0.24500909923753725, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137700.4375174} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.2299587726593, "x": 41.71887067650024, "y": 0.6725043375320299, "z": null, "yaw": 4.045750889122622, "pitch": null, "roll": null}, "v": 0.8767137962098824, "accelerator_pedal_position": 0.24500909923753725, "brake_pedal_position": 0.0, "acceleration": 0.02978490961946617, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.2210316166237989, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137700.4575174} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24326813899953884, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8768896665172404, "gear": 1, "accelerator_pedal_position": 0.24165095141491222, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137700.4575174} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.2299587726593, "x": 41.71887067650024, "y": 0.6725043375320299, "z": null, "yaw": 4.045750889122622, "pitch": null, "roll": null}, "v": 0.8767137962098824, "accelerator_pedal_position": 0.24500909923753725, "brake_pedal_position": 0.0, "acceleration": 0.02978490961946617, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.2210316166237989, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137700.4675174} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24326813899953884, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8770785868227285, "gear": 1, "accelerator_pedal_position": 0.24326813899953884, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137700.4675174} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.2299587726593, "x": 41.71887067650024, "y": 0.6725043375320299, "z": null, "yaw": 4.045750889122622, "pitch": null, "roll": null}, "v": 0.8767137962098824, "accelerator_pedal_position": 0.24500909923753725, "brake_pedal_position": 0.0, "acceleration": 0.02978490961946617, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.2210316166237989, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137700.4875174} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24326813899953884, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8774560447242281, "gear": 1, "accelerator_pedal_position": 0.24326813899953884, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137700.4875174} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.2299587726593, "x": 41.71887067650024, "y": 0.6725043375320299, "z": null, "yaw": 4.045750889122622, "pitch": null, "roll": null}, "v": 0.8767137962098824, "accelerator_pedal_position": 0.24500909923753725, "brake_pedal_position": 0.0, "acceleration": 0.02978490961946617, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.2210316166237989, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137700.5175173} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24326813899953884, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8780212759879085, "gear": 1, "accelerator_pedal_position": 0.24326813899953884, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137700.5175173} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.2299587726593, "x": 41.71887067650024, "y": 0.6725043375320299, "z": null, "yaw": 4.045750889122622, "pitch": null, "roll": null}, "v": 0.8767137962098824, "accelerator_pedal_position": 0.24500909923753725, "brake_pedal_position": 0.0, "acceleration": 0.02978490961946617, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.2210316166237989, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137700.5375173} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24326813899953884, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8783974606921695, "gear": 1, "accelerator_pedal_position": 0.24326813899953884, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137700.5375173} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137700.5475173, "x": 45.65823592831964, "y": 5.59740740212574, "z": null, "yaw": 4.018018374893089, "pitch": null, "roll": null}, "v": 0.8785853624393996, "accelerator_pedal_position": 0.24326813899953884, "brake_pedal_position": 0.0, "acceleration": 0.01877747823421999, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.2215034642337225, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137700.5575173} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2490876715992612, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8787731372217418, "gear": 1, "accelerator_pedal_position": 0.24326813899953884, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137700.5575173} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.33995866775513, "x": 41.65823592831964, "y": 0.5974074021257403, "z": null, "yaw": 4.018018374893089, "pitch": null, "roll": null}, "v": 0.8785853624393996, "accelerator_pedal_position": 0.24326813899953884, "brake_pedal_position": 0.0, "acceleration": 0.01877747823421999, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.2215034642337225, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137700.5775173} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24632609697398097, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.879875501968747, "gear": 1, "accelerator_pedal_position": 0.2490876715992612, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137700.5775173} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.33995866775513, "x": 41.65823592831964, "y": 0.5974074021257403, "z": null, "yaw": 4.018018374893089, "pitch": null, "roll": null}, "v": 0.8785853624393996, "accelerator_pedal_position": 0.24326813899953884, "brake_pedal_position": 0.0, "acceleration": 0.01877747823421999, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.2215034642337225, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137700.5975173} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24632609697398097, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8806312968588066, "gear": 1, "accelerator_pedal_position": 0.24632609697398097, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137700.5975173} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.33995866775513, "x": 41.65823592831964, "y": 0.5974074021257403, "z": null, "yaw": 4.018018374893089, "pitch": null, "roll": null}, "v": 0.8785853624393996, "accelerator_pedal_position": 0.24326813899953884, "brake_pedal_position": 0.0, "acceleration": 0.01877747823421999, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.2215034642337225, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137700.6075172} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24632609697398097, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.881386070125935, "gear": 1, "accelerator_pedal_position": 0.24632609697398097, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137700.6075172} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.33995866775513, "x": 41.65823592831964, "y": 0.5974074021257403, "z": null, "yaw": 4.018018374893089, "pitch": null, "roll": null}, "v": 0.8785853624393996, "accelerator_pedal_position": 0.24326813899953884, "brake_pedal_position": 0.0, "acceleration": 0.01877747823421999, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.2215034642337225, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137700.6375172} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24632609697398097, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8821398229232839, "gear": 1, "accelerator_pedal_position": 0.24632609697398097, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137700.6375172} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137700.6575172, "x": 45.595321183479776, "y": 5.523763007477365, "z": null, "yaw": 3.9902858606635556, "pitch": null, "roll": null}, "v": 0.8828925564033699, "accelerator_pedal_position": 0.24632609697398097, "brake_pedal_position": 0.0, "acceleration": 0.03759848560568774, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.22258936712367852, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137700.6575172} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24048373595061084, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8829142236552717, "gear": 1, "accelerator_pedal_position": 0.24048373595061084, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137700.6575172} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.44995856285095, "x": 41.595321183479776, "y": 0.5237630074773652, "z": null, "yaw": 3.9902858606635556, "pitch": null, "roll": null}, "v": 0.8828925564033699, "accelerator_pedal_position": 0.24632609697398097, "brake_pedal_position": 0.0, "acceleration": 0.03759848560568774, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.22258936712367852, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137700.6775172} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24328800297926353, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.882925046287724, "gear": 1, "accelerator_pedal_position": 0.24048373595061084, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137700.6775172} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.44995856285095, "x": 41.595321183479776, "y": 0.5237630074773652, "z": null, "yaw": 3.9902858606635556, "pitch": null, "roll": null}, "v": 0.8828925564033699, "accelerator_pedal_position": 0.24632609697398097, "brake_pedal_position": 0.0, "acceleration": 0.03759848560568774, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.22258936712367852, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137700.7075171} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24328800297926353, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8834829146527027, "gear": 1, "accelerator_pedal_position": 0.24328800297926353, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137700.7075171} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.44995856285095, "x": 41.595321183479776, "y": 0.5237630074773652, "z": null, "yaw": 3.9902858606635556, "pitch": null, "roll": null}, "v": 0.8828925564033699, "accelerator_pedal_position": 0.24632609697398097, "brake_pedal_position": 0.0, "acceleration": 0.03759848560568774, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.22258936712367852, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137700.7175171} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24328800297926353, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8834829146527027, "gear": 1, "accelerator_pedal_position": 0.24328800297926353, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137700.7175171} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.44995856285095, "x": 41.595321183479776, "y": 0.5237630074773652, "z": null, "yaw": 3.9902858606635556, "pitch": null, "roll": null}, "v": 0.8828925564033699, "accelerator_pedal_position": 0.24632609697398097, "brake_pedal_position": 0.0, "acceleration": 0.03759848560568774, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.22258936712367852, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137700.737517} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24328800297926353, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8838541980292967, "gear": 1, "accelerator_pedal_position": 0.24328800297926353, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137700.737517} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.44995856285095, "x": 41.595321183479776, "y": 0.5237630074773652, "z": null, "yaw": 3.9902858606635556, "pitch": null, "roll": null}, "v": 0.8828925564033699, "accelerator_pedal_position": 0.24632609697398097, "brake_pedal_position": 0.0, "acceleration": 0.03759848560568774, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.22258936712367852, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137700.757517} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24328800297926353, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8844101813575275, "gear": 1, "accelerator_pedal_position": 0.24328800297926353, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137700.757517} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137700.767517, "x": 45.53018089219855, "y": 5.451660573676218, "z": null, "yaw": 3.9625533464340226, "pitch": null, "roll": null}, "v": 0.8844101813575275, "accelerator_pedal_position": 0.24328800297926353, "brake_pedal_position": 0.0, "acceleration": 0.0185076958636321, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.22297198126582643, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137700.777517} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24253735390177442, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8845952583161638, "gear": 1, "accelerator_pedal_position": 0.24328800297926353, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137700.777517} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.55995845794678, "x": 41.53018089219855, "y": 0.45166057367621804, "z": null, "yaw": 3.9625533464340226, "pitch": null, "roll": null}, "v": 0.8844101813575275, "accelerator_pedal_position": 0.24328800297926353, "brake_pedal_position": 0.0, "acceleration": 0.0185076958636321, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.22297198126582643, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137700.797517} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2429026309611513, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8848712371001826, "gear": 1, "accelerator_pedal_position": 0.24253735390177442, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137700.797517} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.55995845794678, "x": 41.53018089219855, "y": 0.45166057367621804, "z": null, "yaw": 3.9625533464340226, "pitch": null, "roll": null}, "v": 0.8844101813575275, "accelerator_pedal_position": 0.24328800297926353, "brake_pedal_position": 0.0, "acceleration": 0.0185076958636321, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.22297198126582643, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137700.817517} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2429026309611513, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8853529481517617, "gear": 1, "accelerator_pedal_position": 0.2429026309611513, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137700.817517} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.55995845794678, "x": 41.53018089219855, "y": 0.45166057367621804, "z": null, "yaw": 3.9625533464340226, "pitch": null, "roll": null}, "v": 0.8844101813575275, "accelerator_pedal_position": 0.24328800297926353, "brake_pedal_position": 0.0, "acceleration": 0.0185076958636321, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.22297198126582643, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137700.837517} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2429026309611513, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8855133011284777, "gear": 1, "accelerator_pedal_position": 0.2429026309611513, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137700.837517} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.55995845794678, "x": 41.53018089219855, "y": 0.45166057367621804, "z": null, "yaw": 3.9625533464340226, "pitch": null, "roll": null}, "v": 0.8844101813575275, "accelerator_pedal_position": 0.24328800297926353, "brake_pedal_position": 0.0, "acceleration": 0.0185076958636321, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.22297198126582643, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137700.857517} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2429026309611513, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8858336814317181, "gear": 1, "accelerator_pedal_position": 0.2429026309611513, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137700.857517} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137700.877517, "x": 45.4629289391355, "y": 5.381248347488137, "z": null, "yaw": 3.9348208322044895, "pitch": null, "roll": null}, "v": 0.8861536279903627, "accelerator_pedal_position": 0.2429026309611513, "brake_pedal_position": 0.0, "acceleration": 0.01598107958367262, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.22341152816176763, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137700.877517} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25111922010365056, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8863134387861994, "gear": 1, "accelerator_pedal_position": 0.2429026309611513, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137700.877517} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.6699583530426, "x": 41.4629289391355, "y": 0.3812483474881372, "z": null, "yaw": 3.9348208322044895, "pitch": null, "roll": null}, "v": 0.8861536279903627, "accelerator_pedal_position": 0.2429026309611513, "brake_pedal_position": 0.0, "acceleration": 0.01598107958367262, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.22341152816176763, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137700.897517} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24721555026987407, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8869866781721072, "gear": 1, "accelerator_pedal_position": 0.25111922010365056, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137700.897517} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.6699583530426, "x": 41.4629289391355, "y": 0.3812483474881372, "z": null, "yaw": 3.9348208322044895, "pitch": null, "roll": null}, "v": 0.8861536279903627, "accelerator_pedal_position": 0.2429026309611513, "brake_pedal_position": 0.0, "acceleration": 0.01598107958367262, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.22341152816176763, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137700.917517} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24721555026987407, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8878439957151332, "gear": 1, "accelerator_pedal_position": 0.24721555026987407, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137700.917517} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.6699583530426, "x": 41.4629289391355, "y": 0.3812483474881372, "z": null, "yaw": 3.9348208322044895, "pitch": null, "roll": null}, "v": 0.8861536279903627, "accelerator_pedal_position": 0.2429026309611513, "brake_pedal_position": 0.0, "acceleration": 0.01598107958367262, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.22341152816176763, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137700.937517} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24721555026987407, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8891277949618812, "gear": 1, "accelerator_pedal_position": 0.24721555026987407, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137700.937517} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.6699583530426, "x": 41.4629289391355, "y": 0.3812483474881372, "z": null, "yaw": 3.9348208322044895, "pitch": null, "roll": null}, "v": 0.8861536279903627, "accelerator_pedal_position": 0.2429026309611513, "brake_pedal_position": 0.0, "acceleration": 0.01598107958367262, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.22341152816176763, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137700.957517} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24721555026987407, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8899822116143339, "gear": 1, "accelerator_pedal_position": 0.24721555026987407, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137700.957517} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.6699583530426, "x": 41.4629289391355, "y": 0.3812483474881372, "z": null, "yaw": 3.9348208322044895, "pitch": null, "roll": null}, "v": 0.8861536279903627, "accelerator_pedal_position": 0.2429026309611513, "brake_pedal_position": 0.0, "acceleration": 0.01598107958367262, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.22341152816176763, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137700.967517} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24721555026987407, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.890835470149621, "gear": 1, "accelerator_pedal_position": 0.24721555026987407, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137700.967517} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137700.9875169, "x": 45.393511429399084, "y": 5.312492423100834, "z": null, "yaw": 3.9070883179749565, "pitch": null, "roll": null}, "v": 0.890835470149621, "accelerator_pedal_position": 0.24721555026987407, "brake_pedal_position": 0.0, "acceleration": 0.04261953733046486, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.22459188501905902, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137700.9975169} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24146681887857513, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8916875718463882, "gear": 1, "accelerator_pedal_position": 0.24721555026987407, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137700.9975169} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.77995824813843, "x": 41.393511429399084, "y": 0.31249242310083414, "z": null, "yaw": 3.9070883179749565, "pitch": null, "roll": null}, "v": 0.890835470149621, "accelerator_pedal_position": 0.24721555026987407, "brake_pedal_position": 0.0, "acceleration": 0.04261953733046486, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.22459188501905902, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137701.0175169} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24422848571554598, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8918201703002552, "gear": 1, "accelerator_pedal_position": 0.24146681887857513, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137701.0175169} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.77995824813843, "x": 41.393511429399084, "y": 0.31249242310083414, "z": null, "yaw": 3.9070883179749565, "pitch": null, "roll": null}, "v": 0.890835470149621, "accelerator_pedal_position": 0.24721555026987407, "brake_pedal_position": 0.0, "acceleration": 0.04261953733046486, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.22459188501905902, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137701.0275168} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24422848571554598, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8918201703002552, "gear": 1, "accelerator_pedal_position": 0.24146681887857513, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137701.0275168} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.77995824813843, "x": 41.393511429399084, "y": 0.31249242310083414, "z": null, "yaw": 3.9070883179749565, "pitch": null, "roll": null}, "v": 0.890835470149621, "accelerator_pedal_position": 0.24721555026987407, "brake_pedal_position": 0.0, "acceleration": 0.04261953733046486, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.22459188501905902, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137701.0575168} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24422848571554598, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8927745423555684, "gear": 1, "accelerator_pedal_position": 0.24422848571554598, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137701.0575168} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.77995824813843, "x": 41.393511429399084, "y": 0.31249242310083414, "z": null, "yaw": 3.9070883179749565, "pitch": null, "roll": null}, "v": 0.890835470149621, "accelerator_pedal_position": 0.24721555026987407, "brake_pedal_position": 0.0, "acceleration": 0.04261953733046486, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.22459188501905902, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137701.0775168} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24422848571554598, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8930127308032644, "gear": 1, "accelerator_pedal_position": 0.24422848571554598, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137701.0775168} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137701.0975168, "x": 45.321904150059815, "y": 5.24539658937687, "z": null, "yaw": 3.8793558037454234, "pitch": null, "roll": null}, "v": 0.8934886229081584, "accelerator_pedal_position": 0.24422848571554598, "brake_pedal_position": 0.0, "acceleration": 0.02377038538409121, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.22526078135205232, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137701.0975168} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2524590303917035, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8934886229081584, "gear": 1, "accelerator_pedal_position": 0.24422848571554598, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137701.0975168} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.88995814323425, "x": 41.321904150059815, "y": 0.24539658937687037, "z": null, "yaw": 3.8793558037454234, "pitch": null, "roll": null}, "v": 0.8934886229081584, "accelerator_pedal_position": 0.24422848571554598, "brake_pedal_position": 0.0, "acceleration": 0.02377038538409121, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.22526078135205232, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137701.1175168} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24855343562208548, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8949923381864814, "gear": 1, "accelerator_pedal_position": 0.2524590303917035, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137701.1175168} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.88995814323425, "x": 41.321904150059815, "y": 0.24539658937687037, "z": null, "yaw": 3.8793558037454234, "pitch": null, "roll": null}, "v": 0.8934886229081584, "accelerator_pedal_position": 0.24422848571554598, "brake_pedal_position": 0.0, "acceleration": 0.02377038538409121, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.22526078135205232, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137701.1375167} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24855343562208548, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8960059787711867, "gear": 1, "accelerator_pedal_position": 0.24855343562208548, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137701.1375167} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.88995814323425, "x": 41.321904150059815, "y": 0.24539658937687037, "z": null, "yaw": 3.8793558037454234, "pitch": null, "roll": null}, "v": 0.8934886229081584, "accelerator_pedal_position": 0.24422848571554598, "brake_pedal_position": 0.0, "acceleration": 0.02377038538409121, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.22526078135205232, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137701.1575167} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24855343562208548, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8970182429944163, "gear": 1, "accelerator_pedal_position": 0.24855343562208548, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137701.1575167} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.88995814323425, "x": 41.321904150059815, "y": 0.24539658937687037, "z": null, "yaw": 3.8793558037454234, "pitch": null, "roll": null}, "v": 0.8934886229081584, "accelerator_pedal_position": 0.24422848571554598, "brake_pedal_position": 0.0, "acceleration": 0.02377038538409121, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.22526078135205232, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137701.1775167} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24855343562208548, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8980291323153161, "gear": 1, "accelerator_pedal_position": 0.24855343562208548, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137701.1775167} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.88995814323425, "x": 41.321904150059815, "y": 0.24539658937687037, "z": null, "yaw": 3.8793558037454234, "pitch": null, "roll": null}, "v": 0.8934886229081584, "accelerator_pedal_position": 0.24422848571554598, "brake_pedal_position": 0.0, "acceleration": 0.02377038538409121, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.22526078135205232, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137701.1975167} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24855343562208548, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8990386481927195, "gear": 1, "accelerator_pedal_position": 0.24855343562208548, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137701.1975167} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137701.2075167, "x": 45.248107150543994, "y": 5.179997149776754, "z": null, "yaw": 3.8516232895158904, "pitch": null, "roll": null}, "v": 0.899542891545909, "accelerator_pedal_position": 0.24855343562208548, "brake_pedal_position": 0.0, "acceleration": 0.05039005392343099, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.22678714581701445, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137701.2175167} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24815563908100435, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9000467920851434, "gear": 1, "accelerator_pedal_position": 0.24855343562208548, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137701.2175167} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.99995803833008, "x": 41.248107150543994, "y": 0.17999714977675385, "z": null, "yaw": 3.8516232895158904, "pitch": null, "roll": null}, "v": 0.899542891545909, "accelerator_pedal_position": 0.24855343562208548, "brake_pedal_position": 0.0, "acceleration": 0.05039005392343099, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.22678714581701445, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137701.2375166} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24837640084905893, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9010038577921763, "gear": 1, "accelerator_pedal_position": 0.24815563908100435, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137701.2375166} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.99995803833008, "x": 41.248107150543994, "y": 0.17999714977675385, "z": null, "yaw": 3.8516232895158904, "pitch": null, "roll": null}, "v": 0.899542891545909, "accelerator_pedal_position": 0.24855343562208548, "brake_pedal_position": 0.0, "acceleration": 0.05039005392343099, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.22678714581701445, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137701.2575166} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24837640084905893, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9024783812312547, "gear": 1, "accelerator_pedal_position": 0.24837640084905893, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137701.2575166} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.99995803833008, "x": 41.248107150543994, "y": 0.17999714977675385, "z": null, "yaw": 3.8516232895158904, "pitch": null, "roll": null}, "v": 0.899542891545909, "accelerator_pedal_position": 0.24855343562208548, "brake_pedal_position": 0.0, "acceleration": 0.05039005392343099, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.22678714581701445, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137701.2775166} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24837640084905893, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9029692203708463, "gear": 1, "accelerator_pedal_position": 0.24837640084905893, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137701.2775166} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.99995803833008, "x": 41.248107150543994, "y": 0.17999714977675385, "z": null, "yaw": 3.8516232895158904, "pitch": null, "roll": null}, "v": 0.899542891545909, "accelerator_pedal_position": 0.24855343562208548, "brake_pedal_position": 0.0, "acceleration": 0.05039005392343099, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.22678714581701445, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137701.2975166} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24837640084905893, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9039498967152081, "gear": 1, "accelerator_pedal_position": 0.24837640084905893, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137701.2975166} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137701.3175166, "x": 45.172057485609336, "y": 5.116277211576991, "z": null, "yaw": 3.8238907752863573, "pitch": null, "roll": null}, "v": 0.9049292383409724, "accelerator_pedal_position": 0.24837640084905893, "brake_pedal_position": 0.0, "acceleration": 0.04891707412552593, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.22814511799100798, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137701.3175166} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24716301630545318, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9049292383409724, "gear": 1, "accelerator_pedal_position": 0.24837640084905893, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137701.3175166} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.1099579334259, "x": 41.172057485609336, "y": 0.11627721157699078, "z": null, "yaw": 3.8238907752863573, "pitch": null, "roll": null}, "v": 0.9049292383409724, "accelerator_pedal_position": 0.24837640084905893, "brake_pedal_position": 0.0, "acceleration": 0.04891707412552593, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.22814511799100798, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137701.3375165} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24776874353101372, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9057556252637021, "gear": 1, "accelerator_pedal_position": 0.24716301630545318, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137701.3375165} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.1099579334259, "x": 41.172057485609336, "y": 0.11627721157699078, "z": null, "yaw": 3.8238907752863573, "pitch": null, "roll": null}, "v": 0.9049292383409724, "accelerator_pedal_position": 0.24837640084905893, "brake_pedal_position": 0.0, "acceleration": 0.04891707412552593, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.22814511799100798, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137701.3575165} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24776874353101372, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9066565769622921, "gear": 1, "accelerator_pedal_position": 0.24776874353101372, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137701.3575165} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.1099579334259, "x": 41.172057485609336, "y": 0.11627721157699078, "z": null, "yaw": 3.8238907752863573, "pitch": null, "roll": null}, "v": 0.9049292383409724, "accelerator_pedal_position": 0.24837640084905893, "brake_pedal_position": 0.0, "acceleration": 0.04891707412552593, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.22814511799100798, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137701.3775165} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24776874353101372, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9075563014670469, "gear": 1, "accelerator_pedal_position": 0.24776874353101372, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137701.3775165} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.1099579334259, "x": 41.172057485609336, "y": 0.11627721157699078, "z": null, "yaw": 3.8238907752863573, "pitch": null, "roll": null}, "v": 0.9049292383409724, "accelerator_pedal_position": 0.24837640084905893, "brake_pedal_position": 0.0, "acceleration": 0.04891707412552593, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.22814511799100798, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137701.3975165} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24776874353101372, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9084548001258461, "gear": 1, "accelerator_pedal_position": 0.24776874353101372, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137701.3975165} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.1099579334259, "x": 41.172057485609336, "y": 0.11627721157699078, "z": null, "yaw": 3.8238907752863573, "pitch": null, "roll": null}, "v": 0.9049292383409724, "accelerator_pedal_position": 0.24837640084905893, "brake_pedal_position": 0.0, "acceleration": 0.04891707412552593, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.22814511799100798, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137701.4175165} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24776874353101372, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9098002526001003, "gear": 1, "accelerator_pedal_position": 0.24776874353101372, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137701.4175165} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137701.4275165, "x": 45.093828314592784, "y": 5.054340551669967, "z": null, "yaw": 3.7961582610568243, "pitch": null, "roll": null}, "v": 0.9098002526001003, "accelerator_pedal_position": 0.24776874353101372, "brake_pedal_position": 0.0, "acceleration": 0.044787269442518596, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.22937316773876726, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137701.4375165} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2519699891569769, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9102481252945255, "gear": 1, "accelerator_pedal_position": 0.24776874353101372, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137701.4375165} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.21995782852173, "x": 41.093828314592784, "y": 0.05434055166996732, "z": null, "yaw": 3.7961582610568243, "pitch": null, "roll": null}, "v": 0.9098002526001003, "accelerator_pedal_position": 0.24776874353101372, "brake_pedal_position": 0.0, "acceleration": 0.044787269442518596, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.22937316773876726, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137701.4575164} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24999468617273762, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.912253651157907, "gear": 1, "accelerator_pedal_position": 0.24999468617273762, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137701.4575164} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.21995782852173, "x": 41.093828314592784, "y": 0.05434055166996732, "z": null, "yaw": 3.7961582610568243, "pitch": null, "roll": null}, "v": 0.9098002526001003, "accelerator_pedal_position": 0.24776874353101372, "brake_pedal_position": 0.0, "acceleration": 0.044787269442518596, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.22937316773876726, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137701.4775164} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24999468617273762, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.912838971545719, "gear": 1, "accelerator_pedal_position": 0.24999468617273762, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137701.4775164} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.21995782852173, "x": 41.093828314592784, "y": 0.05434055166996732, "z": null, "yaw": 3.7961582610568243, "pitch": null, "roll": null}, "v": 0.9098002526001003, "accelerator_pedal_position": 0.24776874353101372, "brake_pedal_position": 0.0, "acceleration": 0.044787269442518596, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.22937316773876726, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137701.4975164} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24999468617273762, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9140084140657884, "gear": 1, "accelerator_pedal_position": 0.24999468617273762, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137701.4975164} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.21995782852173, "x": 41.093828314592784, "y": 0.05434055166996732, "z": null, "yaw": 3.7961582610568243, "pitch": null, "roll": null}, "v": 0.9098002526001003, "accelerator_pedal_position": 0.24776874353101372, "brake_pedal_position": 0.0, "acceleration": 0.044787269442518596, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.22937316773876726, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137701.5175164} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24999468617273762, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9157595852700673, "gear": 1, "accelerator_pedal_position": 0.24999468617273762, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137701.5175164} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137701.5375164, "x": 45.01341129428817, "y": 4.994223301728401, "z": null, "yaw": 3.7684257468272913, "pitch": null, "roll": null}, "v": 0.916342511801427, "accelerator_pedal_position": 0.24999468617273762, "brake_pedal_position": 0.0, "acceleration": 0.05825282700019324, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.2310225613423498, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137701.5375164} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24906044425973461, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.916342511801427, "gear": 1, "accelerator_pedal_position": 0.24999468617273762, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137701.5375164} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.329957723617554, "x": 41.01341129428817, "y": -0.005776698271598768, "z": null, "yaw": 3.7684257468272913, "pitch": null, "roll": null}, "v": 0.916342511801427, "accelerator_pedal_position": 0.24999468617273762, "brake_pedal_position": 0.0, "acceleration": 0.05825282700019324, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.2310225613423498, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137701.5575163} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24953934704444317, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9179437834029522, "gear": 1, "accelerator_pedal_position": 0.24953934704444317, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137701.5575163} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.329957723617554, "x": 41.01341129428817, "y": -0.005776698271598768, "z": null, "yaw": 3.7684257468272913, "pitch": null, "roll": null}, "v": 0.916342511801427, "accelerator_pedal_position": 0.24999468617273762, "brake_pedal_position": 0.0, "acceleration": 0.05825282700019324, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.2310225613423498, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137701.5775163} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24953934704444317, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9184967586225796, "gear": 1, "accelerator_pedal_position": 0.24953934704444317, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137701.5775163} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.329957723617554, "x": 41.01341129428817, "y": -0.005776698271598768, "z": null, "yaw": 3.7684257468272913, "pitch": null, "roll": null}, "v": 0.916342511801427, "accelerator_pedal_position": 0.24999468617273762, "brake_pedal_position": 0.0, "acceleration": 0.05825282700019324, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.2310225613423498, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137701.5975163} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24953934704444317, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9196015751445213, "gear": 1, "accelerator_pedal_position": 0.24953934704444317, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137701.5975163} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.329957723617554, "x": 41.01341129428817, "y": -0.005776698271598768, "z": null, "yaw": 3.7684257468272913, "pitch": null, "roll": null}, "v": 0.916342511801427, "accelerator_pedal_position": 0.24999468617273762, "brake_pedal_position": 0.0, "acceleration": 0.05825282700019324, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.2310225613423498, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137701.6175163} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24953934704444317, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9207048810923304, "gear": 1, "accelerator_pedal_position": 0.24953934704444317, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137701.6175163} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.329957723617554, "x": 41.01341129428817, "y": -0.005776698271598768, "z": null, "yaw": 3.7684257468272913, "pitch": null, "roll": null}, "v": 0.916342511801427, "accelerator_pedal_position": 0.24999468617273762, "brake_pedal_position": 0.0, "acceleration": 0.05825282700019324, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.2310225613423498, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137701.6375163} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24953934704444317, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9218066780446109, "gear": 1, "accelerator_pedal_position": 0.24953934704444317, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137701.6375163} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137701.6475163, "x": 44.930795377173105, "y": 4.935961941249939, "z": null, "yaw": 3.740693232597758, "pitch": null, "roll": null}, "v": 0.9223570111406976, "accelerator_pedal_position": 0.24953934704444317, "brake_pedal_position": 0.0, "acceleration": 0.05499564391073081, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.23253889941971195, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137701.6575162} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25788391170481423, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9229069675798048, "gear": 1, "accelerator_pedal_position": 0.24953934704444317, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137701.6575162} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.43995761871338, "x": 40.930795377173105, "y": -0.06403805875006086, "z": null, "yaw": 3.740693232597758, "pitch": null, "roll": null}, "v": 0.9223570111406976, "accelerator_pedal_position": 0.24953934704444317, "brake_pedal_position": 0.0, "acceleration": 0.05499564391073081, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.23253889941971195, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137701.6775162} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25394164569055083, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9250484647408519, "gear": 1, "accelerator_pedal_position": 0.25788391170481423, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137701.6775162} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.43995761871338, "x": 40.930795377173105, "y": -0.06403805875006086, "z": null, "yaw": 3.740693232597758, "pitch": null, "roll": null}, "v": 0.9223570111406976, "accelerator_pedal_position": 0.24953934704444317, "brake_pedal_position": 0.0, "acceleration": 0.05499564391073081, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.23253889941971195, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137701.6975162} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25394164569055083, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9266944150480985, "gear": 1, "accelerator_pedal_position": 0.25394164569055083, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137701.6975162} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.43995761871338, "x": 40.930795377173105, "y": -0.06403805875006086, "z": null, "yaw": 3.740693232597758, "pitch": null, "roll": null}, "v": 0.9223570111406976, "accelerator_pedal_position": 0.24953934704444317, "brake_pedal_position": 0.0, "acceleration": 0.05499564391073081, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.23253889941971195, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137701.7175162} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25394164569055083, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9283381103317625, "gear": 1, "accelerator_pedal_position": 0.25394164569055083, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137701.7175162} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.43995761871338, "x": 40.930795377173105, "y": -0.06403805875006086, "z": null, "yaw": 3.740693232597758, "pitch": null, "roll": null}, "v": 0.9223570111406976, "accelerator_pedal_position": 0.24953934704444317, "brake_pedal_position": 0.0, "acceleration": 0.05499564391073081, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.23253889941971195, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137701.7375162} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25394164569055083, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9299795526010012, "gear": 1, "accelerator_pedal_position": 0.25394164569055083, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137701.7375162} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137701.7575161, "x": 44.84590364255372, "y": 4.879554997330631, "z": null, "yaw": 3.712960718368225, "pitch": null, "roll": null}, "v": 0.9316187438666595, "accelerator_pedal_position": 0.25394164569055083, "brake_pedal_position": 0.0, "acceleration": 0.08187521353337268, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.23487390973437436, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137701.7575161} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2503973707960518, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9316187438666595, "gear": 1, "accelerator_pedal_position": 0.25394164569055083, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137701.7575161} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.549957513809204, "x": 40.84590364255372, "y": -0.12044500266936886, "z": null, "yaw": 3.712960718368225, "pitch": null, "roll": null}, "v": 0.9316187438666595, "accelerator_pedal_position": 0.25394164569055083, "brake_pedal_position": 0.0, "acceleration": 0.08187521353337268, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.23487390973437436, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137701.7775161} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2521334870923577, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9328128038433129, "gear": 1, "accelerator_pedal_position": 0.2503973707960518, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137701.7775161} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.549957513809204, "x": 40.84590364255372, "y": -0.12044500266936886, "z": null, "yaw": 3.712960718368225, "pitch": null, "roll": null}, "v": 0.9316187438666595, "accelerator_pedal_position": 0.25394164569055083, "brake_pedal_position": 0.0, "acceleration": 0.08187521353337268, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.23487390973437436, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137701.797516} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2521334870923577, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.934222164957476, "gear": 1, "accelerator_pedal_position": 0.2521334870923577, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137701.797516} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.549957513809204, "x": 40.84590364255372, "y": -0.12044500266936886, "z": null, "yaw": 3.712960718368225, "pitch": null, "roll": null}, "v": 0.9316187438666595, "accelerator_pedal_position": 0.25394164569055083, "brake_pedal_position": 0.0, "acceleration": 0.08187521353337268, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.23487390973437436, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137701.817516} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2521334870923577, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9356295909114036, "gear": 1, "accelerator_pedal_position": 0.2521334870923577, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137701.817516} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.549957513809204, "x": 40.84590364255372, "y": -0.12044500266936886, "z": null, "yaw": 3.712960718368225, "pitch": null, "roll": null}, "v": 0.9316187438666595, "accelerator_pedal_position": 0.25394164569055083, "brake_pedal_position": 0.0, "acceleration": 0.08187521353337268, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.23487390973437436, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137701.837516} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2521334870923577, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9370350835701511, "gear": 1, "accelerator_pedal_position": 0.2521334870923577, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137701.837516} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.549957513809204, "x": 40.84590364255372, "y": -0.12044500266936886, "z": null, "yaw": 3.712960718368225, "pitch": null, "roll": null}, "v": 0.9316187438666595, "accelerator_pedal_position": 0.25394164569055083, "brake_pedal_position": 0.0, "acceleration": 0.08187521353337268, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.23487390973437436, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137701.857516} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2521334870923577, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9384386447994756, "gear": 1, "accelerator_pedal_position": 0.2521334870923577, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137701.857516} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137701.867516, "x": 44.758702017546625, "y": 4.825036462486578, "z": null, "yaw": 3.685228204138692, "pitch": null, "roll": null}, "v": 0.9391397017113429, "accelerator_pedal_position": 0.2521334870923577, "brake_pedal_position": 0.0, "acceleration": 0.07005747544836388, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.23677004673844157, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137701.877516} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2566550859245074, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9398402764658265, "gear": 1, "accelerator_pedal_position": 0.2521334870923577, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137701.877516} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.65995740890503, "x": 40.758702017546625, "y": -0.1749635375134222, "z": null, "yaw": 3.685228204138692, "pitch": null, "roll": null}, "v": 0.9391397017113429, "accelerator_pedal_position": 0.2521334870923577, "brake_pedal_position": 0.0, "acceleration": 0.07005747544836388, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.23677004673844157, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137701.897516} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2545413137558519, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9418049858230767, "gear": 1, "accelerator_pedal_position": 0.2566550859245074, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137701.897516} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.65995740890503, "x": 40.758702017546625, "y": -0.1749635375134222, "z": null, "yaw": 3.685228204138692, "pitch": null, "roll": null}, "v": 0.9391397017113429, "accelerator_pedal_position": 0.2521334870923577, "brake_pedal_position": 0.0, "acceleration": 0.07005747544836388, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.23677004673844157, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137701.917516} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2545413137558519, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.943502861081574, "gear": 1, "accelerator_pedal_position": 0.2545413137558519, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137701.917516} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.65995740890503, "x": 40.758702017546625, "y": -0.1749635375134222, "z": null, "yaw": 3.685228204138692, "pitch": null, "roll": null}, "v": 0.9391397017113429, "accelerator_pedal_position": 0.2521334870923577, "brake_pedal_position": 0.0, "acceleration": 0.07005747544836388, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.23677004673844157, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137701.937516} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2545413137558519, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9451983987782423, "gear": 1, "accelerator_pedal_position": 0.2545413137558519, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137701.937516} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.65995740890503, "x": 40.758702017546625, "y": -0.1749635375134222, "z": null, "yaw": 3.685228204138692, "pitch": null, "roll": null}, "v": 0.9391397017113429, "accelerator_pedal_position": 0.2521334870923577, "brake_pedal_position": 0.0, "acceleration": 0.07005747544836388, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.23677004673844157, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137701.957516} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2545413137558519, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9468916009817933, "gear": 1, "accelerator_pedal_position": 0.2545413137558519, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137701.957516} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137701.977516, "x": 44.669215703501095, "y": 4.772483824998605, "z": null, "yaw": 3.657495689909159, "pitch": null, "roll": null}, "v": 0.9485824697628387, "accelerator_pedal_position": 0.2545413137558519, "brake_pedal_position": 0.0, "acceleration": 0.08445600046651852, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.23915069855075322, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137701.977516} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2558213496392331, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9485824697628387, "gear": 1, "accelerator_pedal_position": 0.2545413137558519, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137701.977516} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.769957304000854, "x": 40.669215703501095, "y": -0.2275161750013952, "z": null, "yaw": 3.657495689909159, "pitch": null, "roll": null}, "v": 0.9485824697628387, "accelerator_pedal_position": 0.2545413137558519, "brake_pedal_position": 0.0, "acceleration": 0.08445600046651852, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.23915069855075322, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137701.997516} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2552613621105464, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9504309564862784, "gear": 1, "accelerator_pedal_position": 0.2558213496392331, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137701.997516} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.769957304000854, "x": 40.669215703501095, "y": -0.2275161750013952, "z": null, "yaw": 3.657495689909159, "pitch": null, "roll": null}, "v": 0.9485824697628387, "accelerator_pedal_position": 0.2545413137558519, "brake_pedal_position": 0.0, "acceleration": 0.08445600046651852, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.23915069855075322, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137702.017516} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2552613621105464, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9522069189189829, "gear": 1, "accelerator_pedal_position": 0.2552613621105464, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137702.017516} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.769957304000854, "x": 40.669215703501095, "y": -0.2275161750013952, "z": null, "yaw": 3.657495689909159, "pitch": null, "roll": null}, "v": 0.9485824697628387, "accelerator_pedal_position": 0.2545413137558519, "brake_pedal_position": 0.0, "acceleration": 0.08445600046651852, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.23915069855075322, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137702.0375159} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2552613621105464, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9539804301176813, "gear": 1, "accelerator_pedal_position": 0.2552613621105464, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137702.0375159} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.769957304000854, "x": 40.669215703501095, "y": -0.2275161750013952, "z": null, "yaw": 3.657495689909159, "pitch": null, "roll": null}, "v": 0.9485824697628387, "accelerator_pedal_position": 0.2545413137558519, "brake_pedal_position": 0.0, "acceleration": 0.08445600046651852, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.23915069855075322, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137702.0575159} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2552613621105464, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9557514922079341, "gear": 1, "accelerator_pedal_position": 0.2552613621105464, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137702.0575159} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.769957304000854, "x": 40.669215703501095, "y": -0.2275161750013952, "z": null, "yaw": 3.657495689909159, "pitch": null, "roll": null}, "v": 0.9485824697628387, "accelerator_pedal_position": 0.2545413137558519, "brake_pedal_position": 0.0, "acceleration": 0.08445600046651852, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.23915069855075322, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137702.0775158} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2552613621105464, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9575201073175765, "gear": 1, "accelerator_pedal_position": 0.2552613621105464, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137702.0775158} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137702.0875158, "x": 44.57737882842146, "y": 4.72192202874612, "z": null, "yaw": 3.629763175679626, "pitch": null, "roll": null}, "v": 0.9584034979202352, "accelerator_pedal_position": 0.2552613621105464, "brake_pedal_position": 0.0, "acceleration": 0.08827796564664575, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.24162671494278626, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137702.0975158} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25253351048032985, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9592862775767016, "gear": 1, "accelerator_pedal_position": 0.2552613621105464, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137702.0975158} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.87995719909668, "x": 40.57737882842146, "y": -0.2780779712538797, "z": null, "yaw": 3.629763175679626, "pitch": null, "roll": null}, "v": 0.9584034979202352, "accelerator_pedal_position": 0.2552613621105464, "brake_pedal_position": 0.0, "acceleration": 0.08827796564664575, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.24162671494278626, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137702.1175158} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25388417094365834, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9615042515539584, "gear": 1, "accelerator_pedal_position": 0.25388417094365834, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137702.1175158} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.87995719909668, "x": 40.57737882842146, "y": -0.2780779712538797, "z": null, "yaw": 3.629763175679626, "pitch": null, "roll": null}, "v": 0.9584034979202352, "accelerator_pedal_position": 0.2552613621105464, "brake_pedal_position": 0.0, "acceleration": 0.08827796564664575, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.24162671494278626, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137702.1375158} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25388417094365834, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9622988110695844, "gear": 1, "accelerator_pedal_position": 0.25388417094365834, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137702.1375158} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.87995719909668, "x": 40.57737882842146, "y": -0.2780779712538797, "z": null, "yaw": 3.629763175679626, "pitch": null, "roll": null}, "v": 0.9584034979202352, "accelerator_pedal_position": 0.2552613621105464, "brake_pedal_position": 0.0, "acceleration": 0.08827796564664575, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.24162671494278626, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137702.1575158} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25388417094365834, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.967054624198716, "gear": 1, "accelerator_pedal_position": 0.25388417094365834, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137702.1575158} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137702.1975157, "x": 44.48327127676746, "y": 4.673460345903601, "z": null, "yaw": 3.602030661450093, "pitch": null, "roll": null}, "v": 0.967054624198716, "accelerator_pedal_position": 0.25388417094365834, "brake_pedal_position": 0.0, "acceleration": 0.07907139072608754, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.24380778296659947, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137702.1975157} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26288164808412506, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9686355036610531, "gear": 1, "accelerator_pedal_position": 0.25388417094365834, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137702.1975157} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.989957094192505, "x": 40.48327127676746, "y": -0.32653965409639873, "z": null, "yaw": 3.602030661450093, "pitch": null, "roll": null}, "v": 0.967054624198716, "accelerator_pedal_position": 0.25388417094365834, "brake_pedal_position": 0.0, "acceleration": 0.07907139072608754, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.24380778296659947, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137702.2175157} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2586427810523089, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.970808810620397, "gear": 1, "accelerator_pedal_position": 0.2586427810523089, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137702.2175157} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.989957094192505, "x": 40.48327127676746, "y": -0.32653965409639873, "z": null, "yaw": 3.602030661450093, "pitch": null, "roll": null}, "v": 0.967054624198716, "accelerator_pedal_position": 0.25388417094365834, "brake_pedal_position": 0.0, "acceleration": 0.07907139072608754, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.24380778296659947, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137702.2375157} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2586427810523089, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.970808810620397, "gear": 1, "accelerator_pedal_position": 0.2586427810523089, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137702.2375157} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.989957094192505, "x": 40.48327127676746, "y": -0.32653965409639873, "z": null, "yaw": 3.602030661450093, "pitch": null, "roll": null}, "v": 0.967054624198716, "accelerator_pedal_position": 0.25388417094365834, "brake_pedal_position": 0.0, "acceleration": 0.07907139072608754, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.24380778296659947, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137702.2675157} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2586427810523089, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9740631172775404, "gear": 1, "accelerator_pedal_position": 0.2586427810523089, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137702.2675157} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.989957094192505, "x": 40.48327127676746, "y": -0.32653965409639873, "z": null, "yaw": 3.602030661450093, "pitch": null, "roll": null}, "v": 0.967054624198716, "accelerator_pedal_position": 0.25388417094365834, "brake_pedal_position": 0.0, "acceleration": 0.07907139072608754, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.24380778296659947, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137702.2875156} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2586427810523089, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9762288892188044, "gear": 1, "accelerator_pedal_position": 0.2586427810523089, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137702.2875156} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137702.3075156, "x": 44.38689949390877, "y": 4.627168070057186, "z": null, "yaw": 3.57429814722056, "pitch": null, "roll": null}, "v": 0.978391651188228, "accelerator_pedal_position": 0.2586427810523089, "brake_pedal_position": 0.0, "acceleration": 0.10802529678637102, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.24666600353302884, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137702.3075156} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26378651070630044, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.978391651188228, "gear": 1, "accelerator_pedal_position": 0.2586427810523089, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137702.3075156} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.09995698928833, "x": 40.38689949390877, "y": -0.372831929942814, "z": null, "yaw": 3.57429814722056, "pitch": null, "roll": null}, "v": 0.978391651188228, "accelerator_pedal_position": 0.2586427810523089, "brake_pedal_position": 0.0, "acceleration": 0.10802529678637102, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.24666600353302884, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137702.3275156} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2613971073626956, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9811941479768085, "gear": 1, "accelerator_pedal_position": 0.26378651070630044, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137702.3275156} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.09995698928833, "x": 40.38689949390877, "y": -0.372831929942814, "z": null, "yaw": 3.57429814722056, "pitch": null, "roll": null}, "v": 0.978391651188228, "accelerator_pedal_position": 0.2586427810523089, "brake_pedal_position": 0.0, "acceleration": 0.10802529678637102, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.24666600353302884, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137702.3475156} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2613971073626956, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9836941730911912, "gear": 1, "accelerator_pedal_position": 0.2613971073626956, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137702.3475156} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.09995698928833, "x": 40.38689949390877, "y": -0.372831929942814, "z": null, "yaw": 3.57429814722056, "pitch": null, "roll": null}, "v": 0.978391651188228, "accelerator_pedal_position": 0.2586427810523089, "brake_pedal_position": 0.0, "acceleration": 0.10802529678637102, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.24666600353302884, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137702.3675156} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2613971073626956, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9861907163148238, "gear": 1, "accelerator_pedal_position": 0.2613971073626956, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137702.3675156} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.09995698928833, "x": 40.38689949390877, "y": -0.372831929942814, "z": null, "yaw": 3.57429814722056, "pitch": null, "roll": null}, "v": 0.978391651188228, "accelerator_pedal_position": 0.2586427810523089, "brake_pedal_position": 0.0, "acceleration": 0.10802529678637102, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.24666600353302884, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137702.3875155} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2613971073626956, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.98868378000486, "gear": 1, "accelerator_pedal_position": 0.2613971073626956, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137702.3875155} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.09995698928833, "x": 40.38689949390877, "y": -0.372831929942814, "z": null, "yaw": 3.57429814722056, "pitch": null, "roll": null}, "v": 0.978391651188228, "accelerator_pedal_position": 0.2586427810523089, "brake_pedal_position": 0.0, "acceleration": 0.10802529678637102, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.24666600353302884, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137702.4075155} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2613971073626956, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9911733665255873, "gear": 1, "accelerator_pedal_position": 0.2613971073626956, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137702.4075155} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137702.4175155, "x": 44.287982695565574, "y": 4.582986550927029, "z": null, "yaw": 3.546565632991027, "pitch": null, "roll": null}, "v": 0.992416856588242, "accelerator_pedal_position": 0.2613971073626956, "brake_pedal_position": 0.0, "acceleration": 0.12426216601503048, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.2502019508814652, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137702.4275155} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26299460785684753, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9936594782483923, "gear": 1, "accelerator_pedal_position": 0.2613971073626956, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137702.4275155} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.209956884384155, "x": 40.287982695565574, "y": -0.41701344907297067, "z": null, "yaw": 3.546565632991027, "pitch": null, "roll": null}, "v": 0.992416856588242, "accelerator_pedal_position": 0.2613971073626956, "brake_pedal_position": 0.0, "acceleration": 0.12426216601503048, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.2502019508814652, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137702.4475155} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.262308382151976, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9963417353236691, "gear": 1, "accelerator_pedal_position": 0.26299460785684753, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137702.4475155} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.209956884384155, "x": 40.287982695565574, "y": -0.41701344907297067, "z": null, "yaw": 3.546565632991027, "pitch": null, "roll": null}, "v": 0.992416856588242, "accelerator_pedal_position": 0.2613971073626956, "brake_pedal_position": 0.0, "acceleration": 0.12426216601503048, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.2502019508814652, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137702.4675155} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.262308382151976, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.998934494983955, "gear": 1, "accelerator_pedal_position": 0.262308382151976, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137702.4675155} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.209956884384155, "x": 40.287982695565574, "y": -0.41701344907297067, "z": null, "yaw": 3.546565632991027, "pitch": null, "roll": null}, "v": 0.992416856588242, "accelerator_pedal_position": 0.2613971073626956, "brake_pedal_position": 0.0, "acceleration": 0.12426216601503048, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.2502019508814652, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137702.4875154} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.262308382151976, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0015236278274395, "gear": 1, "accelerator_pedal_position": 0.262308382151976, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137702.4875154} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.209956884384155, "x": 40.287982695565574, "y": -0.41701344907297067, "z": null, "yaw": 3.546565632991027, "pitch": null, "roll": null}, "v": 0.992416856588242, "accelerator_pedal_position": 0.2613971073626956, "brake_pedal_position": 0.0, "acceleration": 0.12426216601503048, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.2502019508814652, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137702.5075154} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.262308382151976, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.004109136246899, "gear": 1, "accelerator_pedal_position": 0.262308382151976, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137702.5075154} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137702.5275154, "x": 44.18645404959124, "y": 4.540975374175843, "z": null, "yaw": 3.518833118761494, "pitch": null, "roll": null}, "v": 1.0066910226430152, "accelerator_pedal_position": 0.262308382151976, "brake_pedal_position": 0.0, "acceleration": 0.12895856916699877, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.2538006646380898, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137702.5275154} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26452395315553223, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0066910226430152, "gear": 1, "accelerator_pedal_position": 0.262308382151976, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137702.5275154} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.31995677947998, "x": 40.18645404959124, "y": -0.45902462582415726, "z": null, "yaw": 3.518833118761494, "pitch": null, "roll": null}, "v": 1.0066910226430152, "accelerator_pedal_position": 0.262308382151976, "brake_pedal_position": 0.0, "acceleration": 0.12895856916699877, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.2538006646380898, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137702.5475154} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.263545038038621, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0095461386456142, "gear": 1, "accelerator_pedal_position": 0.26452395315553223, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137702.5475154} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.31995677947998, "x": 40.18645404959124, "y": -0.45902462582415726, "z": null, "yaw": 3.518833118761494, "pitch": null, "roll": null}, "v": 1.0066910226430152, "accelerator_pedal_position": 0.262308382151976, "brake_pedal_position": 0.0, "acceleration": 0.12895856916699877, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.2538006646380898, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137702.5675154} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.263545038038621, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.012274927377016, "gear": 1, "accelerator_pedal_position": 0.263545038038621, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137702.5675154} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.31995677947998, "x": 40.18645404959124, "y": -0.45902462582415726, "z": null, "yaw": 3.518833118761494, "pitch": null, "roll": null}, "v": 1.0066910226430152, "accelerator_pedal_position": 0.262308382151976, "brake_pedal_position": 0.0, "acceleration": 0.12895856916699877, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.2538006646380898, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137702.5875154} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.263545038038621, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0149998844967891, "gear": 1, "accelerator_pedal_position": 0.263545038038621, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137702.5875154} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.31995677947998, "x": 40.18645404959124, "y": -0.45902462582415726, "z": null, "yaw": 3.518833118761494, "pitch": null, "roll": null}, "v": 1.0066910226430152, "accelerator_pedal_position": 0.262308382151976, "brake_pedal_position": 0.0, "acceleration": 0.12895856916699877, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.2538006646380898, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137702.6075153} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.263545038038621, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0177210124159537, "gear": 1, "accelerator_pedal_position": 0.263545038038621, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137702.6075153} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.31995677947998, "x": 40.18645404959124, "y": -0.45902462582415726, "z": null, "yaw": 3.518833118761494, "pitch": null, "roll": null}, "v": 1.0066910226430152, "accelerator_pedal_position": 0.262308382151976, "brake_pedal_position": 0.0, "acceleration": 0.12895856916699877, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.2538006646380898, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137702.6275153} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.263545038038621, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0204383135546564, "gear": 1, "accelerator_pedal_position": 0.263545038038621, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137702.6275153} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137702.6375153, "x": 44.08228872874602, "y": 4.501219167335518, "z": null, "yaw": 3.491100604531961, "pitch": null, "roll": null}, "v": 1.0217955298401158, "accelerator_pedal_position": 0.263545038038621, "brake_pedal_position": 0.0, "acceleration": 0.13562605020136304, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.25760871882694136, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137702.6475153} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26926483581452176, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0231517903421294, "gear": 1, "accelerator_pedal_position": 0.263545038038621, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137702.6475153} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.429956674575806, "x": 40.08228872874602, "y": -0.49878083266448225, "z": null, "yaw": 3.491100604531961, "pitch": null, "roll": null}, "v": 1.0217955298401158, "accelerator_pedal_position": 0.263545038038621, "brake_pedal_position": 0.0, "acceleration": 0.13562605020136304, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.25760871882694136, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137702.6675153} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2666220064682397, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0265761679325094, "gear": 1, "accelerator_pedal_position": 0.26926483581452176, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137702.6675153} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.429956674575806, "x": 40.08228872874602, "y": -0.49878083266448225, "z": null, "yaw": 3.491100604531961, "pitch": null, "roll": null}, "v": 1.0217955298401158, "accelerator_pedal_position": 0.263545038038621, "brake_pedal_position": 0.0, "acceleration": 0.13562605020136304, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.25760871882694136, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137702.6875153} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2666220064682397, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0296654807545018, "gear": 1, "accelerator_pedal_position": 0.2666220064682397, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137702.6875153} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.429956674575806, "x": 40.08228872874602, "y": -0.49878083266448225, "z": null, "yaw": 3.491100604531961, "pitch": null, "roll": null}, "v": 1.0217955298401158, "accelerator_pedal_position": 0.263545038038621, "brake_pedal_position": 0.0, "acceleration": 0.13562605020136304, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.25760871882694136, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137702.7075152} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2666220064682397, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0327504343737444, "gear": 1, "accelerator_pedal_position": 0.2666220064682397, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137702.7075152} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.429956674575806, "x": 40.08228872874602, "y": -0.49878083266448225, "z": null, "yaw": 3.491100604531961, "pitch": null, "roll": null}, "v": 1.0217955298401158, "accelerator_pedal_position": 0.263545038038621, "brake_pedal_position": 0.0, "acceleration": 0.13562605020136304, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.25760871882694136, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137702.7275152} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2666220064682397, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0358310311358978, "gear": 1, "accelerator_pedal_position": 0.2666220064682397, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137702.7275152} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137702.7475152, "x": 43.97540133591943, "y": 4.4637858914553545, "z": null, "yaw": 3.4633680903024278, "pitch": null, "roll": null}, "v": 1.0389072733994298, "accelerator_pedal_position": 0.2666220064682397, "brake_pedal_position": 0.0, "acceleration": 0.15364889352930416, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.2619228249337666, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137702.7475152} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26967433129498847, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0389072733994298, "gear": 1, "accelerator_pedal_position": 0.2666220064682397, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137702.7475152} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.53995656967163, "x": 39.97540133591943, "y": -0.5362141085446455, "z": null, "yaw": 3.4633680903024278, "pitch": null, "roll": null}, "v": 1.0389072733994298, "accelerator_pedal_position": 0.2666220064682397, "brake_pedal_position": 0.0, "acceleration": 0.15364889352930416, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.2619228249337666, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137702.7675152} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2683128966484159, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0423605690529616, "gear": 1, "accelerator_pedal_position": 0.26967433129498847, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137702.7675152} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.53995656967163, "x": 39.97540133591943, "y": -0.5362141085446455, "z": null, "yaw": 3.4633680903024278, "pitch": null, "roll": null}, "v": 1.0389072733994298, "accelerator_pedal_position": 0.2666220064682397, "brake_pedal_position": 0.0, "acceleration": 0.15364889352930416, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.2619228249337666, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137702.7875152} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2683128966484159, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0456388554860374, "gear": 1, "accelerator_pedal_position": 0.2683128966484159, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137702.7875152} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.53995656967163, "x": 39.97540133591943, "y": -0.5362141085446455, "z": null, "yaw": 3.4633680903024278, "pitch": null, "roll": null}, "v": 1.0389072733994298, "accelerator_pedal_position": 0.2666220064682397, "brake_pedal_position": 0.0, "acceleration": 0.15364889352930416, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.2619228249337666, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137702.8075151} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2683128966484159, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0505475732447431, "gear": 1, "accelerator_pedal_position": 0.2683128966484159, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137702.8075151} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.53995656967163, "x": 39.97540133591943, "y": -0.5362141085446455, "z": null, "yaw": 3.4633680903024278, "pitch": null, "roll": null}, "v": 1.0389072733994298, "accelerator_pedal_position": 0.2666220064682397, "brake_pedal_position": 0.0, "acceleration": 0.15364889352930416, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.2619228249337666, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137702.8175151} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2683128966484159, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0505475732447431, "gear": 1, "accelerator_pedal_position": 0.2683128966484159, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137702.8175151} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.53995656967163, "x": 39.97540133591943, "y": -0.5362141085446455, "z": null, "yaw": 3.4633680903024278, "pitch": null, "roll": null}, "v": 1.0389072733994298, "accelerator_pedal_position": 0.2666220064682397, "brake_pedal_position": 0.0, "acceleration": 0.15364889352930416, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.2619228249337666, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137702.847515} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2683128966484159, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0554458436548548, "gear": 1, "accelerator_pedal_position": 0.2683128966484159, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137702.847515} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137702.857515, "x": 43.86566813886469, "y": 4.428740554789001, "z": null, "yaw": 3.4356355760728947, "pitch": null, "roll": null}, "v": 1.0570762801806646, "accelerator_pedal_position": 0.2683128966484159, "brake_pedal_position": 0.0, "acceleration": 0.16292768742236013, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.2665034816528309, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137702.867515} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2721260905303637, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0605719991888547, "gear": 1, "accelerator_pedal_position": 0.2721260905303637, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137702.867515} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.649956464767456, "x": 39.86566813886469, "y": -0.5712594452109991, "z": null, "yaw": 3.4356355760728947, "pitch": null, "roll": null}, "v": 1.0570762801806646, "accelerator_pedal_position": 0.2683128966484159, "brake_pedal_position": 0.0, "acceleration": 0.16292768742236013, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.2665034816528309, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137702.887515} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2704085131368061, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0624371125508616, "gear": 1, "accelerator_pedal_position": 0.2721260905303637, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137702.887515} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.649956464767456, "x": 39.86566813886469, "y": -0.5712594452109991, "z": null, "yaw": 3.4356355760728947, "pitch": null, "roll": null}, "v": 1.0570762801806646, "accelerator_pedal_position": 0.2683128966484159, "brake_pedal_position": 0.0, "acceleration": 0.16292768742236013, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.2665034816528309, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137702.907515} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2704085131368061, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0677026663437321, "gear": 1, "accelerator_pedal_position": 0.2704085131368061, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137702.907515} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.649956464767456, "x": 39.86566813886469, "y": -0.5712594452109991, "z": null, "yaw": 3.4356355760728947, "pitch": null, "roll": null}, "v": 1.0570762801806646, "accelerator_pedal_position": 0.2683128966484159, "brake_pedal_position": 0.0, "acceleration": 0.16292768742236013, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.2665034816528309, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137702.927515} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2704085131368061, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.069455348183239, "gear": 1, "accelerator_pedal_position": 0.2704085131368061, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137702.927515} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.649956464767456, "x": 39.86566813886469, "y": -0.5712594452109991, "z": null, "yaw": 3.4356355760728947, "pitch": null, "roll": null}, "v": 1.0570762801806646, "accelerator_pedal_position": 0.2683128966484159, "brake_pedal_position": 0.0, "acceleration": 0.16292768742236013, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.2665034816528309, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137702.947515} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2704085131368061, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0729569593911592, "gear": 1, "accelerator_pedal_position": 0.2704085131368061, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137702.947515} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137702.967515, "x": 43.753033668162125, "y": 4.3961817922436275, "z": null, "yaw": 3.4079030618433617, "pitch": null, "roll": null}, "v": 1.0764535691703807, "accelerator_pedal_position": 0.2704085131368061, "brake_pedal_position": 0.0, "acceleration": 0.17464300578072234, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.2713887629495314, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137702.967515} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2773346383913051, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0764535691703807, "gear": 1, "accelerator_pedal_position": 0.2704085131368061, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137702.967515} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.75995635986328, "x": 39.753033668162125, "y": -0.6038182077563725, "z": null, "yaw": 3.4079030618433617, "pitch": null, "roll": null}, "v": 1.0764535691703807, "accelerator_pedal_position": 0.2704085131368061, "brake_pedal_position": 0.0, "acceleration": 0.17464300578072234, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.2713887629495314, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137702.987515} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27414179884232, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0808106356255969, "gear": 1, "accelerator_pedal_position": 0.2773346383913051, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137702.987515} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.75995635986328, "x": 39.753033668162125, "y": -0.6038182077563725, "z": null, "yaw": 3.4079030618433617, "pitch": null, "roll": null}, "v": 1.0764535691703807, "accelerator_pedal_position": 0.2704085131368061, "brake_pedal_position": 0.0, "acceleration": 0.17464300578072234, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.2713887629495314, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137703.007515} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27414179884232, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0847625035324324, "gear": 1, "accelerator_pedal_position": 0.27414179884232, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137703.007515} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.75995635986328, "x": 39.753033668162125, "y": -0.6038182077563725, "z": null, "yaw": 3.4079030618433617, "pitch": null, "roll": null}, "v": 1.0764535691703807, "accelerator_pedal_position": 0.2704085131368061, "brake_pedal_position": 0.0, "acceleration": 0.17464300578072234, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.2713887629495314, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137703.027515} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27414179884232, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0887087084286196, "gear": 1, "accelerator_pedal_position": 0.27414179884232, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137703.027515} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.75995635986328, "x": 39.753033668162125, "y": -0.6038182077563725, "z": null, "yaw": 3.4079030618433617, "pitch": null, "roll": null}, "v": 1.0764535691703807, "accelerator_pedal_position": 0.2704085131368061, "brake_pedal_position": 0.0, "acceleration": 0.17464300578072234, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.2713887629495314, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137703.047515} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27414179884232, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.09264925220245, "gear": 1, "accelerator_pedal_position": 0.27414179884232, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137703.047515} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.75995635986328, "x": 39.753033668162125, "y": -0.6038182077563725, "z": null, "yaw": 3.4079030618433617, "pitch": null, "roll": null}, "v": 1.0764535691703807, "accelerator_pedal_position": 0.2704085131368061, "brake_pedal_position": 0.0, "acceleration": 0.17464300578072234, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.2713887629495314, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137703.067515} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27414179884232, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0965841367662976, "gear": 1, "accelerator_pedal_position": 0.27414179884232, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137703.067515} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137703.077515, "x": 43.63732811505842, "y": 4.366186000298468, "z": null, "yaw": 3.3801705476138286, "pitch": null, "roll": null}, "v": 1.0985494574486587, "accelerator_pedal_position": 0.27414179884232, "brake_pedal_position": 0.0, "acceleration": 0.19639066078745943, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.27695944055036326, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137703.0875149} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2770652687568726, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1005133640565332, "gear": 1, "accelerator_pedal_position": 0.27414179884232, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137703.0875149} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.869956254959106, "x": 39.63732811505842, "y": -0.6338139997015322, "z": null, "yaw": 3.3801705476138286, "pitch": null, "roll": null}, "v": 1.0985494574486587, "accelerator_pedal_position": 0.27414179884232, "brake_pedal_position": 0.0, "acceleration": 0.19639066078745943, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.27695944055036326, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137703.1075149} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2757939304979185, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.104802238122798, "gear": 1, "accelerator_pedal_position": 0.2770652687568726, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137703.1075149} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.869956254959106, "x": 39.63732811505842, "y": -0.6338139997015322, "z": null, "yaw": 3.3801705476138286, "pitch": null, "roll": null}, "v": 1.0985494574486587, "accelerator_pedal_position": 0.27414179884232, "brake_pedal_position": 0.0, "acceleration": 0.19639066078745943, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.27695944055036326, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137703.1275148} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2757939304979185, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1089260720775764, "gear": 1, "accelerator_pedal_position": 0.2757939304979185, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137703.1275148} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.869956254959106, "x": 39.63732811505842, "y": -0.6338139997015322, "z": null, "yaw": 3.3801705476138286, "pitch": null, "roll": null}, "v": 1.0985494574486587, "accelerator_pedal_position": 0.27414179884232, "brake_pedal_position": 0.0, "acceleration": 0.19639066078745943, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.27695944055036326, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137703.1475148} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2757939304979185, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1130439568360004, "gear": 1, "accelerator_pedal_position": 0.2757939304979185, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137703.1475148} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.869956254959106, "x": 39.63732811505842, "y": -0.6338139997015322, "z": null, "yaw": 3.3801705476138286, "pitch": null, "roll": null}, "v": 1.0985494574486587, "accelerator_pedal_position": 0.27414179884232, "brake_pedal_position": 0.0, "acceleration": 0.19639066078745943, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.27695944055036326, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137703.1675148} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2757939304979185, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1171558942002608, "gear": 1, "accelerator_pedal_position": 0.2757939304979185, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137703.1675148} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137703.1875148, "x": 43.5184535819713, "y": 4.338862788781374, "z": null, "yaw": 3.3524380333842956, "pitch": null, "roll": null}, "v": 1.1212618859993155, "accelerator_pedal_position": 0.2757939304979185, "brake_pedal_position": 0.0, "acceleration": 0.20507668914207738, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.2826855564409844, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137703.1875148} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28365280804800413, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1212618859993155, "gear": 1, "accelerator_pedal_position": 0.2757939304979185, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137703.1875148} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.97995615005493, "x": 39.5184535819713, "y": -0.6611372112186258, "z": null, "yaw": 3.3524380333842956, "pitch": null, "roll": null}, "v": 1.1212618859993155, "accelerator_pedal_position": 0.2757939304979185, "brake_pedal_position": 0.0, "acceleration": 0.20507668914207738, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.2826855564409844, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137703.2075148} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2800354203213295, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1263439378188007, "gear": 1, "accelerator_pedal_position": 0.28365280804800413, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137703.2075148} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.97995615005493, "x": 39.5184535819713, "y": -0.6611372112186258, "z": null, "yaw": 3.3524380333842956, "pitch": null, "roll": null}, "v": 1.1212618859993155, "accelerator_pedal_position": 0.2757939304979185, "brake_pedal_position": 0.0, "acceleration": 0.20507668914207738, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.2826855564409844, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137703.2275147} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2800354203213295, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1309666138036627, "gear": 1, "accelerator_pedal_position": 0.2800354203213295, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137703.2275147} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.97995615005493, "x": 39.5184535819713, "y": -0.6611372112186258, "z": null, "yaw": 3.3524380333842956, "pitch": null, "roll": null}, "v": 1.1212618859993155, "accelerator_pedal_position": 0.2757939304979185, "brake_pedal_position": 0.0, "acceleration": 0.20507668914207738, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.2826855564409844, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137703.2475147} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2800354203213295, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1355825804495934, "gear": 1, "accelerator_pedal_position": 0.2800354203213295, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137703.2475147} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.97995615005493, "x": 39.5184535819713, "y": -0.6611372112186258, "z": null, "yaw": 3.3524380333842956, "pitch": null, "roll": null}, "v": 1.1212618859993155, "accelerator_pedal_position": 0.2757939304979185, "brake_pedal_position": 0.0, "acceleration": 0.20507668914207738, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.2826855564409844, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137703.2675147} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2800354203213295, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1401918389747456, "gear": 1, "accelerator_pedal_position": 0.2800354203213295, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137703.2675147} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.97995615005493, "x": 39.5184535819713, "y": -0.6611372112186258, "z": null, "yaw": 3.3524380333842956, "pitch": null, "roll": null}, "v": 1.1212618859993155, "accelerator_pedal_position": 0.2757939304979185, "brake_pedal_position": 0.0, "acceleration": 0.20507668914207738, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.2826855564409844, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137703.2875147} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2800354203213295, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1447943906326337, "gear": 1, "accelerator_pedal_position": 0.2800354203213295, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137703.2875147} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137703.2975147, "x": 43.3962449515374, "y": 4.314320367801951, "z": null, "yaw": 3.3247055191547625, "pitch": null, "roll": null}, "v": 1.147093151787718, "accelerator_pedal_position": 0.2800354203213295, "brake_pedal_position": 0.0, "acceleration": 0.22970849243014058, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.2891979741322908, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137703.3075147} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2886102484936504, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1522215723328917, "gear": 1, "accelerator_pedal_position": 0.2886102484936504, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137703.3075147} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.08995604515076, "x": 39.3962449515374, "y": -0.685679632198049, "z": null, "yaw": 3.3247055191547625, "pitch": null, "roll": null}, "v": 1.147093151787718, "accelerator_pedal_position": 0.2800354203213295, "brake_pedal_position": 0.0, "acceleration": 0.22970849243014058, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.2891979741322908, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137703.3275146} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2846700432515362, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1550508406224034, "gear": 1, "accelerator_pedal_position": 0.2886102484936504, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137703.3275146} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.08995604515076, "x": 39.3962449515374, "y": -0.685679632198049, "z": null, "yaw": 3.3247055191547625, "pitch": null, "roll": null}, "v": 1.147093151787718, "accelerator_pedal_position": 0.2800354203213295, "brake_pedal_position": 0.0, "acceleration": 0.22970849243014058, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.2891979741322908, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137703.3475146} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2846700432515362, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.160210829341265, "gear": 1, "accelerator_pedal_position": 0.2846700432515362, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137703.3475146} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.08995604515076, "x": 39.3962449515374, "y": -0.685679632198049, "z": null, "yaw": 3.3247055191547625, "pitch": null, "roll": null}, "v": 1.147093151787718, "accelerator_pedal_position": 0.2800354203213295, "brake_pedal_position": 0.0, "acceleration": 0.22970849243014058, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.2891979741322908, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137703.3675146} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2846700432515362, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.165363268828228, "gear": 1, "accelerator_pedal_position": 0.2846700432515362, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137703.3675146} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.08995604515076, "x": 39.3962449515374, "y": -0.685679632198049, "z": null, "yaw": 3.3247055191547625, "pitch": null, "roll": null}, "v": 1.147093151787718, "accelerator_pedal_position": 0.2800354203213295, "brake_pedal_position": 0.0, "acceleration": 0.22970849243014058, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.2891979741322908, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137703.3875146} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2846700432515362, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1705081595129017, "gear": 1, "accelerator_pedal_position": 0.2846700432515362, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137703.3875146} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137703.4075146, "x": 43.27048552954639, "y": 4.292674587818235, "z": null, "yaw": 3.2969730049252295, "pitch": null, "roll": null}, "v": 1.1756455018709053, "accelerator_pedal_position": 0.2846700432515362, "brake_pedal_position": 0.0, "acceleration": 0.2565840717678631, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.29639641463200517, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137703.4075146} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2919997631232104, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1786694500805637, "gear": 1, "accelerator_pedal_position": 0.2919997631232104, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137703.4075146} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.19995594024658, "x": 39.27048552954639, "y": -0.7073254121817651, "z": null, "yaw": 3.2969730049252295, "pitch": null, "roll": null}, "v": 1.1756455018709053, "accelerator_pedal_position": 0.2846700432515362, "brake_pedal_position": 0.0, "acceleration": 0.2565840717678631, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.29639641463200517, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137703.4275146} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2886687187756353, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1816911743834688, "gear": 1, "accelerator_pedal_position": 0.2919997631232104, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137703.4275146} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.19995594024658, "x": 39.27048552954639, "y": -0.7073254121817651, "z": null, "yaw": 3.2969730049252295, "pitch": null, "roll": null}, "v": 1.1756455018709053, "accelerator_pedal_position": 0.2846700432515362, "brake_pedal_position": 0.0, "acceleration": 0.2565840717678631, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.29639641463200517, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137703.4475145} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2886687187756353, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1873117233843764, "gear": 1, "accelerator_pedal_position": 0.2886687187756353, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137703.4475145} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.19995594024658, "x": 39.27048552954639, "y": -0.7073254121817651, "z": null, "yaw": 3.2969730049252295, "pitch": null, "roll": null}, "v": 1.1756455018709053, "accelerator_pedal_position": 0.2846700432515362, "brake_pedal_position": 0.0, "acceleration": 0.2565840717678631, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.29639641463200517, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137703.4675145} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2886687187756353, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1929239887134249, "gear": 1, "accelerator_pedal_position": 0.2886687187756353, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137703.4675145} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.19995594024658, "x": 39.27048552954639, "y": -0.7073254121817651, "z": null, "yaw": 3.2969730049252295, "pitch": null, "roll": null}, "v": 1.1756455018709053, "accelerator_pedal_position": 0.2846700432515362, "brake_pedal_position": 0.0, "acceleration": 0.2565840717678631, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.29639641463200517, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137703.4875145} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2886687187756353, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1985279699848876, "gear": 1, "accelerator_pedal_position": 0.2886687187756353, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137703.4875145} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.19995594024658, "x": 39.27048552954639, "y": -0.7073254121817651, "z": null, "yaw": 3.2969730049252295, "pitch": null, "roll": null}, "v": 1.1756455018709053, "accelerator_pedal_position": 0.2846700432515362, "brake_pedal_position": 0.0, "acceleration": 0.2565840717678631, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.29639641463200517, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137703.5075145} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2886687187756353, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2097110790935786, "gear": 1, "accelerator_pedal_position": 0.2886687187756353, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137703.5075145} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137703.5175145, "x": 43.1409148076054, "y": 4.274056373354789, "z": null, "yaw": 3.2692404906956964, "pitch": null, "roll": null}, "v": 1.2069184085788875, "accelerator_pedal_position": 0.2886687187756353, "brake_pedal_position": 0.0, "acceleration": 0.27926705146911035, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.3042807449072593, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137703.5275145} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2951501130002343, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2097110790935786, "gear": 1, "accelerator_pedal_position": 0.2886687187756353, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137703.5275145} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.30995583534241, "x": 39.1409148076054, "y": -0.7259436266452113, "z": null, "yaw": 3.2692404906956964, "pitch": null, "roll": null}, "v": 1.2069184085788875, "accelerator_pedal_position": 0.2886687187756353, "brake_pedal_position": 0.0, "acceleration": 0.27926705146911035, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.3042807449072593, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137703.5475144} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29223963752122967, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.216100079924623, "gear": 1, "accelerator_pedal_position": 0.2951501130002343, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137703.5475144} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.30995583534241, "x": 39.1409148076054, "y": -0.7259436266452113, "z": null, "yaw": 3.2692404906956964, "pitch": null, "roll": null}, "v": 1.2069184085788875, "accelerator_pedal_position": 0.2886687187756353, "brake_pedal_position": 0.0, "acceleration": 0.27926705146911035, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.3042807449072593, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137703.5675144} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29223963752122967, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2221159173717446, "gear": 1, "accelerator_pedal_position": 0.29223963752122967, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137703.5675144} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.30995583534241, "x": 39.1409148076054, "y": -0.7259436266452113, "z": null, "yaw": 3.2692404906956964, "pitch": null, "roll": null}, "v": 1.2069184085788875, "accelerator_pedal_position": 0.2886687187756353, "brake_pedal_position": 0.0, "acceleration": 0.27926705146911035, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.3042807449072593, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137703.5875144} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29223963752122967, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2281228051125916, "gear": 1, "accelerator_pedal_position": 0.29223963752122967, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137703.5875144} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.30995583534241, "x": 39.1409148076054, "y": -0.7259436266452113, "z": null, "yaw": 3.2692404906956964, "pitch": null, "roll": null}, "v": 1.2069184085788875, "accelerator_pedal_position": 0.2886687187756353, "brake_pedal_position": 0.0, "acceleration": 0.27926705146911035, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.3042807449072593, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137703.6075144} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29223963752122967, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2341207420338571, "gear": 1, "accelerator_pedal_position": 0.29223963752122967, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137703.6075144} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137703.6275144, "x": 43.00738199425798, "y": 4.258634800395307, "z": null, "yaw": 3.2415079764661634, "pitch": null, "roll": null}, "v": 1.2401097270883623, "accelerator_pedal_position": 0.29223963752122967, "brake_pedal_position": 0.0, "acceleration": 0.2991135268010755, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.31264873320599523, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137703.6275144} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.30589147283408186, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2401097270883623, "gear": 1, "accelerator_pedal_position": 0.29223963752122967, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137703.6275144} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.41995573043823, "x": 39.00738199425798, "y": -0.7413651996046928, "z": null, "yaw": 3.2415079764661634, "pitch": null, "roll": null}, "v": 1.2401097270883623, "accelerator_pedal_position": 0.29223963752122967, "brake_pedal_position": 0.0, "acceleration": 0.2991135268010755, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.31264873320599523, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137703.6475143} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2995789208138424, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2477955998837207, "gear": 1, "accelerator_pedal_position": 0.30589147283408186, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137703.6475143} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.41995573043823, "x": 39.00738199425798, "y": -0.7413651996046928, "z": null, "yaw": 3.2415079764661634, "pitch": null, "roll": null}, "v": 1.2401097270883623, "accelerator_pedal_position": 0.29223963752122967, "brake_pedal_position": 0.0, "acceleration": 0.2991135268010755, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.31264873320599523, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137703.6675143} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2995789208138424, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2546811878819817, "gear": 1, "accelerator_pedal_position": 0.2995789208138424, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137703.6675143} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.41995573043823, "x": 39.00738199425798, "y": -0.7413651996046928, "z": null, "yaw": 3.2415079764661634, "pitch": null, "roll": null}, "v": 1.2401097270883623, "accelerator_pedal_position": 0.29223963752122967, "brake_pedal_position": 0.0, "acceleration": 0.2991135268010755, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.31264873320599523, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137703.6875143} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2995789208138424, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2615564432273214, "gear": 1, "accelerator_pedal_position": 0.2995789208138424, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137703.6875143} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.41995573043823, "x": 39.00738199425798, "y": -0.7413651996046928, "z": null, "yaw": 3.2415079764661634, "pitch": null, "roll": null}, "v": 1.2401097270883623, "accelerator_pedal_position": 0.29223963752122967, "brake_pedal_position": 0.0, "acceleration": 0.2991135268010755, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.31264873320599523, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137703.7075143} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2995789208138424, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2684213625245804, "gear": 1, "accelerator_pedal_position": 0.2995789208138424, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137703.7075143} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.41995573043823, "x": 39.00738199425798, "y": -0.7413651996046928, "z": null, "yaw": 3.2415079764661634, "pitch": null, "roll": null}, "v": 1.2401097270883623, "accelerator_pedal_position": 0.29223963752122967, "brake_pedal_position": 0.0, "acceleration": 0.2991135268010755, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.31264873320599523, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137703.7275143} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2995789208138424, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2752759424689082, "gear": 1, "accelerator_pedal_position": 0.2995789208138424, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137703.7275143} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137703.7375143, "x": 42.86953268663845, "y": 4.246578261499913, "z": null, "yaw": 3.2137754622366304, "pitch": null, "roll": null}, "v": 1.2786993541755949, "accelerator_pedal_position": 0.2995789208138424, "brake_pedal_position": 0.0, "acceleration": 0.3420825669940443, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.3223777094088045, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137703.7475142} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3095368127060639, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.358952224416786, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2821201798455353, "gear": 1, "accelerator_pedal_position": 0.2995789208138424, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137703.7475142} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.52995562553406, "x": 38.86953268663845, "y": -0.7534217385000872, "z": null, "yaw": 3.2137754622366304, "pitch": null, "roll": null}, "v": 1.2786993541755949, "accelerator_pedal_position": 0.2995789208138424, "brake_pedal_position": 0.0, "acceleration": 0.3420825669940443, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.3223777094088045, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137703.7675142} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3050160223379775, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.358952224416786, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.290198336777559, "gear": 1, "accelerator_pedal_position": 0.3095368127060639, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137703.7675142} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.52995562553406, "x": 38.86953268663845, "y": -0.7534217385000872, "z": null, "yaw": 3.2137754622366304, "pitch": null, "roll": null}, "v": 1.2786993541755949, "accelerator_pedal_position": 0.2995789208138424, "brake_pedal_position": 0.0, "acceleration": 0.3420825669940443, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.3223777094088045, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137703.7875142} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3050160223379775, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.358952224416786, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.29769937335553, "gear": 1, "accelerator_pedal_position": 0.3050160223379775, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137703.7875142} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.52995562553406, "x": 38.86953268663845, "y": -0.7534217385000872, "z": null, "yaw": 3.2137754622366304, "pitch": null, "roll": null}, "v": 1.2786993541755949, "accelerator_pedal_position": 0.2995789208138424, "brake_pedal_position": 0.0, "acceleration": 0.3420825669940443, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.3223777094088045, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137703.8075142} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3050160223379775, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.358952224416786, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.308929580256869, "gear": 1, "accelerator_pedal_position": 0.3050160223379775, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137703.8075142} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.52995562553406, "x": 38.86953268663845, "y": -0.7534217385000872, "z": null, "yaw": 3.2137754622366304, "pitch": null, "roll": null}, "v": 1.2786993541755949, "accelerator_pedal_position": 0.2995789208138424, "brake_pedal_position": 0.0, "acceleration": 0.3420825669940443, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.3223777094088045, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137703.8275142} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3050160223379775, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.358952224416786, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.312667287198257, "gear": 1, "accelerator_pedal_position": 0.3050160223379775, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137703.8275142} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137703.8475142, "x": 42.727055208202295, "y": 4.238090324975117, "z": null, "yaw": 3.1860429480070973, "pitch": null, "roll": null}, "v": 1.320134154272668, "accelerator_pedal_position": 0.3050160223379775, "brake_pedal_position": 0.0, "acceleration": 0.3729158900459537, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.3328239928932582, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137703.8475142} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.32078270280903637, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -9.294357495402547, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.320134154272668, "gear": 1, "accelerator_pedal_position": 0.3050160223379775, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.439958915163416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137703.8475142} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.63995552062988, "x": 38.727055208202295, "y": -0.7619096750248833, "z": null, "yaw": 3.1860429480070973, "pitch": null, "roll": null}, "v": 1.320134154272668, "accelerator_pedal_position": 0.3050160223379775, "brake_pedal_position": 0.0, "acceleration": 0.3729158900459537, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.3328239928932582, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137703.8675141} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.31351464649488214, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -9.294357495402547, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3295597028468578, "gear": 1, "accelerator_pedal_position": 0.32078270280903637, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.36469813759867, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137703.8675141} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.63995552062988, "x": 38.727055208202295, "y": -0.7619096750248833, "z": null, "yaw": 3.1860429480070973, "pitch": null, "roll": null}, "v": 1.320134154272668, "accelerator_pedal_position": 0.3050160223379775, "brake_pedal_position": 0.0, "acceleration": 0.3729158900459537, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.3328239928932582, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137703.887514} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.31351464649488214, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -9.294357495402547, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3380626688365211, "gear": 1, "accelerator_pedal_position": 0.31351464649488214, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.289111201208042, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137703.887514} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.63995552062988, "x": 38.727055208202295, "y": -0.7619096750248833, "z": null, "yaw": 3.1860429480070973, "pitch": null, "roll": null}, "v": 1.320134154272668, "accelerator_pedal_position": 0.3050160223379775, "brake_pedal_position": 0.0, "acceleration": 0.3729158900459537, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.3328239928932582, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137703.907514} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.31351464649488214, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -9.294357495402547, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3507926618178905, "gear": 1, "accelerator_pedal_position": 0.31351464649488214, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.175119248823584, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137703.907514} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.63995552062988, "x": 38.727055208202295, "y": -0.7619096750248833, "z": null, "yaw": 3.1860429480070973, "pitch": null, "roll": null}, "v": 1.320134154272668, "accelerator_pedal_position": 0.3050160223379775, "brake_pedal_position": 0.0, "acceleration": 0.3729158900459537, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.3328239928932582, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137703.927514} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.31351464649488214, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -9.294357495402547, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3550294668113896, "gear": 1, "accelerator_pedal_position": 0.31351464649488214, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.13695885194916, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137703.927514} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.63995552062988, "x": 38.727055208202295, "y": -0.7619096750248833, "z": null, "yaw": 3.1860429480070973, "pitch": null, "roll": null}, "v": 1.320134154272668, "accelerator_pedal_position": 0.3050160223379775, "brake_pedal_position": 0.0, "acceleration": 0.3729158900459537, "steering_wheel_angle": -10.439958915163416, "front_wheel_angle": -0.5731426120521247, "heading_rate": -0.3328239928932582, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137703.947514} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.31351464649488214, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -9.294357495402547, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.363493281308533, "gear": 1, "accelerator_pedal_position": 0.31351464649488214, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.060393439080897, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137703.947514} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137703.957514, "x": 42.57949655546732, "y": 4.233370273582826, "z": null, "yaw": 3.1590813554227397, "pitch": null, "roll": null}, "v": 1.3677202886809916, "accelerator_pedal_position": 0.31351464649488214, "brake_pedal_position": 0.0, "acceleration": 0.4223739382782675, "steering_wheel_angle": -10.021988423087063, "front_wheel_angle": -0.5449596716738445, "heading_rate": -0.3238673714398931, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137703.967514} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3274450029819195, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.6757298872218, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3719440280637742, "gear": 1, "accelerator_pedal_position": 0.31351464649488214, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.983501867386758, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137703.967514} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.74995541572571, "x": 38.57949655546732, "y": -0.7666297264171744, "z": null, "yaw": 3.1590813554227397, "pitch": null, "roll": null}, "v": 1.3677202886809916, "accelerator_pedal_position": 0.31351464649488214, "brake_pedal_position": 0.0, "acceleration": 0.4223739382782675, "steering_wheel_angle": -10.021988423087063, "front_wheel_angle": -0.5449596716738445, "heading_rate": -0.3238673714398931, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137703.987514} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.32109022835633527, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.6757298872218, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3821223182287732, "gear": 1, "accelerator_pedal_position": 0.3274450029819195, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.91197145795197, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137703.987514} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.74995541572571, "x": 38.57949655546732, "y": -0.7666297264171744, "z": null, "yaw": 3.1590813554227397, "pitch": null, "roll": null}, "v": 1.3677202886809916, "accelerator_pedal_position": 0.31351464649488214, "brake_pedal_position": 0.0, "acceleration": 0.4223739382782675, "steering_wheel_angle": -10.021988423087063, "front_wheel_angle": -0.5449596716738445, "heading_rate": -0.3238673714398931, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137704.007514} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.32109022835633527, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.6757298872218, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3914907814733335, "gear": 1, "accelerator_pedal_position": 0.32109022835633527, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.840161078614173, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137704.007514} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.74995541572571, "x": 38.57949655546732, "y": -0.7666297264171744, "z": null, "yaw": 3.1590813554227397, "pitch": null, "roll": null}, "v": 1.3677202886809916, "accelerator_pedal_position": 0.31351464649488214, "brake_pedal_position": 0.0, "acceleration": 0.4223739382782675, "steering_wheel_angle": -10.021988423087063, "front_wheel_angle": -0.5449596716738445, "heading_rate": -0.3238673714398931, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137704.027514} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.32109022835633527, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.6757298872218, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4008446762508697, "gear": 1, "accelerator_pedal_position": 0.32109022835633527, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.768070729373363, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137704.027514} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.74995541572571, "x": 38.57949655546732, "y": -0.7666297264171744, "z": null, "yaw": 3.1590813554227397, "pitch": null, "roll": null}, "v": 1.3677202886809916, "accelerator_pedal_position": 0.31351464649488214, "brake_pedal_position": 0.0, "acceleration": 0.4223739382782675, "steering_wheel_angle": -10.021988423087063, "front_wheel_angle": -0.5449596716738445, "heading_rate": -0.3238673714398931, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137704.047514} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.32109022835633527, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.6757298872218, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4101839902316384, "gear": 1, "accelerator_pedal_position": 0.32109022835633527, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.695700410229538, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137704.047514} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137704.067514, "x": 42.42645634598359, "y": 4.232488245269339, "z": null, "yaw": 3.133734479718361, "pitch": null, "roll": null}, "v": 1.4195087112686182, "accelerator_pedal_position": 0.32109022835633527, "brake_pedal_position": 0.0, "acceleration": 0.4656884418499894, "steering_wheel_angle": -9.6230501211827, "front_wheel_angle": -0.5186601001292904, "heading_rate": -0.3164972319821525, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137704.067514} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3369341016976882, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.302108164754769, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4195087112686182, "gear": 1, "accelerator_pedal_position": 0.32109022835633527, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.6230501211827, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137704.067514} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.85995531082153, "x": 38.42645634598359, "y": -0.7675117547306609, "z": null, "yaw": 3.133734479718361, "pitch": null, "roll": null}, "v": 1.4195087112686182, "accelerator_pedal_position": 0.32109022835633527, "brake_pedal_position": 0.0, "acceleration": 0.4656884418499894, "steering_wheel_angle": -9.6230501211827, "front_wheel_angle": -0.5186601001292904, "heading_rate": -0.3164972319821525, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137704.087514} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.32969666377209306, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.302108164754769, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4307985342919796, "gear": 1, "accelerator_pedal_position": 0.3369341016976882, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.554150308295416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137704.087514} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.85995531082153, "x": 38.42645634598359, "y": -0.7675117547306609, "z": null, "yaw": 3.133734479718361, "pitch": null, "roll": null}, "v": 1.4195087112686182, "accelerator_pedal_position": 0.32109022835633527, "brake_pedal_position": 0.0, "acceleration": 0.4656884418499894, "steering_wheel_angle": -9.6230501211827, "front_wheel_angle": -0.5186601001292904, "heading_rate": -0.3164972319821525, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137704.107514} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.32969666377209306, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.302108164754769, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4411663021863583, "gear": 1, "accelerator_pedal_position": 0.32969666377209306, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.485000562239293, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137704.107514} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.85995531082153, "x": 38.42645634598359, "y": -0.7675117547306609, "z": null, "yaw": 3.133734479718361, "pitch": null, "roll": null}, "v": 1.4195087112686182, "accelerator_pedal_position": 0.32109022835633527, "brake_pedal_position": 0.0, "acceleration": 0.4656884418499894, "steering_wheel_angle": -9.6230501211827, "front_wheel_angle": -0.5186601001292904, "heading_rate": -0.3164972319821525, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137704.127514} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.32969666377209306, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.302108164754769, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4515177428281876, "gear": 1, "accelerator_pedal_position": 0.32969666377209306, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.415600883014323, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137704.127514} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.85995531082153, "x": 38.42645634598359, "y": -0.7675117547306609, "z": null, "yaw": 3.133734479718361, "pitch": null, "roll": null}, "v": 1.4195087112686182, "accelerator_pedal_position": 0.32109022835633527, "brake_pedal_position": 0.0, "acceleration": 0.4656884418499894, "steering_wheel_angle": -9.6230501211827, "front_wheel_angle": -0.5186601001292904, "heading_rate": -0.3164972319821525, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137704.1475139} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.32969666377209306, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.302108164754769, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4618528390857628, "gear": 1, "accelerator_pedal_position": 0.32969666377209306, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.34595127062051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137704.1475139} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.85995531082153, "x": 38.42645634598359, "y": -0.7675117547306609, "z": null, "yaw": 3.133734479718361, "pitch": null, "roll": null}, "v": 1.4195087112686182, "accelerator_pedal_position": 0.32109022835633527, "brake_pedal_position": 0.0, "acceleration": 0.4656884418499894, "steering_wheel_angle": -9.6230501211827, "front_wheel_angle": -0.5186601001292904, "heading_rate": -0.3164972319821525, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137704.1675138} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.32969666377209306, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.302108164754769, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4721715740572416, "gear": 1, "accelerator_pedal_position": 0.32969666377209306, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.27605172505786, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137704.1675138} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137704.1775138, "x": 42.267406547785605, "y": 4.235496551087422, "z": null, "yaw": 3.109841829843897, "pitch": null, "roll": null}, "v": 1.4773248008416227, "accelerator_pedal_position": 0.32969666377209306, "brake_pedal_position": 0.0, "acceleration": 0.514913022861683, "steering_wheel_angle": -9.241008227338217, "front_wheel_angle": -0.4939892745923293, "heading_rate": -0.3107710466498059, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137704.1875138} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3465631398974567, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.601615363952598, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4824739310702395, "gear": 1, "accelerator_pedal_position": 0.32969666377209306, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.205902246326362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137704.1875138} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.96995520591736, "x": 38.267406547785605, "y": -0.7645034489125777, "z": null, "yaw": 3.109841829843897, "pitch": null, "roll": null}, "v": 1.4773248008416227, "accelerator_pedal_position": 0.32969666377209306, "brake_pedal_position": 0.0, "acceleration": 0.514913022861683, "steering_wheel_angle": -9.241008227338217, "front_wheel_angle": -0.4939892745923293, "heading_rate": -0.3107710466498059, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137704.2075138} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.338879339072645, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.601615363952598, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.494867362372467, "gear": 1, "accelerator_pedal_position": 0.3465631398974567, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.139765500063051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137704.2075138} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.96995520591736, "x": 38.267406547785605, "y": -0.7645034489125777, "z": null, "yaw": 3.109841829843897, "pitch": null, "roll": null}, "v": 1.4773248008416227, "accelerator_pedal_position": 0.32969666377209306, "brake_pedal_position": 0.0, "acceleration": 0.514913022861683, "steering_wheel_angle": -9.241008227338217, "front_wheel_angle": -0.4939892745923293, "heading_rate": -0.3107710466498059, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137704.2275138} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.338879339072645, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.601615363952598, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.506280922059394, "gear": 1, "accelerator_pedal_position": 0.338879339072645, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.07340812373578, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137704.2275138} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.96995520591736, "x": 38.267406547785605, "y": -0.7645034489125777, "z": null, "yaw": 3.109841829843897, "pitch": null, "roll": null}, "v": 1.4773248008416227, "accelerator_pedal_position": 0.32969666377209306, "brake_pedal_position": 0.0, "acceleration": 0.514913022861683, "steering_wheel_angle": -9.241008227338217, "front_wheel_angle": -0.4939892745923293, "heading_rate": -0.3107710466498059, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137704.2475138} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.338879339072645, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.601615363952598, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5176762117250922, "gear": 1, "accelerator_pedal_position": 0.338879339072645, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.006830117344556, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137704.2475138} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.96995520591736, "x": 38.267406547785605, "y": -0.7645034489125777, "z": null, "yaw": 3.109841829843897, "pitch": null, "roll": null}, "v": 1.4773248008416227, "accelerator_pedal_position": 0.32969666377209306, "brake_pedal_position": 0.0, "acceleration": 0.514913022861683, "steering_wheel_angle": -9.241008227338217, "front_wheel_angle": -0.4939892745923293, "heading_rate": -0.3107710466498059, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137704.2675138} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.338879339072645, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.601615363952598, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5290532086947237, "gear": 1, "accelerator_pedal_position": 0.338879339072645, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.94003148088938, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137704.2675138} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137704.2875137, "x": 42.10188735581583, "y": 4.242483359218454, "z": null, "yaw": 3.0872883699777796, "pitch": null, "roll": null}, "v": 1.5404118905797124, "accelerator_pedal_position": 0.338879339072645, "brake_pedal_position": 0.0, "acceleration": 0.5672465867486518, "steering_wheel_angle": -8.873012214370247, "front_wheel_angle": -0.47067419876040106, "heading_rate": -0.30616549778671015, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137704.2875137} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.355806199328354, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.365803491190441, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5404118905797124, "gear": 1, "accelerator_pedal_position": 0.338879339072645, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.873012214370247, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137704.2875137} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.079955101013184, "x": 38.10188735581583, "y": -0.7575166407815459, "z": null, "yaw": 3.0872883699777796, "pitch": null, "roll": null}, "v": 1.5404118905797124, "accelerator_pedal_position": 0.338879339072645, "brake_pedal_position": 0.0, "acceleration": 0.5672465867486518, "steering_wheel_angle": -8.873012214370247, "front_wheel_angle": -0.47067419876040106, "heading_rate": -0.30616549778671015, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137704.3075137} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3481311692195449, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.365803491190441, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5538672366035267, "gear": 1, "accelerator_pedal_position": 0.355806199328354, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.808470200294403, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137704.3075137} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.079955101013184, "x": 38.10188735581583, "y": -0.7575166407815459, "z": null, "yaw": 3.0872883699777796, "pitch": null, "roll": null}, "v": 1.5404118905797124, "accelerator_pedal_position": 0.338879339072645, "brake_pedal_position": 0.0, "acceleration": 0.5672465867486518, "steering_wheel_angle": -8.873012214370247, "front_wheel_angle": -0.47067419876040106, "heading_rate": -0.30616549778671015, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137704.3275137} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3481311692195449, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.365803491190441, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5663418018724362, "gear": 1, "accelerator_pedal_position": 0.3481311692195449, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.743724879030715, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137704.3275137} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.079955101013184, "x": 38.10188735581583, "y": -0.7575166407815459, "z": null, "yaw": 3.0872883699777796, "pitch": null, "roll": null}, "v": 1.5404118905797124, "accelerator_pedal_position": 0.338879339072645, "brake_pedal_position": 0.0, "acceleration": 0.5672465867486518, "steering_wheel_angle": -8.873012214370247, "front_wheel_angle": -0.47067419876040106, "heading_rate": -0.30616549778671015, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137704.3475137} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3481311692195449, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.365803491190441, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5787961006087432, "gear": 1, "accelerator_pedal_position": 0.3481311692195449, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.678776250579174, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137704.3475137} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.079955101013184, "x": 38.10188735581583, "y": -0.7575166407815459, "z": null, "yaw": 3.0872883699777796, "pitch": null, "roll": null}, "v": 1.5404118905797124, "accelerator_pedal_position": 0.338879339072645, "brake_pedal_position": 0.0, "acceleration": 0.5672465867486518, "steering_wheel_angle": -8.873012214370247, "front_wheel_angle": -0.47067419876040106, "heading_rate": -0.30616549778671015, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137704.3675137} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3481311692195449, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.365803491190441, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.597439485419558, "gear": 1, "accelerator_pedal_position": 0.3481311692195449, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.58097210692465, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137704.3675137} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.079955101013184, "x": 38.10188735581583, "y": -0.7575166407815459, "z": null, "yaw": 3.0872883699777796, "pitch": null, "roll": null}, "v": 1.5404118905797124, "accelerator_pedal_position": 0.338879339072645, "brake_pedal_position": 0.0, "acceleration": 0.5672465867486518, "steering_wheel_angle": -8.873012214370247, "front_wheel_angle": -0.47067419876040106, "heading_rate": -0.30616549778671015, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137704.3875136} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3481311692195449, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.365803491190441, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.603643782462112, "gear": 1, "accelerator_pedal_position": 0.3481311692195449, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.548269072112552, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137704.3875136} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137704.3975136, "x": 41.929280954874905, "y": 4.253574969577048, "z": null, "yaw": 3.0659684835699803, "pitch": null, "roll": null}, "v": 1.6098429913089995, "accelerator_pedal_position": 0.3481311692195449, "brake_pedal_position": 0.0, "acceleration": 0.6194117134900385, "steering_wheel_angle": -8.51551521050349, "front_wheel_angle": -0.4484232721675711, "heading_rate": -0.3025447729341533, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137704.4075136} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3693210735087848, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.8148642960265657, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6160371084439, "gear": 1, "accelerator_pedal_position": 0.3481311692195449, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.482710522097465, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137704.4075136} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.18995499610901, "x": 37.929280954874905, "y": -0.7464250304229516, "z": null, "yaw": 3.0659684835699803, "pitch": null, "roll": null}, "v": 1.6098429913089995, "accelerator_pedal_position": 0.3481311692195449, "brake_pedal_position": 0.0, "acceleration": 0.6194117134900385, "steering_wheel_angle": -8.51551521050349, "front_wheel_angle": -0.4484232721675711, "heading_rate": -0.3025447729341533, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137704.4275136} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.35966178562594764, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.8148642960265657, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6310576996125872, "gear": 1, "accelerator_pedal_position": 0.3693210735087848, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.419971754620633, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137704.4275136} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.18995499610901, "x": 37.929280954874905, "y": -0.7464250304229516, "z": null, "yaw": 3.0659684835699803, "pitch": null, "roll": null}, "v": 1.6098429913089995, "accelerator_pedal_position": 0.3481311692195449, "brake_pedal_position": 0.0, "acceleration": 0.6194117134900385, "steering_wheel_angle": -8.51551521050349, "front_wheel_angle": -0.4484232721675711, "heading_rate": -0.3025447729341533, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137704.4475136} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.35966178562594764, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.8148642960265657, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.644846591887992, "gear": 1, "accelerator_pedal_position": 0.35966178562594764, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.357047916220264, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137704.4475136} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.18995499610901, "x": 37.929280954874905, "y": -0.7464250304229516, "z": null, "yaw": 3.0659684835699803, "pitch": null, "roll": null}, "v": 1.6098429913089995, "accelerator_pedal_position": 0.3481311692195449, "brake_pedal_position": 0.0, "acceleration": 0.6194117134900385, "steering_wheel_angle": -8.51551521050349, "front_wheel_angle": -0.4484232721675711, "heading_rate": -0.3025447729341533, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137704.4675136} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.35966178562594764, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.8148642960265657, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6586126515071837, "gear": 1, "accelerator_pedal_position": 0.35966178562594764, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.293939006896364, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137704.4675136} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.18995499610901, "x": 37.929280954874905, "y": -0.7464250304229516, "z": null, "yaw": 3.0659684835699803, "pitch": null, "roll": null}, "v": 1.6098429913089995, "accelerator_pedal_position": 0.3481311692195449, "brake_pedal_position": 0.0, "acceleration": 0.6194117134900385, "steering_wheel_angle": -8.51551521050349, "front_wheel_angle": -0.4484232721675711, "heading_rate": -0.3025447729341533, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137704.4875135} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.35966178562594764, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.8148642960265657, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6723558405078829, "gear": 1, "accelerator_pedal_position": 0.35966178562594764, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.23064502664893, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137704.4875135} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137704.5075135, "x": 41.749029521542404, "y": 4.268925783706423, "z": null, "yaw": 3.045807483802307, "pitch": null, "roll": null}, "v": 1.6860761213682132, "accelerator_pedal_position": 0.35966178562594764, "brake_pedal_position": 0.0, "acceleration": 0.6851538272232811, "steering_wheel_angle": -8.16716597547796, "front_wheel_angle": -0.42710086788981627, "heading_rate": -0.29975058452384523, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137704.5075135} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3850523667486503, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.3489211647993496, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6860761213682132, "gear": 1, "accelerator_pedal_position": 0.35966178562594764, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.16716597547796, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137704.5075135} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.299954891204834, "x": 37.749029521542404, "y": -0.7310742162935773, "z": null, "yaw": 3.045807483802307, "pitch": null, "roll": null}, "v": 1.6860761213682132, "accelerator_pedal_position": 0.35966178562594764, "brake_pedal_position": 0.0, "acceleration": 0.6851538272232811, "steering_wheel_angle": -8.16716597547796, "front_wheel_angle": -0.42710086788981627, "heading_rate": -0.29975058452384523, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137704.5275135} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3734434548001493, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.3489211647993496, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7029459486338054, "gear": 1, "accelerator_pedal_position": 0.3850523667486503, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.106043873889039, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137704.5275135} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.299954891204834, "x": 37.749029521542404, "y": -0.7310742162935773, "z": null, "yaw": 3.045807483802307, "pitch": null, "roll": null}, "v": 1.6860761213682132, "accelerator_pedal_position": 0.35966178562594764, "brake_pedal_position": 0.0, "acceleration": 0.6851538272232811, "steering_wheel_angle": -8.16716597547796, "front_wheel_angle": -0.42710086788981627, "heading_rate": -0.29975058452384523, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137704.5475135} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3734434548001493, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.3489211647993496, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7183369521493306, "gear": 1, "accelerator_pedal_position": 0.3734434548001493, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.044751165797486, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137704.5475135} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.299954891204834, "x": 37.749029521542404, "y": -0.7310742162935773, "z": null, "yaw": 3.045807483802307, "pitch": null, "roll": null}, "v": 1.6860761213682132, "accelerator_pedal_position": 0.35966178562594764, "brake_pedal_position": 0.0, "acceleration": 0.6851538272232811, "steering_wheel_angle": -8.16716597547796, "front_wheel_angle": -0.42710086788981627, "heading_rate": -0.29975058452384523, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137704.5675135} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3734434548001493, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.3489211647993496, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7337020205225229, "gear": 1, "accelerator_pedal_position": 0.3734434548001493, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.9832878512033005, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137704.5675135} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.299954891204834, "x": 37.749029521542404, "y": -0.7310742162935773, "z": null, "yaw": 3.045807483802307, "pitch": null, "roll": null}, "v": 1.6860761213682132, "accelerator_pedal_position": 0.35966178562594764, "brake_pedal_position": 0.0, "acceleration": 0.6851538272232811, "steering_wheel_angle": -8.16716597547796, "front_wheel_angle": -0.42710086788981627, "heading_rate": -0.29975058452384523, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137704.5875134} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3734434548001493, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.3489211647993496, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7490411030621065, "gear": 1, "accelerator_pedal_position": 0.3734434548001493, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.921653930106481, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137704.5875134} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.299954891204834, "x": 37.749029521542404, "y": -0.7310742162935773, "z": null, "yaw": 3.045807483802307, "pitch": null, "roll": null}, "v": 1.6860761213682132, "accelerator_pedal_position": 0.35966178562594764, "brake_pedal_position": 0.0, "acceleration": 0.6851538272232811, "steering_wheel_angle": -8.16716597547796, "front_wheel_angle": -0.42710086788981627, "heading_rate": -0.29975058452384523, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137704.6075134} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3734434548001493, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.3489211647993496, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7643541496410255, "gear": 1, "accelerator_pedal_position": 0.3734434548001493, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.859849402507029, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137704.6075134} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137704.6175134, "x": 41.560233242573666, "y": 4.288750410464625, "z": null, "yaw": 3.0267294643269493, "pitch": null, "roll": null}, "v": 1.7720008939346787, "accelerator_pedal_position": 0.3734434548001493, "brake_pedal_position": 0.0, "acceleration": 0.764021676123146, "steering_wheel_angle": -7.8288831612688154, "front_wheel_angle": -0.4067178012451142, "heading_rate": -0.2981492073631407, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137704.6275134} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3268978803300253, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8842873902793347, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7796411106959102, "gear": 1, "accelerator_pedal_position": 0.3734434548001493, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.797874268404945, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137704.6275134} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.40995478630066, "x": 37.560233242573666, "y": -0.7112495895353748, "z": null, "yaw": 3.0267294643269493, "pitch": null, "roll": null}, "v": 1.7720008939346787, "accelerator_pedal_position": 0.3734434548001493, "brake_pedal_position": 0.0, "acceleration": 0.764021676123146, "steering_wheel_angle": -7.8288831612688154, "front_wheel_angle": -0.4067178012451142, "heading_rate": -0.2981492073631407, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137704.6475134} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3496161715932554, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8842873902793347, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7890862339923246, "gear": 1, "accelerator_pedal_position": 0.3268978803300253, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.734751489862406, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137704.6475134} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.40995478630066, "x": 37.560233242573666, "y": -0.7112495895353748, "z": null, "yaw": 3.0267294643269493, "pitch": null, "roll": null}, "v": 1.7720008939346787, "accelerator_pedal_position": 0.3734434548001493, "brake_pedal_position": 0.0, "acceleration": 0.764021676123146, "steering_wheel_angle": -7.8288831612688154, "front_wheel_angle": -0.4067178012451142, "heading_rate": -0.2981492073631407, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137704.6675134} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3496161715932554, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8842873902793347, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8013537356348475, "gear": 1, "accelerator_pedal_position": 0.3496161715932554, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.671452705778603, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137704.6675134} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.40995478630066, "x": 37.560233242573666, "y": -0.7112495895353748, "z": null, "yaw": 3.0267294643269493, "pitch": null, "roll": null}, "v": 1.7720008939346787, "accelerator_pedal_position": 0.3734434548001493, "brake_pedal_position": 0.0, "acceleration": 0.764021676123146, "steering_wheel_angle": -7.8288831612688154, "front_wheel_angle": -0.4067178012451142, "heading_rate": -0.2981492073631407, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137704.6875134} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3496161715932554, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8842873902793347, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.813600154653195, "gear": 1, "accelerator_pedal_position": 0.3496161715932554, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.60797791615353, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137704.6875134} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.40995478630066, "x": 37.560233242573666, "y": -0.7112495895353748, "z": null, "yaw": 3.0267294643269493, "pitch": null, "roll": null}, "v": 1.7720008939346787, "accelerator_pedal_position": 0.3734434548001493, "brake_pedal_position": 0.0, "acceleration": 0.764021676123146, "steering_wheel_angle": -7.8288831612688154, "front_wheel_angle": -0.4067178012451142, "heading_rate": -0.2981492073631407, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137704.7075133} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3496161715932554, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8842873902793347, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8258254673153862, "gear": 1, "accelerator_pedal_position": 0.3496161715932554, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.544327120987192, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137704.7075133} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137704.7275133, "x": 41.36353597517628, "y": 4.31310693659543, "z": null, "yaw": 3.00869671028852, "pitch": null, "roll": null}, "v": 1.8380296502401587, "accelerator_pedal_position": 0.3496161715932554, "brake_pedal_position": 0.0, "acceleration": 0.6094160599942187, "steering_wheel_angle": -7.480500320279587, "front_wheel_angle": -0.38604381576876723, "heading_rate": -0.29181431368386096, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137704.7275133} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2841648556083542, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.989465271486398, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8380296502401587, "gear": 1, "accelerator_pedal_position": 0.3496161715932554, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.480500320279587, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137704.7275133} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.519954681396484, "x": 37.36353597517628, "y": -0.68689306340457, "z": null, "yaw": 3.00869671028852, "pitch": null, "roll": null}, "v": 1.8380296502401587, "accelerator_pedal_position": 0.3496161715932554, "brake_pedal_position": 0.0, "acceleration": 0.6094160599942187, "steering_wheel_angle": -7.480500320279587, "front_wheel_angle": -0.38604381576876723, "heading_rate": -0.29181431368386096, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137704.7475133} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3157653148982765, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.989465271486398, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8420348183325401, "gear": 1, "accelerator_pedal_position": 0.2841648556083542, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.414455931709232, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137704.7475133} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.519954681396484, "x": 37.36353597517628, "y": -0.68689306340457, "z": null, "yaw": 3.00869671028852, "pitch": null, "roll": null}, "v": 1.8380296502401587, "accelerator_pedal_position": 0.3496161715932554, "brake_pedal_position": 0.0, "acceleration": 0.6094160599942187, "steering_wheel_angle": -7.480500320279587, "front_wheel_angle": -0.38604381576876723, "heading_rate": -0.29181431368386096, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137704.7675133} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3157653148982765, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.989465271486398, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8499813759195398, "gear": 1, "accelerator_pedal_position": 0.3157653148982765, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.348224146362853, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137704.7675133} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.519954681396484, "x": 37.36353597517628, "y": -0.68689306340457, "z": null, "yaw": 3.00869671028852, "pitch": null, "roll": null}, "v": 1.8380296502401587, "accelerator_pedal_position": 0.3496161715932554, "brake_pedal_position": 0.0, "acceleration": 0.6094160599942187, "steering_wheel_angle": -7.480500320279587, "front_wheel_angle": -0.38604381576876723, "heading_rate": -0.29181431368386096, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137704.7875133} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3157653148982765, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.989465271486398, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8579141188822608, "gear": 1, "accelerator_pedal_position": 0.3157653148982765, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.2818049642404485, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137704.7875133} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.519954681396484, "x": 37.36353597517628, "y": -0.68689306340457, "z": null, "yaw": 3.00869671028852, "pitch": null, "roll": null}, "v": 1.8380296502401587, "accelerator_pedal_position": 0.3496161715932554, "brake_pedal_position": 0.0, "acceleration": 0.6094160599942187, "steering_wheel_angle": -7.480500320279587, "front_wheel_angle": -0.38604381576876723, "heading_rate": -0.29181431368386096, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137704.8075132} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3157653148982765, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.989465271486398, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.865833046076213, "gear": 1, "accelerator_pedal_position": 0.3157653148982765, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.2151983853420205, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137704.8075132} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.519954681396484, "x": 37.36353597517628, "y": -0.68689306340457, "z": null, "yaw": 3.00869671028852, "pitch": null, "roll": null}, "v": 1.8380296502401587, "accelerator_pedal_position": 0.3496161715932554, "brake_pedal_position": 0.0, "acceleration": 0.6094160599942187, "steering_wheel_angle": -7.480500320279587, "front_wheel_angle": -0.38604381576876723, "heading_rate": -0.29181431368386096, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137704.8275132} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3157653148982765, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.989465271486398, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.873738156490298, "gear": 1, "accelerator_pedal_position": 0.3157653148982765, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.148404409667568, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137704.8275132} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137704.8375132, "x": 41.16156331356984, "y": 4.3417203294258515, "z": null, "yaw": 2.991716112694061, "pitch": null, "roll": null}, "v": 1.8776855301252864, "accelerator_pedal_position": 0.3157653148982765, "brake_pedal_position": 0.0, "acceleration": 0.39439191210754476, "steering_wheel_angle": -7.114937148039333, "front_wheel_angle": -0.36468128054290005, "heading_rate": -0.2800075405279551, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137704.8475132} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25974174814787093, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.9684728834072405, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8816294492463619, "gear": 1, "accelerator_pedal_position": 0.3157653148982765, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.081423037217092, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137704.8475132} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.62995457649231, "x": 37.16156331356984, "y": -0.6582796705741485, "z": null, "yaw": 2.991716112694061, "pitch": null, "roll": null}, "v": 1.8776855301252864, "accelerator_pedal_position": 0.3157653148982765, "brake_pedal_position": 0.0, "acceleration": 0.39439191210754476, "steering_wheel_angle": -7.114937148039333, "front_wheel_angle": -0.36468128054290005, "heading_rate": -0.2800075405279551, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137704.8675132} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2866829871858609, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.9684728834072405, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8825070477197725, "gear": 1, "accelerator_pedal_position": 0.25974174814787093, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.012238952858787, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137704.8675132} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.62995457649231, "x": 37.16156331356984, "y": -0.6582796705741485, "z": null, "yaw": 2.991716112694061, "pitch": null, "roll": null}, "v": 1.8776855301252864, "accelerator_pedal_position": 0.3157653148982765, "brake_pedal_position": 0.0, "acceleration": 0.39439191210754476, "steering_wheel_angle": -7.114937148039333, "front_wheel_angle": -0.36468128054290005, "heading_rate": -0.2800075405279551, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137704.8875132} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2866829871858609, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.9684728834072405, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8867492870833071, "gear": 1, "accelerator_pedal_position": 0.2866829871858609, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.942856074429421, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137704.8875132} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.62995457649231, "x": 37.16156331356984, "y": -0.6582796705741485, "z": null, "yaw": 2.991716112694061, "pitch": null, "roll": null}, "v": 1.8776855301252864, "accelerator_pedal_position": 0.3157653148982765, "brake_pedal_position": 0.0, "acceleration": 0.39439191210754476, "steering_wheel_angle": -7.114937148039333, "front_wheel_angle": -0.36468128054290005, "heading_rate": -0.2800075405279551, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137704.9075131} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2866829871858609, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.9684728834072405, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8909840876549424, "gear": 1, "accelerator_pedal_position": 0.2866829871858609, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.8732744019289935, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137704.9075131} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.62995457649231, "x": 37.16156331356984, "y": -0.6582796705741485, "z": null, "yaw": 2.991716112694061, "pitch": null, "roll": null}, "v": 1.8776855301252864, "accelerator_pedal_position": 0.3157653148982765, "brake_pedal_position": 0.0, "acceleration": 0.39439191210754476, "steering_wheel_angle": -7.114937148039333, "front_wheel_angle": -0.36468128054290005, "heading_rate": -0.2800075405279551, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137704.9275131} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2866829871858609, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.9684728834072405, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8973223536338055, "gear": 1, "accelerator_pedal_position": 0.2866829871858609, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.768529154295111, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137704.9275131} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137704.947513, "x": 40.95651831688222, "y": 4.374224606365354, "z": null, "yaw": 2.975799701928147, "pitch": null, "roll": null}, "v": 1.899431395944745, "accelerator_pedal_position": 0.2866829871858609, "brake_pedal_position": 0.0, "acceleration": 0.21071870383538716, "steering_wheel_angle": -6.733514674714953, "front_wheel_angle": -0.34273689382654704, "heading_rate": -0.26474751927235524, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137704.947513} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2464553507099414, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.8537040595964127, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.899431395944745, "gear": 1, "accelerator_pedal_position": 0.2866829871858609, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.733514674714953, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137704.947513} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.739954471588135, "x": 36.95651831688222, "y": -0.6257753936346457, "z": null, "yaw": 2.975799701928147, "pitch": null, "roll": null}, "v": 1.899431395944745, "accelerator_pedal_position": 0.2866829871858609, "brake_pedal_position": 0.0, "acceleration": 0.21071870383538716, "steering_wheel_angle": -6.733514674714953, "front_wheel_angle": -0.34273689382654704, "heading_rate": -0.26474751927235524, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137704.967513} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26575679944092934, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.8537040595964127, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9002170021798421, "gear": 1, "accelerator_pedal_position": 0.26575679944092934, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.588916166765429, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137704.967513} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.739954471588135, "x": 36.95651831688222, "y": -0.6257753936346457, "z": null, "yaw": 2.975799701928147, "pitch": null, "roll": null}, "v": 1.899431395944745, "accelerator_pedal_position": 0.2866829871858609, "brake_pedal_position": 0.0, "acceleration": 0.21071870383538716, "steering_wheel_angle": -6.733514674714953, "front_wheel_angle": -0.34273689382654704, "heading_rate": -0.26474751927235524, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137704.987513} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26575679944092934, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.8537040595964127, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9018135173023476, "gear": 1, "accelerator_pedal_position": 0.26575679944092934, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.516301368860232, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137704.987513} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.739954471588135, "x": 36.95651831688222, "y": -0.6257753936346457, "z": null, "yaw": 2.975799701928147, "pitch": null, "roll": null}, "v": 1.899431395944745, "accelerator_pedal_position": 0.2866829871858609, "brake_pedal_position": 0.0, "acceleration": 0.21071870383538716, "steering_wheel_angle": -6.733514674714953, "front_wheel_angle": -0.34273689382654704, "heading_rate": -0.26474751927235524, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137705.017513} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26575679944092934, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.8537040595964127, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9049981228782231, "gear": 1, "accelerator_pedal_position": 0.26575679944092934, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.370440685188967, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137705.017513} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.739954471588135, "x": 36.95651831688222, "y": -0.6257753936346457, "z": null, "yaw": 2.975799701928147, "pitch": null, "roll": null}, "v": 1.899431395944745, "accelerator_pedal_position": 0.2866829871858609, "brake_pedal_position": 0.0, "acceleration": 0.21071870383538716, "steering_wheel_angle": -6.733514674714953, "front_wheel_angle": -0.34273689382654704, "heading_rate": -0.26474751927235524, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137705.047513} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26575679944092934, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.8537040595964127, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.905792521997025, "gear": 1, "accelerator_pedal_position": 0.26575679944092934, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.333844037633469, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137705.047513} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137705.057513, "x": 40.75048136864282, "y": 4.410150613421645, "z": null, "yaw": 2.9609634659316173, "pitch": null, "roll": null}, "v": 1.905792521997025, "accelerator_pedal_position": 0.26575679944092934, "brake_pedal_position": 0.0, "acceleration": 0.07936991903695922, "steering_wheel_angle": -6.333844037633469, "front_wheel_angle": -0.32010316959041657, "heading_rate": -0.24678815243054378, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137705.077513} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23123174002288147, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.685979949536623, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.907379220939977, "gear": 1, "accelerator_pedal_position": 0.26575679944092934, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.260492970557254, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137705.077513} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.84995436668396, "x": 36.75048136864282, "y": -0.5898493865783552, "z": null, "yaw": 2.9609634659316173, "pitch": null, "roll": null}, "v": 1.905792521997025, "accelerator_pedal_position": 0.26575679944092934, "brake_pedal_position": 0.0, "acceleration": 0.07936991903695922, "steering_wheel_angle": -6.333844037633469, "front_wheel_angle": -0.32010316959041657, "heading_rate": -0.24678815243054378, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137705.097513} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24771492789546098, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.685979949536623, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9046493936057864, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.184829560895108, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137705.097513} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.84995436668396, "x": 36.75048136864282, "y": -0.5898493865783552, "z": null, "yaw": 2.9609634659316173, "pitch": null, "roll": null}, "v": 1.905792521997025, "accelerator_pedal_position": 0.26575679944092934, "brake_pedal_position": 0.0, "acceleration": 0.07936991903695922, "steering_wheel_angle": -6.333844037633469, "front_wheel_angle": -0.32010316959041657, "heading_rate": -0.24678815243054378, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137705.117513} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24771492789546098, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.685979949536623, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9039838655964427, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.108943613002457, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137705.117513} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.84995436668396, "x": 36.75048136864282, "y": -0.5898493865783552, "z": null, "yaw": 2.9609634659316173, "pitch": null, "roll": null}, "v": 1.905792521997025, "accelerator_pedal_position": 0.26575679944092934, "brake_pedal_position": 0.0, "acceleration": 0.07936991903695922, "steering_wheel_angle": -6.333844037633469, "front_wheel_angle": -0.32010316959041657, "heading_rate": -0.24678815243054378, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137705.137513} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24771492789546098, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.685979949536623, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9033195095048998, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.032835126879302, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137705.137513} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.84995436668396, "x": 36.75048136864282, "y": -0.5898493865783552, "z": null, "yaw": 2.9609634659316173, "pitch": null, "roll": null}, "v": 1.905792521997025, "accelerator_pedal_position": 0.26575679944092934, "brake_pedal_position": 0.0, "acceleration": 0.07936991903695922, "steering_wheel_angle": -6.333844037633469, "front_wheel_angle": -0.32010316959041657, "heading_rate": -0.24678815243054378, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137705.157513} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24771492789546098, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.685979949536623, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.902656323091076, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.956504102525642, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137705.157513} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137705.167513, "x": 40.544620861741905, "y": 4.44909430892283, "z": null, "yaw": 2.947216579995698, "pitch": null, "roll": null}, "v": 1.902325167814617, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3313046688317399, "steering_wheel_angle": -5.918255138512374, "front_wheel_angle": -0.2969410657639719, "heading_rate": -0.22737821514466267, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137705.177513} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2199358228498015, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.465525047930564, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9019943041197658, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.87995053994148, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137705.177513} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.959954261779785, "x": 36.544620861741905, "y": -0.5509056910771699, "z": null, "yaw": 2.947216579995698, "pitch": null, "roll": null}, "v": 1.902325167814617, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3313046688317399, "steering_wheel_angle": -5.918255138512374, "front_wheel_angle": -0.2969410657639719, "heading_rate": -0.22737821514466267, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137705.1975129} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23314070547656113, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.465525047930564, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8978625903569724, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.801001480738309, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137705.1975129} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.959954261779785, "x": 36.544620861741905, "y": -0.5509056910771699, "z": null, "yaw": 2.947216579995698, "pitch": null, "roll": null}, "v": 1.902325167814617, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3313046688317399, "steering_wheel_angle": -5.918255138512374, "front_wheel_angle": -0.2969410657639719, "heading_rate": -0.22737821514466267, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137705.2175128} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23314070547656113, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.465525047930564, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.895388028072832, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.7218171275255285, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137705.2175128} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.959954261779785, "x": 36.544620861741905, "y": -0.5509056910771699, "z": null, "yaw": 2.947216579995698, "pitch": null, "roll": null}, "v": 1.902325167814617, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3313046688317399, "steering_wheel_angle": -5.918255138512374, "front_wheel_angle": -0.2969410657639719, "heading_rate": -0.22737821514466267, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137705.2375128} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23314070547656113, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.465525047930564, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8929178151530572, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.6423974803031385, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137705.2375128} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.959954261779785, "x": 36.544620861741905, "y": -0.5509056910771699, "z": null, "yaw": 2.947216579995698, "pitch": null, "roll": null}, "v": 1.902325167814617, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3313046688317399, "steering_wheel_angle": -5.918255138512374, "front_wheel_angle": -0.2969410657639719, "heading_rate": -0.22737821514466267, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137705.2575128} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23314070547656113, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.465525047930564, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8904519415133665, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.562742539071136, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137705.2575128} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137705.2775128, "x": 40.34026190139196, "y": 4.490563795459544, "z": null, "yaw": 2.934575105754685, "pitch": null, "roll": null}, "v": 1.8879903971000516, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3300445972504227, "steering_wheel_angle": -5.482852303829524, "front_wheel_angle": -0.27306346324833647, "heading_rate": -0.20654250198086962, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137705.2775128} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.151845231360302, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8879903971000516, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.482852303829524, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137705.2775128} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.06995415687561, "x": 36.34026190139196, "y": -0.5094362045404557, "z": null, "yaw": 2.934575105754685, "pitch": null, "roll": null}, "v": 1.8879903971000516, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3300445972504227, "steering_wheel_angle": -5.482852303829524, "front_wheel_angle": -0.27306346324833647, "heading_rate": -0.20654250198086962, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137705.2975128} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21920252455363504, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.151845231360302, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8813924005307956, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.400621964045607, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137705.2975128} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.06995415687561, "x": 36.34026190139196, "y": -0.5094362045404557, "z": null, "yaw": 2.934575105754685, "pitch": null, "roll": null}, "v": 1.8879903971000516, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3300445972504227, "steering_wheel_angle": -5.482852303829524, "front_wheel_angle": -0.27306346324833647, "heading_rate": -0.20654250198086962, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137705.3175128} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21920252455363504, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.151845231360302, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8772052311549827, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.318143825137435, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137705.3175128} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.06995415687561, "x": 36.34026190139196, "y": -0.5094362045404557, "z": null, "yaw": 2.934575105754685, "pitch": null, "roll": null}, "v": 1.8879903971000516, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3300445972504227, "steering_wheel_angle": -5.482852303829524, "front_wheel_angle": -0.27306346324833647, "heading_rate": -0.20654250198086962, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137705.3375127} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21920252455363504, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.151845231360302, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8730253915624844, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.235417887105009, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137705.3375127} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.06995415687561, "x": 36.34026190139196, "y": -0.5094362045404557, "z": null, "yaw": 2.934575105754685, "pitch": null, "roll": null}, "v": 1.8879903971000516, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3300445972504227, "steering_wheel_angle": -5.482852303829524, "front_wheel_angle": -0.27306346324833647, "heading_rate": -0.20654250198086962, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137705.3575127} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21920252455363504, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.151845231360302, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8688528619368938, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.152444149948328, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137705.3575127} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.06995415687561, "x": 36.34026190139196, "y": -0.5094362045404557, "z": null, "yaw": 2.934575105754685, "pitch": null, "roll": null}, "v": 1.8879903971000516, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3300445972504227, "steering_wheel_angle": -5.482852303829524, "front_wheel_angle": -0.27306346324833647, "heading_rate": -0.20654250198086962, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137705.3775127} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21920252455363504, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.151845231360302, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8646876225331184, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.069222613667391, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137705.3775127} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137705.3875127, "x": 40.138596526190945, "y": 4.534039600553964, "z": null, "yaw": 2.923056532845705, "pitch": null, "roll": null}, "v": 1.8626077305134912, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3278234621033608, "steering_wheel_angle": -5.027518920855328, "front_wheel_angle": -0.24849818894518802, "heading_rate": -0.18461848042800355, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137705.3975127} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.977991316132613, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8605296536770597, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.985753278262201, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137705.3975127} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.179954051971436, "x": 36.138596526190945, "y": -0.4659603994460362, "z": null, "yaw": 2.923056532845705, "pitch": null, "roll": null}, "v": 1.8626077305134912, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3278234621033608, "steering_wheel_angle": -5.027518920855328, "front_wheel_angle": -0.24849818894518802, "heading_rate": -0.18461848042800355, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137705.4175127} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.216178693226823, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.977991316132613, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8539796662184047, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.899218214779924, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137705.4175127} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.179954051971436, "x": 36.138596526190945, "y": -0.4659603994460362, "z": null, "yaw": 2.923056532845705, "pitch": null, "roll": null}, "v": 1.8626077305134912, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3278234621033608, "steering_wheel_angle": -5.027518920855328, "front_wheel_angle": -0.24849818894518802, "heading_rate": -0.18461848042800355, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137705.4375126} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.216178693226823, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.977991316132613, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8494625421775248, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.812418415855213, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137705.4375126} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.179954051971436, "x": 36.138596526190945, "y": -0.4659603994460362, "z": null, "yaw": 2.923056532845705, "pitch": null, "roll": null}, "v": 1.8626077305134912, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3278234621033608, "steering_wheel_angle": -5.027518920855328, "front_wheel_angle": -0.24849818894518802, "heading_rate": -0.18461848042800355, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137705.4575126} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.216178693226823, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.977991316132613, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8449532755827567, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.725353881488067, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137705.4575126} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.179954051971436, "x": 36.138596526190945, "y": -0.4659603994460362, "z": null, "yaw": 2.923056532845705, "pitch": null, "roll": null}, "v": 1.8626077305134912, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3278234621033608, "steering_wheel_angle": -5.027518920855328, "front_wheel_angle": -0.24849818894518802, "heading_rate": -0.18461848042800355, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137705.4775126} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.216178693226823, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.977991316132613, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8404518446363682, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.638024611678488, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137705.4775126} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137705.4975126, "x": 39.94016066231619, "y": 4.579109577758597, "z": null, "yaw": 2.912676162614875, "pitch": null, "roll": null}, "v": 1.835958227620897, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.32550533751673355, "steering_wheel_angle": -4.550430606426475, "front_wheel_angle": -0.22318236265963662, "heading_rate": -0.1627715463187115, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137705.4975126} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.607847576768607, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.835958227620897, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.550430606426475, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137705.4975126} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.28995394706726, "x": 35.94016066231619, "y": -0.4208904222414027, "z": null, "yaw": 2.912676162614875, "pitch": null, "roll": null}, "v": 1.835958227620897, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.32550533751673355, "steering_wheel_angle": -4.550430606426475, "front_wheel_angle": -0.22318236265963662, "heading_rate": -0.1627715463187115, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137705.5175126} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.607847576768607, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8294509425661176, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.460185580506756, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137705.5175126} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.28995394706726, "x": 35.94016066231619, "y": -0.4208904222414027, "z": null, "yaw": 2.912676162614875, "pitch": null, "roll": null}, "v": 1.835958227620897, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.32550533751673355, "steering_wheel_angle": -4.550430606426475, "front_wheel_angle": -0.22318236265963662, "heading_rate": -0.1627715463187115, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137705.5375125} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.607847576768607, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.822954926053605, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.369661265992292, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137705.5375125} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.28995394706726, "x": 35.94016066231619, "y": -0.4208904222414027, "z": null, "yaw": 2.912676162614875, "pitch": null, "roll": null}, "v": 1.835958227620897, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.32550533751673355, "steering_wheel_angle": -4.550430606426475, "front_wheel_angle": -0.22318236265963662, "heading_rate": -0.1627715463187115, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137705.5575125} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.607847576768607, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8164701416978362, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.278857662883084, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137705.5575125} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.28995394706726, "x": 35.94016066231619, "y": -0.4208904222414027, "z": null, "yaw": 2.912676162614875, "pitch": null, "roll": null}, "v": 1.835958227620897, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.32550533751673355, "steering_wheel_angle": -4.550430606426475, "front_wheel_angle": -0.22318236265963662, "heading_rate": -0.1627715463187115, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137705.5775125} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.607847576768607, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8099965532637539, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.187774771179131, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137705.5775125} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.28995394706726, "x": 35.94016066231619, "y": -0.4208904222414027, "z": null, "yaw": 2.912676162614875, "pitch": null, "roll": null}, "v": 1.835958227620897, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.32550533751673355, "steering_wheel_angle": -4.550430606426475, "front_wheel_angle": -0.22318236265963662, "heading_rate": -0.1627715463187115, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137705.5975125} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.607847576768607, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8035341246659804, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.096412590880434, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137705.5975125} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137705.6075125, "x": 39.745409282020645, "y": 4.625364853177232, "z": null, "yaw": 2.9034574812803062, "pitch": null, "roll": null}, "v": 1.800307084069764, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.322426410173006, "steering_wheel_angle": -4.050626767508057, "front_wheel_angle": -0.19710291826583928, "heading_rate": -0.14043497279674516, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137705.6175125} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.340404223575545, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7970828199680338, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.004771121986995, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137705.6175125} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.399953842163086, "x": 35.745409282020645, "y": -0.3746351468227678, "z": null, "yaw": 2.9034574812803062, "pitch": null, "roll": null}, "v": 1.800307084069764, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.322426410173006, "steering_wheel_angle": -4.050626767508057, "front_wheel_angle": -0.19710291826583928, "heading_rate": -0.14043497279674516, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137705.6375124} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.340404223575545, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7906426033815508, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.909758137625614, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137705.6375124} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.399953842163086, "x": 35.745409282020645, "y": -0.3746351468227678, "z": null, "yaw": 2.9034574812803062, "pitch": null, "roll": null}, "v": 1.800307084069764, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.322426410173006, "steering_wheel_angle": -4.050626767508057, "front_wheel_angle": -0.19710291826583928, "heading_rate": -0.14043497279674516, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137705.6575124} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.340404223575545, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7842134392655138, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.814446788446034, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137705.6575124} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.399953842163086, "x": 35.745409282020645, "y": -0.3746351468227678, "z": null, "yaw": 2.9034574812803062, "pitch": null, "roll": null}, "v": 1.800307084069764, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.322426410173006, "steering_wheel_angle": -4.050626767508057, "front_wheel_angle": -0.19710291826583928, "heading_rate": -0.14043497279674516, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137705.6775124} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.340404223575545, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7777952921254834, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.7188370744482557, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137705.6775124} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.399953842163086, "x": 35.745409282020645, "y": -0.3746351468227678, "z": null, "yaw": 2.9034574812803062, "pitch": null, "roll": null}, "v": 1.800307084069764, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.322426410173006, "steering_wheel_angle": -4.050626767508057, "front_wheel_angle": -0.19710291826583928, "heading_rate": -0.14043497279674516, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137705.6975124} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.340404223575545, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7713881266128346, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.6229289956322774, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137705.6975124} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137705.7175124, "x": 39.55485794703115, "y": 4.672374721034209, "z": null, "yaw": 2.8954192487018013, "pitch": null, "roll": null}, "v": 1.7649919075239993, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.31940155971245204, "steering_wheel_angle": -3.526722551998101, "front_wheel_angle": -0.17022716416851166, "heading_rate": -0.11851002938810143, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137705.7175124} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.033518450338585, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7649919075239993, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.526722551998101, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137705.7175124} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.50995373725891, "x": 35.55485794703115, "y": -0.3276252789657912, "z": null, "yaw": 2.8954192487018013, "pitch": null, "roll": null}, "v": 1.7649919075239993, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.31940155971245204, "steering_wheel_angle": -3.526722551998101, "front_wheel_angle": -0.17022716416851166, "heading_rate": -0.11851002938810143, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137705.7375124} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.033518450338585, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7586065997997113, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.4269344051710497, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137705.7375124} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.50995373725891, "x": 35.55485794703115, "y": -0.3276252789657912, "z": null, "yaw": 2.8954192487018013, "pitch": null, "roll": null}, "v": 1.7649919075239993, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.31940155971245204, "steering_wheel_angle": -3.526722551998101, "front_wheel_angle": -0.17022716416851166, "heading_rate": -0.11851002938810143, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137705.7575123} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.033518450338585, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.752232168524259, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.3268272794028286, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137705.7575123} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.50995373725891, "x": 35.55485794703115, "y": -0.3276252789657912, "z": null, "yaw": 2.8954192487018013, "pitch": null, "roll": null}, "v": 1.7649919075239993, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.31940155971245204, "steering_wheel_angle": -3.526722551998101, "front_wheel_angle": -0.17022716416851166, "heading_rate": -0.11851002938810143, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137705.7775123} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.033518450338585, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7458685789247392, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.2264011746934385, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137705.7775123} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.50995373725891, "x": 35.55485794703115, "y": -0.3276252789657912, "z": null, "yaw": 2.8954192487018013, "pitch": null, "roll": null}, "v": 1.7649919075239993, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.31940155971245204, "steering_wheel_angle": -3.526722551998101, "front_wheel_angle": -0.17022716416851166, "heading_rate": -0.11851002938810143, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137705.7975123} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.033518450338585, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7395157963703187, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.125656091042879, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137705.7975123} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.50995373725891, "x": 35.55485794703115, "y": -0.3276252789657912, "z": null, "yaw": 2.8954192487018013, "pitch": null, "roll": null}, "v": 1.7649919075239993, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.31940155971245204, "steering_wheel_angle": -3.526722551998101, "front_wheel_angle": -0.17022716416851166, "heading_rate": -0.11851002938810143, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137705.8175123} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.033518450338585, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7331737863714984, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.0245920284511487, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137705.8175123} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137705.8275123, "x": 39.36841247896322, "y": 4.719856318374707, "z": null, "yaw": 2.888592122842486, "pitch": null, "roll": null}, "v": 1.730006810340936, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.316429576155307, "steering_wheel_angle": -2.973940380052344, "front_wheel_angle": -0.14235615203255853, "heading_rate": -0.0968571617009345, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137705.8375123} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.520210423851745, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.726842514579383, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.923208986918248, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137705.8375123} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.619953632354736, "x": 35.36841247896322, "y": -0.2801436816252929, "z": null, "yaw": 2.888592122842486, "pitch": null, "roll": null}, "v": 1.730006810340936, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.316429576155307, "steering_wheel_angle": -2.973940380052344, "front_wheel_angle": -0.14235615203255853, "heading_rate": -0.0968571617009345, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137705.8575122} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.520210423851745, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7205219467849548, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.818942313969023, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137705.8575122} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.619953632354736, "x": 35.36841247896322, "y": -0.2801436816252929, "z": null, "yaw": 2.888592122842486, "pitch": null, "roll": null}, "v": 1.730006810340936, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.316429576155307, "steering_wheel_angle": -2.973940380052344, "front_wheel_angle": -0.14235615203255853, "heading_rate": -0.0968571617009345, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137705.8775122} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.520210423851745, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.714212048918352, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.714340398120042, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137705.8775122} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.619953632354736, "x": 35.36841247896322, "y": -0.2801436816252929, "z": null, "yaw": 2.888592122842486, "pitch": null, "roll": null}, "v": 1.730006810340936, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.316429576155307, "steering_wheel_angle": -2.973940380052344, "front_wheel_angle": -0.14235615203255853, "heading_rate": -0.0968571617009345, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137705.8975122} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.520210423851745, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7079127870481516, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.609403239371303, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137705.8975122} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.619953632354736, "x": 35.36841247896322, "y": -0.2801436816252929, "z": null, "yaw": 2.888592122842486, "pitch": null, "roll": null}, "v": 1.730006810340936, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.316429576155307, "steering_wheel_angle": -2.973940380052344, "front_wheel_angle": -0.14235615203255853, "heading_rate": -0.0968571617009345, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137705.9175122} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.520210423851745, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.701624127380656, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.504130837722808, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137705.9175122} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137705.9375122, "x": 39.18597580311682, "y": 4.767536970887653, "z": null, "yaw": 2.8829991807288646, "pitch": null, "roll": null}, "v": 1.695346036259186, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.31350928363955666, "steering_wheel_angle": -2.398523193174555, "front_wheel_angle": -0.1138472270476578, "heading_rate": -0.07572213785541793, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137705.9375122} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.153953387889592, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.695346036259186, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.398523193174555, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137705.9375122} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.72995352745056, "x": 35.18597580311682, "y": -0.23246302911234729, "z": null, "yaw": 2.8829991807288646, "pitch": null, "roll": null}, "v": 1.695346036259186, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.31350928363955666, "steering_wheel_angle": -2.398523193174555, "front_wheel_angle": -0.1138472270476578, "heading_rate": -0.07572213785541793, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137705.9575121} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.153953387889592, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.689078480163375, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.2888718886298554, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137705.9575121} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.72995352745056, "x": 35.18597580311682, "y": -0.23246302911234729, "z": null, "yaw": 2.8829991807288646, "pitch": null, "roll": null}, "v": 1.695346036259186, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.31350928363955666, "steering_wheel_angle": -2.398523193174555, "front_wheel_angle": -0.1138472270476578, "heading_rate": -0.07572213785541793, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137705.9775121} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.153953387889592, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6828214257084708, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.1788615004948695, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137705.9775121} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.72995352745056, "x": 35.18597580311682, "y": -0.23246302911234729, "z": null, "yaw": 2.8829991807288646, "pitch": null, "roll": null}, "v": 1.695346036259186, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.31350928363955666, "steering_wheel_angle": -2.398523193174555, "front_wheel_angle": -0.1138472270476578, "heading_rate": -0.07572213785541793, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137705.997512} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.153953387889592, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6765748396446392, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.0684920287695974, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137705.997512} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.72995352745056, "x": 35.18597580311682, "y": -0.23246302911234729, "z": null, "yaw": 2.8829991807288646, "pitch": null, "roll": null}, "v": 1.695346036259186, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.31350928363955666, "steering_wheel_angle": -2.398523193174555, "front_wheel_angle": -0.1138472270476578, "heading_rate": -0.07572213785541793, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137706.017512} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.153953387889592, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.670338688856273, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.9577634734540377, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137706.017512} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.72995352745056, "x": 35.18597580311682, "y": -0.23246302911234729, "z": null, "yaw": 2.8829991807288646, "pitch": null, "roll": null}, "v": 1.695346036259186, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.31350928363955666, "steering_wheel_angle": -2.398523193174555, "front_wheel_angle": -0.1138472270476578, "heading_rate": -0.07572213785541793, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137706.037512} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.153953387889592, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6641129403613055, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.8466758345481915, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137706.037512} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137706.047512, "x": 39.0074493034494, "y": 4.815155043710024, "z": null, "yaw": 2.8786699982206843, "pitch": null, "roll": null}, "v": 1.661003956703297, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.31063953927700494, "steering_wheel_angle": -1.7909973587489114, "front_wheel_angle": -0.08427598856310779, "heading_rate": -0.05481058638983216, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137706.057512} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.732054880734557, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.657897561310527, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.735229112052059, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137706.057512} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.83995342254639, "x": 35.0074493034494, "y": -0.1848449562899761, "z": null, "yaw": 2.8786699982206843, "pitch": null, "roll": null}, "v": 1.661003956703297, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.31063953927700494, "steering_wheel_angle": -1.7909973587489114, "front_wheel_angle": -0.08427598856310779, "heading_rate": -0.05481058638983216, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137706.077512} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.732054880734557, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6516925189869067, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.61960394681638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137706.077512} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.83995342254639, "x": 35.0074493034494, "y": -0.1848449562899761, "z": null, "yaw": 2.8786699982206843, "pitch": null, "roll": null}, "v": 1.661003956703297, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.31063953927700494, "steering_wheel_angle": -1.7909973587489114, "front_wheel_angle": -0.08427598856310779, "heading_rate": -0.05481058638983216, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137706.097512} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.732054880734557, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6454977808049187, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.5035947879595193, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137706.097512} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.83995342254639, "x": 35.0074493034494, "y": -0.1848449562899761, "z": null, "yaw": 2.8786699982206843, "pitch": null, "roll": null}, "v": 1.661003956703297, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.31063953927700494, "steering_wheel_angle": -1.7909973587489114, "front_wheel_angle": -0.08427598856310779, "heading_rate": -0.05481058638983216, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137706.117512} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.732054880734557, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6393133143098702, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.387201635481477, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137706.117512} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.83995342254639, "x": 35.0074493034494, "y": -0.1848449562899761, "z": null, "yaw": 2.8786699982206843, "pitch": null, "roll": null}, "v": 1.661003956703297, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.31063953927700494, "steering_wheel_angle": -1.7909973587489114, "front_wheel_angle": -0.08427598856310779, "heading_rate": -0.05481058638983216, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137706.137512} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.732054880734557, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6331390871772367, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.2704244893822527, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137706.137512} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137706.157512, "x": 38.832733495679456, "y": 4.862458251505596, "z": null, "yaw": 2.875637188590957, "pitch": null, "roll": null}, "v": 1.6269750672119994, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3078192320538949, "steering_wheel_angle": -1.153263349661847, "front_wheel_angle": -0.053787933668145355, "heading_rate": -0.034217234098101804, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137706.157512} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6269750672119994, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.153263349661847, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137706.157512} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.94995331764221, "x": 34.832733495679456, "y": -0.13754174849440393, "z": null, "yaw": 2.875637188590957, "pitch": null, "roll": null}, "v": 1.6269750672119994, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3078192320538949, "steering_wheel_angle": -1.153263349661847, "front_wheel_angle": -0.053787933668145355, "heading_rate": -0.034217234098101804, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137706.177512} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6208212223479865, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.0339040833591207, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137706.177512} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.94995331764221, "x": 34.832733495679456, "y": -0.13754174849440393, "z": null, "yaw": 2.875637188590957, "pitch": null, "roll": null}, "v": 1.6269750672119994, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3078192320538949, "steering_wheel_angle": -1.153263349661847, "front_wheel_angle": -0.053787933668145355, "heading_rate": -0.034217234098101804, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137706.197512} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6146775206472195, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.9141488991670826, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137706.197512} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.94995331764221, "x": 34.832733495679456, "y": -0.13754174849440393, "z": null, "yaw": 2.875637188590957, "pitch": null, "roll": null}, "v": 1.6269750672119994, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3078192320538949, "steering_wheel_angle": -1.153263349661847, "front_wheel_angle": -0.053787933668145355, "heading_rate": -0.034217234098101804, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137706.217512} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6085439302992626, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7939977970857327, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137706.217512} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.94995331764221, "x": 34.832733495679456, "y": -0.13754174849440393, "z": null, "yaw": 2.875637188590957, "pitch": null, "roll": null}, "v": 1.6269750672119994, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3078192320538949, "steering_wheel_angle": -1.153263349661847, "front_wheel_angle": -0.053787933668145355, "heading_rate": -0.034217234098101804, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137706.2375119} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.602420419620577, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6734507771150708, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137706.2375119} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.94995331764221, "x": 34.832733495679456, "y": -0.13754174849440393, "z": null, "yaw": 2.875637188590957, "pitch": null, "roll": null}, "v": 1.6269750672119994, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3078192320538949, "steering_wheel_angle": -1.153263349661847, "front_wheel_angle": -0.053787933668145355, "heading_rate": -0.034217234098101804, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137706.2575119} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5963069570538777, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5525078392550972, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137706.2575119} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137706.2675118, "x": 38.66172907380108, "y": 4.909203528737859, "z": null, "yaw": 2.873931420224553, "pitch": null, "roll": null}, "v": 1.5932539839852369, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30504728177411017, "steering_wheel_angle": -0.4918879011166184, "front_wheel_angle": -0.02273702619339683, "heading_rate": -0.014153164627657268, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137706.2775118} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5902035111674957, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4311689835058116, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137706.2775118} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.05995321273804, "x": 34.66172907380108, "y": -0.09079647126214141, "z": null, "yaw": 2.873931420224553, "pitch": null, "roll": null}, "v": 1.5932539839852369, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30504728177411017, "steering_wheel_angle": -0.4918879011166184, "front_wheel_angle": -0.02273702619339683, "heading_rate": -0.014153164627657268, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137706.2975118} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5841100506547432, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3094342098672142, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137706.2975118} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.05995321273804, "x": 34.66172907380108, "y": -0.09079647126214141, "z": null, "yaw": 2.873931420224553, "pitch": null, "roll": null}, "v": 1.5932539839852369, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30504728177411017, "steering_wheel_angle": -0.4918879011166184, "front_wheel_angle": -0.02273702619339683, "heading_rate": -0.014153164627657268, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137706.3175118} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5780265443332826, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.18730351833930486, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137706.3175118} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.05995321273804, "x": 34.66172907380108, "y": -0.09079647126214141, "z": null, "yaw": 2.873931420224553, "pitch": null, "roll": null}, "v": 1.5932539839852369, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30504728177411017, "steering_wheel_angle": -0.4918879011166184, "front_wheel_angle": -0.02273702619339683, "heading_rate": -0.014153164627657268, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137706.3375118} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5719529611444996, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.06477690892208365, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137706.3375118} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.05995321273804, "x": 34.66172907380108, "y": -0.09079647126214141, "z": null, "yaw": 2.873931420224553, "pitch": null, "roll": null}, "v": 1.5932539839852369, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30504728177411017, "steering_wheel_angle": -0.4918879011166184, "front_wheel_angle": -0.02273702619339683, "heading_rate": -0.014153164627657268, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137706.3575118} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5658892701528797, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.058057180413825134, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137706.3575118} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137706.3775117, "x": 38.49433853313986, "y": 4.955159052028748, "z": null, "yaw": 2.8735608629536715, "pitch": null, "roll": null}, "v": 1.559835440545389, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30232263804308374, "steering_wheel_angle": 0.18060546622258122, "front_wheel_angle": 0.008313881281351979, "heading_rate": 0.005065853699771298, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137706.3775117} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21764479304303622, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.559835440545389, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.18060546622258122, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137706.3775117} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.16995310783386, "x": 34.49433853313986, "y": -0.044840947971252376, "z": null, "yaw": 2.8735608629536715, "pitch": null, "roll": null}, "v": 1.559835440545389, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30232263804308374, "steering_wheel_angle": 0.18060546622258122, "front_wheel_angle": 0.008313881281351979, "heading_rate": 0.005065853699771298, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137706.3975117} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.555996145869472, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.30275783414202545, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137706.3975117} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.16995310783386, "x": 34.49433853313986, "y": -0.044840947971252376, "z": null, "yaw": 2.8735608629536715, "pitch": null, "roll": null}, "v": 1.559835440545389, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30232263804308374, "steering_wheel_angle": 0.18060546622258122, "front_wheel_angle": 0.008313881281351979, "heading_rate": 0.005065853699771298, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137706.4175117} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5499583739215919, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4245142841721578, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137706.4175117} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.16995310783386, "x": 34.49433853313986, "y": -0.044840947971252376, "z": null, "yaw": 2.8735608629536715, "pitch": null, "roll": null}, "v": 1.559835440545389, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30232263804308374, "steering_wheel_angle": 0.18060546622258122, "front_wheel_angle": 0.008313881281351979, "heading_rate": 0.005065853699771298, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137706.4375117} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5439303827464264, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5458748163129783, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137706.4375117} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.16995310783386, "x": 34.49433853313986, "y": -0.044840947971252376, "z": null, "yaw": 2.8735608629536715, "pitch": null, "roll": null}, "v": 1.559835440545389, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30232263804308374, "steering_wheel_angle": 0.18060546622258122, "front_wheel_angle": 0.008313881281351979, "heading_rate": 0.005065853699771298, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137706.4575117} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5379121419710025, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.6668394305644868, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137706.4575117} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.16995310783386, "x": 34.49433853313986, "y": -0.044840947971252376, "z": null, "yaw": 2.8735608629536715, "pitch": null, "roll": null}, "v": 1.559835440545389, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30232263804308374, "steering_wheel_angle": 0.18060546622258122, "front_wheel_angle": 0.008313881281351979, "heading_rate": 0.005065853699771298, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137706.4775116} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5319036213420045, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.7874081269266836, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137706.4775116} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137706.4875116, "x": 38.330266605783414, "y": 5.000162251314204, "z": null, "yaw": 2.8745248015422513, "pitch": null, "roll": null}, "v": 1.5289029966608254, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29982059356502583, "steering_wheel_angle": 0.8475440058992901, "front_wheel_angle": 0.039364788756100506, "heading_rate": 0.023521894544415972, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137706.4975116} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22445588463442362, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.525904790725175, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.9075809053995685, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137706.4975116} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.27995300292969, "x": 34.330266605783414, "y": 0.00016225131420366523, "z": null, "yaw": 2.8745248015422513, "pitch": null, "roll": null}, "v": 1.5289029966608254, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29982059356502583, "steering_wheel_angle": 0.8475440058992901, "front_wheel_angle": 0.039364788756100506, "heading_rate": 0.023521894544415972, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137706.5175116} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21802807979836497, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5211047007713798, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.087097727066436, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137706.5175116} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.27995300292969, "x": 34.330266605783414, "y": 0.00016225131420366523, "z": null, "yaw": 2.8745248015422513, "pitch": null, "roll": null}, "v": 1.5289029966608254, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29982059356502583, "steering_wheel_angle": 0.8475440058992901, "front_wheel_angle": 0.039364788756100506, "heading_rate": 0.023521894544415972, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137706.5375116} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21802807979836497, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5192395274573212, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.1467387086774024, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137706.5375116} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.27995300292969, "x": 34.330266605783414, "y": 0.00016225131420366523, "z": null, "yaw": 2.8745248015422513, "pitch": null, "roll": null}, "v": 1.5289029966608254, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29982059356502583, "steering_wheel_angle": 0.8475440058992901, "front_wheel_angle": 0.039364788756100506, "heading_rate": 0.023521894544415972, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137706.5575116} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21802807979836497, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5117938118454217, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.3843128403979892, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137706.5575116} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.27995300292969, "x": 34.330266605783414, "y": 0.00016225131420366523, "z": null, "yaw": 2.8745248015422513, "pitch": null, "roll": null}, "v": 1.5289029966608254, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29982059356502583, "steering_wheel_angle": 0.8475440058992901, "front_wheel_angle": 0.039364788756100506, "heading_rate": 0.023521894544415972, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137706.5775115} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21802807979836497, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5099361178739434, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.443458924647316, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137706.5775115} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137706.5975115, "x": 38.16904143341238, "y": 5.04411253302091, "z": null, "yaw": 2.876825097348096, "pitch": null, "roll": null}, "v": 1.5080799140943983, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2981470459776696, "steering_wheel_angle": 1.5025060294243144, "front_wheel_angle": 0.07041569623084931, "heading_rate": 0.041550140560550626, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137706.6075115} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5032452145878121, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.6203033005613279, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137706.6075115} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.38995289802551, "x": 34.16904143341238, "y": 0.04411253302091023, "z": null, "yaw": 2.876825097348096, "pitch": null, "roll": null}, "v": 1.5080799140943983, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2981470459776696, "steering_wheel_angle": 1.5025060294243144, "front_wheel_angle": 0.07041569623084931, "heading_rate": 0.041550140560550626, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137706.6175115} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.500267617363, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.6790534669213428, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137706.6175115} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.38995289802551, "x": 34.16904143341238, "y": 0.04411253302091023, "z": null, "yaw": 2.876825097348096, "pitch": null, "roll": null}, "v": 1.5080799140943983, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2981470459776696, "steering_wheel_angle": 1.5025060294243144, "front_wheel_angle": 0.07041569623084931, "heading_rate": 0.041550140560550626, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137706.6475115} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.49431956860623, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.7962568612243885, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137706.6475115} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.38995289802551, "x": 34.16904143341238, "y": 0.04411253302091023, "z": null, "yaw": 2.876825097348096, "pitch": null, "roll": null}, "v": 1.5080799140943983, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2981470459776696, "steering_wheel_angle": 1.5025060294243144, "front_wheel_angle": 0.07041569623084931, "heading_rate": 0.041550140560550626, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137706.6675115} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4854153046346197, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.9713196066364973, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137706.6675115} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.38995289802551, "x": 34.16904143341238, "y": 0.04411253302091023, "z": null, "yaw": 2.876825097348096, "pitch": null, "roll": null}, "v": 1.5080799140943983, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2981470459776696, "steering_wheel_angle": 1.5025060294243144, "front_wheel_angle": 0.07041569623084931, "heading_rate": 0.041550140560550626, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137706.6875114} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4824519511195782, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.0294758961625448, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137706.6875114} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137706.7075114, "x": 38.01033796195807, "y": 5.086880426952942, "z": null, "yaw": 2.880466202726162, "pitch": null, "roll": null}, "v": 1.476532323936191, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2956280932330937, "steering_wheel_angle": 2.1454915367976546, "front_wheel_angle": 0.10146660370559812, "heading_rate": 0.05872460854199647, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137706.7075114} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22976694267027545, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.476532323936191, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.1454915367976546, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137706.7075114} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.49995279312134, "x": 34.01033796195807, "y": 0.08688042695294218, "z": null, "yaw": 2.880466202726162, "pitch": null, "roll": null}, "v": 1.476532323936191, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2956280932330937, "steering_wheel_angle": 2.1454915367976546, "front_wheel_angle": 0.10146660370559812, "heading_rate": 0.05872460854199647, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137706.7275114} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22219346243437021, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4743415013194412, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.261111259543453, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137706.7275114} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.49995279312134, "x": 34.01033796195807, "y": 0.08688042695294218, "z": null, "yaw": 2.880466202726162, "pitch": null, "roll": null}, "v": 1.476532323936191, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2956280932330937, "steering_wheel_angle": 2.1454915367976546, "front_wheel_angle": 0.10146660370559812, "heading_rate": 0.05872460854199647, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137706.7475114} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22219346243437021, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4712078517186633, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.3763350643999392, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137706.7475114} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.49995279312134, "x": 34.01033796195807, "y": 0.08688042695294218, "z": null, "yaw": 2.880466202726162, "pitch": null, "roll": null}, "v": 1.476532323936191, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2956280932330937, "steering_wheel_angle": 2.1454915367976546, "front_wheel_angle": 0.10146660370559812, "heading_rate": 0.05872460854199647, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137706.7675114} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22219346243437021, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.463395475175922, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.662662435775416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137706.7675114} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.49995279312134, "x": 34.01033796195807, "y": 0.08688042695294218, "z": null, "yaw": 2.880466202726162, "pitch": null, "roll": null}, "v": 1.476532323936191, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2956280932330937, "steering_wheel_angle": 2.1454915367976546, "front_wheel_angle": 0.10146660370559812, "heading_rate": 0.05872460854199647, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137706.7975113} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22219346243437021, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4618367162088055, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.7196309716335274, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137706.7975113} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137706.8175113, "x": 37.85408138777619, "y": 5.128276603630547, "z": null, "yaw": 2.8854551956035497, "pitch": null, "roll": null}, "v": 1.4602791925943637, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29433811283295863, "steering_wheel_angle": 2.7765005280193105, "front_wheel_angle": 0.13251751118034663, "heading_rate": 0.07603645665669549, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137706.8175113} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2201275326789244, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4569097065776062, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.889942702373893, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137706.8175113} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.60995268821716, "x": 33.85408138777619, "y": 0.12827660363054694, "z": null, "yaw": 2.8854551956035497, "pitch": null, "roll": null}, "v": 1.4602791925943637, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29433811283295863, "steering_wheel_angle": 2.7765005280193105, "front_wheel_angle": 0.13251751118034663, "heading_rate": 0.07603645665669549, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137706.8375113} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22101302497432562, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4569097065776062, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.889942702373893, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137706.8375113} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.60995268821716, "x": 33.85408138777619, "y": 0.12827660363054694, "z": null, "yaw": 2.8854551956035497, "pitch": null, "roll": null}, "v": 1.4602791925943637, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29433811283295863, "steering_wheel_angle": 2.7765005280193105, "front_wheel_angle": 0.13251751118034663, "heading_rate": 0.07603645665669549, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137706.8575113} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22101302497432562, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4520313697735525, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.059363617863308, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137706.8575113} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.60995268821716, "x": 33.85408138777619, "y": 0.12827660363054694, "z": null, "yaw": 2.8854551956035497, "pitch": null, "roll": null}, "v": 1.4602791925943637, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29433811283295863, "steering_wheel_angle": 2.7765005280193105, "front_wheel_angle": 0.13251751118034663, "heading_rate": 0.07603645665669549, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137706.8775113} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22101302497432562, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.448785570499318, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.171815997494611, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137706.8775113} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.60995268821716, "x": 33.85408138777619, "y": 0.12827660363054694, "z": null, "yaw": 2.8854551956035497, "pitch": null, "roll": null}, "v": 1.4602791925943637, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29433811283295863, "steering_wheel_angle": 2.7765005280193105, "front_wheel_angle": 0.13251751118034663, "heading_rate": 0.07603645665669549, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137706.8975112} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22101302497432562, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.447164593812035, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.227893718101771, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137706.8975112} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.60995268821716, "x": 33.85408138777619, "y": 0.12827660363054694, "z": null, "yaw": 2.8854551956035497, "pitch": null, "roll": null}, "v": 1.4602791925943637, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29433811283295863, "steering_wheel_angle": 2.7765005280193105, "front_wheel_angle": 0.13251751118034663, "heading_rate": 0.07603645665669549, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137706.9175112} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22101302497432562, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4423093371013036, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.3955330030892825, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137706.9175112} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137706.9275112, "x": 37.699455428837, "y": 5.168314920626051, "z": null, "yaw": 2.8918018347989785, "pitch": null, "roll": null}, "v": 1.4423093371013036, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2929180290939612, "steering_wheel_angle": 3.3955330030892825, "front_wheel_angle": 0.16356841865509544, "heading_rate": 0.0929855354252418, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137706.9375112} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23324557182491476, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4406934708712593, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.4512148058071292, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137706.9375112} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.71995258331299, "x": 33.699455428837, "y": 0.16831492062605058, "z": null, "yaw": 2.8918018347989785, "pitch": null, "roll": null}, "v": 1.4423093371013036, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2929180290939612, "steering_wheel_angle": 3.3955330030892825, "front_wheel_angle": 0.16356841865509544, "heading_rate": 0.0929855354252418, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137706.9575112} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22731234969490216, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4389940242346504, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.5622814728258416, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137706.9575112} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.71995258331299, "x": 33.699455428837, "y": 0.16831492062605058, "z": null, "yaw": 2.8918018347989785, "pitch": null, "roll": null}, "v": 1.4423093371013036, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2929180290939612, "steering_wheel_angle": 3.3955330030892825, "front_wheel_angle": 0.16356841865509544, "heading_rate": 0.0929855354252418, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137706.9775112} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22731234969490216, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.436555893769709, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.672952221955241, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137706.9775112} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.71995258331299, "x": 33.699455428837, "y": 0.16831492062605058, "z": null, "yaw": 2.8918018347989785, "pitch": null, "roll": null}, "v": 1.4423093371013036, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2929180290939612, "steering_wheel_angle": 3.3955330030892825, "front_wheel_angle": 0.16356841865509544, "heading_rate": 0.0929855354252418, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137706.9975111} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22731234969490216, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4341216015224247, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.783227053195329, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137706.9975111} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.71995258331299, "x": 33.699455428837, "y": 0.16831492062605058, "z": null, "yaw": 2.8918018347989785, "pitch": null, "roll": null}, "v": 1.4423093371013036, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2929180290939612, "steering_wheel_angle": 3.3955330030892825, "front_wheel_angle": 0.16356841865509544, "heading_rate": 0.0929855354252418, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137707.0175111} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22731234969490216, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4304773414157375, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.947896954013001, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137707.0175111} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137707.037511, "x": 37.5462211728974, "y": 5.206855409660629, "z": null, "yaw": 2.899518637011167, "pitch": null, "roll": null}, "v": 1.4292644980585305, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2918911949570316, "steering_wheel_angle": 4.002588962007569, "front_wheel_angle": 0.19461932612984398, "heading_rate": 0.11005019058417036, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137707.037511} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23859975041366785, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4292644980585305, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.002588962007569, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137707.037511} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.82995247840881, "x": 33.5462211728974, "y": 0.20685540966062899, "z": null, "yaw": 2.899518637011167, "pitch": null, "roll": null}, "v": 1.4292644980585305, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2918911949570316, "steering_wheel_angle": 4.002588962007569, "front_wheel_angle": 0.19461932612984398, "heading_rate": 0.11005019058417036, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137707.057511} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23314655998447792, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.428252040913009, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.111676039579721, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137707.057511} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.82995247840881, "x": 33.5462211728974, "y": 0.20685540966062899, "z": null, "yaw": 2.899518637011167, "pitch": null, "roll": null}, "v": 1.4292644980585305, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2918911949570316, "steering_wheel_angle": 4.002588962007569, "front_wheel_angle": 0.19461932612984398, "heading_rate": 0.11005019058417036, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137707.077511} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23314655998447792, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4265597930388572, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.220367199262562, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137707.077511} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.82995247840881, "x": 33.5462211728974, "y": 0.20685540966062899, "z": null, "yaw": 2.899518637011167, "pitch": null, "roll": null}, "v": 1.4292644980585305, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2918911949570316, "steering_wheel_angle": 4.002588962007569, "front_wheel_angle": 0.19461932612984398, "heading_rate": 0.11005019058417036, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137707.097511} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23314655998447792, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4248702022923134, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.328662441056091, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137707.097511} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.82995247840881, "x": 33.5462211728974, "y": 0.20685540966062899, "z": null, "yaw": 2.899518637011167, "pitch": null, "roll": null}, "v": 1.4292644980585305, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2918911949570316, "steering_wheel_angle": 4.002588962007569, "front_wheel_angle": 0.19461932612984398, "heading_rate": 0.11005019058417036, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137707.117511} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23314655998447792, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.42318326335978, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.436561764960307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137707.117511} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.82995247840881, "x": 33.5462211728974, "y": 0.20685540966062899, "z": null, "yaw": 2.899518637011167, "pitch": null, "roll": null}, "v": 1.4292644980585305, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2918911949570316, "steering_wheel_angle": 4.002588962007569, "front_wheel_angle": 0.19461932612984398, "heading_rate": 0.11005019058417036, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137707.137511} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23314655998447792, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.421498970941374, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.5440651709752125, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137707.137511} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137707.147511, "x": 37.39382552635008, "y": 5.243835389611542, "z": null, "yaw": 2.9086209767789284, "pitch": null, "roll": null}, "v": 1.4206578155224943, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29121557706417617, "steering_wheel_angle": 4.597668404774173, "front_wheel_angle": 0.22567023360459276, "heading_rate": 0.12740460488720828, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137707.157511} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2242134115432084, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4198173197508823, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.651172659100804, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137707.157511} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.93995237350464, "x": 33.39382552635008, "y": 0.24383538961154194, "z": null, "yaw": 2.9086209767789284, "pitch": null, "roll": null}, "v": 1.4206578155224943, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29121557706417617, "steering_wheel_angle": 4.597668404774173, "front_wheel_angle": 0.22567023360459276, "heading_rate": 0.12740460488720828, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137707.177511} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.228415818203643, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.415626130548889, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.811091545246734, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137707.177511} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.93995237350464, "x": 33.39382552635008, "y": 0.24383538961154194, "z": null, "yaw": 2.9086209767789284, "pitch": null, "roll": null}, "v": 1.4206578155224943, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29121557706417617, "steering_wheel_angle": 4.597668404774173, "front_wheel_angle": 0.22567023360459276, "heading_rate": 0.12740460488720828, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137707.197511} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.228415818203643, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4133625687706066, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.917209238649047, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137707.197511} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.93995237350464, "x": 33.39382552635008, "y": 0.24383538961154194, "z": null, "yaw": 2.9086209767789284, "pitch": null, "roll": null}, "v": 1.4206578155224943, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29121557706417617, "steering_wheel_angle": 4.597668404774173, "front_wheel_angle": 0.22567023360459276, "heading_rate": 0.12740460488720828, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137707.217511} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.228415818203643, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4099738656956207, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.0756434327100575, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137707.217511} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.93995237350464, "x": 33.39382552635008, "y": 0.24383538961154194, "z": null, "yaw": 2.9086209767789284, "pitch": null, "roll": null}, "v": 1.4206578155224943, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29121557706417617, "steering_wheel_angle": 4.597668404774173, "front_wheel_angle": 0.22567023360459276, "heading_rate": 0.12740460488720828, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137707.237511} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.228415818203643, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4099738656956207, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.0756434327100575, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137707.237511} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137707.257511, "x": 37.24224924093999, "y": 5.279057633689925, "z": null, "yaw": 2.9191272111323796, "pitch": null, "roll": null}, "v": 1.4077191456522267, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2902026892129697, "steering_wheel_angle": 5.18077133138909, "front_wheel_angle": 0.2567211410793416, "heading_rate": 0.14435373134025967, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137707.257511} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24227963826310397, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4065931073978246, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.233186811520115, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137707.257511} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.049952268600464, "x": 33.24224924093999, "y": 0.2790576336899253, "z": null, "yaw": 2.9191272111323796, "pitch": null, "roll": null}, "v": 1.4077191456522267, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2902026892129697, "steering_wheel_angle": 5.18077133138909, "front_wheel_angle": 0.2567211410793416, "heading_rate": 0.14435373134025967, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137707.2875109} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2356006434430095, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.406075970336027, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.337720833365181, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137707.2875109} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.049952268600464, "x": 33.24224924093999, "y": 0.2790576336899253, "z": null, "yaw": 2.9191272111323796, "pitch": null, "roll": null}, "v": 1.4077191456522267, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2902026892129697, "steering_wheel_angle": 5.18077133138909, "front_wheel_angle": 0.2567211410793416, "heading_rate": 0.14435373134025967, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137707.2975109} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2356006434430095, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4047250926927803, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.441858937320935, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137707.2975109} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.049952268600464, "x": 33.24224924093999, "y": 0.2790576336899253, "z": null, "yaw": 2.9191272111323796, "pitch": null, "roll": null}, "v": 1.4077191456522267, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2902026892129697, "steering_wheel_angle": 5.18077133138909, "front_wheel_angle": 0.2567211410793416, "heading_rate": 0.14435373134025967, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137707.3175108} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2356006434430095, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4033763243304151, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.545601123387377, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137707.3175108} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.049952268600464, "x": 33.24224924093999, "y": 0.2790576336899253, "z": null, "yaw": 2.9191272111323796, "pitch": null, "roll": null}, "v": 1.4077191456522267, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2902026892129697, "steering_wheel_angle": 5.18077133138909, "front_wheel_angle": 0.2567211410793416, "heading_rate": 0.14435373134025967, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137707.3375108} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2356006434430095, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4027027298726689, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.597323747212105, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137707.3375108} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.049952268600464, "x": 33.24224924093999, "y": 0.2790576336899253, "z": null, "yaw": 2.9191272111323796, "pitch": null, "roll": null}, "v": 1.4077191456522267, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2902026892129697, "steering_wheel_angle": 5.18077133138909, "front_wheel_angle": 0.2567211410793416, "heading_rate": 0.14435373134025967, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137707.3575108} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2356006434430095, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.401357117895559, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.70047205644458, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137707.3575108} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137707.3675108, "x": 37.091375441450765, "y": 5.312347189377161, "z": null, "yaw": 2.9310588311227193, "pitch": null, "roll": null}, "v": 1.4006850993746116, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.28965344244483127, "steering_wheel_angle": 5.751897741852325, "front_wheel_angle": 0.2877720485540901, "heading_rate": 0.16194767281266428, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137707.3775108} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23051960503840765, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3993426347684919, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.854452174250832, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137707.3775108} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.15995216369629, "x": 33.091375441450765, "y": 0.312347189377161, "z": null, "yaw": 2.9310588311227193, "pitch": null, "roll": null}, "v": 1.4006850993746116, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.28965344244483127, "steering_wheel_angle": 5.751897741852325, "front_wheel_angle": 0.2877720485540901, "heading_rate": 0.16194767281266428, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137707.3975108} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23289730095078953, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.39835462278506, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.905580921241593, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137707.3975108} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.15995216369629, "x": 33.091375441450765, "y": 0.312347189377161, "z": null, "yaw": 2.9310588311227193, "pitch": null, "roll": null}, "v": 1.4006850993746116, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.28965344244483127, "steering_wheel_angle": 5.751897741852325, "front_wheel_angle": 0.2877720485540901, "heading_rate": 0.16194767281266428, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137707.4175107} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23289730095078953, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.395840676801964, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.058373285379909, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137707.4175107} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.15995216369629, "x": 33.091375441450765, "y": 0.312347189377161, "z": null, "yaw": 2.9310588311227193, "pitch": null, "roll": null}, "v": 1.4006850993746116, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.28965344244483127, "steering_wheel_angle": 5.751897741852325, "front_wheel_angle": 0.2877720485540901, "heading_rate": 0.16194767281266428, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137707.4375107} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23289730095078953, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3950040006534858, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.1091061144813565, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137707.4375107} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.15995216369629, "x": 33.091375441450765, "y": 0.312347189377161, "z": null, "yaw": 2.9310588311227193, "pitch": null, "roll": null}, "v": 1.4006850993746116, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.28965344244483127, "steering_wheel_angle": 5.751897741852325, "front_wheel_angle": 0.2877720485540901, "heading_rate": 0.16194767281266428, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137707.4575107} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23289730095078953, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3916638080008332, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.311047636163876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137707.4575107} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137707.4775107, "x": 36.940946022220956, "y": 5.34355859110001, "z": null, "yaw": 2.9444406429532584, "pitch": null, "roll": null}, "v": 1.3916638080008332, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2889504719450355, "steering_wheel_angle": 6.311047636163876, "front_wheel_angle": 0.3188229560288389, "heading_rate": 0.17943961376722972, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137707.4775107} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24834469608787935, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3916638080008332, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.311047636163876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137707.4775107} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.269952058792114, "x": 32.940946022220956, "y": 0.34355859110000964, "z": null, "yaw": 2.9444406429532584, "pitch": null, "roll": null}, "v": 1.3916638080008332, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2889504719450355, "steering_wheel_angle": 6.311047636163876, "front_wheel_angle": 0.3188229560288389, "heading_rate": 0.17943961376722972, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137707.4975107} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24093523028316693, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3920596161198995, "gear": 1, "accelerator_pedal_position": 0.24834469608787935, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.46146449296632, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137707.4975107} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.269952058792114, "x": 32.940946022220956, "y": 0.34355859110000964, "z": null, "yaw": 2.9444406429532584, "pitch": null, "roll": null}, "v": 1.3916638080008332, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2889504719450355, "steering_wheel_angle": 6.311047636163876, "front_wheel_angle": 0.3188229560288389, "heading_rate": 0.17943961376722972, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137707.5175107} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24093523028316693, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3913971522185145, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.561247500139642, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137707.5175107} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.269952058792114, "x": 32.940946022220956, "y": 0.34355859110000964, "z": null, "yaw": 2.9444406429532584, "pitch": null, "roll": null}, "v": 1.3916638080008332, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2889504719450355, "steering_wheel_angle": 6.311047636163876, "front_wheel_angle": 0.3188229560288389, "heading_rate": 0.17943961376722972, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137707.5375106} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24093523028316693, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.390735719123787, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.660634589423653, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137707.5375106} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.269952058792114, "x": 32.940946022220956, "y": 0.34355859110000964, "z": null, "yaw": 2.9444406429532584, "pitch": null, "roll": null}, "v": 1.3916638080008332, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2889504719450355, "steering_wheel_angle": 6.311047636163876, "front_wheel_angle": 0.3188229560288389, "heading_rate": 0.17943961376722972, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137707.5575106} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24093523028316693, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3904053885728784, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.710179664857168, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137707.5575106} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.269952058792114, "x": 32.940946022220956, "y": 0.34355859110000964, "z": null, "yaw": 2.9444406429532584, "pitch": null, "roll": null}, "v": 1.3916638080008332, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2889504719450355, "steering_wheel_angle": 6.311047636163876, "front_wheel_angle": 0.3188229560288389, "heading_rate": 0.17943961376722972, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137707.5775106} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24093523028316693, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.389745498353849, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.808972877307212, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137707.5775106} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137707.5875106, "x": 36.79069032702662, "y": 5.37253722829999, "z": null, "yaw": 2.95930098205555, "pitch": null, "roll": null}, "v": 1.3894159382423505, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.28877556340653626, "steering_wheel_angle": 6.858221014323742, "front_wheel_angle": 0.34987386350358746, "heading_rate": 0.1980382068674003, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137707.6075106} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2552821858094143, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3887575869086157, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.956420349939816, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137707.6075106} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.37995195388794, "x": 32.79069032702662, "y": 0.3725372282999899, "z": null, "yaw": 2.95930098205555, "pitch": null, "roll": null}, "v": 1.3894159382423505, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.28877556340653626, "steering_wheel_angle": 6.858221014323742, "front_wheel_angle": 0.34987386350358746, "heading_rate": 0.1980382068674003, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137707.6275105} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2484369724411658, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3898929313089081, "gear": 1, "accelerator_pedal_position": 0.2552821858094143, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.05422376766658, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137707.6275105} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.37995195388794, "x": 32.79069032702662, "y": 0.3725372282999899, "z": null, "yaw": 2.95930098205555, "pitch": null, "roll": null}, "v": 1.3894159382423505, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.28877556340653626, "steering_wheel_angle": 6.858221014323742, "front_wheel_angle": 0.34987386350358746, "heading_rate": 0.1980382068674003, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137707.6375105} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2484369724411658, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3901711911764767, "gear": 1, "accelerator_pedal_position": 0.2484369724411658, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.151631267504033, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137707.6375105} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.37995195388794, "x": 32.79069032702662, "y": 0.3725372282999899, "z": null, "yaw": 2.95930098205555, "pitch": null, "roll": null}, "v": 1.3894159382423505, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.28877556340653626, "steering_wheel_angle": 6.858221014323742, "front_wheel_angle": 0.34987386350358746, "heading_rate": 0.1980382068674003, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137707.6575105} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2484369724411658, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3903101587643836, "gear": 1, "accelerator_pedal_position": 0.2484369724411658, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.2001865482142655, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137707.6575105} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.37995195388794, "x": 32.79069032702662, "y": 0.3725372282999899, "z": null, "yaw": 2.95930098205555, "pitch": null, "roll": null}, "v": 1.3894159382423505, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.28877556340653626, "steering_wheel_angle": 6.858221014323742, "front_wheel_angle": 0.34987386350358746, "heading_rate": 0.1980382068674003, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137707.6775105} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2484369724411658, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.390587769650047, "gear": 1, "accelerator_pedal_position": 0.2484369724411658, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.29700017121775, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137707.6775105} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137707.6975105, "x": 36.6401388758025, "y": 5.399152089002255, "z": null, "yaw": 2.97567196418474, "pitch": null, "roll": null}, "v": 1.390864948683692, "accelerator_pedal_position": 0.2484369724411658, "brake_pedal_position": 0.0, "acceleration": 0.013842777268332718, "steering_wheel_angle": 7.393417876331923, "front_wheel_angle": 0.38092477097833655, "heading_rate": 0.21758637912714646, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137707.6975105} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26303238289221154, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.390864948683692, "gear": 1, "accelerator_pedal_position": 0.2484369724411658, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.393417876331923, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137707.6975105} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.489951848983765, "x": 32.6401388758025, "y": 0.3991520890022553, "z": null, "yaw": 2.97567196418474, "pitch": null, "roll": null}, "v": 1.390864948683692, "accelerator_pedal_position": 0.2484369724411658, "brake_pedal_position": 0.0, "acceleration": 0.013842777268332718, "steering_wheel_angle": 7.393417876331923, "front_wheel_angle": 0.38092477097833655, "heading_rate": 0.21758637912714646, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137707.7175105} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25609077346368914, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3929654128446642, "gear": 1, "accelerator_pedal_position": 0.26303238289221154, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.489439663556782, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137707.7175105} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.489951848983765, "x": 32.6401388758025, "y": 0.3991520890022553, "z": null, "yaw": 2.97567196418474, "pitch": null, "roll": null}, "v": 1.390864948683692, "accelerator_pedal_position": 0.2484369724411658, "brake_pedal_position": 0.0, "acceleration": 0.013842777268332718, "steering_wheel_angle": 7.393417876331923, "front_wheel_angle": 0.38092477097833655, "heading_rate": 0.21758637912714646, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137707.7375104} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25609077346368914, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3941952445929464, "gear": 1, "accelerator_pedal_position": 0.25609077346368914, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.585065532892331, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137707.7375104} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.489951848983765, "x": 32.6401388758025, "y": 0.3991520890022553, "z": null, "yaw": 2.97567196418474, "pitch": null, "roll": null}, "v": 1.390864948683692, "accelerator_pedal_position": 0.2484369724411658, "brake_pedal_position": 0.0, "acceleration": 0.013842777268332718, "steering_wheel_angle": 7.393417876331923, "front_wheel_angle": 0.38092477097833655, "heading_rate": 0.21758637912714646, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137707.7575104} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25609077346368914, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3954231615564439, "gear": 1, "accelerator_pedal_position": 0.25609077346368914, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.680295484338568, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137707.7575104} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.489951848983765, "x": 32.6401388758025, "y": 0.3991520890022553, "z": null, "yaw": 2.97567196418474, "pitch": null, "roll": null}, "v": 1.390864948683692, "accelerator_pedal_position": 0.2484369724411658, "brake_pedal_position": 0.0, "acceleration": 0.013842777268332718, "steering_wheel_angle": 7.393417876331923, "front_wheel_angle": 0.38092477097833655, "heading_rate": 0.21758637912714646, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137707.7775104} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25609077346368914, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.397261451982604, "gear": 1, "accelerator_pedal_position": 0.25609077346368914, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.822398065465462, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137707.7775104} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137707.8075104, "x": 36.48863361434647, "y": 5.423275262681312, "z": null, "yaw": 2.9935897784763044, "pitch": null, "roll": null}, "v": 1.3984845923874518, "accelerator_pedal_position": 0.25609077346368914, "brake_pedal_position": 0.0, "acceleration": 0.061085512977233414, "steering_wheel_angle": 7.91663822218842, "front_wheel_angle": 0.4119756784530851, "heading_rate": 0.23871592206803718, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137707.8075104} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2702097110684939, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3984845923874518, "gear": 1, "accelerator_pedal_position": 0.25609077346368914, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.91663822218842, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137707.8075104} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.59995174407959, "x": 32.48863361434647, "y": 0.42327526268131166, "z": null, "yaw": 2.9935897784763044, "pitch": null, "roll": null}, "v": 1.3984845923874518, "accelerator_pedal_position": 0.25609077346368914, "brake_pedal_position": 0.0, "acceleration": 0.061085512977233414, "steering_wheel_angle": 7.91663822218842, "front_wheel_angle": 0.4119756784530851, "heading_rate": 0.23871592206803718, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137707.8175104} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.263531624734543, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4014700053119848, "gear": 1, "accelerator_pedal_position": 0.2702097110684939, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.010482461022063, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137707.8175104} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.59995174407959, "x": 32.48863361434647, "y": 0.42327526268131166, "z": null, "yaw": 2.9935897784763044, "pitch": null, "roll": null}, "v": 1.3984845923874518, "accelerator_pedal_position": 0.25609077346368914, "brake_pedal_position": 0.0, "acceleration": 0.061085512977233414, "steering_wheel_angle": 7.91663822218842, "front_wheel_angle": 0.4119756784530851, "heading_rate": 0.23871592206803718, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137707.8375103} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.263531624734543, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4025435850376589, "gear": 1, "accelerator_pedal_position": 0.263531624734543, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.057256111230394, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137707.8375103} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.59995174407959, "x": 32.48863361434647, "y": 0.42327526268131166, "z": null, "yaw": 2.9935897784763044, "pitch": null, "roll": null}, "v": 1.3984845923874518, "accelerator_pedal_position": 0.25609077346368914, "brake_pedal_position": 0.0, "acceleration": 0.061085512977233414, "steering_wheel_angle": 7.91663822218842, "front_wheel_angle": 0.4119756784530851, "heading_rate": 0.23871592206803718, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137707.8575103} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.263531624734543, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4057592989708012, "gear": 1, "accelerator_pedal_position": 0.263531624734543, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.19698318502142, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137707.8575103} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.59995174407959, "x": 32.48863361434647, "y": 0.42327526268131166, "z": null, "yaw": 2.9935897784763044, "pitch": null, "roll": null}, "v": 1.3984845923874518, "accelerator_pedal_position": 0.25609077346368914, "brake_pedal_position": 0.0, "acceleration": 0.061085512977233414, "steering_wheel_angle": 7.91663822218842, "front_wheel_angle": 0.4119756784530851, "heading_rate": 0.23871592206803718, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137707.8775103} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.263531624734543, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4068295299465605, "gear": 1, "accelerator_pedal_position": 0.263531624734543, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.243360917340437, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137707.8775103} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.59995174407959, "x": 32.48863361434647, "y": 0.42327526268131166, "z": null, "yaw": 2.9935897784763044, "pitch": null, "roll": null}, "v": 1.3984845923874518, "accelerator_pedal_position": 0.25609077346368914, "brake_pedal_position": 0.0, "acceleration": 0.061085512977233414, "steering_wheel_angle": 7.91663822218842, "front_wheel_angle": 0.4119756784530851, "heading_rate": 0.23871592206803718, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137707.8975103} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.263531624734543, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.408967483940131, "gear": 1, "accelerator_pedal_position": 0.263531624734543, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.33581944356149, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137707.8975103} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137707.9175103, "x": 36.335628941779476, "y": 5.444720841633471, "z": null, "yaw": 3.0130950284481797, "pitch": null, "roll": null}, "v": 1.4111020968202697, "accelerator_pedal_position": 0.263531624734543, "brake_pedal_position": 0.0, "acceleration": 0.10660545847337455, "steering_wheel_angle": 8.427882051893233, "front_wheel_angle": 0.4430265859278339, "heading_rate": 0.261540715684972, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137707.9175103} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27789329523676826, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.920054241619905, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4111020968202697, "gear": 1, "accelerator_pedal_position": 0.263531624734543, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.427882051893233, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137707.9175103} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.709951639175415, "x": 32.335628941779476, "y": 0.4447208416334707, "z": null, "yaw": 3.0130950284481797, "pitch": null, "roll": null}, "v": 1.4111020968202697, "accelerator_pedal_position": 0.263531624734543, "brake_pedal_position": 0.0, "acceleration": 0.10660545847337455, "steering_wheel_angle": 8.427882051893233, "front_wheel_angle": 0.4430265859278339, "heading_rate": 0.261540715684972, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137707.9375103} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2711294773290152, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.920054241619905, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4150278784027601, "gear": 1, "accelerator_pedal_position": 0.27789329523676826, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.519194393616216, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137707.9375103} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.709951639175415, "x": 32.335628941779476, "y": 0.4447208416334707, "z": null, "yaw": 3.0130950284481797, "pitch": null, "roll": null}, "v": 1.4111020968202697, "accelerator_pedal_position": 0.263531624734543, "brake_pedal_position": 0.0, "acceleration": 0.10660545847337455, "steering_wheel_angle": 8.427882051893233, "front_wheel_angle": 0.4430265859278339, "heading_rate": 0.261540715684972, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137707.9575102} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2711294773290152, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.920054241619905, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4196378097459523, "gear": 1, "accelerator_pedal_position": 0.2711294773290152, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.655426300647763, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137707.9575102} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.709951639175415, "x": 32.335628941779476, "y": 0.4447208416334707, "z": null, "yaw": 3.0130950284481797, "pitch": null, "roll": null}, "v": 1.4111020968202697, "accelerator_pedal_position": 0.263531624734543, "brake_pedal_position": 0.0, "acceleration": 0.10660545847337455, "steering_wheel_angle": 8.427882051893233, "front_wheel_angle": 0.4430265859278339, "heading_rate": 0.261540715684972, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137707.9775102} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2711294773290152, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.920054241619905, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.422705079334669, "gear": 1, "accelerator_pedal_position": 0.2711294773290152, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.745756501633505, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137707.9775102} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.709951639175415, "x": 32.335628941779476, "y": 0.4447208416334707, "z": null, "yaw": 3.0130950284481797, "pitch": null, "roll": null}, "v": 1.4111020968202697, "accelerator_pedal_position": 0.263531624734543, "brake_pedal_position": 0.0, "acceleration": 0.10660545847337455, "steering_wheel_angle": 8.427882051893233, "front_wheel_angle": 0.4430265859278339, "heading_rate": 0.261540715684972, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137707.9975102} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2711294773290152, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.920054241619905, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4257675389541506, "gear": 1, "accelerator_pedal_position": 0.2711294773290152, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.83569384632435, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137707.9975102} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.709951639175415, "x": 32.335628941779476, "y": 0.4447208416334707, "z": null, "yaw": 3.0130950284481797, "pitch": null, "roll": null}, "v": 1.4111020968202697, "accelerator_pedal_position": 0.263531624734543, "brake_pedal_position": 0.0, "acceleration": 0.10660545847337455, "steering_wheel_angle": 8.427882051893233, "front_wheel_angle": 0.4430265859278339, "heading_rate": 0.261540715684972, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137708.0175102} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2711294773290152, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.920054241619905, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4303522179910286, "gear": 1, "accelerator_pedal_position": 0.2711294773290152, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.969863257807688, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137708.0175102} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137708.0275102, "x": 36.18058938107474, "y": 5.4632590356431, "z": null, "yaw": 3.0342301938252714, "pitch": null, "roll": null}, "v": 1.4288251923972066, "accelerator_pedal_position": 0.2711294773290152, "brake_pedal_position": 0.0, "acceleration": 0.1527025593821955, "steering_wheel_angle": 8.925238334720298, "front_wheel_angle": 0.4739572035847093, "heading_rate": 0.2862976267151372, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137708.0375102} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.275497804484986, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.263850384187679, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4303522179910286, "gear": 1, "accelerator_pedal_position": 0.2711294773290152, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.969863257807688, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137708.0375102} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.81995153427124, "x": 32.18058938107474, "y": 0.4632590356430999, "z": null, "yaw": 3.0342301938252714, "pitch": null, "roll": null}, "v": 1.4288251923972066, "accelerator_pedal_position": 0.2711294773290152, "brake_pedal_position": 0.0, "acceleration": 0.1527025593821955, "steering_wheel_angle": 8.925238334720298, "front_wheel_angle": 0.4739572035847093, "heading_rate": 0.2862976267151372, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137708.0575101} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2735235126859268, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.263850384187679, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4356211199633082, "gear": 1, "accelerator_pedal_position": 0.2735235126859268, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.969863257807688, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137708.0575101} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.81995153427124, "x": 32.18058938107474, "y": 0.4632590356430999, "z": null, "yaw": 3.0342301938252714, "pitch": null, "roll": null}, "v": 1.4288251923972066, "accelerator_pedal_position": 0.2711294773290152, "brake_pedal_position": 0.0, "acceleration": 0.1527025593821955, "steering_wheel_angle": 8.925238334720298, "front_wheel_angle": 0.4739572035847093, "heading_rate": 0.2862976267151372, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137708.07751} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2735235126859268, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.263850384187679, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4372924281461885, "gear": 1, "accelerator_pedal_position": 0.2735235126859268, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.969863257807688, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137708.07751} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.81995153427124, "x": 32.18058938107474, "y": 0.4632590356430999, "z": null, "yaw": 3.0342301938252714, "pitch": null, "roll": null}, "v": 1.4288251923972066, "accelerator_pedal_position": 0.2711294773290152, "brake_pedal_position": 0.0, "acceleration": 0.1527025593821955, "steering_wheel_angle": 8.925238334720298, "front_wheel_angle": 0.4739572035847093, "heading_rate": 0.2862976267151372, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137708.09751} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2735235126859268, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.263850384187679, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4422984597685833, "gear": 1, "accelerator_pedal_position": 0.2735235126859268, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.969863257807688, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137708.09751} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.81995153427124, "x": 32.18058938107474, "y": 0.4632590356430999, "z": null, "yaw": 3.0342301938252714, "pitch": null, "roll": null}, "v": 1.4288251923972066, "accelerator_pedal_position": 0.2711294773290152, "brake_pedal_position": 0.0, "acceleration": 0.1527025593821955, "steering_wheel_angle": 8.925238334720298, "front_wheel_angle": 0.4739572035847093, "heading_rate": 0.2862976267151372, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137708.11751} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2735235126859268, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.263850384187679, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4456292415360164, "gear": 1, "accelerator_pedal_position": 0.2735235126859268, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.969863257807688, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137708.11751} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137708.13751, "x": 36.02324303937578, "y": 5.478611503154395, "z": null, "yaw": 3.0564101364661527, "pitch": null, "roll": null}, "v": 1.4472926620677204, "accelerator_pedal_position": 0.2735235126859268, "brake_pedal_position": 0.0, "acceleration": 0.1662107606869056, "steering_wheel_angle": 8.969863257807688, "front_wheel_angle": 0.4767690779171527, "heading_rate": 0.29200888186066803, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137708.13751} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2920887157622095, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.62978831753155, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4472926620677204, "gear": 1, "accelerator_pedal_position": 0.2735235126859268, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.969863257807688, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137708.13751} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.929951429367065, "x": 32.02324303937578, "y": 0.4786115031543954, "z": null, "yaw": 3.0564101364661527, "pitch": null, "roll": null}, "v": 1.4472926620677204, "accelerator_pedal_position": 0.2735235126859268, "brake_pedal_position": 0.0, "acceleration": 0.1662107606869056, "steering_wheel_angle": 8.969863257807688, "front_wheel_angle": 0.4767690779171527, "heading_rate": 0.29200888186066803, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137708.15751} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2833589590545885, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.62978831753155, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4552076638690856, "gear": 1, "accelerator_pedal_position": 0.2833589590545885, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.969863257807688, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137708.15751} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.929951429367065, "x": 32.02324303937578, "y": 0.4786115031543954, "z": null, "yaw": 3.0564101364661527, "pitch": null, "roll": null}, "v": 1.4472926620677204, "accelerator_pedal_position": 0.2735235126859268, "brake_pedal_position": 0.0, "acceleration": 0.1662107606869056, "steering_wheel_angle": 8.969863257807688, "front_wheel_angle": 0.4767690779171527, "heading_rate": 0.29200888186066803, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137708.17751} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2833589590545885, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.62978831753155, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4574782320435646, "gear": 1, "accelerator_pedal_position": 0.2833589590545885, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.969863257807688, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137708.17751} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.929951429367065, "x": 32.02324303937578, "y": 0.4786115031543954, "z": null, "yaw": 3.0564101364661527, "pitch": null, "roll": null}, "v": 1.4472926620677204, "accelerator_pedal_position": 0.2735235126859268, "brake_pedal_position": 0.0, "acceleration": 0.1662107606869056, "steering_wheel_angle": 8.969863257807688, "front_wheel_angle": 0.4767690779171527, "heading_rate": 0.29200888186066803, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137708.19751} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2833589590545885, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.62978831753155, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4620139788964353, "gear": 1, "accelerator_pedal_position": 0.2833589590545885, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.969863257807688, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137708.19751} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.929951429367065, "x": 32.02324303937578, "y": 0.4786115031543954, "z": null, "yaw": 3.0564101364661527, "pitch": null, "roll": null}, "v": 1.4472926620677204, "accelerator_pedal_position": 0.2735235126859268, "brake_pedal_position": 0.0, "acceleration": 0.1662107606869056, "steering_wheel_angle": 8.969863257807688, "front_wheel_angle": 0.4767690779171527, "heading_rate": 0.29200888186066803, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137708.21751} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2833589590545885, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.62978831753155, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4665425423768206, "gear": 1, "accelerator_pedal_position": 0.2833589590545885, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.969863257807688, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137708.21751} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.929951429367065, "x": 32.02324303937578, "y": 0.4786115031543954, "z": null, "yaw": 3.0564101364661527, "pitch": null, "roll": null}, "v": 1.4472926620677204, "accelerator_pedal_position": 0.2735235126859268, "brake_pedal_position": 0.0, "acceleration": 0.1662107606869056, "steering_wheel_angle": 8.969863257807688, "front_wheel_angle": 0.4767690779171527, "heading_rate": 0.29200888186066803, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137708.23751} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2833589590545885, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.62978831753155, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4710639256612987, "gear": 1, "accelerator_pedal_position": 0.2833589590545885, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.969863257807688, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137708.23751} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137708.24751, "x": 35.86314359678499, "y": 5.490651524303537, "z": null, "yaw": 3.078603973170045, "pitch": null, "roll": null}, "v": 1.4733219257320416, "accelerator_pedal_position": 0.2833589590545885, "brake_pedal_position": 0.0, "acceleration": 0.22562062283614842, "steering_wheel_angle": 8.969863257807688, "front_wheel_angle": 0.4767690779171527, "heading_rate": 0.29726060210874544, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137708.25751} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.30071904222028517, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.89075989555182, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.475578131960403, "gear": 1, "accelerator_pedal_position": 0.2833589590545885, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.969863257807688, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137708.25751} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.03995132446289, "x": 31.863143596784987, "y": 0.4906515243035372, "z": null, "yaw": 3.078603973170045, "pitch": null, "roll": null}, "v": 1.4733219257320416, "accelerator_pedal_position": 0.2833589590545885, "brake_pedal_position": 0.0, "acceleration": 0.22562062283614842, "steering_wheel_angle": 8.969863257807688, "front_wheel_angle": 0.4767690779171527, "heading_rate": 0.29726060210874544, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137708.27751} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29260941210206887, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.89075989555182, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4822543116026758, "gear": 1, "accelerator_pedal_position": 0.30071904222028517, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.893605448850264, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137708.27751} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.03995132446289, "x": 31.863143596784987, "y": 0.4906515243035372, "z": null, "yaw": 3.078603973170045, "pitch": null, "roll": null}, "v": 1.4733219257320416, "accelerator_pedal_position": 0.2833589590545885, "brake_pedal_position": 0.0, "acceleration": 0.22562062283614842, "steering_wheel_angle": 8.969863257807688, "front_wheel_angle": 0.4767690779171527, "heading_rate": 0.29726060210874544, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137708.29751} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29260941210206887, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.89075989555182, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4879065656673012, "gear": 1, "accelerator_pedal_position": 0.29260941210206887, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.817061280526435, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137708.29751} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.03995132446289, "x": 31.863143596784987, "y": 0.4906515243035372, "z": null, "yaw": 3.078603973170045, "pitch": null, "roll": null}, "v": 1.4733219257320416, "accelerator_pedal_position": 0.2833589590545885, "brake_pedal_position": 0.0, "acceleration": 0.22562062283614842, "steering_wheel_angle": 8.969863257807688, "front_wheel_angle": 0.4767690779171527, "heading_rate": 0.29726060210874544, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137708.31751} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29260941210206887, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.89075989555182, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.496368054504291, "gear": 1, "accelerator_pedal_position": 0.29260941210206887, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.701708104228675, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137708.31751} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.03995132446289, "x": 31.863143596784987, "y": 0.4906515243035372, "z": null, "yaw": 3.078603973170045, "pitch": null, "roll": null}, "v": 1.4733219257320416, "accelerator_pedal_position": 0.2833589590545885, "brake_pedal_position": 0.0, "acceleration": 0.22562062283614842, "steering_wheel_angle": 8.969863257807688, "front_wheel_angle": 0.4767690779171527, "heading_rate": 0.29726060210874544, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137708.3375099} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29260941210206887, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.89075989555182, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.499184046997964, "gear": 1, "accelerator_pedal_position": 0.29260941210206887, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.66311386577955, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137708.3375099} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137708.3575099, "x": 35.69972760846231, "y": 5.499319216941686, "z": null, "yaw": 3.100267349617838, "pitch": null, "roll": null}, "v": 1.5048092775770707, "accelerator_pedal_position": 0.29260941210206887, "brake_pedal_position": 0.0, "acceleration": 0.28092385214025656, "steering_wheel_angle": 8.585710619356494, "front_wheel_angle": 0.45276225186858277, "heading_rate": 0.2859528101465999, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137708.3575099} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3090762552492835, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.0777807893218245, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5086476937951743, "gear": 1, "accelerator_pedal_position": 0.3090762552492835, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.548241871226665, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137708.3575099} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.149951219558716, "x": 31.69972760846231, "y": 0.4993192169416858, "z": null, "yaw": 3.100267349617838, "pitch": null, "roll": null}, "v": 1.5048092775770707, "accelerator_pedal_position": 0.29260941210206887, "brake_pedal_position": 0.0, "acceleration": 0.28092385214025656, "steering_wheel_angle": 8.585710619356494, "front_wheel_angle": 0.45276225186858277, "heading_rate": 0.2859528101465999, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137708.3775098} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3014262958142747, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.0777807893218245, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5124830341149575, "gear": 1, "accelerator_pedal_position": 0.3090762552492835, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.510706388302365, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137708.3775098} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.149951219558716, "x": 31.69972760846231, "y": 0.4993192169416858, "z": null, "yaw": 3.100267349617838, "pitch": null, "roll": null}, "v": 1.5048092775770707, "accelerator_pedal_position": 0.29260941210206887, "brake_pedal_position": 0.0, "acceleration": 0.28092385214025656, "steering_wheel_angle": 8.585710619356494, "front_wheel_angle": 0.45276225186858277, "heading_rate": 0.2859528101465999, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137708.3975098} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3014262958142747, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.0777807893218245, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.519188624259748, "gear": 1, "accelerator_pedal_position": 0.3014262958142747, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.435435218070353, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137708.3975098} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.149951219558716, "x": 31.69972760846231, "y": 0.4993192169416858, "z": null, "yaw": 3.100267349617838, "pitch": null, "roll": null}, "v": 1.5048092775770707, "accelerator_pedal_position": 0.29260941210206887, "brake_pedal_position": 0.0, "acceleration": 0.28092385214025656, "steering_wheel_angle": 8.585710619356494, "front_wheel_angle": 0.45276225186858277, "heading_rate": 0.2859528101465999, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137708.4175098} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3014262958142747, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.0777807893218245, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5292268125582973, "gear": 1, "accelerator_pedal_position": 0.3014262958142747, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.3220279517638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137708.4175098} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.149951219558716, "x": 31.69972760846231, "y": 0.4993192169416858, "z": null, "yaw": 3.100267349617838, "pitch": null, "roll": null}, "v": 1.5048092775770707, "accelerator_pedal_position": 0.29260941210206887, "brake_pedal_position": 0.0, "acceleration": 0.28092385214025656, "steering_wheel_angle": 8.585710619356494, "front_wheel_angle": 0.45276225186858277, "heading_rate": 0.2859528101465999, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137708.4375098} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3014262958142747, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.0777807893218245, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5325674891759855, "gear": 1, "accelerator_pedal_position": 0.3014262958142747, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.284092060072675, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137708.4375098} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.149951219558716, "x": 31.69972760846231, "y": 0.4993192169416858, "z": null, "yaw": 3.100267349617838, "pitch": null, "roll": null}, "v": 1.5048092775770707, "accelerator_pedal_position": 0.29260941210206887, "brake_pedal_position": 0.0, "acceleration": 0.28092385214025656, "steering_wheel_angle": 8.585710619356494, "front_wheel_angle": 0.45276225186858277, "heading_rate": 0.2859528101465999, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137708.4575098} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3014262958142747, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.0777807893218245, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.542573359693317, "gear": 1, "accelerator_pedal_position": 0.3014262958142747, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.16988397623247, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137708.4575098} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137708.4675097, "x": 35.53235266513477, "y": 5.504668599191224, "z": null, "yaw": 3.1205591412237306, "pitch": null, "roll": null}, "v": 1.542573359693317, "accelerator_pedal_position": 0.3014262958142747, "brake_pedal_position": 0.0, "acceleration": 0.33299035515419567, "steering_wheel_angle": 8.16988397623247, "front_wheel_angle": 0.4272659088318139, "heading_rate": 0.2743587221885025, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137708.4775097} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.31373171806864875, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.177441401670043, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.545903263244859, "gear": 1, "accelerator_pedal_position": 0.3014262958142747, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.13168114536346, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137708.4775097} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.25995111465454, "x": 31.532352665134773, "y": 0.5046685991912243, "z": null, "yaw": 3.1205591412237306, "pitch": null, "roll": null}, "v": 1.542573359693317, "accelerator_pedal_position": 0.3014262958142747, "brake_pedal_position": 0.0, "acceleration": 0.33299035515419567, "steering_wheel_angle": 8.16988397623247, "front_wheel_angle": 0.4272659088318139, "heading_rate": 0.2743587221885025, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137708.4975097} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3081035347693165, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.177441401670043, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5540925450364214, "gear": 1, "accelerator_pedal_position": 0.31373171806864875, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.060517871407116, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137708.4975097} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.25995111465454, "x": 31.532352665134773, "y": 0.5046685991912243, "z": null, "yaw": 3.1205591412237306, "pitch": null, "roll": null}, "v": 1.542573359693317, "accelerator_pedal_position": 0.3014262958142747, "brake_pedal_position": 0.0, "acceleration": 0.33299035515419567, "steering_wheel_angle": 8.16988397623247, "front_wheel_angle": 0.4272659088318139, "heading_rate": 0.2743587221885025, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137708.5175097} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3081035347693165, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.177441401670043, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5690259679099974, "gear": 1, "accelerator_pedal_position": 0.3081035347693165, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.917500083736472, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137708.5175097} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.25995111465454, "x": 31.532352665134773, "y": 0.5046685991912243, "z": null, "yaw": 3.1205591412237306, "pitch": null, "roll": null}, "v": 1.542573359693317, "accelerator_pedal_position": 0.3014262958142747, "brake_pedal_position": 0.0, "acceleration": 0.33299035515419567, "steering_wheel_angle": 8.16988397623247, "front_wheel_angle": 0.4272659088318139, "heading_rate": 0.2743587221885025, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137708.5375097} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3081035347693165, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.177441401670043, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5690259679099974, "gear": 1, "accelerator_pedal_position": 0.3081035347693165, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.917500083736472, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137708.5375097} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.25995111465454, "x": 31.532352665134773, "y": 0.5046685991912243, "z": null, "yaw": 3.1205591412237306, "pitch": null, "roll": null}, "v": 1.542573359693317, "accelerator_pedal_position": 0.3014262958142747, "brake_pedal_position": 0.0, "acceleration": 0.33299035515419567, "steering_wheel_angle": 8.16988397623247, "front_wheel_angle": 0.4272659088318139, "heading_rate": 0.2743587221885025, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137708.5675097} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3081035347693165, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.177441401670043, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5876244989442967, "gear": 1, "accelerator_pedal_position": 0.3081035347693165, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.737431774602001, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137708.5675097} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137708.5775096, "x": 35.36061105566415, "y": 5.5067731251058625, "z": null, "yaw": 3.1395610195500656, "pitch": null, "roll": null}, "v": 1.5839108608131212, "accelerator_pedal_position": 0.3081035347693165, "brake_pedal_position": 0.0, "acceleration": 0.37136381311755434, "steering_wheel_angle": 7.77356064305522, "front_wheel_angle": 0.40341365942599255, "heading_rate": 0.26408181693435984, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137708.5875096} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.32456758969452576, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.351043230487847, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.591335102462942, "gear": 1, "accelerator_pedal_position": 0.3081035347693165, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.701245302835616, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137708.5875096} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.369951009750366, "x": 31.36061105566415, "y": 0.5067731251058625, "z": null, "yaw": 3.1395610195500656, "pitch": null, "roll": null}, "v": 1.5839108608131212, "accelerator_pedal_position": 0.3081035347693165, "brake_pedal_position": 0.0, "acceleration": 0.37136381311755434, "steering_wheel_angle": 7.77356064305522, "front_wheel_angle": 0.40341365942599255, "heading_rate": 0.26408181693435984, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137708.6075096} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3169835053134181, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.351043230487847, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.600804368566407, "gear": 1, "accelerator_pedal_position": 0.32456758969452576, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.63076933909628, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137708.6075096} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.369951009750366, "x": 31.36061105566415, "y": 0.5067731251058625, "z": null, "yaw": 3.1395610195500656, "pitch": null, "roll": null}, "v": 1.5839108608131212, "accelerator_pedal_position": 0.3081035347693165, "brake_pedal_position": 0.0, "acceleration": 0.37136381311755434, "steering_wheel_angle": 7.77356064305522, "front_wheel_angle": 0.40341365942599255, "heading_rate": 0.26408181693435984, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137708.6275096} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3169835053134181, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.351043230487847, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6050591780015704, "gear": 1, "accelerator_pedal_position": 0.3169835053134181, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.595449804953128, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137708.6275096} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.369951009750366, "x": 31.36061105566415, "y": 0.5067731251058625, "z": null, "yaw": 3.1395610195500656, "pitch": null, "roll": null}, "v": 1.5839108608131212, "accelerator_pedal_position": 0.3081035347693165, "brake_pedal_position": 0.0, "acceleration": 0.37136381311755434, "steering_wheel_angle": 7.77356064305522, "front_wheel_angle": 0.40341365942599255, "heading_rate": 0.26408181693435984, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137708.6475096} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3169835053134181, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.351043230487847, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.613558321805006, "gear": 1, "accelerator_pedal_position": 0.3169835053134181, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.52464763211986, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137708.6475096} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.369951009750366, "x": 31.36061105566415, "y": 0.5067731251058625, "z": null, "yaw": 3.1395610195500656, "pitch": null, "roll": null}, "v": 1.5839108608131212, "accelerator_pedal_position": 0.3081035347693165, "brake_pedal_position": 0.0, "acceleration": 0.37136381311755434, "steering_wheel_angle": 7.77356064305522, "front_wheel_angle": 0.40341365942599255, "heading_rate": 0.26408181693435984, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137708.6675096} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3169835053134181, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.351043230487847, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.622043493892205, "gear": 1, "accelerator_pedal_position": 0.3169835053134181, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.453627986557306, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137708.6675096} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137708.6875095, "x": 35.18407876211867, "y": 5.5056782850167565, "z": null, "yaw": 3.1573676367842447, "pitch": null, "roll": null}, "v": 1.6305146884438313, "accelerator_pedal_position": 0.3169835053134181, "brake_pedal_position": 0.0, "acceleration": 0.42303539229436066, "steering_wheel_angle": 7.382390868265467, "front_wheel_angle": 0.38027792224528667, "heading_rate": 0.2545991468724216, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137708.6875095} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.33170453754097096, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.5180599747467607, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6305146884438313, "gear": 1, "accelerator_pedal_position": 0.3169835053134181, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.382390868265467, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137708.6875095} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.47995090484619, "x": 31.184078762118673, "y": 0.5056782850167565, "z": null, "yaw": 3.1573676367842447, "pitch": null, "roll": null}, "v": 1.6305146884438313, "accelerator_pedal_position": 0.3169835053134181, "brake_pedal_position": 0.0, "acceleration": 0.42303539229436066, "steering_wheel_angle": 7.382390868265467, "front_wheel_angle": 0.38027792224528667, "heading_rate": 0.2545991468724216, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137708.7075095} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3249861940173695, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.5180599747467607, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6408112678896802, "gear": 1, "accelerator_pedal_position": 0.33170453754097096, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.312879653012157, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137708.7075095} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.47995090484619, "x": 31.184078762118673, "y": 0.5056782850167565, "z": null, "yaw": 3.1573676367842447, "pitch": null, "roll": null}, "v": 1.6305146884438313, "accelerator_pedal_position": 0.3169835053134181, "brake_pedal_position": 0.0, "acceleration": 0.42303539229436066, "steering_wheel_angle": 7.382390868265467, "front_wheel_angle": 0.38027792224528667, "heading_rate": 0.2545991468724216, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137708.7275095} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3249861940173695, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.5180599747467607, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6502513657342857, "gear": 1, "accelerator_pedal_position": 0.3249861940173695, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.243162616519813, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137708.7275095} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.47995090484619, "x": 31.184078762118673, "y": 0.5056782850167565, "z": null, "yaw": 3.1573676367842447, "pitch": null, "roll": null}, "v": 1.6305146884438313, "accelerator_pedal_position": 0.3169835053134181, "brake_pedal_position": 0.0, "acceleration": 0.42303539229436066, "steering_wheel_angle": 7.382390868265467, "front_wheel_angle": 0.38027792224528667, "heading_rate": 0.2545991468724216, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137708.7475095} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3249861940173695, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.5180599747467607, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.659675807479213, "gear": 1, "accelerator_pedal_position": 0.3249861940173695, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.173239758788436, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137708.7475095} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.47995090484619, "x": 31.184078762118673, "y": 0.5056782850167565, "z": null, "yaw": 3.1573676367842447, "pitch": null, "roll": null}, "v": 1.6305146884438313, "accelerator_pedal_position": 0.3169835053134181, "brake_pedal_position": 0.0, "acceleration": 0.42303539229436066, "steering_wheel_angle": 7.382390868265467, "front_wheel_angle": 0.38027792224528667, "heading_rate": 0.2545991468724216, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137708.7675095} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3249861940173695, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.5180599747467607, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.669084583576327, "gear": 1, "accelerator_pedal_position": 0.3249861940173695, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.103111079818028, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137708.7675095} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.47995090484619, "x": 31.184078762118673, "y": 0.5056782850167565, "z": null, "yaw": 3.1573676367842447, "pitch": null, "roll": null}, "v": 1.6305146884438313, "accelerator_pedal_position": 0.3169835053134181, "brake_pedal_position": 0.0, "acceleration": 0.42303539229436066, "steering_wheel_angle": 7.382390868265467, "front_wheel_angle": 0.38027792224528667, "heading_rate": 0.2545991468724216, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137708.7875094} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3249861940173695, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.5180599747467607, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6784776846703575, "gear": 1, "accelerator_pedal_position": 0.3249861940173695, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.032776579608586, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137708.7875094} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137708.7975094, "x": 35.002099629842, "y": 5.501403111840146, "z": null, "yaw": 3.1740394453438925, "pitch": null, "roll": null}, "v": 1.6831683542203142, "accelerator_pedal_position": 0.3249861940173695, "brake_pedal_position": 0.0, "acceleration": 0.4686747378110563, "steering_wheel_angle": 6.997532146539229, "front_wheel_angle": 0.3578898433591713, "heading_rate": 0.24589750898241436, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137708.8075094} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3384273110021454, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.664094667716579, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6933779955008603, "gear": 1, "accelerator_pedal_position": 0.3384273110021454, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.9278220820608585, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137708.8075094} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.58995079994202, "x": 31.002099629842, "y": 0.5014031118401459, "z": null, "yaw": 3.1740394453438925, "pitch": null, "roll": null}, "v": 1.6831683542203142, "accelerator_pedal_position": 0.3249861940173695, "brake_pedal_position": 0.0, "acceleration": 0.4686747378110563, "steering_wheel_angle": 6.997532146539229, "front_wheel_angle": 0.3578898433591713, "heading_rate": 0.24589750898241436, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137708.8275094} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.33236029675069445, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.664094667716579, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6988962605371793, "gear": 1, "accelerator_pedal_position": 0.3384273110021454, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.893359129750287, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137708.8275094} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.58995079994202, "x": 31.002099629842, "y": 0.5014031118401459, "z": null, "yaw": 3.1740394453438925, "pitch": null, "roll": null}, "v": 1.6831683542203142, "accelerator_pedal_position": 0.3249861940173695, "brake_pedal_position": 0.0, "acceleration": 0.4686747378110563, "steering_wheel_angle": 6.997532146539229, "front_wheel_angle": 0.3578898433591713, "heading_rate": 0.24589750898241436, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137708.8475094} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.33236029675069445, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.664094667716579, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7091608372325546, "gear": 1, "accelerator_pedal_position": 0.33236029675069445, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.824286896495185, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137708.8475094} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.58995079994202, "x": 31.002099629842, "y": 0.5014031118401459, "z": null, "yaw": 3.1740394453438925, "pitch": null, "roll": null}, "v": 1.6831683542203142, "accelerator_pedal_position": 0.3249861940173695, "brake_pedal_position": 0.0, "acceleration": 0.4686747378110563, "steering_wheel_angle": 6.997532146539229, "front_wheel_angle": 0.3578898433591713, "heading_rate": 0.24589750898241436, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137708.8675094} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.33236029675069445, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.664094667716579, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7194081496322602, "gear": 1, "accelerator_pedal_position": 0.33236029675069445, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.7550195583948085, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137708.8675094} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.58995079994202, "x": 31.002099629842, "y": 0.5014031118401459, "z": null, "yaw": 3.1740394453438925, "pitch": null, "roll": null}, "v": 1.6831683542203142, "accelerator_pedal_position": 0.3249861940173695, "brake_pedal_position": 0.0, "acceleration": 0.4686747378110563, "steering_wheel_angle": 6.997532146539229, "front_wheel_angle": 0.3578898433591713, "heading_rate": 0.24589750898241436, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137708.8875093} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.33236029675069445, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.664094667716579, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7296381847883697, "gear": 1, "accelerator_pedal_position": 0.33236029675069445, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.685557115449155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137708.8875093} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137708.9075093, "x": 34.81425842316359, "y": 5.493949114595055, "z": null, "yaw": 3.189624387373186, "pitch": null, "roll": null}, "v": 1.7398509299870224, "accelerator_pedal_position": 0.33236029675069445, "brake_pedal_position": 0.0, "acceleration": 0.509988495606722, "steering_wheel_angle": 6.615899567658226, "front_wheel_angle": 0.3360386965539333, "heading_rate": 0.23738506445165783, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137708.9075093} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3559458261947668, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2129351817816023, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7398509299870224, "gear": 1, "accelerator_pedal_position": 0.33236029675069445, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.615899567658226, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137708.9075093} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.69995069503784, "x": 30.814258423163587, "y": 0.49394911459505497, "z": null, "yaw": 3.189624387373186, "pitch": null, "roll": null}, "v": 1.7398509299870224, "accelerator_pedal_position": 0.33236029675069445, "brake_pedal_position": 0.0, "acceleration": 0.509988495606722, "steering_wheel_angle": 6.615899567658226, "front_wheel_angle": 0.3360386965539333, "heading_rate": 0.23738506445165783, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137708.9275093} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3450783788812145, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2129351817816023, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7529933122184371, "gear": 1, "accelerator_pedal_position": 0.3559458261947668, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.548949968674409, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137708.9275093} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.69995069503784, "x": 30.814258423163587, "y": 0.49394911459505497, "z": null, "yaw": 3.189624387373186, "pitch": null, "roll": null}, "v": 1.7398509299870224, "accelerator_pedal_position": 0.33236029675069445, "brake_pedal_position": 0.0, "acceleration": 0.509988495606722, "steering_wheel_angle": 6.615899567658226, "front_wheel_angle": 0.3360386965539333, "heading_rate": 0.23738506445165783, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137708.9475093} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3450783788812145, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2129351817816023, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7647555111089142, "gear": 1, "accelerator_pedal_position": 0.3450783788812145, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.481821124069047, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137708.9475093} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.69995069503784, "x": 30.814258423163587, "y": 0.49394911459505497, "z": null, "yaw": 3.189624387373186, "pitch": null, "roll": null}, "v": 1.7398509299870224, "accelerator_pedal_position": 0.33236029675069445, "brake_pedal_position": 0.0, "acceleration": 0.509988495606722, "steering_wheel_angle": 6.615899567658226, "front_wheel_angle": 0.3360386965539333, "heading_rate": 0.23738506445165783, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137708.9675093} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3450783788812145, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2129351817816023, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.776497667224696, "gear": 1, "accelerator_pedal_position": 0.3450783788812145, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.414513033842139, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137708.9675093} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.69995069503784, "x": 30.814258423163587, "y": 0.49394911459505497, "z": null, "yaw": 3.189624387373186, "pitch": null, "roll": null}, "v": 1.7398509299870224, "accelerator_pedal_position": 0.33236029675069445, "brake_pedal_position": 0.0, "acceleration": 0.509988495606722, "steering_wheel_angle": 6.615899567658226, "front_wheel_angle": 0.3360386965539333, "heading_rate": 0.23738506445165783, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137708.9875093} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3450783788812145, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2129351817816023, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7882197595909228, "gear": 1, "accelerator_pedal_position": 0.3450783788812145, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.347025697993686, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137708.9875093} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.69995069503784, "x": 30.814258423163587, "y": 0.49394911459505497, "z": null, "yaw": 3.189624387373186, "pitch": null, "roll": null}, "v": 1.7398509299870224, "accelerator_pedal_position": 0.33236029675069445, "brake_pedal_position": 0.0, "acceleration": 0.509988495606722, "steering_wheel_angle": 6.615899567658226, "front_wheel_angle": 0.3360386965539333, "heading_rate": 0.23738506445165783, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137709.0075092} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3450783788812145, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2129351817816023, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7999217675509693, "gear": 1, "accelerator_pedal_position": 0.3450783788812145, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.279359116523688, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137709.0075092} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137709.0175092, "x": 34.619806155129034, "y": 5.4832875347704375, "z": null, "yaw": 3.2041770143936867, "pitch": null, "roll": null}, "v": 1.8057652335103394, "accelerator_pedal_position": 0.3450783788812145, "brake_pedal_position": 0.0, "acceleration": 0.5838437255465271, "steering_wheel_angle": 6.245458608680609, "front_wheel_angle": 0.31514592708365063, "heading_rate": 0.2299605858622824, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137709.0275092} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3642057381120383, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.28477620790274594, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8116036707658045, "gear": 1, "accelerator_pedal_position": 0.3450783788812145, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.211513289432145, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137709.0275092} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.80995059013367, "x": 30.619806155129034, "y": 0.4832875347704375, "z": null, "yaw": 3.2041770143936867, "pitch": null, "roll": null}, "v": 1.8057652335103394, "accelerator_pedal_position": 0.3450783788812145, "brake_pedal_position": 0.0, "acceleration": 0.5838437255465271, "steering_wheel_angle": 6.245458608680609, "front_wheel_angle": 0.31514592708365063, "heading_rate": 0.2299605858622824, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137709.0475092} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3555266319237444, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.28477620790274594, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8256553367096628, "gear": 1, "accelerator_pedal_position": 0.3642057381120383, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.145192626358907, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137709.0475092} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.80995059013367, "x": 30.619806155129034, "y": 0.4832875347704375, "z": null, "yaw": 3.2041770143936867, "pitch": null, "roll": null}, "v": 1.8057652335103394, "accelerator_pedal_position": 0.3450783788812145, "brake_pedal_position": 0.0, "acceleration": 0.5838437255465271, "steering_wheel_angle": 6.245458608680609, "front_wheel_angle": 0.31514592708365063, "heading_rate": 0.2299605858622824, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137709.0675092} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3555266319237444, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.28477620790274594, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8385983015849265, "gear": 1, "accelerator_pedal_position": 0.3555266319237444, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.078701576118593, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137709.0675092} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.80995059013367, "x": 30.619806155129034, "y": 0.4832875347704375, "z": null, "yaw": 3.2041770143936867, "pitch": null, "roll": null}, "v": 1.8057652335103394, "accelerator_pedal_position": 0.3450783788812145, "brake_pedal_position": 0.0, "acceleration": 0.5838437255465271, "steering_wheel_angle": 6.245458608680609, "front_wheel_angle": 0.31514592708365063, "heading_rate": 0.2299605858622824, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137709.0875092} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3555266319237444, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.28477620790274594, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8515188312200135, "gear": 1, "accelerator_pedal_position": 0.3555266319237444, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.012040138711205, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137709.0875092} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.80995059013367, "x": 30.619806155129034, "y": 0.4832875347704375, "z": null, "yaw": 3.2041770143936867, "pitch": null, "roll": null}, "v": 1.8057652335103394, "accelerator_pedal_position": 0.3450783788812145, "brake_pedal_position": 0.0, "acceleration": 0.5838437255465271, "steering_wheel_angle": 6.245458608680609, "front_wheel_angle": 0.31514592708365063, "heading_rate": 0.2299605858622824, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137709.1075091} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3555266319237444, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.28477620790274594, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8644168977570026, "gear": 1, "accelerator_pedal_position": 0.3555266319237444, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.9452083141367424, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137709.1075091} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137709.127509, "x": 34.41806506065913, "y": 5.469370549635152, "z": null, "yaw": 3.217744941749977, "pitch": null, "roll": null}, "v": 1.8772924737342755, "accelerator_pedal_position": 0.3555266319237444, "brake_pedal_position": 0.0, "acceleration": 0.6429345555172951, "steering_wheel_angle": 5.878206102395201, "front_wheel_angle": 0.29472843898060475, "heading_rate": 0.2226128679055704, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137709.127509} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.32792335364361824, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.42108968566076915, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8772924737342755, "gear": 1, "accelerator_pedal_position": 0.3555266319237444, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.878206102395201, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137709.127509} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.91995048522949, "x": 30.41806506065913, "y": 0.4693705496351521, "z": null, "yaw": 3.217744941749977, "pitch": null, "roll": null}, "v": 1.8772924737342755, "accelerator_pedal_position": 0.3555266319237444, "brake_pedal_position": 0.0, "acceleration": 0.6429345555172951, "steering_wheel_angle": 5.878206102395201, "front_wheel_angle": 0.29472843898060475, "heading_rate": 0.2226128679055704, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137709.147509} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.34154097879256606, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.42108968566076915, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8866966345668081, "gear": 1, "accelerator_pedal_position": 0.32792335364361824, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.8108603774216165, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137709.147509} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.91995048522949, "x": 30.41806506065913, "y": 0.4693705496351521, "z": null, "yaw": 3.217744941749977, "pitch": null, "roll": null}, "v": 1.8772924737342755, "accelerator_pedal_position": 0.3555266319237444, "brake_pedal_position": 0.0, "acceleration": 0.6429345555172951, "steering_wheel_angle": 5.878206102395201, "front_wheel_angle": 0.29472843898060475, "heading_rate": 0.2226128679055704, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137709.167509} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.34154097879256606, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.42108968566076915, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.897785765764583, "gear": 1, "accelerator_pedal_position": 0.34154097879256606, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.7433433869788955, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137709.167509} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.91995048522949, "x": 30.41806506065913, "y": 0.4693705496351521, "z": null, "yaw": 3.217744941749977, "pitch": null, "roll": null}, "v": 1.8772924737342755, "accelerator_pedal_position": 0.3555266319237444, "brake_pedal_position": 0.0, "acceleration": 0.6429345555172951, "steering_wheel_angle": 5.878206102395201, "front_wheel_angle": 0.29472843898060475, "heading_rate": 0.2226128679055704, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137709.187509} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.34154097879256606, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.42108968566076915, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.90885541078327, "gear": 1, "accelerator_pedal_position": 0.34154097879256606, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.67565513106704, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137709.187509} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.91995048522949, "x": 30.41806506065913, "y": 0.4693705496351521, "z": null, "yaw": 3.217744941749977, "pitch": null, "roll": null}, "v": 1.8772924737342755, "accelerator_pedal_position": 0.3555266319237444, "brake_pedal_position": 0.0, "acceleration": 0.6429345555172951, "steering_wheel_angle": 5.878206102395201, "front_wheel_angle": 0.29472843898060475, "heading_rate": 0.2226128679055704, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137709.207509} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.34154097879256606, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.42108968566076915, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9199055548713868, "gear": 1, "accelerator_pedal_position": 0.34154097879256606, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.6077956096860495, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137709.207509} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.91995048522949, "x": 30.41806506065913, "y": 0.4693705496351521, "z": null, "yaw": 3.217744941749977, "pitch": null, "roll": null}, "v": 1.8772924737342755, "accelerator_pedal_position": 0.3555266319237444, "brake_pedal_position": 0.0, "acceleration": 0.6429345555172951, "steering_wheel_angle": 5.878206102395201, "front_wheel_angle": 0.29472843898060475, "heading_rate": 0.2226128679055704, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137709.227509} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.34154097879256606, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.42108968566076915, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.930936183562202, "gear": 1, "accelerator_pedal_position": 0.34154097879256606, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.539764822835924, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137709.227509} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137709.237509, "x": 34.20938152154076, "y": 5.452220947934573, "z": null, "yaw": 3.230354999204081, "pitch": null, "roll": null}, "v": 1.9364441751904573, "accelerator_pedal_position": 0.34154097879256606, "brake_pedal_position": 0.0, "acceleration": 0.5503107482577243, "steering_wheel_angle": 5.505685204859934, "front_wheel_angle": 0.2743060455432516, "heading_rate": 0.21285724423200872, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137709.247509} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2929332113060243, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0798168912126571, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9419472826730346, "gear": 1, "accelerator_pedal_position": 0.34154097879256606, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.471562770516661, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137709.247509} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.02995038032532, "x": 30.209381521540763, "y": 0.4522209479345731, "z": null, "yaw": 3.230354999204081, "pitch": null, "roll": null}, "v": 1.9364441751904573, "accelerator_pedal_position": 0.34154097879256606, "brake_pedal_position": 0.0, "acceleration": 0.5503107482577243, "steering_wheel_angle": 5.505685204859934, "front_wheel_angle": 0.2743060455432516, "heading_rate": 0.21285724423200872, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137709.267509} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.31647699617045666, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0798168912126571, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9468655687007543, "gear": 1, "accelerator_pedal_position": 0.2929332113060243, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.401949774754395, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137709.267509} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.02995038032532, "x": 30.209381521540763, "y": 0.4522209479345731, "z": null, "yaw": 3.230354999204081, "pitch": null, "roll": null}, "v": 1.9364441751904573, "accelerator_pedal_position": 0.34154097879256606, "brake_pedal_position": 0.0, "acceleration": 0.5503107482577243, "steering_wheel_angle": 5.505685204859934, "front_wheel_angle": 0.2743060455432516, "heading_rate": 0.21285724423200872, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137709.287509} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.31647699617045666, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0798168912126571, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9547167761221154, "gear": 1, "accelerator_pedal_position": 0.31647699617045666, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.332159254839228, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137709.287509} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.02995038032532, "x": 30.209381521540763, "y": 0.4522209479345731, "z": null, "yaw": 3.230354999204081, "pitch": null, "roll": null}, "v": 1.9364441751904573, "accelerator_pedal_position": 0.34154097879256606, "brake_pedal_position": 0.0, "acceleration": 0.5503107482577243, "steering_wheel_angle": 5.505685204859934, "front_wheel_angle": 0.2743060455432516, "heading_rate": 0.21285724423200872, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137709.307509} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.31647699617045666, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0798168912126571, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.962554005974838, "gear": 1, "accelerator_pedal_position": 0.31647699617045666, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.26219121077116, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137709.307509} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.02995038032532, "x": 30.209381521540763, "y": 0.4522209479345731, "z": null, "yaw": 3.230354999204081, "pitch": null, "roll": null}, "v": 1.9364441751904573, "accelerator_pedal_position": 0.34154097879256606, "brake_pedal_position": 0.0, "acceleration": 0.5503107482577243, "steering_wheel_angle": 5.505685204859934, "front_wheel_angle": 0.2743060455432516, "heading_rate": 0.21285724423200872, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137709.327509} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.31647699617045666, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0798168912126571, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9703772585853878, "gear": 1, "accelerator_pedal_position": 0.31647699617045666, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.192045642550191, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137709.327509} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137709.347509, "x": 33.9952605301297, "y": 5.4319995218993276, "z": null, "yaw": 3.242011137583876, "pitch": null, "roll": null}, "v": 1.978186534410982, "accelerator_pedal_position": 0.31647699617045666, "brake_pedal_position": 0.0, "acceleration": 0.38993967969555554, "steering_wheel_angle": 5.1217225501763215, "front_wheel_angle": 0.2535474636748652, "heading_rate": 0.20023275160271609, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137709.347509} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2765954774978158, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.7037115654000743, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.978186534410982, "gear": 1, "accelerator_pedal_position": 0.31647699617045666, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.1217225501763215, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137709.347509} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.13995027542114, "x": 29.9952605301297, "y": 0.43199952189932755, "z": null, "yaw": 3.242011137583876, "pitch": null, "roll": null}, "v": 1.978186534410982, "accelerator_pedal_position": 0.31647699617045666, "brake_pedal_position": 0.0, "acceleration": 0.38993967969555554, "steering_wheel_angle": 5.1217225501763215, "front_wheel_angle": 0.2535474636748652, "heading_rate": 0.20023275160271609, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137709.367509} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29587020475518344, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.7037115654000743, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.980998877988657, "gear": 1, "accelerator_pedal_position": 0.2765954774978158, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.049967653692039, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137709.367509} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.13995027542114, "x": 29.9952605301297, "y": 0.43199952189932755, "z": null, "yaw": 3.242011137583876, "pitch": null, "roll": null}, "v": 1.978186534410982, "accelerator_pedal_position": 0.31647699617045666, "brake_pedal_position": 0.0, "acceleration": 0.38993967969555554, "steering_wheel_angle": 5.1217225501763215, "front_wheel_angle": 0.2535474636748652, "heading_rate": 0.20023275160271609, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137709.3875089} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29587020475518344, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.7037115654000743, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9862144445706575, "gear": 1, "accelerator_pedal_position": 0.29587020475518344, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.978028868410218, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137709.3875089} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.13995027542114, "x": 29.9952605301297, "y": 0.43199952189932755, "z": null, "yaw": 3.242011137583876, "pitch": null, "roll": null}, "v": 1.978186534410982, "accelerator_pedal_position": 0.31647699617045666, "brake_pedal_position": 0.0, "acceleration": 0.38993967969555554, "steering_wheel_angle": 5.1217225501763215, "front_wheel_angle": 0.2535474636748652, "heading_rate": 0.20023275160271609, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137709.4075089} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29587020475518344, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.7037115654000743, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9914206588103593, "gear": 1, "accelerator_pedal_position": 0.29587020475518344, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.905906194330857, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137709.4075089} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.13995027542114, "x": 29.9952605301297, "y": 0.43199952189932755, "z": null, "yaw": 3.242011137583876, "pitch": null, "roll": null}, "v": 1.978186534410982, "accelerator_pedal_position": 0.31647699617045666, "brake_pedal_position": 0.0, "acceleration": 0.38993967969555554, "steering_wheel_angle": 5.1217225501763215, "front_wheel_angle": 0.2535474636748652, "heading_rate": 0.20023275160271609, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137709.4275088} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29587020475518344, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.7037115654000743, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9966175266410016, "gear": 1, "accelerator_pedal_position": 0.29587020475518344, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.833599631453957, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137709.4275088} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.13995027542114, "x": 29.9952605301297, "y": 0.43199952189932755, "z": null, "yaw": 3.242011137583876, "pitch": null, "roll": null}, "v": 1.978186534410982, "accelerator_pedal_position": 0.31647699617045666, "brake_pedal_position": 0.0, "acceleration": 0.38993967969555554, "steering_wheel_angle": 5.1217225501763215, "front_wheel_angle": 0.2535474636748652, "heading_rate": 0.20023275160271609, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137709.4475088} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29587020475518344, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.7037115654000743, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0018050540435195, "gear": 1, "accelerator_pedal_position": 0.29587020475518344, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.761109179779518, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137709.4475088} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137709.4575088, "x": 33.77767019959277, "y": 5.408986462292981, "z": null, "yaw": 3.25270581512881, "pitch": null, "roll": null}, "v": 2.0043953169662574, "accelerator_pedal_position": 0.29587020475518344, "brake_pedal_position": 0.0, "acceleration": 0.25879300800482097, "steering_wheel_angle": 4.724794995643222, "front_wheel_angle": 0.23238582129274124, "heading_rate": 0.18529804228620322, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137709.4675088} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2540048792898185, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.330110498453424, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0069832470463056, "gear": 1, "accelerator_pedal_position": 0.29587020475518344, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.688434839307541, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137709.4675088} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.24995017051697, "x": 29.77767019959277, "y": 0.4089864622929813, "z": null, "yaw": 3.25270581512881, "pitch": null, "roll": null}, "v": 2.0043953169662574, "accelerator_pedal_position": 0.29587020475518344, "brake_pedal_position": 0.0, "acceleration": 0.25879300800482097, "steering_wheel_angle": 4.724794995643222, "front_wheel_angle": 0.23238582129274124, "heading_rate": 0.18529804228620322, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137709.4875088} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2741201281576019, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.330110498453424, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.00692130528924, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.614227070513955, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137709.4875088} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.24995017051697, "x": 29.77767019959277, "y": 0.4089864622929813, "z": null, "yaw": 3.25270581512881, "pitch": null, "roll": null}, "v": 2.0043953169662574, "accelerator_pedal_position": 0.29587020475518344, "brake_pedal_position": 0.0, "acceleration": 0.25879300800482097, "steering_wheel_angle": 4.724794995643222, "front_wheel_angle": 0.23238582129274124, "heading_rate": 0.18529804228620322, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137709.5075088} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2741201281576019, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.330110498453424, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0093727478840275, "gear": 1, "accelerator_pedal_position": 0.2741201281576019, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.539828546461602, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137709.5075088} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.24995017051697, "x": 29.77767019959277, "y": 0.4089864622929813, "z": null, "yaw": 3.25270581512881, "pitch": null, "roll": null}, "v": 2.0043953169662574, "accelerator_pedal_position": 0.29587020475518344, "brake_pedal_position": 0.0, "acceleration": 0.25879300800482097, "steering_wheel_angle": 4.724794995643222, "front_wheel_angle": 0.23238582129274124, "heading_rate": 0.18529804228620322, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137709.5275087} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2741201281576019, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.330110498453424, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0118197712860777, "gear": 1, "accelerator_pedal_position": 0.2741201281576019, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.465239267150482, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137709.5275087} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.24995017051697, "x": 29.77767019959277, "y": 0.4089864622929813, "z": null, "yaw": 3.25270581512881, "pitch": null, "roll": null}, "v": 2.0043953169662574, "accelerator_pedal_position": 0.29587020475518344, "brake_pedal_position": 0.0, "acceleration": 0.25879300800482097, "steering_wheel_angle": 4.724794995643222, "front_wheel_angle": 0.23238582129274124, "heading_rate": 0.18529804228620322, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137709.5475087} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2741201281576019, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.330110498453424, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0142623810677383, "gear": 1, "accelerator_pedal_position": 0.2741201281576019, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.390459232580593, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137709.5475087} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137709.5675087, "x": 33.558067357953604, "y": 5.383482298307297, "z": null, "yaw": 3.2624331902568375, "pitch": null, "roll": null}, "v": 2.0167005828042592, "accelerator_pedal_position": 0.2741201281576019, "brake_pedal_position": 0.0, "acceleration": 0.12174495943796837, "steering_wheel_angle": 4.315488442751936, "front_wheel_angle": 0.21086829706180152, "heading_rate": 0.1686232336140213, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137709.5675087} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25019742166049663, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.8845258173594237, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0167005828042592, "gear": 1, "accelerator_pedal_position": 0.2741201281576019, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.315488442751936, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137709.5675087} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.35995006561279, "x": 29.558067357953604, "y": 0.38348229830729696, "z": null, "yaw": 3.2624331902568375, "pitch": null, "roll": null}, "v": 2.0167005828042592, "accelerator_pedal_position": 0.2741201281576019, "brake_pedal_position": 0.0, "acceleration": 0.12174495943796837, "steering_wheel_angle": 4.315488442751936, "front_wheel_angle": 0.21086829706180152, "heading_rate": 0.1686232336140213, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137709.5875087} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2616737691411575, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.8845258173594237, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.016145394548389, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.239051577804054, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137709.5875087} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.35995006561279, "x": 29.558067357953604, "y": 0.38348229830729696, "z": null, "yaw": 3.2624331902568375, "pitch": null, "roll": null}, "v": 2.0167005828042592, "accelerator_pedal_position": 0.2741201281576019, "brake_pedal_position": 0.0, "acceleration": 0.12174495943796837, "steering_wheel_angle": 4.315488442751936, "front_wheel_angle": 0.21086829706180152, "heading_rate": 0.1686232336140213, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137709.6075087} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2616737691411575, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.8845258173594237, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0179032254933684, "gear": 1, "accelerator_pedal_position": 0.2616737691411575, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.085586022739897, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137709.6075087} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.35995006561279, "x": 29.558067357953604, "y": 0.38348229830729696, "z": null, "yaw": 3.2624331902568375, "pitch": null, "roll": null}, "v": 2.0167005828042592, "accelerator_pedal_position": 0.2741201281576019, "brake_pedal_position": 0.0, "acceleration": 0.12174495943796837, "steering_wheel_angle": 4.315488442751936, "front_wheel_angle": 0.21086829706180152, "heading_rate": 0.1686232336140213, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137709.6275086} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2616737691411575, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.8845258173594237, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0179032254933684, "gear": 1, "accelerator_pedal_position": 0.2616737691411575, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.085586022739897, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137709.6275086} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.35995006561279, "x": 29.558067357953604, "y": 0.38348229830729696, "z": null, "yaw": 3.2624331902568375, "pitch": null, "roll": null}, "v": 2.0167005828042592, "accelerator_pedal_position": 0.2741201281576019, "brake_pedal_position": 0.0, "acceleration": 0.12174495943796837, "steering_wheel_angle": 4.315488442751936, "front_wheel_angle": 0.21086829706180152, "heading_rate": 0.1686232336140213, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137709.6475086} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2616737691411575, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.8845258173594237, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0187797605167592, "gear": 1, "accelerator_pedal_position": 0.2616737691411575, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.00855733262362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137709.6475086} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.35995006561279, "x": 29.558067357953604, "y": 0.38348229830729696, "z": null, "yaw": 3.2624331902568375, "pitch": null, "roll": null}, "v": 2.0167005828042592, "accelerator_pedal_position": 0.2741201281576019, "brake_pedal_position": 0.0, "acceleration": 0.12174495943796837, "steering_wheel_angle": 4.315488442751936, "front_wheel_angle": 0.21086829706180152, "heading_rate": 0.1686232336140213, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137709.6675086} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2616737691411575, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.8845258173594237, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0209641756109398, "gear": 1, "accelerator_pedal_position": 0.2616737691411575, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.815122528962348, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137709.6675086} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137709.6775086, "x": 33.3378545791737, "y": 5.355833636043231, "z": null, "yaw": 3.271184259439548, "pitch": null, "roll": null}, "v": 2.0200915946851548, "accelerator_pedal_position": 0.2616737691411575, "brake_pedal_position": 0.0, "acceleration": 0.043648776888800256, "steering_wheel_angle": 3.8926444067189556, "front_wheel_angle": 0.18894994885089156, "heading_rate": 0.15090018535695476, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137709.6975086} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22672481329502855, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.3651135316310232, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0213998744745463, "gear": 1, "accelerator_pedal_position": 0.2616737691411575, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.776287611937994, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137709.6975086} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.46994996070862, "x": 29.3378545791737, "y": 0.35583363604323104, "z": null, "yaw": 3.271184259439548, "pitch": null, "roll": null}, "v": 2.0200915946851548, "accelerator_pedal_position": 0.2616737691411575, "brake_pedal_position": 0.0, "acceleration": 0.043648776888800256, "steering_wheel_angle": 3.8926444067189556, "front_wheel_angle": 0.18894994885089156, "heading_rate": 0.15090018535695476, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137709.7175086} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24339052925721102, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.3651135316310232, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.018945053303243, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.697289266489871, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137709.7175086} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.46994996070862, "x": 29.3378545791737, "y": 0.35583363604323104, "z": null, "yaw": 3.271184259439548, "pitch": null, "roll": null}, "v": 2.0200915946851548, "accelerator_pedal_position": 0.2616737691411575, "brake_pedal_position": 0.0, "acceleration": 0.043648776888800256, "steering_wheel_angle": 3.8926444067189556, "front_wheel_angle": 0.18894994885089156, "heading_rate": 0.15090018535695476, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137709.7375085} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24339052925721102, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.3651135316310232, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0182398749423416, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.657713856912252, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137709.7375085} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.46994996070862, "x": 29.3378545791737, "y": 0.35583363604323104, "z": null, "yaw": 3.271184259439548, "pitch": null, "roll": null}, "v": 2.0200915946851548, "accelerator_pedal_position": 0.2616737691411575, "brake_pedal_position": 0.0, "acceleration": 0.043648776888800256, "steering_wheel_angle": 3.8926444067189556, "front_wheel_angle": 0.18894994885089156, "heading_rate": 0.15090018535695476, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137709.7575085} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24339052925721102, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.3651135316310232, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0154255275779382, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.4989039729113878, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137709.7575085} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137709.7875085, "x": 33.11776481592783, "y": 5.326342350064532, "z": null, "yaw": 3.2789552210009925, "pitch": null, "roll": null}, "v": 2.0147235288870036, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3413272854228592, "steering_wheel_angle": 3.4590744404885747, "front_wheel_angle": 0.16679008012577706, "heading_rate": 0.1324949300571155, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137709.7875085} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23134471284499986, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.8732551673794076, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0147235288870036, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.4590744404885747, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137709.7875085} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.57994985580444, "x": 29.117764815927828, "y": 0.3263423500645324, "z": null, "yaw": 3.2789552210009925, "pitch": null, "roll": null}, "v": 2.0147235288870036, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3413272854228592, "steering_wheel_angle": 3.4590744404885747, "front_wheel_angle": 0.16679008012577706, "heading_rate": 0.1324949300571155, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137709.8075085} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23704386675908062, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.8732551673794076, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0107209781235413, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.33729531239625, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137709.8075085} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.57994985580444, "x": 29.117764815927828, "y": 0.3263423500645324, "z": null, "yaw": 3.2789552210009925, "pitch": null, "roll": null}, "v": 2.0147235288870036, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3413272854228592, "steering_wheel_angle": 3.4590744404885747, "front_wheel_angle": 0.16679008012577706, "heading_rate": 0.1324949300571155, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137709.8275084} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23704386675908062, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.8732551673794076, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0096265594217355, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.2965972295915975, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137709.8275084} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.57994985580444, "x": 29.117764815927828, "y": 0.3263423500645324, "z": null, "yaw": 3.2789552210009925, "pitch": null, "roll": null}, "v": 2.0147235288870036, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3413272854228592, "steering_wheel_angle": 3.4590744404885747, "front_wheel_angle": 0.16679008012577706, "heading_rate": 0.1324949300571155, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137709.8475084} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23704386675908062, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.8732551673794076, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0074406824995177, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.215043503821477, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137709.8475084} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.57994985580444, "x": 29.117764815927828, "y": 0.3263423500645324, "z": null, "yaw": 3.2789552210009925, "pitch": null, "roll": null}, "v": 2.0147235288870036, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3413272854228592, "steering_wheel_angle": 3.4590744404885747, "front_wheel_angle": 0.16679008012577706, "heading_rate": 0.1324949300571155, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137709.8675084} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23704386675908062, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.8732551673794076, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0052587453626964, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.133279697836936, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137709.8675084} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.57994985580444, "x": 29.117764815927828, "y": 0.3263423500645324, "z": null, "yaw": 3.2789552210009925, "pitch": null, "roll": null}, "v": 2.0147235288870036, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3413272854228592, "steering_wheel_angle": 3.4590744404885747, "front_wheel_angle": 0.16679008012577706, "heading_rate": 0.1324949300571155, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137709.8875084} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23704386675908062, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.8732551673794076, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.00308073900679, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.051305811637975, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137709.8875084} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137709.8975084, "x": 32.89899329801239, "y": 5.295395837342295, "z": null, "yaw": 3.285735961061177, "pitch": null, "roll": null}, "v": 2.0019932070650315, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3401794283645969, "steering_wheel_angle": 3.010240088458086, "front_wheel_angle": 0.14417155355936395, "heading_rate": 0.11353398770609319, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137709.9075084} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23024190490116844, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.384433730074591, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.000906654453828, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.969121845224593, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137709.9075084} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.68994975090027, "x": 28.898993298012392, "y": 0.29539583734229513, "z": null, "yaw": 3.285735961061177, "pitch": null, "roll": null}, "v": 2.0019932070650315, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3401794283645969, "steering_wheel_angle": 3.010240088458086, "front_wheel_angle": 0.14417155355936395, "heading_rate": 0.11353398770609319, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137709.9275084} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23339348015579903, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.384433730074591, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9978866200970817, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.885307631932299, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137709.9275084} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.68994975090027, "x": 28.898993298012392, "y": 0.29539583734229513, "z": null, "yaw": 3.285735961061177, "pitch": null, "roll": null}, "v": 2.0019932070650315, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3401794283645969, "steering_wheel_angle": 3.010240088458086, "front_wheel_angle": 0.14417155355936395, "heading_rate": 0.11353398770609319, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137709.9475083} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23339348015579903, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.384433730074591, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.995265787486408, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.801276043551992, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137709.9475083} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.68994975090027, "x": 28.898993298012392, "y": 0.29539583734229513, "z": null, "yaw": 3.285735961061177, "pitch": null, "roll": null}, "v": 2.0019932070650315, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3401794283645969, "steering_wheel_angle": 3.010240088458086, "front_wheel_angle": 0.14417155355936395, "heading_rate": 0.11353398770609319, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137709.9675083} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23339348015579903, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.384433730074591, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9926496659795592, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.717027080083671, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137709.9675083} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.68994975090027, "x": 28.898993298012392, "y": 0.29539583734229513, "z": null, "yaw": 3.285735961061177, "pitch": null, "roll": null}, "v": 2.0019932070650315, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3401794283645969, "steering_wheel_angle": 3.010240088458086, "front_wheel_angle": 0.14417155355936395, "heading_rate": 0.11353398770609319, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137709.9875083} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23339348015579903, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.384433730074591, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9900382443716358, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.632560741527337, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137709.9875083} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137710.0075083, "x": 32.68186853152459, "y": 5.263279672996962, "z": null, "yaw": 3.291517613089193, "pitch": null, "roll": null}, "v": 1.9874315114926182, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3388704157033693, "steering_wheel_angle": 2.5478770278829894, "front_wheel_angle": 0.1211990685466696, "heading_rate": 0.09455517191226798, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137710.0075083} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.6084642200110935, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9874315114926182, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.5478770278829894, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137710.0075083} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.799949645996094, "x": 28.681868531524593, "y": 0.263279672996962, "z": null, "yaw": 3.291517613089193, "pitch": null, "roll": null}, "v": 1.9874315114926182, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3388704157033693, "steering_wheel_angle": 2.5478770278829894, "front_wheel_angle": 0.1211990685466696, "heading_rate": 0.09455517191226798, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137710.0275083} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21902070516655847, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.6084642200110935, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9806571433457827, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.4623216011861593, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137710.0275083} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.799949645996094, "x": 28.681868531524593, "y": 0.263279672996962, "z": null, "yaw": 3.291517613089193, "pitch": null, "roll": null}, "v": 1.9874315114926182, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3388704157033693, "steering_wheel_angle": 2.5478770278829894, "front_wheel_angle": 0.1211990685466696, "heading_rate": 0.09455517191226798, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137710.0475082} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21902070516655847, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.6084642200110935, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9762714392873557, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.3765454401929658, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137710.0475082} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.799949645996094, "x": 28.681868531524593, "y": 0.263279672996962, "z": null, "yaw": 3.291517613089193, "pitch": null, "roll": null}, "v": 1.9874315114926182, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3388704157033693, "steering_wheel_angle": 2.5478770278829894, "front_wheel_angle": 0.1211990685466696, "heading_rate": 0.09455517191226798, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137710.0675082} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21902070516655847, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.6084642200110935, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.971893586277179, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.290548544903409, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137710.0675082} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.799949645996094, "x": 28.681868531524593, "y": 0.263279672996962, "z": null, "yaw": 3.291517613089193, "pitch": null, "roll": null}, "v": 1.9874315114926182, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3388704157033693, "steering_wheel_angle": 2.5478770278829894, "front_wheel_angle": 0.1211990685466696, "heading_rate": 0.09455517191226798, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137710.0875082} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21902070516655847, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.6084642200110935, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.96752356259792, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.204330915317488, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137710.0875082} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.799949645996094, "x": 28.681868531524593, "y": 0.263279672996962, "z": null, "yaw": 3.291517613089193, "pitch": null, "roll": null}, "v": 1.9874315114926182, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3388704157033693, "steering_wheel_angle": 2.5478770278829894, "front_wheel_angle": 0.1211990685466696, "heading_rate": 0.09455517191226798, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137710.1075082} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21902070516655847, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.6084642200110935, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9631613466122086, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.1178925514352045, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137710.1075082} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137710.1175082, "x": 32.467192793548755, "y": 5.230357215355431, "z": null, "yaw": 3.296292273539536, "pitch": null, "roll": null}, "v": 1.9609831597645293, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3365037075170273, "steering_wheel_angle": 2.0745905941329266, "front_wheel_angle": 0.09801409297822085, "heading_rate": 0.07532103364176322, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137710.1275082} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22079704399344938, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.068320689215595, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.958806916762269, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.031233453256557, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137710.1275082} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.90994954109192, "x": 28.467192793548755, "y": 0.23035721535543097, "z": null, "yaw": 3.296292273539536, "pitch": null, "roll": null}, "v": 1.9609831597645293, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3365037075170273, "steering_wheel_angle": 2.0745905941329266, "front_wheel_angle": 0.09801409297822085, "heading_rate": 0.07532103364176322, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137710.1475081} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21977084722524515, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.068320689215595, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.954682194965562, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.9429401818842198, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137710.1475081} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.90994954109192, "x": 28.467192793548755, "y": 0.23035721535543097, "z": null, "yaw": 3.296292273539536, "pitch": null, "roll": null}, "v": 1.9609831597645293, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3365037075170273, "steering_wheel_angle": 2.0745905941329266, "front_wheel_angle": 0.09801409297822085, "heading_rate": 0.07532103364176322, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137710.1675081} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21977084722524515, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.068320689215595, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9504366038446563, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.854418944996636, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137710.1675081} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.90994954109192, "x": 28.467192793548755, "y": 0.23035721535543097, "z": null, "yaw": 3.296292273539536, "pitch": null, "roll": null}, "v": 1.9609831597645293, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3365037075170273, "steering_wheel_angle": 2.0745905941329266, "front_wheel_angle": 0.09801409297822085, "heading_rate": 0.07532103364176322, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137710.187508} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21977084722524515, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.068320689215595, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.946198569055511, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.7656697425938046, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137710.187508} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.90994954109192, "x": 28.467192793548755, "y": 0.23035721535543097, "z": null, "yaw": 3.296292273539536, "pitch": null, "roll": null}, "v": 1.9609831597645293, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3365037075170273, "steering_wheel_angle": 2.0745905941329266, "front_wheel_angle": 0.09801409297822085, "heading_rate": 0.07532103364176322, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137710.207508} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21977084722524515, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.068320689215595, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9419680699681319, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.6766925746757275, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137710.207508} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137710.227508, "x": 32.2552682775196, "y": 5.196919679387254, "z": null, "yaw": 3.3000547092749253, "pitch": null, "roll": null}, "v": 1.937745086027523, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3344358144856143, "steering_wheel_angle": 1.5874874412424032, "front_wheel_angle": 0.07448665594004619, "heading_rate": 0.05648581387913737, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137710.227508} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22217807797788672, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.521328596179543, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.937745086027523, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.5874874412424032, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137710.227508} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.019949436187744, "x": 28.255268277519598, "y": 0.1969196793872543, "z": null, "yaw": 3.3000547092749253, "pitch": null, "roll": null}, "v": 1.937745086027523, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3344358144856143, "steering_wheel_angle": 1.5874874412424032, "front_wheel_angle": 0.07448665594004619, "heading_rate": 0.05648581387913737, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137710.247508} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22087422321337924, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.521328596179543, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9338303671251582, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.4965734408098372, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137710.247508} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.019949436187744, "x": 28.255268277519598, "y": 0.1969196793872543, "z": null, "yaw": 3.3000547092749253, "pitch": null, "roll": null}, "v": 1.937745086027523, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3344358144856143, "steering_wheel_angle": 1.5874874412424032, "front_wheel_angle": 0.07448665594004619, "heading_rate": 0.05648581387913737, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137710.267508} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22087422321337924, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.521328596179543, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.929759679941379, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.4054238726318857, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137710.267508} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.019949436187744, "x": 28.255268277519598, "y": 0.1969196793872543, "z": null, "yaw": 3.3000547092749253, "pitch": null, "roll": null}, "v": 1.937745086027523, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3344358144856143, "steering_wheel_angle": 1.5874874412424032, "front_wheel_angle": 0.07448665594004619, "heading_rate": 0.05648581387913737, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137710.287508} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22087422321337924, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.521328596179543, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9256962040851702, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.3140387367085495, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137710.287508} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.019949436187744, "x": 28.255268277519598, "y": 0.1969196793872543, "z": null, "yaw": 3.3000547092749253, "pitch": null, "roll": null}, "v": 1.937745086027523, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3344358144856143, "steering_wheel_angle": 1.5874874412424032, "front_wheel_angle": 0.07448665594004619, "heading_rate": 0.05648581387913737, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137710.307508} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22087422321337924, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.521328596179543, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.921639920179665, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.222418033039828, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137710.307508} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.019949436187744, "x": 28.255268277519598, "y": 0.1969196793872543, "z": null, "yaw": 3.3000547092749253, "pitch": null, "roll": null}, "v": 1.937745086027523, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3344358144856143, "steering_wheel_angle": 1.5874874412424032, "front_wheel_angle": 0.07448665594004619, "heading_rate": 0.05648581387913737, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137710.327508} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22087422321337924, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.521328596179543, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9175908089173532, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.1305617616257213, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137710.327508} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137710.337508, "x": 32.04592113018214, "y": 5.163180730297328, "z": null, "yaw": 3.3027913292393603, "pitch": null, "roll": null}, "v": 1.9155689370126863, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.33247249037511345, "steering_wheel_angle": 1.0845452880141486, "front_wheel_angle": 0.0505353252481898, "heading_rate": 0.03784624612650023, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137710.347508} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22465196821616698, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.966986271376027, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9135488510597713, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.0384699224662295, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137710.347508} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.12994933128357, "x": 28.045921130182137, "y": 0.16318073029732805, "z": null, "yaw": 3.3027913292393603, "pitch": null, "roll": null}, "v": 1.9155689370126863, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.33247249037511345, "steering_wheel_angle": 1.0845452880141486, "front_wheel_angle": 0.0505353252481898, "heading_rate": 0.03784624612650023, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137710.367508} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2227034544521002, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.966986271376027, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9099860372364998, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.9445876917642021, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137710.367508} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.12994933128357, "x": 28.045921130182137, "y": 0.16318073029732805, "z": null, "yaw": 3.3027913292393603, "pitch": null, "roll": null}, "v": 1.9155689370126863, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.33247249037511345, "steering_wheel_angle": 1.0845452880141486, "front_wheel_angle": 0.0505353252481898, "heading_rate": 0.03784624612650023, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137710.387508} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2227034544521002, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.966986271376027, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9061860498402952, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.8504619028860013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137710.387508} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.12994933128357, "x": 28.045921130182137, "y": 0.16318073029732805, "z": null, "yaw": 3.3027913292393603, "pitch": null, "roll": null}, "v": 1.9155689370126863, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.33247249037511345, "steering_wheel_angle": 1.0845452880141486, "front_wheel_angle": 0.0505353252481898, "heading_rate": 0.03784624612650023, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137710.407508} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2227034544521002, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.966986271376027, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9023927583170355, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.7560925558316277, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137710.407508} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.12994933128357, "x": 28.045921130182137, "y": 0.16318073029732805, "z": null, "yaw": 3.3027913292393603, "pitch": null, "roll": null}, "v": 1.9155689370126863, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.33247249037511345, "steering_wheel_angle": 1.0845452880141486, "front_wheel_angle": 0.0505353252481898, "heading_rate": 0.03784624612650023, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137710.4275079} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2227034544521002, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.966986271376027, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8986061451149798, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.6614796506010806, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137710.4275079} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137710.4475079, "x": 31.83899196631854, "y": 5.129350034316167, "z": null, "yaw": 3.3044894987778255, "pitch": null, "roll": null}, "v": 1.894826192743681, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3306449726442592, "steering_wheel_angle": 0.5666231871943608, "front_wheel_angle": 0.026217789352200663, "heading_rate": 0.019409976396926192, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137710.4475079} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.982411824081449, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.894826192743681, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5666231871943608, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137710.4475079} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.239949226379395, "x": 27.83899196631854, "y": 0.12935003431616732, "z": null, "yaw": 3.3044894987778255, "pitch": null, "roll": null}, "v": 1.894826192743681, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3306449726442592, "steering_wheel_angle": 0.5666231871943608, "front_wheel_angle": 0.026217789352200663, "heading_rate": 0.019409976396926192, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137710.4675078} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.982411824081449, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8882161984519072, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4714672178047174, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137710.4675078} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.239949226379395, "x": 27.83899196631854, "y": 0.12935003431616732, "z": null, "yaw": 3.3044894987778255, "pitch": null, "roll": null}, "v": 1.894826192743681, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3306449726442592, "steering_wheel_angle": 0.5666231871943608, "front_wheel_angle": 0.026217789352200663, "heading_rate": 0.019409976396926192, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137710.4875078} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.982411824081449, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8816178058696276, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3760674039486064, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137710.4875078} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.239949226379395, "x": 27.83899196631854, "y": 0.12935003431616732, "z": null, "yaw": 3.3044894987778255, "pitch": null, "roll": null}, "v": 1.894826192743681, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3306449726442592, "steering_wheel_angle": 0.5666231871943608, "front_wheel_angle": 0.026217789352200663, "heading_rate": 0.019409976396926192, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137710.5075078} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.982411824081449, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8750309772258988, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.28042374562602757, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137710.5075078} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.239949226379395, "x": 27.83899196631854, "y": 0.12935003431616732, "z": null, "yaw": 3.3044894987778255, "pitch": null, "roll": null}, "v": 1.894826192743681, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3306449726442592, "steering_wheel_angle": 0.5666231871943608, "front_wheel_angle": 0.026217789352200663, "heading_rate": 0.019409976396926192, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137710.5275078} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.982411824081449, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8684556749075323, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.18453624283698108, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137710.5275078} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.239949226379395, "x": 27.83899196631854, "y": 0.12935003431616732, "z": null, "yaw": 3.3044894987778255, "pitch": null, "roll": null}, "v": 1.894826192743681, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3306449726442592, "steering_wheel_angle": 0.5666231871943608, "front_wheel_angle": 0.026217789352200663, "heading_rate": 0.019409976396926192, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137710.5475078} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.982411824081449, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.86189186145826, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.08840489558146687, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137710.5475078} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137710.5575078, "x": 31.635122922906426, "y": 5.095763694318021, "z": null, "yaw": 3.3051401794804582, "pitch": null, "roll": null}, "v": 1.8586142513971544, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3274751819248238, "steering_wheel_angle": 0.04024778027878437, "front_wheel_angle": 0.0018493236011369277, "heading_rate": 0.0013426496558223858, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137710.5675077} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22742163816578226, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.385523370387006, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8553394995779062, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.007968632253507017, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137710.5675077} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.34994912147522, "x": 27.635122922906426, "y": 0.09576369431802068, "z": null, "yaw": 3.3051401794804582, "pitch": null, "roll": null}, "v": 1.8586142513971544, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3274751819248238, "steering_wheel_angle": 0.04024778027878437, "front_wheel_angle": 0.0018493236011369277, "heading_rate": 0.0013426496558223858, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137710.5875077} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22113893914737326, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.385523370387006, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8522247648382708, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.10581616789334689, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137710.5875077} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.34994912147522, "x": 27.635122922906426, "y": 0.09576369431802068, "z": null, "yaw": 3.3051401794804582, "pitch": null, "roll": null}, "v": 1.8586142513971544, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3274751819248238, "steering_wheel_angle": 0.04024778027878437, "front_wheel_angle": 0.0018493236011369277, "heading_rate": 0.0013426496558223858, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137710.6075077} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22113893914737326, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.385523370387006, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8483304554002953, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.20341213135276198, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137710.6075077} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.34994912147522, "x": 27.635122922906426, "y": 0.09576369431802068, "z": null, "yaw": 3.3051401794804582, "pitch": null, "roll": null}, "v": 1.8586142513971544, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3274751819248238, "steering_wheel_angle": 0.04024778027878437, "front_wheel_angle": 0.0018493236011369277, "heading_rate": 0.0013426496558223858, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137710.6275077} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22113893914737326, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.385523370387006, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8444429180306163, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.30075652263175223, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137710.6275077} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.34994912147522, "x": 27.635122922906426, "y": 0.09576369431802068, "z": null, "yaw": 3.3051401794804582, "pitch": null, "roll": null}, "v": 1.8586142513971544, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3274751819248238, "steering_wheel_angle": 0.04024778027878437, "front_wheel_angle": 0.0018493236011369277, "heading_rate": 0.0013426496558223858, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137710.6475077} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22113893914737326, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.385523370387006, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8405621349102885, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3978493417303177, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137710.6475077} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137710.6675076, "x": 31.434521948079365, "y": 5.062679767479148, "z": null, "yaw": 3.3047375415419027, "pitch": null, "roll": null}, "v": 1.8366880882828278, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.32556863575054173, "steering_wheel_angle": -0.4946905886484585, "front_wheel_angle": -0.02286743375085046, "heading_rate": -0.01640924439242143, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137710.6675076} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22966470626867783, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.750070137018506, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8366880882828278, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4946905886484585, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137710.6675076} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.459949016571045, "x": 27.434521948079365, "y": 0.06267976747914794, "z": null, "yaw": 3.3047375415419027, "pitch": null, "roll": null}, "v": 1.8366880882828278, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.32556863575054173, "steering_wheel_angle": -0.4946905886484585, "front_wheel_angle": -0.02286743375085046, "heading_rate": -0.01640924439242143, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137710.6875076} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22545955440173993, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.750070137018506, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8338860193519617, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5926929716516729, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137710.6875076} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.459949016571045, "x": 27.434521948079365, "y": 0.06267976747914794, "z": null, "yaw": 3.3047375415419027, "pitch": null, "roll": null}, "v": 1.8366880882828278, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.32556863575054173, "steering_wheel_angle": -0.4946905886484585, "front_wheel_angle": -0.02286743375085046, "heading_rate": -0.01640924439242143, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137710.7075076} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22545955440173993, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.750070137018506, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8305633903839456, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6904363598548092, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137710.7075076} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.459949016571045, "x": 27.434521948079365, "y": 0.06267976747914794, "z": null, "yaw": 3.3047375415419027, "pitch": null, "roll": null}, "v": 1.8366880882828278, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.32556863575054173, "steering_wheel_angle": -0.4946905886484585, "front_wheel_angle": -0.02286743375085046, "heading_rate": -0.01640924439242143, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137710.7275076} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22545955440173993, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.750070137018506, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8272465155691104, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7879207532578673, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137710.7275076} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.459949016571045, "x": 27.434521948079365, "y": 0.06267976747914794, "z": null, "yaw": 3.3047375415419027, "pitch": null, "roll": null}, "v": 1.8366880882828278, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.32556863575054173, "steering_wheel_angle": -0.4946905886484585, "front_wheel_angle": -0.02286743375085046, "heading_rate": -0.01640924439242143, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137710.7475076} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22545955440173993, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.750070137018506, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8239353805436112, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.8851461518608472, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137710.7475076} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.459949016571045, "x": 27.434521948079365, "y": 0.06267976747914794, "z": null, "yaw": 3.3047375415419027, "pitch": null, "roll": null}, "v": 1.8366880882828278, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.32556863575054173, "steering_wheel_angle": -0.4946905886484585, "front_wheel_angle": -0.02286743375085046, "heading_rate": -0.01640924439242143, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137710.7675076} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22545955440173993, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.750070137018506, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.820629970991299, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.9821125556637487, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137710.7675076} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137710.7775075, "x": 31.236001997306087, "y": 5.030119951407559, "z": null, "yaw": 3.303263792840904, "pitch": null, "roll": null}, "v": 1.818979408806785, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3240358313369701, "steering_wheel_angle": -1.03049863451517, "front_wheel_angle": -0.04798151278848881, "heading_rate": -0.03411891519930124, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137710.7875075} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2165571963841683, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.660223018771749, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.817330272643524, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.0788199646665722, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137710.7875075} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.56994891166687, "x": 27.236001997306087, "y": 0.030119951407558965, "z": null, "yaw": 3.303263792840904, "pitch": null, "roll": null}, "v": 1.818979408806785, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3240358313369701, "steering_wheel_angle": -1.03049863451517, "front_wheel_angle": -0.04798151278848881, "heading_rate": -0.03411891519930124, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137710.8075075} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22067963144893338, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.660223018771749, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8109813024025683, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.2228736960494764, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137710.8075075} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.56994891166687, "x": 27.236001997306087, "y": 0.030119951407558965, "z": null, "yaw": 3.303263792840904, "pitch": null, "roll": null}, "v": 1.818979408806785, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3240358313369701, "steering_wheel_angle": -1.03049863451517, "front_wheel_angle": -0.04798151278848881, "heading_rate": -0.03411891519930124, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137710.8275075} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22067963144893338, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.660223018771749, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.80904032338916, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.2707630439989723, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137710.8275075} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.56994891166687, "x": 27.236001997306087, "y": 0.030119951407558965, "z": null, "yaw": 3.303263792840904, "pitch": null, "roll": null}, "v": 1.818979408806785, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3240358313369701, "steering_wheel_angle": -1.03049863451517, "front_wheel_angle": -0.04798151278848881, "heading_rate": -0.03411891519930124, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137710.8475075} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22067963144893338, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.660223018771749, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.805163382551919, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.3663488961307566, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137710.8475075} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.56994891166687, "x": 27.236001997306087, "y": 0.030119951407558965, "z": null, "yaw": 3.303263792840904, "pitch": null, "roll": null}, "v": 1.818979408806785, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3240358313369701, "steering_wheel_angle": -1.03049863451517, "front_wheel_angle": -0.04798151278848881, "heading_rate": -0.03411891519930124, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137710.8675075} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22067963144893338, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.660223018771749, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7993604814063044, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.5092455649104124, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137710.8675075} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137710.8875074, "x": 31.039557738521875, "y": 4.998296540859234, "z": null, "yaw": 3.3007098959476067, "pitch": null, "roll": null}, "v": 1.797429508316955, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.32217900378953307, "steering_wheel_angle": -1.5567492253254924, "front_wheel_angle": -0.07301302999084314, "heading_rate": -0.051355263535596295, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137710.8875074} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23198876419441858, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.944756105477125, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.797429508316955, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.5567492253254924, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137710.8875074} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.679948806762695, "x": 27.039557738521875, "y": -0.0017034591407663058, "z": null, "yaw": 3.3007098959476067, "pitch": null, "roll": null}, "v": 1.797429508316955, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.32217900378953307, "steering_wheel_angle": -1.5567492253254924, "front_wheel_angle": -0.07301302999084314, "heading_rate": -0.051355263535596295, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137710.9075074} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22646198755113545, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.944756105477125, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7934197584444687, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.700524199136136, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137710.9075074} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.679948806762695, "x": 27.039557738521875, "y": -0.0017034591407663058, "z": null, "yaw": 3.3007098959476067, "pitch": null, "roll": null}, "v": 1.797429508316955, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.32217900378953307, "steering_wheel_angle": -1.5567492253254924, "front_wheel_angle": -0.07301302999084314, "heading_rate": -0.051355263535596295, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137710.9275074} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22646198755113545, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.944756105477125, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7918552873441944, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.748317619837049, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137710.9275074} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.679948806762695, "x": 27.039557738521875, "y": -0.0017034591407663058, "z": null, "yaw": 3.3007098959476067, "pitch": null, "roll": null}, "v": 1.797429508316955, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.32217900378953307, "steering_wheel_angle": -1.5567492253254924, "front_wheel_angle": -0.07301302999084314, "heading_rate": -0.051355263535596295, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137710.9475074} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22646198755113545, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.944756105477125, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7887303729260475, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.843707105384923, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137710.9475074} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.679948806762695, "x": 27.039557738521875, "y": -0.0017034591407663058, "z": null, "yaw": 3.3007098959476067, "pitch": null, "roll": null}, "v": 1.797429508316955, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.32217900378953307, "steering_wheel_angle": -1.5567492253254924, "front_wheel_angle": -0.07301302999084314, "heading_rate": -0.051355263535596295, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137710.9675074} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22646198755113545, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.944756105477125, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7856108179510535, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.9388334497941946, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137710.9675074} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.679948806762695, "x": 27.039557738521875, "y": -0.0017034591407663058, "z": null, "yaw": 3.3007098959476067, "pitch": null, "roll": null}, "v": 1.797429508316955, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.32217900378953307, "steering_wheel_angle": -1.5567492253254924, "front_wheel_angle": -0.07301302999084314, "heading_rate": -0.051355263535596295, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137710.9875073} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22646198755113545, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.944756105477125, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.782496609336416, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.033696653064863, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137710.9875073} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137710.9975073, "x": 30.845074473445923, "y": 4.967398490089087, "z": null, "yaw": 3.2970693304666474, "pitch": null, "roll": null}, "v": 1.7809415058374642, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3207646017640194, "steering_wheel_angle": -2.0810295767732208, "front_wheel_angle": -0.09832734086164803, "heading_rate": -0.06862569811771498, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137711.0075073} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23713146768877524, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.195114458110013, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.77938773404177, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.1282967151969285, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137711.0075073} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.78994870185852, "x": 26.845074473445923, "y": -0.03260150991091315, "z": null, "yaw": 3.2970693304666474, "pitch": null, "roll": null}, "v": 1.7809415058374642, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3207646017640194, "steering_wheel_angle": -2.0810295767732208, "front_wheel_angle": -0.09832734086164803, "heading_rate": -0.06862569811771498, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137711.0275073} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23194299630561094, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.195114458110013, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.777617293513262, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.2236185772551758, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137711.0275073} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.78994870185852, "x": 26.845074473445923, "y": -0.03260150991091315, "z": null, "yaw": 3.2970693304666474, "pitch": null, "roll": null}, "v": 1.7809415058374642, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3207646017640194, "steering_wheel_angle": -2.0810295767732208, "front_wheel_angle": -0.09832734086164803, "heading_rate": -0.06862569811771498, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137711.0475073} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23194299630561094, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.195114458110013, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7752015997469899, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.3186717669130563, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137711.0475073} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.78994870185852, "x": 26.845074473445923, "y": -0.03260150991091315, "z": null, "yaw": 3.2970693304666474, "pitch": null, "roll": null}, "v": 1.7809415058374642, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3207646017640194, "steering_wheel_angle": -2.0810295767732208, "front_wheel_angle": -0.09832734086164803, "heading_rate": -0.06862569811771498, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137711.0675073} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23194299630561094, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.195114458110013, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7727900358290682, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.4134562841705702, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137711.0675073} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.78994870185852, "x": 26.845074473445923, "y": -0.03260150991091315, "z": null, "yaw": 3.2970693304666474, "pitch": null, "roll": null}, "v": 1.7809415058374642, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3207646017640194, "steering_wheel_angle": -2.0810295767732208, "front_wheel_angle": -0.09832734086164803, "heading_rate": -0.06862569811771498, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137711.0875072} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23194299630561094, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.195114458110013, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7703825923738823, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.507972129027718, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137711.0875072} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137711.1075072, "x": 30.65210806040921, "y": 4.937559998091566, "z": null, "yaw": 3.2923262975123193, "pitch": null, "roll": null}, "v": 1.7679792600237745, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3196564696399309, "steering_wheel_angle": -2.6022193014845, "front_wheel_angle": -0.12388226215792277, "heading_rate": -0.08599555369453386, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137711.1075072} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23387340329296719, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.13864726154983, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7679792600237745, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.6022193014845, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137711.1075072} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.899948596954346, "x": 26.65210806040921, "y": -0.062440001908433906, "z": null, "yaw": 3.2923262975123193, "pitch": null, "roll": null}, "v": 1.7679792600237745, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3196564696399309, "steering_wheel_angle": -2.6022193014845, "front_wheel_angle": -0.12388226215792277, "heading_rate": -0.08599555369453386, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137711.1275072} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2328697322548228, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.13864726154983, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7658212273631513, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.6959761312686976, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137711.1275072} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.899948596954346, "x": 26.65210806040921, "y": -0.062440001908433906, "z": null, "yaw": 3.2923262975123193, "pitch": null, "roll": null}, "v": 1.7679792600237745, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3196564696399309, "steering_wheel_angle": -2.6022193014845, "front_wheel_angle": -0.12388226215792277, "heading_rate": -0.08599555369453386, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137711.1475072} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2328697322548228, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.13864726154983, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.763541470534678, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.789465556416895, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137711.1475072} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.899948596954346, "x": 26.65210806040921, "y": -0.062440001908433906, "z": null, "yaw": 3.2923262975123193, "pitch": null, "roll": null}, "v": 1.7679792600237745, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3196564696399309, "steering_wheel_angle": -2.6022193014845, "front_wheel_angle": -0.12388226215792277, "heading_rate": -0.08599555369453386, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137711.1675072} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2328697322548228, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.13864726154983, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.761265600503187, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.8826875769290945, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137711.1675072} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.899948596954346, "x": 26.65210806040921, "y": -0.062440001908433906, "z": null, "yaw": 3.2923262975123193, "pitch": null, "roll": null}, "v": 1.7679792600237745, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3196564696399309, "steering_wheel_angle": -2.6022193014845, "front_wheel_angle": -0.12388226215792277, "heading_rate": -0.08599555369453386, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137711.1875072} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2328697322548228, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.13864726154983, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7589936085710591, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.9756421928052936, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137711.1875072} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.899948596954346, "x": 26.65210806040921, "y": -0.062440001908433906, "z": null, "yaw": 3.2923262975123193, "pitch": null, "roll": null}, "v": 1.7679792600237745, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3196564696399309, "steering_wheel_angle": -2.6022193014845, "front_wheel_angle": -0.12388226215792277, "heading_rate": -0.08599555369453386, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137711.2075071} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2328697322548228, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.13864726154983, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7567254860660841, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.068329404045494, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137711.2075071} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137711.2175071, "x": 30.460369426786553, "y": 4.908940971621265, "z": null, "yaw": 3.286468619319421, "pitch": null, "roll": null}, "v": 1.755592873145638, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.31860070701967946, "steering_wheel_angle": -3.114572732927094, "front_wheel_angle": -0.14940082432171342, "heading_rate": -0.10322502847957611, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137711.227507} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24493786604782652, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.3097913896748965, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7544612243413678, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.160749210649695, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137711.227507} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.00994849205017, "x": 26.460369426786553, "y": -0.09105902837873536, "z": null, "yaw": 3.286468619319421, "pitch": null, "roll": null}, "v": 1.755592873145638, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.31860070701967946, "steering_wheel_angle": -3.114572732927094, "front_wheel_angle": -0.14940082432171342, "heading_rate": -0.10322502847957611, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137711.247507} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23911069370249746, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.3097913896748965, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7537086898204495, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.2535667508449326, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137711.247507} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.00994849205017, "x": 26.460369426786553, "y": -0.09105902837873536, "z": null, "yaw": 3.286468619319421, "pitch": null, "roll": null}, "v": 1.755592873145638, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.31860070701967946, "steering_wheel_angle": -3.114572732927094, "front_wheel_angle": -0.14940082432171342, "heading_rate": -0.10322502847957611, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137711.267507} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23911069370249746, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.3097913896748965, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7522293484914029, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.3461130066331295, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137711.267507} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.00994849205017, "x": 26.460369426786553, "y": -0.09105902837873536, "z": null, "yaw": 3.286468619319421, "pitch": null, "roll": null}, "v": 1.755592873145638, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.31860070701967946, "steering_wheel_angle": -3.114572732927094, "front_wheel_angle": -0.14940082432171342, "heading_rate": -0.10322502847957611, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137711.287507} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23911069370249746, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.3097913896748965, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7507525225106086, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.438387978014288, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137711.287507} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.00994849205017, "x": 26.460369426786553, "y": -0.09105902837873536, "z": null, "yaw": 3.286468619319421, "pitch": null, "roll": null}, "v": 1.755592873145638, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.31860070701967946, "steering_wheel_angle": -3.114572732927094, "front_wheel_angle": -0.14940082432171342, "heading_rate": -0.10322502847957611, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137711.307507} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23911069370249746, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.3097913896748965, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.749278206729144, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.530391664988408, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137711.307507} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137711.327507, "x": 30.269572927994837, "y": 4.881703505803953, "z": null, "yaw": 3.2794868267057873, "pitch": null, "roll": null}, "v": 1.747806396011284, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.31793859177994377, "steering_wheel_angle": -3.6221240675554878, "front_wheel_angle": -0.17508707522236552, "heading_rate": -0.12077507133186736, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137711.327507} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23554265857787215, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.895266795806955, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.747806396011284, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.6221240675554878, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137711.327507} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.119948387145996, "x": 26.269572927994837, "y": -0.11829649419604671, "z": null, "yaw": 3.2794868267057873, "pitch": null, "roll": null}, "v": 1.747806396011284, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.31793859177994377, "steering_wheel_angle": -3.6221240675554878, "front_wheel_angle": -0.17508707522236552, "heading_rate": -0.12077507133186736, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137711.347507} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23719127687108027, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.895266795806955, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7458912702601606, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.712021561676558, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137711.347507} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.119948387145996, "x": 26.269572927994837, "y": -0.11829649419604671, "z": null, "yaw": 3.2794868267057873, "pitch": null, "roll": null}, "v": 1.747806396011284, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.31793859177994377, "steering_wheel_angle": -3.6221240675554878, "front_wheel_angle": -0.17508707522236552, "heading_rate": -0.12077507133186736, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137711.367507} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23719127687108027, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.895266795806955, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.744185385868053, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.801656981194723, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137711.367507} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.119948387145996, "x": 26.269572927994837, "y": -0.11829649419604671, "z": null, "yaw": 3.2794868267057873, "pitch": null, "roll": null}, "v": 1.747806396011284, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.31793859177994377, "steering_wheel_angle": -3.6221240675554878, "front_wheel_angle": -0.17508707522236552, "heading_rate": -0.12077507133186736, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137711.387507} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23719127687108027, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.895266795806955, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7424823965735374, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.8910303261099823, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137711.387507} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.119948387145996, "x": 26.269572927994837, "y": -0.11829649419604671, "z": null, "yaw": 3.2794868267057873, "pitch": null, "roll": null}, "v": 1.747806396011284, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.31793859177994377, "steering_wheel_angle": -3.6221240675554878, "front_wheel_angle": -0.17508707522236552, "heading_rate": -0.12077507133186736, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137711.407507} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23719127687108027, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.895266795806955, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7407822963036963, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.980141596422337, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137711.407507} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.119948387145996, "x": 26.269572927994837, "y": -0.11829649419604671, "z": null, "yaw": 3.2794868267057873, "pitch": null, "roll": null}, "v": 1.747806396011284, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.31793859177994377, "steering_wheel_angle": -3.6221240675554878, "front_wheel_angle": -0.17508707522236552, "heading_rate": -0.12077507133186736, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137711.427507} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23719127687108027, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.895266795806955, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.739085079001817, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.0689907921317845, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137711.427507} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137711.437507, "x": 30.079530185108798, "y": 4.856025489320928, "z": null, "yaw": 3.271375363899069, "pitch": null, "roll": null}, "v": 1.738237549575558, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3171265752663223, "steering_wheel_angle": -4.113317112010419, "front_wheel_angle": -0.20035003336873577, "heading_rate": -0.13788737624629013, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137711.447507} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25143529170491596, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.951120465081538, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7373907386273373, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.1575779132383275, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137711.447507} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.22994828224182, "x": 26.079530185108798, "y": -0.1439745106790724, "z": null, "yaw": 3.271375363899069, "pitch": null, "roll": null}, "v": 1.738237549575558, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3171265752663223, "steering_wheel_angle": -4.113317112010419, "front_wheel_angle": -0.20035003336873577, "heading_rate": -0.13788737624629013, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137711.467507} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24459055615423572, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.951120465081538, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7370953035312224, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.290270365383244, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137711.467507} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24459055615423572, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.951120465081538, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7370953035312224, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.290270365383244, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137711.4775069} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.22994828224182, "x": 26.079530185108798, "y": -0.1439745106790724, "z": null, "yaw": 3.271375363899069, "pitch": null, "roll": null}, "v": 1.738237549575558, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3171265752663223, "steering_wheel_angle": -4.113317112010419, "front_wheel_angle": -0.20035003336873577, "heading_rate": -0.13788737624629013, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137711.5075068} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24459055615423572, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.951120465081538, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7355636999601194, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.466272158668381, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137711.5075068} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.22994828224182, "x": 26.079530185108798, "y": -0.1439745106790724, "z": null, "yaw": 3.271375363899069, "pitch": null, "roll": null}, "v": 1.738237549575558, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3171265752663223, "steering_wheel_angle": -4.113317112010419, "front_wheel_angle": -0.20035003336873577, "heading_rate": -0.13788737624629013, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137711.5175068} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24459055615423572, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.951120465081538, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7355636999601194, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.466272158668381, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137711.5175068} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137711.5475068, "x": 29.890015739342648, "y": 4.8320816340526385, "z": null, "yaw": 3.2621330368987675, "pitch": null, "roll": null}, "v": 1.7344183999554847, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3168029918588157, "steering_wheel_angle": -4.59758239645117, "front_wheel_angle": -0.22566570012559095, "heading_rate": -0.15553942339746055, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137711.5475068} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.258078210688019, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.944193818382105, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7344183999554847, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.59758239645117, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137711.5475068} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.33994817733765, "x": 25.890015739342648, "y": -0.16791836594736154, "z": null, "yaw": 3.2621330368987675, "pitch": null, "roll": null}, "v": 1.7344183999554847, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3168029918588157, "steering_wheel_angle": -4.59758239645117, "front_wheel_angle": -0.22566570012559095, "heading_rate": -0.15553942339746055, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137711.5675068} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25163086085824593, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.944193818382105, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7353998421434054, "gear": 1, "accelerator_pedal_position": 0.25163086085824593, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.728263109635213, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137711.5675068} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.33994817733765, "x": 25.890015739342648, "y": -0.16791836594736154, "z": null, "yaw": 3.2621330368987675, "pitch": null, "roll": null}, "v": 1.7344183999554847, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3168029918588157, "steering_wheel_angle": -4.59758239645117, "front_wheel_angle": -0.22566570012559095, "heading_rate": -0.15553942339746055, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137711.5875068} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25163086085824593, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.944193818382105, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7354579097647629, "gear": 1, "accelerator_pedal_position": 0.25163086085824593, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.771691782877179, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137711.5875068} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.33994817733765, "x": 25.890015739342648, "y": -0.16791836594736154, "z": null, "yaw": 3.2621330368987675, "pitch": null, "roll": null}, "v": 1.7344183999554847, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3168029918588157, "steering_wheel_angle": -4.59758239645117, "front_wheel_angle": -0.22566570012559095, "heading_rate": -0.15553942339746055, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137711.6075068} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25163086085824593, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.944193818382105, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.735573897483703, "gear": 1, "accelerator_pedal_position": 0.25163086085824593, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.858351782632037, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137711.6075068} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.33994817733765, "x": 25.890015739342648, "y": -0.16791836594736154, "z": null, "yaw": 3.2621330368987675, "pitch": null, "roll": null}, "v": 1.7344183999554847, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3168029918588157, "steering_wheel_angle": -4.59758239645117, "front_wheel_angle": -0.22566570012559095, "heading_rate": -0.15553942339746055, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137711.6275067} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25163086085824593, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.944193818382105, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7356896887773992, "gear": 1, "accelerator_pedal_position": 0.25163086085824593, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.944748653414797, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137711.6275067} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.33994817733765, "x": 25.890015739342648, "y": -0.16791836594736154, "z": null, "yaw": 3.2621330368987675, "pitch": null, "roll": null}, "v": 1.7344183999554847, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3168029918588157, "steering_wheel_angle": -4.59758239645117, "front_wheel_angle": -0.22566570012559095, "heading_rate": -0.15553942339746055, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137711.6475067} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25163086085824593, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.944193818382105, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7358052839731366, "gear": 1, "accelerator_pedal_position": 0.25163086085824593, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.03088239522546, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137711.6475067} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137711.6575067, "x": 29.700402944006672, "y": 4.8100039733207245, "z": null, "yaw": 3.251745990646336, "pitch": null, "roll": null}, "v": 1.7358630081364035, "accelerator_pedal_position": 0.25163086085824593, "brake_pedal_position": 0.0, "acceleration": 0.005767526127053169, "steering_wheel_angle": -5.073850592766256, "front_wheel_angle": -0.2509794257776427, "heading_rate": -0.1738476745744824, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137711.6675067} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25109231817761846, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.256688850522532, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.735920683397674, "gear": 1, "accelerator_pedal_position": 0.25163086085824593, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.116753008064028, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137711.6675067} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.44994807243347, "x": 25.700402944006672, "y": -0.1899960266792755, "z": null, "yaw": 3.251745990646336, "pitch": null, "roll": null}, "v": 1.7358630081364035, "accelerator_pedal_position": 0.25163086085824593, "brake_pedal_position": 0.0, "acceleration": 0.005767526127053169, "steering_wheel_angle": -5.073850592766256, "front_wheel_angle": -0.2509794257776427, "heading_rate": -0.1738476745744824, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137711.6875067} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25135809005378046, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.256688850522532, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7359685980577406, "gear": 1, "accelerator_pedal_position": 0.25109231817761846, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.200042170376734, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137711.6875067} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.44994807243347, "x": 25.700402944006672, "y": -0.1899960266792755, "z": null, "yaw": 3.251745990646336, "pitch": null, "roll": null}, "v": 1.7358630081364035, "accelerator_pedal_position": 0.25163086085824593, "brake_pedal_position": 0.0, "acceleration": 0.005767526127053169, "steering_wheel_angle": -5.073850592766256, "front_wheel_angle": -0.2509794257776427, "heading_rate": -0.1738476745744824, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137711.7075067} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25135809005378046, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.256688850522532, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7360496389783253, "gear": 1, "accelerator_pedal_position": 0.25135809005378046, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.283082283008777, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137711.7075067} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.44994807243347, "x": 25.700402944006672, "y": -0.1899960266792755, "z": null, "yaw": 3.251745990646336, "pitch": null, "roll": null}, "v": 1.7358630081364035, "accelerator_pedal_position": 0.25163086085824593, "brake_pedal_position": 0.0, "acceleration": 0.005767526127053169, "steering_wheel_angle": -5.073850592766256, "front_wheel_angle": -0.2509794257776427, "heading_rate": -0.1738476745744824, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137711.7275066} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25135809005378046, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.256688850522532, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.73613054264039, "gear": 1, "accelerator_pedal_position": 0.25135809005378046, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.365873345960157, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137711.7275066} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.44994807243347, "x": 25.700402944006672, "y": -0.1899960266792755, "z": null, "yaw": 3.251745990646336, "pitch": null, "roll": null}, "v": 1.7358630081364035, "accelerator_pedal_position": 0.25163086085824593, "brake_pedal_position": 0.0, "acceleration": 0.005767526127053169, "steering_wheel_angle": -5.073850592766256, "front_wheel_angle": -0.2509794257776427, "heading_rate": -0.1738476745744824, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137711.7475066} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25135809005378046, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.256688850522532, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7362113092737912, "gear": 1, "accelerator_pedal_position": 0.25135809005378046, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.448415359230872, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137711.7475066} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137711.7675066, "x": 29.51048969607527, "y": 4.789988649654323, "z": null, "yaw": 3.2402120782433705, "pitch": null, "roll": null}, "v": 1.73629193910801, "accelerator_pedal_position": 0.25135809005378046, "brake_pedal_position": 0.0, "acceleration": 0.004026368902612765, "steering_wheel_angle": -5.530708322820925, "front_wheel_angle": -0.27566902130275067, "heading_rate": -0.19185417718867717, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137711.7675066} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2671085783712125, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.0918311144352035, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7373166083168756, "gear": 1, "accelerator_pedal_position": 0.2671085783712125, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.530708322820925, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137711.7675066} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.5599479675293, "x": 25.51048969607527, "y": -0.21001135034567664, "z": null, "yaw": 3.2402120782433705, "pitch": null, "roll": null}, "v": 1.73629193910801, "accelerator_pedal_position": 0.25135809005378046, "brake_pedal_position": 0.0, "acceleration": 0.004026368902612765, "steering_wheel_angle": -5.530708322820925, "front_wheel_angle": -0.27566902130275067, "heading_rate": -0.19185417718867717, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137711.7875066} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2596111108325727, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.0918311144352035, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7383404092611645, "gear": 1, "accelerator_pedal_position": 0.2671085783712125, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.530708322820925, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137711.7875066} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.5599479675293, "x": 25.51048969607527, "y": -0.21001135034567664, "z": null, "yaw": 3.2402120782433705, "pitch": null, "roll": null}, "v": 1.73629193910801, "accelerator_pedal_position": 0.25135809005378046, "brake_pedal_position": 0.0, "acceleration": 0.004026368902612765, "steering_wheel_angle": -5.530708322820925, "front_wheel_angle": -0.27566902130275067, "heading_rate": -0.19185417718867717, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137711.8075066} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2596111108325727, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.0918311144352035, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7400020242668905, "gear": 1, "accelerator_pedal_position": 0.2596111108325727, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.530708322820925, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137711.8075066} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.5599479675293, "x": 25.51048969607527, "y": -0.21001135034567664, "z": null, "yaw": 3.2402120782433705, "pitch": null, "roll": null}, "v": 1.73629193910801, "accelerator_pedal_position": 0.25135809005378046, "brake_pedal_position": 0.0, "acceleration": 0.004026368902612765, "steering_wheel_angle": -5.530708322820925, "front_wheel_angle": -0.27566902130275067, "heading_rate": -0.19185417718867717, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137711.8175066} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2596111108325727, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.0918311144352035, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7405549569773475, "gear": 1, "accelerator_pedal_position": 0.2596111108325727, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.530708322820925, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137711.8175066} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.5599479675293, "x": 25.51048969607527, "y": -0.21001135034567664, "z": null, "yaw": 3.2402120782433705, "pitch": null, "roll": null}, "v": 1.73629193910801, "accelerator_pedal_position": 0.25135809005378046, "brake_pedal_position": 0.0, "acceleration": 0.004026368902612765, "steering_wheel_angle": -5.530708322820925, "front_wheel_angle": -0.27566902130275067, "heading_rate": -0.19185417718867717, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137711.8475065} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2596111108325727, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.0918311144352035, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7416594159816534, "gear": 1, "accelerator_pedal_position": 0.2596111108325727, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.530708322820925, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137711.8475065} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.5599479675293, "x": 25.51048969607527, "y": -0.21001135034567664, "z": null, "yaw": 3.2402120782433705, "pitch": null, "roll": null}, "v": 1.73629193910801, "accelerator_pedal_position": 0.25135809005378046, "brake_pedal_position": 0.0, "acceleration": 0.004026368902612765, "steering_wheel_angle": -5.530708322820925, "front_wheel_angle": -0.27566902130275067, "heading_rate": -0.19185417718867717, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137711.8675065} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2596111108325727, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.0918311144352035, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7433125934936273, "gear": 1, "accelerator_pedal_position": 0.2596111108325727, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.530708322820925, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137711.8675065} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137711.8775065, "x": 29.31993363322317, "y": 4.772198231353218, "z": null, "yaw": 3.228057463564, "pitch": null, "roll": null}, "v": 1.7433125934936273, "accelerator_pedal_position": 0.2596111108325727, "brake_pedal_position": 0.0, "acceleration": 0.05501242504256321, "steering_wheel_angle": -5.530708322820925, "front_wheel_angle": -0.27566902130275067, "heading_rate": -0.1926299349055336, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137711.8875065} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2739918690743322, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.862255326393931, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7438627177440529, "gear": 1, "accelerator_pedal_position": 0.2596111108325727, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.530708322820925, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137711.8875065} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.66994786262512, "x": 25.31993363322317, "y": -0.22780176864678214, "z": null, "yaw": 3.228057463564, "pitch": null, "roll": null}, "v": 1.7433125934936273, "accelerator_pedal_position": 0.2596111108325727, "brake_pedal_position": 0.0, "acceleration": 0.05501242504256321, "steering_wheel_angle": -5.530708322820925, "front_wheel_angle": -0.27566902130275067, "heading_rate": -0.1926299349055336, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137711.9075065} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2671892435592858, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.862255326393931, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7477792296402077, "gear": 1, "accelerator_pedal_position": 0.2671892435592858, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.530708322820925, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137711.9075065} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.66994786262512, "x": 25.31993363322317, "y": -0.22780176864678214, "z": null, "yaw": 3.228057463564, "pitch": null, "roll": null}, "v": 1.7433125934936273, "accelerator_pedal_position": 0.2596111108325727, "brake_pedal_position": 0.0, "acceleration": 0.05501242504256321, "steering_wheel_angle": -5.530708322820925, "front_wheel_angle": -0.27566902130275067, "heading_rate": -0.1926299349055336, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137711.9175065} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2671892435592858, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.862255326393931, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7477792296402077, "gear": 1, "accelerator_pedal_position": 0.2671892435592858, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.530708322820925, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137711.9175065} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.66994786262512, "x": 25.31993363322317, "y": -0.22780176864678214, "z": null, "yaw": 3.228057463564, "pitch": null, "roll": null}, "v": 1.7433125934936273, "accelerator_pedal_position": 0.2596111108325727, "brake_pedal_position": 0.0, "acceleration": 0.05501242504256321, "steering_wheel_angle": -5.530708322820925, "front_wheel_angle": -0.27566902130275067, "heading_rate": -0.1926299349055336, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137711.9475064} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2671892435592858, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.862255326393931, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7508365249574878, "gear": 1, "accelerator_pedal_position": 0.2671892435592858, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.530708322820925, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137711.9475064} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.66994786262512, "x": 25.31993363322317, "y": -0.22780176864678214, "z": null, "yaw": 3.228057463564, "pitch": null, "roll": null}, "v": 1.7433125934936273, "accelerator_pedal_position": 0.2596111108325727, "brake_pedal_position": 0.0, "acceleration": 0.05501242504256321, "steering_wheel_angle": -5.530708322820925, "front_wheel_angle": -0.27566902130275067, "heading_rate": -0.1926299349055336, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137711.9675064} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2671892435592858, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.862255326393931, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7528703931346865, "gear": 1, "accelerator_pedal_position": 0.2671892435592858, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.530708322820925, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137711.9675064} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137711.9875064, "x": 29.12821354157748, "y": 4.7566477498800595, "z": null, "yaw": 3.215902848884629, "pitch": null, "roll": null}, "v": 1.7549008032857247, "accelerator_pedal_position": 0.2671892435592858, "brake_pedal_position": 0.0, "acceleration": 0.10139096378752116, "steering_wheel_angle": -5.530708322820925, "front_wheel_angle": -0.27566902130275067, "heading_rate": -0.1939103914950486, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137711.9875064} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2675538789294041, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.927819165420825, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7549008032857247, "gear": 1, "accelerator_pedal_position": 0.2671892435592858, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.530708322820925, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137711.9875064} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.77994775772095, "x": 25.12821354157748, "y": -0.24335225011994055, "z": null, "yaw": 3.215902848884629, "pitch": null, "roll": null}, "v": 1.7549008032857247, "accelerator_pedal_position": 0.2671892435592858, "brake_pedal_position": 0.0, "acceleration": 0.10139096378752116, "steering_wheel_angle": -5.530708322820925, "front_wheel_angle": -0.27566902130275067, "heading_rate": -0.1939103914950486, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137712.0075064} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2674552746693858, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.927819165420825, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7569733196646873, "gear": 1, "accelerator_pedal_position": 0.2675538789294041, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.530708322820925, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137712.0075064} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.77994775772095, "x": 25.12821354157748, "y": -0.24335225011994055, "z": null, "yaw": 3.215902848884629, "pitch": null, "roll": null}, "v": 1.7549008032857247, "accelerator_pedal_position": 0.2671892435592858, "brake_pedal_position": 0.0, "acceleration": 0.10139096378752116, "steering_wheel_angle": -5.530708322820925, "front_wheel_angle": -0.27566902130275067, "heading_rate": -0.1939103914950486, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137712.0275064} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2674552746693858, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.927819165420825, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.759029988632254, "gear": 1, "accelerator_pedal_position": 0.2674552746693858, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.530708322820925, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137712.0275064} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.77994775772095, "x": 25.12821354157748, "y": -0.24335225011994055, "z": null, "yaw": 3.215902848884629, "pitch": null, "roll": null}, "v": 1.7549008032857247, "accelerator_pedal_position": 0.2671892435592858, "brake_pedal_position": 0.0, "acceleration": 0.10139096378752116, "steering_wheel_angle": -5.530708322820925, "front_wheel_angle": -0.27566902130275067, "heading_rate": -0.1939103914950486, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137712.0475063} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2674552746693858, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.927819165420825, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7610831557489695, "gear": 1, "accelerator_pedal_position": 0.2674552746693858, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.530708322820925, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137712.0475063} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.77994775772095, "x": 25.12821354157748, "y": -0.24335225011994055, "z": null, "yaw": 3.215902848884629, "pitch": null, "roll": null}, "v": 1.7549008032857247, "accelerator_pedal_position": 0.2671892435592858, "brake_pedal_position": 0.0, "acceleration": 0.10139096378752116, "steering_wheel_angle": -5.530708322820925, "front_wheel_angle": -0.27566902130275067, "heading_rate": -0.1939103914950486, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137712.0675063} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2674552746693858, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.927819165420825, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.763132825291888, "gear": 1, "accelerator_pedal_position": 0.2674552746693858, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.530708322820925, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137712.0675063} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.77994775772095, "x": 25.12821354157748, "y": -0.24335225011994055, "z": null, "yaw": 3.215902848884629, "pitch": null, "roll": null}, "v": 1.7549008032857247, "accelerator_pedal_position": 0.2671892435592858, "brake_pedal_position": 0.0, "acceleration": 0.10139096378752116, "steering_wheel_angle": -5.530708322820925, "front_wheel_angle": -0.27566902130275067, "heading_rate": -0.1939103914950486, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137712.0875063} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2674552746693858, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.927819165420825, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7651790015393904, "gear": 1, "accelerator_pedal_position": 0.2674552746693858, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.530708322820925, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137712.0875063} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137712.0975063, "x": 28.93506686495389, "y": 4.743342342745117, "z": null, "yaw": 3.2037482342052583, "pitch": null, "roll": null}, "v": 1.7662007810147098, "accelerator_pedal_position": 0.2674552746693858, "brake_pedal_position": 0.0, "acceleration": 0.10209077564435587, "steering_wheel_angle": -5.530708322820925, "front_wheel_angle": -0.27566902130275067, "heading_rate": -0.19515899945124204, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137712.1075063} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28208821193348266, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.616875582979295, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7672216887711534, "gear": 1, "accelerator_pedal_position": 0.2674552746693858, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.530708322820925, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137712.1075063} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.88994765281677, "x": 24.93506686495389, "y": -0.2566576572548831, "z": null, "yaw": 3.2037482342052583, "pitch": null, "roll": null}, "v": 1.7662007810147098, "accelerator_pedal_position": 0.2674552746693858, "brake_pedal_position": 0.0, "acceleration": 0.10209077564435587, "steering_wheel_angle": -5.530708322820925, "front_wheel_angle": -0.27566902130275067, "heading_rate": -0.19515899945124204, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137712.1275063} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.275193505607804, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.616875582979295, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7710892276310708, "gear": 1, "accelerator_pedal_position": 0.28208821193348266, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.4532189158524895, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137712.1275063} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.88994765281677, "x": 24.93506686495389, "y": -0.2566576572548831, "z": null, "yaw": 3.2037482342052583, "pitch": null, "roll": null}, "v": 1.7662007810147098, "accelerator_pedal_position": 0.2674552746693858, "brake_pedal_position": 0.0, "acceleration": 0.10209077564435587, "steering_wheel_angle": -5.530708322820925, "front_wheel_angle": -0.27566902130275067, "heading_rate": -0.19515899945124204, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137712.1475062} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.275193505607804, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.616875582979295, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.774088693322798, "gear": 1, "accelerator_pedal_position": 0.275193505607804, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.375508646440735, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137712.1475062} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.88994765281677, "x": 24.93506686495389, "y": -0.2566576572548831, "z": null, "yaw": 3.2037482342052583, "pitch": null, "roll": null}, "v": 1.7662007810147098, "accelerator_pedal_position": 0.2674552746693858, "brake_pedal_position": 0.0, "acceleration": 0.10209077564435587, "steering_wheel_angle": -5.530708322820925, "front_wheel_angle": -0.27566902130275067, "heading_rate": -0.19515899945124204, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137712.1675062} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.275193505607804, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.616875582979295, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7770830341126094, "gear": 1, "accelerator_pedal_position": 0.275193505607804, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.336570688318612, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137712.1675062} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.88994765281677, "x": 24.93506686495389, "y": -0.2566576572548831, "z": null, "yaw": 3.2037482342052583, "pitch": null, "roll": null}, "v": 1.7662007810147098, "accelerator_pedal_position": 0.2674552746693858, "brake_pedal_position": 0.0, "acceleration": 0.10209077564435587, "steering_wheel_angle": -5.530708322820925, "front_wheel_angle": -0.27566902130275067, "heading_rate": -0.19515899945124204, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137712.1875062} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.275193505607804, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.616875582979295, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.78007225517204, "gear": 1, "accelerator_pedal_position": 0.275193505607804, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.336570688318612, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137712.1875062} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137712.2075062, "x": 28.74024937348394, "y": 4.732282377029234, "z": null, "yaw": 3.191904122810309, "pitch": null, "roll": null}, "v": 1.7830563616821673, "accelerator_pedal_position": 0.275193505607804, "brake_pedal_position": 0.0, "acceleration": 0.14901369207531395, "steering_wheel_angle": -5.336570688318612, "front_wheel_angle": -0.2651273373969083, "heading_rate": -0.18911491022557675, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137712.2075062} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2876923546243396, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.283714588364853, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7830563616821673, "gear": 1, "accelerator_pedal_position": 0.275193505607804, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.336570688318612, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137712.2075062} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.9999475479126, "x": 24.74024937348394, "y": -0.26771762297076585, "z": null, "yaw": 3.191904122810309, "pitch": null, "roll": null}, "v": 1.7830563616821673, "accelerator_pedal_position": 0.275193505607804, "brake_pedal_position": 0.0, "acceleration": 0.14901369207531395, "steering_wheel_angle": -5.336570688318612, "front_wheel_angle": -0.2651273373969083, "heading_rate": -0.18911491022557675, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137712.2275062} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2818503113692834, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.283714588364853, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7875970455008348, "gear": 1, "accelerator_pedal_position": 0.2876923546243396, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.259412443794772, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137712.2275062} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.9999475479126, "x": 24.74024937348394, "y": -0.26771762297076585, "z": null, "yaw": 3.191904122810309, "pitch": null, "roll": null}, "v": 1.7830563616821673, "accelerator_pedal_position": 0.275193505607804, "brake_pedal_position": 0.0, "acceleration": 0.14901369207531395, "steering_wheel_angle": -5.336570688318612, "front_wheel_angle": -0.2651273373969083, "heading_rate": -0.18911491022557675, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137712.2475061} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2818503113692834, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.283714588364853, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7914000051197903, "gear": 1, "accelerator_pedal_position": 0.2818503113692834, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.1820383013190785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137712.2475061} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.9999475479126, "x": 24.74024937348394, "y": -0.26771762297076585, "z": null, "yaw": 3.191904122810309, "pitch": null, "roll": null}, "v": 1.7830563616821673, "accelerator_pedal_position": 0.275193505607804, "brake_pedal_position": 0.0, "acceleration": 0.14901369207531395, "steering_wheel_angle": -5.336570688318612, "front_wheel_angle": -0.2651273373969083, "heading_rate": -0.18911491022557675, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137712.2675061} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2818503113692834, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.283714588364853, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7951964409774328, "gear": 1, "accelerator_pedal_position": 0.2818503113692834, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.104448260891534, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137712.2675061} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.9999475479126, "x": 24.74024937348394, "y": -0.26771762297076585, "z": null, "yaw": 3.191904122810309, "pitch": null, "roll": null}, "v": 1.7830563616821673, "accelerator_pedal_position": 0.275193505607804, "brake_pedal_position": 0.0, "acceleration": 0.14901369207531395, "steering_wheel_angle": -5.336570688318612, "front_wheel_angle": -0.2651273373969083, "heading_rate": -0.18911491022557675, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137712.287506} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2818503113692834, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.283714588364853, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7989863585022083, "gear": 1, "accelerator_pedal_position": 0.2818503113692834, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.026642322512137, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137712.287506} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.9999475479126, "x": 24.74024937348394, "y": -0.26771762297076585, "z": null, "yaw": 3.191904122810309, "pitch": null, "roll": null}, "v": 1.7830563616821673, "accelerator_pedal_position": 0.275193505607804, "brake_pedal_position": 0.0, "acceleration": 0.14901369207531395, "steering_wheel_angle": -5.336570688318612, "front_wheel_angle": -0.2651273373969083, "heading_rate": -0.18911491022557675, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137712.307506} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2818503113692834, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.283714588364853, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.802769763142919, "gear": 1, "accelerator_pedal_position": 0.2818503113692834, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.026642322512137, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137712.307506} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137712.317506, "x": 28.543200184768434, "y": 4.723384044779636, "z": null, "yaw": 3.180690302509204, "pitch": null, "roll": null}, "v": 1.8046590248400374, "accelerator_pedal_position": 0.2818503113692834, "brake_pedal_position": 0.0, "acceleration": 0.18876355285665336, "steering_wheel_angle": -5.026642322512137, "front_wheel_angle": -0.24845128322069793, "heading_rate": -0.17883950971212068, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137712.327506} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2866830709649421, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.5795886598277447, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.806546660368604, "gear": 1, "accelerator_pedal_position": 0.2818503113692834, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.026642322512137, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137712.327506} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.10994744300842, "x": 24.543200184768434, "y": -0.27661595522036375, "z": null, "yaw": 3.180690302509204, "pitch": null, "roll": null}, "v": 1.8046590248400374, "accelerator_pedal_position": 0.2818503113692834, "brake_pedal_position": 0.0, "acceleration": 0.18876355285665336, "steering_wheel_angle": -5.026642322512137, "front_wheel_angle": -0.24845128322069793, "heading_rate": -0.17883950971212068, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137712.347506} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2845231024768037, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.5795886598277447, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8109208903385134, "gear": 1, "accelerator_pedal_position": 0.2866830709649421, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.950412640058649, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137712.347506} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.10994744300842, "x": 24.543200184768434, "y": -0.27661595522036375, "z": null, "yaw": 3.180690302509204, "pitch": null, "roll": null}, "v": 1.8046590248400374, "accelerator_pedal_position": 0.2818503113692834, "brake_pedal_position": 0.0, "acceleration": 0.18876355285665336, "steering_wheel_angle": -5.026642322512137, "front_wheel_angle": -0.24845128322069793, "heading_rate": -0.17883950971212068, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137712.367506} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2845231024768037, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.5795886598277447, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8150177030781787, "gear": 1, "accelerator_pedal_position": 0.2845231024768037, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.8739768509688215, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137712.367506} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.10994744300842, "x": 24.543200184768434, "y": -0.27661595522036375, "z": null, "yaw": 3.180690302509204, "pitch": null, "roll": null}, "v": 1.8046590248400374, "accelerator_pedal_position": 0.2818503113692834, "brake_pedal_position": 0.0, "acceleration": 0.18876355285665336, "steering_wheel_angle": -5.026642322512137, "front_wheel_angle": -0.24845128322069793, "heading_rate": -0.17883950971212068, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137712.387506} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2845231024768037, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.5795886598277447, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8191074494189108, "gear": 1, "accelerator_pedal_position": 0.2845231024768037, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.797334955242656, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137712.387506} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.10994744300842, "x": 24.543200184768434, "y": -0.27661595522036375, "z": null, "yaw": 3.180690302509204, "pitch": null, "roll": null}, "v": 1.8046590248400374, "accelerator_pedal_position": 0.2818503113692834, "brake_pedal_position": 0.0, "acceleration": 0.18876355285665336, "steering_wheel_angle": -5.026642322512137, "front_wheel_angle": -0.24845128322069793, "heading_rate": -0.17883950971212068, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137712.407506} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2845231024768037, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.5795886598277447, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8231901348616852, "gear": 1, "accelerator_pedal_position": 0.2845231024768037, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.720486952880148, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137712.407506} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137712.427506, "x": 28.34367212798187, "y": 4.7165527410579, "z": null, "yaw": 3.1701692713964436, "pitch": null, "roll": null}, "v": 1.8272657649326092, "accelerator_pedal_position": 0.2845231024768037, "brake_pedal_position": 0.0, "acceleration": 0.20351710047644495, "steering_wheel_angle": -4.643432843881302, "front_wheel_angle": -0.22808437825028888, "heading_rate": -0.16568419953514654, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137712.427506} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29478375351567243, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.236316623777126, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8272657649326092, "gear": 1, "accelerator_pedal_position": 0.2845231024768037, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.643432843881302, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137712.427506} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.21994733810425, "x": 24.34367212798187, "y": -0.28344725894210043, "z": null, "yaw": 3.1701692713964436, "pitch": null, "roll": null}, "v": 1.8272657649326092, "accelerator_pedal_position": 0.2845231024768037, "brake_pedal_position": 0.0, "acceleration": 0.20351710047644495, "steering_wheel_angle": -4.643432843881302, "front_wheel_angle": -0.22808437825028888, "heading_rate": -0.16568419953514654, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137712.447506} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2900464046965335, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.236316623777126, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8326163712534393, "gear": 1, "accelerator_pedal_position": 0.29478375351567243, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.567013925630526, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137712.447506} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.21994733810425, "x": 24.34367212798187, "y": -0.28344725894210043, "z": null, "yaw": 3.1701692713964436, "pitch": null, "roll": null}, "v": 1.8272657649326092, "accelerator_pedal_position": 0.2845231024768037, "brake_pedal_position": 0.0, "acceleration": 0.20351710047644495, "steering_wheel_angle": -4.643432843881302, "front_wheel_angle": -0.22808437825028888, "heading_rate": -0.16568419953514654, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137712.467506} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2900464046965335, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.236316623777126, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8373657997146757, "gear": 1, "accelerator_pedal_position": 0.2900464046965335, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.490393359103211, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137712.467506} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.21994733810425, "x": 24.34367212798187, "y": -0.28344725894210043, "z": null, "yaw": 3.1701692713964436, "pitch": null, "roll": null}, "v": 1.8272657649326092, "accelerator_pedal_position": 0.2845231024768037, "brake_pedal_position": 0.0, "acceleration": 0.20351710047644495, "steering_wheel_angle": -4.643432843881302, "front_wheel_angle": -0.22808437825028888, "heading_rate": -0.16568419953514654, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137712.487506} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2900464046965335, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.236316623777126, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8421069940011998, "gear": 1, "accelerator_pedal_position": 0.2900464046965335, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.413571144299355, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137712.487506} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.21994733810425, "x": 24.34367212798187, "y": -0.28344725894210043, "z": null, "yaw": 3.1701692713964436, "pitch": null, "roll": null}, "v": 1.8272657649326092, "accelerator_pedal_position": 0.2845231024768037, "brake_pedal_position": 0.0, "acceleration": 0.20351710047644495, "steering_wheel_angle": -4.643432843881302, "front_wheel_angle": -0.22808437825028888, "heading_rate": -0.16568419953514654, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137712.507506} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2900464046965335, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.236316623777126, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.846839959401089, "gear": 1, "accelerator_pedal_position": 0.2900464046965335, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.336547281218959, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137712.507506} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.21994733810425, "x": 24.34367212798187, "y": -0.28344725894210043, "z": null, "yaw": 3.1701692713964436, "pitch": null, "roll": null}, "v": 1.8272657649326092, "accelerator_pedal_position": 0.2845231024768037, "brake_pedal_position": 0.0, "acceleration": 0.20351710047644495, "steering_wheel_angle": -4.643432843881302, "front_wheel_angle": -0.22808437825028888, "heading_rate": -0.16568419953514654, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137712.5275059} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2900464046965335, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.236316623777126, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8515647012400267, "gear": 1, "accelerator_pedal_position": 0.2900464046965335, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.259321769862023, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137712.5275059} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137712.5375059, "x": 28.141370836201457, "y": 4.711665064616184, "z": null, "yaw": 3.1606498877286757, "pitch": null, "roll": null}, "v": 1.8539239899986522, "accelerator_pedal_position": 0.2900464046965335, "brake_pedal_position": 0.0, "acceleration": 0.23572348824647626, "steering_wheel_angle": -4.220633396079852, "front_wheel_angle": -0.2059244172564113, "heading_rate": -0.15127250929075486, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137712.5475059} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2961394146423589, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.752909437659125, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.856281224881117, "gear": 1, "accelerator_pedal_position": 0.2900464046965335, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.181894610228546, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137712.5475059} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.32994723320007, "x": 24.141370836201457, "y": -0.2883349353838156, "z": null, "yaw": 3.1606498877286757, "pitch": null, "roll": null}, "v": 1.8539239899986522, "accelerator_pedal_position": 0.2900464046965335, "brake_pedal_position": 0.0, "acceleration": 0.23572348824647626, "steering_wheel_angle": -4.220633396079852, "front_wheel_angle": -0.2059244172564113, "heading_rate": -0.15127250929075486, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137712.5675058} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29341430386709433, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.752909437659125, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8617508299882355, "gear": 1, "accelerator_pedal_position": 0.2961394146423589, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.105423299228571, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137712.5675058} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.32994723320007, "x": 24.141370836201457, "y": -0.2883349353838156, "z": null, "yaw": 3.1606498877286757, "pitch": null, "roll": null}, "v": 1.8539239899986522, "accelerator_pedal_position": 0.2900464046965335, "brake_pedal_position": 0.0, "acceleration": 0.23572348824647626, "steering_wheel_angle": -4.220633396079852, "front_wheel_angle": -0.2059244172564113, "heading_rate": -0.15127250929075486, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137712.5875058} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29341430386709433, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.752909437659125, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8668704092476043, "gear": 1, "accelerator_pedal_position": 0.29341430386709433, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.02875630096901, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137712.5875058} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.32994723320007, "x": 24.141370836201457, "y": -0.2883349353838156, "z": null, "yaw": 3.1606498877286757, "pitch": null, "roll": null}, "v": 1.8539239899986522, "accelerator_pedal_position": 0.2900464046965335, "brake_pedal_position": 0.0, "acceleration": 0.23572348824647626, "steering_wheel_angle": -4.220633396079852, "front_wheel_angle": -0.2059244172564113, "heading_rate": -0.15127250929075486, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137712.6075058} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29341430386709433, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.752909437659125, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.87198105241629, "gear": 1, "accelerator_pedal_position": 0.29341430386709433, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.951893615449865, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137712.6075058} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.32994723320007, "x": 24.141370836201457, "y": -0.2883349353838156, "z": null, "yaw": 3.1606498877286757, "pitch": null, "roll": null}, "v": 1.8539239899986522, "accelerator_pedal_position": 0.2900464046965335, "brake_pedal_position": 0.0, "acceleration": 0.23572348824647626, "steering_wheel_angle": -4.220633396079852, "front_wheel_angle": -0.2059244172564113, "heading_rate": -0.15127250929075486, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137712.6275058} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29341430386709433, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.752909437659125, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8770827646490977, "gear": 1, "accelerator_pedal_position": 0.29341430386709433, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.874835242671134, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137712.6275058} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137712.6475058, "x": 27.936046740251538, "y": 4.7085668434973975, "z": null, "yaw": 3.1521192765829014, "pitch": null, "roll": null}, "v": 1.8821755511465559, "accelerator_pedal_position": 0.29341430386709433, "brake_pedal_position": 0.0, "acceleration": 0.2543047735586732, "steering_wheel_angle": -3.7975811826328183, "front_wheel_angle": -0.18406445396167248, "heading_rate": -0.1368780554843919, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137712.6475058} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.30023867642308966, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.465156101740268, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8821755511465559, "gear": 1, "accelerator_pedal_position": 0.29341430386709433, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.7975811826328183, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137712.6475058} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.4399471282959, "x": 23.936046740251538, "y": -0.2914331565026025, "z": null, "yaw": 3.1521192765829014, "pitch": null, "roll": null}, "v": 1.8821755511465559, "accelerator_pedal_position": 0.29341430386709433, "brake_pedal_position": 0.0, "acceleration": 0.2543047735586732, "steering_wheel_angle": -3.7975811826328183, "front_wheel_angle": -0.18406445396167248, "heading_rate": -0.1368780554843919, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137712.6675057} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2971770182101405, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.465156101740268, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8881120896690888, "gear": 1, "accelerator_pedal_position": 0.30023867642308966, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.720804847154854, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137712.6675057} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.4399471282959, "x": 23.936046740251538, "y": -0.2914331565026025, "z": null, "yaw": 3.1521192765829014, "pitch": null, "roll": null}, "v": 1.8821755511465559, "accelerator_pedal_position": 0.29341430386709433, "brake_pedal_position": 0.0, "acceleration": 0.2543047735586732, "steering_wheel_angle": -3.7975811826328183, "front_wheel_angle": -0.18406445396167248, "heading_rate": -0.1368780554843919, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137712.6875057} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2971770182101405, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.465156101740268, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8936556769775954, "gear": 1, "accelerator_pedal_position": 0.2971770182101405, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.6438362083360705, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137712.6875057} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.4399471282959, "x": 23.936046740251538, "y": -0.2914331565026025, "z": null, "yaw": 3.1521192765829014, "pitch": null, "roll": null}, "v": 1.8821755511465559, "accelerator_pedal_position": 0.29341430386709433, "brake_pedal_position": 0.0, "acceleration": 0.2543047735586732, "steering_wheel_angle": -3.7975811826328183, "front_wheel_angle": -0.18406445396167248, "heading_rate": -0.1368780554843919, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137712.7075057} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2971770182101405, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.465156101740268, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.899189528992929, "gear": 1, "accelerator_pedal_position": 0.2971770182101405, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.566675266176469, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137712.7075057} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.4399471282959, "x": 23.936046740251538, "y": -0.2914331565026025, "z": null, "yaw": 3.1521192765829014, "pitch": null, "roll": null}, "v": 1.8821755511465559, "accelerator_pedal_position": 0.29341430386709433, "brake_pedal_position": 0.0, "acceleration": 0.2543047735586732, "steering_wheel_angle": -3.7975811826328183, "front_wheel_angle": -0.18406445396167248, "heading_rate": -0.1368780554843919, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137712.7175057} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2971770182101405, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.465156101740268, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9019528057798627, "gear": 1, "accelerator_pedal_position": 0.2971770182101405, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.528022681343861, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137712.7175057} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.4399471282959, "x": 23.936046740251538, "y": -0.2914331565026025, "z": null, "yaw": 3.1521192765829014, "pitch": null, "roll": null}, "v": 1.8821755511465559, "accelerator_pedal_position": 0.29341430386709433, "brake_pedal_position": 0.0, "acceleration": 0.2543047735586732, "steering_wheel_angle": -3.7975811826328183, "front_wheel_angle": -0.18406445396167248, "heading_rate": -0.1368780554843919, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137712.7475057} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2971770182101405, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.465156101740268, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9102280466100143, "gear": 1, "accelerator_pedal_position": 0.2971770182101405, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.4117764718348096, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137712.7475057} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137712.7575057, "x": 27.72745281417265, "y": 4.707106801824796, "z": null, "yaw": 3.1445559376465546, "pitch": null, "roll": null}, "v": 1.9129815991058376, "accelerator_pedal_position": 0.2971770182101405, "brake_pedal_position": 0.0, "acceleration": 0.2751122978729107, "steering_wheel_angle": -3.3729315836613827, "front_wheel_angle": -0.1624240606912227, "heading_rate": -0.12245146929467879, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137712.7675056} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.30163973515396725, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.2008717191898106, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9157327220845668, "gear": 1, "accelerator_pedal_position": 0.2971770182101405, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.3340386196527523, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137712.7675056} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.549947023391724, "x": 23.72745281417265, "y": -0.29289319817520365, "z": null, "yaw": 3.1445559376465546, "pitch": null, "roll": null}, "v": 1.9129815991058376, "accelerator_pedal_position": 0.2971770182101405, "brake_pedal_position": 0.0, "acceleration": 0.2751122978729107, "steering_wheel_angle": -3.3729315836613827, "front_wheel_angle": -0.1624240606912227, "heading_rate": -0.12245146929467879, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137712.7875056} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2997210644378604, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.2008717191898106, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.921785275140837, "gear": 1, "accelerator_pedal_position": 0.30163973515396725, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.2567207856248763, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137712.7875056} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.549947023391724, "x": 23.72745281417265, "y": -0.29289319817520365, "z": null, "yaw": 3.1445559376465546, "pitch": null, "roll": null}, "v": 1.9129815991058376, "accelerator_pedal_position": 0.2971770182101405, "brake_pedal_position": 0.0, "acceleration": 0.2751122978729107, "steering_wheel_angle": -3.3729315836613827, "front_wheel_angle": -0.1624240606912227, "heading_rate": -0.12245146929467879, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137712.8075056} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2997210644378604, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.2008717191898106, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9275874036373644, "gear": 1, "accelerator_pedal_position": 0.2997210644378604, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.179213654692557, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137712.8075056} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.549947023391724, "x": 23.72745281417265, "y": -0.29289319817520365, "z": null, "yaw": 3.1445559376465546, "pitch": null, "roll": null}, "v": 1.9129815991058376, "accelerator_pedal_position": 0.2971770182101405, "brake_pedal_position": 0.0, "acceleration": 0.2751122978729107, "steering_wheel_angle": -3.3729315836613827, "front_wheel_angle": -0.1624240606912227, "heading_rate": -0.12245146929467879, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137712.8275056} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2997210644378604, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.2008717191898106, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.933379264276138, "gear": 1, "accelerator_pedal_position": 0.2997210644378604, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.101517226855793, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137712.8275056} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.549947023391724, "x": 23.72745281417265, "y": -0.29289319817520365, "z": null, "yaw": 3.1445559376465546, "pitch": null, "roll": null}, "v": 1.9129815991058376, "accelerator_pedal_position": 0.2971770182101405, "brake_pedal_position": 0.0, "acceleration": 0.2751122978729107, "steering_wheel_angle": -3.3729315836613827, "front_wheel_angle": -0.1624240606912227, "heading_rate": -0.12245146929467879, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137712.8475056} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2997210644378604, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.2008717191898106, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9391608618155702, "gear": 1, "accelerator_pedal_position": 0.2997210644378604, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.023631502114585, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137712.8475056} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137712.8675056, "x": 27.51542441525765, "y": 4.707134130851234, "z": null, "yaw": 3.1379450433787976, "pitch": null, "roll": null}, "v": 1.9449322010769179, "accelerator_pedal_position": 0.2997210644378604, "brake_pedal_position": 0.0, "acceleration": 0.2881824300149225, "steering_wheel_angle": -2.984617653404814, "front_wheel_angle": -0.1428899256036506, "heading_rate": -0.10930398975717227, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137712.8675056} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.30162254767404856, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.5435167281215925, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9449322010769179, "gear": 1, "accelerator_pedal_position": 0.2997210644378604, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.984617653404814, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137712.8675056} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.65994691848755, "x": 23.51542441525765, "y": -0.2928658691487662, "z": null, "yaw": 3.1379450433787976, "pitch": null, "roll": null}, "v": 1.9449322010769179, "accelerator_pedal_position": 0.2997210644378604, "brake_pedal_position": 0.0, "acceleration": 0.2881824300149225, "steering_wheel_angle": -2.984617653404814, "front_wheel_angle": -0.1428899256036506, "heading_rate": -0.10930398975717227, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137712.8875055} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.30093271011459216, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.5435167281215925, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9509308666290628, "gear": 1, "accelerator_pedal_position": 0.30162254767404856, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.907926655316149, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137712.8875055} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.65994691848755, "x": 23.51542441525765, "y": -0.2928658691487662, "z": null, "yaw": 3.1379450433787976, "pitch": null, "roll": null}, "v": 1.9449322010769179, "accelerator_pedal_position": 0.2997210644378604, "brake_pedal_position": 0.0, "acceleration": 0.2881824300149225, "steering_wheel_angle": -2.984617653404814, "front_wheel_angle": -0.1428899256036506, "heading_rate": -0.10930398975717227, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137712.9075055} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.30093271011459216, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.5435167281215925, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9597796280220923, "gear": 1, "accelerator_pedal_position": 0.30093271011459216, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.792548511761479, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137712.9075055} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.65994691848755, "x": 23.51542441525765, "y": -0.2928658691487662, "z": null, "yaw": 3.1379450433787976, "pitch": null, "roll": null}, "v": 1.9449322010769179, "accelerator_pedal_position": 0.2997210644378604, "brake_pedal_position": 0.0, "acceleration": 0.2881824300149225, "steering_wheel_angle": -2.984617653404814, "front_wheel_angle": -0.1428899256036506, "heading_rate": -0.10930398975717227, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137712.9175055} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.30093271011459216, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.5435167281215925, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9656656628399667, "gear": 1, "accelerator_pedal_position": 0.30093271011459216, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.7154019851105833, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137712.9175055} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.65994691848755, "x": 23.51542441525765, "y": -0.2928658691487662, "z": null, "yaw": 3.1379450433787976, "pitch": null, "roll": null}, "v": 1.9449322010769179, "accelerator_pedal_position": 0.2997210644378604, "brake_pedal_position": 0.0, "acceleration": 0.2881824300149225, "steering_wheel_angle": -2.984617653404814, "front_wheel_angle": -0.1428899256036506, "heading_rate": -0.10930398975717227, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137712.9375055} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.30093271011459216, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.5435167281215925, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9656656628399667, "gear": 1, "accelerator_pedal_position": 0.30093271011459216, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.7154019851105833, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137712.9375055} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.65994691848755, "x": 23.51542441525765, "y": -0.2928658691487662, "z": null, "yaw": 3.1379450433787976, "pitch": null, "roll": null}, "v": 1.9449322010769179, "accelerator_pedal_position": 0.2997210644378604, "brake_pedal_position": 0.0, "acceleration": 0.2881824300149225, "steering_wheel_angle": -2.984617653404814, "front_wheel_angle": -0.1428899256036506, "heading_rate": -0.10930398975717227, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137712.9575055} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.30093271011459216, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.5435167281215925, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9715411917906136, "gear": 1, "accelerator_pedal_position": 0.30093271011459216, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.6380732470347965, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137712.9575055} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137712.9775054, "x": 27.299856044354804, "y": 4.708503256424009, "z": null, "yaw": 3.132182271110561, "pitch": null, "roll": null}, "v": 1.9774062198231808, "accelerator_pedal_position": 0.30093271011459216, "brake_pedal_position": 0.0, "acceleration": 0.2928577736430879, "steering_wheel_angle": -2.560562297534116, "front_wheel_angle": -0.12182501906804387, "heading_rate": -0.09456891216553324, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137712.9875054} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3036823870311761, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3263374582211838, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9803347975596117, "gear": 1, "accelerator_pedal_position": 0.30093271011459216, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.521738493499442, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137712.9875054} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.769946813583374, "x": 23.299856044354804, "y": -0.2914967435759914, "z": null, "yaw": 3.132182271110561, "pitch": null, "roll": null}, "v": 1.9774062198231808, "accelerator_pedal_position": 0.30093271011459216, "brake_pedal_position": 0.0, "acceleration": 0.2928577736430879, "steering_wheel_angle": -2.560562297534116, "front_wheel_angle": -0.12182501906804387, "heading_rate": -0.09456891216553324, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137713.0075054} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.30259377400148124, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3263374582211838, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9926413375131582, "gear": 1, "accelerator_pedal_position": 0.30259377400148124, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.366944166657356, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137713.0075054} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.769946813583374, "x": 23.299856044354804, "y": -0.2914967435759914, "z": null, "yaw": 3.132182271110561, "pitch": null, "roll": null}, "v": 1.9774062198231808, "accelerator_pedal_position": 0.30093271011459216, "brake_pedal_position": 0.0, "acceleration": 0.2928577736430879, "steering_wheel_angle": -2.560562297534116, "front_wheel_angle": -0.12182501906804387, "heading_rate": -0.09456891216553324, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137713.0275054} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.30259377400148124, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3263374582211838, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9926413375131582, "gear": 1, "accelerator_pedal_position": 0.30259377400148124, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.366944166657356, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137713.0275054} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.769946813583374, "x": 23.299856044354804, "y": -0.2914967435759914, "z": null, "yaw": 3.132182271110561, "pitch": null, "roll": null}, "v": 1.9774062198231808, "accelerator_pedal_position": 0.30093271011459216, "brake_pedal_position": 0.0, "acceleration": 0.2928577736430879, "steering_wheel_angle": -2.560562297534116, "front_wheel_angle": -0.12182501906804387, "heading_rate": -0.09456891216553324, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137713.0575054} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.30259377400148124, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3263374582211838, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0016893829290794, "gear": 1, "accelerator_pedal_position": 0.30259377400148124, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.2503759592048507, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137713.0575054} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137713.0875053, "x": 27.080687291643024, "y": 4.71106658213521, "z": null, "yaw": 3.1273363995328216, "pitch": null, "roll": null}, "v": 2.010713019631892, "accelerator_pedal_position": 0.30259377400148124, "brake_pedal_position": 0.0, "acceleration": 0.30024576805449094, "steering_wheel_angle": -2.1334027840486796, "front_wheel_angle": -0.10087743350100478, "heading_rate": -0.07950250654690896, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137713.0875053} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.30354901557589153, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1345314009338971, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.010713019631892, "gear": 1, "accelerator_pedal_position": 0.30259377400148124, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.1334027840486796, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137713.0875053} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.8799467086792, "x": 23.080687291643024, "y": -0.28893341786479, "z": null, "yaw": 3.1273363995328216, "pitch": null, "roll": null}, "v": 2.010713019631892, "accelerator_pedal_position": 0.30259377400148124, "brake_pedal_position": 0.0, "acceleration": 0.30024576805449094, "steering_wheel_angle": -2.1334027840486796, "front_wheel_angle": -0.10087743350100478, "heading_rate": -0.07950250654690896, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137713.1075053} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.30332222651338825, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1345314009338971, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.01987703644457, "gear": 1, "accelerator_pedal_position": 0.30332222651338825, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.016653792960984, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137713.1075053} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.8799467086792, "x": 23.080687291643024, "y": -0.28893341786479, "z": null, "yaw": 3.1273363995328216, "pitch": null, "roll": null}, "v": 2.010713019631892, "accelerator_pedal_position": 0.30259377400148124, "brake_pedal_position": 0.0, "acceleration": 0.30024576805449094, "steering_wheel_angle": -2.1334027840486796, "front_wheel_angle": -0.10087743350100478, "heading_rate": -0.07950250654690896, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137713.1275053} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.30332222651338825, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1345314009338971, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.022916746759199, "gear": 1, "accelerator_pedal_position": 0.30332222651338825, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.9776484302768764, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137713.1275053} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.8799467086792, "x": 23.080687291643024, "y": -0.28893341786479, "z": null, "yaw": 3.1273363995328216, "pitch": null, "roll": null}, "v": 2.010713019631892, "accelerator_pedal_position": 0.30259377400148124, "brake_pedal_position": 0.0, "acceleration": 0.30024576805449094, "steering_wheel_angle": -2.1334027840486796, "front_wheel_angle": -0.10087743350100478, "heading_rate": -0.07950250654690896, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137713.1475053} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.30332222651338825, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1345314009338971, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0289879217865696, "gear": 1, "accelerator_pedal_position": 0.30332222651338825, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.9385985514319983, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137713.1475053} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.8799467086792, "x": 23.080687291643024, "y": -0.28893341786479, "z": null, "yaw": 3.1273363995328216, "pitch": null, "roll": null}, "v": 2.010713019631892, "accelerator_pedal_position": 0.30259377400148124, "brake_pedal_position": 0.0, "acceleration": 0.30024576805449094, "steering_wheel_angle": -2.1334027840486796, "front_wheel_angle": -0.10087743350100478, "heading_rate": -0.07950250654690896, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137713.1675053} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.30332222651338825, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1345314009338971, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0380740799918846, "gear": 1, "accelerator_pedal_position": 0.30332222651338825, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.9385985514319983, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137713.1675053} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.8799467086792, "x": 23.080687291643024, "y": -0.28893341786479, "z": null, "yaw": 3.1273363995328216, "pitch": null, "roll": null}, "v": 2.010713019631892, "accelerator_pedal_position": 0.30259377400148124, "brake_pedal_position": 0.0, "acceleration": 0.30024576805449094, "steering_wheel_angle": -2.1334027840486796, "front_wheel_angle": -0.10087743350100478, "heading_rate": -0.07950250654690896, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137713.1875052} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.30332222651338825, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1345314009338971, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.041097307513422, "gear": 1, "accelerator_pedal_position": 0.30332222651338825, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.9385985514319983, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137713.1875052} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137713.1975052, "x": 26.857863498601844, "y": 4.714663345102015, "z": null, "yaw": 3.123285632716884, "pitch": null, "roll": null}, "v": 2.0441177901948784, "accelerator_pedal_position": 0.30332222651338825, "brake_pedal_position": 0.0, "acceleration": 0.30177385079702057, "steering_wheel_angle": -1.9385985514319983, "front_wheel_angle": -0.09141205685011901, "heading_rate": -0.07319501034640942, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137713.2075052} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3027897739613036, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9674189231679969, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0471355287028485, "gear": 1, "accelerator_pedal_position": 0.30332222651338825, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.9385985514319983, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137713.2075052} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.989946603775024, "x": 22.857863498601844, "y": -0.28533665489798477, "z": null, "yaw": 3.123285632716884, "pitch": null, "roll": null}, "v": 2.0441177901948784, "accelerator_pedal_position": 0.30332222651338825, "brake_pedal_position": 0.0, "acceleration": 0.30177385079702057, "steering_wheel_angle": -1.9385985514319983, "front_wheel_angle": -0.09141205685011901, "heading_rate": -0.07319501034640942, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137713.2275052} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.30327377983412707, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9674189231679969, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.053096249601662, "gear": 1, "accelerator_pedal_position": 0.3027897739613036, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.8607268832521096, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137713.2275052} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.989946603775024, "x": 22.857863498601844, "y": -0.28533665489798477, "z": null, "yaw": 3.123285632716884, "pitch": null, "roll": null}, "v": 2.0441177901948784, "accelerator_pedal_position": 0.30332222651338825, "brake_pedal_position": 0.0, "acceleration": 0.30177385079702057, "steering_wheel_angle": -1.9385985514319983, "front_wheel_angle": -0.09141205685011901, "heading_rate": -0.07319501034640942, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137713.2475052} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.30327377983412707, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9674189231679969, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.059106596269718, "gear": 1, "accelerator_pedal_position": 0.30327377983412707, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.7826787909984099, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137713.2475052} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.989946603775024, "x": 22.857863498601844, "y": -0.28533665489798477, "z": null, "yaw": 3.123285632716884, "pitch": null, "roll": null}, "v": 2.0441177901948784, "accelerator_pedal_position": 0.30332222651338825, "brake_pedal_position": 0.0, "acceleration": 0.30177385079702057, "steering_wheel_angle": -1.9385985514319983, "front_wheel_angle": -0.09141205685011901, "heading_rate": -0.07319501034640942, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137713.2775052} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.30327377983412707, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9674189231679969, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0681015827900957, "gear": 1, "accelerator_pedal_position": 0.30327377983412707, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.7826787909984099, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137713.2775052} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.989946603775024, "x": 22.857863498601844, "y": -0.28533665489798477, "z": null, "yaw": 3.123285632716884, "pitch": null, "roll": null}, "v": 2.0441177901948784, "accelerator_pedal_position": 0.30332222651338825, "brake_pedal_position": 0.0, "acceleration": 0.30177385079702057, "steering_wheel_angle": -1.9385985514319983, "front_wheel_angle": -0.09141205685011901, "heading_rate": -0.07319501034640942, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137713.2775052} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137713.3075051, "x": 26.63140738017354, "y": 4.719200972102838, "z": null, "yaw": 3.1195693323078832, "pitch": null, "roll": null}, "v": 2.0770719459092017, "accelerator_pedal_position": 0.30327377983412707, "brake_pedal_position": 0.0, "acceleration": 0.29846524798300356, "steering_wheel_angle": -1.7826787909984099, "front_wheel_angle": -0.08387471932482018, "heading_rate": -0.06821230818626471, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137713.3075051} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.30408108097044095, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7153179180151065, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0801070547100515, "gear": 1, "accelerator_pedal_position": 0.30408108097044095, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.7438575938400913, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137713.3075051} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.09994649887085, "x": 22.63140738017354, "y": -0.28079902789716193, "z": null, "yaw": 3.1195693323078832, "pitch": null, "roll": null}, "v": 2.0770719459092017, "accelerator_pedal_position": 0.30327377983412707, "brake_pedal_position": 0.0, "acceleration": 0.29846524798300356, "steering_wheel_angle": -1.7826787909984099, "front_wheel_angle": -0.08387471932482018, "heading_rate": -0.06821230818626471, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137713.327505} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3039256659569318, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7153179180151065, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0831393842074437, "gear": 1, "accelerator_pedal_position": 0.30408108097044095, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.7049928952878304, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137713.327505} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.09994649887085, "x": 22.63140738017354, "y": -0.28079902789716193, "z": null, "yaw": 3.1195693323078832, "pitch": null, "roll": null}, "v": 2.0770719459092017, "accelerator_pedal_position": 0.30327377983412707, "brake_pedal_position": 0.0, "acceleration": 0.29846524798300356, "steering_wheel_angle": -1.7826787909984099, "front_wheel_angle": -0.08387471932482018, "heading_rate": -0.06821230818626471, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137713.347505} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3039256659569318, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7153179180151065, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0891762901499034, "gear": 1, "accelerator_pedal_position": 0.3039256659569318, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.6271329940014816, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137713.347505} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.09994649887085, "x": 22.63140738017354, "y": -0.28079902789716193, "z": null, "yaw": 3.1195693323078832, "pitch": null, "roll": null}, "v": 2.0770719459092017, "accelerator_pedal_position": 0.30327377983412707, "brake_pedal_position": 0.0, "acceleration": 0.29846524798300356, "steering_wheel_angle": -1.7826787909984099, "front_wheel_angle": -0.08387471932482018, "heading_rate": -0.06821230818626471, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137713.367505} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3039256659569318, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7153179180151065, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.095202123050484, "gear": 1, "accelerator_pedal_position": 0.3039256659569318, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.5490990871393644, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137713.367505} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.09994649887085, "x": 22.63140738017354, "y": -0.28079902789716193, "z": null, "yaw": 3.1195693323078832, "pitch": null, "roll": null}, "v": 2.0770719459092017, "accelerator_pedal_position": 0.30327377983412707, "brake_pedal_position": 0.0, "acceleration": 0.29846524798300356, "steering_wheel_angle": -1.7826787909984099, "front_wheel_angle": -0.08387471932482018, "heading_rate": -0.06821230818626471, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137713.387505} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3039256659569318, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7153179180151065, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1012168887020355, "gear": 1, "accelerator_pedal_position": 0.3039256659569318, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.5490990871393644, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137713.387505} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.09994649887085, "x": 22.63140738017354, "y": -0.28079902789716193, "z": null, "yaw": 3.1195693323078832, "pitch": null, "roll": null}, "v": 2.0770719459092017, "accelerator_pedal_position": 0.30327377983412707, "brake_pedal_position": 0.0, "acceleration": 0.29846524798300356, "steering_wheel_angle": -1.7826787909984099, "front_wheel_angle": -0.08387471932482018, "heading_rate": -0.06821230818626471, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137713.407505} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3039256659569318, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7153179180151065, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1072205929667325, "gear": 1, "accelerator_pedal_position": 0.3039256659569318, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.5490990871393644, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137713.407505} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137713.417505, "x": 26.401332233140238, "y": 4.72462392365247, "z": null, "yaw": 3.116287882098609, "pitch": null, "roll": null}, "v": 2.110218298929815, "accelerator_pedal_position": 0.3039256659569318, "brake_pedal_position": 0.0, "acceleration": 0.29949428459295063, "steering_wheel_angle": -1.5490990871393644, "front_wheel_angle": -0.07264647428191703, "heading_rate": -0.05998834786279657, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137713.427505} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.30234170655889103, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5726228357087781, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1132132417757443, "gear": 1, "accelerator_pedal_position": 0.3039256659569318, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.5490990871393644, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137713.427505} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.209946393966675, "x": 22.401332233140238, "y": -0.2753760763475297, "z": null, "yaw": 3.116287882098609, "pitch": null, "roll": null}, "v": 2.110218298929815, "accelerator_pedal_position": 0.3039256659569318, "brake_pedal_position": 0.0, "acceleration": 0.29949428459295063, "steering_wheel_angle": -1.5490990871393644, "front_wheel_angle": -0.07264647428191703, "heading_rate": -0.05998834786279657, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137713.447505} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.30332799260551446, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5726228357087781, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1189969376016933, "gear": 1, "accelerator_pedal_position": 0.30234170655889103, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.4711931737681787, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137713.447505} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.209946393966675, "x": 22.401332233140238, "y": -0.2753760763475297, "z": null, "yaw": 3.116287882098609, "pitch": null, "roll": null}, "v": 2.110218298929815, "accelerator_pedal_position": 0.3039256659569318, "brake_pedal_position": 0.0, "acceleration": 0.29949428459295063, "steering_wheel_angle": -1.5490990871393644, "front_wheel_angle": -0.07264647428191703, "heading_rate": -0.05998834786279657, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137713.467505} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.30332799260551446, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5726228357087781, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.124893184531914, "gear": 1, "accelerator_pedal_position": 0.30332799260551446, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.39311459458636, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137713.467505} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.209946393966675, "x": 22.401332233140238, "y": -0.2753760763475297, "z": null, "yaw": 3.116287882098609, "pitch": null, "roll": null}, "v": 2.110218298929815, "accelerator_pedal_position": 0.3039256659569318, "brake_pedal_position": 0.0, "acceleration": 0.29949428459295063, "steering_wheel_angle": -1.5490990871393644, "front_wheel_angle": -0.07264647428191703, "heading_rate": -0.05998834786279657, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137713.487505} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.30332799260551446, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5726228357087781, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1307785321769432, "gear": 1, "accelerator_pedal_position": 0.30332799260551446, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.39311459458636, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137713.487505} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.209946393966675, "x": 22.401332233140238, "y": -0.2753760763475297, "z": null, "yaw": 3.116287882098609, "pitch": null, "roll": null}, "v": 2.110218298929815, "accelerator_pedal_position": 0.3039256659569318, "brake_pedal_position": 0.0, "acceleration": 0.29949428459295063, "steering_wheel_angle": -1.5490990871393644, "front_wheel_angle": -0.07264647428191703, "heading_rate": -0.05998834786279657, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137713.507505} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.30332799260551446, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5726228357087781, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.136652986835728, "gear": 1, "accelerator_pedal_position": 0.30332799260551446, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.39311459458636, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137713.507505} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137713.527505, "x": 26.16767593086037, "y": 4.730855442788464, "z": null, "yaw": 3.1133803581011787, "pitch": null, "roll": null}, "v": 2.142516554872426, "accelerator_pedal_position": 0.30332799260551446, "brake_pedal_position": 0.0, "acceleration": 0.2927703541618198, "steering_wheel_angle": -1.39311459458636, "front_wheel_angle": -0.06518985076057966, "heading_rate": -0.0546361423775504, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137713.527505} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3036849369188853, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.35955971316951185, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.142516554872426, "gear": 1, "accelerator_pedal_position": 0.30332799260551446, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.39311459458636, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137713.527505} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.3199462890625, "x": 22.16767593086037, "y": -0.2691445572115363, "z": null, "yaw": 3.1133803581011787, "pitch": null, "roll": null}, "v": 2.142516554872426, "accelerator_pedal_position": 0.30332799260551446, "brake_pedal_position": 0.0, "acceleration": 0.2927703541618198, "steering_wheel_angle": -1.39311459458636, "front_wheel_angle": -0.06518985076057966, "heading_rate": -0.0546361423775504, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137713.547505} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.303742656568763, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.35955971316951185, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.148413840028146, "gear": 1, "accelerator_pedal_position": 0.3036849369188853, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.3153098040355395, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137713.547505} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.3199462890625, "x": 22.16767593086037, "y": -0.2691445572115363, "z": null, "yaw": 3.1133803581011787, "pitch": null, "roll": null}, "v": 2.142516554872426, "accelerator_pedal_position": 0.30332799260551446, "brake_pedal_position": 0.0, "acceleration": 0.2927703541618198, "steering_wheel_angle": -1.39311459458636, "front_wheel_angle": -0.06518985076057966, "heading_rate": -0.0546361423775504, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137713.567505} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.303742656568763, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.35955971316951185, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1543073801486505, "gear": 1, "accelerator_pedal_position": 0.303742656568763, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.2373343101609722, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137713.567505} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.3199462890625, "x": 22.16767593086037, "y": -0.2691445572115363, "z": null, "yaw": 3.1133803581011787, "pitch": null, "roll": null}, "v": 2.142516554872426, "accelerator_pedal_position": 0.30332799260551446, "brake_pedal_position": 0.0, "acceleration": 0.2927703541618198, "steering_wheel_angle": -1.39311459458636, "front_wheel_angle": -0.06518985076057966, "heading_rate": -0.0546361423775504, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137713.5875049} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.303742656568763, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.35955971316951185, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.160189956708777, "gear": 1, "accelerator_pedal_position": 0.303742656568763, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.198282549477284, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137713.5875049} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.3199462890625, "x": 22.16767593086037, "y": -0.2691445572115363, "z": null, "yaw": 3.1133803581011787, "pitch": null, "roll": null}, "v": 2.142516554872426, "accelerator_pedal_position": 0.30332799260551446, "brake_pedal_position": 0.0, "acceleration": 0.2927703541618198, "steering_wheel_angle": -1.39311459458636, "front_wheel_angle": -0.06518985076057966, "heading_rate": -0.0546361423775504, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137713.6075048} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.303742656568763, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.35955971316951185, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1660615762682407, "gear": 1, "accelerator_pedal_position": 0.303742656568763, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.198282549477284, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137713.6075048} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.3199462890625, "x": 22.16767593086037, "y": -0.2691445572115363, "z": null, "yaw": 3.1133803581011787, "pitch": null, "roll": null}, "v": 2.142516554872426, "accelerator_pedal_position": 0.30332799260551446, "brake_pedal_position": 0.0, "acceleration": 0.2927703541618198, "steering_wheel_angle": -1.39311459458636, "front_wheel_angle": -0.06518985076057966, "heading_rate": -0.0546361423775504, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137713.6275048} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.303742656568763, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.35955971316951185, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.171922245451824, "gear": 1, "accelerator_pedal_position": 0.303742656568763, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.198282549477284, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137713.6275048} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137713.6375048, "x": 25.930482396842052, "y": 4.737829671291199, "z": null, "yaw": 3.110865954351812, "pitch": null, "roll": null}, "v": 2.174848475740617, "accelerator_pedal_position": 0.303742656568763, "brake_pedal_position": 0.0, "acceleration": 0.2923495208434248, "steering_wheel_angle": -1.198282549477284, "front_wheel_angle": -0.055922191835843155, "heading_rate": -0.04755829502342899, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137713.6475048} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3059967253525336, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.12544911658853267, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1777719709490513, "gear": 1, "accelerator_pedal_position": 0.303742656568763, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.198282549477284, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137713.6475048} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.429946184158325, "x": 21.930482396842052, "y": -0.26217032870880086, "z": null, "yaw": 3.110865954351812, "pitch": null, "roll": null}, "v": 2.174848475740617, "accelerator_pedal_position": 0.303742656568763, "brake_pedal_position": 0.0, "acceleration": 0.2923495208434248, "steering_wheel_angle": -1.198282549477284, "front_wheel_angle": -0.055922191835843155, "heading_rate": -0.04755829502342899, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137713.6675048} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3051528813645305, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.12544911658853267, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.183892386227303, "gear": 1, "accelerator_pedal_position": 0.3059967253525336, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.120535497590674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137713.6675048} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.429946184158325, "x": 21.930482396842052, "y": -0.26217032870880086, "z": null, "yaw": 3.110865954351812, "pitch": null, "roll": null}, "v": 2.174848475740617, "accelerator_pedal_position": 0.303742656568763, "brake_pedal_position": 0.0, "acceleration": 0.2923495208434248, "steering_wheel_angle": -1.198282549477284, "front_wheel_angle": -0.055922191835843155, "heading_rate": -0.04755829502342899, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137713.6875048} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3051528813645305, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.12544911658853267, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1898959126135176, "gear": 1, "accelerator_pedal_position": 0.3051528813645305, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.0426198479277766, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137713.6875048} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.429946184158325, "x": 21.930482396842052, "y": -0.26217032870880086, "z": null, "yaw": 3.110865954351812, "pitch": null, "roll": null}, "v": 2.174848475740617, "accelerator_pedal_position": 0.303742656568763, "brake_pedal_position": 0.0, "acceleration": 0.2923495208434248, "steering_wheel_angle": -1.198282549477284, "front_wheel_angle": -0.055922191835843155, "heading_rate": -0.04755829502342899, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137713.7075047} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3051528813645305, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.12544911658853267, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1958881855186596, "gear": 1, "accelerator_pedal_position": 0.3051528813645305, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.9645356004885923, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137713.7075047} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.429946184158325, "x": 21.930482396842052, "y": -0.26217032870880086, "z": null, "yaw": 3.110865954351812, "pitch": null, "roll": null}, "v": 2.174848475740617, "accelerator_pedal_position": 0.303742656568763, "brake_pedal_position": 0.0, "acceleration": 0.2923495208434248, "steering_wheel_angle": -1.198282549477284, "front_wheel_angle": -0.055922191835843155, "heading_rate": -0.04755829502342899, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137713.7275047} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3051528813645305, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.12544911658853267, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2018692116809424, "gear": 1, "accelerator_pedal_position": 0.3051528813645305, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.9645356004885923, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137713.7275047} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137713.7475047, "x": 25.689718576460105, "y": 4.745475684750189, "z": null, "yaw": 3.1087419070513707, "pitch": null, "roll": null}, "v": 2.20783899790674, "accelerator_pedal_position": 0.3051528813645305, "brake_pedal_position": 0.0, "acceleration": 0.2980680282262002, "steering_wheel_angle": -0.9645356004885923, "front_wheel_angle": -0.044869801340843486, "heading_rate": -0.03872337246189904, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137713.7475047} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.30191533800505393, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.017275695147314595, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.20783899790674, "gear": 1, "accelerator_pedal_position": 0.3051528813645305, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.9645356004885923, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137713.7475047} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.53994607925415, "x": 21.689718576460105, "y": -0.2545243152498111, "z": null, "yaw": 3.1087419070513707, "pitch": null, "roll": null}, "v": 2.20783899790674, "accelerator_pedal_position": 0.3051528813645305, "brake_pedal_position": 0.0, "acceleration": 0.2980680282262002, "steering_wheel_angle": -0.9645356004885923, "front_wheel_angle": -0.044869801340843486, "heading_rate": -0.03872337246189904, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137713.7675047} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.30369286602348305, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.017275695147314595, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.213393048789752, "gear": 1, "accelerator_pedal_position": 0.30191533800505393, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.8864786178762404, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137713.7675047} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.53994607925415, "x": 21.689718576460105, "y": -0.2545243152498111, "z": null, "yaw": 3.1087419070513707, "pitch": null, "roll": null}, "v": 2.20783899790674, "accelerator_pedal_position": 0.3051528813645305, "brake_pedal_position": 0.0, "acceleration": 0.2980680282262002, "steering_wheel_angle": -0.9645356004885923, "front_wheel_angle": -0.044869801340843486, "heading_rate": -0.03872337246189904, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137713.7875047} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.30369286602348305, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.017275695147314595, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.219158722533795, "gear": 1, "accelerator_pedal_position": 0.30369286602348305, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.8473872181622732, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137713.7875047} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.53994607925415, "x": 21.689718576460105, "y": -0.2545243152498111, "z": null, "yaw": 3.1087419070513707, "pitch": null, "roll": null}, "v": 2.20783899790674, "accelerator_pedal_position": 0.3051528813645305, "brake_pedal_position": 0.0, "acceleration": 0.2980680282262002, "steering_wheel_angle": -0.9645356004885923, "front_wheel_angle": -0.044869801340843486, "heading_rate": -0.03872337246189904, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137713.8075047} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.30369286602348305, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.017275695147314595, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.224913521084918, "gear": 1, "accelerator_pedal_position": 0.30369286602348305, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.8473872181622732, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137713.8075047} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.53994607925415, "x": 21.689718576460105, "y": -0.2545243152498111, "z": null, "yaw": 3.1087419070513707, "pitch": null, "roll": null}, "v": 2.20783899790674, "accelerator_pedal_position": 0.3051528813645305, "brake_pedal_position": 0.0, "acceleration": 0.2980680282262002, "steering_wheel_angle": -0.9645356004885923, "front_wheel_angle": -0.044869801340843486, "heading_rate": -0.03872337246189904, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137713.8275046} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.30369286602348305, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.017275695147314595, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2306574517150404, "gear": 1, "accelerator_pedal_position": 0.30369286602348305, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.8473872181622732, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137713.8275046} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.53994607925415, "x": 21.689718576460105, "y": -0.2545243152498111, "z": null, "yaw": 3.1087419070513707, "pitch": null, "roll": null}, "v": 2.20783899790674, "accelerator_pedal_position": 0.3051528813645305, "brake_pedal_position": 0.0, "acceleration": 0.2980680282262002, "steering_wheel_angle": -0.9645356004885923, "front_wheel_angle": -0.044869801340843486, "heading_rate": -0.03872337246189904, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137713.8475046} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.30369286602348305, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.017275695147314595, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.236390521757343, "gear": 1, "accelerator_pedal_position": 0.30369286602348305, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.8473872181622732, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137713.8475046} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137713.8575046, "x": 25.445431082468694, "y": 4.753701133669297, "z": null, "yaw": 3.1070067542365987, "pitch": null, "roll": null}, "v": 2.2392529863663517, "accelerator_pedal_position": 0.30369286602348305, "brake_pedal_position": 0.0, "acceleration": 0.28597522395894515, "steering_wheel_angle": -0.8473872181622732, "front_wheel_angle": -0.039357423011372634, "heading_rate": -0.03444404707624365, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137713.8675046} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2887633443841659, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.1173964712982087, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.242112738605941, "gear": 1, "accelerator_pedal_position": 0.30369286602348305, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.8473872181622732, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137713.8675046} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.649945974349976, "x": 21.445431082468694, "y": -0.24629886633070264, "z": null, "yaw": 3.1070067542365987, "pitch": null, "roll": null}, "v": 2.2392529863663517, "accelerator_pedal_position": 0.30369286602348305, "brake_pedal_position": 0.0, "acceleration": 0.28597522395894515, "steering_wheel_angle": -0.8473872181622732, "front_wheel_angle": -0.039357423011372634, "heading_rate": -0.03444404707624365, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137713.8875046} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29609875518234813, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.1173964712982087, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2459588049251913, "gear": 1, "accelerator_pedal_position": 0.2887633443841659, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7688158838919352, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137713.8875046} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.649945974349976, "x": 21.445431082468694, "y": -0.24629886633070264, "z": null, "yaw": 3.1070067542365987, "pitch": null, "roll": null}, "v": 2.2392529863663517, "accelerator_pedal_position": 0.30369286602348305, "brake_pedal_position": 0.0, "acceleration": 0.28597522395894515, "steering_wheel_angle": -0.8473872181622732, "front_wheel_angle": -0.039357423011372634, "heading_rate": -0.03444404707624365, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137713.9075046} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29609875518234813, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.1173964712982087, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.250714065862416, "gear": 1, "accelerator_pedal_position": 0.29609875518234813, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7294668859920291, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137713.9075046} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.649945974349976, "x": 21.445431082468694, "y": -0.24629886633070264, "z": null, "yaw": 3.1070067542365987, "pitch": null, "roll": null}, "v": 2.2392529863663517, "accelerator_pedal_position": 0.30369286602348305, "brake_pedal_position": 0.0, "acceleration": 0.28597522395894515, "steering_wheel_angle": -0.8473872181622732, "front_wheel_angle": -0.039357423011372634, "heading_rate": -0.03444404707624365, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137713.9275045} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29609875518234813, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.1173964712982087, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2554602969987196, "gear": 1, "accelerator_pedal_position": 0.29609875518234813, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7294668859920291, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137713.9275045} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.649945974349976, "x": 21.445431082468694, "y": -0.24629886633070264, "z": null, "yaw": 3.1070067542365987, "pitch": null, "roll": null}, "v": 2.2392529863663517, "accelerator_pedal_position": 0.30369286602348305, "brake_pedal_position": 0.0, "acceleration": 0.28597522395894515, "steering_wheel_angle": -0.8473872181622732, "front_wheel_angle": -0.039357423011372634, "heading_rate": -0.03444404707624365, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137713.9475045} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29609875518234813, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.1173964712982087, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2601975064744577, "gear": 1, "accelerator_pedal_position": 0.29609875518234813, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7294668859920291, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137713.9475045} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137713.9675045, "x": 25.197989841756993, "y": 4.762439607926418, "z": null, "yaw": 3.105487814378033, "pitch": null, "roll": null}, "v": 2.2649257024658556, "accelerator_pedal_position": 0.29609875518234813, "brake_pedal_position": 0.0, "acceleration": 0.23607205038947848, "steering_wheel_angle": -0.7294668859920291, "front_wheel_angle": -0.03382657102595926, "heading_rate": -0.029939025508427787, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137713.9675045} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2799115950196004, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.25651222286087455, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2649257024658556, "gear": 1, "accelerator_pedal_position": 0.29609875518234813, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7294668859920291, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137713.9675045} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.7599458694458, "x": 21.197989841756993, "y": -0.23756039207358182, "z": null, "yaw": 3.105487814378033, "pitch": null, "roll": null}, "v": 2.2649257024658556, "accelerator_pedal_position": 0.29609875518234813, "brake_pedal_position": 0.0, "acceleration": 0.23607205038947848, "steering_wheel_angle": -0.7294668859920291, "front_wheel_angle": -0.03382657102595926, "heading_rate": -0.029939025508427787, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137713.9875045} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2878056737690983, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.25651222286087455, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.267622462672448, "gear": 1, "accelerator_pedal_position": 0.2799115950196004, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6503509503044005, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137713.9875045} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.7599458694458, "x": 21.197989841756993, "y": -0.23756039207358182, "z": null, "yaw": 3.105487814378033, "pitch": null, "roll": null}, "v": 2.2649257024658556, "accelerator_pedal_position": 0.29609875518234813, "brake_pedal_position": 0.0, "acceleration": 0.23607205038947848, "steering_wheel_angle": -0.7294668859920291, "front_wheel_angle": -0.03382657102595926, "heading_rate": -0.029939025508427787, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137714.0075045} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2878056737690983, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.25651222286087455, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2713003724406913, "gear": 1, "accelerator_pedal_position": 0.2878056737690983, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5710648834875667, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137714.0075045} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.7599458694458, "x": 21.197989841756993, "y": -0.23756039207358182, "z": null, "yaw": 3.105487814378033, "pitch": null, "roll": null}, "v": 2.2649257024658556, "accelerator_pedal_position": 0.29609875518234813, "brake_pedal_position": 0.0, "acceleration": 0.23607205038947848, "steering_wheel_angle": -0.7294668859920291, "front_wheel_angle": -0.03382657102595926, "heading_rate": -0.029939025508427787, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137714.0275044} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2878056737690983, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.25651222286087455, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.274971267545241, "gear": 1, "accelerator_pedal_position": 0.2878056737690983, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5710648834875667, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137714.0275044} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.7599458694458, "x": 21.197989841756993, "y": -0.23756039207358182, "z": null, "yaw": 3.105487814378033, "pitch": null, "roll": null}, "v": 2.2649257024658556, "accelerator_pedal_position": 0.29609875518234813, "brake_pedal_position": 0.0, "acceleration": 0.23607205038947848, "steering_wheel_angle": -0.7294668859920291, "front_wheel_angle": -0.03382657102595926, "heading_rate": -0.029939025508427787, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137714.0475044} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2878056737690983, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.25651222286087455, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2786351559771414, "gear": 1, "accelerator_pedal_position": 0.2878056737690983, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5710648834875667, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137714.0475044} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.7599458694458, "x": 21.197989841756993, "y": -0.23756039207358182, "z": null, "yaw": 3.105487814378033, "pitch": null, "roll": null}, "v": 2.2649257024658556, "accelerator_pedal_position": 0.29609875518234813, "brake_pedal_position": 0.0, "acceleration": 0.23607205038947848, "steering_wheel_angle": -0.7294668859920291, "front_wheel_angle": -0.03382657102595926, "heading_rate": -0.029939025508427787, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137714.0675044} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2878056737690983, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.25651222286087455, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.282292045743027, "gear": 1, "accelerator_pedal_position": 0.2878056737690983, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5710648834875667, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137714.0675044} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137714.0775044, "x": 24.94809917244826, "y": 4.771609987999102, "z": null, "yaw": 3.10427976187113, "pitch": null, "roll": null}, "v": 2.284117868632518, "accelerator_pedal_position": 0.2878056737690983, "brake_pedal_position": 0.0, "acceleration": 0.18240762324717497, "steering_wheel_angle": -0.5710648834875667, "front_wheel_angle": -0.026424880328539683, "heading_rate": -0.023582653893200186, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137714.0875044} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27078586531437465, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3991683868998795, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.28594194486499, "gear": 1, "accelerator_pedal_position": 0.2878056737690983, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5710648834875667, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137714.0875044} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.869945764541626, "x": 20.94809917244826, "y": -0.22839001200089815, "z": null, "yaw": 3.10427976187113, "pitch": null, "roll": null}, "v": 2.284117868632518, "accelerator_pedal_position": 0.2878056737690983, "brake_pedal_position": 0.0, "acceleration": 0.18240762324717497, "steering_wheel_angle": -0.5710648834875667, "front_wheel_angle": -0.026424880328539683, "heading_rate": -0.023582653893200186, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137714.1075044} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.279030171996691, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3991683868998795, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.287458403795834, "gear": 1, "accelerator_pedal_position": 0.27078586531437465, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.49130531893183876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137714.1075044} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.869945764541626, "x": 20.94809917244826, "y": -0.22839001200089815, "z": null, "yaw": 3.10427976187113, "pitch": null, "roll": null}, "v": 2.284117868632518, "accelerator_pedal_position": 0.2878056737690983, "brake_pedal_position": 0.0, "acceleration": 0.18240762324717497, "steering_wheel_angle": -0.5710648834875667, "front_wheel_angle": -0.026424880328539683, "heading_rate": -0.023582653893200186, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137714.1275043} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.279030171996691, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3991683868998795, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.290002005217958, "gear": 1, "accelerator_pedal_position": 0.279030171996691, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45136124990042925, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137714.1275043} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.869945764541626, "x": 20.94809917244826, "y": -0.22839001200089815, "z": null, "yaw": 3.10427976187113, "pitch": null, "roll": null}, "v": 2.284117868632518, "accelerator_pedal_position": 0.2878056737690983, "brake_pedal_position": 0.0, "acceleration": 0.18240762324717497, "steering_wheel_angle": -0.5710648834875667, "front_wheel_angle": -0.026424880328539683, "heading_rate": -0.023582653893200186, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137714.1475043} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.279030171996691, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3991683868998795, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2925407360788252, "gear": 1, "accelerator_pedal_position": 0.279030171996691, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45136124990042925, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137714.1475043} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.869945764541626, "x": 20.94809917244826, "y": -0.22839001200089815, "z": null, "yaw": 3.10427976187113, "pitch": null, "roll": null}, "v": 2.284117868632518, "accelerator_pedal_position": 0.2878056737690983, "brake_pedal_position": 0.0, "acceleration": 0.18240762324717497, "steering_wheel_angle": -0.5710648834875667, "front_wheel_angle": -0.026424880328539683, "heading_rate": -0.023582653893200186, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137714.1675043} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.279030171996691, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3991683868998795, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2950746031278992, "gear": 1, "accelerator_pedal_position": 0.279030171996691, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45136124990042925, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137714.1675043} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137714.1875043, "x": 24.696359015834748, "y": 4.781123613912837, "z": null, "yaw": 3.1033182912629713, "pitch": null, "roll": null}, "v": 2.297603613116521, "accelerator_pedal_position": 0.279030171996691, "brake_pedal_position": 0.0, "acceleration": 0.12626857069343173, "steering_wheel_angle": -0.45136124990042925, "front_wheel_angle": -0.020852440118658885, "heading_rate": -0.01871780750132042, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137714.1875043} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27174013849100537, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.46946866647736163, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.297603613116521, "gear": 1, "accelerator_pedal_position": 0.279030171996691, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.45136124990042925, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137714.1875043} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.97994565963745, "x": 20.696359015834748, "y": -0.21887638608716298, "z": null, "yaw": 3.1033182912629713, "pitch": null, "roll": null}, "v": 2.297603613116521, "accelerator_pedal_position": 0.279030171996691, "brake_pedal_position": 0.0, "acceleration": 0.12626857069343173, "steering_wheel_angle": -0.45136124990042925, "front_wheel_angle": -0.020852440118658885, "heading_rate": -0.01871780750132042, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137714.2075043} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27531003557998074, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.46946866647736163, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.299216955887581, "gear": 1, "accelerator_pedal_position": 0.27174013849100537, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.37119327180916184, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137714.2075043} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.97994565963745, "x": 20.696359015834748, "y": -0.21887638608716298, "z": null, "yaw": 3.1033182912629713, "pitch": null, "roll": null}, "v": 2.297603613116521, "accelerator_pedal_position": 0.279030171996691, "brake_pedal_position": 0.0, "acceleration": 0.12626857069343173, "steering_wheel_angle": -0.45136124990042925, "front_wheel_angle": -0.020852440118658885, "heading_rate": -0.01871780750132042, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137714.2275043} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27531003557998074, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.46946866647736163, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.301273226228698, "gear": 1, "accelerator_pedal_position": 0.27531003557998074, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.37119327180916184, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137714.2275043} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.97994565963745, "x": 20.696359015834748, "y": -0.21887638608716298, "z": null, "yaw": 3.1033182912629713, "pitch": null, "roll": null}, "v": 2.297603613116521, "accelerator_pedal_position": 0.279030171996691, "brake_pedal_position": 0.0, "acceleration": 0.12626857069343173, "steering_wheel_angle": -0.45136124990042925, "front_wheel_angle": -0.020852440118658885, "heading_rate": -0.01871780750132042, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137714.2475042} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27531003557998074, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.46946866647736163, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.303325549802207, "gear": 1, "accelerator_pedal_position": 0.27531003557998074, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.37119327180916184, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137714.2475042} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.97994565963745, "x": 20.696359015834748, "y": -0.21887638608716298, "z": null, "yaw": 3.1033182912629713, "pitch": null, "roll": null}, "v": 2.297603613116521, "accelerator_pedal_position": 0.279030171996691, "brake_pedal_position": 0.0, "acceleration": 0.12626857069343173, "steering_wheel_angle": -0.45136124990042925, "front_wheel_angle": -0.020852440118658885, "heading_rate": -0.01871780750132042, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137714.2675042} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27531003557998074, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.46946866647736163, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.308439130285694, "gear": 1, "accelerator_pedal_position": 0.27531003557998074, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.37119327180916184, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137714.2675042} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137714.2975042, "x": 24.443288802599675, "y": 4.790904187016335, "z": null, "yaw": 3.1025603285161303, "pitch": null, "roll": null}, "v": 2.308439130285694, "accelerator_pedal_position": 0.27531003557998074, "brake_pedal_position": 0.0, "acceleration": 0.1019768536782531, "steering_wheel_angle": -0.37119327180916184, "front_wheel_angle": -0.017130464611275122, "heading_rate": -0.015448634157910672, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137714.2975042} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26962699888589786, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5331926791737125, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.308439130285694, "gear": 1, "accelerator_pedal_position": 0.27531003557998074, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.37119327180916184, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137714.2975042} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.089945554733276, "x": 20.443288802599675, "y": -0.20909581298366486, "z": null, "yaw": 3.1025603285161303, "pitch": null, "roll": null}, "v": 2.308439130285694, "accelerator_pedal_position": 0.27531003557998074, "brake_pedal_position": 0.0, "acceleration": 0.1019768536782531, "steering_wheel_angle": -0.37119327180916184, "front_wheel_angle": -0.017130464611275122, "heading_rate": -0.015448634157910672, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137714.3175042} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2724125121820507, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5331926791737125, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.310430949558052, "gear": 1, "accelerator_pedal_position": 0.26962699888589786, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3309757492361931, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137714.3175042} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.089945554733276, "x": 20.443288802599675, "y": -0.20909581298366486, "z": null, "yaw": 3.1025603285161303, "pitch": null, "roll": null}, "v": 2.308439130285694, "accelerator_pedal_position": 0.27531003557998074, "brake_pedal_position": 0.0, "acceleration": 0.1019768536782531, "steering_wheel_angle": -0.37119327180916184, "front_wheel_angle": -0.017130464611275122, "heading_rate": -0.015448634157910672, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137714.3375041} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2724125121820507, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5331926791737125, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3121036592939417, "gear": 1, "accelerator_pedal_position": 0.2724125121820507, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3309757492361931, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137714.3375041} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.089945554733276, "x": 20.443288802599675, "y": -0.20909581298366486, "z": null, "yaw": 3.1025603285161303, "pitch": null, "roll": null}, "v": 2.308439130285694, "accelerator_pedal_position": 0.27531003557998074, "brake_pedal_position": 0.0, "acceleration": 0.1019768536782531, "steering_wheel_angle": -0.37119327180916184, "front_wheel_angle": -0.017130464611275122, "heading_rate": -0.015448634157910672, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137714.3575041} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2724125121820507, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5331926791737125, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3137731511577893, "gear": 1, "accelerator_pedal_position": 0.2724125121820507, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3309757492361931, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137714.3575041} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.089945554733276, "x": 20.443288802599675, "y": -0.20909581298366486, "z": null, "yaw": 3.1025603285161303, "pitch": null, "roll": null}, "v": 2.308439130285694, "accelerator_pedal_position": 0.27531003557998074, "brake_pedal_position": 0.0, "acceleration": 0.1019768536782531, "steering_wheel_angle": -0.37119327180916184, "front_wheel_angle": -0.017130464611275122, "heading_rate": -0.015448634157910672, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137714.377504} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2724125121820507, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5331926791737125, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.314606691974087, "gear": 1, "accelerator_pedal_position": 0.2724125121820507, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3309757492361931, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137714.377504} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.089945554733276, "x": 20.443288802599675, "y": -0.20909581298366486, "z": null, "yaw": 3.1025603285161303, "pitch": null, "roll": null}, "v": 2.308439130285694, "accelerator_pedal_position": 0.27531003557998074, "brake_pedal_position": 0.0, "acceleration": 0.1019768536782531, "steering_wheel_angle": -0.37119327180916184, "front_wheel_angle": -0.017130464611275122, "heading_rate": -0.015448634157910672, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137714.397504} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2724125121820507, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5331926791737125, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.316271366546386, "gear": 1, "accelerator_pedal_position": 0.2724125121820507, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3309757492361931, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137714.397504} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137714.407504, "x": 24.18914414664728, "y": 4.8009067230697084, "z": null, "yaw": 3.1018970206953695, "pitch": null, "roll": null}, "v": 2.317102501570143, "accelerator_pedal_position": 0.2724125121820507, "brake_pedal_position": 0.0, "acceleration": 0.08303343603148355, "steering_wheel_angle": -0.3309757492361931, "front_wheel_angle": -0.015266280071064411, "heading_rate": -0.013818860954082824, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137714.417504} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2676986938421892, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5978089069089432, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.318467756614441, "gear": 1, "accelerator_pedal_position": 0.2676986938421892, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2906446490445676, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137714.417504} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.1999454498291, "x": 20.18914414664728, "y": -0.19909327693029155, "z": null, "yaw": 3.1018970206953695, "pitch": null, "roll": null}, "v": 2.317102501570143, "accelerator_pedal_position": 0.2724125121820507, "brake_pedal_position": 0.0, "acceleration": 0.08303343603148355, "steering_wheel_angle": -0.3309757492361931, "front_wheel_angle": -0.015266280071064411, "heading_rate": -0.013818860954082824, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137714.437504} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2700069053597248, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5978089069089432, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3190021618274246, "gear": 1, "accelerator_pedal_position": 0.2676986938421892, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2502702300343383, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137714.437504} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.1999454498291, "x": 20.18914414664728, "y": -0.19909327693029155, "z": null, "yaw": 3.1018970206953695, "pitch": null, "roll": null}, "v": 2.317102501570143, "accelerator_pedal_position": 0.2724125121820507, "brake_pedal_position": 0.0, "acceleration": 0.08303343603148355, "steering_wheel_angle": -0.3309757492361931, "front_wheel_angle": -0.015266280071064411, "heading_rate": -0.013818860954082824, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137714.457504} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2700069053597248, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5978089069089432, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.32035781497972, "gear": 1, "accelerator_pedal_position": 0.2700069053597248, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2502702300343383, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137714.457504} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.1999454498291, "x": 20.18914414664728, "y": -0.19909327693029155, "z": null, "yaw": 3.1018970206953695, "pitch": null, "roll": null}, "v": 2.317102501570143, "accelerator_pedal_position": 0.2724125121820507, "brake_pedal_position": 0.0, "acceleration": 0.08303343603148355, "steering_wheel_angle": -0.3309757492361931, "front_wheel_angle": -0.015266280071064411, "heading_rate": -0.013818860954082824, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137714.477504} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2700069053597248, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5978089069089432, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3217108556823898, "gear": 1, "accelerator_pedal_position": 0.2700069053597248, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2502702300343383, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137714.477504} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.1999454498291, "x": 20.18914414664728, "y": -0.19909327693029155, "z": null, "yaw": 3.1018970206953695, "pitch": null, "roll": null}, "v": 2.317102501570143, "accelerator_pedal_position": 0.2724125121820507, "brake_pedal_position": 0.0, "acceleration": 0.08303343603148355, "steering_wheel_angle": -0.3309757492361931, "front_wheel_angle": -0.015266280071064411, "heading_rate": -0.013818860954082824, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137714.497504} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2700069053597248, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5978089069089432, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.323061288237893, "gear": 1, "accelerator_pedal_position": 0.2700069053597248, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2502702300343383, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137714.497504} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137714.517504, "x": 23.934103102303524, "y": 4.811101422666872, "z": null, "yaw": 3.1013650292359305, "pitch": null, "roll": null}, "v": 2.3244091169446293, "accelerator_pedal_position": 0.2700069053597248, "brake_pedal_position": 0.0, "acceleration": 0.06729392522169547, "steering_wheel_angle": -0.2502702300343383, "front_wheel_angle": -0.011531394138637872, "heading_rate": -0.010470650697548458, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137714.517504} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26215898412925087, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6823222686059174, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3244091169446293, "gear": 1, "accelerator_pedal_position": 0.2700069053597248, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2502702300343383, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137714.517504} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.30994534492493, "x": 19.934103102303524, "y": -0.18889857733312798, "z": null, "yaw": 3.1013650292359305, "pitch": null, "roll": null}, "v": 2.3244091169446293, "accelerator_pedal_position": 0.2700069053597248, "brake_pedal_position": 0.0, "acceleration": 0.06729392522169547, "steering_wheel_angle": -0.2502702300343383, "front_wheel_angle": -0.011531394138637872, "heading_rate": -0.010470650697548458, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137714.537504} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26594976513610885, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6823222686059174, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3247738292548568, "gear": 1, "accelerator_pedal_position": 0.26215898412925087, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.16920553677141575, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137714.537504} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.30994534492493, "x": 19.934103102303524, "y": -0.18889857733312798, "z": null, "yaw": 3.1013650292359305, "pitch": null, "roll": null}, "v": 2.3244091169446293, "accelerator_pedal_position": 0.2700069053597248, "brake_pedal_position": 0.0, "acceleration": 0.06729392522169547, "steering_wheel_angle": -0.2502702300343383, "front_wheel_angle": -0.011531394138637872, "heading_rate": -0.010470650697548458, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137714.557504} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26594976513610885, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6823222686059174, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3260296647746346, "gear": 1, "accelerator_pedal_position": 0.26594976513610885, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.16920553677141575, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137714.557504} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.30994534492493, "x": 19.934103102303524, "y": -0.18889857733312798, "z": null, "yaw": 3.1013650292359305, "pitch": null, "roll": null}, "v": 2.3244091169446293, "accelerator_pedal_position": 0.2700069053597248, "brake_pedal_position": 0.0, "acceleration": 0.06729392522169547, "steering_wheel_angle": -0.2502702300343383, "front_wheel_angle": -0.011531394138637872, "heading_rate": -0.010470650697548458, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137714.577504} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26594976513610885, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6823222686059174, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3264474688631127, "gear": 1, "accelerator_pedal_position": 0.26594976513610885, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.16920553677141575, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137714.577504} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.30994534492493, "x": 19.934103102303524, "y": -0.18889857733312798, "z": null, "yaw": 3.1013650292359305, "pitch": null, "roll": null}, "v": 2.3244091169446293, "accelerator_pedal_position": 0.2700069053597248, "brake_pedal_position": 0.0, "acceleration": 0.06729392522169547, "steering_wheel_angle": -0.2502702300343383, "front_wheel_angle": -0.011531394138637872, "heading_rate": -0.010470650697548458, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137714.597504} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26594976513610885, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6823222686059174, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.327281867541154, "gear": 1, "accelerator_pedal_position": 0.26594976513610885, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.16920553677141575, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137714.597504} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.30994534492493, "x": 19.934103102303524, "y": -0.18889857733312798, "z": null, "yaw": 3.1013650292359305, "pitch": null, "roll": null}, "v": 2.3244091169446293, "accelerator_pedal_position": 0.2700069053597248, "brake_pedal_position": 0.0, "acceleration": 0.06729392522169547, "steering_wheel_angle": -0.2502702300343383, "front_wheel_angle": -0.011531394138637872, "heading_rate": -0.010470650697548458, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137714.617504} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26594976513610885, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6823222686059174, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3281146559154884, "gear": 1, "accelerator_pedal_position": 0.26594976513610885, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.16920553677141575, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137714.617504} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137714.6275039, "x": 23.678441718058277, "y": 4.821435526313023, "z": null, "yaw": 3.1010084484476907, "pitch": null, "roll": null}, "v": 2.3285304471234287, "accelerator_pedal_position": 0.26594976513610885, "brake_pedal_position": 0.0, "acceleration": 0.04153896931270046, "steering_wheel_angle": -0.16920553677141575, "front_wheel_angle": -0.007787932829792397, "heading_rate": -0.0070839083408566145, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137714.6375039} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2595663209277819, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7566376854545528, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3289458368165556, "gear": 1, "accelerator_pedal_position": 0.26594976513610885, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.16920553677141575, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137714.6375039} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.41994524002075, "x": 19.678441718058277, "y": -0.17856447368697737, "z": null, "yaw": 3.1010084484476907, "pitch": null, "roll": null}, "v": 2.3285304471234287, "accelerator_pedal_position": 0.26594976513610885, "brake_pedal_position": 0.0, "acceleration": 0.04153896931270046, "steering_wheel_angle": -0.16920553677141575, "front_wheel_angle": -0.007787932829792397, "heading_rate": -0.0070839083408566145, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137714.6575038} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2626363686186192, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7566376854545528, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.328977867878422, "gear": 1, "accelerator_pedal_position": 0.2595663209277819, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.08780188852383415, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137714.6575038} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.41994524002075, "x": 19.678441718058277, "y": -0.17856447368697737, "z": null, "yaw": 3.1010084484476907, "pitch": null, "roll": null}, "v": 2.3285304471234287, "accelerator_pedal_position": 0.26594976513610885, "brake_pedal_position": 0.0, "acceleration": 0.04153896931270046, "steering_wheel_angle": -0.16920553677141575, "front_wheel_angle": -0.007787932829792397, "heading_rate": -0.0070839083408566145, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137714.6775038} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2626363686186192, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7566376854545528, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3293934077415073, "gear": 1, "accelerator_pedal_position": 0.2626363686186192, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.08780188852383415, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137714.6775038} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.41994524002075, "x": 19.678441718058277, "y": -0.17856447368697737, "z": null, "yaw": 3.1010084484476907, "pitch": null, "roll": null}, "v": 2.3285304471234287, "accelerator_pedal_position": 0.26594976513610885, "brake_pedal_position": 0.0, "acceleration": 0.04153896931270046, "steering_wheel_angle": -0.16920553677141575, "front_wheel_angle": -0.007787932829792397, "heading_rate": -0.0070839083408566145, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137714.6975038} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2626363686186192, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7566376854545528, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.329808145287328, "gear": 1, "accelerator_pedal_position": 0.2626363686186192, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.08780188852383415, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137714.6975038} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.41994524002075, "x": 19.678441718058277, "y": -0.17856447368697737, "z": null, "yaw": 3.1010084484476907, "pitch": null, "roll": null}, "v": 2.3285304471234287, "accelerator_pedal_position": 0.26594976513610885, "brake_pedal_position": 0.0, "acceleration": 0.04153896931270046, "steering_wheel_angle": -0.16920553677141575, "front_wheel_angle": -0.007787932829792397, "heading_rate": -0.0070839083408566145, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137714.7175038} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2626363686186192, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7566376854545528, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3302220819962143, "gear": 1, "accelerator_pedal_position": 0.2626363686186192, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.08780188852383415, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137714.7175038} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137714.7375038, "x": 23.422413151381342, "y": 4.831860031705859, "z": null, "yaw": 3.1007983551373797, "pitch": null, "roll": null}, "v": 2.330635219346037, "accelerator_pedal_position": 0.2626363686186192, "brake_pedal_position": 0.0, "acceleration": 0.02062693764250667, "steering_wheel_angle": -0.08780188852383415, "front_wheel_angle": -0.004036881897563995, "heading_rate": -0.003675214935705646, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137714.7375038} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2571445788396138, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8248456807585592, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.330635219346037, "gear": 1, "accelerator_pedal_position": 0.2626363686186192, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.08780188852383415, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137714.7375038} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.52994513511658, "x": 19.422413151381342, "y": -0.1681399682941409, "z": null, "yaw": 3.1007983551373797, "pitch": null, "roll": null}, "v": 2.330635219346037, "accelerator_pedal_position": 0.2626363686186192, "brake_pedal_position": 0.0, "acceleration": 0.02062693764250667, "steering_wheel_angle": -0.08780188852383415, "front_wheel_angle": -0.004036881897563995, "heading_rate": -0.003675214935705646, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137714.7575037} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2597752079293217, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8248456807585592, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3303614167026265, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.006070916148393004, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137714.7575037} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.52994513511658, "x": 19.422413151381342, "y": -0.1681399682941409, "z": null, "yaw": 3.1007983551373797, "pitch": null, "roll": null}, "v": 2.330635219346037, "accelerator_pedal_position": 0.2626363686186192, "brake_pedal_position": 0.0, "acceleration": 0.02062693764250667, "steering_wheel_angle": -0.08780188852383415, "front_wheel_angle": -0.004036881897563995, "heading_rate": -0.003675214935705646, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137714.7775037} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2597752079293217, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8248456807585592, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.33041681263935, "gear": 1, "accelerator_pedal_position": 0.2597752079293217, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.006070916148393004, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137714.7775037} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.52994513511658, "x": 19.422413151381342, "y": -0.1681399682941409, "z": null, "yaw": 3.1007983551373797, "pitch": null, "roll": null}, "v": 2.330635219346037, "accelerator_pedal_position": 0.2626363686186192, "brake_pedal_position": 0.0, "acceleration": 0.02062693764250667, "steering_wheel_angle": -0.08780188852383415, "front_wheel_angle": -0.004036881897563995, "heading_rate": -0.003675214935705646, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137714.7975037} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2597752079293217, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8248456807585592, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3304721015938967, "gear": 1, "accelerator_pedal_position": 0.2597752079293217, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.006070916148393004, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137714.7975037} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.52994513511658, "x": 19.422413151381342, "y": -0.1681399682941409, "z": null, "yaw": 3.1007983551373797, "pitch": null, "roll": null}, "v": 2.330635219346037, "accelerator_pedal_position": 0.2626363686186192, "brake_pedal_position": 0.0, "acceleration": 0.02062693764250667, "steering_wheel_angle": -0.08780188852383415, "front_wheel_angle": -0.004036881897563995, "heading_rate": -0.003675214935705646, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137714.8175037} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2597752079293217, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8248456807585592, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3306098572801184, "gear": 1, "accelerator_pedal_position": 0.2597752079293217, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.006070916148393004, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137714.8175037} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137714.8475037, "x": 23.166272874066344, "y": 4.8423212568301075, "z": null, "yaw": 3.1007643544382346, "pitch": null, "roll": null}, "v": 2.3306098572801184, "accelerator_pedal_position": 0.2597752079293217, "brake_pedal_position": 0.0, "acceleration": 0.002747133625741971, "steering_wheel_angle": -0.006070916148393004, "front_wheel_angle": -0.0002788242938873058, "heading_rate": -0.0002538401033683005, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137714.8475037} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25659809713193354, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8844330491063888, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3306373286163757, "gear": 1, "accelerator_pedal_position": 0.2597752079293217, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.006070916148393004, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137714.8475037} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.6399450302124, "x": 19.166272874066344, "y": -0.1576787431698925, "z": null, "yaw": 3.1007643544382346, "pitch": null, "roll": null}, "v": 2.3306098572801184, "accelerator_pedal_position": 0.2597752079293217, "brake_pedal_position": 0.0, "acceleration": 0.002747133625741971, "steering_wheel_angle": -0.006070916148393004, "front_wheel_angle": -0.0002788242938873058, "heading_rate": -0.0002538401033683005, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137714.8775036} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.258110821102259, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8844330491063888, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3302952446830187, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.03489548276222291, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137714.8775036} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.6399450302124, "x": 19.166272874066344, "y": -0.1576787431698925, "z": null, "yaw": 3.1007643544382346, "pitch": null, "roll": null}, "v": 2.3306098572801184, "accelerator_pedal_position": 0.2597752079293217, "brake_pedal_position": 0.0, "acceleration": 0.002747133625741971, "steering_wheel_angle": -0.006070916148393004, "front_wheel_angle": -0.0002788242938873058, "heading_rate": -0.0002538401033683005, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137714.8875036} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.258110821102259, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8844330491063888, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3302189957868293, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.03489548276222291, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137714.8875036} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.6399450302124, "x": 19.166272874066344, "y": -0.1576787431698925, "z": null, "yaw": 3.1007643544382346, "pitch": null, "roll": null}, "v": 2.3306098572801184, "accelerator_pedal_position": 0.2597752079293217, "brake_pedal_position": 0.0, "acceleration": 0.002747133625741971, "steering_wheel_angle": -0.006070916148393004, "front_wheel_angle": -0.0002788242938873058, "heading_rate": -0.0002538401033683005, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137714.9175036} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.258110821102259, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8844330491063888, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3299906907711794, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.03489548276222291, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137714.9175036} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.6399450302124, "x": 19.166272874066344, "y": -0.1576787431698925, "z": null, "yaw": 3.1007643544382346, "pitch": null, "roll": null}, "v": 2.3306098572801184, "accelerator_pedal_position": 0.2597752079293217, "brake_pedal_position": 0.0, "acceleration": 0.002747133625741971, "steering_wheel_angle": -0.006070916148393004, "front_wheel_angle": -0.0002788242938873058, "heading_rate": -0.0002538401033683005, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137714.9375036} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.258110821102259, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8844330491063888, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3298388547658853, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.03489548276222291, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137714.9375036} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.6399450302124, "x": 19.166272874066344, "y": -0.1576787431698925, "z": null, "yaw": 3.1007643544382346, "pitch": null, "roll": null}, "v": 2.3306098572801184, "accelerator_pedal_position": 0.2597752079293217, "brake_pedal_position": 0.0, "acceleration": 0.002747133625741971, "steering_wheel_angle": -0.006070916148393004, "front_wheel_angle": -0.0002788242938873058, "heading_rate": -0.0002538401033683005, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137714.9475036} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.258110821102259, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8844330491063888, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3296873119585935, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.03489548276222291, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137714.9475036} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137714.9575036, "x": 22.91016684060786, "y": 4.852778669631695, "z": null, "yaw": 3.100818541525912, "pitch": null, "roll": null}, "v": 2.3296873119585935, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37075879531293826, "steering_wheel_angle": 0.03489548276222291, "front_wheel_angle": 0.0016032811871363425, "heading_rate": 0.0014590418123381402, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137714.9775035} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2547013437686575, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.942407058050056, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3295360617739513, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.03489548276222291, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137714.9775035} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.74994492530823, "x": 18.91016684060786, "y": -0.1472213303683052, "z": null, "yaw": 3.100818541525912, "pitch": null, "roll": null}, "v": 2.3296873119585935, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37075879531293826, "steering_wheel_angle": 0.03489548276222291, "front_wheel_angle": 0.0016032811871363425, "heading_rate": 0.0014590418123381402, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137715.0075035} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2563181150689095, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.942407058050056, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3284843499109553, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.11682880070956317, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137715.0075035} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.74994492530823, "x": 18.91016684060786, "y": -0.1472213303683052, "z": null, "yaw": 3.100818541525912, "pitch": null, "roll": null}, "v": 2.3296873119585935, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37075879531293826, "steering_wheel_angle": 0.03489548276222291, "front_wheel_angle": 0.0016032811871363425, "heading_rate": 0.0014590418123381402, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137715.0275035} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2563181150689095, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.942407058050056, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3282978059910286, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.11682880070956317, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137715.0275035} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.74994492530823, "x": 18.91016684060786, "y": -0.1472213303683052, "z": null, "yaw": 3.100818541525912, "pitch": null, "roll": null}, "v": 2.3296873119585935, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37075879531293826, "steering_wheel_angle": 0.03489548276222291, "front_wheel_angle": 0.0016032811871363425, "heading_rate": 0.0014590418123381402, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137715.0475035} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2563181150689095, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.942407058050056, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3277392543562083, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.11682880070956317, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137715.0475035} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137715.0675035, "x": 22.65421637364296, "y": 4.863204175885072, "z": null, "yaw": 3.100997889863812, "pitch": null, "roll": null}, "v": 2.32755342991721, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3705527211870542, "steering_wheel_angle": 0.11682880070956317, "front_wheel_angle": 0.005373508004917755, "heading_rate": 0.004885643503244162, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137715.0675035} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2572781711221299, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9952053925628329, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.327367784897146, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.11682880070956317, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137715.0675035} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.85994482040405, "x": 18.65421637364296, "y": -0.13679582411492763, "z": null, "yaw": 3.100997889863812, "pitch": null, "roll": null}, "v": 2.32755342991721, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3705527211870542, "steering_wheel_angle": 0.11682880070956317, "front_wheel_angle": 0.005373508004917755, "heading_rate": 0.004885643503244162, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137715.0875034} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25680530045097616, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9952053925628329, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.327242322619213, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.15778892207968143, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137715.0875034} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.85994482040405, "x": 18.65421637364296, "y": -0.13679582411492763, "z": null, "yaw": 3.100997889863812, "pitch": null, "roll": null}, "v": 2.32755342991721, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3705527211870542, "steering_wheel_angle": 0.11682880070956317, "front_wheel_angle": 0.005373508004917755, "heading_rate": 0.004885643503244162, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137715.1075034} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25680530045097616, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9952053925628329, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.326932681028615, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.15778892207968143, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137715.1075034} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.85994482040405, "x": 18.65421637364296, "y": -0.13679582411492763, "z": null, "yaw": 3.100997889863812, "pitch": null, "roll": null}, "v": 2.32755342991721, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3705527211870542, "steering_wheel_angle": 0.11682880070956317, "front_wheel_angle": 0.005373508004917755, "heading_rate": 0.004885643503244162, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137715.1275034} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25680530045097616, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9952053925628329, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3266236370066684, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.15778892207968143, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137715.1275034} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.85994482040405, "x": 18.65421637364296, "y": -0.13679582411492763, "z": null, "yaw": 3.100997889863812, "pitch": null, "roll": null}, "v": 2.32755342991721, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3705527211870542, "steering_wheel_angle": 0.11682880070956317, "front_wheel_angle": 0.005373508004917755, "heading_rate": 0.004885643503244162, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137715.1475034} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25680530045097616, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9952053925628329, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.326315189361957, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.15778892207968143, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137715.1475034} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.85994482040405, "x": 18.65421637364296, "y": -0.13679582411492763, "z": null, "yaw": 3.100997889863812, "pitch": null, "roll": null}, "v": 2.32755342991721, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3705527211870542, "steering_wheel_angle": 0.11682880070956317, "front_wheel_angle": 0.005373508004917755, "heading_rate": 0.004885643503244162, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137715.1675034} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25680530045097616, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9952053925628329, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3260073369055854, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.15778892207968143, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137715.1675034} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137715.1775033, "x": 22.39848051355494, "y": 4.873558357089247, "z": null, "yaw": 3.1012951579443655, "pitch": null, "roll": null}, "v": 2.325853633502185, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3703886329198624, "steering_wheel_angle": 0.15778892207968143, "front_wheel_angle": 0.007261373391618018, "heading_rate": 0.006597339269516452, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137715.1875033} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25153487579940365, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0388938547497868, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.325546671604642, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.15778892207968143, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137715.1875033} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.96994471549988, "x": 18.39848051355494, "y": -0.12644164291075288, "z": null, "yaw": 3.1012951579443655, "pitch": null, "roll": null}, "v": 2.325853633502185, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3703886329198624, "steering_wheel_angle": 0.15778892207968143, "front_wheel_angle": 0.007261373391618018, "heading_rate": 0.006597339269516452, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137715.2075033} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2540321011082205, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0388938547497868, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.325064011274121, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1987542959543611, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137715.2075033} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.96994471549988, "x": 18.39848051355494, "y": -0.12644164291075288, "z": null, "yaw": 3.1012951579443655, "pitch": null, "roll": null}, "v": 2.325853633502185, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3703886329198624, "steering_wheel_angle": 0.15778892207968143, "front_wheel_angle": 0.007261373391618018, "heading_rate": 0.006597339269516452, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137715.2275033} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2540321011082205, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0388938547497868, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3244120900674337, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1987542959543611, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137715.2275033} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.96994471549988, "x": 18.39848051355494, "y": -0.12644164291075288, "z": null, "yaw": 3.1012951579443655, "pitch": null, "roll": null}, "v": 2.325853633502185, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3703886329198624, "steering_wheel_angle": 0.15778892207968143, "front_wheel_angle": 0.007261373391618018, "heading_rate": 0.006597339269516452, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137715.2475033} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2540321011082205, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0388938547497868, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3237614263509085, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1987542959543611, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137715.2475033} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.96994471549988, "x": 18.39848051355494, "y": -0.12644164291075288, "z": null, "yaw": 3.1012951579443655, "pitch": null, "roll": null}, "v": 2.325853633502185, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3703886329198624, "steering_wheel_angle": 0.15778892207968143, "front_wheel_angle": 0.007261373391618018, "heading_rate": 0.006597339269516452, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137715.2675033} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2540321011082205, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0388938547497868, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.323112017529711, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1987542959543611, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137715.2675033} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137715.2875032, "x": 22.14300145040674, "y": 4.883818010006803, "z": null, "yaw": 3.1016662468017038, "pitch": null, "roll": null}, "v": 2.32246386101499, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37006157690795605, "steering_wheel_angle": 0.1987542959543611, "front_wheel_angle": 0.009151525062740412, "heading_rate": 0.008302609217741274, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137715.2875032} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25447074495515976, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0833440332840112, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.32246386101499, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1987542959543611, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137715.2875032} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.0799446105957, "x": 18.14300145040674, "y": -0.11618198999319684, "z": null, "yaw": 3.1016662468017038, "pitch": null, "roll": null}, "v": 2.32246386101499, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37006157690795605, "steering_wheel_angle": 0.1987542959543611, "front_wheel_angle": 0.009151525062740412, "heading_rate": 0.008302609217741274, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137715.3075032} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25423694826272797, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0833440332840112, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.321871758264627, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.23972580873071597, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137715.3075032} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.0799446105957, "x": 18.14300145040674, "y": -0.11618198999319684, "z": null, "yaw": 3.1016662468017038, "pitch": null, "roll": null}, "v": 2.32246386101499, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37006157690795605, "steering_wheel_angle": 0.1987542959543611, "front_wheel_angle": 0.009151525062740412, "heading_rate": 0.008302609217741274, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137715.3275032} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25423694826272797, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0833440332840112, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.321251586520333, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.23972580873071597, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137715.3275032} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.0799446105957, "x": 18.14300145040674, "y": -0.11618198999319684, "z": null, "yaw": 3.1016662468017038, "pitch": null, "roll": null}, "v": 2.32246386101499, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37006157690795605, "steering_wheel_angle": 0.1987542959543611, "front_wheel_angle": 0.009151525062740412, "heading_rate": 0.008302609217741274, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137715.3475032} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25423694826272797, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0833440332840112, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.320632610239462, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.23972580873071597, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137715.3475032} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.0799446105957, "x": 18.14300145040674, "y": -0.11618198999319684, "z": null, "yaw": 3.1016662468017038, "pitch": null, "roll": null}, "v": 2.32246386101499, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37006157690795605, "steering_wheel_angle": 0.1987542959543611, "front_wheel_angle": 0.009151525062740412, "heading_rate": 0.008302609217741274, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137715.3675032} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25423694826272797, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0833440332840112, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3197063819376247, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.23972580873071597, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137715.3675032} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.0799446105957, "x": 18.14300145040674, "y": -0.11618198999319684, "z": null, "yaw": 3.1016662468017038, "pitch": null, "roll": null}, "v": 2.32246386101499, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37006157690795605, "steering_wheel_angle": 0.1987542959543611, "front_wheel_angle": 0.009151525062740412, "heading_rate": 0.008302609217741274, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137715.3875031} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25423694826272797, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0833440332840112, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.319398234243236, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.23972580873071597, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137715.3875031} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137715.3975031, "x": 21.887899454252743, "y": 4.893955347578066, "z": null, "yaw": 3.102133420181254, "pitch": null, "roll": null}, "v": 2.319090383575634, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3697363212507115, "steering_wheel_angle": 0.23972580873071597, "front_wheel_angle": 0.011044011425934473, "heading_rate": 0.010005117987270405, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137715.4075031} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25245897487354674, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.114275198877235, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3187828296295474, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.23972580873071597, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137715.4075031} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.18994450569153, "x": 17.887899454252743, "y": -0.10604465242193406, "z": null, "yaw": 3.102133420181254, "pitch": null, "roll": null}, "v": 2.319090383575634, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3697363212507115, "steering_wheel_angle": 0.23972580873071597, "front_wheel_angle": 0.011044011425934473, "heading_rate": 0.010005117987270405, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137715.427503} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25328084789554733, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.114275198877235, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.317946471096717, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2806880586446658, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137715.427503} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.18994450569153, "x": 17.887899454252743, "y": -0.10604465242193406, "z": null, "yaw": 3.102133420181254, "pitch": null, "roll": null}, "v": 2.319090383575634, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3697363212507115, "steering_wheel_angle": 0.23972580873071597, "front_wheel_angle": 0.011044011425934473, "heading_rate": 0.010005117987270405, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137715.447503} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25328084789554733, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.114275198877235, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3172144083045194, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2806880586446658, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137715.447503} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.18994450569153, "x": 17.887899454252743, "y": -0.10604465242193406, "z": null, "yaw": 3.102133420181254, "pitch": null, "roll": null}, "v": 2.319090383575634, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3697363212507115, "steering_wheel_angle": 0.23972580873071597, "front_wheel_angle": 0.011044011425934473, "heading_rate": 0.010005117987270405, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137715.467503} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25328084789554733, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.114275198877235, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.316483755487743, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2806880586446658, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137715.467503} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.18994450569153, "x": 17.887899454252743, "y": -0.10604465242193406, "z": null, "yaw": 3.102133420181254, "pitch": null, "roll": null}, "v": 2.319090383575634, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3697363212507115, "steering_wheel_angle": 0.23972580873071597, "front_wheel_angle": 0.011044011425934473, "heading_rate": 0.010005117987270405, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137715.487503} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25328084789554733, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.114275198877235, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3157545097172934, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2806880586446658, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137715.487503} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137715.507503, "x": 21.633199714026134, "y": 4.9039496390466475, "z": null, "yaw": 3.1026745864563523, "pitch": null, "roll": null}, "v": 2.315026668070949, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3693448181423442, "steering_wheel_angle": 0.2806880586446658, "front_wheel_angle": 0.012938127525430212, "heading_rate": 0.011700695956037262, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137715.507503} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2544083761105947, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1530242295846378, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.315026668070949, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2806880586446658, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137715.507503} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.29994440078735, "x": 17.633199714026134, "y": -0.09605036095335251, "z": null, "yaw": 3.1026745864563523, "pitch": null, "roll": null}, "v": 2.315026668070949, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3693448181423442, "steering_wheel_angle": 0.2806880586446658, "front_wheel_angle": 0.012938127525430212, "heading_rate": 0.011700695956037262, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137715.527503} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2538416288215815, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1530242295846378, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.31444110080137, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.32164995278476866, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137715.527503} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.29994440078735, "x": 17.633199714026134, "y": -0.09605036095335251, "z": null, "yaw": 3.1026745864563523, "pitch": null, "roll": null}, "v": 2.315026668070949, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3693448181423442, "steering_wheel_angle": 0.2806880586446658, "front_wheel_angle": 0.012938127525430212, "heading_rate": 0.011700695956037262, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137715.537503} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2538416288215815, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1530242295846378, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.313785851388624, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.32164995278476866, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137715.537503} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.29994440078735, "x": 17.633199714026134, "y": -0.09605036095335251, "z": null, "yaw": 3.1026745864563523, "pitch": null, "roll": null}, "v": 2.315026668070949, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3693448181423442, "steering_wheel_angle": 0.2806880586446658, "front_wheel_angle": 0.012938127525430212, "heading_rate": 0.011700695956037262, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137715.557503} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2538416288215815, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1530242295846378, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3131318631035818, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.32164995278476866, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137715.557503} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.29994440078735, "x": 17.633199714026134, "y": -0.09605036095335251, "z": null, "yaw": 3.1026745864563523, "pitch": null, "roll": null}, "v": 2.315026668070949, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3693448181423442, "steering_wheel_angle": 0.2806880586446658, "front_wheel_angle": 0.012938127525430212, "heading_rate": 0.011700695956037262, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137715.577503} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2538416288215815, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1530242295846378, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.312805341071768, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.32164995278476866, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137715.577503} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.29994440078735, "x": 17.633199714026134, "y": -0.09605036095335251, "z": null, "yaw": 3.1026745864563523, "pitch": null, "roll": null}, "v": 2.315026668070949, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3693448181423442, "steering_wheel_angle": 0.2806880586446658, "front_wheel_angle": 0.012938127525430212, "heading_rate": 0.011700695956037262, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137715.597503} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2538416288215815, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1530242295846378, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.31215323960847, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.32164995278476866, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137715.597503} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137715.617503, "x": 21.37891005585054, "y": 4.913779043922272, "z": null, "yaw": 3.1033046358470986, "pitch": null, "roll": null}, "v": 2.3115023927885185, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36900555275809643, "steering_wheel_angle": 0.32164995278476866, "front_wheel_angle": 0.014834291231334649, "heading_rate": 0.01339531839984004, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137715.617503} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25353058288551295, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.176542651270812, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3115023927885185, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.32164995278476866, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137715.617503} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.40994429588318, "x": 17.37891005585054, "y": -0.08622095607772806, "z": null, "yaw": 3.1033046358470986, "pitch": null, "roll": null}, "v": 2.3115023927885185, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36900555275809643, "steering_wheel_angle": 0.32164995278476866, "front_wheel_angle": 0.014834291231334649, "heading_rate": 0.01339531839984004, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137715.637503} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25365285126782416, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.176542651270812, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3108139359927895, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.36259405856315374, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137715.637503} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.40994429588318, "x": 17.37891005585054, "y": -0.08622095607772806, "z": null, "yaw": 3.1033046358470986, "pitch": null, "roll": null}, "v": 2.3115023927885185, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36900555275809643, "steering_wheel_angle": 0.32164995278476866, "front_wheel_angle": 0.014834291231334649, "heading_rate": 0.01339531839984004, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137715.657503} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25365285126782416, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.176542651270812, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.309806636139416, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.36259405856315374, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137715.657503} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.40994429588318, "x": 17.37891005585054, "y": -0.08622095607772806, "z": null, "yaw": 3.1033046358470986, "pitch": null, "roll": null}, "v": 2.3115023927885185, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36900555275809643, "steering_wheel_angle": 0.32164995278476866, "front_wheel_angle": 0.014834291231334649, "heading_rate": 0.01339531839984004, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137715.6775029} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25365285126782416, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.176542651270812, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3094715153559497, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.36259405856315374, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137715.6775029} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.40994429588318, "x": 17.37891005585054, "y": -0.08622095607772806, "z": null, "yaw": 3.1033046358470986, "pitch": null, "roll": null}, "v": 2.3115023927885185, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36900555275809643, "steering_wheel_angle": 0.32164995278476866, "front_wheel_angle": 0.014834291231334649, "heading_rate": 0.01339531839984004, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137715.6975029} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25365285126782416, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.176542651270812, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3088022405425086, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.36259405856315374, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137715.6975029} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.40994429588318, "x": 17.37891005585054, "y": -0.08622095607772806, "z": null, "yaw": 3.1033046358470986, "pitch": null, "roll": null}, "v": 2.3115023927885185, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36900555275809643, "steering_wheel_angle": 0.32164995278476866, "front_wheel_angle": 0.014834291231334649, "heading_rate": 0.01339531839984004, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137715.7175028} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25365285126782416, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.176542651270812, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3081342525188604, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.36259405856315374, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137715.7175028} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137715.7275028, "x": 21.1250140388153, "y": 4.923423610533383, "z": null, "yaw": 3.1040162296136895, "pitch": null, "roll": null}, "v": 2.3078007402240748, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3686494795769916, "steering_wheel_angle": 0.36259405856315374, "front_wheel_angle": 0.016731700959040828, "heading_rate": 0.015084779506412644, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137715.7375028} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2531049441176114, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1982944041201498, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3074675486325438, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.36259405856315374, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137715.7375028} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.519944190979004, "x": 17.1250140388153, "y": -0.07657638946661738, "z": null, "yaw": 3.1040162296136895, "pitch": null, "roll": null}, "v": 2.3078007402240748, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3686494795769916, "steering_wheel_angle": 0.36259405856315374, "front_wheel_angle": 0.016731700959040828, "heading_rate": 0.015084779506412644, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137715.7575028} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25333872301593513, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1982944041201498, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3067336707666266, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.36259405856315374, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137715.7575028} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.519944190979004, "x": 17.1250140388153, "y": -0.07657638946661738, "z": null, "yaw": 3.1040162296136895, "pitch": null, "roll": null}, "v": 2.3078007402240748, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3686494795769916, "steering_wheel_angle": 0.36259405856315374, "front_wheel_angle": 0.016731700959040828, "heading_rate": 0.015084779506412644, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137715.7775028} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25333872301593513, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1982944041201498, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.306030411615408, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.36259405856315374, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137715.7775028} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.519944190979004, "x": 17.1250140388153, "y": -0.07657638946661738, "z": null, "yaw": 3.1040162296136895, "pitch": null, "roll": null}, "v": 2.3078007402240748, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3686494795769916, "steering_wheel_angle": 0.36259405856315374, "front_wheel_angle": 0.016731700959040828, "heading_rate": 0.015084779506412644, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137715.7875028} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25333872301593513, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1982944041201498, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3056792889721667, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.36259405856315374, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137715.7875028} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.519944190979004, "x": 17.1250140388153, "y": -0.07657638946661738, "z": null, "yaw": 3.1040162296136895, "pitch": null, "roll": null}, "v": 2.3078007402240748, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3686494795769916, "steering_wheel_angle": 0.36259405856315374, "front_wheel_angle": 0.016731700959040828, "heading_rate": 0.015084779506412644, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137715.8175027} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25333872301593513, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1982944041201498, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3046279445801736, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.36259405856315374, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137715.8175027} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137715.8375027, "x": 20.871525942049843, "y": 4.932870336381235, "z": null, "yaw": 3.104735236985852, "pitch": null, "roll": null}, "v": 2.3039287311153, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36827731253635054, "steering_wheel_angle": 0.36259405856315374, "front_wheel_angle": 0.016731700959040828, "heading_rate": 0.015059470387373614, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137715.8375027} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25034332897105543, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.177613249051566, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3039287311153, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.36259405856315374, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137715.8375027} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.62994408607483, "x": 16.871525942049843, "y": -0.06712966361876482, "z": null, "yaw": 3.104735236985852, "pitch": null, "roll": null}, "v": 2.3039287311153, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36827731253635054, "steering_wheel_angle": 0.36259405856315374, "front_wheel_angle": 0.016731700959040828, "heading_rate": 0.015059470387373614, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137715.8575027} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2517413522019897, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.177613249051566, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.302856616241061, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.36259405856315374, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137715.8575027} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.62994408607483, "x": 16.871525942049843, "y": -0.06712966361876482, "z": null, "yaw": 3.104735236985852, "pitch": null, "roll": null}, "v": 2.3039287311153, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36827731253635054, "steering_wheel_angle": 0.36259405856315374, "front_wheel_angle": 0.016731700959040828, "heading_rate": 0.015059470387373614, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137715.8775027} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2517413522019897, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.177613249051566, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3019612291592226, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.36259405856315374, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137715.8775027} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.62994408607483, "x": 16.871525942049843, "y": -0.06712966361876482, "z": null, "yaw": 3.104735236985852, "pitch": null, "roll": null}, "v": 2.3039287311153, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36827731253635054, "steering_wheel_angle": 0.36259405856315374, "front_wheel_angle": 0.016731700959040828, "heading_rate": 0.015059470387373614, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137715.8875027} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2517413522019897, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.177613249051566, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3015141805072123, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.36259405856315374, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137715.8875027} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.62994408607483, "x": 16.871525942049843, "y": -0.06712966361876482, "z": null, "yaw": 3.104735236985852, "pitch": null, "roll": null}, "v": 2.3039287311153, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36827731253635054, "steering_wheel_angle": 0.36259405856315374, "front_wheel_angle": 0.016731700959040828, "heading_rate": 0.015059470387373614, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137715.9175026} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2517413522019897, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.177613249051566, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3001756086753264, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.36259405856315374, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137715.9175026} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.62994408607483, "x": 16.871525942049843, "y": -0.06712966361876482, "z": null, "yaw": 3.104735236985852, "pitch": null, "roll": null}, "v": 2.3039287311153, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36827731253635054, "steering_wheel_angle": 0.36259405856315374, "front_wheel_angle": 0.016731700959040828, "heading_rate": 0.015059470387373614, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137715.9375026} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2517413522019897, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.177613249051566, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.299285368042271, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.36259405856315374, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137715.9375026} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137715.9475026, "x": 20.61852543455188, "y": 4.942116741836345, "z": null, "yaw": 3.1054542443580146, "pitch": null, "roll": null}, "v": 2.298840888550505, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.367788738736242, "steering_wheel_angle": 0.36259405856315374, "front_wheel_angle": 0.016731700959040828, "heading_rate": 0.01502621405726003, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137715.9575026} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2549684511025345, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.22251694648997, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2983968356757667, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.36259405856315374, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137715.9575026} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.739943981170654, "x": 16.61852543455188, "y": -0.05788325816365525, "z": null, "yaw": 3.1054542443580146, "pitch": null, "roll": null}, "v": 2.298840888550505, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.367788738736242, "steering_wheel_angle": 0.36259405856315374, "front_wheel_angle": 0.016731700959040828, "heading_rate": 0.01502621405726003, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137715.9775026} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25339451188363443, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.22251694648997, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2979132017973383, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4035460720482305, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137715.9775026} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.739943981170654, "x": 16.61852543455188, "y": -0.05788325816365525, "z": null, "yaw": 3.1054542443580146, "pitch": null, "roll": null}, "v": 2.298840888550505, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.367788738736242, "steering_wheel_angle": 0.36259405856315374, "front_wheel_angle": 0.016731700959040828, "heading_rate": 0.01502621405726003, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137715.9975026} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25339451188363443, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.22251694648997, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2972338476575236, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4035460720482305, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137715.9975026} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.739943981170654, "x": 16.61852543455188, "y": -0.05788325816365525, "z": null, "yaw": 3.1054542443580146, "pitch": null, "roll": null}, "v": 2.298840888550505, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.367788738736242, "steering_wheel_angle": 0.36259405856315374, "front_wheel_angle": 0.016731700959040828, "heading_rate": 0.01502621405726003, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137716.0175025} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25339451188363443, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.22251694648997, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.296555796546737, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4035460720482305, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137716.0175025} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.739943981170654, "x": 16.61852543455188, "y": -0.05788325816365525, "z": null, "yaw": 3.1054542443580146, "pitch": null, "roll": null}, "v": 2.298840888550505, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.367788738736242, "steering_wheel_angle": 0.36259405856315374, "front_wheel_angle": 0.016731700959040828, "heading_rate": 0.01502621405726003, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137716.0375025} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25339451188363443, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.22251694648997, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.295879045781903, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4035460720482305, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137716.0375025} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137716.0575025, "x": 20.3659952303182, "y": 4.951157999894509, "z": null, "yaw": 3.1062400643289387, "pitch": null, "roll": null}, "v": 2.295203592686147, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3674397749531013, "steering_wheel_angle": 0.4035460720482305, "front_wheel_angle": 0.018631553546843413, "heading_rate": 0.016706311532940683, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137716.0575025} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2533180148497985, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2359085359212987, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.295203592686147, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4035460720482305, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137716.0575025} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.84994387626648, "x": 16.3659952303182, "y": -0.04884200010549122, "z": null, "yaw": 3.1062400643289387, "pitch": null, "roll": null}, "v": 2.295203592686147, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3674397749531013, "steering_wheel_angle": 0.4035460720482305, "front_wheel_angle": 0.018631553546843413, "heading_rate": 0.016706311532940683, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137716.0675025} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2533278542968725, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2359085359212987, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2948615708647284, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4035460720482305, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137716.0675025} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.84994387626648, "x": 16.3659952303182, "y": -0.04884200010549122, "z": null, "yaw": 3.1062400643289387, "pitch": null, "roll": null}, "v": 2.295203592686147, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3674397749531013, "steering_wheel_angle": 0.4035460720482305, "front_wheel_angle": 0.018631553546843413, "heading_rate": 0.016706311532940683, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137716.0975025} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2533278542968725, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2359085359212987, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.293839315184024, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4035460720482305, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137716.0975025} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.84994387626648, "x": 16.3659952303182, "y": -0.04884200010549122, "z": null, "yaw": 3.1062400643289387, "pitch": null, "roll": null}, "v": 2.295203592686147, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3674397749531013, "steering_wheel_angle": 0.4035460720482305, "front_wheel_angle": 0.018631553546843413, "heading_rate": 0.016706311532940683, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137716.1175025} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2533278542968725, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2359085359212987, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.292819997107289, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4035460720482305, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137716.1175025} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.84994387626648, "x": 16.3659952303182, "y": -0.04884200010549122, "z": null, "yaw": 3.1062400643289387, "pitch": null, "roll": null}, "v": 2.295203592686147, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3674397749531013, "steering_wheel_angle": 0.4035460720482305, "front_wheel_angle": 0.018631553546843413, "heading_rate": 0.016706311532940683, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137716.1375024} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2533278542968725, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2359085359212987, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2924808756483763, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4035460720482305, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137716.1375024} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.84994387626648, "x": 16.3659952303182, "y": -0.04884200010549122, "z": null, "yaw": 3.1062400643289387, "pitch": null, "roll": null}, "v": 2.295203592686147, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3674397749531013, "steering_wheel_angle": 0.4035460720482305, "front_wheel_angle": 0.018631553546843413, "heading_rate": 0.016706311532940683, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137716.1575024} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2533278542968725, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2359085359212987, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2914654602825726, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4035460720482305, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137716.1575024} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137716.1675024, "x": 20.11386454730163, "y": 4.959983340883742, "z": null, "yaw": 3.107040731544032, "pitch": null, "roll": null}, "v": 2.2914654602825726, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36708141257080884, "steering_wheel_angle": 0.4035460720482305, "front_wheel_angle": 0.018631553546843413, "heading_rate": 0.016679102441475115, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137716.1775024} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24940271240320752, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2043874083364337, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.291127637050419, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4035460720482305, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137716.1775024} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.959943771362305, "x": 16.11386454730163, "y": -0.04001665911625807, "z": null, "yaw": 3.107040731544032, "pitch": null, "roll": null}, "v": 2.2914654602825726, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36708141257080884, "steering_wheel_angle": 0.4035460720482305, "front_wheel_angle": 0.018631553546843413, "heading_rate": 0.016679102441475115, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137716.1975024} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2512445247101771, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2043874083364337, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2899625537337935, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4035460720482305, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137716.1975024} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.959943771362305, "x": 16.11386454730163, "y": -0.04001665911625807, "z": null, "yaw": 3.107040731544032, "pitch": null, "roll": null}, "v": 2.2914654602825726, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36708141257080884, "steering_wheel_angle": 0.4035460720482305, "front_wheel_angle": 0.018631553546843413, "heading_rate": 0.016679102441475115, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137716.2175024} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2512445247101771, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2043874083364337, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2890298180385624, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4035460720482305, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137716.2175024} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.959943771362305, "x": 16.11386454730163, "y": -0.04001665911625807, "z": null, "yaw": 3.107040731544032, "pitch": null, "roll": null}, "v": 2.2914654602825726, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36708141257080884, "steering_wheel_angle": 0.4035460720482305, "front_wheel_angle": 0.018631553546843413, "heading_rate": 0.016679102441475115, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137716.2375023} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2512445247101771, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2043874083364337, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2880988683342274, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4035460720482305, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137716.2375023} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.959943771362305, "x": 16.11386454730163, "y": -0.04001665911625807, "z": null, "yaw": 3.107040731544032, "pitch": null, "roll": null}, "v": 2.2914654602825726, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36708141257080884, "steering_wheel_angle": 0.4035460720482305, "front_wheel_angle": 0.018631553546843413, "heading_rate": 0.016679102441475115, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137716.2575023} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2512445247101771, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2043874083364337, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2871697008544936, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4035460720482305, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137716.2575023} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137716.2775023, "x": 19.862213706149166, "y": 4.9685901675465205, "z": null, "yaw": 3.1078413987591254, "pitch": null, "roll": null}, "v": 2.2862423118422672, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3665811546766921, "steering_wheel_angle": 0.4035460720482305, "front_wheel_angle": 0.018631553546843413, "heading_rate": 0.016641084225877772, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137716.2775023} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25444677991977593, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2443207643421577, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2862423118422672, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4035460720482305, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137716.2775023} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.06994366645813, "x": 15.862213706149166, "y": -0.0314098324534795, "z": null, "yaw": 3.1078413987591254, "pitch": null, "roll": null}, "v": 2.2862423118422672, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3665811546766921, "steering_wheel_angle": 0.4035460720482305, "front_wheel_angle": 0.018631553546843413, "heading_rate": 0.016641084225877772, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137716.2975023} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2528837808186765, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2443207643421577, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2857167878807387, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4035460720482305, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137716.2975023} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.06994366645813, "x": 15.862213706149166, "y": -0.0314098324534795, "z": null, "yaw": 3.1078413987591254, "pitch": null, "roll": null}, "v": 2.2862423118422672, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3665811546766921, "steering_wheel_angle": 0.4035460720482305, "front_wheel_angle": 0.018631553546843413, "heading_rate": 0.016641084225877772, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137716.3075023} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2528837808186765, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2443207643421577, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2849969880760774, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4035460720482305, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137716.3075023} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2528837808186765, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2443207643421577, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2849969880760774, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4035460720482305, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137716.3175023} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.06994366645813, "x": 15.862213706149166, "y": -0.0314098324534795, "z": null, "yaw": 3.1078413987591254, "pitch": null, "roll": null}, "v": 2.2862423118422672, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3665811546766921, "steering_wheel_angle": 0.4035460720482305, "front_wheel_angle": 0.018631553546843413, "heading_rate": 0.016641084225877772, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137716.3475022} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2528837808186765, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2443207643421577, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.283919869522005, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4035460720482305, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137716.3475022} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.06994366645813, "x": 15.862213706149166, "y": -0.0314098324534795, "z": null, "yaw": 3.1078413987591254, "pitch": null, "roll": null}, "v": 2.2862423118422672, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3665811546766921, "steering_wheel_angle": 0.4035460720482305, "front_wheel_angle": 0.018631553546843413, "heading_rate": 0.016641084225877772, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137716.3675022} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2528837808186765, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2443207643421577, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2828458398360714, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4035460720482305, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137716.3675022} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137716.3875022, "x": 19.611046377193585, "y": 4.976979115413402, "z": null, "yaw": 3.1086420659742187, "pitch": null, "roll": null}, "v": 2.282488514704475, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36622196393280215, "steering_wheel_angle": 0.4035460720482305, "front_wheel_angle": 0.018631553546843413, "heading_rate": 0.016613761114056557, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137716.3875022} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25556017085991695, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2872611151525801, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.282488514704475, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4035460720482305, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137716.3875022} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.179943561553955, "x": 15.611046377193585, "y": -0.023020884586597568, "z": null, "yaw": 3.1086420659742187, "pitch": null, "roll": null}, "v": 2.282488514704475, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36622196393280215, "steering_wheel_angle": 0.4035460720482305, "front_wheel_angle": 0.018631553546843413, "heading_rate": 0.016613761114056557, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137716.4075022} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2542583318475616, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2872611151525801, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.281838567061468, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.44452762856447037, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137716.4075022} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.179943561553955, "x": 15.611046377193585, "y": -0.023020884586597568, "z": null, "yaw": 3.1086420659742187, "pitch": null, "roll": null}, "v": 2.282488514704475, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36622196393280215, "steering_wheel_angle": 0.4035460720482305, "front_wheel_angle": 0.018631553546843413, "heading_rate": 0.016613761114056557, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137716.4275022} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2542583318475616, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2872611151525801, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.281568114793797, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.44452762856447037, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137716.4275022} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.179943561553955, "x": 15.611046377193585, "y": -0.023020884586597568, "z": null, "yaw": 3.1086420659742187, "pitch": null, "roll": null}, "v": 2.282488514704475, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36622196393280215, "steering_wheel_angle": 0.4035460720482305, "front_wheel_angle": 0.018631553546843413, "heading_rate": 0.016613761114056557, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137716.4475021} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2542583318475616, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2872611151525801, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.281027985930002, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.44452762856447037, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137716.4475021} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.179943561553955, "x": 15.611046377193585, "y": -0.023020884586597568, "z": null, "yaw": 3.1086420659742187, "pitch": null, "roll": null}, "v": 2.282488514704475, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36622196393280215, "steering_wheel_angle": 0.4035460720482305, "front_wheel_angle": 0.018631553546843413, "heading_rate": 0.016613761114056557, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137716.467502} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2542583318475616, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2872611151525801, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.280488889549997, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.44452762856447037, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137716.467502} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.179943561553955, "x": 15.611046377193585, "y": -0.023020884586597568, "z": null, "yaw": 3.1086420659742187, "pitch": null, "roll": null}, "v": 2.282488514704475, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36622196393280215, "steering_wheel_angle": 0.4035460720482305, "front_wheel_angle": 0.018631553546843413, "heading_rate": 0.016613761114056557, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137716.487502} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2542583318475616, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2872611151525801, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.279950823563942, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.44452762856447037, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137716.487502} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137716.497502, "x": 19.36023889166766, "y": 4.985147368291713, "z": null, "yaw": 3.1095171097335244, "pitch": null, "roll": null}, "v": 2.2796821763168453, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3659536170660094, "steering_wheel_angle": 0.44452762856447037, "front_wheel_angle": 0.02053486239381278, "heading_rate": 0.01828888318005129, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137716.507502} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2536014771980589, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.289774930049558, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2791045985978644, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.44452762856447037, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137716.507502} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.28994345664978, "x": 15.36023889166766, "y": -0.014852631708286879, "z": null, "yaw": 3.1095171097335244, "pitch": null, "roll": null}, "v": 2.2796821763168453, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3659536170660094, "steering_wheel_angle": 0.44452762856447037, "front_wheel_angle": 0.02053486239381278, "heading_rate": 0.01828888318005129, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137716.527502} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2538938197968662, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.289774930049558, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.278795706846309, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.44452762856447037, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137716.527502} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.28994345664978, "x": 15.36023889166766, "y": -0.014852631708286879, "z": null, "yaw": 3.1095171097335244, "pitch": null, "roll": null}, "v": 2.2796821763168453, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3659536170660094, "steering_wheel_angle": 0.44452762856447037, "front_wheel_angle": 0.02053486239381278, "heading_rate": 0.01828888318005129, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137716.547502} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2538938197968662, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.289774930049558, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2782153341118057, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.44452762856447037, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137716.547502} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.28994345664978, "x": 15.36023889166766, "y": -0.014852631708286879, "z": null, "yaw": 3.1095171097335244, "pitch": null, "roll": null}, "v": 2.2796821763168453, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3659536170660094, "steering_wheel_angle": 0.44452762856447037, "front_wheel_angle": 0.02053486239381278, "heading_rate": 0.01828888318005129, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137716.567502} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2538938197968662, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.289774930049558, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2776360701393017, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.44452762856447037, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137716.567502} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.28994345664978, "x": 15.36023889166766, "y": -0.014852631708286879, "z": null, "yaw": 3.1095171097335244, "pitch": null, "roll": null}, "v": 2.2796821763168453, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3659536170660094, "steering_wheel_angle": 0.44452762856447037, "front_wheel_angle": 0.02053486239381278, "heading_rate": 0.01828888318005129, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137716.587502} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2538938197968662, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.289774930049558, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.277057912676429, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.44452762856447037, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137716.587502} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137716.607502, "x": 19.109760075550696, "y": 4.9930838186110975, "z": null, "yaw": 3.1103995911472513, "pitch": null, "roll": null}, "v": 2.2764808594758916, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36564769400939556, "steering_wheel_angle": 0.44452762856447037, "front_wheel_angle": 0.02053486239381278, "heading_rate": 0.01826320042903679, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137716.607502} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2544797675885063, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3014231815055308, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.276229368010079, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.48548049202401683, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137716.607502} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.399943351745605, "x": 15.109760075550696, "y": -0.006916181388902487, "z": null, "yaw": 3.1103995911472513, "pitch": null, "roll": null}, "v": 2.2764808594758916, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36564769400939556, "steering_wheel_angle": 0.44452762856447037, "front_wheel_angle": 0.02053486239381278, "heading_rate": 0.01826320042903679, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137716.627502} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2541774362561937, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3014231815055308, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2759781167867765, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.48548049202401683, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137716.627502} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.399943351745605, "x": 15.109760075550696, "y": -0.006916181388902487, "z": null, "yaw": 3.1103995911472513, "pitch": null, "roll": null}, "v": 2.2764808594758916, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36564769400939556, "steering_wheel_angle": 0.44452762856447037, "front_wheel_angle": 0.02053486239381278, "heading_rate": 0.01826320042903679, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137716.647502} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2541774362561937, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3014231815055308, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.27543856073103, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.48548049202401683, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137716.647502} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.399943351745605, "x": 15.109760075550696, "y": -0.006916181388902487, "z": null, "yaw": 3.1103995911472513, "pitch": null, "roll": null}, "v": 2.2764808594758916, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36564769400939556, "steering_wheel_angle": 0.44452762856447037, "front_wheel_angle": 0.02053486239381278, "heading_rate": 0.01826320042903679, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137716.667502} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2541774362561937, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3014231815055308, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2749000348589203, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.48548049202401683, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137716.667502} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.399943351745605, "x": 15.109760075550696, "y": -0.006916181388902487, "z": null, "yaw": 3.1103995911472513, "pitch": null, "roll": null}, "v": 2.2764808594758916, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36564769400939556, "steering_wheel_angle": 0.44452762856447037, "front_wheel_angle": 0.02053486239381278, "heading_rate": 0.01826320042903679, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137716.687502} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2541774362561937, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3014231815055308, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2743625370875518, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.48548049202401683, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137716.687502} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.399943351745605, "x": 15.109760075550696, "y": -0.006916181388902487, "z": null, "yaw": 3.1103995911472513, "pitch": null, "roll": null}, "v": 2.2764808594758916, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36564769400939556, "steering_wheel_angle": 0.44452762856447037, "front_wheel_angle": 0.02053486239381278, "heading_rate": 0.01826320042903679, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137716.707502} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2541774362561937, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3014231815055308, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2735582135744696, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.48548049202401683, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137716.707502} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137716.7175019, "x": 18.859610304591126, "y": 5.0007812528447815, "z": null, "yaw": 3.111356484565363, "pitch": null, "roll": null}, "v": 2.2735582135744696, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3653685801838429, "steering_wheel_angle": 0.48548049202401683, "front_wheel_angle": 0.02243892977652675, "heading_rate": 0.019931553569482088, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137716.7275019} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2562470911318816, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.333201648992882, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.273290617538643, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.48548049202401683, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137716.7275019} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.50994324684143, "x": 14.859610304591126, "y": 0.000781252844781477, "z": null, "yaw": 3.111356484565363, "pitch": null, "roll": null}, "v": 2.2735582135744696, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3653685801838429, "steering_wheel_angle": 0.48548049202401683, "front_wheel_angle": 0.02243892977652675, "heading_rate": 0.019931553569482088, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137716.7475019} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25524027487284895, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.333201648992882, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.273014774994868, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.48548049202401683, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137716.7475019} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.50994324684143, "x": 14.859610304591126, "y": 0.000781252844781477, "z": null, "yaw": 3.111356484565363, "pitch": null, "roll": null}, "v": 2.2735582135744696, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3653685801838429, "steering_wheel_angle": 0.48548049202401683, "front_wheel_angle": 0.02243892977652675, "heading_rate": 0.019931553569482088, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137716.7675018} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25524027487284895, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.333201648992882, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.271813745285647, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.48548049202401683, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137716.7675018} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.50994324684143, "x": 14.859610304591126, "y": 0.000781252844781477, "z": null, "yaw": 3.111356484565363, "pitch": null, "roll": null}, "v": 2.2735582135744696, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3653685801838429, "steering_wheel_angle": 0.48548049202401683, "front_wheel_angle": 0.02243892977652675, "heading_rate": 0.019931553569482088, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137716.8075018} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25524027487284895, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.333201648992882, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2712158058928242, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.48548049202401683, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137716.8075018} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137716.8275018, "x": 18.609736167007085, "y": 5.0082291841464555, "z": null, "yaw": 3.1123208191839136, "pitch": null, "roll": null}, "v": 2.2714149287555063, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36516400422350914, "steering_wheel_angle": 0.48548049202401683, "front_wheel_angle": 0.02243892977652675, "heading_rate": 0.019912764080860786, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137716.8375018} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25521112071980223, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3375786063253772, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.271016873045737, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.48548049202401683, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137716.8375018} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.619943141937256, "x": 14.609736167007085, "y": 0.00822918414645546, "z": null, "yaw": 3.1123208191839136, "pitch": null, "roll": null}, "v": 2.2714149287555063, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36516400422350914, "steering_wheel_angle": 0.48548049202401683, "front_wheel_angle": 0.02243892977652675, "heading_rate": 0.019912764080860786, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137716.8575017} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2552094169091384, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3375786063253772, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2704156450288018, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137716.8575017} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.619943141937256, "x": 14.609736167007085, "y": 0.00822918414645546, "z": null, "yaw": 3.1123208191839136, "pitch": null, "roll": null}, "v": 2.2714149287555063, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36516400422350914, "steering_wheel_angle": 0.48548049202401683, "front_wheel_angle": 0.02243892977652675, "heading_rate": 0.019912764080860786, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137716.8775017} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2552094169091384, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3375786063253772, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2702155470429894, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137716.8775017} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.619943141937256, "x": 14.609736167007085, "y": 0.00822918414645546, "z": null, "yaw": 3.1123208191839136, "pitch": null, "roll": null}, "v": 2.2714149287555063, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36516400422350914, "steering_wheel_angle": 0.48548049202401683, "front_wheel_angle": 0.02243892977652675, "heading_rate": 0.019912764080860786, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137716.8975017} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2552094169091384, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3375786063253772, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.269815923599557, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137716.8975017} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.619943141937256, "x": 14.609736167007085, "y": 0.00822918414645546, "z": null, "yaw": 3.1123208191839136, "pitch": null, "roll": null}, "v": 2.2714149287555063, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36516400422350914, "steering_wheel_angle": 0.48548049202401683, "front_wheel_angle": 0.02243892977652675, "heading_rate": 0.019912764080860786, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137716.9175017} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2552094169091384, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3375786063253772, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.269616397761876, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137716.9175017} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137716.9375017, "x": 18.3600940898107, "y": 5.015424517365384, "z": null, "yaw": 3.113344749174987, "pitch": null, "roll": null}, "v": 2.2692179169059603, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36495439538936825, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.021583939673249106, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137716.9375017} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2560984375628978, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3393753040775087, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2692179169059603, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137716.9375017} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.72994303703308, "x": 14.360094089810701, "y": 0.01542451736538375, "z": null, "yaw": 3.113344749174987, "pitch": null, "roll": null}, "v": 2.2692179169059603, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36495439538936825, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.021583939673249106, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137716.9575016} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2556591239780977, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3393753040775087, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2687881522660827, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137716.9575016} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.72994303703308, "x": 14.360094089810701, "y": 0.01542451736538375, "z": null, "yaw": 3.113344749174987, "pitch": null, "roll": null}, "v": 2.2692179169059603, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36495439538936825, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.021583939673249106, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137716.9775016} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2556591239780977, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3393753040775087, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2686177134705945, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137716.9775016} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.72994303703308, "x": 14.360094089810701, "y": 0.01542451736538375, "z": null, "yaw": 3.113344749174987, "pitch": null, "roll": null}, "v": 2.2692179169059603, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36495439538936825, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.021583939673249106, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137716.9975016} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2556591239780977, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3393753040775087, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.268277323381972, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137716.9975016} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.72994303703308, "x": 14.360094089810701, "y": 0.01542451736538375, "z": null, "yaw": 3.113344749174987, "pitch": null, "roll": null}, "v": 2.2692179169059603, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36495439538936825, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.021583939673249106, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137717.0175016} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2556591239780977, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3393753040775087, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2677679545949276, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137717.0175016} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.72994303703308, "x": 14.360094089810701, "y": 0.01542451736538375, "z": null, "yaw": 3.113344749174987, "pitch": null, "roll": null}, "v": 2.2692179169059603, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36495439538936825, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.021583939673249106, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137717.0375016} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2556591239780977, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3393753040775087, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2675984887166725, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137717.0375016} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137717.0475016, "x": 18.110662668604988, "y": 5.022353606152676, "z": null, "yaw": 3.1143910274307567, "pitch": null, "roll": null}, "v": 2.267429184430342, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36478381028558154, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.021566925928752513, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137717.0575016} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25681934371952303, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3548205891603875, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2671635737281868, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137717.0575016} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.839942932128906, "x": 14.110662668604988, "y": 0.022353606152676342, "z": null, "yaw": 3.1143910274307567, "pitch": null, "roll": null}, "v": 2.267429184430342, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36478381028558154, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.021566925928752513, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137717.0775015} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2562538608855962, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3548205891603875, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2670671978567887, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137717.0775015} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.839942932128906, "x": 14.110662668604988, "y": 0.022353606152676342, "z": null, "yaw": 3.1143910274307567, "pitch": null, "roll": null}, "v": 2.267429184430342, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36478381028558154, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.021566925928752513, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137717.0975015} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2562538608855962, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3548205891603875, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.266672694227755, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137717.0975015} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.839942932128906, "x": 14.110662668604988, "y": 0.022353606152676342, "z": null, "yaw": 3.1143910274307567, "pitch": null, "roll": null}, "v": 2.267429184430342, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36478381028558154, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.021566925928752513, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137717.1175015} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2562538608855962, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3548205891603875, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2664103182476367, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137717.1175015} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.839942932128906, "x": 14.110662668604988, "y": 0.022353606152676342, "z": null, "yaw": 3.1143910274307567, "pitch": null, "roll": null}, "v": 2.267429184430342, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36478381028558154, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.021566925928752513, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137717.1375015} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2562538608855962, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3548205891603875, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.266148442272598, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137717.1375015} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137717.1575015, "x": 17.86140460839794, "y": 5.02901688810502, "z": null, "yaw": 3.1154373056865263, "pitch": null, "roll": null}, "v": 2.26601769148057, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3646492463550578, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.021553500343466002, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137717.1575015} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25647459789031757, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3416741427823173, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.265770359738573, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137717.1575015} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.94994282722473, "x": 13.86140460839794, "y": 0.029016888105020122, "z": null, "yaw": 3.1154373056865263, "pitch": null, "roll": null}, "v": 2.26601769148057, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3646492463550578, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.021553500343466002, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137717.1775014} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2563592324833517, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3416741427823173, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2656537653945414, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137717.1775014} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.94994282722473, "x": 13.86140460839794, "y": 0.029016888105020122, "z": null, "yaw": 3.1154373056865263, "pitch": null, "roll": null}, "v": 2.26601769148057, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3646492463550578, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.021553500343466002, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137717.2075014} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2563592324833517, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3416741427823173, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.265406496187234, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137717.2075014} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.94994282722473, "x": 13.86140460839794, "y": 0.029016888105020122, "z": null, "yaw": 3.1154373056865263, "pitch": null, "roll": null}, "v": 2.26601769148057, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3646492463550578, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.021553500343466002, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137717.2275014} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2563592324833517, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3416741427823173, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.265159698096742, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137717.2275014} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.94994282722473, "x": 13.86140460839794, "y": 0.029016888105020122, "z": null, "yaw": 3.1154373056865263, "pitch": null, "roll": null}, "v": 2.26601769148057, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3646492463550578, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.021553500343466002, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137717.2475014} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2563592324833517, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3416741427823173, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2649133702011044, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137717.2475014} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137717.2675014, "x": 17.612292297041844, "y": 5.035415453572945, "z": null, "yaw": 3.116483583942296, "pitch": null, "roll": null}, "v": 2.264667511580256, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3645205649590839, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.021540657944638063, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137717.2675014} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25711707018902724, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.340062203351731, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.264667511580256, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137717.2675014} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.05994272232056, "x": 13.612292297041844, "y": 0.035415453572944955, "z": null, "yaw": 3.116483583942296, "pitch": null, "roll": null}, "v": 2.264667511580256, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3645205649590839, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.021540657944638063, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137717.2875013} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2567463906090798, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.340062203351731, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2645168058946124, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137717.2875013} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.05994272232056, "x": 13.612292297041844, "y": 0.035415453572944955, "z": null, "yaw": 3.116483583942296, "pitch": null, "roll": null}, "v": 2.264667511580256, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3645205649590839, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.021540657944638063, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137717.3075013} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2567463906090798, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.340062203351731, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2643200744187704, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137717.3075013} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.05994272232056, "x": 13.612292297041844, "y": 0.035415453572944955, "z": null, "yaw": 3.116483583942296, "pitch": null, "roll": null}, "v": 2.264667511580256, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3645205649590839, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.021540657944638063, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137717.3275013} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2567463906090798, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.340062203351731, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2641237176848628, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137717.3275013} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.05994272232056, "x": 13.612292297041844, "y": 0.035415453572944955, "z": null, "yaw": 3.116483583942296, "pitch": null, "roll": null}, "v": 2.264667511580256, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3645205649590839, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.021540657944638063, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137717.3475013} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2567463906090798, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.340062203351731, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2639277349636506, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137717.3475013} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.05994272232056, "x": 13.612292297041844, "y": 0.035415453572944955, "z": null, "yaw": 3.116483583942296, "pitch": null, "roll": null}, "v": 2.264667511580256, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3645205649590839, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.021540657944638063, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137717.3675013} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2567463906090798, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.340062203351731, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.263732125527373, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137717.3675013} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137717.3775012, "x": 17.363304112778163, "y": 5.041550152054505, "z": null, "yaw": 3.1175298621980656, "pitch": null, "roll": null}, "v": 2.263634460564062, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36442213273873464, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.02153083195540768, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137717.3875012} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2577382327786236, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3317109751502934, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2635368886497425, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137717.3875012} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.16994261741638, "x": 13.363304112778163, "y": 0.04155015205450496, "z": null, "yaw": 3.1175298621980656, "pitch": null, "roll": null}, "v": 2.263634460564062, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36442213273873464, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.02153083195540768, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137717.4075012} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25725842714617797, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3317109751502934, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2634659448195, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137717.4075012} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.16994261741638, "x": 13.363304112778163, "y": 0.04155015205450496, "z": null, "yaw": 3.1175298621980656, "pitch": null, "roll": null}, "v": 2.263634460564062, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36442213273873464, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.02153083195540768, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137717.4275012} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25725842714617797, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3317109751502934, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2633351889656423, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137717.4275012} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.16994261741638, "x": 13.363304112778163, "y": 0.04155015205450496, "z": null, "yaw": 3.1175298621980656, "pitch": null, "roll": null}, "v": 2.263634460564062, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36442213273873464, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.02153083195540768, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137717.4475012} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25725842714617797, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3317109751502934, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2632046821284066, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137717.4475012} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.16994261741638, "x": 13.363304112778163, "y": 0.04155015205450496, "z": null, "yaw": 3.1175298621980656, "pitch": null, "roll": null}, "v": 2.263634460564062, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36442213273873464, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.02153083195540768, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137717.4675012} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25725842714617797, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3317109751502934, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2630744238267466, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137717.4675012} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137717.4875011, "x": 17.114407654438786, "y": 5.047422020554624, "z": null, "yaw": 3.1185761404538352, "pitch": null, "roll": null}, "v": 2.2629444135805703, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3643563948685836, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.021524268490368717, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137717.4875011} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25727910461132797, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3056255343091239, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2629444135805703, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137717.4875011} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.27994251251221, "x": 13.114407654438786, "y": 0.047422020554623856, "z": null, "yaw": 3.1185761404538352, "pitch": null, "roll": null}, "v": 2.2629444135805703, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3643563948685836, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.021524268490368717, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137717.5075011} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2572642495923005, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3056255343091239, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.262817234362829, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137717.5075011} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.27994251251221, "x": 13.114407654438786, "y": 0.047422020554623856, "z": null, "yaw": 3.1185761404538352, "pitch": null, "roll": null}, "v": 2.2629444135805703, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3643563948685836, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.021524268490368717, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137717.527501} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2572642495923005, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3056255343091239, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2626884413308597, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137717.527501} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.27994251251221, "x": 13.114407654438786, "y": 0.047422020554623856, "z": null, "yaw": 3.1185761404538352, "pitch": null, "roll": null}, "v": 2.2629444135805703, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3643563948685836, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.021524268490368717, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137717.547501} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2572642495923005, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3056255343091239, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2625598935441245, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137717.547501} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.27994251251221, "x": 13.114407654438786, "y": 0.047422020554623856, "z": null, "yaw": 3.1185761404538352, "pitch": null, "roll": null}, "v": 2.2629444135805703, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3643563948685836, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.021524268490368717, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137717.567501} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2572642495923005, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3056255343091239, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2624315905290255, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137717.567501} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.27994251251221, "x": 13.114407654438786, "y": 0.047422020554623856, "z": null, "yaw": 3.1185761404538352, "pitch": null, "roll": null}, "v": 2.2629444135805703, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3643563948685836, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.021524268490368717, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137717.587501} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2572642495923005, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3056255343091239, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2623035318129046, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137717.587501} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137717.597501, "x": 16.865582231689675, "y": 5.05303173434803, "z": null, "yaw": 3.119622418709605, "pitch": null, "roll": null}, "v": 2.2622395939195115, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36428925949894675, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.02151756451322687, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137717.607501} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25937239184534605, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3312616585533255, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2621757169240406, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137717.607501} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.38994240760803, "x": 12.865582231689675, "y": 0.05303173434803021, "z": null, "yaw": 3.119622418709605, "pitch": null, "roll": null}, "v": 2.2622395939195115, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36428925949894675, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.02151756451322687, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137717.627501} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25836339900217314, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3312616585533255, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.262311537681427, "gear": 1, "accelerator_pedal_position": 0.25937239184534605, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137717.627501} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.38994240760803, "x": 12.865582231689675, "y": 0.05303173434803021, "z": null, "yaw": 3.119622418709605, "pitch": null, "roll": null}, "v": 2.2622395939195115, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36428925949894675, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.02151756451322687, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137717.647501} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25836339900217314, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3312616585533255, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.262321035794857, "gear": 1, "accelerator_pedal_position": 0.25836339900217314, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137717.647501} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.38994240760803, "x": 12.865582231689675, "y": 0.05303173434803021, "z": null, "yaw": 3.119622418709605, "pitch": null, "roll": null}, "v": 2.2622395939195115, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36428925949894675, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.02151756451322687, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137717.667501} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25836339900217314, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3312616585533255, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2623305158236864, "gear": 1, "accelerator_pedal_position": 0.25836339900217314, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137717.667501} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.38994240760803, "x": 12.865582231689675, "y": 0.05303173434803021, "z": null, "yaw": 3.119622418709605, "pitch": null, "roll": null}, "v": 2.2622395939195115, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36428925949894675, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.02151756451322687, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137717.687501} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25836339900217314, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3312616585533255, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2623399778023128, "gear": 1, "accelerator_pedal_position": 0.25836339900217314, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137717.687501} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137717.707501, "x": 16.6167868876548, "y": 5.058380326461812, "z": null, "yaw": 3.1206686969653745, "pitch": null, "roll": null}, "v": 2.262349421765068, "accelerator_pedal_position": 0.25836339900217314, "brake_pedal_position": 0.0, "acceleration": 0.0004715236137212142, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.021518609154014903, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137717.707501} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2580326047919743, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2911494077187369, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.262349421765068, "gear": 1, "accelerator_pedal_position": 0.25836339900217314, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137717.707501} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.49994230270386, "x": 12.6167868876548, "y": 0.058380326461811904, "z": null, "yaw": 3.1206686969653745, "pitch": null, "roll": null}, "v": 2.262349421765068, "accelerator_pedal_position": 0.25836339900217314, "brake_pedal_position": 0.0, "acceleration": 0.0004715236137212142, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.021518609154014903, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137717.727501} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25819092292551116, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2911494077187369, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.262317518161892, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137717.727501} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.49994230270386, "x": 12.6167868876548, "y": 0.058380326461811904, "z": null, "yaw": 3.1206686969653745, "pitch": null, "roll": null}, "v": 2.262349421765068, "accelerator_pedal_position": 0.25836339900217314, "brake_pedal_position": 0.0, "acceleration": 0.0004715236137212142, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.021518609154014903, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137717.747501} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25819092292551116, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2911494077187369, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.262305455646109, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137717.747501} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.49994230270386, "x": 12.6167868876548, "y": 0.058380326461811904, "z": null, "yaw": 3.1206686969653745, "pitch": null, "roll": null}, "v": 2.262349421765068, "accelerator_pedal_position": 0.25836339900217314, "brake_pedal_position": 0.0, "acceleration": 0.0004715236137212142, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.021518609154014903, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137717.7675009} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25819092292551116, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2911494077187369, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.262293416097551, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137717.7675009} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.49994230270386, "x": 12.6167868876548, "y": 0.058380326461811904, "z": null, "yaw": 3.1206686969653745, "pitch": null, "roll": null}, "v": 2.262349421765068, "accelerator_pedal_position": 0.25836339900217314, "brake_pedal_position": 0.0, "acceleration": 0.0004715236137212142, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.021518609154014903, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137717.7875009} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25819092292551116, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2911494077187369, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2622813994724313, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137717.7875009} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.49994230270386, "x": 12.6167868876548, "y": 0.058380326461811904, "z": null, "yaw": 3.1206686969653745, "pitch": null, "roll": null}, "v": 2.262349421765068, "accelerator_pedal_position": 0.25836339900217314, "brake_pedal_position": 0.0, "acceleration": 0.0004715236137212142, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.021518609154014903, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137717.8075008} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25819092292551116, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2911494077187369, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.262269405727045, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137717.8075008} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137717.8175008, "x": 16.367985686359667, "y": 5.063468616856231, "z": null, "yaw": 3.121714975221144, "pitch": null, "roll": null}, "v": 2.262263417420617, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36429152856902697, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.021517791113328532, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137717.8275008} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2582206135353783, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2558956918678588, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.262257434817771, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137717.8275008} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.60994219779968, "x": 12.367985686359667, "y": 0.06346861685623129, "z": null, "yaw": 3.121714975221144, "pitch": null, "roll": null}, "v": 2.262263417420617, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36429152856902697, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.021517791113328532, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137717.8475008} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2582058510219083, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2558956918678588, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2622491962598787, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137717.8475008} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.60994219779968, "x": 12.367985686359667, "y": 0.06346861685623129, "z": null, "yaw": 3.121714975221144, "pitch": null, "roll": null}, "v": 2.262263417420617, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36429152856902697, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.021517791113328532, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137717.8675008} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2582058510219083, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2558956918678588, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.262239128952746, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137717.8675008} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.60994219779968, "x": 12.367985686359667, "y": 0.06346861685623129, "z": null, "yaw": 3.121714975221144, "pitch": null, "roll": null}, "v": 2.262263417420617, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36429152856902697, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.021517791113328532, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137717.8875008} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2582058510219083, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2558956918678588, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2622290808136603, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137717.8875008} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.60994219779968, "x": 12.367985686359667, "y": 0.06346861685623129, "z": null, "yaw": 3.121714975221144, "pitch": null, "roll": null}, "v": 2.262263417420617, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36429152856902697, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.021517791113328532, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137717.9075007} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2582058510219083, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2558956918678588, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2622190518060856, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137717.9075007} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137717.9275007, "x": 16.119186264224354, "y": 5.068296453790032, "z": null, "yaw": 3.122761253476914, "pitch": null, "roll": null}, "v": 2.2622090418935556, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3642863495869274, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.02151727391395026, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137717.9275007} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2596142224440413, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2663228420803956, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2622090418935556, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137717.9275007} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.71994209289551, "x": 12.119186264224354, "y": 0.06829645379003235, "z": null, "yaw": 3.122761253476914, "pitch": null, "roll": null}, "v": 2.2622090418935556, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3642863495869274, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.02151727391395026, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137717.9475007} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25894317446155257, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2663228420803956, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2623750136297645, "gear": 1, "accelerator_pedal_position": 0.2596142224440413, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137717.9475007} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.71994209289551, "x": 12.119186264224354, "y": 0.06829645379003235, "z": null, "yaw": 3.122761253476914, "pitch": null, "roll": null}, "v": 2.2622090418935556, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3642863495869274, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.02151727391395026, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137717.9675007} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25894317446155257, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2663228420803956, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.262456828301423, "gear": 1, "accelerator_pedal_position": 0.25894317446155257, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137717.9675007} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.71994209289551, "x": 12.119186264224354, "y": 0.06829645379003235, "z": null, "yaw": 3.122761253476914, "pitch": null, "roll": null}, "v": 2.2622090418935556, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3642863495869274, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.02151727391395026, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137717.9875007} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25894317446155257, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2663228420803956, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.262538487192439, "gear": 1, "accelerator_pedal_position": 0.25894317446155257, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137717.9875007} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.71994209289551, "x": 12.119186264224354, "y": 0.06829645379003235, "z": null, "yaw": 3.122761253476914, "pitch": null, "roll": null}, "v": 2.2622090418935556, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3642863495869274, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.02151727391395026, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137718.0075006} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25894317446155257, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2663228420803956, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2626199905967637, "gear": 1, "accelerator_pedal_position": 0.25894317446155257, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137718.0075006} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.71994209289551, "x": 12.119186264224354, "y": 0.06829645379003235, "z": null, "yaw": 3.122761253476914, "pitch": null, "roll": null}, "v": 2.2622090418935556, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3642863495869274, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.02151727391395026, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137718.0275006} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25894317446155257, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2663228420803956, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2627013388078034, "gear": 1, "accelerator_pedal_position": 0.25894317446155257, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137718.0275006} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137718.0375006, "x": 15.870354738163003, "y": 5.072864468488833, "z": null, "yaw": 3.1238075317326834, "pitch": null, "roll": null}, "v": 2.262741954807382, "accelerator_pedal_position": 0.25894317446155257, "brake_pedal_position": 0.0, "acceleration": 0.004057731103879025, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.021522342779349845, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137718.0475006} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25959639726090084, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2461243259165546, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.262782532118421, "gear": 1, "accelerator_pedal_position": 0.25894317446155257, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137718.0475006} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.82994198799133, "x": 11.870354738163003, "y": 0.07286446848883266, "z": null, "yaw": 3.1238075317326834, "pitch": null, "roll": null}, "v": 2.262741954807382, "accelerator_pedal_position": 0.25894317446155257, "brake_pedal_position": 0.0, "acceleration": 0.004057731103879025, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.021522342779349845, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137718.0675006} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2592892060368146, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2461243259165546, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.262945184780881, "gear": 1, "accelerator_pedal_position": 0.25959639726090084, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137718.0675006} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.82994198799133, "x": 11.870354738163003, "y": 0.07286446848883266, "z": null, "yaw": 3.1238075317326834, "pitch": null, "roll": null}, "v": 2.262741954807382, "accelerator_pedal_position": 0.25894317446155257, "brake_pedal_position": 0.0, "acceleration": 0.004057731103879025, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.021522342779349845, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137718.0875006} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2592892060368146, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2461243259165546, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2630691470977458, "gear": 1, "accelerator_pedal_position": 0.2592892060368146, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137718.0875006} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.82994198799133, "x": 11.870354738163003, "y": 0.07286446848883266, "z": null, "yaw": 3.1238075317326834, "pitch": null, "roll": null}, "v": 2.262741954807382, "accelerator_pedal_position": 0.25894317446155257, "brake_pedal_position": 0.0, "acceleration": 0.004057731103879025, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.021522342779349845, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137718.1075006} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2592892060368146, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2461243259165546, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.263192873352204, "gear": 1, "accelerator_pedal_position": 0.2592892060368146, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137718.1075006} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.82994198799133, "x": 11.870354738163003, "y": 0.07286446848883266, "z": null, "yaw": 3.1238075317326834, "pitch": null, "roll": null}, "v": 2.262741954807382, "accelerator_pedal_position": 0.25894317446155257, "brake_pedal_position": 0.0, "acceleration": 0.004057731103879025, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.021522342779349845, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137718.1275005} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2592892060368146, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2461243259165546, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2633163639876708, "gear": 1, "accelerator_pedal_position": 0.2592892060368146, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137718.1275005} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137718.1475005, "x": 15.621455213048499, "y": 5.077173228560555, "z": null, "yaw": 3.124853809988453, "pitch": null, "roll": null}, "v": 2.263439619446752, "accelerator_pedal_position": 0.2592892060368146, "brake_pedal_position": 0.0, "acceleration": 0.0061539676489409945, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.02152897870064067, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137718.1475005} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2606391554189126, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1976382835433428, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.263439619446752, "gear": 1, "accelerator_pedal_position": 0.2592892060368146, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137718.1475005} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.93994188308716, "x": 11.621455213048499, "y": 0.07717322856055464, "z": null, "yaw": 3.124853809988453, "pitch": null, "roll": null}, "v": 2.263439619446752, "accelerator_pedal_position": 0.2592892060368146, "brake_pedal_position": 0.0, "acceleration": 0.0061539676489409945, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.02152897870064067, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137718.1675005} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2600013857412493, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1976382835433428, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2637313034622277, "gear": 1, "accelerator_pedal_position": 0.2606391554189126, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137718.1675005} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.93994188308716, "x": 11.621455213048499, "y": 0.07717322856055464, "z": null, "yaw": 3.124853809988453, "pitch": null, "roll": null}, "v": 2.263439619446752, "accelerator_pedal_position": 0.2592892060368146, "brake_pedal_position": 0.0, "acceleration": 0.0061539676489409945, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.02152897870064067, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137718.1875005} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2600013857412493, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1976382835433428, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2639427487176027, "gear": 1, "accelerator_pedal_position": 0.2600013857412493, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137718.1875005} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.93994188308716, "x": 11.621455213048499, "y": 0.07717322856055464, "z": null, "yaw": 3.124853809988453, "pitch": null, "roll": null}, "v": 2.263439619446752, "accelerator_pedal_position": 0.2592892060368146, "brake_pedal_position": 0.0, "acceleration": 0.0061539676489409945, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.02152897870064067, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137718.2075005} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2600013857412493, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1976382835433428, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.264153791244161, "gear": 1, "accelerator_pedal_position": 0.2600013857412493, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137718.2075005} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.93994188308716, "x": 11.621455213048499, "y": 0.07717322856055464, "z": null, "yaw": 3.124853809988453, "pitch": null, "roll": null}, "v": 2.263439619446752, "accelerator_pedal_position": 0.2592892060368146, "brake_pedal_position": 0.0, "acceleration": 0.0061539676489409945, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.02152897870064067, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137718.2275004} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2600013857412493, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1976382835433428, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.264364431791153, "gear": 1, "accelerator_pedal_position": 0.2600013857412493, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137718.2275004} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.93994188308716, "x": 11.621455213048499, "y": 0.07717322856055464, "z": null, "yaw": 3.124853809988453, "pitch": null, "roll": null}, "v": 2.263439619446752, "accelerator_pedal_position": 0.2592892060368146, "brake_pedal_position": 0.0, "acceleration": 0.0061539676489409945, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.02152897870064067, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137718.2475004} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2600013857412493, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1976382835433428, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2645746711065025, "gear": 1, "accelerator_pedal_position": 0.2600013857412493, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137718.2475004} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137718.2575004, "x": 15.37244409612488, "y": 5.081223307246686, "z": null, "yaw": 3.1259000882442227, "pitch": null, "roll": null}, "v": 2.2646796405356757, "accelerator_pedal_position": 0.2600013857412493, "brake_pedal_position": 0.0, "acceleration": 0.010486940113456356, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.021540773310659164, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137718.2675004} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2645683021670035, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1118047143538408, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2647845099368102, "gear": 1, "accelerator_pedal_position": 0.2600013857412493, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137718.2675004} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.04994177818298, "x": 11.37244409612488, "y": 0.08122330724668636, "z": null, "yaw": 3.1259000882442227, "pitch": null, "roll": null}, "v": 2.2646796405356757, "accelerator_pedal_position": 0.2600013857412493, "brake_pedal_position": 0.0, "acceleration": 0.010486940113456356, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.021540773310659164, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137718.2875004} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26240258093482544, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1118047143538408, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2655645415617895, "gear": 1, "accelerator_pedal_position": 0.2645683021670035, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137718.2875004} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.04994177818298, "x": 11.37244409612488, "y": 0.08122330724668636, "z": null, "yaw": 3.1259000882442227, "pitch": null, "roll": null}, "v": 2.2646796405356757, "accelerator_pedal_position": 0.2600013857412493, "brake_pedal_position": 0.0, "acceleration": 0.010486940113456356, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.021540773310659164, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137718.3075004} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26240258093482544, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1118047143538408, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2660725009055054, "gear": 1, "accelerator_pedal_position": 0.26240258093482544, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137718.3075004} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.04994177818298, "x": 11.37244409612488, "y": 0.08122330724668636, "z": null, "yaw": 3.1259000882442227, "pitch": null, "roll": null}, "v": 2.2646796405356757, "accelerator_pedal_position": 0.2600013857412493, "brake_pedal_position": 0.0, "acceleration": 0.010486940113456356, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.021540773310659164, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137718.3275003} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26240258093482544, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1118047143538408, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2665794923481286, "gear": 1, "accelerator_pedal_position": 0.26240258093482544, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137718.3275003} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.04994177818298, "x": 11.37244409612488, "y": 0.08122330724668636, "z": null, "yaw": 3.1259000882442227, "pitch": null, "roll": null}, "v": 2.2646796405356757, "accelerator_pedal_position": 0.2600013857412493, "brake_pedal_position": 0.0, "acceleration": 0.010486940113456356, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.021540773310659164, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137718.3475003} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26240258093482544, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1118047143538408, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2670855176311977, "gear": 1, "accelerator_pedal_position": 0.26240258093482544, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137718.3475003} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137718.3675003, "x": 15.123210400919291, "y": 5.085016156692972, "z": null, "yaw": 3.1269463664999924, "pitch": null, "roll": null}, "v": 2.2675905784935204, "accelerator_pedal_position": 0.26240258093482544, "brake_pedal_position": 0.0, "acceleration": 0.025216931601257098, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.021568461047833543, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137718.3675003} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2663346929124689, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0271784664407477, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2675905784935204, "gear": 1, "accelerator_pedal_position": 0.26240258093482544, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137718.3675003} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.15994167327881, "x": 11.123210400919291, "y": 0.08501615669297191, "z": null, "yaw": 3.1269463664999924, "pitch": null, "roll": null}, "v": 2.2675905784935204, "accelerator_pedal_position": 0.26240258093482544, "brake_pedal_position": 0.0, "acceleration": 0.025216931601257098, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.021568461047833543, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137718.3875003} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26448339892951644, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0271784664407477, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2685859563161968, "gear": 1, "accelerator_pedal_position": 0.2663346929124689, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137718.3875003} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.15994167327881, "x": 11.123210400919291, "y": 0.08501615669297191, "z": null, "yaw": 3.1269463664999924, "pitch": null, "roll": null}, "v": 2.2675905784935204, "accelerator_pedal_position": 0.26240258093482544, "brake_pedal_position": 0.0, "acceleration": 0.025216931601257098, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.021568461047833543, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137718.4075003} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26448339892951644, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0271784664407477, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.269728679408047, "gear": 1, "accelerator_pedal_position": 0.26448339892951644, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137718.4075003} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.15994167327881, "x": 11.123210400919291, "y": 0.08501615669297191, "z": null, "yaw": 3.1269463664999924, "pitch": null, "roll": null}, "v": 2.2675905784935204, "accelerator_pedal_position": 0.26240258093482544, "brake_pedal_position": 0.0, "acceleration": 0.025216931601257098, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.021568461047833543, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137718.4275002} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26448339892951644, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0271784664407477, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.270108860673625, "gear": 1, "accelerator_pedal_position": 0.26448339892951644, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137718.4275002} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.15994167327881, "x": 11.123210400919291, "y": 0.08501615669297191, "z": null, "yaw": 3.1269463664999924, "pitch": null, "roll": null}, "v": 2.2675905784935204, "accelerator_pedal_position": 0.26240258093482544, "brake_pedal_position": 0.0, "acceleration": 0.025216931601257098, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.021568461047833543, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137718.4475002} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26448339892951644, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0271784664407477, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.270868135461659, "gear": 1, "accelerator_pedal_position": 0.26448339892951644, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137718.4475002} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.15994167327881, "x": 11.123210400919291, "y": 0.08501615669297191, "z": null, "yaw": 3.1269463664999924, "pitch": null, "roll": null}, "v": 2.2675905784935204, "accelerator_pedal_position": 0.26240258093482544, "brake_pedal_position": 0.0, "acceleration": 0.025216931601257098, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.021568461047833543, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137718.4575002} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26448339892951644, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0271784664407477, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.271625962038638, "gear": 1, "accelerator_pedal_position": 0.26448339892951644, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137718.4575002} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137718.4775002, "x": 14.873568999345759, "y": 5.088553947085199, "z": null, "yaw": 3.127992644755762, "pitch": null, "roll": null}, "v": 2.2720043330395727, "accelerator_pedal_position": 0.26448339892951644, "brake_pedal_position": 0.0, "acceleration": 0.0378009897639931, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.02161044300608655, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137718.4875002} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26928401995374346, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8956285198556073, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2723823429372128, "gear": 1, "accelerator_pedal_position": 0.26448339892951644, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137718.4875002} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.269941568374634, "x": 10.873568999345759, "y": 0.08855394708519881, "z": null, "yaw": 3.127992644755762, "pitch": null, "roll": null}, "v": 2.2720043330395727, "accelerator_pedal_position": 0.26448339892951644, "brake_pedal_position": 0.0, "acceleration": 0.0378009897639931, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.02161044300608655, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137718.5075002} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2670300891442, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8956285198556073, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.273737071902892, "gear": 1, "accelerator_pedal_position": 0.26928401995374346, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137718.5075002} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.269941568374634, "x": 10.873568999345759, "y": 0.08855394708519881, "z": null, "yaw": 3.127992644755762, "pitch": null, "roll": null}, "v": 2.2720043330395727, "accelerator_pedal_position": 0.26448339892951644, "brake_pedal_position": 0.0, "acceleration": 0.0378009897639931, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.02161044300608655, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137718.5275002} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2670300891442, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8956285198556073, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2748076086007445, "gear": 1, "accelerator_pedal_position": 0.2670300891442, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137718.5275002} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.269941568374634, "x": 10.873568999345759, "y": 0.08855394708519881, "z": null, "yaw": 3.127992644755762, "pitch": null, "roll": null}, "v": 2.2720043330395727, "accelerator_pedal_position": 0.26448339892951644, "brake_pedal_position": 0.0, "acceleration": 0.0378009897639931, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.02161044300608655, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137718.5475001} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2670300891442, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8956285198556073, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.275876101746716, "gear": 1, "accelerator_pedal_position": 0.2670300891442, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137718.5475001} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.269941568374634, "x": 10.873568999345759, "y": 0.08855394708519881, "z": null, "yaw": 3.127992644755762, "pitch": null, "roll": null}, "v": 2.2720043330395727, "accelerator_pedal_position": 0.26448339892951644, "brake_pedal_position": 0.0, "acceleration": 0.0378009897639931, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.02161044300608655, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137718.5675} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2670300891442, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8956285198556073, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2769425547852986, "gear": 1, "accelerator_pedal_position": 0.2670300891442, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137718.5675} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137718.5875, "x": 14.62336746662663, "y": 5.091837829577894, "z": null, "yaw": 3.1290389230115316, "pitch": null, "roll": null}, "v": 2.2780069711570214, "accelerator_pedal_position": 0.2670300891442, "brake_pedal_position": 0.0, "acceleration": 0.05314455098699905, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.021667537821900455, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137718.5875} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2681195409723345, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8899851670493583, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2780069711570214, "gear": 1, "accelerator_pedal_position": 0.2670300891442, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137718.5875} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.37994146347046, "x": 10.62336746662663, "y": 0.09183782957789433, "z": null, "yaw": 3.1290389230115316, "pitch": null, "roll": null}, "v": 2.2780069711570214, "accelerator_pedal_position": 0.2670300891442, "brake_pedal_position": 0.0, "acceleration": 0.05314455098699905, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.021667537821900455, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137718.6075} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2676444305401714, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8899851670493583, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2792054707016582, "gear": 1, "accelerator_pedal_position": 0.2681195409723345, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137718.6075} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.37994146347046, "x": 10.62336746662663, "y": 0.09183782957789433, "z": null, "yaw": 3.1290389230115316, "pitch": null, "roll": null}, "v": 2.2780069711570214, "accelerator_pedal_position": 0.2670300891442, "brake_pedal_position": 0.0, "acceleration": 0.05314455098699905, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.021667537821900455, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137718.6275} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2676444305401714, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8899851670493583, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2803423199171973, "gear": 1, "accelerator_pedal_position": 0.2676444305401714, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137718.6275} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.37994146347046, "x": 10.62336746662663, "y": 0.09183782957789433, "z": null, "yaw": 3.1290389230115316, "pitch": null, "roll": null}, "v": 2.2780069711570214, "accelerator_pedal_position": 0.2670300891442, "brake_pedal_position": 0.0, "acceleration": 0.05314455098699905, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.021667537821900455, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137718.6475} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2676444305401714, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8899851670493583, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2814769964897064, "gear": 1, "accelerator_pedal_position": 0.2676444305401714, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137718.6475} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.37994146347046, "x": 10.62336746662663, "y": 0.09183782957789433, "z": null, "yaw": 3.1290389230115316, "pitch": null, "roll": null}, "v": 2.2780069711570214, "accelerator_pedal_position": 0.2670300891442, "brake_pedal_position": 0.0, "acceleration": 0.05314455098699905, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.021667537821900455, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137718.6675} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2676444305401714, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8899851670493583, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2826095040565937, "gear": 1, "accelerator_pedal_position": 0.2676444305401714, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137718.6675} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.37994146347046, "x": 10.62336746662663, "y": 0.09183782957789433, "z": null, "yaw": 3.1290389230115316, "pitch": null, "roll": null}, "v": 2.2780069711570214, "accelerator_pedal_position": 0.2670300891442, "brake_pedal_position": 0.0, "acceleration": 0.05314455098699905, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.021667537821900455, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137718.6875} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2676444305401714, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8899851670493583, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2837398462512657, "gear": 1, "accelerator_pedal_position": 0.2676444305401714, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137718.6875} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137718.6975, "x": 14.372486876015575, "y": 5.094868090468963, "z": null, "yaw": 3.1300852012673013, "pitch": null, "roll": null}, "v": 2.284304206468365, "accelerator_pedal_position": 0.2676444305401714, "brake_pedal_position": 0.0, "acceleration": 0.05638202347576221, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.02172743473442511, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137718.7075} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26921513197115743, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8103004728188956, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2848680267031227, "gear": 1, "accelerator_pedal_position": 0.2676444305401714, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137718.7075} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.489941358566284, "x": 10.372486876015575, "y": 0.09486809046896294, "z": null, "yaw": 3.1300852012673013, "pitch": null, "roll": null}, "v": 2.284304206468365, "accelerator_pedal_position": 0.2676444305401714, "brake_pedal_position": 0.0, "acceleration": 0.05638202347576221, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.02172743473442511, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137718.7275} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2685130575093849, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8103004728188956, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.286190292759417, "gear": 1, "accelerator_pedal_position": 0.26921513197115743, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137718.7275} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.489941358566284, "x": 10.372486876015575, "y": 0.09486809046896294, "z": null, "yaw": 3.1300852012673013, "pitch": null, "roll": null}, "v": 2.284304206468365, "accelerator_pedal_position": 0.2676444305401714, "brake_pedal_position": 0.0, "acceleration": 0.05638202347576221, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.02172743473442511, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137718.7475} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2685130575093849, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8103004728188956, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2874223114564343, "gear": 1, "accelerator_pedal_position": 0.2685130575093849, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137718.7475} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.489941358566284, "x": 10.372486876015575, "y": 0.09486809046896294, "z": null, "yaw": 3.1300852012673013, "pitch": null, "roll": null}, "v": 2.284304206468365, "accelerator_pedal_position": 0.2676444305401714, "brake_pedal_position": 0.0, "acceleration": 0.05638202347576221, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.02172743473442511, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137718.7675} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2685130575093849, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8103004728188956, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2886519721571315, "gear": 1, "accelerator_pedal_position": 0.2685130575093849, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137718.7675} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.489941358566284, "x": 10.372486876015575, "y": 0.09486809046896294, "z": null, "yaw": 3.1300852012673013, "pitch": null, "roll": null}, "v": 2.284304206468365, "accelerator_pedal_position": 0.2676444305401714, "brake_pedal_position": 0.0, "acceleration": 0.05638202347576221, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.02172743473442511, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137718.7875} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2685130575093849, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8103004728188956, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2898792787700106, "gear": 1, "accelerator_pedal_position": 0.2685130575093849, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137718.7875} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137718.8075, "x": 14.120887721860221, "y": 5.097643747547057, "z": null, "yaw": 3.131131479523071, "pitch": null, "roll": null}, "v": 2.291104235199561, "accelerator_pedal_position": 0.2685130575093849, "brake_pedal_position": 0.0, "acceleration": 0.06115981150818395, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.02179211402715281, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137718.8075} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27015020839059245, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6416796218094053, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.291104235199561, "gear": 1, "accelerator_pedal_position": 0.2685130575093849, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137718.8075} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.59994125366211, "x": 10.120887721860221, "y": 0.09764374754705685, "z": null, "yaw": 3.131131479523071, "pitch": null, "roll": null}, "v": 2.291104235199561, "accelerator_pedal_position": 0.2685130575093849, "brake_pedal_position": 0.0, "acceleration": 0.06115981150818395, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.02179211402715281, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137718.8274999} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26942022231298896, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6416796218094053, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.292531391145837, "gear": 1, "accelerator_pedal_position": 0.27015020839059245, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137718.8274999} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.59994125366211, "x": 10.120887721860221, "y": 0.09764374754705685, "z": null, "yaw": 3.131131479523071, "pitch": null, "roll": null}, "v": 2.291104235199561, "accelerator_pedal_position": 0.2685130575093849, "brake_pedal_position": 0.0, "acceleration": 0.06115981150818395, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.02179211402715281, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137718.8474998} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26942022231298896, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6416796218094053, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.293864608208609, "gear": 1, "accelerator_pedal_position": 0.26942022231298896, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137718.8474998} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.59994125366211, "x": 10.120887721860221, "y": 0.09764374754705685, "z": null, "yaw": 3.131131479523071, "pitch": null, "roll": null}, "v": 2.291104235199561, "accelerator_pedal_position": 0.2685130575093849, "brake_pedal_position": 0.0, "acceleration": 0.06115981150818395, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.02179211402715281, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137718.8674998} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26942022231298896, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6416796218094053, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.295195270169759, "gear": 1, "accelerator_pedal_position": 0.26942022231298896, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137718.8674998} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.59994125366211, "x": 10.120887721860221, "y": 0.09764374754705685, "z": null, "yaw": 3.131131479523071, "pitch": null, "roll": null}, "v": 2.291104235199561, "accelerator_pedal_position": 0.2685130575093849, "brake_pedal_position": 0.0, "acceleration": 0.06115981150818395, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.02179211402715281, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137718.8874998} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26942022231298896, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6416796218094053, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2965233812181975, "gear": 1, "accelerator_pedal_position": 0.26942022231298896, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137718.8874998} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.59994125366211, "x": 10.120887721860221, "y": 0.09764374754705685, "z": null, "yaw": 3.131131479523071, "pitch": null, "roll": null}, "v": 2.291104235199561, "accelerator_pedal_position": 0.2685130575093849, "brake_pedal_position": 0.0, "acceleration": 0.06115981150818395, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.02179211402715281, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137718.9074998} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26942022231298896, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6416796218094053, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2978489455388758, "gear": 1, "accelerator_pedal_position": 0.26942022231298896, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137718.9074998} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137718.9174998, "x": 13.868503709063745, "y": 5.100163965133131, "z": null, "yaw": 3.1321777577788406, "pitch": null, "roll": null}, "v": 2.2985107739830166, "accelerator_pedal_position": 0.26942022231298896, "brake_pedal_position": 0.0, "acceleration": 0.06611933297586997, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.021862562213331264, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137718.9274998} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.269884164264886, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6343025352389301, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2991719673127755, "gear": 1, "accelerator_pedal_position": 0.26942022231298896, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137718.9274998} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.709941148757935, "x": 9.868503709063745, "y": 0.10016396513313097, "z": null, "yaw": 3.1321777577788406, "pitch": null, "roll": null}, "v": 2.2985107739830166, "accelerator_pedal_position": 0.26942022231298896, "brake_pedal_position": 0.0, "acceleration": 0.06611933297586997, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.021862562213331264, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137718.9474998} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26971735438007016, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6343025352389301, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3005504156252594, "gear": 1, "accelerator_pedal_position": 0.269884164264886, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137718.9474998} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.709941148757935, "x": 9.868503709063745, "y": 0.10016396513313097, "z": null, "yaw": 3.1321777577788406, "pitch": null, "roll": null}, "v": 2.2985107739830166, "accelerator_pedal_position": 0.26942022231298896, "brake_pedal_position": 0.0, "acceleration": 0.06611933297586997, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.021862562213331264, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137718.9674997} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26971735438007016, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6343025352389301, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.302581882373197, "gear": 1, "accelerator_pedal_position": 0.26971735438007016, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137718.9674997} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.709941148757935, "x": 9.868503709063745, "y": 0.10016396513313097, "z": null, "yaw": 3.1321777577788406, "pitch": null, "roll": null}, "v": 2.2985107739830166, "accelerator_pedal_position": 0.26942022231298896, "brake_pedal_position": 0.0, "acceleration": 0.06611933297586997, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.021862562213331264, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137718.9774997} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26971735438007016, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6343025352389301, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.302581882373197, "gear": 1, "accelerator_pedal_position": 0.26971735438007016, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137718.9774997} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.709941148757935, "x": 9.868503709063745, "y": 0.10016396513313097, "z": null, "yaw": 3.1321777577788406, "pitch": null, "roll": null}, "v": 2.2985107739830166, "accelerator_pedal_position": 0.26942022231298896, "brake_pedal_position": 0.0, "acceleration": 0.06611933297586997, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.021862562213331264, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137719.0074997} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26971735438007016, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6343025352389301, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3046075013832903, "gear": 1, "accelerator_pedal_position": 0.26971735438007016, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137719.0074997} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137719.0274997, "x": 13.615304939402504, "y": 5.102427377992972, "z": null, "yaw": 3.13322403603461, "pitch": null, "roll": null}, "v": 2.305954672412955, "accelerator_pedal_position": 0.26971735438007016, "brake_pedal_position": 0.0, "acceleration": 0.06726146174255931, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.021933365750289344, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137719.0274997} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27010283799376883, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6265618334199268, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.305954672412955, "gear": 1, "accelerator_pedal_position": 0.26971735438007016, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137719.0274997} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.81994104385376, "x": 9.615304939402504, "y": 0.10242737799297164, "z": null, "yaw": 3.13322403603461, "pitch": null, "roll": null}, "v": 2.305954672412955, "accelerator_pedal_position": 0.26971735438007016, "brake_pedal_position": 0.0, "acceleration": 0.06726146174255931, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.021933365750289344, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137719.0474997} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26997374642962113, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6265618334199268, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.307347417382196, "gear": 1, "accelerator_pedal_position": 0.27010283799376883, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137719.0474997} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.81994104385376, "x": 9.615304939402504, "y": 0.10242737799297164, "z": null, "yaw": 3.13322403603461, "pitch": null, "roll": null}, "v": 2.305954672412955, "accelerator_pedal_position": 0.26971735438007016, "brake_pedal_position": 0.0, "acceleration": 0.06726146174255931, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.021933365750289344, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137719.0674996} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26997374642962113, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6265618334199268, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3094073360251204, "gear": 1, "accelerator_pedal_position": 0.26997374642962113, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137719.0674996} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.81994104385376, "x": 9.615304939402504, "y": 0.10242737799297164, "z": null, "yaw": 3.13322403603461, "pitch": null, "roll": null}, "v": 2.305954672412955, "accelerator_pedal_position": 0.26971735438007016, "brake_pedal_position": 0.0, "acceleration": 0.06726146174255931, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.021933365750289344, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137719.0874996} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26997374642962113, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6265618334199268, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3100926552845906, "gear": 1, "accelerator_pedal_position": 0.26997374642962113, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137719.0874996} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.81994104385376, "x": 9.615304939402504, "y": 0.10242737799297164, "z": null, "yaw": 3.13322403603461, "pitch": null, "roll": null}, "v": 2.305954672412955, "accelerator_pedal_position": 0.26971735438007016, "brake_pedal_position": 0.0, "acceleration": 0.06726146174255931, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.021933365750289344, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137719.1074996} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26997374642962113, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6265618334199268, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3114613166153095, "gear": 1, "accelerator_pedal_position": 0.26997374642962113, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137719.1074996} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.81994104385376, "x": 9.615304939402504, "y": 0.10242737799297164, "z": null, "yaw": 3.13322403603461, "pitch": null, "roll": null}, "v": 2.305954672412955, "accelerator_pedal_position": 0.26971735438007016, "brake_pedal_position": 0.0, "acceleration": 0.06726146174255931, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.021933365750289344, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137719.1174996} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26997374642962113, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6265618334199268, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.312144659767032, "gear": 1, "accelerator_pedal_position": 0.26997374642962113, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137719.1174996} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137719.1374996, "x": 13.36127866172958, "y": 5.1044323864732535, "z": null, "yaw": 3.13427031429038, "pitch": null, "roll": null}, "v": 2.3135093737425194, "accelerator_pedal_position": 0.26997374642962113, "brake_pedal_position": 0.0, "acceleration": 0.06813719027406095, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.02200522320237974, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137719.1474996} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2701861054190544, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6196600487551814, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.31419074564526, "gear": 1, "accelerator_pedal_position": 0.26997374642962113, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137719.1474996} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.929940938949585, "x": 9.36127866172958, "y": 0.10443238647325348, "z": null, "yaw": 3.13427031429038, "pitch": null, "roll": null}, "v": 2.3135093737425194, "accelerator_pedal_position": 0.26997374642962113, "brake_pedal_position": 0.0, "acceleration": 0.06813719027406095, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.02200522320237974, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137719.1674995} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27014035134623515, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6196600487551814, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.315578054068945, "gear": 1, "accelerator_pedal_position": 0.2701861054190544, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137719.1674995} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.929940938949585, "x": 9.36127866172958, "y": 0.10443238647325348, "z": null, "yaw": 3.13427031429038, "pitch": null, "roll": null}, "v": 2.3135093737425194, "accelerator_pedal_position": 0.26997374642962113, "brake_pedal_position": 0.0, "acceleration": 0.06813719027406095, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.02200522320237974, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137719.1874995} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27014035134623515, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6196600487551814, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3169569751905015, "gear": 1, "accelerator_pedal_position": 0.27014035134623515, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137719.1874995} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.929940938949585, "x": 9.36127866172958, "y": 0.10443238647325348, "z": null, "yaw": 3.13427031429038, "pitch": null, "roll": null}, "v": 2.3135093737425194, "accelerator_pedal_position": 0.26997374642962113, "brake_pedal_position": 0.0, "acceleration": 0.06813719027406095, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.02200522320237974, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137719.2074995} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27014035134623515, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6196600487551814, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.318333240900431, "gear": 1, "accelerator_pedal_position": 0.27014035134623515, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137719.2074995} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.929940938949585, "x": 9.36127866172958, "y": 0.10443238647325348, "z": null, "yaw": 3.13427031429038, "pitch": null, "roll": null}, "v": 2.3135093737425194, "accelerator_pedal_position": 0.26997374642962113, "brake_pedal_position": 0.0, "acceleration": 0.06813719027406095, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.02200522320237974, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137719.2274995} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27014035134623515, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6196600487551814, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.319706855555027, "gear": 1, "accelerator_pedal_position": 0.27014035134623515, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137719.2274995} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137719.2474995, "x": 13.106419783381085, "y": 5.106177298797799, "z": null, "yaw": 3.1353165925461495, "pitch": null, "roll": null}, "v": 2.3210778235065654, "accelerator_pedal_position": 0.27014035134623515, "brake_pedal_position": 0.0, "acceleration": 0.06844928211090157, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.022077211424361486, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137719.2474995} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2706102093381443, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5658255526698056, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3210778235065654, "gear": 1, "accelerator_pedal_position": 0.27014035134623515, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137719.2474995} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.03994083404541, "x": 9.106419783381085, "y": 0.10617729879779869, "z": null, "yaw": 3.1353165925461495, "pitch": null, "roll": null}, "v": 2.3210778235065654, "accelerator_pedal_position": 0.27014035134623515, "brake_pedal_position": 0.0, "acceleration": 0.06844928211090157, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.022077211424361486, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137719.2674994} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27044202460213357, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5658255526698056, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3225048530329064, "gear": 1, "accelerator_pedal_position": 0.2706102093381443, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137719.2674994} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.03994083404541, "x": 9.106419783381085, "y": 0.10617729879779869, "z": null, "yaw": 3.1353165925461495, "pitch": null, "roll": null}, "v": 2.3210778235065654, "accelerator_pedal_position": 0.27014035134623515, "brake_pedal_position": 0.0, "acceleration": 0.06844928211090157, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.022077211424361486, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137719.2874994} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27044202460213357, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5658255526698056, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.323908118395457, "gear": 1, "accelerator_pedal_position": 0.27044202460213357, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137719.2874994} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.03994083404541, "x": 9.106419783381085, "y": 0.10617729879779869, "z": null, "yaw": 3.1353165925461495, "pitch": null, "roll": null}, "v": 2.3210778235065654, "accelerator_pedal_position": 0.27014035134623515, "brake_pedal_position": 0.0, "acceleration": 0.06844928211090157, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.022077211424361486, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137719.2974994} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27044202460213357, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5658255526698056, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.324608735979618, "gear": 1, "accelerator_pedal_position": 0.27044202460213357, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137719.2974994} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.03994083404541, "x": 9.106419783381085, "y": 0.10617729879779869, "z": null, "yaw": 3.1353165925461495, "pitch": null, "roll": null}, "v": 2.3210778235065654, "accelerator_pedal_position": 0.27014035134623515, "brake_pedal_position": 0.0, "acceleration": 0.06844928211090157, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.022077211424361486, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137719.3174994} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27044202460213357, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5658255526698056, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3267065349963136, "gear": 1, "accelerator_pedal_position": 0.27044202460213357, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137719.3174994} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.03994083404541, "x": 9.106419783381085, "y": 0.10617729879779869, "z": null, "yaw": 3.1353165925461495, "pitch": null, "roll": null}, "v": 2.3210778235065654, "accelerator_pedal_position": 0.27014035134623515, "brake_pedal_position": 0.0, "acceleration": 0.06844928211090157, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.022077211424361486, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137719.3374994} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27044202460213357, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5658255526698056, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.327404451936449, "gear": 1, "accelerator_pedal_position": 0.27044202460213357, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137719.3374994} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137719.3574994, "x": 12.85071782279183, "y": 5.107660436135077, "z": null, "yaw": 3.136362870801919, "pitch": null, "roll": null}, "v": 2.328798265039636, "accelerator_pedal_position": 0.27044202460213357, "brake_pedal_position": 0.0, "acceleration": 0.06958972691883669, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.02215064533437038, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137719.3674994} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2752669778385002, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.42751272564130927, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.329494162308824, "gear": 1, "accelerator_pedal_position": 0.27044202460213357, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137719.3674994} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.149940729141235, "x": 8.85071782279183, "y": 0.10766043613507659, "z": null, "yaw": 3.136362870801919, "pitch": null, "roll": null}, "v": 2.328798265039636, "accelerator_pedal_position": 0.27044202460213357, "brake_pedal_position": 0.0, "acceleration": 0.06958972691883669, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.02215064533437038, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137719.3774993} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2730261428382777, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.42751272564130927, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3304909470373527, "gear": 1, "accelerator_pedal_position": 0.2752669778385002, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137719.3774993} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.149940729141235, "x": 8.85071782279183, "y": 0.10766043613507659, "z": null, "yaw": 3.136362870801919, "pitch": null, "roll": null}, "v": 2.328798265039636, "accelerator_pedal_position": 0.27044202460213357, "brake_pedal_position": 0.0, "acceleration": 0.06958972691883669, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.02215064533437038, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137719.3974993} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2730261428382777, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.42751272564130927, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.332201659503513, "gear": 1, "accelerator_pedal_position": 0.2730261428382777, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137719.3974993} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.149940729141235, "x": 8.85071782279183, "y": 0.10766043613507659, "z": null, "yaw": 3.136362870801919, "pitch": null, "roll": null}, "v": 2.328798265039636, "accelerator_pedal_position": 0.27044202460213357, "brake_pedal_position": 0.0, "acceleration": 0.06958972691883669, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.02215064533437038, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137719.4274993} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2730261428382777, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.42751272564130927, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3347615334972973, "gear": 1, "accelerator_pedal_position": 0.2730261428382777, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137719.4274993} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.149940729141235, "x": 8.85071782279183, "y": 0.10766043613507659, "z": null, "yaw": 3.136362870801919, "pitch": null, "roll": null}, "v": 2.328798265039636, "accelerator_pedal_position": 0.27044202460213357, "brake_pedal_position": 0.0, "acceleration": 0.06958972691883669, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.02215064533437038, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137719.4474993} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2730261428382777, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.42751272564130927, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.336463993965181, "gear": 1, "accelerator_pedal_position": 0.2730261428382777, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137719.4474993} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137719.4674993, "x": 12.59408624138612, "y": 5.108880433889789, "z": null, "yaw": 3.1374091490576888, "pitch": null, "roll": null}, "v": 2.3381631627601758, "accelerator_pedal_position": 0.2730261428382777, "brake_pedal_position": 0.0, "acceleration": 0.08483516484434006, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.022239720687574835, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137719.4674993} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2722267263133262, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3502153039339571, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3381631627601758, "gear": 1, "accelerator_pedal_position": 0.2730261428382777, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137719.4674993} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.25994062423706, "x": 8.59408624138612, "y": 0.10888043388978907, "z": null, "yaw": 3.1374091490576888, "pitch": null, "roll": null}, "v": 2.3381631627601758, "accelerator_pedal_position": 0.2730261428382777, "brake_pedal_position": 0.0, "acceleration": 0.08483516484434006, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.022239720687574835, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137719.4874992} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27267637639176273, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3502153039339571, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3397591663813073, "gear": 1, "accelerator_pedal_position": 0.2722267263133262, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137719.4874992} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.25994062423706, "x": 8.59408624138612, "y": 0.10888043388978907, "z": null, "yaw": 3.1374091490576888, "pitch": null, "roll": null}, "v": 2.3381631627601758, "accelerator_pedal_position": 0.2730261428382777, "brake_pedal_position": 0.0, "acceleration": 0.08483516484434006, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.022239720687574835, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137719.5074992} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27267637639176273, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3502153039339571, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.342231611225316, "gear": 1, "accelerator_pedal_position": 0.27267637639176273, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137719.5074992} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.25994062423706, "x": 8.59408624138612, "y": 0.10888043388978907, "z": null, "yaw": 3.1374091490576888, "pitch": null, "roll": null}, "v": 2.3381631627601758, "accelerator_pedal_position": 0.2730261428382777, "brake_pedal_position": 0.0, "acceleration": 0.08483516484434006, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.022239720687574835, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137719.5274992} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27267637639176273, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3502153039339571, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.343054164052126, "gear": 1, "accelerator_pedal_position": 0.27267637639176273, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137719.5274992} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.25994062423706, "x": 8.59408624138612, "y": 0.10888043388978907, "z": null, "yaw": 3.1374091490576888, "pitch": null, "roll": null}, "v": 2.3381631627601758, "accelerator_pedal_position": 0.2730261428382777, "brake_pedal_position": 0.0, "acceleration": 0.08483516484434006, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.022239720687574835, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137719.5474992} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27267637639176273, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3502153039339571, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3446968803444603, "gear": 1, "accelerator_pedal_position": 0.27267637639176273, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137719.5474992} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.25994062423706, "x": 8.59408624138612, "y": 0.10888043388978907, "z": null, "yaw": 3.1374091490576888, "pitch": null, "roll": null}, "v": 2.3381631627601758, "accelerator_pedal_position": 0.2730261428382777, "brake_pedal_position": 0.0, "acceleration": 0.08483516484434006, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.022239720687574835, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137719.5574992} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27267637639176273, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3502153039339571, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3479727732973394, "gear": 1, "accelerator_pedal_position": 0.27267637639176273, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137719.5574992} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137719.5774992, "x": 12.336442140967232, "y": 5.109835677154612, "z": null, "yaw": 3.1384554273134584, "pitch": null, "roll": null}, "v": 2.3471549909234577, "accelerator_pedal_position": 0.27267637639176273, "brake_pedal_position": 0.0, "acceleration": 0.08177823738817508, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.022325247544727946, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137719.5874991} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2726842877872588, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3267485727900111, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3479727732973394, "gear": 1, "accelerator_pedal_position": 0.27267637639176273, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137719.5874991} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.369940519332886, "x": 8.336442140967232, "y": 0.10983567715461184, "z": null, "yaw": 3.1384554273134584, "pitch": null, "roll": null}, "v": 2.3471549909234577, "accelerator_pedal_position": 0.27267637639176273, "brake_pedal_position": 0.0, "acceleration": 0.08177823738817508, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.022325247544727946, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137719.6074991} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2727468737951782, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3267485727900111, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.351241867236858, "gear": 1, "accelerator_pedal_position": 0.2727468737951782, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137719.6074991} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.369940519332886, "x": 8.336442140967232, "y": 0.10983567715461184, "z": null, "yaw": 3.1384554273134584, "pitch": null, "roll": null}, "v": 2.3471549909234577, "accelerator_pedal_position": 0.27267637639176273, "brake_pedal_position": 0.0, "acceleration": 0.08177823738817508, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.022325247544727946, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137719.627499} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2727468737951782, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3267485727900111, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.351241867236858, "gear": 1, "accelerator_pedal_position": 0.2727468737951782, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137719.627499} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.369940519332886, "x": 8.336442140967232, "y": 0.10983567715461184, "z": null, "yaw": 3.1384554273134584, "pitch": null, "roll": null}, "v": 2.3471549909234577, "accelerator_pedal_position": 0.27267637639176273, "brake_pedal_position": 0.0, "acceleration": 0.08177823738817508, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.022325247544727946, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137719.647499} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2727468737951782, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3267485727900111, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.353694160568985, "gear": 1, "accelerator_pedal_position": 0.2727468737951782, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137719.647499} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.369940519332886, "x": 8.336442140967232, "y": 0.10983567715461184, "z": null, "yaw": 3.1384554273134584, "pitch": null, "roll": null}, "v": 2.3471549909234577, "accelerator_pedal_position": 0.27267637639176273, "brake_pedal_position": 0.0, "acceleration": 0.08177823738817508, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.022325247544727946, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137719.667499} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2727468737951782, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3267485727900111, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3553250583536167, "gear": 1, "accelerator_pedal_position": 0.2727468737951782, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137719.667499} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137719.687499, "x": 12.077806503329418, "y": 5.110523989597227, "z": null, "yaw": 3.139501705569228, "pitch": null, "roll": null}, "v": 2.356139319823588, "accelerator_pedal_position": 0.2727468737951782, "brake_pedal_position": 0.0, "acceleration": 0.08134707028449667, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.022410703071735878, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137719.687499} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2727212515955053, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3013591418233106, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.356139319823588, "gear": 1, "accelerator_pedal_position": 0.2727468737951782, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137719.687499} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.47994041442871, "x": 8.077806503329418, "y": 0.11052398959722698, "z": null, "yaw": 3.139501705569228, "pitch": null, "roll": null}, "v": 2.356139319823588, "accelerator_pedal_position": 0.2727468737951782, "brake_pedal_position": 0.0, "acceleration": 0.08134707028449667, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.022410703071735878, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137719.707499} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2727998737012933, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3013591418233106, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3585790748351565, "gear": 1, "accelerator_pedal_position": 0.2727998737012933, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137719.707499} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.47994041442871, "x": 8.077806503329418, "y": 0.11052398959722698, "z": null, "yaw": 3.139501705569228, "pitch": null, "roll": null}, "v": 2.356139319823588, "accelerator_pedal_position": 0.2727468737951782, "brake_pedal_position": 0.0, "acceleration": 0.08134707028449667, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.022410703071735878, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137719.727499} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2727998737012933, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3013591418233106, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3593934878788447, "gear": 1, "accelerator_pedal_position": 0.2727998737012933, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137719.727499} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.47994041442871, "x": 8.077806503329418, "y": 0.11052398959722698, "z": null, "yaw": 3.139501705569228, "pitch": null, "roll": null}, "v": 2.356139319823588, "accelerator_pedal_position": 0.2727468737951782, "brake_pedal_position": 0.0, "acceleration": 0.08134707028449667, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.022410703071735878, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137719.747499} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2727998737012933, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3013591418233106, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3610199402698004, "gear": 1, "accelerator_pedal_position": 0.2727998737012933, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137719.747499} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.47994041442871, "x": 8.077806503329418, "y": 0.11052398959722698, "z": null, "yaw": 3.139501705569228, "pitch": null, "roll": null}, "v": 2.356139319823588, "accelerator_pedal_position": 0.2727468737951782, "brake_pedal_position": 0.0, "acceleration": 0.08134707028449667, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.022410703071735878, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137719.767499} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2727998737012933, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3013591418233106, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.362643231975451, "gear": 1, "accelerator_pedal_position": 0.2727998737012933, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137719.767499} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.47994041442871, "x": 8.077806503329418, "y": 0.11052398959722698, "z": null, "yaw": 3.139501705569228, "pitch": null, "roll": null}, "v": 2.356139319823588, "accelerator_pedal_position": 0.2727468737951782, "brake_pedal_position": 0.0, "acceleration": 0.08134707028449667, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.022410703071735878, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137719.787499} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2727998737012933, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3013591418233106, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3642633680844396, "gear": 1, "accelerator_pedal_position": 0.2727998737012933, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137719.787499} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137719.797499, "x": 11.818184374990583, "y": 5.110943289950869, "z": null, "yaw": 3.1405479838249977, "pitch": null, "roll": null}, "v": 2.3650722543793616, "accelerator_pedal_position": 0.2727998737012933, "brake_pedal_position": 0.0, "acceleration": 0.08080993022976435, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.022495669755244085, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137719.807499} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2727210789250162, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.26766086931395283, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3666827419528382, "gear": 1, "accelerator_pedal_position": 0.2727210789250162, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137719.807499} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.589940309524536, "x": 7.818184374990583, "y": 0.11094328995086933, "z": null, "yaw": 3.1405479838249977, "pitch": null, "roll": null}, "v": 2.3650722543793616, "accelerator_pedal_position": 0.2727998737012933, "brake_pedal_position": 0.0, "acceleration": 0.08080993022976435, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.022495669755244085, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137719.827499} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27282476330592986, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.26766086931395283, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3674843492945694, "gear": 1, "accelerator_pedal_position": 0.2727210789250162, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137719.827499} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.589940309524536, "x": 7.818184374990583, "y": 0.11094328995086933, "z": null, "yaw": 3.1405479838249977, "pitch": null, "roll": null}, "v": 2.3650722543793616, "accelerator_pedal_position": 0.2727998737012933, "brake_pedal_position": 0.0, "acceleration": 0.08080993022976435, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.022495669755244085, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137719.847499} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27282476330592986, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.26766086931395283, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.369098177953364, "gear": 1, "accelerator_pedal_position": 0.27282476330592986, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137719.847499} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.589940309524536, "x": 7.818184374990583, "y": 0.11094328995086933, "z": null, "yaw": 3.1405479838249977, "pitch": null, "roll": null}, "v": 2.3650722543793616, "accelerator_pedal_position": 0.2727998737012933, "brake_pedal_position": 0.0, "acceleration": 0.08080993022976435, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.022495669755244085, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137719.8674989} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27282476330592986, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.26766086931395283, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3715130324684575, "gear": 1, "accelerator_pedal_position": 0.27282476330592986, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137719.8674989} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.589940309524536, "x": 7.818184374990583, "y": 0.11094328995086933, "z": null, "yaw": 3.1405479838249977, "pitch": null, "roll": null}, "v": 2.3650722543793616, "accelerator_pedal_position": 0.2727998737012933, "brake_pedal_position": 0.0, "acceleration": 0.08080993022976435, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.022495669755244085, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137719.8874989} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27282476330592986, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.26766086931395283, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.372316416252527, "gear": 1, "accelerator_pedal_position": 0.27282476330592986, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137719.8874989} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137719.9074988, "x": 11.5575837211401, "y": 5.111091510657875, "z": null, "yaw": 3.1415942620807673, "pitch": null, "roll": null}, "v": 2.373920836044148, "accelerator_pedal_position": 0.27282476330592986, "brake_pedal_position": 0.0, "acceleration": 0.08010372750180861, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.022579834106064556, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137719.9074988} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27279687992990403, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.2314269290568924, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.373920836044148, "gear": 1, "accelerator_pedal_position": 0.27282476330592986, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137719.9074988} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.69994020462036, "x": 7.5575837211401, "y": 0.11109151065787515, "z": null, "yaw": 3.1415942620807673, "pitch": null, "roll": null}, "v": 2.373920836044148, "accelerator_pedal_position": 0.27282476330592986, "brake_pedal_position": 0.0, "acceleration": 0.08010372750180861, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.022579834106064556, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137719.9274988} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2728758158822575, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.2314269290568924, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.375518645968608, "gear": 1, "accelerator_pedal_position": 0.27279687992990403, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137719.9274988} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.69994020462036, "x": 7.5575837211401, "y": 0.11109151065787515, "z": null, "yaw": 3.1415942620807673, "pitch": null, "roll": null}, "v": 2.373920836044148, "accelerator_pedal_position": 0.27282476330592986, "brake_pedal_position": 0.0, "acceleration": 0.08010372750180861, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.022579834106064556, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137719.9474988} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2728758158822575, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.2314269290568924, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.377123203789236, "gear": 1, "accelerator_pedal_position": 0.2728758158822575, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137719.9474988} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.69994020462036, "x": 7.5575837211401, "y": 0.11109151065787515, "z": null, "yaw": 3.1415942620807673, "pitch": null, "roll": null}, "v": 2.373920836044148, "accelerator_pedal_position": 0.27282476330592986, "brake_pedal_position": 0.0, "acceleration": 0.08010372750180861, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.022579834106064556, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137719.9674988} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2728758158822575, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.2314269290568924, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3787246331433884, "gear": 1, "accelerator_pedal_position": 0.2728758158822575, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137719.9674988} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.69994020462036, "x": 7.5575837211401, "y": 0.11109151065787515, "z": null, "yaw": 3.1415942620807673, "pitch": null, "roll": null}, "v": 2.373920836044148, "accelerator_pedal_position": 0.27282476330592986, "brake_pedal_position": 0.0, "acceleration": 0.08010372750180861, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.022579834106064556, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137719.9874988} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2728758158822575, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.2314269290568924, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3803229391054237, "gear": 1, "accelerator_pedal_position": 0.2728758158822575, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137719.9874988} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.69994020462036, "x": 7.5575837211401, "y": 0.11109151065787515, "z": null, "yaw": 3.1415942620807673, "pitch": null, "roll": null}, "v": 2.373920836044148, "accelerator_pedal_position": 0.27282476330592986, "brake_pedal_position": 0.0, "acceleration": 0.08010372750180861, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.022579834106064556, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137720.0074987} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2728758158822575, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.2314269290568924, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.382714552778818, "gear": 1, "accelerator_pedal_position": 0.2728758158822575, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137720.0074987} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137720.0174987, "x": 11.296012370398559, "y": 5.110966607830612, "z": null, "yaw": 3.142640540336537, "pitch": null, "roll": null}, "v": 2.382714552778818, "accelerator_pedal_position": 0.2728758158822575, "brake_pedal_position": 0.0, "acceleration": 0.07956483522492885, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.022663476602490615, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137720.0274987} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.272984174020741, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.17885788136476863, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.383510201131067, "gear": 1, "accelerator_pedal_position": 0.2728758158822575, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137720.0274987} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.80994009971619, "x": 7.296012370398559, "y": 0.11096660783061196, "z": null, "yaw": 3.142640540336537, "pitch": null, "roll": null}, "v": 2.382714552778818, "accelerator_pedal_position": 0.2728758158822575, "brake_pedal_position": 0.0, "acceleration": 0.07956483522492885, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.022663476602490615, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137720.0474987} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2729979441238793, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.17885788136476863, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.385112705475461, "gear": 1, "accelerator_pedal_position": 0.272984174020741, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137720.0474987} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.80994009971619, "x": 7.296012370398559, "y": 0.11096660783061196, "z": null, "yaw": 3.142640540336537, "pitch": null, "roll": null}, "v": 2.382714552778818, "accelerator_pedal_position": 0.2728758158822575, "brake_pedal_position": 0.0, "acceleration": 0.07956483522492885, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.022663476602490615, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137720.0674987} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2729979441238793, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.17885788136476863, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3899066125698987, "gear": 1, "accelerator_pedal_position": 0.2729979441238793, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137720.0674987} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.80994009971619, "x": 7.296012370398559, "y": 0.11096660783061196, "z": null, "yaw": 3.142640540336537, "pitch": null, "roll": null}, "v": 2.382714552778818, "accelerator_pedal_position": 0.2728758158822575, "brake_pedal_position": 0.0, "acceleration": 0.07956483522492885, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.022663476602490615, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137720.1074986} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2729979441238793, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.17885788136476863, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3914983394656453, "gear": 1, "accelerator_pedal_position": 0.2729979441238793, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137720.1074986} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137720.1274986, "x": 11.033474479566305, "y": 5.110566555881111, "z": null, "yaw": 3.1436868185923066, "pitch": null, "roll": null}, "v": 2.3914983394656453, "accelerator_pedal_position": 0.2729979441238793, "brake_pedal_position": 0.0, "acceleration": 0.07946959072429383, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.02274702464806998, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137720.1274986} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27319743460867885, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.1354232953916807, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3914983394656453, "gear": 1, "accelerator_pedal_position": 0.2729979441238793, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137720.1274986} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.91993999481201, "x": 7.033474479566305, "y": 0.1105665558811113, "z": null, "yaw": 3.1436868185923066, "pitch": null, "roll": null}, "v": 2.3914983394656453, "accelerator_pedal_position": 0.2729979441238793, "brake_pedal_position": 0.0, "acceleration": 0.07946959072429383, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.02274702464806998, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137720.1474986} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27316785215434103, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.1354232953916807, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3939174631553457, "gear": 1, "accelerator_pedal_position": 0.27319743460867885, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137720.1474986} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.91993999481201, "x": 7.033474479566305, "y": 0.1105665558811113, "z": null, "yaw": 3.1436868185923066, "pitch": null, "roll": null}, "v": 2.3914983394656453, "accelerator_pedal_position": 0.2729979441238793, "brake_pedal_position": 0.0, "acceleration": 0.07946959072429383, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.02274702464806998, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137720.1674986} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27316785215434103, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.1354232953916807, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3955225730707355, "gear": 1, "accelerator_pedal_position": 0.27316785215434103, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137720.1674986} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.91993999481201, "x": 7.033474479566305, "y": 0.1105665558811113, "z": null, "yaw": 3.1436868185923066, "pitch": null, "roll": null}, "v": 2.3914983394656453, "accelerator_pedal_position": 0.2729979441238793, "brake_pedal_position": 0.0, "acceleration": 0.07946959072429383, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.02274702464806998, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137720.1874986} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27316785215434103, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.1354232953916807, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3963239497040374, "gear": 1, "accelerator_pedal_position": 0.27316785215434103, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137720.1874986} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.91993999481201, "x": 7.033474479566305, "y": 0.1105665558811113, "z": null, "yaw": 3.1436868185923066, "pitch": null, "roll": null}, "v": 2.3914983394656453, "accelerator_pedal_position": 0.2729979441238793, "brake_pedal_position": 0.0, "acceleration": 0.07946959072429383, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.02274702464806998, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137720.2074986} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27316785215434103, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.1354232953916807, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3987233739899314, "gear": 1, "accelerator_pedal_position": 0.27316785215434103, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137720.2074986} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.91993999481201, "x": 7.033474479566305, "y": 0.1105665558811113, "z": null, "yaw": 3.1436868185923066, "pitch": null, "roll": null}, "v": 2.3914983394656453, "accelerator_pedal_position": 0.2729979441238793, "brake_pedal_position": 0.0, "acceleration": 0.07946959072429383, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.02274702464806998, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137720.2274985} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27316785215434103, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.1354232953916807, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.39952161568009, "gear": 1, "accelerator_pedal_position": 0.27316785215434103, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137720.2274985} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137720.2374985, "x": 10.76996842176044, "y": 5.109889326811573, "z": null, "yaw": 3.1447330968480762, "pitch": null, "roll": null}, "v": 2.400319075233485, "accelerator_pedal_position": 0.27316785215434103, "brake_pedal_position": 0.0, "acceleration": 0.07966780557365982, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.022830924139286016, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137720.2474985} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2735413524790532, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.08692662371016711, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4011157532892216, "gear": 1, "accelerator_pedal_position": 0.27316785215434103, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137720.2474985} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.02993988990784, "x": 6.76996842176044, "y": 0.10988932681157326, "z": null, "yaw": 3.1447330968480762, "pitch": null, "roll": null}, "v": 2.400319075233485, "accelerator_pedal_position": 0.27316785215434103, "brake_pedal_position": 0.0, "acceleration": 0.07966780557365982, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.022830924139286016, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137720.2674985} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27342930162776985, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.08692662371016711, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4035640643477194, "gear": 1, "accelerator_pedal_position": 0.27342930162776985, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137720.2674985} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.02993988990784, "x": 6.76996842176044, "y": 0.10988932681157326, "z": null, "yaw": 3.1447330968480762, "pitch": null, "roll": null}, "v": 2.400319075233485, "accelerator_pedal_position": 0.27316785215434103, "brake_pedal_position": 0.0, "acceleration": 0.07966780557365982, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.022830924139286016, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137720.2874985} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27342930162776985, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.08692662371016711, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4043739016461387, "gear": 1, "accelerator_pedal_position": 0.27342930162776985, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137720.2874985} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.02993988990784, "x": 6.76996842176044, "y": 0.10988932681157326, "z": null, "yaw": 3.1447330968480762, "pitch": null, "roll": null}, "v": 2.400319075233485, "accelerator_pedal_position": 0.27316785215434103, "brake_pedal_position": 0.0, "acceleration": 0.07966780557365982, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.022830924139286016, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137720.3074985} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27342930162776985, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.08692662371016711, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4076053144851173, "gear": 1, "accelerator_pedal_position": 0.27342930162776985, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137720.3074985} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.02993988990784, "x": 6.76996842176044, "y": 0.10988932681157326, "z": null, "yaw": 3.1447330968480762, "pitch": null, "roll": null}, "v": 2.400319075233485, "accelerator_pedal_position": 0.27316785215434103, "brake_pedal_position": 0.0, "acceleration": 0.07966780557365982, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.022830924139286016, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137720.3274984} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27342930162776985, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.08692662371016711, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4076053144851173, "gear": 1, "accelerator_pedal_position": 0.27342930162776985, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137720.3274984} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137720.3474984, "x": 10.5054896580401, "y": 5.108932876258027, "z": null, "yaw": 3.145779375103846, "pitch": null, "roll": null}, "v": 2.4092162681583984, "accelerator_pedal_position": 0.27342930162776985, "brake_pedal_position": 0.0, "acceleration": 0.08042909149805078, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.02291555086196518, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137720.3474984} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2739331957648007, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.038325939221021475, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4092162681583984, "gear": 1, "accelerator_pedal_position": 0.27342930162776985, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137720.3474984} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.13993978500366, "x": 6.5054896580401, "y": 0.10893287625802728, "z": null, "yaw": 3.145779375103846, "pitch": null, "roll": null}, "v": 2.4092162681583984, "accelerator_pedal_position": 0.27342930162776985, "brake_pedal_position": 0.0, "acceleration": 0.08042909149805078, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.02291555086196518, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137720.3674984} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27375974310124657, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.038325939221021475, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4141861866597485, "gear": 1, "accelerator_pedal_position": 0.27375974310124657, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137720.3674984} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.13993978500366, "x": 6.5054896580401, "y": 0.10893287625802728, "z": null, "yaw": 3.145779375103846, "pitch": null, "roll": null}, "v": 2.4092162681583984, "accelerator_pedal_position": 0.27342930162776985, "brake_pedal_position": 0.0, "acceleration": 0.08042909149805078, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.02291555086196518, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137720.4074984} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27375974310124657, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.038325939221021475, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4150062480158607, "gear": 1, "accelerator_pedal_position": 0.27375974310124657, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137720.4074984} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.13993978500366, "x": 6.5054896580401, "y": 0.10893287625802728, "z": null, "yaw": 3.145779375103846, "pitch": null, "roll": null}, "v": 2.4092162681583984, "accelerator_pedal_position": 0.27342930162776985, "brake_pedal_position": 0.0, "acceleration": 0.08042909149805078, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.02291555086196518, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137720.4174984} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27375974310124657, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.038325939221021475, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4150062480158607, "gear": 1, "accelerator_pedal_position": 0.27375974310124657, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137720.4174984} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.13993978500366, "x": 6.5054896580401, "y": 0.10893287625802728, "z": null, "yaw": 3.145779375103846, "pitch": null, "roll": null}, "v": 2.4092162681583984, "accelerator_pedal_position": 0.27342930162776985, "brake_pedal_position": 0.0, "acceleration": 0.08042909149805078, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.02291555086196518, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137720.4474983} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27375974310124657, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.038325939221021475, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4174615983913563, "gear": 1, "accelerator_pedal_position": 0.27375974310124657, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137720.4474983} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137720.4574983, "x": 10.24002346622734, "y": 5.107695097392308, "z": null, "yaw": 3.1468256533596155, "pitch": null, "roll": null}, "v": 2.418278439478019, "accelerator_pedal_position": 0.27375974310124657, "brake_pedal_position": 0.0, "acceleration": 0.08160376630044763, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.023001746796526647, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137720.4674983} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27312291865997834, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.00823763498768521, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4190944771410234, "gear": 1, "accelerator_pedal_position": 0.27375974310124657, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137720.4674983} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.24993968009949, "x": 6.24002346622734, "y": 0.10769509739230809, "z": null, "yaw": 3.1468256533596155, "pitch": null, "roll": null}, "v": 2.418278439478019, "accelerator_pedal_position": 0.27375974310124657, "brake_pedal_position": 0.0, "acceleration": 0.08160376630044763, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.023001746796526647, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137720.4874983} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27349402262934264, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.00823763498768521, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.420644580932383, "gear": 1, "accelerator_pedal_position": 0.27312291865997834, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137720.4874983} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.24993968009949, "x": 6.24002346622734, "y": 0.10769509739230809, "z": null, "yaw": 3.1468256533596155, "pitch": null, "roll": null}, "v": 2.418278439478019, "accelerator_pedal_position": 0.27375974310124657, "brake_pedal_position": 0.0, "acceleration": 0.08160376630044763, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.023001746796526647, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137720.5074983} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27349402262934264, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.00823763498768521, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4222380006279107, "gear": 1, "accelerator_pedal_position": 0.27349402262934264, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137720.5074983} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.24993968009949, "x": 6.24002346622734, "y": 0.10769509739230809, "z": null, "yaw": 3.1468256533596155, "pitch": null, "roll": null}, "v": 2.418278439478019, "accelerator_pedal_position": 0.27375974310124657, "brake_pedal_position": 0.0, "acceleration": 0.08160376630044763, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.023001746796526647, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137720.5274982} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27349402262934264, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.00823763498768521, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4238282848450634, "gear": 1, "accelerator_pedal_position": 0.27349402262934264, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137720.5274982} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.24993968009949, "x": 6.24002346622734, "y": 0.10769509739230809, "z": null, "yaw": 3.1468256533596155, "pitch": null, "roll": null}, "v": 2.418278439478019, "accelerator_pedal_position": 0.27375974310124657, "brake_pedal_position": 0.0, "acceleration": 0.08160376630044763, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.023001746796526647, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137720.5474982} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27349402262934264, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.00823763498768521, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4254154387426277, "gear": 1, "accelerator_pedal_position": 0.27349402262934264, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137720.5474982} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137720.5674982, "x": 9.973581075752051, "y": 5.106173990064244, "z": null, "yaw": 3.147871931615385, "pitch": null, "roll": null}, "v": 2.4269994674752056, "accelerator_pedal_position": 0.27349402262934264, "brake_pedal_position": 0.0, "acceleration": 0.07908440390838178, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.023084697905266634, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137720.5674982} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2676391332969468, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.057678601823442775, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4269994674752056, "gear": 1, "accelerator_pedal_position": 0.27349402262934264, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137720.5674982} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.35993957519531, "x": 5.973581075752051, "y": 0.106173990064244, "z": null, "yaw": 3.147871931615385, "pitch": null, "roll": null}, "v": 2.4269994674752056, "accelerator_pedal_position": 0.27349402262934264, "brake_pedal_position": 0.0, "acceleration": 0.07908440390838178, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.023084697905266634, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137720.5874982} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2704925951239101, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.057678601823442775, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4278488756590946, "gear": 1, "accelerator_pedal_position": 0.2676391332969468, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137720.5874982} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.35993957519531, "x": 5.973581075752051, "y": 0.106173990064244, "z": null, "yaw": 3.147871931615385, "pitch": null, "roll": null}, "v": 2.4269994674752056, "accelerator_pedal_position": 0.27349402262934264, "brake_pedal_position": 0.0, "acceleration": 0.07908440390838178, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.023084697905266634, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137720.6074982} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2704925951239101, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.057678601823442775, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4296543481121566, "gear": 1, "accelerator_pedal_position": 0.2704925951239101, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137720.6074982} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.35993957519531, "x": 5.973581075752051, "y": 0.106173990064244, "z": null, "yaw": 3.147871931615385, "pitch": null, "roll": null}, "v": 2.4269994674752056, "accelerator_pedal_position": 0.27349402262934264, "brake_pedal_position": 0.0, "acceleration": 0.07908440390838178, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.023084697905266634, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137720.6174982} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2704925951239101, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.057678601823442775, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4296543481121566, "gear": 1, "accelerator_pedal_position": 0.2704925951239101, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137720.6174982} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.35993957519531, "x": 5.973581075752051, "y": 0.106173990064244, "z": null, "yaw": 3.147871931615385, "pitch": null, "roll": null}, "v": 2.4269994674752056, "accelerator_pedal_position": 0.27349402262934264, "brake_pedal_position": 0.0, "acceleration": 0.07908440390838178, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.023084697905266634, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137720.6374981} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2704925951239101, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.057678601823442775, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.431454485941357, "gear": 1, "accelerator_pedal_position": 0.2704925951239101, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137720.6374981} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.35993957519531, "x": 5.973581075752051, "y": 0.106173990064244, "z": null, "yaw": 3.147871931615385, "pitch": null, "roll": null}, "v": 2.4269994674752056, "accelerator_pedal_position": 0.27349402262934264, "brake_pedal_position": 0.0, "acceleration": 0.07908440390838178, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.023084697905266634, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137720.6574981} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2704925951239101, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.057678601823442775, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.433249302967467, "gear": 1, "accelerator_pedal_position": 0.2704925951239101, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137720.6574981} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137720.677498, "x": 9.706320176106525, "y": 5.104368592401216, "z": null, "yaw": 3.148918209871155, "pitch": null, "roll": null}, "v": 2.433249302967467, "accelerator_pedal_position": 0.2704925951239101, "brake_pedal_position": 0.0, "acceleration": 0.059709232672148116, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.02314414396870008, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137720.687498} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2654668558830994, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.10634663774085881, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4338463952941884, "gear": 1, "accelerator_pedal_position": 0.2704925951239101, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137720.687498} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.46993947029114, "x": 5.706320176106525, "y": 0.1043685924012161, "z": null, "yaw": 3.148918209871155, "pitch": null, "roll": null}, "v": 2.433249302967467, "accelerator_pedal_position": 0.2704925951239101, "brake_pedal_position": 0.0, "acceleration": 0.059709232672148116, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.02314414396870008, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137720.707498} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26790701859405563, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.10634663774085881, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.434410905562945, "gear": 1, "accelerator_pedal_position": 0.2654668558830994, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137720.707498} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.46993947029114, "x": 5.706320176106525, "y": 0.1043685924012161, "z": null, "yaw": 3.148918209871155, "pitch": null, "roll": null}, "v": 2.433249302967467, "accelerator_pedal_position": 0.2704925951239101, "brake_pedal_position": 0.0, "acceleration": 0.059709232672148116, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.02314414396870008, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137720.717498} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26790701859405563, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.10634663774085881, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4348452531265794, "gear": 1, "accelerator_pedal_position": 0.26790701859405563, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137720.717498} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.46993947029114, "x": 5.706320176106525, "y": 0.1043685924012161, "z": null, "yaw": 3.148918209871155, "pitch": null, "roll": null}, "v": 2.433249302967467, "accelerator_pedal_position": 0.2704925951239101, "brake_pedal_position": 0.0, "acceleration": 0.059709232672148116, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.02314414396870008, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137720.737498} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26790701859405563, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.10634663774085881, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.435712662633027, "gear": 1, "accelerator_pedal_position": 0.26790701859405563, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137720.737498} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.46993947029114, "x": 5.706320176106525, "y": 0.1043685924012161, "z": null, "yaw": 3.148918209871155, "pitch": null, "roll": null}, "v": 2.433249302967467, "accelerator_pedal_position": 0.2704925951239101, "brake_pedal_position": 0.0, "acceleration": 0.059709232672148116, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.02314414396870008, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137720.767498} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26790701859405563, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.10634663774085881, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.437010568617438, "gear": 1, "accelerator_pedal_position": 0.26790701859405563, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137720.767498} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.46993947029114, "x": 5.706320176106525, "y": 0.1043685924012161, "z": null, "yaw": 3.148918209871155, "pitch": null, "roll": null}, "v": 2.433249302967467, "accelerator_pedal_position": 0.2704925951239101, "brake_pedal_position": 0.0, "acceleration": 0.059709232672148116, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.02314414396870008, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137720.777498} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26790701859405563, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.10634663774085881, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4374423499441025, "gear": 1, "accelerator_pedal_position": 0.26790701859405563, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137720.777498} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137720.787498, "x": 9.43844184514469, "y": 5.102278751269989, "z": null, "yaw": 3.1499644881269244, "pitch": null, "roll": null}, "v": 2.437873704910329, "accelerator_pedal_position": 0.26790701859405563, "brake_pedal_position": 0.0, "acceleration": 0.043092898956399006, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.023188129525052323, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137720.797498} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26307083685337207, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.15670976761039423, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.438304633899893, "gear": 1, "accelerator_pedal_position": 0.26790701859405563, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137720.797498} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.57993936538696, "x": 5.438441845144689, "y": 0.10227875126998942, "z": null, "yaw": 3.1499644881269244, "pitch": null, "roll": null}, "v": 2.437873704910329, "accelerator_pedal_position": 0.26790701859405563, "brake_pedal_position": 0.0, "acceleration": 0.043092898956399006, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.023188129525052323, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137720.817498} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26540856116657174, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.15670976761039423, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4385609913138304, "gear": 1, "accelerator_pedal_position": 0.26307083685337207, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137720.817498} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.57993936538696, "x": 5.438441845144689, "y": 0.10227875126998942, "z": null, "yaw": 3.1499644881269244, "pitch": null, "roll": null}, "v": 2.437873704910329, "accelerator_pedal_position": 0.26790701859405563, "brake_pedal_position": 0.0, "acceleration": 0.043092898956399006, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.023188129525052323, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137720.847498} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26540856116657174, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.15670976761039423, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.439382469177274, "gear": 1, "accelerator_pedal_position": 0.26540856116657174, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137720.847498} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.57993936538696, "x": 5.438441845144689, "y": 0.10227875126998942, "z": null, "yaw": 3.1499644881269244, "pitch": null, "roll": null}, "v": 2.437873704910329, "accelerator_pedal_position": 0.26790701859405563, "brake_pedal_position": 0.0, "acceleration": 0.043092898956399006, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.023188129525052323, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137720.867498} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26540856116657174, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.15670976761039423, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.439928769508283, "gear": 1, "accelerator_pedal_position": 0.26540856116657174, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137720.867498} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.57993936538696, "x": 5.438441845144689, "y": 0.10227875126998942, "z": null, "yaw": 3.1499644881269244, "pitch": null, "roll": null}, "v": 2.437873704910329, "accelerator_pedal_position": 0.26790701859405563, "brake_pedal_position": 0.0, "acceleration": 0.043092898956399006, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.023188129525052323, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137720.877498} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26540856116657174, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.15670976761039423, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4402015149564122, "gear": 1, "accelerator_pedal_position": 0.26540856116657174, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137720.877498} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137720.897498, "x": 9.170144771504784, "y": 5.099904927171025, "z": null, "yaw": 3.151010766382694, "pitch": null, "roll": null}, "v": 2.440746197675892, "accelerator_pedal_position": 0.26540856116657174, "brake_pedal_position": 0.0, "acceleration": 0.027193777392585494, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.023215451586147403, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137720.897498} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26125989179637976, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.20796378500085203, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.440746197675892, "gear": 1, "accelerator_pedal_position": 0.26540856116657174, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137720.897498} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.68993926048279, "x": 5.170144771504784, "y": 0.09990492717102484, "z": null, "yaw": 3.151010766382694, "pitch": null, "roll": null}, "v": 2.440746197675892, "accelerator_pedal_position": 0.26540856116657174, "brake_pedal_position": 0.0, "acceleration": 0.027193777392585494, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.023215451586147403, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137720.9174979} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26325706964782797, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.20796378500085203, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4407714770563795, "gear": 1, "accelerator_pedal_position": 0.26125989179637976, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137720.9174979} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.68993926048279, "x": 5.170144771504784, "y": 0.09990492717102484, "z": null, "yaw": 3.151010766382694, "pitch": null, "roll": null}, "v": 2.440746197675892, "accelerator_pedal_position": 0.26540856116657174, "brake_pedal_position": 0.0, "acceleration": 0.027193777392585494, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.023215451586147403, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137720.9374979} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26325706964782797, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.20796378500085203, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.441046230386324, "gear": 1, "accelerator_pedal_position": 0.26325706964782797, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137720.9374979} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.68993926048279, "x": 5.170144771504784, "y": 0.09990492717102484, "z": null, "yaw": 3.151010766382694, "pitch": null, "roll": null}, "v": 2.440746197675892, "accelerator_pedal_position": 0.26540856116657174, "brake_pedal_position": 0.0, "acceleration": 0.027193777392585494, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.023215451586147403, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137720.9574978} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26325706964782797, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.20796378500085203, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4413204409645637, "gear": 1, "accelerator_pedal_position": 0.26325706964782797, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137720.9574978} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.68993926048279, "x": 5.170144771504784, "y": 0.09990492717102484, "z": null, "yaw": 3.151010766382694, "pitch": null, "roll": null}, "v": 2.440746197675892, "accelerator_pedal_position": 0.26540856116657174, "brake_pedal_position": 0.0, "acceleration": 0.027193777392585494, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.023215451586147403, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137720.9774978} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26325706964782797, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.20796378500085203, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.441594109833197, "gear": 1, "accelerator_pedal_position": 0.26325706964782797, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137720.9774978} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.68993926048279, "x": 5.170144771504784, "y": 0.09990492717102484, "z": null, "yaw": 3.151010766382694, "pitch": null, "roll": null}, "v": 2.440746197675892, "accelerator_pedal_position": 0.26540856116657174, "brake_pedal_position": 0.0, "acceleration": 0.027193777392585494, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.023215451586147403, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137720.9974978} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26325706964782797, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.20796378500085203, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4418672380324407, "gear": 1, "accelerator_pedal_position": 0.26325706964782797, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137720.9974978} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137721.0074978, "x": 8.901624076940168, "y": 5.097248166267878, "z": null, "yaw": 3.1520570446384637, "pitch": null, "roll": null}, "v": 2.442003599705596, "accelerator_pedal_position": 0.26325706964782797, "brake_pedal_position": 0.0, "acceleration": 0.013622689503894114, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.023227411517078658, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137721.0274978} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2598500306736955, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.26233252622439707, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.442275918847057, "gear": 1, "accelerator_pedal_position": 0.26325706964782797, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137721.0274978} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.79993915557861, "x": 4.901624076940168, "y": 0.09724816626787813, "z": null, "yaw": 3.1520570446384637, "pitch": null, "roll": null}, "v": 2.442003599705596, "accelerator_pedal_position": 0.26325706964782797, "brake_pedal_position": 0.0, "acceleration": 0.013622689503894114, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.023227411517078658, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137721.0374978} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26148189887820844, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.26233252622439707, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4421220305225364, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137721.0374978} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.79993915557861, "x": 4.901624076940168, "y": 0.09724816626787813, "z": null, "yaw": 3.1520570446384637, "pitch": null, "roll": null}, "v": 2.442003599705596, "accelerator_pedal_position": 0.26325706964782797, "brake_pedal_position": 0.0, "acceleration": 0.013622689503894114, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.023227411517078658, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137721.0674977} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26148189887820844, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.26233252622439707, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.442172328978932, "gear": 1, "accelerator_pedal_position": 0.26148189887820844, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137721.0674977} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.79993915557861, "x": 4.901624076940168, "y": 0.09724816626787813, "z": null, "yaw": 3.1520570446384637, "pitch": null, "roll": null}, "v": 2.442003599705596, "accelerator_pedal_position": 0.26325706964782797, "brake_pedal_position": 0.0, "acceleration": 0.013622689503894114, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.023227411517078658, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137721.0774977} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26148189887820844, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.26233252622439707, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4421974409258875, "gear": 1, "accelerator_pedal_position": 0.26148189887820844, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137721.0774977} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.79993915557861, "x": 4.901624076940168, "y": 0.09724816626787813, "z": null, "yaw": 3.1520570446384637, "pitch": null, "roll": null}, "v": 2.442003599705596, "accelerator_pedal_position": 0.26325706964782797, "brake_pedal_position": 0.0, "acceleration": 0.013622689503894114, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.023227411517078658, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137721.1074977} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26148189887820844, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.26233252622439707, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4422726279349027, "gear": 1, "accelerator_pedal_position": 0.26148189887820844, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137721.1074977} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137721.1174977, "x": 8.633000164559833, "y": 5.094309309341231, "z": null, "yaw": 3.1531033228942333, "pitch": null, "roll": null}, "v": 2.4422976407419075, "accelerator_pedal_position": 0.26148189887820844, "brake_pedal_position": 0.0, "acceleration": 0.0024988082919724097, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.023230208323829528, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137721.1174977} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25774477472632795, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.3162570730420585, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4422976407419075, "gear": 1, "accelerator_pedal_position": 0.26148189887820844, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137721.1174977} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.90993905067444, "x": 4.633000164559833, "y": 0.09430930934123083, "z": null, "yaw": 3.1531033228942333, "pitch": null, "roll": null}, "v": 2.4422976407419075, "accelerator_pedal_position": 0.26148189887820844, "brake_pedal_position": 0.0, "acceleration": 0.0024988082919724097, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.023230208323829528, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137721.1374977} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.259526572938399, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.3162570730420585, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.441880682559451, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137721.1374977} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.90993905067444, "x": 4.633000164559833, "y": 0.09430930934123083, "z": null, "yaw": 3.1531033228942333, "pitch": null, "roll": null}, "v": 2.4422976407419075, "accelerator_pedal_position": 0.26148189887820844, "brake_pedal_position": 0.0, "acceleration": 0.0024988082919724097, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.023230208323829528, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137721.1674976} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.259526572938399, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.3162570730420585, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4415905465290946, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137721.1674976} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.90993905067444, "x": 4.633000164559833, "y": 0.09430930934123083, "z": null, "yaw": 3.1531033228942333, "pitch": null, "roll": null}, "v": 2.4422976407419075, "accelerator_pedal_position": 0.26148189887820844, "brake_pedal_position": 0.0, "acceleration": 0.0024988082919724097, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.023230208323829528, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137721.1674976} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.90993905067444, "x": 4.633000164559833, "y": 0.09430930934123083, "z": null, "yaw": 3.1531033228942333, "pitch": null, "roll": null}, "v": 2.4422976407419075, "accelerator_pedal_position": 0.26148189887820844, "brake_pedal_position": 0.0, "acceleration": 0.0024988082919724097, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.023230208323829528, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137721.1974976} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.259526572938399, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.3162570730420585, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.441301269897321, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137721.1974976} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.90993905067444, "x": 4.633000164559833, "y": 0.09430930934123083, "z": null, "yaw": 3.1531033228942333, "pitch": null, "roll": null}, "v": 2.4422976407419075, "accelerator_pedal_position": 0.26148189887820844, "brake_pedal_position": 0.0, "acceleration": 0.0024988082919724097, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.023230208323829528, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137721.2174976} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.259526572938399, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.3162570730420585, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.441108894970958, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137721.2174976} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137721.2274976, "x": 8.364441111774253, "y": 5.0910901507280135, "z": null, "yaw": 3.154149601150003, "pitch": null, "roll": null}, "v": 2.441012850068412, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3816360798454117, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.023217987882512333, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137721.2374976} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25618416273765476, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.37093235357209114, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4409169000786077, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5264299915594152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137721.2374976} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.01993894577026, "x": 4.364441111774253, "y": 0.09109015072801352, "z": null, "yaw": 3.154149601150003, "pitch": null, "roll": null}, "v": 2.441012850068412, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3816360798454117, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.023217987882512333, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137721.2574975} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.257766112777678, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.37093235357209114, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.439593775395906, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.48659642713850976, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137721.2574975} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.01993894577026, "x": 4.364441111774253, "y": 0.09109015072801352, "z": null, "yaw": 3.154149601150003, "pitch": null, "roll": null}, "v": 2.441012850068412, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3816360798454117, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.023217987882512333, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137721.2874975} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.257766112777678, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.37093235357209114, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.439593775395906, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.48659642713850976, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137721.2874975} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.01993894577026, "x": 4.364441111774253, "y": 0.09109015072801352, "z": null, "yaw": 3.154149601150003, "pitch": null, "roll": null}, "v": 2.441012850068412, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3816360798454117, "steering_wheel_angle": 0.5264299915594152, "front_wheel_angle": 0.024344937803966703, "heading_rate": 0.023217987882512333, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137721.3174975} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.257766112777678, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.37093235357209114, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4389806516366064, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.48659642713850976, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137721.3174975} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.257766112777678, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.37093235357209114, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.438776680697487, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.48659642713850976, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137721.3274975} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137721.3374975, "x": 8.096078063047093, "y": 5.0875988917663575, "z": null, "yaw": 3.15513066062564, "pitch": null, "roll": null}, "v": 2.438572911235912, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3813950239959315, "steering_wheel_angle": 0.48659642713850976, "front_wheel_angle": 0.022490843520825393, "heading_rate": 0.021427660659936197, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137721.3474975} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25523095716040856, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.42736397816550387, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4383693430445574, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.48659642713850976, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137721.3474975} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.12993884086609, "x": 4.096078063047093, "y": 0.08759889176635749, "z": null, "yaw": 3.15513066062564, "pitch": null, "roll": null}, "v": 2.438572911235912, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3813950239959315, "steering_wheel_angle": 0.48659642713850976, "front_wheel_angle": 0.022490843520825393, "heading_rate": 0.021427660659936197, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137721.3774974} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2564198085549359, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.42736397816550387, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.437284971627047, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4066806137360635, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137721.3774974} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.12993884086609, "x": 4.096078063047093, "y": 0.08759889176635749, "z": null, "yaw": 3.15513066062564, "pitch": null, "roll": null}, "v": 2.438572911235912, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3813950239959315, "steering_wheel_angle": 0.48659642713850976, "front_wheel_angle": 0.022490843520825393, "heading_rate": 0.021427660659936197, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137721.3774974} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.12993884086609, "x": 4.096078063047093, "y": 0.08759889176635749, "z": null, "yaw": 3.15513066062564, "pitch": null, "roll": null}, "v": 2.438572911235912, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3813950239959315, "steering_wheel_angle": 0.48659642713850976, "front_wheel_angle": 0.022490843520825393, "heading_rate": 0.021427660659936197, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137721.4074974} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2564198085549359, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.42736397816550387, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.436140906462392, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4066806137360635, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137721.4074974} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.12993884086609, "x": 4.096078063047093, "y": 0.08759889176635749, "z": null, "yaw": 3.15513066062564, "pitch": null, "roll": null}, "v": 2.438572911235912, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3813950239959315, "steering_wheel_angle": 0.48659642713850976, "front_wheel_angle": 0.022490843520825393, "heading_rate": 0.021427660659936197, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137721.4274974} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2564198085549359, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.42736397816550387, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4358555957922303, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4066806137360635, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137721.4274974} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137721.4474974, "x": 7.828028245576121, "y": 5.083863365166985, "z": null, "yaw": 3.155973864801613, "pitch": null, "roll": null}, "v": 2.435285819133379, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3810704611653903, "steering_wheel_angle": 0.4066806137360635, "front_wheel_angle": 0.018777057474859103, "heading_rate": 0.01786440496885542, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137721.4474974} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2540629483933798, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4763136574399739, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.435285819133379, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4066806137360635, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137721.4474974} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.23993873596191, "x": 3.828028245576121, "y": 0.08386336516698467, "z": null, "yaw": 3.155973864801613, "pitch": null, "roll": null}, "v": 2.435285819133379, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3810704611653903, "steering_wheel_angle": 0.4066806137360635, "front_wheel_angle": 0.018777057474859103, "heading_rate": 0.01786440496885542, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137721.4674973} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25516053470770517, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4763136574399739, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4340603852990474, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3666058866234366, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137721.4674973} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.23993873596191, "x": 3.828028245576121, "y": 0.08386336516698467, "z": null, "yaw": 3.155973864801613, "pitch": null, "roll": null}, "v": 2.435285819133379, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3810704611653903, "steering_wheel_angle": 0.4066806137360635, "front_wheel_angle": 0.018777057474859103, "heading_rate": 0.01786440496885542, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137721.4874973} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25516053470770517, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4763136574399739, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4336984235297012, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3666058866234366, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137721.4874973} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.23993873596191, "x": 3.828028245576121, "y": 0.08386336516698467, "z": null, "yaw": 3.155973864801613, "pitch": null, "roll": null}, "v": 2.435285819133379, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3810704611653903, "steering_wheel_angle": 0.4066806137360635, "front_wheel_angle": 0.018777057474859103, "heading_rate": 0.01786440496885542, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137721.5074973} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25516053470770517, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4763136574399739, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4329755711378236, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3666058866234366, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137721.5074973} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.23993873596191, "x": 3.828028245576121, "y": 0.08386336516698467, "z": null, "yaw": 3.155973864801613, "pitch": null, "roll": null}, "v": 2.435285819133379, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3810704611653903, "steering_wheel_angle": 0.4066806137360635, "front_wheel_angle": 0.018777057474859103, "heading_rate": 0.01786440496885542, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137721.5274973} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25516053470770517, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4763136574399739, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4322541444198453, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3666058866234366, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137721.5274973} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.23993873596191, "x": 3.828028245576121, "y": 0.08386336516698467, "z": null, "yaw": 3.155973864801613, "pitch": null, "roll": null}, "v": 2.435285819133379, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3810704611653903, "steering_wheel_angle": 0.4066806137360635, "front_wheel_angle": 0.018777057474859103, "heading_rate": 0.01786440496885542, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137721.5474973} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25516053470770517, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4763136574399739, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4315341403558453, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3666058866234366, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137721.5474973} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137721.5574973, "x": 7.560387935821909, "y": 5.079923904892417, "z": null, "yaw": 3.156708133049091, "pitch": null, "roll": null}, "v": 2.4311746708773274, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3806648363470212, "steering_wheel_angle": 0.3666058866234366, "front_wheel_angle": 0.01691772648839027, "heading_rate": 0.01606791894670369, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137721.5674973} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24995275393753377, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.48456581894183226, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4301313088495213, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3666058866234366, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137721.5674973} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.34993863105774, "x": 3.5603879358219093, "y": 0.07992390489241696, "z": null, "yaw": 3.156708133049091, "pitch": null, "roll": null}, "v": 2.4311746708773274, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3806648363470212, "steering_wheel_angle": 0.3666058866234366, "front_wheel_angle": 0.01691772648839027, "heading_rate": 0.01606791894670369, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137721.5874972} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2524017460176896, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.48456581894183226, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4294477364983673, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3666058866234366, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137721.5874972} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.34993863105774, "x": 3.5603879358219093, "y": 0.07992390489241696, "z": null, "yaw": 3.156708133049091, "pitch": null, "roll": null}, "v": 2.4311746708773274, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3806648363470212, "steering_wheel_angle": 0.3666058866234366, "front_wheel_angle": 0.01691772648839027, "heading_rate": 0.01606791894670369, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137721.6074972} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2524017460176896, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.48456581894183226, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4283885860852736, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3666058866234366, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137721.6074972} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.34993863105774, "x": 3.5603879358219093, "y": 0.07992390489241696, "z": null, "yaw": 3.156708133049091, "pitch": null, "roll": null}, "v": 2.4311746708773274, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3806648363470212, "steering_wheel_angle": 0.3666058866234366, "front_wheel_angle": 0.01691772648839027, "heading_rate": 0.01606791894670369, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137721.6274972} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2524017460176896, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.48456581894183226, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4273315227171985, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3666058866234366, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137721.6274972} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.34993863105774, "x": 3.5603879358219093, "y": 0.07992390489241696, "z": null, "yaw": 3.156708133049091, "pitch": null, "roll": null}, "v": 2.4311746708773274, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3806648363470212, "steering_wheel_angle": 0.3666058866234366, "front_wheel_angle": 0.01691772648839027, "heading_rate": 0.01606791894670369, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137721.6474972} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2524017460176896, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.48456581894183226, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4262765418349077, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3666058866234366, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137721.6474972} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137721.6674972, "x": 7.293290833608472, "y": 5.075798052230042, "z": null, "yaw": 3.1574351359688335, "pitch": null, "roll": null}, "v": 2.42522363889079, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.38007827893088636, "steering_wheel_angle": 0.3666058866234366, "front_wheel_angle": 0.01691772648839027, "heading_rate": 0.016028587877342716, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137721.6674972} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25135691816283057, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5306717970359958, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.42522363889079, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3666058866234366, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137721.6674972} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.45993852615356, "x": 3.293290833608472, "y": 0.07579805223004232, "z": null, "yaw": 3.1574351359688335, "pitch": null, "roll": null}, "v": 2.42522363889079, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.38007827893088636, "steering_wheel_angle": 0.3666058866234366, "front_wheel_angle": 0.01691772648839027, "heading_rate": 0.016028587877342716, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137721.6874971} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25180976537394156, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5306717970359958, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.424042270184807, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3264295267520694, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137721.6874971} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.45993852615356, "x": 3.293290833608472, "y": 0.07579805223004232, "z": null, "yaw": 3.1574351359688335, "pitch": null, "roll": null}, "v": 2.42522363889079, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.38007827893088636, "steering_wheel_angle": 0.3666058866234366, "front_wheel_angle": 0.01691772648839027, "heading_rate": 0.016028587877342716, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137721.7074971} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25180976537394156, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5306717970359958, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.422919805348011, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3264295267520694, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137721.7074971} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.45993852615356, "x": 3.293290833608472, "y": 0.07579805223004232, "z": null, "yaw": 3.1574351359688335, "pitch": null, "roll": null}, "v": 2.42522363889079, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.38007827893088636, "steering_wheel_angle": 0.3666058866234366, "front_wheel_angle": 0.01691772648839027, "heading_rate": 0.016028587877342716, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137721.727497} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25180976537394156, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5306717970359958, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4217995498707725, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3264295267520694, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137721.727497} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.45993852615356, "x": 3.293290833608472, "y": 0.07579805223004232, "z": null, "yaw": 3.1574351359688335, "pitch": null, "roll": null}, "v": 2.42522363889079, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.38007827893088636, "steering_wheel_angle": 0.3666058866234366, "front_wheel_angle": 0.01691772648839027, "heading_rate": 0.016028587877342716, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137721.747497} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25180976537394156, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5306717970359958, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.420681498902643, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3264295267520694, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137721.747497} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.45993852615356, "x": 3.293290833608472, "y": 0.07579805223004232, "z": null, "yaw": 3.1574351359688335, "pitch": null, "roll": null}, "v": 2.42522363889079, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.38007827893088636, "steering_wheel_angle": 0.3666058866234366, "front_wheel_angle": 0.01691772648839027, "heading_rate": 0.016028587877342716, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137721.767497} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25180976537394156, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5306717970359958, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4195656476056815, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3264295267520694, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137721.767497} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137721.777497, "x": 7.026864869179305, "y": 5.071496754328157, "z": null, "yaw": 3.1580893839620794, "pitch": null, "roll": null}, "v": 2.419008545325443, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3794664506898473, "steering_wheel_angle": 0.3264295267520694, "front_wheel_angle": 0.015055676882266094, "heading_rate": 0.014227563704790216, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137721.787497} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2519652119586995, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5879748736792844, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4184519911544156, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3264295267520694, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137721.787497} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.56993842124939, "x": 3.026864869179305, "y": 0.07149675432815705, "z": null, "yaw": 3.1580893839620794, "pitch": null, "roll": null}, "v": 2.419008545325443, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3794664506898473, "steering_wheel_angle": 0.3264295267520694, "front_wheel_angle": 0.015055676882266094, "heading_rate": 0.014227563704790216, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137721.807497} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.251844574230186, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5879748736792844, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.41735994600301, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.24582303616488915, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137721.807497} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.56993842124939, "x": 3.026864869179305, "y": 0.07149675432815705, "z": null, "yaw": 3.1580893839620794, "pitch": null, "roll": null}, "v": 2.419008545325443, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3794664506898473, "steering_wheel_angle": 0.3264295267520694, "front_wheel_angle": 0.015055676882266094, "heading_rate": 0.014227563704790216, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137721.827497} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.251844574230186, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5879748736792844, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4162549756045393, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.24582303616488915, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137721.827497} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.56993842124939, "x": 3.026864869179305, "y": 0.07149675432815705, "z": null, "yaw": 3.1580893839620794, "pitch": null, "roll": null}, "v": 2.419008545325443, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3794664506898473, "steering_wheel_angle": 0.3264295267520694, "front_wheel_angle": 0.015055676882266094, "heading_rate": 0.014227563704790216, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137721.847497} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.251844574230186, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5879748736792844, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.415152177186326, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.24582303616488915, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137721.847497} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.56993842124939, "x": 3.026864869179305, "y": 0.07149675432815705, "z": null, "yaw": 3.1580893839620794, "pitch": null, "roll": null}, "v": 2.419008545325443, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3794664506898473, "steering_wheel_angle": 0.3264295267520694, "front_wheel_angle": 0.015055676882266094, "heading_rate": 0.014227563704790216, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137721.867497} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.251844574230186, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5879748736792844, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4135020416225186, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.24582303616488915, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137721.867497} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137721.887497, "x": 6.761114158705008, "y": 5.067045462931163, "z": null, "yaw": 3.1586124916833884, "pitch": null, "roll": null}, "v": 2.4129530772806023, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3788710793956094, "steering_wheel_angle": 0.24582303616488915, "front_wheel_angle": 0.011325819957245707, "heading_rate": 0.010675719023314486, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137721.887497} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2523400492356106, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6455829970881704, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4129530772806023, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.24582303616488915, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137721.887497} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.67993831634521, "x": 2.7611141587050083, "y": 0.06704546293116298, "z": null, "yaw": 3.1586124916833884, "pitch": null, "roll": null}, "v": 2.4129530772806023, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3788710793956094, "steering_wheel_angle": 0.24582303616488915, "front_wheel_angle": 0.011325819957245707, "heading_rate": 0.010675719023314486, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137721.907497} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25205874699389613, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6455829970881704, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4119186702694613, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2053920143708647, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137721.907497} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.67993831634521, "x": 2.7611141587050083, "y": 0.06704546293116298, "z": null, "yaw": 3.1586124916833884, "pitch": null, "roll": null}, "v": 2.4129530772806023, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3788710793956094, "steering_wheel_angle": 0.24582303616488915, "front_wheel_angle": 0.011325819957245707, "heading_rate": 0.010675719023314486, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137721.927497} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25205874699389613, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6455829970881704, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4108511492258393, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2053920143708647, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137721.927497} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.67993831634521, "x": 2.7611141587050083, "y": 0.06704546293116298, "z": null, "yaw": 3.1586124916833884, "pitch": null, "roll": null}, "v": 2.4129530772806023, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3788710793956094, "steering_wheel_angle": 0.24582303616488915, "front_wheel_angle": 0.011325819957245707, "heading_rate": 0.010675719023314486, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137721.947497} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25205874699389613, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6455829970881704, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.409785724241106, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2053920143708647, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137721.947497} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.67993831634521, "x": 2.7611141587050083, "y": 0.06704546293116298, "z": null, "yaw": 3.1586124916833884, "pitch": null, "roll": null}, "v": 2.4129530772806023, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3788710793956094, "steering_wheel_angle": 0.24582303616488915, "front_wheel_angle": 0.011325819957245707, "heading_rate": 0.010675719023314486, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137721.9674969} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25205874699389613, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6455829970881704, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4071313020788363, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2053920143708647, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137721.9674969} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137721.9974968, "x": 6.4960186700334335, "y": 5.062482421707218, "z": null, "yaw": 3.159026198568676, "pitch": null, "roll": null}, "v": 2.4071313020788363, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37829937615841935, "steering_wheel_angle": 0.2053920143708647, "front_wheel_angle": 0.00945798381158284, "heading_rate": 0.008893471782162508, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137721.9974968} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2527964700333372, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7043426874216931, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4071313020788363, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2053920143708647, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137721.9974968} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.78993821144104, "x": 2.4960186700334335, "y": 0.06248242170721774, "z": null, "yaw": 3.159026198568676, "pitch": null, "roll": null}, "v": 2.4071313020788363, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37829937615841935, "steering_wheel_angle": 0.2053920143708647, "front_wheel_angle": 0.00945798381158284, "heading_rate": 0.008893471782162508, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137722.0174968} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2524016148087605, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7043426874216931, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4056584026095926, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.12427060999755074, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137722.0174968} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.78993821144104, "x": 2.4960186700334335, "y": 0.06248242170721774, "z": null, "yaw": 3.159026198568676, "pitch": null, "roll": null}, "v": 2.4071313020788363, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37829937615841935, "steering_wheel_angle": 0.2053920143708647, "front_wheel_angle": 0.00945798381158284, "heading_rate": 0.008893471782162508, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137722.0374968} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2524016148087605, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7043426874216931, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4051519550988307, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.12427060999755074, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137722.0374968} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.78993821144104, "x": 2.4960186700334335, "y": 0.06248242170721774, "z": null, "yaw": 3.159026198568676, "pitch": null, "roll": null}, "v": 2.4071313020788363, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37829937615841935, "steering_wheel_angle": 0.2053920143708647, "front_wheel_angle": 0.00945798381158284, "heading_rate": 0.008893471782162508, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137722.0574968} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2524016148087605, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7043426874216931, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.403635591608762, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.12427060999755074, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137722.0574968} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.78993821144104, "x": 2.4960186700334335, "y": 0.06248242170721774, "z": null, "yaw": 3.159026198568676, "pitch": null, "roll": null}, "v": 2.4071313020788363, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37829937615841935, "steering_wheel_angle": 0.2053920143708647, "front_wheel_angle": 0.00945798381158284, "heading_rate": 0.008893471782162508, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137722.0774968} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2524016148087605, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7043426874216931, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.40313112833278, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.12427060999755074, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137722.0774968} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.78993821144104, "x": 2.4960186700334335, "y": 0.06248242170721774, "z": null, "yaw": 3.159026198568676, "pitch": null, "roll": null}, "v": 2.4071313020788363, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37829937615841935, "steering_wheel_angle": 0.2053920143708647, "front_wheel_angle": 0.00945798381158284, "heading_rate": 0.008893471782162508, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137722.0974967} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2524016148087605, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7043426874216931, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.402123685390939, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.12427060999755074, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137722.0974967} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137722.1074967, "x": 6.23154887946744, "y": 5.057836687672648, "z": null, "yaw": 3.1592937505443532, "pitch": null, "roll": null}, "v": 2.4016207046537996, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3777588553229081, "steering_wheel_angle": 0.12427060999755074, "front_wheel_angle": 0.005716351795665624, "heading_rate": 0.005362757173253961, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137722.1174967} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2520197250775029, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7367274452754978, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.400592353865736, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.12427060999755074, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137722.1174967} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.89993810653687, "x": 2.2315488794674403, "y": 0.05783668767264771, "z": null, "yaw": 3.1592937505443532, "pitch": null, "roll": null}, "v": 2.4016207046537996, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3777588553229081, "steering_wheel_angle": 0.12427060999755074, "front_wheel_angle": 0.005716351795665624, "heading_rate": 0.005362757173253961, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137722.1374967} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25216039486090497, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7367274452754978, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.400067006141203, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.12427060999755074, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137722.1374967} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.89993810653687, "x": 2.2315488794674403, "y": 0.05783668767264771, "z": null, "yaw": 3.1592937505443532, "pitch": null, "roll": null}, "v": 2.4016207046537996, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3777588553229081, "steering_wheel_angle": 0.12427060999755074, "front_wheel_angle": 0.005716351795665624, "heading_rate": 0.005362757173253961, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137722.1574967} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25216039486090497, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7367274452754978, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.398520399730833, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.12427060999755074, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137722.1574967} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.89993810653687, "x": 2.2315488794674403, "y": 0.05783668767264771, "z": null, "yaw": 3.1592937505443532, "pitch": null, "roll": null}, "v": 2.4016207046537996, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3777588553229081, "steering_wheel_angle": 0.12427060999755074, "front_wheel_angle": 0.005716351795665624, "heading_rate": 0.005362757173253961, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137722.1774967} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25216039486090497, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7367274452754978, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3980058741989816, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.12427060999755074, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137722.1774967} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.89993810653687, "x": 2.2315488794674403, "y": 0.05783668767264771, "z": null, "yaw": 3.1592937505443532, "pitch": null, "roll": null}, "v": 2.4016207046537996, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3777588553229081, "steering_wheel_angle": 0.12427060999755074, "front_wheel_angle": 0.005716351795665624, "heading_rate": 0.005362757173253961, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137722.1974967} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25216039486090497, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7367274452754978, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3969783347574767, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.12427060999755074, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137722.1974967} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137722.2174966, "x": 5.96769628026668, "y": 5.053136263962381, "z": null, "yaw": 3.1595393777110075, "pitch": null, "roll": null}, "v": 2.395952807171225, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.377203538900478, "steering_wheel_angle": 0.12427060999755074, "front_wheel_angle": 0.005716351795665624, "heading_rate": 0.005350100904167403, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137722.2174966} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2517869743047556, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7669674685596184, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3954174576762672, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.08357534941383628, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137722.2174966} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.00993800163269, "x": 1.9676962802666802, "y": 0.053136263962381136, "z": null, "yaw": 3.1595393777110075, "pitch": null, "roll": null}, "v": 2.395952807171225, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.377203538900478, "steering_wheel_angle": 0.12427060999755074, "front_wheel_angle": 0.005716351795665624, "heading_rate": 0.005350100904167403, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137722.2374966} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25192248386223925, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7669674685596184, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3948826323618224, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.08357534941383628, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137722.2374966} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.00993800163269, "x": 1.9676962802666802, "y": 0.053136263962381136, "z": null, "yaw": 3.1595393777110075, "pitch": null, "roll": null}, "v": 2.395952807171225, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.377203538900478, "steering_wheel_angle": 0.12427060999755074, "front_wheel_angle": 0.005716351795665624, "heading_rate": 0.005350100904167403, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137722.2574966} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25192248386223925, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7669674685596184, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.392782389197081, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.08357534941383628, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137722.2574966} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.00993800163269, "x": 1.9676962802666802, "y": 0.053136263962381136, "z": null, "yaw": 3.1595393777110075, "pitch": null, "roll": null}, "v": 2.395952807171225, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.377203538900478, "steering_wheel_angle": 0.12427060999755074, "front_wheel_angle": 0.005716351795665624, "heading_rate": 0.005350100904167403, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137722.2774966} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25192248386223925, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7669674685596184, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.392782389197081, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.08357534941383628, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137722.2774966} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.00993800163269, "x": 1.9676962802666802, "y": 0.053136263962381136, "z": null, "yaw": 3.1595393777110075, "pitch": null, "roll": null}, "v": 2.395952807171225, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.377203538900478, "steering_wheel_angle": 0.12427060999755074, "front_wheel_angle": 0.005716351795665624, "heading_rate": 0.005350100904167403, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137722.2974966} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25192248386223925, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7669674685596184, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3917353482959114, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.08357534941383628, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137722.2974966} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.00993800163269, "x": 1.9676962802666802, "y": 0.053136263962381136, "z": null, "yaw": 3.1595393777110075, "pitch": null, "roll": null}, "v": 2.395952807171225, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.377203538900478, "steering_wheel_angle": 0.12427060999755074, "front_wheel_angle": 0.005716351795665624, "heading_rate": 0.005350100904167403, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137722.3174965} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25192248386223925, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7669674685596184, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3906903552409235, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.08357534941383628, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137722.3174965} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137722.3274965, "x": 5.7044747912782565, "y": 5.048390289690109, "z": null, "yaw": 3.1597117997609465, "pitch": null, "roll": null}, "v": 2.3901686252672287, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3766374918354798, "steering_wheel_angle": 0.08357534941383628, "front_wheel_angle": 0.0038423441633651306, "heading_rate": 0.00358745924320795, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137722.3374965} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2517705155418515, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7947790137840659, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3891266956565542, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.08357534941383628, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137722.3374965} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.11993789672852, "x": 1.7044747912782565, "y": 0.04839028969010872, "z": null, "yaw": 3.1597117997609465, "pitch": null, "roll": null}, "v": 2.3901686252672287, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3766374918354798, "steering_wheel_angle": 0.08357534941383628, "front_wheel_angle": 0.0038423441633651306, "heading_rate": 0.00358745924320795, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137722.3574965} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2517997540278803, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7947790137840659, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3875428056030517, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.04280552166316452, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137722.3574965} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.11993789672852, "x": 1.7044747912782565, "y": 0.04839028969010872, "z": null, "yaw": 3.1597117997609465, "pitch": null, "roll": null}, "v": 2.3901686252672287, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3766374918354798, "steering_wheel_angle": 0.08357534941383628, "front_wheel_angle": 0.0038423441633651306, "heading_rate": 0.00358745924320795, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137722.3774965} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2517997540278803, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7947790137840659, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.387016482762134, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.04280552166316452, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137722.3774965} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.11993789672852, "x": 1.7044747912782565, "y": 0.04839028969010872, "z": null, "yaw": 3.1597117997609465, "pitch": null, "roll": null}, "v": 2.3901686252672287, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3766374918354798, "steering_wheel_angle": 0.08357534941383628, "front_wheel_angle": 0.0038423441633651306, "heading_rate": 0.00358745924320795, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137722.4074965} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2517997540278803, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7947790137840659, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.385440598751651, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.04280552166316452, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137722.4074965} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2517997540278803, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7947790137840659, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.385440598751651, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.04280552166316452, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137722.4174964} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137722.4374964, "x": 5.4418883536523195, "y": 5.043617118056763, "z": null, "yaw": 3.1598182935915067, "pitch": null, "roll": null}, "v": 2.384392574265248, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.376072908195375, "steering_wheel_angle": 0.04280552166316452, "front_wheel_angle": 0.001966913889276555, "heading_rate": 0.0018319925468086732, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137722.4374964} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2494056272511468, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7726951451565164, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.383869329810037, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.04280552166316452, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137722.4374964} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.22993779182434, "x": 1.4418883536523195, "y": 0.04361711805676283, "z": null, "yaw": 3.1598182935915067, "pitch": null, "roll": null}, "v": 2.384392574265248, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.376072908195375, "steering_wheel_angle": 0.04280552166316452, "front_wheel_angle": 0.001966913889276555, "heading_rate": 0.0018319925468086732, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137722.4574964} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2505026722726529, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7726951451565164, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3825938193087257, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.04280552166316452, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137722.4574964} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.22993779182434, "x": 1.4418883536523195, "y": 0.04361711805676283, "z": null, "yaw": 3.1598182935915067, "pitch": null, "roll": null}, "v": 2.384392574265248, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.376072908195375, "steering_wheel_angle": 0.04280552166316452, "front_wheel_angle": 0.001966913889276555, "heading_rate": 0.0018319925468086732, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137722.4874964} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2505026722726529, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7726951451565164, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3813892972321113, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.04280552166316452, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137722.4874964} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.22993779182434, "x": 1.4418883536523195, "y": 0.04361711805676283, "z": null, "yaw": 3.1598182935915067, "pitch": null, "roll": null}, "v": 2.384392574265248, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.376072908195375, "steering_wheel_angle": 0.04280552166316452, "front_wheel_angle": 0.001966913889276555, "heading_rate": 0.0018319925468086732, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137722.4974964} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2505026722726529, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7726951451565164, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.380787918102039, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.04280552166316452, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137722.4974964} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.22993779182434, "x": 1.4418883536523195, "y": 0.04361711805676283, "z": null, "yaw": 3.1598182935915067, "pitch": null, "roll": null}, "v": 2.384392574265248, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.376072908195375, "steering_wheel_angle": 0.04280552166316452, "front_wheel_angle": 0.001966913889276555, "heading_rate": 0.0018319925468086732, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137722.5174963} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2505026722726529, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7726951451565164, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.378987300593086, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.04280552166316452, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137722.5174963} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.22993779182434, "x": 1.4418883536523195, "y": 0.04361711805676283, "z": null, "yaw": 3.1598182935915067, "pitch": null, "roll": null}, "v": 2.384392574265248, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.376072908195375, "steering_wheel_angle": 0.04280552166316452, "front_wheel_angle": 0.001966913889276555, "heading_rate": 0.0018319925468086732, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137722.5374963} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2505026722726529, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7726951451565164, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.378388265902192, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.04280552166316452, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137722.5374963} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137722.5474963, "x": 5.179978335331492, "y": 5.0388330518670035, "z": null, "yaw": 3.1599028095316766, "pitch": null, "roll": null}, "v": 2.3777898157119437, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3754283348626316, "steering_wheel_angle": 0.04280552166316452, "front_wheel_angle": 0.001966913889276555, "heading_rate": 0.001826919470928223, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137722.5574963} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2515058339412557, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8089188041108015, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.376594666266289, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.04280552166316452, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137722.5574963} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.33993768692017, "x": 1.1799783353314917, "y": 0.038833051867003476, "z": null, "yaw": 3.1599028095316766, "pitch": null, "roll": null}, "v": 2.3777898157119437, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3754283348626316, "steering_wheel_angle": 0.04280552166316452, "front_wheel_angle": 0.001966913889276555, "heading_rate": 0.001826919470928223, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137722.5774963} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2509790272962633, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8089188041108015, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3755271811957894, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.04280552166316452, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137722.5774963} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.33993768692017, "x": 1.1799783353314917, "y": 0.038833051867003476, "z": null, "yaw": 3.1599028095316766, "pitch": null, "roll": null}, "v": 2.3777898157119437, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3754283348626316, "steering_wheel_angle": 0.04280552166316452, "front_wheel_angle": 0.001966913889276555, "heading_rate": 0.001826919470928223, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137722.5974963} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2509790272962633, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8089188041108015, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.374961293872348, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.04280552166316452, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137722.5974963} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.33993768692017, "x": 1.1799783353314917, "y": 0.038833051867003476, "z": null, "yaw": 3.1599028095316766, "pitch": null, "roll": null}, "v": 2.3777898157119437, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3754283348626316, "steering_wheel_angle": 0.04280552166316452, "front_wheel_angle": 0.001966913889276555, "heading_rate": 0.001826919470928223, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137722.6174963} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2509790272962633, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8089188041108015, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.373266940101683, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.04280552166316452, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137722.6174963} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.33993768692017, "x": 1.1799783353314917, "y": 0.038833051867003476, "z": null, "yaw": 3.1599028095316766, "pitch": null, "roll": null}, "v": 2.3777898157119437, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3754283348626316, "steering_wheel_angle": 0.04280552166316452, "front_wheel_angle": 0.001966913889276555, "heading_rate": 0.001826919470928223, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137722.6374962} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2509790272962633, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8089188041108015, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.372140121744429, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.04280552166316452, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137722.6374962} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137722.6574962, "x": 4.918777680515301, "y": 5.034039859599437, "z": null, "yaw": 3.1599873254718465, "pitch": null, "roll": null}, "v": 2.3715775360138545, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3748226768939482, "steering_wheel_angle": 0.04280552166316452, "front_wheel_angle": 0.001966913889276555, "heading_rate": 0.001822146410389273, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137722.6574962} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2526278768057759, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.863597147858119, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3710154984509315, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.04280552166316452, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137722.6574962} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.44993758201599, "x": 0.9187776805153014, "y": 0.034039859599436895, "z": null, "yaw": 3.1599873254718465, "pitch": null, "roll": null}, "v": 2.3715775360138545, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3748226768939482, "steering_wheel_angle": 0.04280552166316452, "front_wheel_angle": 0.001966913889276555, "heading_rate": 0.001822146410389273, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137722.6774962} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25179656458835536, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.863597147858119, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3705570615526774, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0019150499636457778, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137722.6774962} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.44993758201599, "x": 0.9187776805153014, "y": 0.034039859599436895, "z": null, "yaw": 3.1599873254718465, "pitch": null, "roll": null}, "v": 2.3715775360138545, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3748226768939482, "steering_wheel_angle": 0.04280552166316452, "front_wheel_angle": 0.001966913889276555, "heading_rate": 0.001822146410389273, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137722.6974962} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25179656458835536, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.863597147858119, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3690287092087785, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.038979431126779956, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137722.6974962} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.44993758201599, "x": 0.9187776805153014, "y": 0.034039859599436895, "z": null, "yaw": 3.1599873254718465, "pitch": null, "roll": null}, "v": 2.3715775360138545, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3748226768939482, "steering_wheel_angle": 0.04280552166316452, "front_wheel_angle": 0.001966913889276555, "heading_rate": 0.001822146410389273, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137722.7174962} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25179656458835536, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.863597147858119, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3680122867823203, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.038979431126779956, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137722.7174962} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.44993758201599, "x": 0.9187776805153014, "y": 0.034039859599436895, "z": null, "yaw": 3.1599873254718465, "pitch": null, "roll": null}, "v": 2.3715775360138545, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3748226768939482, "steering_wheel_angle": 0.04280552166316452, "front_wheel_angle": 0.001966913889276555, "heading_rate": 0.001822146410389273, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137722.7474961} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25179656458835536, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.863597147858119, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3669978426783986, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.038979431126779956, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137722.7474961} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.44993758201599, "x": 0.9187776805153014, "y": 0.034039859599436895, "z": null, "yaw": 3.1599873254718465, "pitch": null, "roll": null}, "v": 2.3715775360138545, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3748226768939482, "steering_wheel_angle": 0.04280552166316452, "front_wheel_angle": 0.001966913889276555, "heading_rate": 0.001822146410389273, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137722.757496} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25179656458835536, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.863597147858119, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3659853726350497, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.038979431126779956, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137722.757496} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137722.767496, "x": 4.658228845004504, "y": 5.029247723682814, "z": null, "yaw": 3.1599470662768328, "pitch": null, "roll": null}, "v": 2.3659853726350497, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37427813646698266, "steering_wheel_angle": -0.038979431126779956, "front_wheel_angle": -0.001791015105785413, "heading_rate": -0.0016552812786738192, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137722.777496} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.253555228657496, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9182614023718536, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3649748724010062, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.038979431126779956, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137722.777496} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.55993747711182, "x": 0.658228845004504, "y": 0.02924772368281392, "z": null, "yaw": 3.1599470662768328, "pitch": null, "roll": null}, "v": 2.3659853726350497, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37427813646698266, "steering_wheel_angle": -0.038979431126779956, "front_wheel_angle": -0.001791015105785413, "heading_rate": -0.0016552812786738192, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137722.797496} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2526762803434443, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9182614023718536, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.364186063805982, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.07989146541480008, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137722.797496} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.55993747711182, "x": 0.658228845004504, "y": 0.02924772368281392, "z": null, "yaw": 3.1599470662768328, "pitch": null, "roll": null}, "v": 2.3659853726350497, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37427813646698266, "steering_wheel_angle": -0.038979431126779956, "front_wheel_angle": -0.001791015105785413, "heading_rate": -0.0016552812786738192, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137722.817496} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2526762803434443, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9182614023718536, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3632889741895373, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.07989146541480008, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137722.817496} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.55993747711182, "x": 0.658228845004504, "y": 0.02924772368281392, "z": null, "yaw": 3.1599470662768328, "pitch": null, "roll": null}, "v": 2.3659853726350497, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37427813646698266, "steering_wheel_angle": -0.038979431126779956, "front_wheel_angle": -0.001791015105785413, "heading_rate": -0.0016552812786738192, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137722.837496} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2526762803434443, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9182614023718536, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.362841083746355, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.07989146541480008, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137722.837496} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.55993747711182, "x": 0.658228845004504, "y": 0.02924772368281392, "z": null, "yaw": 3.1599470662768328, "pitch": null, "roll": null}, "v": 2.3659853726350497, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37427813646698266, "steering_wheel_angle": -0.038979431126779956, "front_wheel_angle": -0.001791015105785413, "heading_rate": -0.0016552812786738192, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137722.857496} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2526762803434443, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9182614023718536, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.361946609268445, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.07989146541480008, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137722.857496} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137722.877496, "x": 4.3982632439444584, "y": 5.0244896284670375, "z": null, "yaw": 3.1598113022417857, "pitch": null, "roll": null}, "v": 2.3610538735796043, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3737984476184327, "steering_wheel_angle": -0.07989146541480008, "front_wheel_angle": -0.00367280122392165, "heading_rate": -0.0033873908394392734, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137722.877496} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2530564781512573, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9356344204650995, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3610538735796043, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.07989146541480008, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137722.877496} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.66993737220764, "x": 0.39826324394445844, "y": 0.024489628467037505, "z": null, "yaw": 3.1598113022417857, "pitch": null, "roll": null}, "v": 2.3610538735796043, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3737984476184327, "steering_wheel_angle": -0.07989146541480008, "front_wheel_angle": -0.00367280122392165, "heading_rate": -0.0033873908394392734, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137722.897496} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.252838883745616, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9356344204650995, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3597756403526957, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.07989146541480008, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137722.897496} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.66993737220764, "x": 0.39826324394445844, "y": 0.024489628467037505, "z": null, "yaw": 3.1598113022417857, "pitch": null, "roll": null}, "v": 2.3610538735796043, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3737984476184327, "steering_wheel_angle": -0.07989146541480008, "front_wheel_angle": -0.00367280122392165, "heading_rate": -0.0033873908394392734, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137722.917496} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.252838883745616, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9356344204650995, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3589074390785996, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.07989146541480008, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137722.917496} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.66993737220764, "x": 0.39826324394445844, "y": 0.024489628467037505, "z": null, "yaw": 3.1598113022417857, "pitch": null, "roll": null}, "v": 2.3610538735796043, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3737984476184327, "steering_wheel_angle": -0.07989146541480008, "front_wheel_angle": -0.00367280122392165, "heading_rate": -0.0033873908394392734, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137722.947496} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.252838883745616, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9356344204650995, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.358040924463802, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.07989146541480008, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137722.947496} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.66993737220764, "x": 0.39826324394445844, "y": 0.024489628467037505, "z": null, "yaw": 3.1598113022417857, "pitch": null, "roll": null}, "v": 2.3610538735796043, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3737984476184327, "steering_wheel_angle": -0.07989146541480008, "front_wheel_angle": -0.00367280122392165, "heading_rate": -0.0033873908394392734, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137722.957496} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.252838883745616, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9356344204650995, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.356744307205754, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.07989146541480008, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137722.957496} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.66993737220764, "x": 0.39826324394445844, "y": 0.024489628467037505, "z": null, "yaw": 3.1598113022417857, "pitch": null, "roll": null}, "v": 2.3610538735796043, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3737984476184327, "steering_wheel_angle": -0.07989146541480008, "front_wheel_angle": -0.00367280122392165, "heading_rate": -0.0033873908394392734, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137722.977496} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.252838883745616, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9356344204650995, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.356744307205754, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.07989146541480008, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137722.977496} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137722.987496, "x": 4.138826326150411, "y": 5.019781125367728, "z": null, "yaw": 3.159653485854577, "pitch": null, "roll": null}, "v": 2.3563129409132975, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3733377538008196, "steering_wheel_angle": -0.07989146541480008, "front_wheel_angle": -0.00367280122392165, "heading_rate": -0.003380589049753764, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137722.997496} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25091632156925675, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8914507677049465, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3558819936093904, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.07989146541480008, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137722.997496} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.77993726730347, "x": 0.13882632615041057, "y": 0.019781125367727803, "z": null, "yaw": 3.159653485854577, "pitch": null, "roll": null}, "v": 2.3563129409132975, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3733377538008196, "steering_wheel_angle": -0.07989146541480008, "front_wheel_angle": -0.00367280122392165, "heading_rate": -0.003380589049753764, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137723.0174959} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25179672732598224, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8914507677049465, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3542315307001607, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.07989146541480008, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137723.0174959} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.77993726730347, "x": 0.13882632615041057, "y": 0.019781125367727803, "z": null, "yaw": 3.159653485854577, "pitch": null, "roll": null}, "v": 2.3563129409132975, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3733377538008196, "steering_wheel_angle": -0.07989146541480008, "front_wheel_angle": -0.00367280122392165, "heading_rate": -0.003380589049753764, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137723.0374959} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25179672732598224, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8914507677049465, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3537374697826703, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.07989146541480008, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137723.0374959} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.77993726730347, "x": 0.13882632615041057, "y": 0.019781125367727803, "z": null, "yaw": 3.159653485854577, "pitch": null, "roll": null}, "v": 2.3563129409132975, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3733377538008196, "steering_wheel_angle": -0.07989146541480008, "front_wheel_angle": -0.00367280122392165, "heading_rate": -0.003380589049753764, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137723.0574958} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25179672732598224, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8914507677049465, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3522581627701866, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.07989146541480008, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137723.0574958} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.77993726730347, "x": 0.13882632615041057, "y": 0.019781125367727803, "z": null, "yaw": 3.159653485854577, "pitch": null, "roll": null}, "v": 2.3563129409132975, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3733377538008196, "steering_wheel_angle": -0.07989146541480008, "front_wheel_angle": -0.00367280122392165, "heading_rate": -0.003380589049753764, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137723.0774958} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25179672732598224, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8914507677049465, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3517660173002435, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.07989146541480008, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137723.0774958} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137723.0974958, "x": 3.879952523032514, "y": 5.015123708845436, "z": null, "yaw": 3.1594956694673684, "pitch": null, "roll": null}, "v": 2.3507831585860046, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3728009725162162, "steering_wheel_angle": -0.07989146541480008, "front_wheel_angle": -0.00367280122392165, "heading_rate": -0.0033726555018541698, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137723.0974958} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2538458212932708, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9423154543226281, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3507831585860046, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.07989146541480008, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137723.0974958} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.88993716239929, "x": -0.12004747696748597, "y": 0.01512370884543568, "z": null, "yaw": 3.1594956694673684, "pitch": null, "roll": null}, "v": 2.3507831585860046, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3728009725162162, "steering_wheel_angle": -0.07989146541480008, "front_wheel_angle": -0.00367280122392165, "heading_rate": -0.0033726555018541698, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137723.1174958} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2528291641316799, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9423154543226281, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.349632734893349, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.1207865507262876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137723.1174958} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.88993716239929, "x": -0.12004747696748597, "y": 0.01512370884543568, "z": null, "yaw": 3.1594956694673684, "pitch": null, "roll": null}, "v": 2.3507831585860046, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3728009725162162, "steering_wheel_angle": -0.07989146541480008, "front_wheel_angle": -0.00367280122392165, "heading_rate": -0.0033726555018541698, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137723.1374958} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2528291641316799, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9423154543226281, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3487830051467258, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.1207865507262876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137723.1374958} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.88993716239929, "x": -0.12004747696748597, "y": 0.01512370884543568, "z": null, "yaw": 3.1594956694673684, "pitch": null, "roll": null}, "v": 2.3507831585860046, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3728009725162162, "steering_wheel_angle": -0.07989146541480008, "front_wheel_angle": -0.00367280122392165, "heading_rate": -0.0033726555018541698, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137723.1574957} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2528291641316799, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9423154543226281, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3479349227352238, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.1207865507262876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137723.1574957} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.88993716239929, "x": -0.12004747696748597, "y": 0.01512370884543568, "z": null, "yaw": 3.1594956694673684, "pitch": null, "roll": null}, "v": 2.3507831585860046, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3728009725162162, "steering_wheel_angle": -0.07989146541480008, "front_wheel_angle": -0.00367280122392165, "heading_rate": -0.0033726555018541698, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137723.1874957} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2528291641316799, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9423154543226281, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.347088484177666, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.1207865507262876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137723.1874957} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.88993716239929, "x": -0.12004747696748597, "y": 0.01512370884543568, "z": null, "yaw": 3.1594956694673684, "pitch": null, "roll": null}, "v": 2.3507831585860046, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3728009725162162, "steering_wheel_angle": -0.07989146541480008, "front_wheel_angle": -0.00367280122392165, "heading_rate": -0.0033726555018541698, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137723.1974957} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2528291641316799, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9423154543226281, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.346665880258551, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.1207865507262876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137723.1974957} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137723.2074957, "x": 3.621629009908076, "y": 5.010524747471449, "z": null, "yaw": 3.159264295564246, "pitch": null, "roll": null}, "v": 2.3462436860012947, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3723607786410742, "steering_wheel_angle": -0.1207865507262876, "front_wheel_angle": -0.005555832980885663, "heading_rate": -0.005091981318494953, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137723.2174957} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25473413035327497, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9946994354429721, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3455195851305985, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.1616965954722383, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137723.2174957} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.99993705749512, "x": -0.3783709900919239, "y": 0.01052474747144938, "z": null, "yaw": 3.159264295564246, "pitch": null, "roll": null}, "v": 2.3462436860012947, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3723607786410742, "steering_wheel_angle": -0.1207865507262876, "front_wheel_angle": -0.005555832980885663, "heading_rate": -0.005091981318494953, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137723.2374957} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25379346453021995, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9946994354429721, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3449158320971937, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.1616965954722383, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137723.2374957} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.99993705749512, "x": -0.3783709900919239, "y": 0.01052474747144938, "z": null, "yaw": 3.159264295564246, "pitch": null, "roll": null}, "v": 2.3462436860012947, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3723607786410742, "steering_wheel_angle": -0.1207865507262876, "front_wheel_angle": -0.005555832980885663, "heading_rate": -0.005091981318494953, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137723.2574956} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25379346453021995, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9946994354429721, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3441957223227066, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.1616965954722383, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137723.2574956} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.99993705749512, "x": -0.3783709900919239, "y": 0.01052474747144938, "z": null, "yaw": 3.159264295564246, "pitch": null, "roll": null}, "v": 2.3462436860012947, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3723607786410742, "steering_wheel_angle": -0.1207865507262876, "front_wheel_angle": -0.005555832980885663, "heading_rate": -0.005091981318494953, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137723.2774956} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25379346453021995, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9946994354429721, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.343477007265195, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.1616965954722383, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137723.2774956} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.99993705749512, "x": -0.3783709900919239, "y": 0.01052474747144938, "z": null, "yaw": 3.159264295564246, "pitch": null, "roll": null}, "v": 2.3462436860012947, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3723607786410742, "steering_wheel_angle": -0.1207865507262876, "front_wheel_angle": -0.005555832980885663, "heading_rate": -0.005091981318494953, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137723.2974956} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25379346453021995, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9946994354429721, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.342759684016835, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.1616965954722383, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137723.2974956} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137723.3174956, "x": 3.3637720673659333, "y": 5.006001714994571, "z": null, "yaw": 3.158959267084502, "pitch": null, "roll": null}, "v": 2.34240154341426, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37198852707660807, "steering_wheel_angle": -0.1616965954722383, "front_wheel_angle": -0.007441586023551901, "heading_rate": -0.006809181389656917, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137723.3174956} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25558222832323974, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0470906688053472, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3420437496766326, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.1616965954722383, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137723.3174956} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 66.10993695259094, "x": -0.6362279326340667, "y": 0.006001714994570584, "z": null, "yaw": 3.158959267084502, "pitch": null, "roll": null}, "v": 2.34240154341426, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37198852707660807, "steering_wheel_angle": -0.1616965954722383, "front_wheel_angle": -0.007441586023551901, "heading_rate": -0.006809181389656917, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137723.3374956} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2547020735772143, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0470906688053472, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.341798100179457, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.20262167291033456, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137723.3374956} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 66.10993695259094, "x": -0.6362279326340667, "y": 0.006001714994570584, "z": null, "yaw": 3.158959267084502, "pitch": null, "roll": null}, "v": 2.34240154341426, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37198852707660807, "steering_wheel_angle": -0.1616965954722383, "front_wheel_angle": -0.007441586023551901, "heading_rate": -0.006809181389656917, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137723.3574955} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2547020735772143, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0470906688053472, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3408977087430465, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.20262167291033456, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137723.3574955} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 66.10993695259094, "x": -0.6362279326340667, "y": 0.006001714994570584, "z": null, "yaw": 3.158959267084502, "pitch": null, "roll": null}, "v": 2.34240154341426, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37198852707660807, "steering_wheel_angle": -0.1616965954722383, "front_wheel_angle": -0.007441586023551901, "heading_rate": -0.006809181389656917, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137723.3774955} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2547020735772143, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0470906688053472, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.340598159278971, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.20262167291033456, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137723.3774955} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 66.10993695259094, "x": -0.6362279326340667, "y": 0.006001714994570584, "z": null, "yaw": 3.158959267084502, "pitch": null, "roll": null}, "v": 2.34240154341426, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37198852707660807, "steering_wheel_angle": -0.1616965954722383, "front_wheel_angle": -0.007441586023551901, "heading_rate": -0.006809181389656917, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137723.3974955} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2547020735772143, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0470906688053472, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.339701249744458, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.20262167291033456, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137723.3974955} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137723.4274955, "x": 3.1063117704020033, "y": 5.001573690431945, "z": null, "yaw": 3.158573108738822, "pitch": null, "roll": null}, "v": 2.3391047561202223, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37166934840705357, "steering_wheel_angle": -0.20262167291033456, "front_wheel_angle": -0.009330072563430186, "heading_rate": -0.008525254059451239, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137723.4274955} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2565452400119218, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1034121933585563, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.33855743820126, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.28446651796552397, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137723.4274955} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 66.21993684768677, "x": -0.8936882295979967, "y": 0.0015736904319449962, "z": null, "yaw": 3.158573108738822, "pitch": null, "roll": null}, "v": 2.3391047561202223, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37166934840705357, "steering_wheel_angle": -0.20262167291033456, "front_wheel_angle": -0.009330072563430186, "heading_rate": -0.008525254059451239, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137723.4574955} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25564322288426, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1034121933585563, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.337842743103858, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.28446651796552397, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137723.4574955} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 66.21993684768677, "x": -0.8936882295979967, "y": 0.0015736904319449962, "z": null, "yaw": 3.158573108738822, "pitch": null, "roll": null}, "v": 2.3391047561202223, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37166934840705357, "steering_wheel_angle": -0.20262167291033456, "front_wheel_angle": -0.009330072563430186, "heading_rate": -0.008525254059451239, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137723.4874954} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25564322288426, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1034121933585563, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3376049722934242, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.28446651796552397, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137723.4874954} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 66.21993684768677, "x": -0.8936882295979967, "y": 0.0015736904319449962, "z": null, "yaw": 3.158573108738822, "pitch": null, "roll": null}, "v": 2.3391047561202223, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37166934840705357, "steering_wheel_angle": -0.20262167291033456, "front_wheel_angle": -0.009330072563430186, "heading_rate": -0.008525254059451239, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137723.5074954} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25564322288426, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1034121933585563, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3373674315368946, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.28446651796552397, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137723.5074954} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 66.21993684768677, "x": -0.8936882295979967, "y": 0.0015736904319449962, "z": null, "yaw": 3.158573108738822, "pitch": null, "roll": null}, "v": 2.3391047561202223, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37166934840705357, "steering_wheel_angle": -0.20262167291033456, "front_wheel_angle": -0.009330072563430186, "heading_rate": -0.008525254059451239, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137723.5274954} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25564322288426, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1034121933585563, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.336893039250296, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.28446651796552397, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137723.5274954} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137723.5374954, "x": 2.849162204013241, "y": 4.997267612326281, "z": null, "yaw": 3.15803179766737, "pitch": null, "roll": null}, "v": 2.336656187253247, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3714324307369512, "steering_wheel_angle": -0.28446651796552397, "front_wheel_angle": -0.013112949359346796, "heading_rate": -0.01196961350681581, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137723.5474954} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25752527585023044, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1582886383526763, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.336419564376144, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.28446651796552397, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137723.5474954} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 66.32993674278259, "x": -1.1508377959867588, "y": -0.0027323876737188613, "z": null, "yaw": 3.15803179766737, "pitch": null, "roll": null}, "v": 2.336656187253247, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3714324307369512, "steering_wheel_angle": -0.28446651796552397, "front_wheel_angle": -0.013112949359346796, "heading_rate": -0.01196961350681581, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137723.5674953} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2566110088253299, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1582886383526763, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3361821478956073, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.325384661404049, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137723.5674953} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 66.32993674278259, "x": -1.1508377959867588, "y": -0.0027323876737188613, "z": null, "yaw": 3.15803179766737, "pitch": null, "roll": null}, "v": 2.336656187253247, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3714324307369512, "steering_wheel_angle": -0.28446651796552397, "front_wheel_angle": -0.013112949359346796, "heading_rate": -0.01196961350681581, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137723.5874953} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2566110088253299, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1582886383526763, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3358309623640583, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.325384661404049, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137723.5874953} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 66.32993674278259, "x": -1.1508377959867588, "y": -0.0027323876737188613, "z": null, "yaw": 3.15803179766737, "pitch": null, "roll": null}, "v": 2.336656187253247, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3714324307369512, "steering_wheel_angle": -0.28446651796552397, "front_wheel_angle": -0.013112949359346796, "heading_rate": -0.01196961350681581, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137723.6074953} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2566110088253299, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1582886383526763, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3354804558258806, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.325384661404049, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137723.6074953} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 66.32993674278259, "x": -1.1508377959867588, "y": -0.0027323876737188613, "z": null, "yaw": 3.15803179766737, "pitch": null, "roll": null}, "v": 2.336656187253247, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3714324307369512, "steering_wheel_angle": -0.28446651796552397, "front_wheel_angle": -0.013112949359346796, "heading_rate": -0.01196961350681581, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137723.6274953} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2566110088253299, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1582886383526763, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.334955966152814, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.325384661404049, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137723.6274953} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137723.6474953, "x": 2.592256509396931, "y": 4.993115953895667, "z": null, "yaw": 3.157401707676176, "pitch": null, "roll": null}, "v": 2.3347814742849335, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.371251119040888, "steering_wheel_angle": -0.325384661404049, "front_wheel_angle": -0.015007277232236625, "heading_rate": -0.013688024825081248, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137723.6474953} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2584597645964174, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2147195702968432, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3347814742849335, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.325384661404049, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137723.6474953} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 66.43993663787842, "x": -1.4077434906030688, "y": -0.00688404610433313, "z": null, "yaw": 3.157401707676176, "pitch": null, "roll": null}, "v": 2.3347814742849335, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.371251119040888, "steering_wheel_angle": -0.325384661404049, "front_wheel_angle": -0.015007277232236625, "heading_rate": -0.013688024825081248, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137723.6674953} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25756559003428214, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2147195702968432, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.334605317020042, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.36632260524063104, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137723.6674953} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 66.43993663787842, "x": -1.4077434906030688, "y": -0.00688404610433313, "z": null, "yaw": 3.157401707676176, "pitch": null, "roll": null}, "v": 2.3347814742849335, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.371251119040888, "steering_wheel_angle": -0.325384661404049, "front_wheel_angle": -0.015007277232236625, "heading_rate": -0.013688024825081248, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137723.6874952} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25756559003428214, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2147195702968432, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.334490825540049, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.36632260524063104, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137723.6874952} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 66.43993663787842, "x": -1.4077434906030688, "y": -0.00688404610433313, "z": null, "yaw": 3.157401707676176, "pitch": null, "roll": null}, "v": 2.3347814742849335, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.371251119040888, "steering_wheel_angle": -0.325384661404049, "front_wheel_angle": -0.015007277232236625, "heading_rate": -0.013688024825081248, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137723.7074952} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25756559003428214, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2147195702968432, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.334148014879029, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.36632260524063104, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137723.7074952} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 66.43993663787842, "x": -1.4077434906030688, "y": -0.00688404610433313, "z": null, "yaw": 3.157401707676176, "pitch": null, "roll": null}, "v": 2.3347814742849335, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.371251119040888, "steering_wheel_angle": -0.325384661404049, "front_wheel_angle": -0.015007277232236625, "heading_rate": -0.013688024825081248, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137723.7274952} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25756559003428214, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2147195702968432, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.334033965553196, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.36632260524063104, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137723.7274952} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 66.43993663787842, "x": -1.4077434906030688, "y": -0.00688404610433313, "z": null, "yaw": 3.157401707676176, "pitch": null, "roll": null}, "v": 2.3347814742849335, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.371251119040888, "steering_wheel_angle": -0.325384661404049, "front_wheel_angle": -0.015007277232236625, "heading_rate": -0.013688024825081248, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137723.7474952} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25756559003428214, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2147195702968432, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3338061975872164, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.36632260524063104, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137723.7474952} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137723.7574952, "x": 2.335509191414302, "y": 4.98913974396683, "z": null, "yaw": 3.1566826826326966, "pitch": null, "roll": null}, "v": 2.333692478728776, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3711458297891914, "steering_wheel_angle": -0.36632260524063104, "front_wheel_angle": -0.016904590284048643, "heading_rate": -0.015411669318149105, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137723.7674952} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25930542560691255, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.272733217018814, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.333465370716104, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.36632260524063104, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137723.7674952} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 66.54993653297424, "x": -1.6644908085856982, "y": -0.010860256033169868, "z": null, "yaw": 3.1566826826326966, "pitch": null, "roll": null}, "v": 2.333692478728776, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3711458297891914, "steering_wheel_angle": -0.36632260524063104, "front_wheel_angle": -0.016904590284048643, "heading_rate": -0.015411669318149105, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137723.7874951} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25846891002098793, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.272733217018814, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.333403793689646, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.44819705342305094, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137723.7874951} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 66.54993653297424, "x": -1.6644908085856982, "y": -0.010860256033169868, "z": null, "yaw": 3.1566826826326966, "pitch": null, "roll": null}, "v": 2.333692478728776, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3711458297891914, "steering_wheel_angle": -0.36632260524063104, "front_wheel_angle": -0.016904590284048643, "heading_rate": -0.015411669318149105, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137723.807495} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25846891002098793, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.272733217018814, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.333233341526175, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.44819705342305094, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137723.807495} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 66.54993653297424, "x": -1.6644908085856982, "y": -0.010860256033169868, "z": null, "yaw": 3.1566826826326966, "pitch": null, "roll": null}, "v": 2.333692478728776, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3711458297891914, "steering_wheel_angle": -0.36632260524063104, "front_wheel_angle": -0.016904590284048643, "heading_rate": -0.015411669318149105, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137723.827495} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25846891002098793, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.272733217018814, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.333233341526175, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.44819705342305094, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137723.827495} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 66.54993653297424, "x": -1.6644908085856982, "y": -0.010860256033169868, "z": null, "yaw": 3.1566826826326966, "pitch": null, "roll": null}, "v": 2.333692478728776, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3711458297891914, "steering_wheel_angle": -0.36632260524063104, "front_wheel_angle": -0.016904590284048643, "heading_rate": -0.015411669318149105, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137723.847495} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25846891002098793, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.272733217018814, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.333119981187939, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.44819705342305094, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137723.847495} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137723.867495, "x": 2.0788687152516374, "y": 4.985359985624941, "z": null, "yaw": 3.1558448536956307, "pitch": null, "roll": null}, "v": 2.3330068398987143, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3710795511450776, "steering_wheel_angle": -0.44819705342305094, "front_wheel_angle": -0.020705383714734966, "heading_rate": -0.018872150828212607, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137723.867495} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2602595983951187, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3313645025961207, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3330068398987143, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.44819705342305094, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137723.867495} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 66.65993642807007, "x": -1.9211312847483626, "y": -0.014640014375059351, "z": null, "yaw": 3.1558448536956307, "pitch": null, "roll": null}, "v": 2.3330068398987143, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3710795511450776, "steering_wheel_angle": -0.44819705342305094, "front_wheel_angle": -0.020705383714734966, "heading_rate": -0.018872150828212607, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137723.887495} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25940183941558825, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3313645025961207, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.333117645096773, "gear": 1, "accelerator_pedal_position": 0.2602595983951187, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.48913430168275096, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137723.887495} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 66.65993642807007, "x": -1.9211312847483626, "y": -0.014640014375059351, "z": null, "yaw": 3.1558448536956307, "pitch": null, "roll": null}, "v": 2.3330068398987143, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3710795511450776, "steering_wheel_angle": -0.44819705342305094, "front_wheel_angle": -0.020705383714734966, "heading_rate": -0.018872150828212607, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137723.907495} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25940183941558825, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3313645025961207, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.333121068134258, "gear": 1, "accelerator_pedal_position": 0.25940183941558825, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.48913430168275096, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137723.907495} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 66.65993642807007, "x": -1.9211312847483626, "y": -0.014640014375059351, "z": null, "yaw": 3.1558448536956307, "pitch": null, "roll": null}, "v": 2.3330068398987143, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3710795511450776, "steering_wheel_angle": -0.44819705342305094, "front_wheel_angle": -0.020705383714734966, "heading_rate": -0.018872150828212607, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137723.927495} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25940183941558825, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3313645025961207, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3331244845573607, "gear": 1, "accelerator_pedal_position": 0.25940183941558825, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.48913430168275096, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137723.927495} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 66.65993642807007, "x": -1.9211312847483626, "y": -0.014640014375059351, "z": null, "yaw": 3.1558448536956307, "pitch": null, "roll": null}, "v": 2.3330068398987143, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3710795511450776, "steering_wheel_angle": -0.44819705342305094, "front_wheel_angle": -0.020705383714734966, "heading_rate": -0.018872150828212607, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137723.947495} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25940183941558825, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3313645025961207, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.333127894378857, "gear": 1, "accelerator_pedal_position": 0.25940183941558825, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.48913430168275096, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137723.947495} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 66.65993642807007, "x": -1.9211312847483626, "y": -0.014640014375059351, "z": null, "yaw": 3.1558448536956307, "pitch": null, "roll": null}, "v": 2.3330068398987143, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3710795511450776, "steering_wheel_angle": -0.44819705342305094, "front_wheel_angle": -0.020705383714734966, "heading_rate": -0.018872150828212607, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137723.967495} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25940183941558825, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3313645025961207, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3331312976114993, "gear": 1, "accelerator_pedal_position": 0.25940183941558825, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.48913430168275096, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137723.967495} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137723.977495, "x": 1.8222513293550997, "y": 4.981813999476046, "z": null, "yaw": 3.154880650585149, "pitch": null, "roll": null}, "v": 2.333132996760978, "accelerator_pedal_position": 0.25940183941558825, "brake_pedal_position": 0.0, "acceleration": 0.00016975070362895694, "steering_wheel_angle": -0.48913430168275096, "front_wheel_angle": -0.022608912250332194, "heading_rate": -0.020608823792894082, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137723.987495} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26112054541911806, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3898493020665574, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3331346942680145, "gear": 1, "accelerator_pedal_position": 0.25940183941558825, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.48913430168275096, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137723.987495} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 66.7699363231659, "x": -2.1777486706449003, "y": -0.01818600052395425, "z": null, "yaw": 3.154880650585149, "pitch": null, "roll": null}, "v": 2.333132996760978, "accelerator_pedal_position": 0.25940183941558825, "brake_pedal_position": 0.0, "acceleration": 0.00016975070362895694, "steering_wheel_angle": -0.48913430168275096, "front_wheel_angle": -0.022608912250332194, "heading_rate": -0.020608823792894082, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137724.007495} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2603030426851518, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3898493020665574, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.333352818776136, "gear": 1, "accelerator_pedal_position": 0.26112054541911806, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5710084342325877, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137724.007495} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 66.7699363231659, "x": -2.1777486706449003, "y": -0.01818600052395425, "z": null, "yaw": 3.154880650585149, "pitch": null, "roll": null}, "v": 2.333132996760978, "accelerator_pedal_position": 0.25940183941558825, "brake_pedal_position": 0.0, "acceleration": 0.00016975070362895694, "steering_wheel_angle": -0.48913430168275096, "front_wheel_angle": -0.022608912250332194, "heading_rate": -0.020608823792894082, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137724.027495} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2603030426851518, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3898493020665574, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3334683833338525, "gear": 1, "accelerator_pedal_position": 0.2603030426851518, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5710084342325877, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137724.027495} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 66.7699363231659, "x": -2.1777486706449003, "y": -0.01818600052395425, "z": null, "yaw": 3.154880650585149, "pitch": null, "roll": null}, "v": 2.333132996760978, "accelerator_pedal_position": 0.25940183941558825, "brake_pedal_position": 0.0, "acceleration": 0.00016975070362895694, "steering_wheel_angle": -0.48913430168275096, "front_wheel_angle": -0.022608912250332194, "heading_rate": -0.020608823792894082, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137724.047495} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2603030426851518, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3898493020665574, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3335837245698445, "gear": 1, "accelerator_pedal_position": 0.2603030426851518, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5710084342325877, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137724.047495} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 66.7699363231659, "x": -2.1777486706449003, "y": -0.01818600052395425, "z": null, "yaw": 3.154880650585149, "pitch": null, "roll": null}, "v": 2.333132996760978, "accelerator_pedal_position": 0.25940183941558825, "brake_pedal_position": 0.0, "acceleration": 0.00016975070362895694, "steering_wheel_angle": -0.48913430168275096, "front_wheel_angle": -0.022608912250332194, "heading_rate": -0.020608823792894082, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137724.0674949} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2603030426851518, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3898493020665574, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3336988429103487, "gear": 1, "accelerator_pedal_position": 0.2603030426851518, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5710084342325877, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137724.0674949} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137724.0874949, "x": 1.5655928828269705, "y": 4.978527833568505, "z": null, "yaw": 3.1537823177200015, "pitch": null, "roll": null}, "v": 2.33381373878081, "accelerator_pedal_position": 0.2603030426851518, "brake_pedal_position": 0.0, "acceleration": 0.005736464169937616, "steering_wheel_angle": -0.5710084342325877, "front_wheel_angle": -0.026422248265757824, "heading_rate": -0.024093343788271118, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137724.0974948} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26202350941306735, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4479845165846192, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3339284126058812, "gear": 1, "accelerator_pedal_position": 0.2603030426851518, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5710084342325877, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137724.0974948} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 66.87993621826172, "x": -2.4344071171730297, "y": -0.02147216643149541, "z": null, "yaw": 3.1537823177200015, "pitch": null, "roll": null}, "v": 2.33381373878081, "accelerator_pedal_position": 0.2603030426851518, "brake_pedal_position": 0.0, "acceleration": 0.005736464169937616, "steering_wheel_angle": -0.5710084342325877, "front_wheel_angle": -0.026422248265757824, "heading_rate": -0.024093343788271118, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137724.1174948} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26120925300013864, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4479845165846192, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.334371392636633, "gear": 1, "accelerator_pedal_position": 0.26120925300013864, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6119449499682529, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137724.1174948} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 66.87993621826172, "x": -2.4344071171730297, "y": -0.02147216643149541, "z": null, "yaw": 3.1537823177200015, "pitch": null, "roll": null}, "v": 2.33381373878081, "accelerator_pedal_position": 0.2603030426851518, "brake_pedal_position": 0.0, "acceleration": 0.005736464169937616, "steering_wheel_angle": -0.5710084342325877, "front_wheel_angle": -0.026422248265757824, "heading_rate": -0.024093343788271118, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137724.1374948} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26120925300013864, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4479845165846192, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3344848562729474, "gear": 1, "accelerator_pedal_position": 0.26120925300013864, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6119449499682529, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137724.1374948} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 66.87993621826172, "x": -2.4344071171730297, "y": -0.02147216643149541, "z": null, "yaw": 3.1537823177200015, "pitch": null, "roll": null}, "v": 2.33381373878081, "accelerator_pedal_position": 0.2603030426851518, "brake_pedal_position": 0.0, "acceleration": 0.005736464169937616, "steering_wheel_angle": -0.5710084342325877, "front_wheel_angle": -0.026422248265757824, "heading_rate": -0.024093343788271118, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137724.1674948} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26120925300013864, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4479845165846192, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3347114545300016, "gear": 1, "accelerator_pedal_position": 0.26120925300013864, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6119449499682529, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137724.1674948} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 66.87993621826172, "x": -2.4344071171730297, "y": -0.02147216643149541, "z": null, "yaw": 3.1537823177200015, "pitch": null, "roll": null}, "v": 2.33381373878081, "accelerator_pedal_position": 0.2603030426851518, "brake_pedal_position": 0.0, "acceleration": 0.005736464169937616, "steering_wheel_angle": -0.5710084342325877, "front_wheel_angle": -0.026422248265757824, "heading_rate": -0.024093343788271118, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137724.1874948} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26120925300013864, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4479845165846192, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.334937614789177, "gear": 1, "accelerator_pedal_position": 0.26120925300013864, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6119449499682529, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137724.1874948} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137724.1974947, "x": 1.3088314125743548, "y": 4.975535290668902, "z": null, "yaw": 3.152586996308958, "pitch": null, "roll": null}, "v": 2.3350505309277954, "accelerator_pedal_position": 0.26120925300013864, "brake_pedal_position": 0.0, "acceleration": 0.011280694884614861, "steering_wheel_angle": -0.6119449499682529, "front_wheel_angle": -0.02833205242523466, "heading_rate": -0.02584940672084105, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137724.2074947} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26285286992082, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.5077223758431035, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3351633378766414, "gear": 1, "accelerator_pedal_position": 0.26120925300013864, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6119449499682529, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137724.2074947} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 66.98993611335754, "x": -2.6911685874256452, "y": -0.0244647093310979, "z": null, "yaw": 3.152586996308958, "pitch": null, "roll": null}, "v": 2.3350505309277954, "accelerator_pedal_position": 0.26120925300013864, "brake_pedal_position": 0.0, "acceleration": 0.011280694884614861, "steering_wheel_angle": -0.6119449499682529, "front_wheel_angle": -0.02833205242523466, "heading_rate": -0.02584940672084105, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137724.2274947} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2620793059534182, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.5077223758431035, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.335593977389346, "gear": 1, "accelerator_pedal_position": 0.26285286992082, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.693820523981195, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137724.2274947} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 66.98993611335754, "x": -2.6911685874256452, "y": -0.0244647093310979, "z": null, "yaw": 3.152586996308958, "pitch": null, "roll": null}, "v": 2.3350505309277954, "accelerator_pedal_position": 0.26120925300013864, "brake_pedal_position": 0.0, "acceleration": 0.011280694884614861, "steering_wheel_angle": -0.6119449499682529, "front_wheel_angle": -0.02833205242523466, "heading_rate": -0.02584940672084105, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137724.2474947} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2620793059534182, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.5077223758431035, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3359271356281748, "gear": 1, "accelerator_pedal_position": 0.2620793059534182, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.693820523981195, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137724.2474947} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 66.98993611335754, "x": -2.6911685874256452, "y": -0.0244647093310979, "z": null, "yaw": 3.152586996308958, "pitch": null, "roll": null}, "v": 2.3350505309277954, "accelerator_pedal_position": 0.26120925300013864, "brake_pedal_position": 0.0, "acceleration": 0.011280694884614861, "steering_wheel_angle": -0.6119449499682529, "front_wheel_angle": -0.02833205242523466, "heading_rate": -0.02584940672084105, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137724.2674947} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2620793059534182, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.5077223758431035, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.336259649738162, "gear": 1, "accelerator_pedal_position": 0.2620793059534182, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.693820523981195, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137724.2674947} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 66.98993611335754, "x": -2.6911685874256452, "y": -0.0244647093310979, "z": null, "yaw": 3.152586996308958, "pitch": null, "roll": null}, "v": 2.3350505309277954, "accelerator_pedal_position": 0.26120925300013864, "brake_pedal_position": 0.0, "acceleration": 0.011280694884614861, "steering_wheel_angle": -0.6119449499682529, "front_wheel_angle": -0.02833205242523466, "heading_rate": -0.02584940672084105, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137724.2874947} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2620793059534182, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.5077223758431035, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.336591520920464, "gear": 1, "accelerator_pedal_position": 0.2620793059534182, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.693820523981195, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137724.2874947} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137724.3074946, "x": 1.0518953012593586, "y": 4.972863771761673, "z": null, "yaw": 3.151242123579341, "pitch": null, "roll": null}, "v": 2.3369227503741694, "accelerator_pedal_position": 0.2620793059534182, "brake_pedal_position": 0.0, "acceleration": 0.016537445277991558, "steering_wheel_angle": -0.693820523981195, "front_wheel_angle": -0.03215813831088136, "heading_rate": -0.0293660162018731, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137724.3074946} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2636950433697062, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.5661040661772458, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3369227503741694, "gear": 1, "accelerator_pedal_position": 0.2620793059534182, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.693820523981195, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137724.3074946} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 67.09993600845337, "x": -2.948104698740641, "y": -0.027136228238327398, "z": null, "yaw": 3.151242123579341, "pitch": null, "roll": null}, "v": 2.3369227503741694, "accelerator_pedal_position": 0.2620793059534182, "brake_pedal_position": 0.0, "acceleration": 0.016537445277991558, "steering_wheel_angle": -0.693820523981195, "front_wheel_angle": -0.03215813831088136, "heading_rate": -0.0293660162018731, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137724.3274946} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2629394408370361, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.5661040661772458, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3374552087790166, "gear": 1, "accelerator_pedal_position": 0.2636950433697062, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7347580455479624, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137724.3274946} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 67.09993600845337, "x": -2.948104698740641, "y": -0.027136228238327398, "z": null, "yaw": 3.151242123579341, "pitch": null, "roll": null}, "v": 2.3369227503741694, "accelerator_pedal_position": 0.2620793059534182, "brake_pedal_position": 0.0, "acceleration": 0.016537445277991558, "steering_wheel_angle": -0.693820523981195, "front_wheel_angle": -0.03215813831088136, "heading_rate": -0.0293660162018731, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137724.3474946} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2629394408370361, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.5661040661772458, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.337892232788751, "gear": 1, "accelerator_pedal_position": 0.2629394408370361, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7347580455479624, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137724.3474946} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 67.09993600845337, "x": -2.948104698740641, "y": -0.027136228238327398, "z": null, "yaw": 3.151242123579341, "pitch": null, "roll": null}, "v": 2.3369227503741694, "accelerator_pedal_position": 0.2620793059534182, "brake_pedal_position": 0.0, "acceleration": 0.016537445277991558, "steering_wheel_angle": -0.693820523981195, "front_wheel_angle": -0.03215813831088136, "heading_rate": -0.0293660162018731, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137724.3674946} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2629394408370361, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.5661040661772458, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.338328411516696, "gear": 1, "accelerator_pedal_position": 0.2629394408370361, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7347580455479624, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137724.3674946} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 67.09993600845337, "x": -2.948104698740641, "y": -0.027136228238327398, "z": null, "yaw": 3.151242123579341, "pitch": null, "roll": null}, "v": 2.3369227503741694, "accelerator_pedal_position": 0.2620793059534182, "brake_pedal_position": 0.0, "acceleration": 0.016537445277991558, "steering_wheel_angle": -0.693820523981195, "front_wheel_angle": -0.03215813831088136, "heading_rate": -0.0293660162018731, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137724.3874946} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2629394408370361, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.5661040661772458, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3387637465217117, "gear": 1, "accelerator_pedal_position": 0.2629394408370361, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7347580455479624, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137724.3874946} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 67.09993600845337, "x": -2.948104698740641, "y": -0.027136228238327398, "z": null, "yaw": 3.151242123579341, "pitch": null, "roll": null}, "v": 2.3369227503741694, "accelerator_pedal_position": 0.2620793059534182, "brake_pedal_position": 0.0, "acceleration": 0.016537445277991558, "steering_wheel_angle": -0.693820523981195, "front_wheel_angle": -0.03215813831088136, "heading_rate": -0.0293660162018731, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137724.4074945} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2629394408370361, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.5661040661772458, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.339198239360085, "gear": 1, "accelerator_pedal_position": 0.2629394408370361, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7347580455479624, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137724.4074945} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137724.4174945, "x": 0.7947151054968254, "y": 4.970551561168241, "z": null, "yaw": 3.149784917371285, "pitch": null, "roll": null}, "v": 2.3394151704524173, "accelerator_pedal_position": 0.2629394408370361, "brake_pedal_position": 0.0, "acceleration": 0.021672113311425434, "steering_wheel_angle": -0.7347580455479624, "front_wheel_angle": -0.03407436248417588, "heading_rate": -0.031150369474616524, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137724.4274945} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2644572846996529, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.6250718351522924, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3396318915855314, "gear": 1, "accelerator_pedal_position": 0.2629394408370361, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7347580455479624, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137724.4274945} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 67.2099359035492, "x": -3.2052848945031744, "y": -0.02944843883175885, "z": null, "yaw": 3.149784917371285, "pitch": null, "roll": null}, "v": 2.3394151704524173, "accelerator_pedal_position": 0.2629394408370361, "brake_pedal_position": 0.0, "acceleration": 0.021672113311425434, "steering_wheel_angle": -0.7347580455479624, "front_wheel_angle": -0.03407436248417588, "heading_rate": -0.031150369474616524, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137724.4474945} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2637528767933187, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.6250718351522924, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3402543434044483, "gear": 1, "accelerator_pedal_position": 0.2644572846996529, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.8166338500258489, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137724.4474945} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 67.2099359035492, "x": -3.2052848945031744, "y": -0.02944843883175885, "z": null, "yaw": 3.149784917371285, "pitch": null, "roll": null}, "v": 2.3394151704524173, "accelerator_pedal_position": 0.2629394408370361, "brake_pedal_position": 0.0, "acceleration": 0.021672113311425434, "steering_wheel_angle": -0.7347580455479624, "front_wheel_angle": -0.03407436248417588, "heading_rate": -0.031150369474616524, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137724.4674945} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2637528767933187, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.6250718351522924, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3407875823485256, "gear": 1, "accelerator_pedal_position": 0.2637528767933187, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.8166338500258489, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137724.4674945} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 67.2099359035492, "x": -3.2052848945031744, "y": -0.02944843883175885, "z": null, "yaw": 3.149784917371285, "pitch": null, "roll": null}, "v": 2.3394151704524173, "accelerator_pedal_position": 0.2629394408370361, "brake_pedal_position": 0.0, "acceleration": 0.021672113311425434, "steering_wheel_angle": -0.7347580455479624, "front_wheel_angle": -0.03407436248417588, "heading_rate": -0.031150369474616524, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137724.4874945} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2637528767933187, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.6250718351522924, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.34131978930226, "gear": 1, "accelerator_pedal_position": 0.2637528767933187, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.8166338500258489, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137724.4874945} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 67.2099359035492, "x": -3.2052848945031744, "y": -0.02944843883175885, "z": null, "yaw": 3.149784917371285, "pitch": null, "roll": null}, "v": 2.3394151704524173, "accelerator_pedal_position": 0.2629394408370361, "brake_pedal_position": 0.0, "acceleration": 0.021672113311425434, "steering_wheel_angle": -0.7347580455479624, "front_wheel_angle": -0.03407436248417588, "heading_rate": -0.031150369474616524, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137724.5074944} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2637528767933187, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.6250718351522924, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.341850966149645, "gear": 1, "accelerator_pedal_position": 0.2637528767933187, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.8166338500258489, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137724.5074944} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137724.5274944, "x": 0.5372375450474345, "y": 4.968624912864733, "z": null, "yaw": 3.148192589068657, "pitch": null, "roll": null}, "v": 2.3423811147716846, "accelerator_pedal_position": 0.2637528767933187, "brake_pedal_position": 0.0, "acceleration": 0.026468931351267266, "steering_wheel_angle": -0.8166338500258489, "front_wheel_angle": -0.03791326949152666, "heading_rate": -0.034706992953104074, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137724.5274944} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2652354433643385, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.6834717455994421, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3423811147716846, "gear": 1, "accelerator_pedal_position": 0.2637528767933187, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.8166338500258489, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137724.5274944} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 67.31993579864502, "x": -3.4627624549525655, "y": -0.03137508713526671, "z": null, "yaw": 3.148192589068657, "pitch": null, "roll": null}, "v": 2.3423811147716846, "accelerator_pedal_position": 0.2637528767933187, "brake_pedal_position": 0.0, "acceleration": 0.026468931351267266, "steering_wheel_angle": -0.8166338500258489, "front_wheel_angle": -0.03791326949152666, "heading_rate": -0.034706992953104074, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137724.5474944} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26455133754587784, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.6834717455994421, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3430954681226064, "gear": 1, "accelerator_pedal_position": 0.2652354433643385, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.8575715067538218, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137724.5474944} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 67.31993579864502, "x": -3.4627624549525655, "y": -0.03137508713526671, "z": null, "yaw": 3.148192589068657, "pitch": null, "roll": null}, "v": 2.3423811147716846, "accelerator_pedal_position": 0.2637528767933187, "brake_pedal_position": 0.0, "acceleration": 0.026468931351267266, "steering_wheel_angle": -0.8166338500258489, "front_wheel_angle": -0.03791326949152666, "heading_rate": -0.034706992953104074, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137724.5674944} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26455133754587784, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.6834717455994421, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3440362598915825, "gear": 1, "accelerator_pedal_position": 0.26455133754587784, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.8575715067538218, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137724.5674944} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 67.31993579864502, "x": -3.4627624549525655, "y": -0.03137508713526671, "z": null, "yaw": 3.148192589068657, "pitch": null, "roll": null}, "v": 2.3423811147716846, "accelerator_pedal_position": 0.2637528767933187, "brake_pedal_position": 0.0, "acceleration": 0.026468931351267266, "steering_wheel_angle": -0.8166338500258489, "front_wheel_angle": -0.03791326949152666, "heading_rate": -0.034706992953104074, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137724.5874944} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26455133754587784, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.6834717455994421, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3443492497594853, "gear": 1, "accelerator_pedal_position": 0.26455133754587784, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.8575715067538218, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137724.5874944} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 67.31993579864502, "x": -3.4627624549525655, "y": -0.03137508713526671, "z": null, "yaw": 3.148192589068657, "pitch": null, "roll": null}, "v": 2.3423811147716846, "accelerator_pedal_position": 0.2637528767933187, "brake_pedal_position": 0.0, "acceleration": 0.026468931351267266, "steering_wheel_angle": -0.8166338500258489, "front_wheel_angle": -0.03791326949152666, "heading_rate": -0.034706992953104074, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137724.6074944} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26455133754587784, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.6834717455994421, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.345286401039978, "gear": 1, "accelerator_pedal_position": 0.26455133754587784, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.8575715067538218, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137724.6074944} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 67.31993579864502, "x": -3.4627624549525655, "y": -0.03137508713526671, "z": null, "yaw": 3.148192589068657, "pitch": null, "roll": null}, "v": 2.3423811147716846, "accelerator_pedal_position": 0.2637528767933187, "brake_pedal_position": 0.0, "acceleration": 0.026468931351267266, "steering_wheel_angle": -0.8166338500258489, "front_wheel_angle": -0.03791326949152666, "heading_rate": -0.034706992953104074, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137724.6274943} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26455133754587784, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.6834717455994421, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3455981796057848, "gear": 1, "accelerator_pedal_position": 0.26455133754587784, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.8575715067538218, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137724.6274943} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739137724.6374943, "x": 0.2793994178917996, "y": 4.967122188208419, "z": null, "yaw": 3.1464875044111973, "pitch": null, "roll": null}, "v": 2.345909656030582, "accelerator_pedal_position": 0.26455133754587784, "brake_pedal_position": 0.0, "acceleration": 0.031117455717632025, "steering_wheel_angle": -0.8575715067538218, "front_wheel_angle": -0.03983593737286159, "heading_rate": -0.036523818098198796, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137724.6474943} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26592588262203487, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3462208305877583, "gear": 1, "accelerator_pedal_position": 0.26455133754587784, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.8575715067538218, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137724.6474943} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 67.42993569374084, "x": -3.7206005821082004, "y": -0.03287781179158067, "z": null, "yaw": 3.1464875044111973, "pitch": null, "roll": null}, "v": 2.345909656030582, "accelerator_pedal_position": 0.26455133754587784, "brake_pedal_position": 0.0, "acceleration": 0.031117455717632025, "steering_wheel_angle": -0.8575715067538218, "front_wheel_angle": -0.03983593737286159, "heading_rate": -0.036523818098198796, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137724.6674943} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26529738315463564, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3470140100533365, "gear": 1, "accelerator_pedal_position": 0.26592588262203487, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137724.6674943} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 67.42993569374084, "x": -3.7206005821082004, "y": -0.03287781179158067, "z": null, "yaw": 3.1464875044111973, "pitch": null, "roll": null}, "v": 2.345909656030582, "accelerator_pedal_position": 0.26455133754587784, "brake_pedal_position": 0.0, "acceleration": 0.031117455717632025, "steering_wheel_angle": -0.8575715067538218, "front_wheel_angle": -0.03983593737286159, "heading_rate": -0.036523818098198796, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137724.6874943} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26529738315463564, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3477271281552423, "gear": 1, "accelerator_pedal_position": 0.26529738315463564, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137724.6874943} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 67.42993569374084, "x": -3.7206005821082004, "y": -0.03287781179158067, "z": null, "yaw": 3.1464875044111973, "pitch": null, "roll": null}, "v": 2.345909656030582, "accelerator_pedal_position": 0.26455133754587784, "brake_pedal_position": 0.0, "acceleration": 0.031117455717632025, "steering_wheel_angle": -0.8575715067538218, "front_wheel_angle": -0.03983593737286159, "heading_rate": -0.036523818098198796, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137724.7074943} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26529738315463564, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3484388641775342, "gear": 1, "accelerator_pedal_position": 0.26529738315463564, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137724.7074943} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 67.42993569374084, "x": -3.7206005821082004, "y": -0.03287781179158067, "z": null, "yaw": 3.1464875044111973, "pitch": null, "roll": null}, "v": 2.345909656030582, "accelerator_pedal_position": 0.26455133754587784, "brake_pedal_position": 0.0, "acceleration": 0.031117455717632025, "steering_wheel_angle": -0.8575715067538218, "front_wheel_angle": -0.03983593737286159, "heading_rate": -0.036523818098198796, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739137724.7274942} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26529738315463564, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3491492205962627, "gear": 1, "accelerator_pedal_position": 0.26529738315463564, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137724.7274942} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3495038822270664, "gear": 1, "accelerator_pedal_position": 0.26529738315463564, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137724.7374942} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.329503882227067, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137724.7574942} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3095038822270673, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137724.7774942} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2895038822270677, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137724.7974942} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.269503882227068, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137724.8174942} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2495038822270685, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137724.8374941} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.229503882227069, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137724.857494} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2095038822270694, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137724.877494} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.18950388222707, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137724.897494} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1595038822270705, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137724.917494} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1495038822270707, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137724.937494} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1195038822270713, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137724.957494} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1095038822270715, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137724.977494} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.089503882227072, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137724.997494} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0695038822270724, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137725.017494} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.049503882227073, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137725.037494} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0295038822270732, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137725.057494} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0095038822270737, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137725.077494} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9895038822270736, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137725.097494} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9695038822270736, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137725.1174939} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9495038822270736, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137725.1374938} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9295038822270736, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137725.1574938} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9095038822270736, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137725.1774938} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8895038822270736, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137725.1974938} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8695038822270735, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137725.2174938} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8495038822270735, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137725.2374938} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8295038822270735, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137725.2574937} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8095038822270735, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137725.2774937} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7895038822270735, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137725.2974937} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7695038822270734, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137725.3174937} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7495038822270734, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137725.3374937} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7295038822270734, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137725.3574936} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7095038822270734, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137725.3774936} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6895038822270734, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137725.3974936} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6695038822270734, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137725.4174936} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6495038822270733, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137725.4374936} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6295038822270733, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137725.4574935} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6095038822270733, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137725.4774935} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5895038822270733, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137725.4974935} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5695038822270733, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137725.5174935} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5495038822270732, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137725.5374935} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5295038822270732, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137725.5574934} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5095038822270732, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137725.5774934} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4895038822270732, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137725.5974934} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4695038822270732, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137725.6174934} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4495038822270732, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137725.6374934} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4195038822270731, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137725.6574934} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4095038822270731, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137725.6774933} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.389503882227073, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137725.6974933} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.369503882227073, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137725.7174933} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.349503882227073, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137725.7374933} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.329503882227073, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137725.7574933} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.309503882227073, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137725.7774932} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.289503882227073, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137725.7974932} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.269503882227073, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137725.8174932} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.249503882227073, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137725.8374932} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.229503882227073, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137725.8574932} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.209503882227073, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137725.8774931} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.189503882227073, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137725.8974931} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.169503882227073, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137725.917493} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.149503882227073, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137725.937493} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1295038822270729, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137725.957493} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1095038822270729, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137725.977493} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0895038822270728, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137725.997493} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0695038822270728, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137726.017493} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0495038822270728, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137726.037493} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0295038822270728, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137726.057493} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0095038822270728, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137726.077493} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9895038822270728, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137726.097493} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9495038822270727, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137726.117493} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9495038822270727, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137726.137493} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9195038822270727, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137726.1574929} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9095038822270727, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137726.1774929} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8895038822270727, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137726.1974928} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8595038822270726, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137726.2174928} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8495038822270726, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137726.2374928} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8295038822270726, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137726.2574928} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8095038822270726, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137726.2774928} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7895038822270726, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137726.2974927} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7695038822270726, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137726.3174927} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7495038822270725, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137726.3374927} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7195038822270725, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137726.3574927} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7095038822270725, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137726.3774927} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6895038822270725, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137726.3974926} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6495038822270724, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137726.4174926} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6495038822270724, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137726.4374926} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6095038822270724, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137726.4674926} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5995038822270724, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137726.4874926} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5795038822270724, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137726.5074925} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5595038822270724, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137726.5274925} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5395038822270724, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137726.5474925} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5195038822270723, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137726.5674925} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.4995038822270723, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137726.5874925} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.4795038822270723, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137726.6074924} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.4595038822270723, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137726.6274924} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.43950388222707226, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137726.6474924} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.41950388222707224, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137726.6674924} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.3995038822270722, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137726.6874924} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.3795038822270722, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137726.7074924} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.3695038822270722, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137726.7174923} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.3395038822270722, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137726.7474923} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.31950388222707216, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137726.7674923} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.29950388222707214, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137726.7874923} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.2795038822270721, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137726.8074923} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.2595038822270721, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137726.8274922} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.23950388222707208, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137726.8474922} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.21950388222707207, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137726.8674922} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.19950388222707205, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137726.8874922} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.17950388222707203, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137726.9074922} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.159503882227072, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137726.9274921} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.139503882227072, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137726.9474921} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.11950388222707199, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137726.967492} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.099503882227072, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137726.987492} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.07950388222707201, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137727.007492} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.059503882227072015, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137727.027492} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.03950388222707201, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137727.047492} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.7423921860564884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.019503882227072007, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.9394474754289166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739137727.067492} diff --git a/tuning logs/2025-02-09_15-47-37 (before tuning)/meta.yaml b/tuning logs/2025-02-09_15-47-37 (before tuning)/meta.yaml new file mode 100644 index 000000000..366338d63 --- /dev/null +++ b/tuning logs/2025-02-09_15-47-37 (before tuning)/meta.yaml @@ -0,0 +1,19 @@ +events: +- description: Ctrl+C pressed, switching to recovery mode + time: 1739137725.9564342 + vehicle_time: 1739137724.7274942 +- description: Mission execution ended + time: 1739137728.310681 + vehicle_time: 1739137727.067492 +exit_reason: normal exit +git_branch: A1_control +git_commit_id: a82b3af20db8a1737308910d5367b8987225d2da +pipelines: +- name: drive + time: 1739137658.1525254 + vehicle_time: 1739137657.2575586 +- name: recovery + time: 1739137725.958551 + vehicle_time: 1739137724.7274942 +start_time: 1739137657.9481173 +start_time_human_readable: '2025-02-09 15:47:37' diff --git a/tuning logs/2025-02-09_15-47-37 (before tuning)/plots/accel.png b/tuning logs/2025-02-09_15-47-37 (before tuning)/plots/accel.png new file mode 100644 index 000000000..82a1dfedb Binary files /dev/null and b/tuning logs/2025-02-09_15-47-37 (before tuning)/plots/accel.png differ diff --git a/tuning logs/2025-02-09_15-47-37 (before tuning)/plots/cte.png b/tuning logs/2025-02-09_15-47-37 (before tuning)/plots/cte.png new file mode 100644 index 000000000..519591891 Binary files /dev/null and b/tuning logs/2025-02-09_15-47-37 (before tuning)/plots/cte.png differ diff --git a/tuning logs/2025-02-09_15-47-37 (before tuning)/plots/error_v.png b/tuning logs/2025-02-09_15-47-37 (before tuning)/plots/error_v.png new file mode 100644 index 000000000..28e419759 Binary files /dev/null and b/tuning logs/2025-02-09_15-47-37 (before tuning)/plots/error_v.png differ diff --git a/tuning logs/2025-02-09_15-47-37 (before tuning)/plots/error_x.png b/tuning logs/2025-02-09_15-47-37 (before tuning)/plots/error_x.png new file mode 100644 index 000000000..0e9b0e8a6 Binary files /dev/null and b/tuning logs/2025-02-09_15-47-37 (before tuning)/plots/error_x.png differ diff --git a/tuning logs/2025-02-09_15-47-37 (before tuning)/plots/error_y.png b/tuning logs/2025-02-09_15-47-37 (before tuning)/plots/error_y.png new file mode 100644 index 000000000..ecc917c1e Binary files /dev/null and b/tuning logs/2025-02-09_15-47-37 (before tuning)/plots/error_y.png differ diff --git a/tuning logs/2025-02-09_15-47-37 (before tuning)/plots/front_wheel_angle.png b/tuning logs/2025-02-09_15-47-37 (before tuning)/plots/front_wheel_angle.png new file mode 100644 index 000000000..0a26b286f Binary files /dev/null and b/tuning logs/2025-02-09_15-47-37 (before tuning)/plots/front_wheel_angle.png differ diff --git a/tuning logs/2025-02-09_15-47-37 (before tuning)/plots/v_vs_vd.png b/tuning logs/2025-02-09_15-47-37 (before tuning)/plots/v_vs_vd.png new file mode 100644 index 000000000..35ee2a3df Binary files /dev/null and b/tuning logs/2025-02-09_15-47-37 (before tuning)/plots/v_vs_vd.png differ diff --git a/tuning logs/2025-02-09_15-47-37 (before tuning)/plots/x_vs_xd.png b/tuning logs/2025-02-09_15-47-37 (before tuning)/plots/x_vs_xd.png new file mode 100644 index 000000000..32bc49df3 Binary files /dev/null and b/tuning logs/2025-02-09_15-47-37 (before tuning)/plots/x_vs_xd.png differ diff --git a/tuning logs/2025-02-09_15-47-37 (before tuning)/plots/y_vs_yd.png b/tuning logs/2025-02-09_15-47-37 (before tuning)/plots/y_vs_yd.png new file mode 100644 index 000000000..c3696e0a5 Binary files /dev/null and b/tuning logs/2025-02-09_15-47-37 (before tuning)/plots/y_vs_yd.png differ diff --git a/tuning logs/2025-02-09_15-47-37 (before tuning)/settings.yaml b/tuning logs/2025-02-09_15-47-37 (before tuning)/settings.yaml new file mode 100644 index 000000000..780af3d3f --- /dev/null +++ b/tuning logs/2025-02-09_15-47-37 (before tuning)/settings.yaml @@ -0,0 +1,321 @@ +control: + longitudinal_control: + pid_d: 0.0 + pid_i: 0.1 + pid_p: 1.0 + pure_pursuit: + crosstrack_gain: 1.0 + desired_speed: trajectory + lookahead: 2.0 + lookahead_scale: 3.0 + recovery: + brake_amount: 0.5 + brake_speed: 2.0 +model_predictive_controller: + dt: 0.1 + lookahead: 20 +run: + after: + show_log_folder: true + computation_graph: + components: + - state_estimation: + inputs: [] + outputs: + - vehicle + - roadgraph_update: + inputs: + - vehicle + outputs: + - roadgraph + - obstacle_detection: + inputs: + - vehicle + outputs: + - obstacles + - agent_detection: + inputs: + - vehicle + outputs: + - agents + - lane_detection: + inputs: + - vehicle + - roadgraph + outputs: + - vehicle_lane + - sign_detection: + inputs: + - vehicle + - roadgraph + outputs: + - roadgraph.signs + - environment_detection: + inputs: + - vehicle + outputs: + - environment + - intent_estimation: + inputs: + - vehicle + - roadgraph + - agents + outputs: + - agent_intents + - relations_estimation: + inputs: + - vehicle + - roadgraph + - agents + - obstacles + outputs: + - relations + - predicate_evaluation: + inputs: + - vehicle + - roadgraph + - agents + - obstacles + outputs: + - predicates + - perception_normalization: + inputs: + - all + outputs: [] + - mission_execution: + inputs: [] + outputs: + - mission + - route_planning: + inputs: + - vehicle + - roadgraph + - mission + outputs: + - route + - driving_logic: + inputs: + - all + outputs: + - intent + - motion_planning: + inputs: + - all + outputs: + - trajectory + - trajectory_tracking: + inputs: + - vehicle + - trajectory + outputs: [] + description: Drive the GEM vehicle along a fixed route (currently xyhead_highbay_backlot_p.csv) + drive: + perception: + agent_detection: OmniscientAgentDetector + perception_normalization: StandardPerceptionNormalizer + state_estimation: OmniscientStateEstimator + planning: + motion_planning: + args: + - null + type: RouteToTrajectoryPlanner + route_planning: + args: + - GEMstack/knowledge/routes/xyhead_highbay_backlot_p.csv + type: StaticRoutePlanner + trajectory_tracking: + args: + desired_speed: 2.5 + print: false + type: pure_pursuit.PurePursuitTrajectoryTracker + log: + components: + - state_estimation + - trajectory_tracking + ros_topics: [] + vehicle_interface: true + mission_execution: StandardExecutor + mode: simulation + name: launch/fixed_route.yaml + recovery: + planning: + trajectory_tracking: + print: false + type: recovery.StopTrajectoryTracker + replay: + components: [] + log: null + ros_topics: [] + variants: + log_ros: + log: + ros_topics: + - /game_control/joy + - /front_radar/front_radar/objects + - /front_radar/front_radar/radar_tracks + - /lidar1/velodyne_points + - /novatel/inspva + - /novatel/imu + - /novatel/bestpos + - /zed2/zed_node/depth/camera_info + - /zed2/zed_node/depth/depth_registered + - /zed2/zed_node/rgb/camera_info + - /zed2/zed_node/rgb/image_rect_color + - /zed2/zed_node/imu/data + - /zed2/zed_node/imu/data_raw + - /zed2/zed_node/imu/mag + - /pacmod/as_rx/enable + - /pacmod/as_rx/accel_cmd + - /pacmod/as_rx/brake_cmd + - /pacmod/as_rx/shift_cmd + - /pacmod/as_rx/steer_cmd + - /pacmod/as_rx/turn_cmd + - /pacmod/as_rx/turn_signal_cmd + - /pacmod/as_rx/vehicle_speed_cmd + - /pacmod/as_tx/enable + - /pacmod/as_tx/global_rpt + - /pacmod/as_tx/accel_rpt + - /pacmod/as_tx/brake_rpt + - /pacmod/as_tx/shift_rpt + - /pacmod/as_tx/steer_rpt + - /pacmod/as_tx/turn_rpt + - /pacmod/as_tx/vehicle_speed_rpt + sim: + run: + drive: + perception: + agent_detection: OmniscientAgentDetector + state_estimation: OmniscientStateEstimator + mode: simulation + vehicle_interface: + args: + scene: scenes/xyhead_demo.yaml + type: gem_simulator.GEMDoubleIntegratorSimulationInterface + visualization: + args: + rate: 20 + save_as: null + type: klampt_visualization.KlamptVisualization + vehicle_interface: + args: + scene: scenes/xyhead_demo.yaml + type: gem_simulator.GEMDoubleIntegratorSimulationInterface + visualization: + args: + rate: 20 + save_as: null + type: klampt_visualization.KlamptVisualization +simulator: + dt: 0.01 + gnss_emulator: + dt: 0.1 + real_time_multiplier: 1.0 +variant: sim +vehicle: + calibration: + calibration_date: '2024-03-05' + front_camera: + center_position: + - 1.78 + - 0 + - 1.58 + reference: rear_axle_center + rotation: + - - 0 + - 0 + - 1 + - - -1 + - 0 + - 0 + - - 0 + - -1 + - 0 + gnss_location: + - 1.1 + - 0.1.62 + gnss_yaw: 0.0 + rear_axle_height: 0.33 + reference: rear_axle_center + top_lidar: + position: + - 1.1 + - 0 + - 2.03 + reference: rear_axle_center + rotation: + - - 1 + - 0 + - 0 + - - 0 + - 1 + - 0 + - - 0 + - 0 + - 1 + control_defaults: + accelerator_pedal_speed: 3.0 + brake_pedal_speed: 3.0 + steering_wheel_speed: 4.0 + dynamics: + acceleration_deadband: 0.1 + acceleration_model: kris_v1 + accelerator_active_range: + - 0.2 + - 1.0 + aerodynamic_drag_coefficient: 0.01 + brake_active_range: + - 0 + - 1 + gravity: 9.81 + internal_dry_deceleration: 0.2 + internal_viscous_deceleration: 0.05 + lateral_friction: 1.0 + longitudinal_friction: 1.0 + mass: 300.0 + max_accelerator_acceleration: + - 0.0 + - 5.0 + max_accelerator_acceleration_reverse: 2.5 + max_accelerator_power: + - 0.0 + - 10000.0 + max_accelerator_power_reverse: 10000.0 + max_brake_deceleration: 8.0 + enable_through_joystick: true + geometry: + bounds: + - - -0.35 + - 2.85 + - - -0.85 + - 0.85 + - - 0 + - 2.5 + height: 2.5 + length: 3.2 + max_steering_angle: 11.0 + max_wheel_angle: 0.6108 + min_steering_angle: -11.0 + min_wheel_angle: -0.6108 + urdf_model: /home/acrl/GEMstack/GEMstack/knowledge/vehicle/model/gem_e4.urdf + wheel_radius: 0.33 + wheelbase: 2.56 + width: 1.7 + limits: + max_acceleration: 1.0 + max_accelerator_pedal: 0.5 + max_brake_pedal: 0.5 + max_deceleration: 2.0 + max_reverse_speed: 0.25 + max_speed: 2.5 + max_steering_rate: 2.0 + max_command_rate: 10.0 + max_gear: 1 + name: GEM + num_wiper_settings: 1 + sensors: + ros_topics: + front_camera: /oak/rgb/image_raw + front_depth: /oak/stereo/image_raw + gnss: /septentrio_gnss/insnavgeod + top_lidar: /ouster/points + version: e4 diff --git a/tuning logs/2025-02-09_15-47-37--2025-02-13_21-10-39/plots/accel_comparison.png b/tuning logs/2025-02-09_15-47-37--2025-02-13_21-10-39/plots/accel_comparison.png new file mode 100644 index 000000000..d3b26928c Binary files /dev/null and b/tuning logs/2025-02-09_15-47-37--2025-02-13_21-10-39/plots/accel_comparison.png differ diff --git a/tuning logs/2025-02-09_15-47-37--2025-02-13_21-10-39/plots/cte_comparison.png b/tuning logs/2025-02-09_15-47-37--2025-02-13_21-10-39/plots/cte_comparison.png new file mode 100644 index 000000000..2c6d66512 Binary files /dev/null and b/tuning logs/2025-02-09_15-47-37--2025-02-13_21-10-39/plots/cte_comparison.png differ diff --git a/tuning logs/2025-02-09_15-47-37--2025-02-13_21-10-39/plots/error_v_comparison.png b/tuning logs/2025-02-09_15-47-37--2025-02-13_21-10-39/plots/error_v_comparison.png new file mode 100644 index 000000000..e2bd1c673 Binary files /dev/null and b/tuning logs/2025-02-09_15-47-37--2025-02-13_21-10-39/plots/error_v_comparison.png differ diff --git a/tuning logs/2025-02-09_15-47-37--2025-02-13_21-10-39/plots/error_x_comparison.png b/tuning logs/2025-02-09_15-47-37--2025-02-13_21-10-39/plots/error_x_comparison.png new file mode 100644 index 000000000..935ab205c Binary files /dev/null and b/tuning logs/2025-02-09_15-47-37--2025-02-13_21-10-39/plots/error_x_comparison.png differ diff --git a/tuning logs/2025-02-09_15-47-37--2025-02-13_21-10-39/plots/error_y_comparison.png b/tuning logs/2025-02-09_15-47-37--2025-02-13_21-10-39/plots/error_y_comparison.png new file mode 100644 index 000000000..3f696a2f0 Binary files /dev/null and b/tuning logs/2025-02-09_15-47-37--2025-02-13_21-10-39/plots/error_y_comparison.png differ diff --git a/tuning logs/2025-02-09_15-47-37--2025-02-13_21-10-39/plots/front_wheel_angle_comparison.png b/tuning logs/2025-02-09_15-47-37--2025-02-13_21-10-39/plots/front_wheel_angle_comparison.png new file mode 100644 index 000000000..04f098495 Binary files /dev/null and b/tuning logs/2025-02-09_15-47-37--2025-02-13_21-10-39/plots/front_wheel_angle_comparison.png differ diff --git a/tuning logs/2025-02-09_16-46-00 (after tuning cte = 0.5 (-50%), decay speed = 1.0 (+250%))/PurePursuitTrajectoryTracker_debug.csv b/tuning logs/2025-02-09_16-46-00 (after tuning cte = 0.5 (-50%), decay speed = 1.0 (+250%))/PurePursuitTrajectoryTracker_debug.csv new file mode 100644 index 000000000..b04f7e18f --- /dev/null +++ b/tuning logs/2025-02-09_16-46-00 (after tuning cte = 0.5 (-50%), decay speed = 1.0 (+250%))/PurePursuitTrajectoryTracker_debug.csv @@ -0,0 +1,3215 @@ +curr pt[0] time,curr pt[0] vehicle time,curr pt[0],curr pt[1] time,curr pt[1] vehicle time,curr pt[1],curr param time,curr param vehicle time,curr param,desired pt[0] time,desired pt[0] vehicle time,desired pt[0],desired pt[1] time,desired pt[1] vehicle time,desired pt[1],desired yaw (rad) time,desired yaw (rad) vehicle time,desired yaw (rad),crosstrack error time,crosstrack error vehicle time,crosstrack error,front wheel angle (rad) time,front wheel angle (rad) vehicle time,front wheel angle (rad),desired speed (m/s) time,desired speed (m/s) vehicle time,desired speed (m/s),feedforward accel (m/s^2) time,feedforward accel (m/s^2) vehicle time,feedforward accel (m/s^2),output accel (m/s^2) time,output accel (m/s^2) vehicle time,output accel (m/s^2),current yaw (rad) time,current yaw (rad) vehicle time,current yaw (rad),current speed (m/s) time,current speed (m/s) vehicle time,current speed (m/s) +1739141160.4165714,0.019999980926513672,0.0,1739141160.4165742,0.019999980926513672,0.0,1739141160.4165773,0.019999980926513672,2e-06,1739141160.4165807,0.019999980926513672,1.9947503416207786,1739141160.416582,0.019999980926513672,-0.06638719928805828,1739141160.4165843,0.019999980926513672,-0.03326867705567338,1739141160.416586,0.019999980926513672,-0.06638719928805828,1739141160.4165876,0.019999980926513672,-0.1279158618748393,1739141160.4165888,0.019999980926513672,2.434486501996753,1739141160.4165907,0.019999980926513672,0.0,1739141160.4165924,0.019999980926513672,2.434486501996753,1739141160.416594,0.019999980926513672,0.0,1739141160.4165952,0.019999980926513672,0.0 +1739141160.4360576,0.039999961853027344,0.0,1739141160.4360883,0.039999961853027344,0.0,1739141160.4360955,0.039999961853027344,2e-06,1739141160.436101,0.039999961853027344,1.9947503416207786,1739141160.4361024,0.039999961853027344,-0.06638719928805828,1739141160.4361045,0.039999961853027344,-0.03326867705567338,1739141160.4361062,0.039999961853027344,-0.06638719928805828,1739141160.4361076,0.039999961853027344,-0.1279158618748393,1739141160.4361088,0.039999961853027344,2.434486501996753,1739141160.4361105,0.039999961853027344,0.0,1739141160.4361122,0.039999961853027344,2.434486501996753,1739141160.4361134,0.039999961853027344,0.0,1739141160.436115,0.039999961853027344,0.0 +1739141160.455421,0.059999942779541016,0.0,1739141160.4554253,0.059999942779541016,0.0,1739141160.4554286,0.059999942779541016,2e-06,1739141160.455432,0.059999942779541016,1.9947503416207786,1739141160.4554334,0.059999942779541016,-0.06638719928805828,1739141160.455435,0.059999942779541016,-0.03326867705567338,1739141160.4554367,0.059999942779541016,-0.06638719928805828,1739141160.4554381,0.059999942779541016,-0.1279158618748393,1739141160.4554396,0.059999942779541016,2.434486501996753,1739141160.4554417,0.059999942779541016,0.0,1739141160.4554434,0.059999942779541016,2.434486501996753,1739141160.4554482,0.059999942779541016,0.0,1739141160.4554498,0.059999942779541016,0.0 +1739141160.476013,0.07999992370605469,0.0007995988206337401,1739141160.4760158,0.07999992370605469,-2.1646030745614553e-08,1739141160.4760184,0.07999992370605469,1.20040117936626e-06,1739141160.4760213,0.07999992370605469,2.1146202376049437,1739141160.4760225,0.07999992370605469,-0.06783879804343307,1739141160.4760242,0.07999992370605469,-0.03208195584793593,1739141160.4760256,0.07999992370605469,-0.06767525364819808,1739141160.4760268,0.07999992370605469,-0.11614238021681811,1739141160.4760282,0.07999992370605469,2.433232524681243,1739141160.4760296,0.07999992370605469,0.0,1739141160.476031,0.07999992370605469,2.3558055646670883,1739141160.4760325,0.07999992370605469,6.2831079484182135,1739141160.4760337,0.07999992370605469,0.039959828283559644 +1739141160.4957104,0.09999990463256836,0.0007995988206337401,1739141160.4957151,0.09999990463256836,-2.1646030745614553e-08,1739141160.4957192,0.09999990463256836,1.20040117936626e-06,1739141160.495723,0.09999990463256836,2.1146202376049437,1739141160.495725,0.09999990463256836,-0.06783879804343307,1739141160.4957273,0.09999990463256836,-0.03208195584793593,1739141160.4957294,0.09999990463256836,-0.06767525364819808,1739141160.495731,0.09999990463256836,-0.11614238021681811,1739141160.4957333,0.09999990463256836,2.433232524681243,1739141160.4957354,0.09999990463256836,0.0,1739141160.4957373,0.09999990463256836,2.3932726963976836,1739141160.4957392,0.09999990463256836,6.2831079484182135,1739141160.4957411,0.09999990463256836,0.039959828283559644 +1739141160.5178921,0.11999988555908203,0.0007995988206337401,1739141160.5178962,0.11999988555908203,-2.1646030745614553e-08,1739141160.517901,0.11999988555908203,1.20040117936626e-06,1739141160.5179064,0.11999988555908203,2.1146202376049437,1739141160.5179095,0.11999988555908203,-0.06783879804343307,1739141160.5179133,0.11999988555908203,-0.03208195584793593,1739141160.517917,0.11999988555908203,-0.06767525364819808,1739141160.5179205,0.11999988555908203,-0.11614238021681811,1739141160.517924,0.11999988555908203,2.433232524681243,1739141160.517928,0.11999988555908203,0.0,1739141160.5179315,0.11999988555908203,2.3932726963976836,1739141160.5179348,0.11999988555908203,6.2831079484182135,1739141160.5179384,0.11999988555908203,0.039959828283559644 +1739141160.557633,0.15999984741210938,0.0007995988206337401,1739141160.557636,0.15999984741210938,-2.1646030745614553e-08,1739141160.5576391,0.15999984741210938,1.20040117936626e-06,1739141160.5576422,0.15999984741210938,2.1146202376049437,1739141160.5576434,0.15999984741210938,-0.06783879804343307,1739141160.5576453,0.15999984741210938,-0.03208195584793593,1739141160.557647,0.15999984741210938,-0.06767525364819808,1739141160.5576484,0.15999984741210938,-0.11614238021681811,1739141160.5576496,0.15999984741210938,2.433232524681243,1739141160.5576515,0.15999984741210938,0.0,1739141160.557653,0.15999984741210938,2.3932726963976836,1739141160.5576544,0.15999984741210938,6.2831079484182135,1739141160.5576556,0.15999984741210938,0.039959828283559644 +1739141160.5639524,0.15999984741210938,0.0007995988206337401,1739141160.5639572,0.15999984741210938,-2.1646030745614553e-08,1739141160.563961,0.15999984741210938,1.20040117936626e-06,1739141160.5639644,0.15999984741210938,2.1146202376049437,1739141160.563966,0.15999984741210938,-0.06783879804343307,1739141160.563968,0.15999984741210938,-0.03208195584793593,1739141160.5639699,0.15999984741210938,-0.06767525364819808,1739141160.5639713,0.15999984741210938,-0.11614238021681811,1739141160.5639734,0.15999984741210938,2.433232524681243,1739141160.563975,0.15999984741210938,0.0,1739141160.563977,0.15999984741210938,2.3932726963976836,1739141160.5639784,0.15999984741210938,6.2831079484182135,1739141160.5639803,0.15999984741210938,0.039959828283559644 +1739141160.5833745,0.18999981880187988,0.010485176694682075,1739141160.5833776,0.18999981880187988,-4.560607775871972e-06,1739141160.5833807,0.18999981880187988,0.0,1739141160.5833838,0.18999981880187988,2.4376948229735214,1739141160.5833852,0.18999981880187988,-0.07264017037900598,1739141160.5833874,0.18999981880187988,-0.029916632396135744,1739141160.583389,0.18999981880187988,-0.07038813757004006,1739141160.5833905,0.18999981880187988,-0.09164783904391784,1739141160.5833917,0.18999981880187988,2.4305935258419877,1739141160.5833933,0.18999981880187988,0.0,1739141160.5833948,0.18999981880187988,2.182611077356889,1739141160.5833964,0.18999981880187988,6.282259370934885,1739141160.5833979,0.18999981880187988,0.14766734168722773 +1739141160.6129937,0.20999979972839355,0.010485176694682075,1739141160.6129975,0.20999979972839355,-4.560607775871972e-06,1739141160.6130018,0.20999979972839355,0.0,1739141160.6130054,0.20999979972839355,2.4376948229735214,1739141160.6130068,0.20999979972839355,-0.07264017037900598,1739141160.613009,0.20999979972839355,-0.029916632396135744,1739141160.6130104,0.20999979972839355,-0.07038813757004006,1739141160.613012,0.20999979972839355,-0.09164783904391784,1739141160.6130137,0.20999979972839355,2.4305935258419877,1739141160.6130154,0.20999979972839355,0.0,1739141160.6130168,0.20999979972839355,2.28292618415476,1739141160.6130183,0.20999979972839355,6.282259370934885,1739141160.61302,0.20999979972839355,0.14766734168722773 +1739141160.7542384,0.2799997329711914,0.010485176694682075,1739141160.7542415,0.2799997329711914,-4.560607775871972e-06,1739141160.7542446,0.2799997329711914,0.0,1739141160.7542477,0.2799997329711914,2.4376948229735214,1739141160.7542489,0.2799997329711914,-0.07264017037900598,1739141160.7542505,0.2799997329711914,-0.029916632396135744,1739141160.7542522,0.2799997329711914,-0.07038813757004006,1739141160.7542539,0.2799997329711914,-0.09164783904391784,1739141160.754255,0.2799997329711914,2.4305935258419877,1739141160.7542567,0.2799997329711914,0.0,1739141160.7542582,0.2799997329711914,2.28292618415476,1739141160.7542598,0.2799997329711914,6.282259370934885,1739141160.754261,0.2799997329711914,0.14766734168722773 +1739141160.7755249,0.2999997138977051,0.032214164598860506,1739141160.7755291,0.2999997138977051,-4.227881880503048e-05,1739141160.7755346,0.2999997138977051,0.0215686294849362,1739141160.7755406,0.2999997138977051,2.7881909390808164,1739141160.7755437,0.2999997138977051,-0.07563853339864564,1739141160.775548,0.2999997138977051,-0.02742305532633603,1739141160.7755518,0.2999997138977051,-0.06815563934689475,1739141160.7755556,0.2999997138977051,-0.06885080297515199,1739141160.7755592,0.2999997138977051,2.432765013557229,1739141160.7755628,0.2999997138977051,0.0,1739141160.7755666,0.2999997138977051,2.0777401956304375,1739141160.7755702,0.2999997138977051,6.280485593288614,1739141160.775574,0.2999997138977051,0.2573171555345345 +1739141160.7955763,0.31999969482421875,0.032214164598860506,1739141160.7955816,0.31999969482421875,-4.227881880503048e-05,1739141160.7955878,0.31999969482421875,0.0215686294849362,1739141160.795594,0.31999969482421875,2.7881909390808164,1739141160.795598,0.31999969482421875,-0.07563853339864564,1739141160.7956028,0.31999969482421875,-0.02742305532633603,1739141160.7956069,0.31999969482421875,-0.06815563934689475,1739141160.795611,0.31999969482421875,-0.06885080297515199,1739141160.7956145,0.31999969482421875,2.432765013557229,1739141160.7956185,0.31999969482421875,0.0,1739141160.7956223,0.31999969482421875,2.1754478580226944,1739141160.795626,0.31999969482421875,6.280485593288614,1739141160.79563,0.31999969482421875,0.2573171555345345 +1739141160.8154519,0.3399996757507324,0.032214164598860506,1739141160.8154562,0.3399996757507324,-4.227881880503048e-05,1739141160.8154612,0.3399996757507324,0.0215686294849362,1739141160.8154671,0.3399996757507324,2.7881909390808164,1739141160.81547,0.3399996757507324,-0.07563853339864564,1739141160.8154743,0.3399996757507324,-0.02742305532633603,1739141160.8154778,0.3399996757507324,-0.06815563934689475,1739141160.8154814,0.3399996757507324,-0.06885080297515199,1739141160.815485,0.3399996757507324,2.432765013557229,1739141160.8154888,0.3399996757507324,0.0,1739141160.8154926,0.3399996757507324,2.1754478580226944,1739141160.8154964,0.3399996757507324,6.280485593288614,1739141160.8155,0.3399996757507324,0.2573171555345345 +1739141160.8358543,0.3599996566772461,0.032214164598860506,1739141160.835859,0.3599996566772461,-4.227881880503048e-05,1739141160.835864,0.3599996566772461,0.0215686294849362,1739141160.8358698,0.3599996566772461,2.7881909390808164,1739141160.8358731,0.3599996566772461,-0.07563853339864564,1739141160.8358774,0.3599996566772461,-0.02742305532633603,1739141160.835881,0.3599996566772461,-0.06815563934689475,1739141160.835885,0.3599996566772461,-0.06885080297515199,1739141160.8358886,0.3599996566772461,2.432765013557229,1739141160.8358932,0.3599996566772461,0.0,1739141160.8358967,0.3599996566772461,2.1754478580226944,1739141160.8359003,0.3599996566772461,6.280485593288614,1739141160.8359044,0.3599996566772461,0.2573171555345345 +1739141160.8553917,0.37999963760375977,0.032214164598860506,1739141160.8553972,0.37999963760375977,-4.227881880503048e-05,1739141160.8554027,0.37999963760375977,0.0215686294849362,1739141160.8554084,0.37999963760375977,2.7881909390808164,1739141160.8554118,0.37999963760375977,-0.07563853339864564,1739141160.8554158,0.37999963760375977,-0.02742305532633603,1739141160.8554196,0.37999963760375977,-0.06815563934689475,1739141160.8554235,0.37999963760375977,-0.06885080297515199,1739141160.855427,0.37999963760375977,2.432765013557229,1739141160.8554308,0.37999963760375977,0.0,1739141160.8554354,0.37999963760375977,2.1754478580226944,1739141160.855439,0.37999963760375977,6.280485593288614,1739141160.8554425,0.37999963760375977,0.2573171555345345 +1739141160.876161,0.39999961853027344,0.06600371751941836,1739141160.8761663,0.39999961853027344,-0.0001707013486127451,1739141160.8761744,0.39999961853027344,0.02190652501414178,1739141160.876181,0.39999961853027344,3.1174053327818583,1739141160.8761842,0.39999961853027344,-0.07900136707813656,1739141160.8761885,0.39999961853027344,-0.025828502855713982,1739141160.8761923,0.39999961853027344,-0.06365183660059058,1739141160.8761961,0.39999961853027344,-0.052461341095494454,1739141160.8761997,0.39999961853027344,2.4371516411716048,1739141160.8762038,0.39999961853027344,0.0,1739141160.8762076,0.39999961853027344,1.9745201393058516,1739141160.8762112,0.39999961853027344,6.278211226924519,1739141160.8762152,0.39999961853027344,0.36695158801381655 +1739141160.8949518,0.4199995994567871,0.06600371751941836,1739141160.894955,0.4199995994567871,-0.0001707013486127451,1739141160.894958,0.4199995994567871,0.02190652501414178,1739141160.8949606,0.4199995994567871,3.1174053327818583,1739141160.8949625,0.4199995994567871,-0.07900136707813656,1739141160.8949642,0.4199995994567871,-0.025828502855713982,1739141160.8949656,0.4199995994567871,-0.06365183660059058,1739141160.894967,0.4199995994567871,-0.052461341095494454,1739141160.8949683,0.4199995994567871,2.4371516411716048,1739141160.8949702,0.4199995994567871,0.0,1739141160.8949718,0.4199995994567871,2.070200053157788,1739141160.8949735,0.4199995994567871,6.278211226924519,1739141160.894975,0.4199995994567871,0.36695158801381655 +1739141160.915313,0.4399995803833008,0.06600371751941836,1739141160.9153178,0.4399995803833008,-0.0001707013486127451,1739141160.915323,0.4399995803833008,0.02190652501414178,1739141160.915329,0.4399995803833008,3.1174053327818583,1739141160.915332,0.4399995803833008,-0.07900136707813656,1739141160.9153364,0.4399995803833008,-0.025828502855713982,1739141160.9153407,0.4399995803833008,-0.06365183660059058,1739141160.9153442,0.4399995803833008,-0.052461341095494454,1739141160.915348,0.4399995803833008,2.4371516411716048,1739141160.9153523,0.4399995803833008,0.0,1739141160.9153564,0.4399995803833008,2.070200053157788,1739141160.9153602,0.4399995803833008,6.278211226924519,1739141160.9153643,0.4399995803833008,0.36695158801381655 +1739141160.9352803,0.45999956130981445,0.06600371751941836,1739141160.9352863,0.45999956130981445,-0.0001707013486127451,1739141160.9352925,0.45999956130981445,0.02190652501414178,1739141160.9352984,0.45999956130981445,3.1174053327818583,1739141160.9353,0.45999956130981445,-0.07900136707813656,1739141160.9353018,0.45999956130981445,-0.025828502855713982,1739141160.9353034,0.45999956130981445,-0.06365183660059058,1739141160.9353046,0.45999956130981445,-0.052461341095494454,1739141160.935306,0.45999956130981445,2.4371516411716048,1739141160.9353077,0.45999956130981445,0.0,1739141160.9353094,0.45999956130981445,2.070200053157788,1739141160.9353108,0.45999956130981445,6.278211226924519,1739141160.935312,0.45999956130981445,0.36695158801381655 +1739141160.9552703,0.4799995422363281,0.06600371751941836,1739141160.955276,0.4799995422363281,-0.0001707013486127451,1739141160.9552808,0.4799995422363281,0.02190652501414178,1739141160.9552855,0.4799995422363281,3.1174053327818583,1739141160.9552882,0.4799995422363281,-0.07900136707813656,1739141160.9552908,0.4799995422363281,-0.025828502855713982,1739141160.955294,0.4799995422363281,-0.06365183660059058,1739141160.9552965,0.4799995422363281,-0.052461341095494454,1739141160.9552994,0.4799995422363281,2.4371516411716048,1739141160.9553022,0.4799995422363281,0.0,1739141160.9553058,0.4799995422363281,2.070200053157788,1739141160.9553082,0.4799995422363281,6.278211226924519,1739141160.9553108,0.4799995422363281,0.36695158801381655 +1739141160.9814847,0.4999995231628418,0.06600371751941836,1739141160.9814954,0.4999995231628418,-0.0001707013486127451,1739141160.9815066,0.4999995231628418,0.02190652501414178,1739141160.9815178,0.4999995231628418,3.1174053327818583,1739141160.9815238,0.4999995231628418,-0.07900136707813656,1739141160.9815304,0.4999995231628418,-0.025828502855713982,1739141160.9815357,0.4999995231628418,-0.06365183660059058,1739141160.981541,0.4999995231628418,-0.052461341095494454,1739141160.9815457,0.4999995231628418,2.4371516411716048,1739141160.9815521,0.4999995231628418,0.0,1739141160.9815578,0.4999995231628418,2.070200053157788,1739141160.9815629,0.4999995231628418,6.278211226924519,1739141160.981568,0.4999995231628418,0.36695158801381655 +1739141161.0119934,0.5399994850158691,0.11185185898860972,1739141161.0120003,0.5399994850158691,-0.0004484227970866783,1739141161.0120082,0.5399994850158691,0.022365006428833694,1739141161.0120156,0.5399994850158691,3.446660143356718,1739141161.0120192,0.5399994850158691,-0.08528449760352176,1739141161.012024,0.5399994850158691,-0.025434080017021438,1739141161.0120277,0.5399994850158691,-0.06066187800611801,1739141161.0120313,0.5399994850158691,-0.04186259691771824,1739141161.0120347,0.5399994850158691,2.440068177886985,1739141161.0120392,0.5399994850158691,0.0,1739141161.012043,0.5399994850158691,1.8664932626900383,1739141161.0120466,0.5399994850158691,6.2759368605604235,1739141161.01205,0.5399994850158691,0.47657163318349777 +1739141161.0310864,0.5599994659423828,0.11185185898860972,1739141161.0310905,0.5599994659423828,-0.0004484227970866783,1739141161.0310953,0.5599994659423828,0.022365006428833694,1739141161.0310998,0.5599994659423828,3.446660143356718,1739141161.0311022,0.5599994659423828,-0.08528449760352176,1739141161.031105,0.5599994659423828,-0.025434080017021438,1739141161.0311074,0.5599994659423828,-0.06066187800611801,1739141161.0311096,0.5599994659423828,-0.04186259691771824,1739141161.0311117,0.5599994659423828,2.440068177886985,1739141161.0311143,0.5599994659423828,0.0,1739141161.0311167,0.5599994659423828,1.9634965447034871,1739141161.0311189,0.5599994659423828,6.2759368605604235,1739141161.0311213,0.5599994659423828,0.47657163318349777 +1739141161.0510693,0.5799994468688965,0.11185185898860972,1739141161.0510733,0.5799994468688965,-0.0004484227970866783,1739141161.0510771,0.5799994468688965,0.022365006428833694,1739141161.0510812,0.5799994468688965,3.446660143356718,1739141161.051083,0.5799994468688965,-0.08528449760352176,1739141161.0510855,0.5799994468688965,-0.025434080017021438,1739141161.0510874,0.5799994468688965,-0.06066187800611801,1739141161.051089,0.5799994468688965,-0.04186259691771824,1739141161.051091,0.5799994468688965,2.440068177886985,1739141161.0510933,0.5799994468688965,0.0,1739141161.0510952,0.5799994468688965,1.9634965447034871,1739141161.0510974,0.5799994468688965,6.2759368605604235,1739141161.051099,0.5799994468688965,0.47657163318349777 +1739141161.0701597,0.5999994277954102,0.11185185898860972,1739141161.070163,0.5999994277954102,-0.0004484227970866783,1739141161.070175,0.5999994277954102,0.022365006428833694,1739141161.070179,0.5999994277954102,3.446660143356718,1739141161.070181,0.5999994277954102,-0.08528449760352176,1739141161.0701833,0.5999994277954102,-0.025434080017021438,1739141161.070185,0.5999994277954102,-0.06066187800611801,1739141161.0701869,0.5999994277954102,-0.04186259691771824,1739141161.0701883,0.5999994277954102,2.440068177886985,1739141161.0701904,0.5999994277954102,0.0,1739141161.070192,0.5999994277954102,1.9634965447034871,1739141161.0701938,0.5999994277954102,6.2759368605604235,1739141161.070196,0.5999994277954102,0.47657163318349777 +1739141161.0901423,0.6199994087219238,0.16974557541537472,1739141161.0901449,0.6199994087219238,-0.0009301888454347207,1739141161.0901477,0.6199994087219238,0.022943943593101344,1739141161.0901506,0.6199994087219238,3.77560823849235,1739141161.0901523,0.6199994087219238,-0.09163573863316334,1739141161.090154,0.6199994087219238,-0.025149716850503545,1739141161.0901554,0.6199994087219238,-0.056364000246784875,1739141161.0901566,0.6199994087219238,-0.033269949081503825,1739141161.0901577,0.6199994087219238,2.44426663164235,1739141161.0901597,0.6199994087219238,0.0,1739141161.090161,0.6199994087219238,1.762507829184635,1739141161.0901625,0.6199994087219238,6.273662494196327,1739141161.0901637,0.6199994087219238,0.5860498424950735 +1739141161.1105554,0.6399993896484375,0.16974557541537472,1739141161.1105583,0.6399993896484375,-0.0009301888454347207,1739141161.1105611,0.6399993896484375,0.022943943593101344,1739141161.1105638,0.6399993896484375,3.77560823849235,1739141161.1105657,0.6399993896484375,-0.09163573863316334,1739141161.1105673,0.6399993896484375,-0.025149716850503545,1739141161.1105688,0.6399993896484375,-0.056364000246784875,1739141161.1105702,0.6399993896484375,-0.033269949081503825,1739141161.1105716,0.6399993896484375,2.44426663164235,1739141161.1105733,0.6399993896484375,0.0,1739141161.1105745,0.6399993896484375,1.8582167891472763,1739141161.1105762,0.6399993896484375,6.273662494196327,1739141161.1105773,0.6399993896484375,0.5860498424950735 +1739141161.1352456,0.6599993705749512,0.16974557541537472,1739141161.1352599,0.6599993705749512,-0.0009301888454347207,1739141161.1352763,0.6599993705749512,0.022943943593101344,1739141161.1352942,0.6599993705749512,3.77560823849235,1739141161.135304,0.6599993705749512,-0.09163573863316334,1739141161.1353154,0.6599993705749512,-0.025149716850503545,1739141161.135325,0.6599993705749512,-0.056364000246784875,1739141161.1353347,0.6599993705749512,-0.033269949081503825,1739141161.1353443,0.6599993705749512,2.44426663164235,1739141161.1353555,0.6599993705749512,0.0,1739141161.1353655,0.6599993705749512,1.8582167891472763,1739141161.1353753,0.6599993705749512,6.273662494196327,1739141161.1353853,0.6599993705749512,0.5860498424950735 +1739141161.1627834,0.6799993515014648,0.16974557541537472,1739141161.1627934,0.6799993515014648,-0.0009301888454347207,1739141161.1628041,0.6799993515014648,0.022943943593101344,1739141161.1628156,0.6799993515014648,3.77560823849235,1739141161.1628206,0.6799993515014648,-0.09163573863316334,1739141161.1628273,0.6799993515014648,-0.025149716850503545,1739141161.1628327,0.6799993515014648,-0.056364000246784875,1739141161.1628375,0.6799993515014648,-0.033269949081503825,1739141161.162842,0.6799993515014648,2.44426663164235,1739141161.1628485,0.6799993515014648,0.0,1739141161.162854,0.6799993515014648,1.8582167891472763,1739141161.1628587,0.6799993515014648,6.273662494196327,1739141161.1628754,0.6799993515014648,0.5860498424950735 +1739141161.1831782,0.7099993228912354,0.16974557541537472,1739141161.1831875,0.7099993228912354,-0.0009301888454347207,1739141161.183198,0.7099993228912354,0.022943943593101344,1739141161.1832087,0.7099993228912354,3.77560823849235,1739141161.1832137,0.7099993228912354,-0.09163573863316334,1739141161.1832204,0.7099993228912354,-0.025149716850503545,1739141161.1832259,0.7099993228912354,-0.056364000246784875,1739141161.1832309,0.7099993228912354,-0.033269949081503825,1739141161.183236,0.7099993228912354,2.44426663164235,1739141161.1832423,0.7099993228912354,0.0,1739141161.1832478,0.7099993228912354,1.8582167891472763,1739141161.1832528,0.7099993228912354,6.273662494196327,1739141161.183258,0.7099993228912354,0.5860498424950735 +1739141161.2088401,0.7399992942810059,0.23969686767931098,1739141161.2088447,0.7399992942810059,-0.0016709333263458248,1739141161.2088497,0.7399992942810059,0.023643456515740707,1739141161.2088542,0.7399992942810059,4.10522972529402,1739141161.2088566,0.7399992942810059,-0.09699392641110156,1739141161.2088592,0.7399992942810059,-0.024654732374600568,1739141161.2088614,0.7399992942810059,-0.049715033318954605,1739141161.2088637,0.7399992942810059,-0.025536167135341938,1739141161.208866,0.7399992942810059,2.450776023149795,1739141161.208869,0.7399992942810059,0.0,1739141161.2088711,0.7399992942810059,1.6612979008532867,1739141161.2088733,0.7399992942810059,6.271388127832232,1739141161.2088754,0.7399992942810059,0.6957071762662096 +1739141161.2284465,0.7599992752075195,0.23969686767931098,1739141161.2284493,0.7599992752075195,-0.0016709333263458248,1739141161.2284524,0.7599992752075195,0.023643456515740707,1739141161.2284558,0.7599992752075195,4.10522972529402,1739141161.2284572,0.7599992752075195,-0.09699392641110156,1739141161.2284594,0.7599992752075195,-0.024654732374600568,1739141161.228461,0.7599992752075195,-0.049715033318954605,1739141161.2284622,0.7599992752075195,-0.025536167135341938,1739141161.228464,0.7599992752075195,2.450776023149795,1739141161.2284656,0.7599992752075195,0.0,1739141161.2284672,0.7599992752075195,1.755068846883585,1739141161.2284684,0.7599992752075195,6.271388127832232,1739141161.22847,0.7599992752075195,0.6957071762662096 +1739141161.249091,0.7799992561340332,0.23969686767931098,1739141161.249093,0.7799992561340332,-0.0016709333263458248,1739141161.249096,0.7799992561340332,0.023643456515740707,1739141161.2490985,0.7799992561340332,4.10522972529402,1739141161.2490997,0.7799992561340332,-0.09699392641110156,1739141161.2491014,0.7799992561340332,-0.024654732374600568,1739141161.2491028,0.7799992561340332,-0.049715033318954605,1739141161.249104,0.7799992561340332,-0.025536167135341938,1739141161.2491052,0.7799992561340332,2.450776023149795,1739141161.2491066,0.7799992561340332,0.0,1739141161.2491083,0.7799992561340332,1.755068846883585,1739141161.2491095,0.7799992561340332,6.271388127832232,1739141161.2491107,0.7799992561340332,0.6957071762662096 +1739141161.2689972,0.7999992370605469,0.23969686767931098,1739141161.2689996,0.7999992370605469,-0.0016709333263458248,1739141161.2690022,0.7999992370605469,0.023643456515740707,1739141161.269005,0.7999992370605469,4.10522972529402,1739141161.2690063,0.7999992370605469,-0.09699392641110156,1739141161.269008,0.7999992370605469,-0.024654732374600568,1739141161.269009,0.7999992370605469,-0.049715033318954605,1739141161.2690105,0.7999992370605469,-0.025536167135341938,1739141161.2690117,0.7999992370605469,2.450776023149795,1739141161.2690134,0.7999992370605469,0.0,1739141161.2690148,0.7999992370605469,1.755068846883585,1739141161.269016,0.7999992370605469,6.271388127832232,1739141161.2690175,0.7999992370605469,0.6957071762662096 +1739141161.2894776,0.8199992179870605,0.23969686767931098,1739141161.2894804,0.8199992179870605,-0.0016709333263458248,1739141161.2894835,0.8199992179870605,0.023643456515740707,1739141161.2894864,0.8199992179870605,4.10522972529402,1739141161.2894878,0.8199992179870605,-0.09699392641110156,1739141161.2894897,0.8199992179870605,-0.024654732374600568,1739141161.289491,0.8199992179870605,-0.049715033318954605,1739141161.2894924,0.8199992179870605,-0.025536167135341938,1739141161.2894938,0.8199992179870605,2.450776023149795,1739141161.2894955,0.8199992179870605,0.0,1739141161.2894971,0.8199992179870605,1.755068846883585,1739141161.2894983,0.8199992179870605,6.271388127832232,1739141161.2895079,0.8199992179870605,0.6957071762662096 +1739141161.3084989,0.8399991989135742,0.32170037677305974,1739141161.3085017,0.8399991989135742,-0.0027254439006423326,1739141161.3085048,0.8399991989135742,0.024463491606678198,1739141161.3085074,0.8399991989135742,4.434748037526654,1739141161.3085089,0.8399991989135742,-0.10134995638948119,1739141161.3085108,0.8399991989135742,-0.02397385715464743,1739141161.3085124,0.8399991989135742,-0.040739720238454895,1739141161.3085139,0.8399991989135742,-0.018484029368296566,1739141161.308515,0.8399991989135742,2.4595904289318744,1739141161.3085175,0.8399991989135742,0.0,1739141161.3085191,0.8399991989135742,1.562704035937794,1739141161.3085206,0.8399991989135742,6.269113761468136,1739141161.3085217,0.8399991989135742,0.805284056308144 +1739141161.3286183,0.8599991798400879,0.32170037677305974,1739141161.328621,0.8599991798400879,-0.0027254439006423326,1739141161.3286235,0.8599991798400879,0.024463491606678198,1739141161.3286264,0.8599991798400879,4.434748037526654,1739141161.3286278,0.8599991798400879,-0.10134995638948119,1739141161.3286295,0.8599991798400879,-0.02397385715464743,1739141161.3286307,0.8599991798400879,-0.040739720238454895,1739141161.3286324,0.8599991798400879,-0.018484029368296566,1739141161.3286335,0.8599991798400879,2.4595904289318744,1739141161.3286352,0.8599991798400879,0.0,1739141161.3286366,0.8599991798400879,1.6543063726237304,1739141161.3286378,0.8599991798400879,6.269113761468136,1739141161.3286393,0.8599991798400879,0.805284056308144 +1739141161.3488953,0.8799991607666016,0.32170037677305974,1739141161.3488977,0.8799991607666016,-0.0027254439006423326,1739141161.348901,0.8799991607666016,0.024463491606678198,1739141161.348904,0.8799991607666016,4.434748037526654,1739141161.3489053,0.8799991607666016,-0.10134995638948119,1739141161.348907,0.8799991607666016,-0.02397385715464743,1739141161.3489082,0.8799991607666016,-0.040739720238454895,1739141161.3489096,0.8799991607666016,-0.018484029368296566,1739141161.348911,0.8799991607666016,2.4595904289318744,1739141161.3489127,0.8799991607666016,0.0,1739141161.3489146,0.8799991607666016,1.6543063726237304,1739141161.348916,0.8799991607666016,6.269113761468136,1739141161.3489172,0.8799991607666016,0.805284056308144 +1739141161.3683226,0.8999991416931152,0.32170037677305974,1739141161.3683257,0.8999991416931152,-0.0027254439006423326,1739141161.3683288,0.8999991416931152,0.024463491606678198,1739141161.3683321,0.8999991416931152,4.434748037526654,1739141161.3683338,0.8999991416931152,-0.10134995638948119,1739141161.368336,0.8999991416931152,-0.02397385715464743,1739141161.3683376,0.8999991416931152,-0.040739720238454895,1739141161.3683395,0.8999991416931152,-0.018484029368296566,1739141161.3683412,0.8999991416931152,2.4595904289318744,1739141161.3683434,0.8999991416931152,0.0,1739141161.3683453,0.8999991416931152,1.6543063726237304,1739141161.3683472,0.8999991416931152,6.269113761468136,1739141161.3683486,0.8999991416931152,0.805284056308144 +1739141161.3909123,0.9199991226196289,0.32170037677305974,1739141161.3909228,0.9199991226196289,-0.0027254439006423326,1739141161.3909342,0.9199991226196289,0.024463491606678198,1739141161.3909442,0.9199991226196289,4.434748037526654,1739141161.39095,0.9199991226196289,-0.10134995638948119,1739141161.3909576,0.9199991226196289,-0.02397385715464743,1739141161.3909636,0.9199991226196289,-0.040739720238454895,1739141161.3909686,0.9199991226196289,-0.018484029368296566,1739141161.390974,0.9199991226196289,2.4595904289318744,1739141161.3909802,0.9199991226196289,0.0,1739141161.390986,0.9199991226196289,1.6543063726237304,1739141161.390992,0.9199991226196289,6.269113761468136,1739141161.3909974,0.9199991226196289,0.805284056308144 +1739141161.4129329,0.9399991035461426,0.32170037677305974,1739141161.4129448,0.9399991035461426,-0.0027254439006423326,1739141161.4129572,0.9399991035461426,0.024463491606678198,1739141161.412967,0.9399991035461426,4.434748037526654,1739141161.412972,0.9399991035461426,-0.10134995638948119,1739141161.4129775,0.9399991035461426,-0.02397385715464743,1739141161.4129825,0.9399991035461426,-0.040739720238454895,1739141161.4129882,0.9399991035461426,-0.018484029368296566,1739141161.4129922,0.9399991035461426,2.4595904289318744,1739141161.412998,0.9399991035461426,0.0,1739141161.4130032,0.9399991035461426,1.6543063726237304,1739141161.413008,0.9399991035461426,6.269113761468136,1739141161.4130125,0.9399991035461426,0.805284056308144 +1739141161.4301212,0.9599990844726562,0.4157598615599376,1739141161.4301248,0.9599990844726562,-0.0041486210906525045,1739141161.4301286,0.9599990844726562,0.025404086454546976,1739141161.4301324,0.9599990844726562,4.764554806554991,1739141161.4301343,0.9599990844726562,-0.10580829457752737,1739141161.4301367,0.9599990844726562,-0.023372259014922587,1739141161.4301388,0.9599990844726562,-0.030564238296994596,1739141161.4301407,0.9599990844726562,-0.012405012350242432,1739141161.4301424,0.9599990844726562,2.4696218371629812,1739141161.4301448,0.9599990844726562,0.0,1739141161.4301465,0.9599990844726562,1.4641571976016263,1739141161.4301484,0.9599990844726562,6.26683939510404,1739141161.43015,0.9599990844726562,0.9149173681280349 +1739141161.448754,0.9799990653991699,0.4157598615599376,1739141161.4487574,0.9799990653991699,-0.0041486210906525045,1739141161.4487605,0.9799990653991699,0.025404086454546976,1739141161.4487634,0.9799990653991699,4.764554806554991,1739141161.448765,0.9799990653991699,-0.10580829457752737,1739141161.4487667,0.9799990653991699,-0.023372259014922587,1739141161.4487681,0.9799990653991699,-0.030564238296994596,1739141161.4487698,0.9799990653991699,-0.012405012350242432,1739141161.448771,0.9799990653991699,2.4696218371629812,1739141161.448773,0.9799990653991699,0.0,1739141161.4487743,0.9799990653991699,1.5547044690349463,1739141161.4487758,0.9799990653991699,6.26683939510404,1739141161.4487774,0.9799990653991699,0.9149173681280349 +1739141161.4683392,0.9999990463256836,0.4157598615599376,1739141161.468342,0.9999990463256836,-0.0041486210906525045,1739141161.468345,0.9999990463256836,0.025404086454546976,1739141161.4683473,0.9999990463256836,4.764554806554991,1739141161.4683487,0.9999990463256836,-0.10580829457752737,1739141161.4683504,0.9999990463256836,-0.023372259014922587,1739141161.468352,0.9999990463256836,-0.030564238296994596,1739141161.4683533,0.9999990463256836,-0.012405012350242432,1739141161.4683547,0.9999990463256836,2.4696218371629812,1739141161.4683564,0.9999990463256836,0.0,1739141161.468358,0.9999990463256836,1.5547044690349463,1739141161.4683595,0.9999990463256836,6.26683939510404,1739141161.4683607,0.9999990463256836,0.9149173681280349 +1739141161.4883142,1.0199990272521973,0.4157598615599376,1739141161.4883163,1.0199990272521973,-0.0041486210906525045,1739141161.488319,1.0199990272521973,0.025404086454546976,1739141161.4883215,1.0199990272521973,4.764554806554991,1739141161.488323,1.0199990272521973,-0.10580829457752737,1739141161.4883246,1.0199990272521973,-0.023372259014922587,1739141161.4883258,1.0199990272521973,-0.030564238296994596,1739141161.4883273,1.0199990272521973,-0.012405012350242432,1739141161.4883285,1.0199990272521973,2.4696218371629812,1739141161.48833,1.0199990272521973,0.0,1739141161.4883316,1.0199990272521973,1.5547044690349463,1739141161.4883325,1.0199990272521973,6.26683939510404,1739141161.488334,1.0199990272521973,0.9149173681280349 +1739141161.5082786,1.039999008178711,0.4157598615599376,1739141161.5082836,1.039999008178711,-0.0041486210906525045,1739141161.5082867,1.039999008178711,0.025404086454546976,1739141161.50829,1.039999008178711,4.764554806554991,1739141161.5082912,1.039999008178711,-0.10580829457752737,1739141161.5082932,1.039999008178711,-0.023372259014922587,1739141161.5082946,1.039999008178711,-0.030564238296994596,1739141161.5082963,1.039999008178711,-0.012405012350242432,1739141161.5082974,1.039999008178711,2.4696218371629812,1739141161.5082994,1.039999008178711,0.0,1739141161.508301,1.039999008178711,1.5547044690349463,1739141161.5083025,1.039999008178711,6.26683939510404,1739141161.5083039,1.039999008178711,0.9149173681280349 +1739141161.5283415,1.0599989891052246,0.521866048632031,1739141161.5283442,1.0599989891052246,-0.005992583930461315,1739141161.5283468,1.0599989891052246,0.02646514832526791,1739141161.5283496,1.0599989891052246,5.094226195105077,1739141161.5283513,1.0599989891052246,-0.11018019165804825,1739141161.528353,1.0599989891052246,-0.022782453244142395,1739141161.5283544,1.0599989891052246,-0.019333959827232815,1739141161.5283558,1.0599989891052246,-0.007098636276849689,1739141161.528357,1.0599989891052246,2.4807406082233756,1739141161.528359,1.0599989891052246,0.0,1739141161.5283604,1.0599989891052246,1.366793779189961,1739141161.5283618,1.0599989891052246,6.264630211239775,1739141161.528363,1.0599989891052246,1.0244655034550187 +1739141161.5488663,1.0799989700317383,0.521866048632031,1739141161.548869,1.0799989700317383,-0.005992583930461315,1739141161.548872,1.0799989700317383,0.02646514832526791,1739141161.548875,1.0799989700317383,5.094226195105077,1739141161.5488763,1.0799989700317383,-0.11018019165804825,1739141161.5488782,1.0799989700317383,-0.022782453244142395,1739141161.5488796,1.0799989700317383,-0.019333959827232815,1739141161.5488808,1.0799989700317383,-0.007098636276849689,1739141161.5488825,1.0799989700317383,2.4807406082233756,1739141161.548884,1.0799989700317383,0.0,1739141161.5488856,1.0799989700317383,1.4562751047683569,1739141161.548887,1.0799989700317383,6.264630211239775,1739141161.5488882,1.0799989700317383,1.0244655034550187 +1739141161.5684235,1.099998950958252,0.521866048632031,1739141161.5684261,1.099998950958252,-0.005992583930461315,1739141161.568429,1.099998950958252,0.02646514832526791,1739141161.5684319,1.099998950958252,5.094226195105077,1739141161.568433,1.099998950958252,-0.11018019165804825,1739141161.568435,1.099998950958252,-0.022782453244142395,1739141161.5684364,1.099998950958252,-0.019333959827232815,1739141161.568438,1.099998950958252,-0.007098636276849689,1739141161.5684392,1.099998950958252,2.4807406082233756,1739141161.568441,1.099998950958252,0.0,1739141161.5684423,1.099998950958252,1.4562751047683569,1739141161.5684435,1.099998950958252,6.264630211239775,1739141161.5684454,1.099998950958252,1.0244655034550187 +1739141161.5882926,1.1199989318847656,0.521866048632031,1739141161.5882952,1.1199989318847656,-0.005992583930461315,1739141161.5882983,1.1199989318847656,0.02646514832526791,1739141161.588301,1.1199989318847656,5.094226195105077,1739141161.5883026,1.1199989318847656,-0.11018019165804825,1739141161.588304,1.1199989318847656,-0.022782453244142395,1739141161.5883057,1.1199989318847656,-0.019333959827232815,1739141161.588307,1.1199989318847656,-0.007098636276849689,1739141161.5883083,1.1199989318847656,2.4807406082233756,1739141161.58831,1.1199989318847656,0.0,1739141161.5883114,1.1199989318847656,1.4562751047683569,1739141161.5883129,1.1199989318847656,6.264630211239775,1739141161.5883143,1.1199989318847656,1.0244655034550187 +1739141161.6082118,1.1399989128112793,0.521866048632031,1739141161.6082146,1.1399989128112793,-0.005992583930461315,1739141161.6082177,1.1399989128112793,0.02646514832526791,1739141161.6082203,1.1399989128112793,5.094226195105077,1739141161.6082218,1.1399989128112793,-0.11018019165804825,1739141161.6082234,1.1399989128112793,-0.022782453244142395,1739141161.608225,1.1399989128112793,-0.019333959827232815,1739141161.6082265,1.1399989128112793,-0.007098636276849689,1739141161.6082277,1.1399989128112793,2.4807406082233756,1739141161.6082296,1.1399989128112793,0.0,1739141161.6082308,1.1399989128112793,1.4562751047683569,1739141161.6082325,1.1399989128112793,6.264630211239775,1739141161.6082337,1.1399989128112793,1.0244655034550187 +1739141161.6282628,1.159998893737793,0.521866048632031,1739141161.6282651,1.159998893737793,-0.005992583930461315,1739141161.628268,1.159998893737793,0.02646514832526791,1739141161.6282709,1.159998893737793,5.094226195105077,1739141161.628272,1.159998893737793,-0.11018019165804825,1739141161.628274,1.159998893737793,-0.022782453244142395,1739141161.6282754,1.159998893737793,-0.019333959827232815,1739141161.6282768,1.159998893737793,-0.007098636276849689,1739141161.628278,1.159998893737793,2.4807406082233756,1739141161.62828,1.159998893737793,0.0,1739141161.6282814,1.159998893737793,1.4562751047683569,1739141161.6282825,1.159998893737793,6.264630211239775,1739141161.628284,1.159998893737793,1.0244655034550187 +1739141161.6485598,1.1799988746643066,0.640023074827214,1739141161.6485634,1.1799988746643066,-0.008296694374183566,1739141161.6485665,1.1799988746643066,0.02764671858721974,1739141161.6485693,1.1799988746643066,5.424215234446647,1739141161.6485705,1.1799988746643066,-0.11384599202548591,1739141161.6485727,1.1799988746643066,-0.02205851568016516,1739141161.6485739,1.1799988746643066,-0.007195285567975036,1739141161.6485755,1.1799988746643066,-0.0024131293176418533,1739141161.648577,1.1799988746643066,2.492815058932308,1739141161.648579,1.1799988746643066,0.0,1739141161.6485803,1.1799988746643066,1.2700721223519225,1739141161.6485817,1.1799988746643066,6.262630397035166,1739141161.6485832,1.1799988746643066,1.1340748054218115 +1739141161.6716995,1.1999988555908203,0.640023074827214,1739141161.671711,1.1999988555908203,-0.008296694374183566,1739141161.6717217,1.1999988555908203,0.02764671858721974,1739141161.671733,1.1999988555908203,5.424215234446647,1739141161.6717386,1.1999988555908203,-0.11384599202548591,1739141161.671746,1.1999988555908203,-0.02205851568016516,1739141161.6717515,1.1999988555908203,-0.007195285567975036,1739141161.6717572,1.1999988555908203,-0.0024131293176418533,1739141161.6717625,1.1999988555908203,2.492815058932308,1739141161.6717696,1.1999988555908203,0.0,1739141161.6717758,1.1999988555908203,1.3587402535104967,1739141161.6717806,1.1999988555908203,6.262630397035166,1739141161.671786,1.1999988555908203,1.1340748054218115 +1739141161.6934595,1.2099988460540771,0.640023074827214,1739141161.6934764,1.2099988460540771,-0.008296694374183566,1739141161.6934888,1.2099988460540771,0.02764671858721974,1739141161.6934972,1.2099988460540771,5.424215234446647,1739141161.6935012,1.2099988460540771,-0.11384599202548591,1739141161.6935062,1.2099988460540771,-0.02205851568016516,1739141161.6935098,1.2099988460540771,-0.007195285567975036,1739141161.6935139,1.2099988460540771,-0.0024131293176418533,1739141161.693518,1.2099988460540771,2.492815058932308,1739141161.6935222,1.2099988460540771,0.0,1739141161.6935263,1.2099988460540771,1.3587402535104967,1739141161.69353,1.2099988460540771,6.262630397035166,1739141161.6935337,1.2099988460540771,1.1340748054218115 +1739141161.7111702,1.2399988174438477,0.640023074827214,1739141161.7111754,1.2399988174438477,-0.008296694374183566,1739141161.7111802,1.2399988174438477,0.02764671858721974,1739141161.7111847,1.2399988174438477,5.424215234446647,1739141161.7111871,1.2399988174438477,-0.11384599202548591,1739141161.7111902,1.2399988174438477,-0.02205851568016516,1739141161.7111926,1.2399988174438477,-0.007195285567975036,1739141161.7111952,1.2399988174438477,-0.0024131293176418533,1739141161.7111974,1.2399988174438477,2.492815058932308,1739141161.7112002,1.2399988174438477,0.0,1739141161.7112026,1.2399988174438477,1.3587402535104967,1739141161.7112048,1.2399988174438477,6.262630397035166,1739141161.7112072,1.2399988174438477,1.1340748054218115 +1739141161.7308326,1.2599987983703613,0.640023074827214,1739141161.7308378,1.2599987983703613,-0.008296694374183566,1739141161.730842,1.2599987983703613,0.02764671858721974,1739141161.7308462,1.2599987983703613,5.424215234446647,1739141161.7308483,1.2599987983703613,-0.11384599202548591,1739141161.7308505,1.2599987983703613,-0.02205851568016516,1739141161.7308528,1.2599987983703613,-0.007195285567975036,1739141161.730855,1.2599987983703613,-0.0024131293176418533,1739141161.7308571,1.2599987983703613,2.492815058932308,1739141161.7308595,1.2599987983703613,0.0,1739141161.7308617,1.2599987983703613,1.3587402535104967,1739141161.7308633,1.2599987983703613,6.262630397035166,1739141161.7308657,1.2599987983703613,1.1340748054218115 +1739141161.7498817,1.279998779296875,0.7702215436698623,1739141161.7498846,1.279998779296875,-0.011085496174882081,1739141161.749888,1.279998779296875,0.02894870327564622,1739141161.749891,1.279998779296875,5.75402763987355,1739141161.7498927,1.279998779296875,-0.11904613586134223,1739141161.7498949,1.279998779296875,-0.02165889991374499,1739141161.7498968,1.279998779296875,0.0036400078639767216,1739141161.7498982,1.279998779296875,0.0011249610882047081,1739141161.7498996,1.279998779296875,2.4963626407818387,1739141161.7499013,1.279998779296875,0.0,1739141161.749903,1.279998779296875,1.1564303077203764,1739141161.7499044,1.279998779296875,6.26079621143314,1739141161.7499058,1.279998779296875,1.2435942155124968 +1739141161.770106,1.2999987602233887,0.7702215436698623,1739141161.7701101,1.2999987602233887,-0.011085496174882081,1739141161.7701135,1.2999987602233887,0.02894870327564622,1739141161.7701168,1.2999987602233887,5.75402763987355,1739141161.7701187,1.2999987602233887,-0.11904613586134223,1739141161.7701206,1.2999987602233887,-0.02165889991374499,1739141161.7701223,1.2999987602233887,0.0036400078639767216,1739141161.770124,1.2999987602233887,0.0011249610882047081,1739141161.7701256,1.2999987602233887,2.4963626407818387,1739141161.7701273,1.2999987602233887,0.0,1739141161.770129,1.2999987602233887,1.2527684252693418,1739141161.7701304,1.2999987602233887,6.26079621143314,1739141161.770132,1.2999987602233887,1.2435942155124968 +1739141161.80162,1.3199987411499023,0.7702215436698623,1739141161.801625,1.3199987411499023,-0.011085496174882081,1739141161.8016307,1.3199987411499023,0.02894870327564622,1739141161.8016367,1.3199987411499023,5.75402763987355,1739141161.8016403,1.3199987411499023,-0.11904613586134223,1739141161.8016446,1.3199987411499023,-0.02165889991374499,1739141161.8016481,1.3199987411499023,0.0036400078639767216,1739141161.8016517,1.3199987411499023,0.0011249610882047081,1739141161.8016553,1.3199987411499023,2.4963626407818387,1739141161.801659,1.3199987411499023,0.0,1739141161.801663,1.3199987411499023,1.2527684252693418,1739141161.8016665,1.3199987411499023,6.26079621143314,1739141161.8016698,1.3199987411499023,1.2435942155124968 +1739141161.8136413,1.3299987316131592,0.7702215436698623,1739141161.8136497,1.3299987316131592,-0.011085496174882081,1739141161.813657,1.3299987316131592,0.02894870327564622,1739141161.8136625,1.3299987316131592,5.75402763987355,1739141161.8136666,1.3299987316131592,-0.11904613586134223,1739141161.813674,1.3299987316131592,-0.02165889991374499,1739141161.8136787,1.3299987316131592,0.0036400078639767216,1739141161.8136833,1.3299987316131592,0.0011249610882047081,1739141161.8136864,1.3299987316131592,2.4963626407818387,1739141161.8136904,1.3299987316131592,0.0,1739141161.8136942,1.3299987316131592,1.2527684252693418,1739141161.8136992,1.3299987316131592,6.26079621143314,1739141161.8137028,1.3299987316131592,1.2435942155124968 +1739141161.835941,1.3499987125396729,0.7702215436698623,1739141161.8359466,1.3499987125396729,-0.011085496174882081,1739141161.8359523,1.3499987125396729,0.02894870327564622,1739141161.835958,1.3499987125396729,5.75402763987355,1739141161.8359616,1.3499987125396729,-0.11904613586134223,1739141161.8359654,1.3499987125396729,-0.02165889991374499,1739141161.835969,1.3499987125396729,0.0036400078639767216,1739141161.8359728,1.3499987125396729,0.0011249610882047081,1739141161.8359764,1.3499987125396729,2.4963626407818387,1739141161.8359802,1.3499987125396729,0.0,1739141161.8359838,1.3499987125396729,1.2527684252693418,1739141161.8359876,1.3499987125396729,6.26079621143314,1739141161.8359914,1.3499987125396729,1.2435942155124968 +1739141161.8508158,1.3699986934661865,0.7702215436698623,1739141161.8508208,1.3699986934661865,-0.011085496174882081,1739141161.8508258,1.3699986934661865,0.02894870327564622,1739141161.8508313,1.3699986934661865,5.75402763987355,1739141161.8508346,1.3699986934661865,-0.11904613586134223,1739141161.8508384,1.3699986934661865,-0.02165889991374499,1739141161.850842,1.3699986934661865,0.0036400078639767216,1739141161.8508453,1.3699986934661865,0.0011249610882047081,1739141161.8508487,1.3699986934661865,2.4963626407818387,1739141161.8508523,1.3699986934661865,0.0,1739141161.8508556,1.3699986934661865,1.2527684252693418,1739141161.8508592,1.3699986934661865,6.26079621143314,1739141161.8508625,1.3699986934661865,1.2435942155124968 +1739141161.8782914,1.3899986743927002,0.912466299607237,1739141161.8782964,1.3899986743927002,-0.014381194012286436,1739141161.8783016,1.3899986743927002,0.03037115083501997,1739141161.8783076,1.3899986743927002,6.084191768394366,1739141161.878311,1.3899986743927002,-0.12178082182642916,1739141161.878315,1.3899986743927002,-0.020763707115391203,1739141161.8783183,1.3899986743927002,0.017002482791109667,1739141161.8783221,1.3899986743927002,0.004879945853145193,1739141161.8783255,1.3899986743927002,2.4830552032449087,1739141161.8783293,1.3899986743927002,0.0,1739141161.8783329,1.3899986743927002,1.0181549026767456,1739141161.8783364,1.3899986743927002,6.259134718639374,1739141161.87834,1.3899986743927002,1.3531795197146586 +1739141161.8902621,1.4099986553192139,0.912466299607237,1739141161.890265,1.4099986553192139,-0.014381194012286436,1739141161.8902683,1.4099986553192139,0.03037115083501997,1739141161.8902712,1.4099986553192139,6.084191768394366,1739141161.8902729,1.4099986553192139,-0.12178082182642916,1739141161.8902743,1.4099986553192139,-0.020763707115391203,1739141161.8902762,1.4099986553192139,0.017002482791109667,1739141161.8902776,1.4099986553192139,0.004879945853145193,1739141161.8902788,1.4099986553192139,2.4830552032449087,1739141161.8902807,1.4099986553192139,0.0,1739141161.8902822,1.4099986553192139,1.1298756835302501,1739141161.8902843,1.4099986553192139,6.259134718639374,1739141161.8902855,1.4099986553192139,1.3531795197146586 +1739141161.9097335,1.4299986362457275,0.912466299607237,1739141161.9097369,1.4299986362457275,-0.014381194012286436,1739141161.9097397,1.4299986362457275,0.03037115083501997,1739141161.9097428,1.4299986362457275,6.084191768394366,1739141161.9097445,1.4299986362457275,-0.12178082182642916,1739141161.909746,1.4299986362457275,-0.020763707115391203,1739141161.9097474,1.4299986362457275,0.017002482791109667,1739141161.909749,1.4299986362457275,0.004879945853145193,1739141161.9097505,1.4299986362457275,2.4830552032449087,1739141161.9097524,1.4299986362457275,0.0,1739141161.9097538,1.4299986362457275,1.1298756835302501,1739141161.9097555,1.4299986362457275,6.259134718639374,1739141161.9097567,1.4299986362457275,1.3531795197146586 +1739141161.9308264,1.4499986171722412,0.912466299607237,1739141161.9308312,1.4499986171722412,-0.014381194012286436,1739141161.9308362,1.4499986171722412,0.03037115083501997,1739141161.9308422,1.4499986171722412,6.084191768394366,1739141161.9308455,1.4499986171722412,-0.12178082182642916,1739141161.93085,1.4499986171722412,-0.020763707115391203,1739141161.9308536,1.4499986171722412,0.017002482791109667,1739141161.9308574,1.4499986171722412,0.004879945853145193,1739141161.930861,1.4499986171722412,2.4830552032449087,1739141161.9308655,1.4499986171722412,0.0,1739141161.930869,1.4499986171722412,1.1298756835302501,1739141161.9308736,1.4499986171722412,6.259134718639374,1739141161.9308772,1.4499986171722412,1.3531795197146586 +1739141161.9502425,1.4699985980987549,0.912466299607237,1739141161.9502451,1.4699985980987549,-0.014381194012286436,1739141161.9502497,1.4699985980987549,0.03037115083501997,1739141161.9502528,1.4699985980987549,6.084191768394366,1739141161.9502544,1.4699985980987549,-0.12178082182642916,1739141161.9502559,1.4699985980987549,-0.020763707115391203,1739141161.950257,1.4699985980987549,0.017002482791109667,1739141161.9502585,1.4699985980987549,0.004879945853145193,1739141161.9502594,1.4699985980987549,2.4830552032449087,1739141161.9502609,1.4699985980987549,0.0,1739141161.9502625,1.4699985980987549,1.1298756835302501,1739141161.9502635,1.4699985980987549,6.259134718639374,1739141161.950265,1.4699985980987549,1.3531795197146586 +1739141161.9697382,1.4899985790252686,0.912466299607237,1739141161.9697409,1.4899985790252686,-0.014381194012286436,1739141161.9697433,1.4899985790252686,0.03037115083501997,1739141161.9697459,1.4899985790252686,6.084191768394366,1739141161.9697475,1.4899985790252686,-0.12178082182642916,1739141161.969749,1.4899985790252686,-0.020763707115391203,1739141161.9697506,1.4899985790252686,0.017002482791109667,1739141161.9697516,1.4899985790252686,0.004879945853145193,1739141161.9697528,1.4899985790252686,2.4830552032449087,1739141161.9697545,1.4899985790252686,0.0,1739141161.9697556,1.4899985790252686,1.1298756835302501,1739141161.9697568,1.4899985790252686,6.259134718639374,1739141161.9697583,1.4899985790252686,1.3531795197146586 +1739141161.9922593,1.5099985599517822,1.066747640077267,1739141161.9922657,1.5099985599517822,-0.018202568168151245,1739141161.9922707,1.5099985599517822,0.2372492949566175,1739141161.992275,1.5099985599517822,6.61952586134293,1739141161.9922798,1.5099985599517822,-0.125,1739141161.992285,1.5099985599517822,-0.019230781758445503,1739141161.9922874,1.5099985599517822,0.035195116965603325,1739141161.9922917,1.5099985599517822,0.008763167635199897,1739141161.9922955,1.5099985599517822,2.4650514638046053,1739141161.9922996,1.5099985599517822,0.0,1739141161.9923036,1.5099985599517822,0.88647708946804,1739141161.9923067,1.5099985599517822,6.257617365298672,1739141161.9923108,1.5099985599517822,1.4626702240268021 +1739141162.009834,1.529998540878296,1.066747640077267,1739141162.0098364,1.529998540878296,-0.018202568168151245,1739141162.0098393,1.529998540878296,0.2372492949566175,1739141162.009842,1.529998540878296,6.61952586134293,1739141162.0098433,1.529998540878296,-0.125,1739141162.009845,1.529998540878296,-0.019230781758445503,1739141162.0098464,1.529998540878296,0.035195116965603325,1739141162.0098479,1.529998540878296,0.008763167635199897,1739141162.009849,1.529998540878296,2.4650514638046053,1739141162.0098507,1.529998540878296,0.0,1739141162.0098524,1.529998540878296,1.0023812397778031,1739141162.0098536,1.529998540878296,6.257617365298672,1739141162.009855,1.529998540878296,1.4626702240268021 +1739141162.0296662,1.5499985218048096,1.066747640077267,1739141162.0296705,1.5499985218048096,-0.018202568168151245,1739141162.029674,1.5499985218048096,0.2372492949566175,1739141162.0296774,1.5499985218048096,6.61952586134293,1739141162.0296788,1.5499985218048096,-0.125,1739141162.0296814,1.5499985218048096,-0.019230781758445503,1739141162.0296834,1.5499985218048096,0.035195116965603325,1739141162.029685,1.5499985218048096,0.008763167635199897,1739141162.0296867,1.5499985218048096,2.4650514638046053,1739141162.0296886,1.5499985218048096,0.0,1739141162.0296903,1.5499985218048096,1.0023812397778031,1739141162.029692,1.5499985218048096,6.257617365298672,1739141162.0296934,1.5499985218048096,1.4626702240268021 +1739141162.0499456,1.5699985027313232,1.066747640077267,1739141162.049948,1.5699985027313232,-0.018202568168151245,1739141162.0499501,1.5699985027313232,0.2372492949566175,1739141162.0499527,1.5699985027313232,6.61952586134293,1739141162.049954,1.5699985027313232,-0.125,1739141162.0499554,1.5699985027313232,-0.019230781758445503,1739141162.0499566,1.5699985027313232,0.035195116965603325,1739141162.049958,1.5699985027313232,0.008763167635199897,1739141162.0499592,1.5699985027313232,2.4650514638046053,1739141162.0499604,1.5699985027313232,0.0,1739141162.0499618,1.5699985027313232,1.0023812397778031,1739141162.049963,1.5699985027313232,6.257617365298672,1739141162.049964,1.5699985027313232,1.4626702240268021 +1739141162.070438,1.589998483657837,1.066747640077267,1739141162.0704403,1.589998483657837,-0.018202568168151245,1739141162.0705268,1.589998483657837,0.2372492949566175,1739141162.0705354,1.589998483657837,6.61952586134293,1739141162.0705388,1.589998483657837,-0.125,1739141162.070543,1.589998483657837,-0.019230781758445503,1739141162.0705597,1.589998483657837,0.035195116965603325,1739141162.0705633,1.589998483657837,0.008763167635199897,1739141162.070567,1.589998483657837,2.4650514638046053,1739141162.0705705,1.589998483657837,0.0,1739141162.070574,1.589998483657837,1.0023812397778031,1739141162.0705776,1.589998483657837,6.257617365298672,1739141162.0705812,1.589998483657837,1.4626702240268021 +1739141162.0901973,1.6099984645843506,1.2328702154097009,1739141162.0901992,1.6099984645843506,-0.02255716596773638,1739141162.090202,1.6099984645843506,0.7292217682363763,1739141162.0902047,1.6099984645843506,7.433141245404912,1739141162.090206,1.6099984645843506,-0.12928852718222686,1739141162.0902073,1.6099984645843506,-0.017212283191578675,1739141162.0902085,1.6099984645843506,0.06023847721384839,1739141162.0902097,1.6099984645843506,0.012030477271656867,1739141162.090211,1.6099984645843506,2.4404814636029806,1739141162.0902123,1.6099984645843506,0.0,1739141162.0902135,1.6099984645843506,0.7507792608640818,1739141162.090215,1.6099984645843506,6.256258851622278,1739141162.090216,1.6099984645843506,1.5698916767389155 +1739141162.1097198,1.6299984455108643,1.2328702154097009,1739141162.1097221,1.6299984455108643,-0.02255716596773638,1739141162.109725,1.6299984455108643,0.7292217682363763,1739141162.1097274,1.6299984455108643,7.433141245404912,1739141162.1097288,1.6299984455108643,-0.12928852718222686,1739141162.1097302,1.6299984455108643,-0.017212283191578675,1739141162.109732,1.6299984455108643,0.06023847721384839,1739141162.109733,1.6299984455108643,0.012030477271656867,1739141162.109734,1.6299984455108643,2.4404814636029806,1739141162.1097357,1.6299984455108643,0.0,1739141162.1097372,1.6299984455108643,0.8705897868640651,1739141162.1097383,1.6299984455108643,6.256258851622278,1739141162.1097395,1.6299984455108643,1.5698916767389155 +1739141162.1296499,1.649998426437378,1.2328702154097009,1739141162.1296527,1.649998426437378,-0.02255716596773638,1739141162.1296556,1.649998426437378,0.7292217682363763,1739141162.1296585,1.649998426437378,7.433141245404912,1739141162.1296597,1.649998426437378,-0.12928852718222686,1739141162.129661,1.649998426437378,-0.017212283191578675,1739141162.1296625,1.649998426437378,0.06023847721384839,1739141162.1296763,1.649998426437378,0.012030477271656867,1739141162.1296778,1.649998426437378,2.4404814636029806,1739141162.1296794,1.649998426437378,0.0,1739141162.1296809,1.649998426437378,0.8705897868640651,1739141162.1296825,1.649998426437378,6.256258851622278,1739141162.1296835,1.649998426437378,1.5698916767389155 +1739141162.1493766,1.6699984073638916,1.2328702154097009,1739141162.149379,1.6699984073638916,-0.02255716596773638,1739141162.1493816,1.6699984073638916,0.7292217682363763,1739141162.1493843,1.6699984073638916,7.433141245404912,1739141162.1493855,1.6699984073638916,-0.12928852718222686,1739141162.1493866,1.6699984073638916,-0.017212283191578675,1739141162.149388,1.6699984073638916,0.06023847721384839,1739141162.149389,1.6699984073638916,0.012030477271656867,1739141162.14939,1.6699984073638916,2.4404814636029806,1739141162.149392,1.6699984073638916,0.0,1739141162.1493928,1.6699984073638916,0.8705897868640651,1739141162.1493943,1.6699984073638916,6.256258851622278,1739141162.1493957,1.6699984073638916,1.5698916767389155 +1739141162.169568,1.6899983882904053,1.2328702154097009,1739141162.169571,1.6899983882904053,-0.02255716596773638,1739141162.1695738,1.6899983882904053,0.7292217682363763,1739141162.1695764,1.6899983882904053,7.433141245404912,1739141162.1695778,1.6899983882904053,-0.12928852718222686,1739141162.1695793,1.6899983882904053,-0.017212283191578675,1739141162.1695802,1.6899983882904053,0.06023847721384839,1739141162.1695817,1.6899983882904053,0.012030477271656867,1739141162.1695828,1.6899983882904053,2.4404814636029806,1739141162.1695843,1.6899983882904053,0.0,1739141162.1695857,1.6899983882904053,0.8705897868640651,1739141162.169587,1.6899983882904053,6.256258851622278,1739141162.1695886,1.6899983882904053,1.5698916767389155 +1739141162.1894999,1.709998369216919,1.2328702154097009,1739141162.1895025,1.709998369216919,-0.02255716596773638,1739141162.189505,1.709998369216919,0.7292217682363763,1739141162.1895082,1.709998369216919,7.433141245404912,1739141162.1895094,1.709998369216919,-0.12928852718222686,1739141162.1895108,1.709998369216919,-0.017212283191578675,1739141162.1895125,1.709998369216919,0.06023847721384839,1739141162.1895137,1.709998369216919,0.012030477271656867,1739141162.189515,1.709998369216919,2.4404814636029806,1739141162.1895165,1.709998369216919,0.0,1739141162.1895177,1.709998369216919,0.8705897868640651,1739141162.1895192,1.709998369216919,6.256258851622278,1739141162.1895201,1.709998369216919,1.5698916767389155 +1739141162.2094986,1.7299983501434326,1.410041036521422,1739141162.209501,1.7299983501434326,-0.02742703300513938,1739141162.2095037,1.7299983501434326,0.7313478180897169,1739141162.2095063,1.7299983501434326,7.714245875441789,1739141162.2095075,1.7299983501434326,-0.131,1739141162.2095091,1.7299983501434326,-0.016427710140494215,1739141162.2095103,1.7299983501434326,0.07366454624474242,1739141162.2095118,1.7299983501434326,0.014231105567678835,1739141162.209513,1.7299983501434326,2.427410165210606,1739141162.2095144,1.7299983501434326,0.0,1739141162.2095158,1.7299983501434326,0.6680982438426931,1739141162.209517,1.7299983501434326,6.2550739217449465,1739141162.2095184,1.7299983501434326,1.662887328903725 +1739141162.232296,1.7499983310699463,1.410041036521422,1739141162.2323062,1.7499983310699463,-0.02742703300513938,1739141162.2323174,1.7499983310699463,0.7313478180897169,1739141162.2323291,1.7499983310699463,7.714245875441789,1739141162.2323344,1.7499983310699463,-0.131,1739141162.232341,1.7499983310699463,-0.016427710140494215,1739141162.2323458,1.7499983310699463,0.07366454624474242,1739141162.2323513,1.7499983310699463,0.014231105567678835,1739141162.2323558,1.7499983310699463,2.427410165210606,1739141162.232362,1.7499983310699463,0.0,1739141162.2323678,1.7499983310699463,0.7645228363068812,1739141162.2323732,1.7499983310699463,6.2550739217449465,1739141162.2323785,1.7499983310699463,1.662887328903725 +1739141162.2551253,1.76999831199646,1.410041036521422,1739141162.2551417,1.76999831199646,-0.02742703300513938,1739141162.255161,1.76999831199646,0.7313478180897169,1739141162.255182,1.76999831199646,7.714245875441789,1739141162.2551947,1.76999831199646,-0.131,1739141162.2552137,1.76999831199646,-0.016427710140494215,1739141162.2552373,1.76999831199646,0.07366454624474242,1739141162.25526,1.76999831199646,0.014231105567678835,1739141162.2552726,1.76999831199646,2.427410165210606,1739141162.2552874,1.76999831199646,0.0,1739141162.255309,1.76999831199646,0.7645228363068812,1739141162.2553263,1.76999831199646,6.2550739217449465,1739141162.2553399,1.76999831199646,1.662887328903725 +1739141162.2753282,1.7899982929229736,1.410041036521422,1739141162.2753394,1.7899982929229736,-0.02742703300513938,1739141162.2753496,1.7899982929229736,0.7313478180897169,1739141162.2753594,1.7899982929229736,7.714245875441789,1739141162.2753646,1.7899982929229736,-0.131,1739141162.2753713,1.7899982929229736,-0.016427710140494215,1739141162.2753763,1.7899982929229736,0.07366454624474242,1739141162.2753816,1.7899982929229736,0.014231105567678835,1739141162.2753866,1.7899982929229736,2.427410165210606,1739141162.2753925,1.7899982929229736,0.0,1739141162.2753978,1.7899982929229736,0.7645228363068812,1739141162.2754028,1.7899982929229736,6.2550739217449465,1739141162.2754078,1.7899982929229736,1.662887328903725 +1739141162.2936945,1.8099982738494873,1.410041036521422,1739141162.2937098,1.8099982738494873,-0.02742703300513938,1739141162.2937276,1.8099982738494873,0.7313478180897169,1739141162.2937455,1.8099982738494873,7.714245875441789,1739141162.293754,1.8099982738494873,-0.131,1739141162.2937655,1.8099982738494873,-0.016427710140494215,1739141162.2937746,1.8099982738494873,0.07366454624474242,1739141162.293784,1.8099982738494873,0.014231105567678835,1739141162.2937927,1.8099982738494873,2.427410165210606,1739141162.293801,1.8099982738494873,0.0,1739141162.2938092,1.8099982738494873,0.7645228363068812,1739141162.2938175,1.8099982738494873,6.2550739217449465,1739141162.2938275,1.8099982738494873,1.662887328903725 +1739141162.3264596,1.8399982452392578,1.5970110073994732,1739141162.3265016,1.8399982452392578,-0.03277972310053201,1739141162.3265228,1.8399982452392578,0.7335914577402536,1739141162.3265405,1.8399982452392578,7.964905805559878,1739141162.326549,1.8399982452392578,-0.13247024813038344,1739141162.3265595,1.8399982452392578,-0.01565389900163043,1739141162.326568,1.8399982452392578,0.08632807447980251,1739141162.3265755,1.8399982452392578,0.01634597350739852,1739141162.326584,1.8399982452392578,2.4151454235494345,1739141162.3265948,1.8399982452392578,0.0,1739141162.3266103,1.8399982452392578,0.5830217861201668,1739141162.3266227,1.8399982452392578,6.253975885688794,1739141162.3266387,1.8399982452392578,1.7456945227366658 +1739141162.3467286,1.8599982261657715,1.5970110073994732,1739141162.3467379,1.8599982261657715,-0.03277972310053201,1739141162.34675,1.8599982261657715,0.7335914577402536,1739141162.3467636,1.8599982261657715,7.964905805559878,1739141162.346771,1.8599982261657715,-0.13247024813038344,1739141162.3467808,1.8599982261657715,-0.01565389900163043,1739141162.3467894,1.8599982261657715,0.08632807447980251,1739141162.3467982,1.8599982261657715,0.01634597350739852,1739141162.346807,1.8599982261657715,2.4151454235494345,1739141162.3468163,1.8599982261657715,0.0,1739141162.3468251,1.8599982261657715,0.6694509008127687,1739141162.346834,1.8599982261657715,6.253975885688794,1739141162.3468425,1.8599982261657715,1.7456945227366658 +1739141162.3638864,1.8799982070922852,1.5970110073994732,1739141162.3638933,1.8799982070922852,-0.03277972310053201,1739141162.3639002,1.8799982070922852,0.7335914577402536,1739141162.3639078,1.8799982070922852,7.964905805559878,1739141162.3639128,1.8799982070922852,-0.13247024813038344,1739141162.3639185,1.8799982070922852,-0.01565389900163043,1739141162.363924,1.8799982070922852,0.08632807447980251,1739141162.363929,1.8799982070922852,0.01634597350739852,1739141162.363934,1.8799982070922852,2.4151454235494345,1739141162.3639395,1.8799982070922852,0.0,1739141162.363945,1.8799982070922852,0.6694509008127687,1739141162.36395,1.8799982070922852,6.253975885688794,1739141162.363955,1.8799982070922852,1.7456945227366658 +1739141162.3828573,1.8999981880187988,1.5970110073994732,1739141162.382861,1.8999981880187988,-0.03277972310053201,1739141162.3828652,1.8999981880187988,0.7335914577402536,1739141162.38287,1.8999981880187988,7.964905805559878,1739141162.3828728,1.8999981880187988,-0.13247024813038344,1739141162.3828764,1.8999981880187988,-0.01565389900163043,1739141162.3828797,1.8999981880187988,0.08632807447980251,1739141162.382883,1.8999981880187988,0.01634597350739852,1739141162.3828862,1.8999981880187988,2.4151454235494345,1739141162.3828895,1.8999981880187988,0.0,1739141162.3828928,1.8999981880187988,0.6694509008127687,1739141162.3828962,1.8999981880187988,6.253975885688794,1739141162.3828993,1.8999981880187988,1.7456945227366658 +1739141162.402337,1.9199981689453125,1.5970110073994732,1739141162.4023407,1.9199981689453125,-0.03277972310053201,1739141162.402345,1.9199981689453125,0.7335914577402536,1739141162.4023502,1.9199981689453125,7.964905805559878,1739141162.4023528,1.9199981689453125,-0.13247024813038344,1739141162.4023564,1.9199981689453125,-0.01565389900163043,1739141162.4023597,1.9199981689453125,0.08632807447980251,1739141162.4023633,1.9199981689453125,0.01634597350739852,1739141162.4023664,1.9199981689453125,2.4151454235494345,1739141162.4023697,1.9199981689453125,0.0,1739141162.4023733,1.9199981689453125,0.6694509008127687,1739141162.4023764,1.9199981689453125,6.253975885688794,1739141162.4023798,1.9199981689453125,1.7456945227366658 +1739141162.4230425,1.9399981498718262,1.792565117050322,1739141162.423046,1.9399981498718262,-0.0385857878635516,1739141162.4230504,1.9399981498718262,1.0381379867216103,1739141162.4230556,1.9399981498718262,8.486890907833011,1739141162.4230583,1.9399981498718262,-0.135,1739141162.4230618,1.9399981498718262,-0.014401382548033415,1739141162.4230652,1.9399981498718262,0.10595314980798105,1739141162.423068,1.9399981498718262,0.018153736482295103,1739141162.4230714,1.9399981498718262,2.3962606790874355,1739141162.4230747,1.9399981498718262,0.0,1739141162.4230778,1.9399981498718262,0.495020386427618,1739141162.4230812,1.9399981498718262,6.252957598171227,1739141162.4230843,1.9399981498718262,1.8181781014594094 +1739141162.4416304,1.9599981307983398,1.792565117050322,1739141162.4416327,1.9599981307983398,-0.0385857878635516,1739141162.4416354,1.9599981307983398,1.0381379867216103,1739141162.441638,1.9599981307983398,8.486890907833011,1739141162.4416392,1.9599981307983398,-0.135,1739141162.4416406,1.9599981307983398,-0.014401382548033415,1739141162.441642,1.9599981307983398,0.10595314980798105,1739141162.4416432,1.9599981307983398,0.018153736482295103,1739141162.4416442,1.9599981307983398,2.3962606790874355,1739141162.4416459,1.9599981307983398,0.0,1739141162.4416473,1.9599981307983398,0.5780825776280261,1739141162.4416485,1.9599981307983398,6.252957598171227,1739141162.4416497,1.9599981307983398,1.8181781014594094 +1739141162.4622724,1.9799981117248535,1.792565117050322,1739141162.4622755,1.9799981117248535,-0.0385857878635516,1739141162.4622786,1.9799981117248535,1.0381379867216103,1739141162.4622815,1.9799981117248535,8.486890907833011,1739141162.462283,1.9799981117248535,-0.135,1739141162.4622846,1.9799981117248535,-0.014401382548033415,1739141162.462286,1.9799981117248535,0.10595314980798105,1739141162.4622877,1.9799981117248535,0.018153736482295103,1739141162.4622889,1.9799981117248535,2.3962606790874355,1739141162.4622908,1.9799981117248535,0.0,1739141162.4622922,1.9799981117248535,0.5780825776280261,1739141162.4622934,1.9799981117248535,6.252957598171227,1739141162.4622948,1.9799981117248535,1.8181781014594094 +1739141162.4817944,1.9999980926513672,1.792565117050322,1739141162.4817977,1.9999980926513672,-0.0385857878635516,1739141162.481802,1.9999980926513672,1.0381379867216103,1739141162.4818053,1.9999980926513672,8.486890907833011,1739141162.4818068,1.9999980926513672,-0.135,1739141162.4818091,1.9999980926513672,-0.014401382548033415,1739141162.4818106,1.9999980926513672,0.10595314980798105,1739141162.481812,1.9999980926513672,0.018153736482295103,1739141162.481813,1.9999980926513672,2.3962606790874355,1739141162.4818149,1.9999980926513672,0.0,1739141162.4818163,1.9999980926513672,0.5780825776280261,1739141162.481818,1.9999980926513672,6.252957598171227,1739141162.4818192,1.9999980926513672,1.8181781014594094 +1739141162.5022893,2.019998073577881,1.792565117050322,1739141162.5022917,2.019998073577881,-0.0385857878635516,1739141162.5022945,2.019998073577881,1.0381379867216103,1739141162.5022972,2.019998073577881,8.486890907833011,1739141162.5022986,2.019998073577881,-0.135,1739141162.5023003,2.019998073577881,-0.014401382548033415,1739141162.5023015,2.019998073577881,0.10595314980798105,1739141162.5023026,2.019998073577881,0.018153736482295103,1739141162.502304,2.019998073577881,2.3962606790874355,1739141162.5023055,2.019998073577881,0.0,1739141162.5023067,2.019998073577881,0.5780825776280261,1739141162.502308,2.019998073577881,6.252957598171227,1739141162.502309,2.019998073577881,1.8181781014594094 +1739141162.5229182,2.0399980545043945,1.792565117050322,1739141162.5229213,2.0399980545043945,-0.0385857878635516,1739141162.522924,2.0399980545043945,1.0381379867216103,1739141162.5229266,2.0399980545043945,8.486890907833011,1739141162.5229282,2.0399980545043945,-0.135,1739141162.5229297,2.0399980545043945,-0.014401382548033415,1739141162.5229309,2.0399980545043945,0.10595314980798105,1739141162.522932,2.0399980545043945,0.018153736482295103,1739141162.5229332,2.0399980545043945,2.3962606790874355,1739141162.5229347,2.0399980545043945,0.0,1739141162.5229363,2.0399980545043945,0.5780825776280261,1739141162.5229375,2.0399980545043945,6.252957598171227,1739141162.522939,2.0399980545043945,1.8181781014594094 +1739141162.5416596,2.059998035430908,1.9954832758876542,1739141162.541662,2.059998035430908,-0.04480857203350386,1739141162.5416646,2.059998035430908,1.0407759227864954,1739141162.541667,2.059998035430908,8.674526758809916,1739141162.5416684,2.059998035430908,-0.135250252441603,1739141162.5416698,2.059998035430908,-0.013540285132096085,1739141162.5416713,2.059998035430908,0.11768026776131742,1739141162.5416725,2.059998035430908,0.020255832671016365,1739141162.5416734,2.059998035430908,2.3850465089774078,1739141162.541675,2.059998035430908,0.0,1739141162.5416763,2.059998035430908,0.4389469472092249,1739141162.5416775,2.059998035430908,6.252026396194094,1739141162.541679,2.059998035430908,1.8798444665666771 +1739141162.5612934,2.079998016357422,1.9954832758876542,1739141162.5612965,2.079998016357422,-0.04480857203350386,1739141162.5612996,2.079998016357422,1.0407759227864954,1739141162.5613022,2.079998016357422,8.674526758809916,1739141162.5613039,2.079998016357422,-0.135250252441603,1739141162.5613053,2.079998016357422,-0.013540285132096085,1739141162.5613067,2.079998016357422,0.11768026776131742,1739141162.5613081,2.079998016357422,0.020255832671016365,1739141162.5613093,2.079998016357422,2.3850465089774078,1739141162.561311,2.079998016357422,0.0,1739141162.5613124,2.079998016357422,0.5052020424107306,1739141162.5613136,2.079998016357422,6.252026396194094,1739141162.5613148,2.079998016357422,1.8798444665666771 +1739141162.5813994,2.0999979972839355,1.9954832758876542,1739141162.5814028,2.0999979972839355,-0.04480857203350386,1739141162.5814056,2.0999979972839355,1.0407759227864954,1739141162.5814083,2.0999979972839355,8.674526758809916,1739141162.5814095,2.0999979972839355,-0.135250252441603,1739141162.5814114,2.0999979972839355,-0.013540285132096085,1739141162.5814126,2.0999979972839355,0.11768026776131742,1739141162.581414,2.0999979972839355,0.020255832671016365,1739141162.581415,2.0999979972839355,2.3850465089774078,1739141162.5814166,2.0999979972839355,0.0,1739141162.5814183,2.0999979972839355,0.5052020424107306,1739141162.5814192,2.0999979972839355,6.252026396194094,1739141162.5814207,2.0999979972839355,1.8798444665666771 +1739141162.601321,2.119997978210449,1.9954832758876542,1739141162.6013243,2.119997978210449,-0.04480857203350386,1739141162.6013272,2.119997978210449,1.0407759227864954,1739141162.6013298,2.119997978210449,8.674526758809916,1739141162.6013315,2.119997978210449,-0.135250252441603,1739141162.601333,2.119997978210449,-0.013540285132096085,1739141162.6013346,2.119997978210449,0.11768026776131742,1739141162.6013355,2.119997978210449,0.020255832671016365,1739141162.6013367,2.119997978210449,2.3850465089774078,1739141162.6013384,2.119997978210449,0.0,1739141162.6013398,2.119997978210449,0.5052020424107306,1739141162.601341,2.119997978210449,6.252026396194094,1739141162.6013424,2.119997978210449,1.8798444665666771 +1739141162.6212366,2.139997959136963,1.9954832758876542,1739141162.621239,2.139997959136963,-0.04480857203350386,1739141162.6212416,2.139997959136963,1.0407759227864954,1739141162.6212442,2.139997959136963,8.674526758809916,1739141162.6212454,2.139997959136963,-0.135250252441603,1739141162.621247,2.139997959136963,-0.013540285132096085,1739141162.6212487,2.139997959136963,0.11768026776131742,1739141162.6212497,2.139997959136963,0.020255832671016365,1739141162.621251,2.139997959136963,2.3850465089774078,1739141162.6212525,2.139997959136963,0.0,1739141162.6212542,2.139997959136963,0.5052020424107306,1739141162.6212552,2.139997959136963,6.252026396194094,1739141162.6212564,2.139997959136963,1.8798444665666771 +1739141162.641567,2.1599979400634766,2.2048881398299383,1739141162.6415706,2.1599979400634766,-0.05141898021752578,1739141162.6415741,2.1599979400634766,1.3760149794004601,1739141162.641577,2.1599979400634766,9.173802912781722,1739141162.6415787,2.1599979400634766,-0.13793273750263293,1739141162.6415806,2.1599979400634766,-0.012413598990436122,1739141162.641582,2.1599979400634766,0.13661938457384057,1739141162.641584,2.1599979400634766,0.021600748851320177,1739141162.641585,2.1599979400634766,2.3670465061195944,1739141162.641587,2.1599979400634766,0.0,1739141162.6415884,2.1599979400634766,0.3664444125542591,1739141162.6415896,2.1599979400634766,6.251167851167464,1739141162.6415915,2.1599979400634766,1.9345269987215237 +1739141162.6631606,2.1799979209899902,2.2048881398299383,1739141162.6631675,2.1799979209899902,-0.05141898021752578,1739141162.6631742,2.1799979209899902,1.3760149794004601,1739141162.663182,2.1799979209899902,9.173802912781722,1739141162.663186,2.1799979209899902,-0.13793273750263293,1739141162.6631916,2.1799979209899902,-0.012413598990436122,1739141162.6631958,2.1799979209899902,0.13661938457384057,1739141162.6632001,2.1799979209899902,0.021600748851320177,1739141162.6632068,2.1799979209899902,2.3670465061195944,1739141162.663212,2.1799979209899902,0.0,1739141162.6632168,2.1799979209899902,0.43251950739807077,1739141162.6632206,2.1799979209899902,6.251167851167464,1739141162.6632264,2.1799979209899902,1.9345269987215237 +1739141162.6822636,2.199997901916504,2.2048881398299383,1739141162.682268,2.199997901916504,-0.05141898021752578,1739141162.682273,2.199997901916504,1.3760149794004601,1739141162.6822777,2.199997901916504,9.173802912781722,1739141162.6822796,2.199997901916504,-0.13793273750263293,1739141162.6822824,2.199997901916504,-0.012413598990436122,1739141162.6822848,2.199997901916504,0.13661938457384057,1739141162.6822872,2.199997901916504,0.021600748851320177,1739141162.6822891,2.199997901916504,2.3670465061195944,1739141162.6822917,2.199997901916504,0.0,1739141162.6822941,2.199997901916504,0.43251950739807077,1739141162.6822958,2.199997901916504,6.251167851167464,1739141162.682298,2.199997901916504,1.9345269987215237 +1739141162.703372,2.2199978828430176,2.2048881398299383,1739141162.7033756,2.2199978828430176,-0.05141898021752578,1739141162.7033794,2.2199978828430176,1.3760149794004601,1739141162.7033832,2.2199978828430176,9.173802912781722,1739141162.703385,2.2199978828430176,-0.13793273750263293,1739141162.7033877,2.2199978828430176,-0.012413598990436122,1739141162.7033896,2.2199978828430176,0.13661938457384057,1739141162.7033916,2.2199978828430176,0.021600748851320177,1739141162.7033932,2.2199978828430176,2.3670465061195944,1739141162.7033958,2.2199978828430176,0.0,1739141162.7033978,2.2199978828430176,0.43251950739807077,1739141162.7033994,2.2199978828430176,6.251167851167464,1739141162.7034016,2.2199978828430176,1.9345269987215237 +1739141162.722229,2.2399978637695312,2.2048881398299383,1739141162.7222338,2.2399978637695312,-0.05141898021752578,1739141162.7222388,2.2399978637695312,1.3760149794004601,1739141162.722243,2.2399978637695312,9.173802912781722,1739141162.7222455,2.2399978637695312,-0.13793273750263293,1739141162.7222486,2.2399978637695312,-0.012413598990436122,1739141162.722251,2.2399978637695312,0.13661938457384057,1739141162.722253,2.2399978637695312,0.021600748851320177,1739141162.722255,2.2399978637695312,2.3670465061195944,1739141162.7222574,2.2399978637695312,0.0,1739141162.7222598,2.2399978637695312,0.43251950739807077,1739141162.7222617,2.2399978637695312,6.251167851167464,1739141162.722264,2.2399978637695312,1.9345269987215237 +1739141162.742738,2.259997844696045,2.2048881398299383,1739141162.7427423,2.259997844696045,-0.05141898021752578,1739141162.7427468,2.259997844696045,1.3760149794004601,1739141162.7427511,2.259997844696045,9.173802912781722,1739141162.742753,2.259997844696045,-0.13793273750263293,1739141162.742756,2.259997844696045,-0.012413598990436122,1739141162.742759,2.259997844696045,0.13661938457384057,1739141162.7427607,2.259997844696045,0.021600748851320177,1739141162.7427628,2.259997844696045,2.3670465061195944,1739141162.7427654,2.259997844696045,0.0,1739141162.7427673,2.259997844696045,0.43251950739807077,1739141162.7427695,2.259997844696045,6.251167851167464,1739141162.7427714,2.259997844696045,1.9345269987215237 +1739141162.762622,2.2799978256225586,2.4198208866743576,1739141162.7626255,2.2799978256225586,-0.05837939922759361,1739141162.7626293,2.2799978256225586,1.6411792832719745,1739141162.7626336,2.2799978256225586,9.577126175937046,1739141162.7626352,2.2799978256225586,-0.1396708823480463,1739141162.7626379,2.2799978256225586,-0.011357345336197394,1739141162.7626395,2.2799978256225586,0.1533892683118602,1739141162.7626417,2.2799978256225586,0.022992838417607422,1739141162.7626433,2.2799978256225586,2.35122160392844,1739141162.7626457,2.2799978256225586,0.0,1739141162.7626476,2.2799978256225586,0.31438383470525894,1739141162.7626493,2.2799978256225586,6.250396555554995,1739141162.7626514,2.2799978256225586,1.9805826588866233 +1739141162.7821054,2.2999978065490723,2.4198208866743576,1739141162.7821097,2.2999978065490723,-0.05837939922759361,1739141162.7821143,2.2999978065490723,1.6411792832719745,1739141162.7821183,2.2999978065490723,9.577126175937046,1739141162.7821205,2.2999978065490723,-0.1396708823480463,1739141162.7821229,2.2999978065490723,-0.011357345336197394,1739141162.7821248,2.2999978065490723,0.1533892683118602,1739141162.782127,2.2999978065490723,0.022992838417607422,1739141162.782129,2.2999978065490723,2.35122160392844,1739141162.7821314,2.2999978065490723,0.0,1739141162.7821336,2.2999978065490723,0.3706389450418166,1739141162.7821352,2.2999978065490723,6.250396555554995,1739141162.7821372,2.2999978065490723,1.9805826588866233 +1739141162.8021169,2.319997787475586,2.4198208866743576,1739141162.8021202,2.319997787475586,-0.05837939922759361,1739141162.8021243,2.319997787475586,1.6411792832719745,1739141162.8021283,2.319997787475586,9.577126175937046,1739141162.8021305,2.319997787475586,-0.1396708823480463,1739141162.8021328,2.319997787475586,-0.011357345336197394,1739141162.8021348,2.319997787475586,0.1533892683118602,1739141162.802137,2.319997787475586,0.022992838417607422,1739141162.8021383,2.319997787475586,2.35122160392844,1739141162.802141,2.319997787475586,0.0,1739141162.8021429,2.319997787475586,0.3706389450418166,1739141162.8021448,2.319997787475586,6.250396555554995,1739141162.8021467,2.319997787475586,1.9805826588866233 +1739141162.8222387,2.3399977684020996,2.4198208866743576,1739141162.8222423,2.3399977684020996,-0.05837939922759361,1739141162.8222466,2.3399977684020996,1.6411792832719745,1739141162.8222501,2.3399977684020996,9.577126175937046,1739141162.8222523,2.3399977684020996,-0.1396708823480463,1739141162.8222547,2.3399977684020996,-0.011357345336197394,1739141162.8222563,2.3399977684020996,0.1533892683118602,1739141162.8222585,2.3399977684020996,0.022992838417607422,1739141162.8222601,2.3399977684020996,2.35122160392844,1739141162.8222625,2.3399977684020996,0.0,1739141162.8222647,2.3399977684020996,0.3706389450418166,1739141162.8222663,2.3399977684020996,6.250396555554995,1739141162.8222682,2.3399977684020996,1.9805826588866233 +1739141162.8428698,2.3599977493286133,2.4198208866743576,1739141162.8428736,2.3599977493286133,-0.05837939922759361,1739141162.8428788,2.3599977493286133,1.6411792832719745,1739141162.842883,2.3599977493286133,9.577126175937046,1739141162.8428855,2.3599977493286133,-0.1396708823480463,1739141162.842888,2.3599977493286133,-0.011357345336197394,1739141162.8428905,2.3599977493286133,0.1533892683118602,1739141162.8428926,2.3599977493286133,0.022992838417607422,1739141162.8428946,2.3599977493286133,2.35122160392844,1739141162.8428974,2.3599977493286133,0.0,1739141162.8428996,2.3599977493286133,0.3706389450418166,1739141162.8429017,2.3599977493286133,6.250396555554995,1739141162.8429039,2.3599977493286133,1.9805826588866233 +1739141162.8634324,2.379997730255127,2.639559712048663,1739141162.8634365,2.379997730255127,-0.06565835056910085,1739141162.8634412,2.379997730255127,2.2308787862233768,1739141162.8634458,2.379997730255127,10.28693454659877,1739141162.863448,2.379997730255127,-0.143,1739141162.8634505,2.379997730255127,-0.010113145276931072,1739141162.8634527,2.379997730255127,0.17874365277696883,1739141162.863455,2.379997730255127,0.023470039191362688,1739141162.8634567,2.379997730255127,2.327496603235671,1739141162.8634596,2.379997730255127,0.0,1739141162.8634617,2.379997730255127,0.24889878808113508,1739141162.8634636,2.379997730255127,6.249698024702864,1739141162.8634658,2.379997730255127,2.0206262828806127 +1739141162.8829231,2.3999977111816406,2.639559712048663,1739141162.8829272,2.3999977111816406,-0.06565835056910085,1739141162.8829317,2.3999977111816406,2.2308787862233768,1739141162.882936,2.3999977111816406,10.28693454659877,1739141162.8829384,2.3999977111816406,-0.143,1739141162.8829412,2.3999977111816406,-0.010113145276931072,1739141162.8829434,2.3999977111816406,0.17874365277696883,1739141162.8829455,2.3999977111816406,0.023470039191362688,1739141162.8829477,2.3999977111816406,2.327496603235671,1739141162.8829503,2.3999977111816406,0.0,1739141162.8829527,2.3999977111816406,0.30687032035505846,1739141162.8829548,2.3999977111816406,6.249698024702864,1739141162.8829567,2.3999977111816406,2.0206262828806127 +1739141162.9030416,2.4199976921081543,2.639559712048663,1739141162.9030457,2.4199976921081543,-0.06565835056910085,1739141162.90305,2.4199976921081543,2.2308787862233768,1739141162.9030545,2.4199976921081543,10.28693454659877,1739141162.9030569,2.4199976921081543,-0.143,1739141162.9030597,2.4199976921081543,-0.010113145276931072,1739141162.903062,2.4199976921081543,0.17874365277696883,1739141162.903064,2.4199976921081543,0.023470039191362688,1739141162.9030662,2.4199976921081543,2.327496603235671,1739141162.9030688,2.4199976921081543,0.0,1739141162.903071,2.4199976921081543,0.30687032035505846,1739141162.903073,2.4199976921081543,6.249698024702864,1739141162.903075,2.4199976921081543,2.0206262828806127 +1739141162.9223466,2.439997673034668,2.639559712048663,1739141162.9223506,2.439997673034668,-0.06565835056910085,1739141162.9223552,2.439997673034668,2.2308787862233768,1739141162.9223597,2.439997673034668,10.28693454659877,1739141162.922362,2.439997673034668,-0.143,1739141162.9223647,2.439997673034668,-0.010113145276931072,1739141162.9223669,2.439997673034668,0.17874365277696883,1739141162.922369,2.439997673034668,0.023470039191362688,1739141162.9223711,2.439997673034668,2.327496603235671,1739141162.9223735,2.439997673034668,0.0,1739141162.922376,2.439997673034668,0.30687032035505846,1739141162.922378,2.439997673034668,6.249698024702864,1739141162.92238,2.439997673034668,2.0206262828806127 +1739141162.942845,2.4599976539611816,2.639559712048663,1739141162.9428494,2.4599976539611816,-0.06565835056910085,1739141162.9428542,2.4599976539611816,2.2308787862233768,1739141162.9428587,2.4599976539611816,10.28693454659877,1739141162.9428608,2.4599976539611816,-0.143,1739141162.9428635,2.4599976539611816,-0.010113145276931072,1739141162.9428656,2.4599976539611816,0.17874365277696883,1739141162.942868,2.4599976539611816,0.023470039191362688,1739141162.94287,2.4599976539611816,2.327496603235671,1739141162.9428728,2.4599976539611816,0.0,1739141162.9428751,2.4599976539611816,0.30687032035505846,1739141162.9428773,2.4599976539611816,6.249698024702864,1739141162.9428794,2.4599976539611816,2.0206262828806127 +1739141162.9630387,2.4799976348876953,2.639559712048663,1739141162.9630427,2.4799976348876953,-0.06565835056910085,1739141162.9630477,2.4799976348876953,2.2308787862233768,1739141162.9630523,2.4799976348876953,10.28693454659877,1739141162.9630544,2.4799976348876953,-0.143,1739141162.963057,2.4799976348876953,-0.010113145276931072,1739141162.9630592,2.4799976348876953,0.17874365277696883,1739141162.9630613,2.4799976348876953,0.023470039191362688,1739141162.9630632,2.4799976348876953,2.327496603235671,1739141162.9630659,2.4799976348876953,0.0,1739141162.9630682,2.4799976348876953,0.30687032035505846,1739141162.9630702,2.4799976348876953,6.249698024702864,1739141162.9630723,2.4799976348876953,2.0206262828806127 +1739141162.9826388,2.499997615814209,2.863274242782845,1739141162.982643,2.499997615814209,-0.07322257934344822,1739141162.9826477,2.499997615814209,2.49520580487368,1739141162.9826522,2.499997615814209,10.648617716547376,1739141162.982654,2.499997615814209,-0.144398372469173,1739141162.9826567,2.499997615814209,-0.009142025714957924,1739141162.982659,2.499997615814209,0.19484897781041574,1739141162.982661,2.499997615814209,0.024686396308865988,1739141162.9826632,2.499997615814209,2.3125507607311797,1739141162.9826658,2.499997615814209,0.0,1739141162.982668,2.499997615814209,0.21638020826214324,1739141162.98267,2.499997615814209,6.249014047877983,1739141162.9826722,2.499997615814209,2.0530800013753687 +1739141163.0022733,2.5199975967407227,2.863274242782845,1739141163.0022771,2.5199975967407227,-0.07322257934344822,1739141163.0022817,2.5199975967407227,2.49520580487368,1739141163.0022862,2.5199975967407227,10.648617716547376,1739141163.002288,2.5199975967407227,-0.144398372469173,1739141163.0022907,2.5199975967407227,-0.009142025714957924,1739141163.002293,2.5199975967407227,0.19484897781041574,1739141163.002295,2.5199975967407227,0.024686396308865988,1739141163.0022972,2.5199975967407227,2.3125507607311797,1739141163.0022993,2.5199975967407227,0.0,1739141163.0023017,2.5199975967407227,0.259470759355811,1739141163.002304,2.5199975967407227,6.249014047877983,1739141163.002306,2.5199975967407227,2.0530800013753687 +1739141163.0224435,2.5399975776672363,2.863274242782845,1739141163.0224476,2.5399975776672363,-0.07322257934344822,1739141163.0224526,2.5399975776672363,2.49520580487368,1739141163.022457,2.5399975776672363,10.648617716547376,1739141163.022459,2.5399975776672363,-0.144398372469173,1739141163.022462,2.5399975776672363,-0.009142025714957924,1739141163.0224645,2.5399975776672363,0.19484897781041574,1739141163.0224667,2.5399975776672363,0.024686396308865988,1739141163.0224783,2.5399975776672363,2.3125507607311797,1739141163.0224814,2.5399975776672363,0.0,1739141163.022484,2.5399975776672363,0.259470759355811,1739141163.022486,2.5399975776672363,6.249014047877983,1739141163.022488,2.5399975776672363,2.0530800013753687 +1739141163.0427873,2.55999755859375,2.863274242782845,1739141163.0427914,2.55999755859375,-0.07322257934344822,1739141163.0427961,2.55999755859375,2.49520580487368,1739141163.0428004,2.55999755859375,10.648617716547376,1739141163.0428026,2.55999755859375,-0.144398372469173,1739141163.0428052,2.55999755859375,-0.009142025714957924,1739141163.0428076,2.55999755859375,0.19484897781041574,1739141163.0428095,2.55999755859375,0.024686396308865988,1739141163.0428116,2.55999755859375,2.3125507607311797,1739141163.0428143,2.55999755859375,0.0,1739141163.0428164,2.55999755859375,0.259470759355811,1739141163.0428188,2.55999755859375,6.249014047877983,1739141163.042821,2.55999755859375,2.0530800013753687 +1739141163.0626469,2.5799975395202637,2.863274242782845,1739141163.0626507,2.5799975395202637,-0.07322257934344822,1739141163.0626552,2.5799975395202637,2.49520580487368,1739141163.0626605,2.5799975395202637,10.648617716547376,1739141163.0626626,2.5799975395202637,-0.144398372469173,1739141163.0626652,2.5799975395202637,-0.009142025714957924,1739141163.0626676,2.5799975395202637,0.19484897781041574,1739141163.0626695,2.5799975395202637,0.024686396308865988,1739141163.0626717,2.5799975395202637,2.3125507607311797,1739141163.0626743,2.5799975395202637,0.0,1739141163.0626764,2.5799975395202637,0.259470759355811,1739141163.0626786,2.5799975395202637,6.249014047877983,1739141163.0626805,2.5799975395202637,2.0530800013753687 +1739141163.0818422,2.5999975204467773,3.0903726039687625,1739141163.0818458,2.5999975204467773,-0.08105126105988791,1739141163.0818496,2.5999975204467773,2.4489409908759066,1739141163.081853,2.5999975204467773,10.686343274286813,1739141163.0818548,2.5999975204467773,-0.14473520780613225,1739141163.0818567,2.5999975204467773,-0.008383715190435658,1739141163.0818586,2.5999975204467773,0.20056269374463323,1739141163.0818603,2.5999975204467773,0.026693334509703126,1739141163.081862,2.5999975204467773,2.3072714926247277,1739141163.0818639,2.5999975204467773,0.0,1739141163.0818658,2.5999975204467773,0.19594275247937706,1739141163.0818675,2.5999975204467773,6.24839562453331,1739141163.0818691,2.5999975204467773,2.0810772931875103 +1739141163.101406,2.619997501373291,3.0903726039687625,1739141163.1014087,2.619997501373291,-0.08105126105988791,1739141163.1014118,2.619997501373291,2.4489409908759066,1739141163.1014147,2.619997501373291,10.686343274286813,1739141163.101416,2.619997501373291,-0.14473520780613225,1739141163.1014178,2.619997501373291,-0.008383715190435658,1739141163.1014192,2.619997501373291,0.20056269374463323,1739141163.101421,2.619997501373291,0.026693334509703126,1739141163.101422,2.619997501373291,2.3072714926247277,1739141163.101424,2.619997501373291,0.0,1739141163.1014252,2.619997501373291,0.2261941994372174,1739141163.1014264,2.619997501373291,6.24839562453331,1739141163.101428,2.619997501373291,2.0810772931875103 +1739141163.12172,2.6399974822998047,3.0903726039687625,1739141163.121726,2.6399974822998047,-0.08105126105988791,1739141163.1217306,2.6399974822998047,2.4489409908759066,1739141163.121734,2.6399974822998047,10.686343274286813,1739141163.1217356,2.6399974822998047,-0.14473520780613225,1739141163.1217377,2.6399974822998047,-0.008383715190435658,1739141163.1217399,2.6399974822998047,0.20056269374463323,1739141163.1217418,2.6399974822998047,0.026693334509703126,1739141163.1217437,2.6399974822998047,2.3072714926247277,1739141163.1217458,2.6399974822998047,0.0,1739141163.1217477,2.6399974822998047,0.2261941994372174,1739141163.1217492,2.6399974822998047,6.24839562453331,1739141163.1217508,2.6399974822998047,2.0810772931875103 +1739141163.1414583,2.6599974632263184,3.0903726039687625,1739141163.1414616,2.6599974632263184,-0.08105126105988791,1739141163.1414645,2.6599974632263184,2.4489409908759066,1739141163.1414673,2.6599974632263184,10.686343274286813,1739141163.141469,2.6599974632263184,-0.14473520780613225,1739141163.1414704,2.6599974632263184,-0.008383715190435658,1739141163.141472,2.6599974632263184,0.20056269374463323,1739141163.1414733,2.6599974632263184,0.026693334509703126,1739141163.1414745,2.6599974632263184,2.3072714926247277,1739141163.1414764,2.6599974632263184,0.0,1739141163.1414778,2.6599974632263184,0.2261941994372174,1739141163.1414793,2.6599974632263184,6.24839562453331,1739141163.1414804,2.6599974632263184,2.0810772931875103 +1739141163.1615982,2.679997444152832,3.0903726039687625,1739141163.1616015,2.679997444152832,-0.08105126105988791,1739141163.1616051,2.679997444152832,2.4489409908759066,1739141163.1616087,2.679997444152832,10.686343274286813,1739141163.1616106,2.679997444152832,-0.14473520780613225,1739141163.1616125,2.679997444152832,-0.008383715190435658,1739141163.1616142,2.679997444152832,0.20056269374463323,1739141163.1616154,2.679997444152832,0.026693334509703126,1739141163.1616166,2.679997444152832,2.3072714926247277,1739141163.1616187,2.679997444152832,0.0,1739141163.16162,2.679997444152832,0.2261941994372174,1739141163.1616216,2.679997444152832,6.24839562453331,1739141163.1616228,2.679997444152832,2.0810772931875103 +1739141163.181739,2.6999974250793457,3.0903726039687625,1739141163.1817417,2.6999974250793457,-0.08105126105988791,1739141163.1817448,2.6999974250793457,2.4489409908759066,1739141163.1817477,2.6999974250793457,10.686343274286813,1739141163.181749,2.6999974250793457,-0.14473520780613225,1739141163.1817508,2.6999974250793457,-0.008383715190435658,1739141163.1817522,2.6999974250793457,0.20056269374463323,1739141163.1817539,2.6999974250793457,0.026693334509703126,1739141163.181755,2.6999974250793457,2.3072714926247277,1739141163.1817567,2.6999974250793457,0.0,1739141163.1817582,2.6999974250793457,0.2261941994372174,1739141163.1817596,2.6999974250793457,6.24839562453331,1739141163.1817608,2.6999974250793457,2.0810772931875103 +1739141163.2016923,2.7199974060058594,3.3203332972008557,1739141163.2016957,2.7199974060058594,-0.08911119508328191,1739141163.201699,2.7199974060058594,2.6255364879520617,1739141163.2017019,2.7199974060058594,10.935440770354642,1739141163.2017033,2.7199974060058594,-0.145,1739141163.2017052,2.7199974060058594,-0.007339069301869827,1739141163.2017066,2.7199974060058594,0.21306045178414626,1739141163.2017083,2.7199974060058594,0.028214723100882834,1739141163.2017095,2.7199974060058594,2.2957659868528597,1739141163.2017114,2.7199974060058594,0.0,1739141163.2017128,2.7199974060058594,0.1580907240782288,1739141163.2017143,2.7199974060058594,6.24786468677656,1739141163.2017155,2.7199974060058594,2.1052450202128847 +1739141163.2215524,2.739997386932373,3.3203332972008557,1739141163.2215555,2.739997386932373,-0.08911119508328191,1739141163.2215586,2.739997386932373,2.6255364879520617,1739141163.2215614,2.739997386932373,10.935440770354642,1739141163.2215629,2.739997386932373,-0.145,1739141163.2215648,2.739997386932373,-0.007339069301869827,1739141163.221566,2.739997386932373,0.21306045178414626,1739141163.2215672,2.739997386932373,0.028214723100882834,1739141163.2215686,2.739997386932373,2.2957659868528597,1739141163.2215703,2.739997386932373,0.0,1739141163.221572,2.739997386932373,0.19052096663997498,1739141163.221573,2.739997386932373,6.24786468677656,1739141163.2215743,2.739997386932373,2.1052450202128847 +1739141163.2416496,2.7599973678588867,3.3203332972008557,1739141163.2416527,2.7599973678588867,-0.08911119508328191,1739141163.2416558,2.7599973678588867,2.6255364879520617,1739141163.241659,2.7599973678588867,10.935440770354642,1739141163.24166,2.7599973678588867,-0.145,1739141163.241662,2.7599973678588867,-0.007339069301869827,1739141163.2416635,2.7599973678588867,0.21306045178414626,1739141163.241665,2.7599973678588867,0.028214723100882834,1739141163.241666,2.7599973678588867,2.2957659868528597,1739141163.2416675,2.7599973678588867,0.0,1739141163.2416692,2.7599973678588867,0.19052096663997498,1739141163.2416704,2.7599973678588867,6.24786468677656,1739141163.2416716,2.7599973678588867,2.1052450202128847 +1739141163.262407,2.7799973487854004,3.3203332972008557,1739141163.262411,2.7799973487854004,-0.08911119508328191,1739141163.2624152,2.7799973487854004,2.6255364879520617,1739141163.262419,2.7799973487854004,10.935440770354642,1739141163.2624211,2.7799973487854004,-0.145,1739141163.2624235,2.7799973487854004,-0.007339069301869827,1739141163.2624254,2.7799973487854004,0.21306045178414626,1739141163.2624273,2.7799973487854004,0.028214723100882834,1739141163.2624292,2.7799973487854004,2.2957659868528597,1739141163.2624314,2.7799973487854004,0.0,1739141163.2624338,2.7799973487854004,0.19052096663997498,1739141163.2624354,2.7799973487854004,6.24786468677656,1739141163.2624373,2.7799973487854004,2.1052450202128847 +1739141163.2879245,2.799997329711914,3.3203332972008557,1739141163.287934,2.799997329711914,-0.08911119508328191,1739141163.287944,2.799997329711914,2.6255364879520617,1739141163.2879536,2.799997329711914,10.935440770354642,1739141163.2879589,2.799997329711914,-0.145,1739141163.2879648,2.799997329711914,-0.007339069301869827,1739141163.2879698,2.799997329711914,0.21306045178414626,1739141163.287974,2.799997329711914,0.028214723100882834,1739141163.2879786,2.799997329711914,2.2957659868528597,1739141163.2879848,2.799997329711914,0.0,1739141163.28799,2.799997329711914,0.19052096663997498,1739141163.2879944,2.799997329711914,6.24786468677656,1739141163.2879992,2.799997329711914,2.1052450202128847 +1739141163.3178177,2.8199973106384277,3.552786752087844,1739141163.3178265,2.8199973106384277,-0.09737493466123315,1739141163.3178368,2.8199973106384277,3.28934510179951,1739141163.317847,2.8199973106384277,11.660860009816368,1739141163.3178515,2.8199973106384277,-0.14969930004908183,1739141163.317858,2.8199973106384277,-0.006453276552530696,1739141163.3178632,2.8199973106384277,0.23774262184617892,1739141163.3178678,2.8199973106384277,0.027771698878090497,1739141163.3178718,2.8199973106384277,2.27321171313612,1739141163.3178775,2.8199973106384277,0.0,1739141163.3178823,2.8199973106384277,0.10823315829416302,1739141163.3178868,2.8199973106384277,6.247406722129389,1739141163.3178911,2.8199973106384277,2.1257938646266292 +1739141163.3467207,2.8499972820281982,3.552786752087844,1739141163.346729,2.8499972820281982,-0.09737493466123315,1739141163.3467386,2.8499972820281982,3.28934510179951,1739141163.3467486,2.8499972820281982,11.660860009816368,1739141163.3467536,2.8499972820281982,-0.14969930004908183,1739141163.346759,2.8499972820281982,-0.006453276552530696,1739141163.346764,2.8499972820281982,0.23774262184617892,1739141163.3467686,2.8499972820281982,0.027771698878090497,1739141163.346773,2.8499972820281982,2.27321171313612,1739141163.3467789,2.8499972820281982,0.0,1739141163.3467836,2.8499972820281982,0.14741784850949058,1739141163.3467884,2.8499972820281982,6.247406722129389,1739141163.346793,2.8499972820281982,2.1257938646266292 +1739141163.3775249,2.8799972534179688,3.552786752087844,1739141163.377531,2.8799972534179688,-0.09737493466123315,1739141163.3775382,2.8799972534179688,3.28934510179951,1739141163.3775449,2.8799972534179688,11.660860009816368,1739141163.377548,2.8799972534179688,-0.14969930004908183,1739141163.3775523,2.8799972534179688,-0.006453276552530696,1739141163.377556,2.8799972534179688,0.23774262184617892,1739141163.377559,2.8799972534179688,0.027771698878090497,1739141163.377562,2.8799972534179688,2.27321171313612,1739141163.377566,2.8799972534179688,0.0,1739141163.3775697,2.8799972534179688,0.14741784850949058,1739141163.3775728,2.8799972534179688,6.247406722129389,1739141163.3775759,2.8799972534179688,2.1257938646266292 +1739141163.396771,2.9099972248077393,3.552786752087844,1739141163.3967755,2.9099972248077393,-0.09737493466123315,1739141163.3967795,2.9099972248077393,3.28934510179951,1739141163.3967829,2.9099972248077393,11.660860009816368,1739141163.3967848,2.9099972248077393,-0.14969930004908183,1739141163.3967872,2.9099972248077393,-0.006453276552530696,1739141163.3967893,2.9099972248077393,0.23774262184617892,1739141163.3967915,2.9099972248077393,0.027771698878090497,1739141163.3967934,2.9099972248077393,2.27321171313612,1739141163.3967953,2.9099972248077393,0.0,1739141163.3967974,2.9099972248077393,0.14741784850949058,1739141163.396799,2.9099972248077393,6.247406722129389,1739141163.3968012,2.9099972248077393,2.1257938646266292 +1739141163.4163926,2.929997205734253,3.7871480860050877,1739141163.4163969,2.929997205734253,-0.10581098221537655,1739141163.416402,2.929997205734253,3.309985771279336,1739141163.4164083,2.929997205734253,11.725257737317227,1739141163.4164116,2.929997205734253,-0.15003801551176094,1739141163.416416,2.929997205734253,-0.0055714241330050525,1739141163.4164197,2.929997205734253,0.2432729472290252,1739141163.4164238,2.929997205734253,0.029647851692463686,1739141163.4164276,2.929997205734253,2.268188630865279,1739141163.4164317,2.929997205734253,0.0,1739141163.4164355,2.929997205734253,0.1099823238713905,1739141163.4164393,2.929997205734253,6.246963353325505,1739141163.416443,2.929997205734253,2.140379857784941 +1739141163.43599,2.9499971866607666,3.7871480860050877,1739141163.4360135,2.9499971866607666,-0.10581098221537655,1739141163.4360192,2.9499971866607666,3.309985771279336,1739141163.4360232,2.9499971866607666,11.725257737317227,1739141163.4360268,2.9499971866607666,-0.15003801551176094,1739141163.436032,2.9499971866607666,-0.0055714241330050525,1739141163.4360344,2.9499971866607666,0.2432729472290252,1739141163.4360363,2.9499971866607666,0.029647851692463686,1739141163.4360378,2.9499971866607666,2.268188630865279,1739141163.43604,2.9499971866607666,0.0,1739141163.436063,2.9499971866607666,0.1278087730803379,1739141163.4360666,2.9499971866607666,6.246963353325505,1739141163.436071,2.9499971866607666,2.140379857784941 +1739141163.455482,2.9699971675872803,3.7871480860050877,1739141163.4554853,2.9699971675872803,-0.10581098221537655,1739141163.4554884,2.9699971675872803,3.309985771279336,1739141163.4554918,2.9699971675872803,11.725257737317227,1739141163.4554932,2.9699971675872803,-0.15003801551176094,1739141163.4554949,2.9699971675872803,-0.0055714241330050525,1739141163.4554965,2.9699971675872803,0.2432729472290252,1739141163.4554977,2.9699971675872803,0.029647851692463686,1739141163.455499,2.9699971675872803,2.268188630865279,1739141163.455501,2.9699971675872803,0.0,1739141163.4555025,2.9699971675872803,0.1278087730803379,1739141163.455504,2.9699971675872803,6.246963353325505,1739141163.4555051,2.9699971675872803,2.140379857784941 +1739141163.4754982,2.989997148513794,3.7871480860050877,1739141163.4755027,2.989997148513794,-0.10581098221537655,1739141163.4755065,2.989997148513794,3.309985771279336,1739141163.4755096,2.989997148513794,11.725257737317227,1739141163.4755116,2.989997148513794,-0.15003801551176094,1739141163.4755137,2.989997148513794,-0.0055714241330050525,1739141163.4755151,2.989997148513794,0.2432729472290252,1739141163.4755166,2.989997148513794,0.029647851692463686,1739141163.475518,2.989997148513794,2.268188630865279,1739141163.4755197,2.989997148513794,0.0,1739141163.4755216,2.989997148513794,0.1278087730803379,1739141163.4755228,2.989997148513794,6.246963353325505,1739141163.475525,2.989997148513794,2.140379857784941 +1739141163.4958322,3.0099971294403076,3.7871480860050877,1739141163.495836,3.0099971294403076,-0.10581098221537655,1739141163.495839,3.0099971294403076,3.309985771279336,1739141163.4958425,3.0099971294403076,11.725257737317227,1739141163.4958441,3.0099971294403076,-0.15003801551176094,1739141163.495846,3.0099971294403076,-0.0055714241330050525,1739141163.4958477,3.0099971294403076,0.2432729472290252,1739141163.4958491,3.0099971294403076,0.029647851692463686,1739141163.4958506,3.0099971294403076,2.268188630865279,1739141163.495852,3.0099971294403076,0.0,1739141163.4958537,3.0099971294403076,0.1278087730803379,1739141163.4958549,3.0099971294403076,6.246963353325505,1739141163.495856,3.0099971294403076,2.140379857784941 +1739141163.5152998,3.0299971103668213,3.7871480860050877,1739141163.5153046,3.0299971103668213,-0.10581098221537655,1739141163.5153089,3.0299971103668213,3.309985771279336,1739141163.5153124,3.0299971103668213,11.725257737317227,1739141163.5153162,3.0299971103668213,-0.15003801551176094,1739141163.515321,3.0299971103668213,-0.0055714241330050525,1739141163.5153227,3.0299971103668213,0.2432729472290252,1739141163.515324,3.0299971103668213,0.029647851692463686,1739141163.5153265,3.0299971103668213,2.268188630865279,1739141163.515328,3.0299971103668213,0.0,1739141163.5153298,3.0299971103668213,0.1278087730803379,1739141163.5153313,3.0299971103668213,6.246963353325505,1739141163.5153327,3.0299971103668213,2.140379857784941 +1739141163.5353568,3.049997091293335,4.023100521273037,1739141163.5353603,3.049997091293335,-0.11440905028565229,1739141163.5353642,3.049997091293335,3.3307667817190563,1739141163.5353687,3.049997091293335,11.786957644045675,1739141163.5353703,3.049997091293335,-0.15058890753612209,1739141163.5353723,3.049997091293335,-0.004660002726552107,1739141163.535374,3.049997091293335,0.24844500869084965,1739141163.5353763,3.049997091293335,0.031652708645417305,1739141163.5353777,3.049997091293335,2.2635009970808855,1739141163.5353794,3.049997091293335,0.0,1739141163.5353813,3.049997091293335,0.09281877550611514,1739141163.535383,3.049997091293335,6.246519984521621,1739141163.5353851,3.049997091293335,2.1540203096446446 +1739141163.5545301,3.0699970722198486,4.023100521273037,1739141163.5545325,3.0699970722198486,-0.11440905028565229,1739141163.5545354,3.0699970722198486,3.3307667817190563,1739141163.554538,3.0699970722198486,11.786957644045675,1739141163.5545392,3.0699970722198486,-0.15058890753612209,1739141163.554541,3.0699970722198486,-0.004660002726552107,1739141163.5545423,3.0699970722198486,0.24844500869084965,1739141163.5545437,3.0699970722198486,0.031652708645417305,1739141163.5545452,3.0699970722198486,2.2635009970808855,1739141163.5545466,3.0699970722198486,0.0,1739141163.5545483,3.0699970722198486,0.10948068743624084,1739141163.5545492,3.0699970722198486,6.246519984521621,1739141163.5545504,3.0699970722198486,2.1540203096446446 +1739141163.5747328,3.0899970531463623,4.023100521273037,1739141163.5747354,3.0899970531463623,-0.11440905028565229,1739141163.5747385,3.0899970531463623,3.3307667817190563,1739141163.5747414,3.0899970531463623,11.786957644045675,1739141163.5747426,3.0899970531463623,-0.15058890753612209,1739141163.574744,3.0899970531463623,-0.004660002726552107,1739141163.5747454,3.0899970531463623,0.24844500869084965,1739141163.5747466,3.0899970531463623,0.031652708645417305,1739141163.5747478,3.0899970531463623,2.2635009970808855,1739141163.5747495,3.0899970531463623,0.0,1739141163.5747507,3.0899970531463623,0.10948068743624084,1739141163.574752,3.0899970531463623,6.246519984521621,1739141163.5747533,3.0899970531463623,2.1540203096446446 +1739141163.594755,3.109997034072876,4.023100521273037,1739141163.594758,3.109997034072876,-0.11440905028565229,1739141163.5947628,3.109997034072876,3.3307667817190563,1739141163.5947666,3.109997034072876,11.786957644045675,1739141163.594769,3.109997034072876,-0.15058890753612209,1739141163.5947711,3.109997034072876,-0.004660002726552107,1739141163.5947733,3.109997034072876,0.24844500869084965,1739141163.5947752,3.109997034072876,0.031652708645417305,1739141163.5947769,3.109997034072876,2.2635009970808855,1739141163.5947793,3.109997034072876,0.0,1739141163.594781,3.109997034072876,0.10948068743624084,1739141163.5947828,3.109997034072876,6.246519984521621,1739141163.5947845,3.109997034072876,2.1540203096446446 +1739141163.6164622,3.1299970149993896,4.023100521273037,1739141163.6164658,3.1299970149993896,-0.11440905028565229,1739141163.6164703,3.1299970149993896,3.3307667817190563,1739141163.6164742,3.1299970149993896,11.786957644045675,1739141163.616476,3.1299970149993896,-0.15058890753612209,1739141163.6164787,3.1299970149993896,-0.004660002726552107,1739141163.6164806,3.1299970149993896,0.24844500869084965,1739141163.6164825,3.1299970149993896,0.031652708645417305,1739141163.6164844,3.1299970149993896,2.2635009970808855,1739141163.6164865,3.1299970149993896,0.0,1739141163.6164887,3.1299970149993896,0.10948068743624084,1739141163.6164906,3.1299970149993896,6.246519984521621,1739141163.6164925,3.1299970149993896,2.1540203096446446 +1739141163.6357546,3.1499969959259033,4.2604709488189005,1739141163.6357582,3.1499969959259033,-0.12315403904035627,1739141163.6357625,3.1499969959259033,3.431947593659263,1739141163.6357665,3.1499969959259033,11.923612672763703,1739141163.6357687,3.1499969959259033,-0.151,1739141163.6357708,3.1499969959259033,-0.003633736579970205,1739141163.635773,3.1499969959259033,0.2555250608344097,1739141163.635775,3.1499969959259033,0.033416219043444675,1739141163.6357768,3.1499969959259033,2.257099783509852,1739141163.6357791,3.1499969959259033,0.0,1739141163.6357813,3.1499969959259033,0.07468450355968057,1739141163.6357832,3.1499969959259033,6.246200921802319,1739141163.635785,3.1499969959259033,2.1658456603031317 +1739141163.6577682,3.169996976852417,4.2604709488189005,1739141163.657773,3.169996976852417,-0.12315403904035627,1739141163.6577775,3.169996976852417,3.431947593659263,1739141163.657782,3.169996976852417,11.923612672763703,1739141163.657784,3.169996976852417,-0.151,1739141163.6577868,3.169996976852417,-0.003633736579970205,1739141163.657789,3.169996976852417,0.2555250608344097,1739141163.657791,3.169996976852417,0.033416219043444675,1739141163.657793,3.169996976852417,2.257099783509852,1739141163.6577954,3.169996976852417,0.0,1739141163.6577978,3.169996976852417,0.0912541232067201,1739141163.6577997,3.169996976852417,6.246200921802319,1739141163.6578016,3.169996976852417,2.1658456603031317 +1739141163.6758356,3.1899969577789307,4.2604709488189005,1739141163.6758397,3.1899969577789307,-0.12315403904035627,1739141163.6758444,3.1899969577789307,3.431947593659263,1739141163.6758485,3.1899969577789307,11.923612672763703,1739141163.6758504,3.1899969577789307,-0.151,1739141163.675853,3.1899969577789307,-0.003633736579970205,1739141163.6758552,3.1899969577789307,0.2555250608344097,1739141163.675857,3.1899969577789307,0.033416219043444675,1739141163.675859,3.1899969577789307,2.257099783509852,1739141163.6758614,3.1899969577789307,0.0,1739141163.6758633,3.1899969577789307,0.0912541232067201,1739141163.6758654,3.1899969577789307,6.246200921802319,1739141163.6758673,3.1899969577789307,2.1658456603031317 +1739141163.6961584,3.2099969387054443,4.2604709488189005,1739141163.696162,3.2099969387054443,-0.12315403904035627,1739141163.696166,3.2099969387054443,3.431947593659263,1739141163.69617,3.2099969387054443,11.923612672763703,1739141163.696172,3.2099969387054443,-0.151,1739141163.6961746,3.2099969387054443,-0.003633736579970205,1739141163.6961763,3.2099969387054443,0.2555250608344097,1739141163.6961784,3.2099969387054443,0.033416219043444675,1739141163.69618,3.2099969387054443,2.257099783509852,1739141163.6961825,3.2099969387054443,0.0,1739141163.6961849,3.2099969387054443,0.0912541232067201,1739141163.6961865,3.2099969387054443,6.246200921802319,1739141163.6961887,3.2099969387054443,2.1658456603031317 +1739141163.7152617,3.229996919631958,4.2604709488189005,1739141163.7152653,3.229996919631958,-0.12315403904035627,1739141163.7152696,3.229996919631958,3.431947593659263,1739141163.7152736,3.229996919631958,11.923612672763703,1739141163.7152758,3.229996919631958,-0.151,1739141163.7152784,3.229996919631958,-0.003633736579970205,1739141163.7152805,3.229996919631958,0.2555250608344097,1739141163.7152824,3.229996919631958,0.033416219043444675,1739141163.715284,3.229996919631958,2.257099783509852,1739141163.7152865,3.229996919631958,0.0,1739141163.7152889,3.229996919631958,0.0912541232067201,1739141163.7152905,3.229996919631958,6.246200921802319,1739141163.7152925,3.229996919631958,2.1658456603031317 +1739141163.738513,3.2499969005584717,4.2604709488189005,1739141163.7385275,3.2499969005584717,-0.12315403904035627,1739141163.7385569,3.2499969005584717,3.431947593659263,1739141163.738586,3.2499969005584717,11.923612672763703,1739141163.7385976,3.2499969005584717,-0.151,1739141163.7386174,3.2499969005584717,-0.003633736579970205,1739141163.7386336,3.2499969005584717,0.2555250608344097,1739141163.7386487,3.2499969005584717,0.033416219043444675,1739141163.7386649,3.2499969005584717,2.257099783509852,1739141163.738681,3.2499969005584717,0.0,1739141163.7386885,3.2499969005584717,0.0912541232067201,1739141163.7386932,3.2499969005584717,6.246200921802319,1739141163.7386978,3.2499969005584717,2.1658456603031317 +1739141163.758985,3.2699968814849854,4.499018729674752,1739141163.7589934,3.2699968814849854,-0.13201130605675981,1739141163.7590034,3.2699968814849854,3.69738828043487,1739141163.7590134,3.2699968814849854,12.218034499026805,1739141163.7590184,3.2699968814849854,-0.15241743215102316,1739141163.7590244,3.2699968814849854,-0.0026436114611861215,1739141163.7590292,3.2699968814849854,0.26720515487214447,1739141163.759034,3.2699968814849854,0.03443975726508477,1739141163.7590382,3.2699968814849854,2.2465791240157356,1739141163.7590442,3.2699968814849854,0.0,1739141163.759049,3.2699968814849854,0.05272213443976237,1739141163.7590535,3.2699968814849854,6.245918419546525,1739141163.7590582,3.2699968814849854,2.1755084143305545 +1739141163.779483,3.289996862411499,4.499018729674752,1739141163.779492,3.289996862411499,-0.13201130605675981,1739141163.779502,3.289996862411499,3.69738828043487,1739141163.7795117,3.289996862411499,12.218034499026805,1739141163.7795167,3.289996862411499,-0.15241743215102316,1739141163.7795227,3.289996862411499,-0.0026436114611861215,1739141163.7795272,3.289996862411499,0.26720515487214447,1739141163.779532,3.289996862411499,0.03443975726508477,1739141163.7795365,3.289996862411499,2.2465791240157356,1739141163.779542,3.289996862411499,0.0,1739141163.779547,3.289996862411499,0.07107070968518103,1739141163.7795515,3.289996862411499,6.245918419546525,1739141163.7795558,3.289996862411499,2.1755084143305545 +1739141163.79885,3.3099968433380127,4.499018729674752,1739141163.7988591,3.3099968433380127,-0.13201130605675981,1739141163.7988687,3.3099968433380127,3.69738828043487,1739141163.7988787,3.3099968433380127,12.218034499026805,1739141163.7988834,3.3099968433380127,-0.15241743215102316,1739141163.7988896,3.3099968433380127,-0.0026436114611861215,1739141163.7988946,3.3099968433380127,0.26720515487214447,1739141163.7988994,3.3099968433380127,0.03443975726508477,1739141163.7989037,3.3099968433380127,2.2465791240157356,1739141163.7989097,3.3099968433380127,0.0,1739141163.7989147,3.3099968433380127,0.07107070968518103,1739141163.798919,3.3099968433380127,6.245918419546525,1739141163.7989235,3.3099968433380127,2.1755084143305545 +1739141163.83205,3.339996814727783,4.499018729674752,1739141163.8320546,3.339996814727783,-0.13201130605675981,1739141163.8320591,3.339996814727783,3.69738828043487,1739141163.8320637,3.339996814727783,12.218034499026805,1739141163.8320658,3.339996814727783,-0.15241743215102316,1739141163.8320684,3.339996814727783,-0.0026436114611861215,1739141163.8320704,3.339996814727783,0.26720515487214447,1739141163.8320725,3.339996814727783,0.03443975726508477,1739141163.8320744,3.339996814727783,2.2465791240157356,1739141163.832077,3.339996814727783,0.0,1739141163.8320794,3.339996814727783,0.07107070968518103,1739141163.832081,3.339996814727783,6.245918419546525,1739141163.8320832,3.339996814727783,2.1755084143305545 +1739141163.8516695,3.359996795654297,4.499018729674752,1739141163.8516736,3.359996795654297,-0.13201130605675981,1739141163.8516774,3.359996795654297,3.69738828043487,1739141163.8516812,3.359996795654297,12.218034499026805,1739141163.8516831,3.359996795654297,-0.15241743215102316,1739141163.8516853,3.359996795654297,-0.0026436114611861215,1739141163.8516872,3.359996795654297,0.26720515487214447,1739141163.851689,3.359996795654297,0.03443975726508477,1739141163.8516908,3.359996795654297,2.2465791240157356,1739141163.851693,3.359996795654297,0.0,1739141163.851695,3.359996795654297,0.07107070968518103,1739141163.8516974,3.359996795654297,6.245918419546525,1739141163.851699,3.359996795654297,2.1755084143305545 +1739141163.8724334,3.3799967765808105,4.738535211435488,1739141163.8724372,3.3799967765808105,-0.14096653922276747,1739141163.8724415,3.3799967765808105,3.8818288463311466,1739141163.872445,3.3799967765808105,12.425296910818863,1739141163.8724473,3.3799967765808105,-0.153,1739141163.8724496,3.3799967765808105,-0.0015654772994959903,1739141163.8724513,3.3799967765808105,0.27603407920232315,1739141163.8724532,3.3799967765808105,0.03587693382287871,1739141163.872455,3.3799967765808105,2.238659166353502,1739141163.872457,3.3799967765808105,0.0,1739141163.8724592,3.3799967765808105,0.041425921313809864,1739141163.872461,3.3799967765808105,6.245701830510337,1739141163.8724625,3.3799967765808105,2.183116672096718 +1739141163.8916843,3.399996757507324,4.738535211435488,1739141163.8916872,3.399996757507324,-0.14096653922276747,1739141163.89169,3.399996757507324,3.8818288463311466,1739141163.8916926,3.399996757507324,12.425296910818863,1739141163.8916938,3.399996757507324,-0.153,1739141163.891696,3.399996757507324,-0.0015654772994959903,1739141163.8916974,3.399996757507324,0.27603407920232315,1739141163.8916986,3.399996757507324,0.03587693382287871,1739141163.8917,3.399996757507324,2.238659166353502,1739141163.8917017,3.399996757507324,0.0,1739141163.8917031,3.399996757507324,0.055542494256783925,1739141163.8917046,3.399996757507324,6.245701830510337,1739141163.8917058,3.399996757507324,2.183116672096718 +1739141163.9106395,3.419996738433838,4.738535211435488,1739141163.910642,3.419996738433838,-0.14096653922276747,1739141163.9106448,3.419996738433838,3.8818288463311466,1739141163.9106474,3.419996738433838,12.425296910818863,1739141163.9106486,3.419996738433838,-0.153,1739141163.9106503,3.419996738433838,-0.0015654772994959903,1739141163.9106517,3.419996738433838,0.27603407920232315,1739141163.910653,3.419996738433838,0.03587693382287871,1739141163.9106545,3.419996738433838,2.238659166353502,1739141163.910656,3.419996738433838,0.0,1739141163.9106576,3.419996738433838,0.055542494256783925,1739141163.9106588,3.419996738433838,6.245701830510337,1739141163.9106598,3.419996738433838,2.183116672096718 +1739141163.930918,3.4399967193603516,4.738535211435488,1739141163.9309206,3.4399967193603516,-0.14096653922276747,1739141163.9309237,3.4399967193603516,3.8818288463311466,1739141163.9309263,3.4399967193603516,12.425296910818863,1739141163.9309278,3.4399967193603516,-0.153,1739141163.9309294,3.4399967193603516,-0.0015654772994959903,1739141163.9309309,3.4399967193603516,0.27603407920232315,1739141163.9309323,3.4399967193603516,0.03587693382287871,1739141163.9309335,3.4399967193603516,2.238659166353502,1739141163.9309351,3.4399967193603516,0.0,1739141163.9309366,3.4399967193603516,0.055542494256783925,1739141163.9309378,3.4399967193603516,6.245701830510337,1739141163.9309394,3.4399967193603516,2.183116672096718 +1739141163.95119,3.4599967002868652,4.738535211435488,1739141163.9511924,3.4599967002868652,-0.14096653922276747,1739141163.9511955,3.4599967002868652,3.8818288463311466,1739141163.951198,3.4599967002868652,12.425296910818863,1739141163.9511995,3.4599967002868652,-0.153,1739141163.951201,3.4599967002868652,-0.0015654772994959903,1739141163.9512024,3.4599967002868652,0.27603407920232315,1739141163.9512036,3.4599967002868652,0.03587693382287871,1739141163.9512048,3.4599967002868652,2.238659166353502,1739141163.9512064,3.4599967002868652,0.0,1739141163.9512076,3.4599967002868652,0.055542494256783925,1739141163.951209,3.4599967002868652,6.245701830510337,1739141163.95121,3.4599967002868652,2.183116672096718 +1739141163.970989,3.479996681213379,4.9788200395938365,1739141163.9709914,3.479996681213379,-0.14999507591035144,1739141163.9709942,3.479996681213379,4.148318067393069,1739141163.9710152,3.479996681213379,12.710061651796522,1739141163.9710164,3.479996681213379,-0.1549194743405092,1739141163.9710183,3.479996681213379,-0.0006369478553662378,1739141163.9710197,3.479996681213379,0.28591218301848936,1739141163.9710207,3.479996681213379,0.03673444710366877,1739141163.9710221,3.479996681213379,2.229831135618113,1739141163.9710236,3.479996681213379,0.0,1739141163.971025,3.479996681213379,0.027054063854146056,1739141163.9710264,3.479996681213379,6.245558526442994,1739141163.9710276,3.479996681213379,2.189211145747843 +1739141163.9934,3.4999966621398926,4.9788200395938365,1739141163.9934063,3.4999966621398926,-0.14999507591035144,1739141163.9934123,3.4999966621398926,4.148318067393069,1739141163.993418,3.4999966621398926,12.710061651796522,1739141163.9934208,3.4999966621398926,-0.1549194743405092,1739141163.9934242,3.4999966621398926,-0.0006369478553662378,1739141163.993427,3.4999966621398926,0.28591218301848936,1739141163.9934297,3.4999966621398926,0.03673444710366877,1739141163.993432,3.4999966621398926,2.229831135618113,1739141163.9934351,3.4999966621398926,0.0,1739141163.9934382,3.4999966621398926,0.04061998987027016,1739141163.9934409,3.4999966621398926,6.245558526442994,1739141163.9934435,3.4999966621398926,2.189211145747843 +1739141164.011096,3.5199966430664062,4.9788200395938365,1739141164.0110998,3.5199966430664062,-0.14999507591035144,1739141164.011104,3.5199966430664062,4.148318067393069,1739141164.0111077,3.5199966430664062,12.710061651796522,1739141164.0111094,3.5199966430664062,-0.1549194743405092,1739141164.0111117,3.5199966430664062,-0.0006369478553662378,1739141164.0111134,3.5199966430664062,0.28591218301848936,1739141164.0111153,3.5199966430664062,0.03673444710366877,1739141164.011117,3.5199966430664062,2.229831135618113,1739141164.0111191,3.5199966430664062,0.0,1739141164.011121,3.5199966430664062,0.04061998987027016,1739141164.011123,3.5199966430664062,6.245558526442994,1739141164.0111244,3.5199966430664062,2.189211145747843 +1739141164.0334644,3.53999662399292,4.9788200395938365,1739141164.0334704,3.53999662399292,-0.14999507591035144,1739141164.0334783,3.53999662399292,4.148318067393069,1739141164.0334852,3.53999662399292,12.710061651796522,1739141164.0334897,3.53999662399292,-0.1549194743405092,1739141164.033495,3.53999662399292,-0.0006369478553662378,1739141164.0335,3.53999662399292,0.28591218301848936,1739141164.0335047,3.53999662399292,0.03673444710366877,1739141164.033509,3.53999662399292,2.229831135618113,1739141164.0335143,3.53999662399292,0.0,1739141164.0335193,3.53999662399292,0.04061998987027016,1739141164.033525,3.53999662399292,6.245558526442994,1739141164.0335298,3.53999662399292,2.189211145747843 +1739141164.0529351,3.5599966049194336,4.9788200395938365,1739141164.0529401,3.5599966049194336,-0.14999507591035144,1739141164.0529463,3.5599966049194336,4.148318067393069,1739141164.0529528,3.5599966049194336,12.710061651796522,1739141164.052956,3.5599966049194336,-0.1549194743405092,1739141164.0529609,3.5599966049194336,-0.0006369478553662378,1739141164.052965,3.5599966049194336,0.28591218301848936,1739141164.052969,3.5599966049194336,0.03673444710366877,1739141164.0529728,3.5599966049194336,2.229831135618113,1739141164.0529768,3.5599966049194336,0.0,1739141164.0529811,3.5599966049194336,0.04061998987027016,1739141164.0529854,3.5599966049194336,6.245558526442994,1739141164.0529895,3.5599966049194336,2.189211145747843 +1739141164.0723338,3.5799965858459473,4.9788200395938365,1739141164.072338,3.5799965858459473,-0.14999507591035144,1739141164.072343,3.5799965858459473,4.148318067393069,1739141164.072348,3.5799965858459473,12.710061651796522,1739141164.072369,3.5799965858459473,-0.1549194743405092,1739141164.0723732,3.5799965858459473,-0.0006369478553662378,1739141164.0723772,3.5799965858459473,0.28591218301848936,1739141164.0724018,3.5799965858459473,0.03673444710366877,1739141164.072405,3.5799965858459473,2.229831135618113,1739141164.0724087,3.5799965858459473,0.0,1739141164.0724125,3.5799965858459473,0.04061998987027016,1739141164.0724158,3.5799965858459473,6.245558526442994,1739141164.0724194,3.5799965858459473,2.189211145747843 +1739141164.0943499,3.599996566772461,5.219659286960111,1739141164.0943575,3.599996566772461,-0.15907466466378128,1739141164.0943666,3.599996566772461,4.496739220235799,1739141164.094376,3.599996566772461,13.071012293509218,1739141164.0943813,3.599996566772461,-0.15618029093251548,1739141164.0943887,3.599996566772461,0.00036864647376524175,1739141164.0943954,3.599996566772461,0.29919555688115396,1739141164.0944016,3.599996566772461,0.03727390929812194,1739141164.094408,3.599996566772461,2.2180146836378274,1739141164.094414,3.599996566772461,0.0,1739141164.0944202,3.599996566772461,0.010084369789715069,1739141164.0944266,3.599996566772461,6.245437211470667,1739141164.094434,3.599996566772461,2.193389535117427 +1739141164.1204674,3.6199965476989746,5.219659286960111,1739141164.120488,3.6199965476989746,-0.15907466466378128,1739141164.1205065,3.6199965476989746,4.496739220235799,1739141164.1205258,3.6199965476989746,13.071012293509218,1739141164.1205356,3.6199965476989746,-0.15618029093251548,1739141164.1205475,3.6199965476989746,0.00036864647376524175,1739141164.120558,3.6199965476989746,0.29919555688115396,1739141164.1205697,3.6199965476989746,0.03727390929812194,1739141164.1205812,3.6199965476989746,2.2180146836378274,1739141164.1205933,3.6199965476989746,0.0,1739141164.120605,3.6199965476989746,0.02462514852040032,1739141164.1206152,3.6199965476989746,6.245437211470667,1739141164.1206253,3.6199965476989746,2.193389535117427 +1739141164.1387858,3.6399965286254883,5.219659286960111,1739141164.1387959,3.6399965286254883,-0.15907466466378128,1739141164.1388068,3.6399965286254883,4.496739220235799,1739141164.138817,3.6399965286254883,13.071012293509218,1739141164.138822,3.6399965286254883,-0.15618029093251548,1739141164.1388285,3.6399965286254883,0.00036864647376524175,1739141164.1388335,3.6399965286254883,0.29919555688115396,1739141164.138838,3.6399965286254883,0.03727390929812194,1739141164.1388423,3.6399965286254883,2.2180146836378274,1739141164.1388488,3.6399965286254883,0.0,1739141164.1388538,3.6399965286254883,0.02462514852040032,1739141164.1388593,3.6399965286254883,6.245437211470667,1739141164.138864,3.6399965286254883,2.193389535117427 +1739141164.156579,3.659996509552002,5.219659286960111,1739141164.1565886,3.659996509552002,-0.15907466466378128,1739141164.1565993,3.659996509552002,4.496739220235799,1739141164.1566095,3.659996509552002,13.071012293509218,1739141164.1566145,3.659996509552002,-0.15618029093251548,1739141164.1566212,3.659996509552002,0.00036864647376524175,1739141164.1566267,3.659996509552002,0.29919555688115396,1739141164.1566315,3.659996509552002,0.03727390929812194,1739141164.1566362,3.659996509552002,2.2180146836378274,1739141164.156642,3.659996509552002,0.0,1739141164.1566472,3.659996509552002,0.02462514852040032,1739141164.1566517,3.659996509552002,6.245437211470667,1739141164.156656,3.659996509552002,2.193389535117427 +1739141164.1818275,3.6899964809417725,5.219659286960111,1739141164.181833,3.6899964809417725,-0.15907466466378128,1739141164.1818385,3.6899964809417725,4.496739220235799,1739141164.1818438,3.6899964809417725,13.071012293509218,1739141164.1818469,3.6899964809417725,-0.15618029093251548,1739141164.18185,3.6899964809417725,0.00036864647376524175,1739141164.1818526,3.6899964809417725,0.29919555688115396,1739141164.1818552,3.6899964809417725,0.03727390929812194,1739141164.1818576,3.6899964809417725,2.2180146836378274,1739141164.1818607,3.6899964809417725,0.0,1739141164.1818633,3.6899964809417725,0.02462514852040032,1739141164.181866,3.6899964809417725,6.245437211470667,1739141164.1818683,3.6899964809417725,2.193389535117427 +1739141164.1998055,3.709996461868286,5.460885848060867,1739141164.1998096,3.709996461868286,-0.16819235810623478,1739141164.1998138,3.709996461868286,5.062636096366671,1739141164.1998181,3.709996461868286,13.644584984397932,1739141164.1998205,3.709996461868286,-0.159,1739141164.1998231,3.709996461868286,0.001123251733367905,1739141164.199825,3.709996461868286,0.3184836815579314,1739141164.1998272,3.709996461868286,0.036519691023274,1739141164.1998293,3.709996461868286,2.200967990444117,1739141164.1998315,3.709996461868286,0.0,1739141164.1998339,3.709996461868286,-0.012809938365071868,1739141164.1998365,3.709996461868286,6.245381916855035,1739141164.1998384,3.709996461868286,2.195951688053978 +1739141164.219429,3.7299964427948,5.460885848060867,1739141164.2194338,3.7299964427948,-0.16819235810623478,1739141164.219438,3.7299964427948,5.062636096366671,1739141164.2194426,3.7299964427948,13.644584984397932,1739141164.219445,3.7299964427948,-0.159,1739141164.2194476,3.7299964427948,0.001123251733367905,1739141164.2194498,3.7299964427948,0.3184836815579314,1739141164.219452,3.7299964427948,0.036519691023274,1739141164.2194543,3.7299964427948,2.200967990444117,1739141164.2194564,3.7299964427948,0.0,1739141164.2194588,3.7299964427948,0.00501630239013906,1739141164.219461,3.7299964427948,6.245381916855035,1739141164.2194629,3.7299964427948,2.195951688053978 +1739141164.239076,3.7499964237213135,5.460885848060867,1739141164.2390795,3.7499964237213135,-0.16819235810623478,1739141164.2390826,3.7499964237213135,5.062636096366671,1739141164.2390852,3.7499964237213135,13.644584984397932,1739141164.239087,3.7499964237213135,-0.159,1739141164.2390885,3.7499964237213135,0.001123251733367905,1739141164.2390902,3.7499964237213135,0.3184836815579314,1739141164.2390914,3.7499964237213135,0.036519691023274,1739141164.239093,3.7499964237213135,2.200967990444117,1739141164.2390947,3.7499964237213135,0.0,1739141164.2390964,3.7499964237213135,0.00501630239013906,1739141164.2390976,3.7499964237213135,6.245381916855035,1739141164.239099,3.7499964237213135,2.195951688053978 +1739141164.2589176,3.769996404647827,5.460885848060867,1739141164.2589226,3.769996404647827,-0.16819235810623478,1739141164.2589257,3.769996404647827,5.062636096366671,1739141164.2589283,3.769996404647827,13.644584984397932,1739141164.2589297,3.769996404647827,-0.159,1739141164.2589314,3.769996404647827,0.001123251733367905,1739141164.2589328,3.769996404647827,0.3184836815579314,1739141164.258934,3.769996404647827,0.036519691023274,1739141164.2589352,3.769996404647827,2.200967990444117,1739141164.258937,3.769996404647827,0.0,1739141164.2589386,3.769996404647827,0.00501630239013906,1739141164.25894,3.769996404647827,6.245381916855035,1739141164.2589412,3.769996404647827,2.195951688053978 +1739141164.2781494,3.789996385574341,5.460885848060867,1739141164.278152,3.789996385574341,-0.16819235810623478,1739141164.2781546,3.789996385574341,5.062636096366671,1739141164.278157,3.789996385574341,13.644584984397932,1739141164.2781584,3.789996385574341,-0.159,1739141164.2781599,3.789996385574341,0.001123251733367905,1739141164.278161,3.789996385574341,0.3184836815579314,1739141164.2781622,3.789996385574341,0.036519691023274,1739141164.2781634,3.789996385574341,2.200967990444117,1739141164.278165,3.789996385574341,0.0,1739141164.2781665,3.789996385574341,0.00501630239013906,1739141164.2781675,3.789996385574341,6.245381916855035,1739141164.278169,3.789996385574341,2.195951688053978 +1739141164.2983284,3.8099963665008545,5.702284372352429,1739141164.298331,3.8099963665008545,-0.17732685434074025,1739141164.2983336,3.8099963665008545,5.071818374785984,1739141164.2983363,3.8099963665008545,13.654929438894724,1739141164.2983375,3.8099963665008545,-0.159,1739141164.2983391,3.8099963665008545,0.002304493881547908,1739141164.2983403,3.8099963665008545,0.3192019090985791,1739141164.2983413,3.8099963665008545,0.03875939849230816,1739141164.2983427,3.8099963665008545,2.2003357629343787,1739141164.2983441,3.8099963665008545,0.0,1739141164.2983456,3.8099963665008545,0.003069755120074188,1739141164.2983465,3.8099963665008545,6.245341293429779,1739141164.2983475,3.8099963665008545,2.196339080079804 +1739141164.3182273,3.829996347427368,5.702284372352429,1739141164.3182297,3.829996347427368,-0.17732685434074025,1739141164.3182323,3.829996347427368,5.071818374785984,1739141164.3182347,3.829996347427368,13.654929438894724,1739141164.3182359,3.829996347427368,-0.159,1739141164.3182375,3.829996347427368,0.002304493881547908,1739141164.3182387,3.829996347427368,0.3192019090985791,1739141164.31824,3.829996347427368,0.03875939849230816,1739141164.3182411,3.829996347427368,2.2003357629343787,1739141164.3182428,3.829996347427368,0.0,1739141164.3182445,3.829996347427368,0.003996682854574551,1739141164.3182454,3.829996347427368,6.245341293429779,1739141164.3182466,3.829996347427368,2.196339080079804 +1739141164.3381991,3.849996328353882,5.702284372352429,1739141164.3382013,3.849996328353882,-0.17732685434074025,1739141164.3382041,3.849996328353882,5.071818374785984,1739141164.3382065,3.849996328353882,13.654929438894724,1739141164.3382077,3.849996328353882,-0.159,1739141164.3382094,3.849996328353882,0.002304493881547908,1739141164.3382106,3.849996328353882,0.3192019090985791,1739141164.3382118,3.849996328353882,0.03875939849230816,1739141164.3382132,3.849996328353882,2.2003357629343787,1739141164.3382146,3.849996328353882,0.0,1739141164.3382158,3.849996328353882,0.003996682854574551,1739141164.3382173,3.849996328353882,6.245341293429779,1739141164.3382182,3.849996328353882,2.196339080079804 +1739141164.358067,3.8699963092803955,5.702284372352429,1739141164.3580692,3.8699963092803955,-0.17732685434074025,1739141164.3580716,3.8699963092803955,5.071818374785984,1739141164.3580742,3.8699963092803955,13.654929438894724,1739141164.3580754,3.8699963092803955,-0.159,1739141164.3580773,3.8699963092803955,0.002304493881547908,1739141164.3580785,3.8699963092803955,0.3192019090985791,1739141164.3580794,3.8699963092803955,0.03875939849230816,1739141164.3580809,3.8699963092803955,2.2003357629343787,1739141164.3580823,3.8699963092803955,0.0,1739141164.3580837,3.8699963092803955,0.003996682854574551,1739141164.3580852,3.8699963092803955,6.245341293429779,1739141164.3580863,3.8699963092803955,2.196339080079804 +1739141164.377985,3.889996290206909,5.702284372352429,1739141164.3779874,3.889996290206909,-0.17732685434074025,1739141164.3779898,3.889996290206909,5.071818374785984,1739141164.3779924,3.889996290206909,13.654929438894724,1739141164.3779938,3.889996290206909,-0.159,1739141164.3779953,3.889996290206909,0.002304493881547908,1739141164.3779964,3.889996290206909,0.3192019090985791,1739141164.3779979,3.889996290206909,0.03875939849230816,1739141164.3779988,3.889996290206909,2.2003357629343787,1739141164.3780005,3.889996290206909,0.0,1739141164.3780017,3.889996290206909,0.003996682854574551,1739141164.3780026,3.889996290206909,6.245341293429779,1739141164.378004,3.889996290206909,2.196339080079804 +1739141164.3980901,3.909996271133423,5.702284372352429,1739141164.3980927,3.909996271133423,-0.17732685434074025,1739141164.3980956,3.909996271133423,5.071818374785984,1739141164.3980985,3.909996271133423,13.654929438894724,1739141164.3980997,3.909996271133423,-0.159,1739141164.3981016,3.909996271133423,0.002304493881547908,1739141164.3981032,3.909996271133423,0.3192019090985791,1739141164.3981047,3.909996271133423,0.03875939849230816,1739141164.3981059,3.909996271133423,2.2003357629343787,1739141164.3981073,3.909996271133423,0.0,1739141164.398109,3.909996271133423,0.003996682854574551,1739141164.3981102,3.909996271133423,6.245341293429779,1739141164.3981116,3.909996271133423,2.196339080079804 +1739141164.4185221,3.9299962520599365,5.943728670181191,1739141164.4185257,3.9299962520599365,-0.18647290505105651,1739141164.418529,3.9299962520599365,5.081002404154187,1739141164.4185321,3.9299962520599365,13.665371075453631,1739141164.4185336,3.9299962520599365,-0.159,1739141164.4185355,3.9299962520599365,0.0035578945107894422,1739141164.4185367,3.9299962520599365,0.3199148423713504,1739141164.4185383,3.9299962520599365,0.04120438450007429,1739141164.4185395,3.9299962520599365,2.1997083753650593,1739141164.4185417,3.9299962520599365,0.0,1739141164.4185436,3.9299962520599365,0.0019986465571474495,1739141164.418545,3.9299962520599365,6.245300670004524,1739141164.4185464,3.9299962520599365,2.196758282476705 +1739141164.4383235,3.94999623298645,5.943728670181191,1739141164.4383273,3.94999623298645,-0.18647290505105651,1739141164.438331,3.94999623298645,5.081002404154187,1739141164.4383337,3.94999623298645,13.665371075453631,1739141164.4383354,3.94999623298645,-0.159,1739141164.4383376,3.94999623298645,0.0035578945107894422,1739141164.438339,3.94999623298645,0.3199148423713504,1739141164.4383404,3.94999623298645,0.04120438450007429,1739141164.4383416,3.94999623298645,2.1997083753650593,1739141164.4383433,3.94999623298645,0.0,1739141164.4383447,3.94999623298645,0.0029500928883541278,1739141164.4383464,3.94999623298645,6.245300670004524,1739141164.4383478,3.94999623298645,2.196758282476705 +1739141164.4585485,3.969996213912964,5.943728670181191,1739141164.4585521,3.969996213912964,-0.18647290505105651,1739141164.4585567,3.969996213912964,5.081002404154187,1739141164.4585621,3.969996213912964,13.665371075453631,1739141164.4585652,3.969996213912964,-0.159,1739141164.458569,3.969996213912964,0.0035578945107894422,1739141164.4585724,3.969996213912964,0.3199148423713504,1739141164.458576,3.969996213912964,0.04120438450007429,1739141164.4585793,3.969996213912964,2.1997083753650593,1739141164.458583,3.969996213912964,0.0,1739141164.4585867,3.969996213912964,0.0029500928883541278,1739141164.4585903,3.969996213912964,6.245300670004524,1739141164.4585936,3.969996213912964,2.196758282476705 +1739141164.478792,3.9899961948394775,5.943728670181191,1739141164.4787946,3.9899961948394775,-0.18647290505105651,1739141164.4787977,3.9899961948394775,5.081002404154187,1739141164.4788003,3.9899961948394775,13.665371075453631,1739141164.4788017,3.9899961948394775,-0.159,1739141164.4788034,3.9899961948394775,0.0035578945107894422,1739141164.4788048,3.9899961948394775,0.3199148423713504,1739141164.478806,3.9899961948394775,0.04120438450007429,1739141164.4788072,3.9899961948394775,2.1997083753650593,1739141164.4788089,3.9899961948394775,0.0,1739141164.4788103,3.9899961948394775,0.0029500928883541278,1739141164.4788117,3.9899961948394775,6.245300670004524,1739141164.478813,3.9899961948394775,2.196758282476705 +1739141164.4986043,4.009996175765991,5.943728670181191,1739141164.498607,4.009996175765991,-0.18647290505105651,1739141164.4986098,4.009996175765991,5.081002404154187,1739141164.4986122,4.009996175765991,13.665371075453631,1739141164.4986136,4.009996175765991,-0.159,1739141164.498615,4.009996175765991,0.0035578945107894422,1739141164.4986165,4.009996175765991,0.3199148423713504,1739141164.498618,4.009996175765991,0.04120438450007429,1739141164.4986188,4.009996175765991,2.1997083753650593,1739141164.4986205,4.009996175765991,0.0,1739141164.498622,4.009996175765991,0.0029500928883541278,1739141164.4986231,4.009996175765991,6.245300670004524,1739141164.4986246,4.009996175765991,2.196758282476705 +1739141164.5190437,4.029996156692505,6.1852144754505485,1739141164.5190465,4.029996156692505,-0.19562000666237633,1739141164.51905,4.029996156692505,5.5157103176902424,1739141164.5190532,4.029996156692505,14.101013160055942,1739141164.5190551,4.029996156692505,-0.161,1739141164.519057,4.029996156692505,0.004373505101574886,1739141164.5190587,4.029996156692505,0.3337433441416869,1739141164.5190609,4.029996156692505,0.040902432209820885,1739141164.5190623,4.029996156692505,2.1875744965106483,1739141164.5190644,4.029996156692505,0.0,1739141164.5190659,4.029996156692505,-0.02081422346717684,1739141164.5190673,4.029996156692505,6.245385038116879,1739141164.5190692,4.029996156692505,2.197072373203134 +1739141164.5389464,4.0499961376190186,6.1852144754505485,1739141164.53895,4.0499961376190186,-0.19562000666237633,1739141164.5389538,4.0499961376190186,5.5157103176902424,1739141164.5389576,4.0499961376190186,14.101013160055942,1739141164.5389593,4.0499961376190186,-0.161,1739141164.538962,4.0499961376190186,0.004373505101574886,1739141164.538964,4.0499961376190186,0.3337433441416869,1739141164.5389655,4.0499961376190186,0.040902432209820885,1739141164.5389674,4.0499961376190186,2.1875744965106483,1739141164.5389698,4.0499961376190186,0.0,1739141164.538972,4.0499961376190186,-0.009497876692485807,1739141164.5389733,4.0499961376190186,6.245385038116879,1739141164.5389757,4.0499961376190186,2.197072373203134 +1739141164.558947,4.069996118545532,6.1852144754505485,1739141164.5589507,4.069996118545532,-0.19562000666237633,1739141164.5589545,4.069996118545532,5.5157103176902424,1739141164.5589583,4.069996118545532,14.101013160055942,1739141164.5589602,4.069996118545532,-0.161,1739141164.5589623,4.069996118545532,0.004373505101574886,1739141164.5589645,4.069996118545532,0.3337433441416869,1739141164.558966,4.069996118545532,0.040902432209820885,1739141164.5589678,4.069996118545532,2.1875744965106483,1739141164.5589702,4.069996118545532,0.0,1739141164.5589721,4.069996118545532,-0.009497876692485807,1739141164.558974,4.069996118545532,6.245385038116879,1739141164.5589755,4.069996118545532,2.197072373203134 +1739141164.5795143,4.089996099472046,6.1852144754505485,1739141164.5795176,4.089996099472046,-0.19562000666237633,1739141164.579522,4.089996099472046,5.5157103176902424,1739141164.5795255,4.089996099472046,14.101013160055942,1739141164.5795271,4.089996099472046,-0.161,1739141164.5795295,4.089996099472046,0.004373505101574886,1739141164.5795312,4.089996099472046,0.3337433441416869,1739141164.579533,4.089996099472046,0.040902432209820885,1739141164.5795345,4.089996099472046,2.1875744965106483,1739141164.579537,4.089996099472046,0.0,1739141164.5795386,4.089996099472046,-0.009497876692485807,1739141164.5795405,4.089996099472046,6.245385038116879,1739141164.579542,4.089996099472046,2.197072373203134 +1739141164.5996141,4.10999608039856,6.1852144754505485,1739141164.5996175,4.10999608039856,-0.19562000666237633,1739141164.5996215,4.10999608039856,5.5157103176902424,1739141164.5996256,4.10999608039856,14.101013160055942,1739141164.5996273,4.10999608039856,-0.161,1739141164.5996296,4.10999608039856,0.004373505101574886,1739141164.5996313,4.10999608039856,0.3337433441416869,1739141164.5996332,4.10999608039856,0.040902432209820885,1739141164.599635,4.10999608039856,2.1875744965106483,1739141164.599637,4.10999608039856,0.0,1739141164.5996392,4.10999608039856,-0.009497876692485807,1739141164.599641,4.10999608039856,6.245385038116879,1739141164.599643,4.10999608039856,2.197072373203134 +1739141164.6197236,4.129996061325073,6.1852144754505485,1739141164.6197276,4.129996061325073,-0.19562000666237633,1739141164.6197321,4.129996061325073,5.5157103176902424,1739141164.6197367,4.129996061325073,14.101013160055942,1739141164.6197388,4.129996061325073,-0.161,1739141164.6197414,4.129996061325073,0.004373505101574886,1739141164.6197438,4.129996061325073,0.3337433441416869,1739141164.6197455,4.129996061325073,0.040902432209820885,1739141164.6197476,4.129996061325073,2.1875744965106483,1739141164.6197498,4.129996061325073,0.0,1739141164.619752,4.129996061325073,-0.009497876692485807,1739141164.619754,4.129996061325073,6.245385038116879,1739141164.6197557,4.129996061325073,2.197072373203134 +1739141164.6392865,4.149996042251587,6.426646843154478,1739141164.6392906,4.149996042251587,-0.20473725354989725,1739141164.6392953,4.149996042251587,5.5386646271158915,1739141164.6392996,4.149996042251587,14.120174903427424,1739141164.6393018,4.149996042251587,-0.161,1739141164.6393046,4.149996042251587,0.005684879816054071,1739141164.6393068,4.149996042251587,0.3335231332346007,1739141164.6393087,4.149996042251587,0.04327050306615881,1739141164.6393108,4.149996042251587,2.187767196103112,1739141164.6393132,4.149996042251587,0.0,1739141164.6393154,4.149996042251587,-0.006716543263858434,1739141164.6393178,4.149996042251587,6.245506168462956,1739141164.63932,4.149996042251587,2.195808184518411 +1739141164.6585581,4.169996023178101,6.426646843154478,1739141164.6585615,4.169996023178101,-0.20473725354989725,1739141164.658565,4.169996023178101,5.5386646271158915,1739141164.6585684,4.169996023178101,14.120174903427424,1739141164.65857,4.169996023178101,-0.161,1739141164.6585717,4.169996023178101,0.005684879816054071,1739141164.6585736,4.169996023178101,0.3335231332346007,1739141164.658575,4.169996023178101,0.04327050306615881,1739141164.6585767,4.169996023178101,2.187767196103112,1739141164.6585784,4.169996023178101,0.0,1739141164.6585803,4.169996023178101,-0.00804098841529921,1739141164.658582,4.169996023178101,6.245506168462956,1739141164.6585836,4.169996023178101,2.195808184518411 +1739141164.6789389,4.189996004104614,6.426646843154478,1739141164.6789453,4.189996004104614,-0.20473725354989725,1739141164.6789486,4.189996004104614,5.5386646271158915,1739141164.6789527,4.189996004104614,14.120174903427424,1739141164.6789548,4.189996004104614,-0.161,1739141164.6789572,4.189996004104614,0.005684879816054071,1739141164.6789594,4.189996004104614,0.3335231332346007,1739141164.6789608,4.189996004104614,0.04327050306615881,1739141164.6789625,4.189996004104614,2.187767196103112,1739141164.6789641,4.189996004104614,0.0,1739141164.6789665,4.189996004104614,-0.00804098841529921,1739141164.6789687,4.189996004104614,6.245506168462956,1739141164.67897,4.189996004104614,2.195808184518411 +1739141164.698294,4.209995985031128,6.426646843154478,1739141164.6982965,4.209995985031128,-0.20473725354989725,1739141164.6982994,4.209995985031128,5.5386646271158915,1739141164.698302,4.209995985031128,14.120174903427424,1739141164.6983032,4.209995985031128,-0.161,1739141164.6983047,4.209995985031128,0.005684879816054071,1739141164.6983063,4.209995985031128,0.3335231332346007,1739141164.6983078,4.209995985031128,0.04327050306615881,1739141164.6983092,4.209995985031128,2.187767196103112,1739141164.6983106,4.209995985031128,0.0,1739141164.6983123,4.209995985031128,-0.00804098841529921,1739141164.6983132,4.209995985031128,6.245506168462956,1739141164.6983144,4.209995985031128,2.195808184518411 +1739141164.718805,4.229995965957642,6.426646843154478,1739141164.7188082,4.229995965957642,-0.20473725354989725,1739141164.718811,4.229995965957642,5.5386646271158915,1739141164.718814,4.229995965957642,14.120174903427424,1739141164.7188156,4.229995965957642,-0.161,1739141164.7188172,4.229995965957642,0.005684879816054071,1739141164.7188187,4.229995965957642,0.3335231332346007,1739141164.7188199,4.229995965957642,0.04327050306615881,1739141164.718821,4.229995965957642,2.187767196103112,1739141164.7188227,4.229995965957642,0.0,1739141164.7188241,4.229995965957642,-0.00804098841529921,1739141164.7188256,4.229995965957642,6.245506168462956,1739141164.7188268,4.229995965957642,2.195808184518411 +1739141164.7396283,4.249995946884155,6.667971864801656,1739141164.7396314,4.249995946884155,-0.21381535133528828,1739141164.7396343,4.249995946884155,5.969182634415689,1739141164.739637,4.249995946884155,14.548086489038466,1739141164.7396386,4.249995946884155,-0.162,1739141164.7396402,4.249995946884155,0.006575361787452888,1739141164.7396426,4.249995946884155,0.3471490614527565,1739141164.739644,4.249995946884155,0.04293028016293557,1739141164.7396455,4.249995946884155,2.1758754891417946,1739141164.7396472,4.249995946884155,0.0,1739141164.7396486,4.249995946884155,-0.029087506657736677,1739141164.73965,4.249995946884155,6.245693551681558,1739141164.7396514,4.249995946884155,2.1949408392490084 +1739141164.758791,4.269995927810669,6.667971864801656,1739141164.7587938,4.269995927810669,-0.21381535133528828,1739141164.7587972,4.269995927810669,5.969182634415689,1739141164.7587996,4.269995927810669,14.548086489038466,1739141164.7588012,4.269995927810669,-0.162,1739141164.7588027,4.269995927810669,0.006575361787452888,1739141164.7588046,4.269995927810669,0.3471490614527565,1739141164.7588058,4.269995927810669,0.04293028016293557,1739141164.758807,4.269995927810669,2.1758754891417946,1739141164.7588089,4.269995927810669,0.0,1739141164.7588103,4.269995927810669,-0.019065350107213774,1739141164.7588117,4.269995927810669,6.245693551681558,1739141164.758813,4.269995927810669,2.1949408392490084 +1739141164.7783692,4.289995908737183,6.667971864801656,1739141164.778372,4.289995908737183,-0.21381535133528828,1739141164.7783747,4.289995908737183,5.969182634415689,1739141164.7783775,4.289995908737183,14.548086489038466,1739141164.778379,4.289995908737183,-0.162,1739141164.7783806,4.289995908737183,0.006575361787452888,1739141164.778382,4.289995908737183,0.3471490614527565,1739141164.7783833,4.289995908737183,0.04293028016293557,1739141164.7783847,4.289995908737183,2.1758754891417946,1739141164.7783864,4.289995908737183,0.0,1739141164.7783878,4.289995908737183,-0.019065350107213774,1739141164.778389,4.289995908737183,6.245693551681558,1739141164.7783902,4.289995908737183,2.1949408392490084 +1739141164.7987812,4.309995889663696,6.667971864801656,1739141164.798784,4.309995889663696,-0.21381535133528828,1739141164.7987869,4.309995889663696,5.969182634415689,1739141164.79879,4.309995889663696,14.548086489038466,1739141164.7987912,4.309995889663696,-0.162,1739141164.798793,4.309995889663696,0.006575361787452888,1739141164.7987943,4.309995889663696,0.3471490614527565,1739141164.7987955,4.309995889663696,0.04293028016293557,1739141164.798797,4.309995889663696,2.1758754891417946,1739141164.7987983,4.309995889663696,0.0,1739141164.7987998,4.309995889663696,-0.019065350107213774,1739141164.7988014,4.309995889663696,6.245693551681558,1739141164.7988026,4.309995889663696,2.1949408392490084 +1739141164.8185005,4.32999587059021,6.667971864801656,1739141164.8185036,4.32999587059021,-0.21381535133528828,1739141164.818507,4.32999587059021,5.969182634415689,1739141164.8185098,4.32999587059021,14.548086489038466,1739141164.818511,4.32999587059021,-0.162,1739141164.818513,4.32999587059021,0.006575361787452888,1739141164.818514,4.32999587059021,0.3471490614527565,1739141164.8185155,4.32999587059021,0.04293028016293557,1739141164.8185167,4.32999587059021,2.1758754891417946,1739141164.8185182,4.32999587059021,0.0,1739141164.8185198,4.32999587059021,-0.019065350107213774,1739141164.8185208,4.32999587059021,6.245693551681558,1739141164.8185225,4.32999587059021,2.1949408392490084 +1739141164.8388112,4.349995851516724,6.667971864801656,1739141164.8388138,4.349995851516724,-0.21381535133528828,1739141164.8388164,4.349995851516724,5.969182634415689,1739141164.838819,4.349995851516724,14.548086489038466,1739141164.8388205,4.349995851516724,-0.162,1739141164.8388224,4.349995851516724,0.006575361787452888,1739141164.8388243,4.349995851516724,0.3471490614527565,1739141164.8388255,4.349995851516724,0.04293028016293557,1739141164.8388267,4.349995851516724,2.1758754891417946,1739141164.8388283,4.349995851516724,0.0,1739141164.8388295,4.349995851516724,-0.019065350107213774,1739141164.8388312,4.349995851516724,6.245693551681558,1739141164.8388324,4.349995851516724,2.1949408392490084 +1739141164.8591096,4.369995832443237,6.909123072188249,1739141164.8591123,4.369995832443237,-0.22283859132289674,1739141164.8591151,4.369995832443237,5.983178427684099,1739141164.8591177,4.369995832443237,14.555224180013434,1739141164.8591197,4.369995832443237,-0.162,1739141164.8591213,4.369995832443237,0.007956644386359454,1739141164.8591228,4.369995832443237,0.34585065446050095,1739141164.8591242,4.369995832443237,0.045426477306428466,1739141164.8591256,4.369995832443237,2.1770058514301978,1739141164.859127,4.369995832443237,0.0,1739141164.8591287,4.369995832443237,-0.01254313586249663,1739141164.8591301,4.369995832443237,6.245895657760722,1739141164.8591313,4.369995832443237,2.1926548051511943 +1739141164.8793185,4.389995813369751,6.909123072188249,1739141164.8793209,4.389995813369751,-0.22283859132289674,1739141164.879324,4.389995813369751,5.983178427684099,1739141164.8793268,4.389995813369751,14.555224180013434,1739141164.8793283,4.389995813369751,-0.162,1739141164.8793297,4.389995813369751,0.007956644386359454,1739141164.879331,4.389995813369751,0.34585065446050095,1739141164.8793323,4.389995813369751,0.045426477306428466,1739141164.8793337,4.389995813369751,2.1770058514301978,1739141164.8793352,4.389995813369751,0.0,1739141164.8793364,4.389995813369751,-0.015648953720996506,1739141164.879338,4.389995813369751,6.245895657760722,1739141164.8793392,4.389995813369751,2.1926548051511943 +1739141164.8990006,4.409995794296265,6.909123072188249,1739141164.899003,4.409995794296265,-0.22283859132289674,1739141164.899006,4.409995794296265,5.983178427684099,1739141164.8990085,4.409995794296265,14.555224180013434,1739141164.8990097,4.409995794296265,-0.162,1739141164.8990116,4.409995794296265,0.007956644386359454,1739141164.8990128,4.409995794296265,0.34585065446050095,1739141164.8990147,4.409995794296265,0.045426477306428466,1739141164.8990157,4.409995794296265,2.1770058514301978,1739141164.8990176,4.409995794296265,0.0,1739141164.8990188,4.409995794296265,-0.015648953720996506,1739141164.8990202,4.409995794296265,6.245895657760722,1739141164.8990216,4.409995794296265,2.1926548051511943 +1739141164.9184275,4.429995775222778,6.909123072188249,1739141164.91843,4.429995775222778,-0.22283859132289674,1739141164.9184332,4.429995775222778,5.983178427684099,1739141164.918436,4.429995775222778,14.555224180013434,1739141164.9184375,4.429995775222778,-0.162,1739141164.9184394,4.429995775222778,0.007956644386359454,1739141164.9184408,4.429995775222778,0.34585065446050095,1739141164.9184422,4.429995775222778,0.045426477306428466,1739141164.9184432,4.429995775222778,2.1770058514301978,1739141164.918445,4.429995775222778,0.0,1739141164.9184463,4.429995775222778,-0.015648953720996506,1739141164.9184477,4.429995775222778,6.245895657760722,1739141164.9184492,4.429995775222778,2.1926548051511943 +1739141164.9389768,4.449995756149292,6.909123072188249,1739141164.9389794,4.449995756149292,-0.22283859132289674,1739141164.9389827,4.449995756149292,5.983178427684099,1739141164.9389856,4.449995756149292,14.555224180013434,1739141164.9389868,4.449995756149292,-0.162,1739141164.9389884,4.449995756149292,0.007956644386359454,1739141164.9389899,4.449995756149292,0.34585065446050095,1739141164.938991,4.449995756149292,0.045426477306428466,1739141164.9389925,4.449995756149292,2.1770058514301978,1739141164.9389942,4.449995756149292,0.0,1739141164.9389954,4.449995756149292,-0.015648953720996506,1739141164.9389968,4.449995756149292,6.245895657760722,1739141164.9389982,4.449995756149292,2.1926548051511943 +1739141164.9585202,4.469995737075806,7.150064773155345,1739141164.9585226,4.469995737075806,-0.2317994083469035,1739141164.9585254,4.469995737075806,6.397257049055639,1739141164.9585283,4.469995737075806,14.964244968195178,1739141164.9585295,4.469995737075806,-0.16389778233213198,1739141164.9585311,4.469995737075806,0.00868932061414714,1739141164.9585326,4.469995737075806,0.35707939297683433,1739141164.958534,4.469995737075806,0.044904920968222,1739141164.958535,4.469995737075806,2.1672497657567162,1739141164.9585364,4.469995737075806,0.0,1739141164.958538,4.469995737075806,-0.031060400466456427,1739141164.9585395,4.469995737075806,6.246164101633525,1739141164.958541,4.469995737075806,2.190971378392623 +1739141164.9786153,4.489995718002319,7.150064773155345,1739141164.978618,4.489995718002319,-0.2317994083469035,1739141164.978621,4.489995718002319,6.397257049055639,1739141164.9786236,4.489995718002319,14.964244968195178,1739141164.978625,4.489995718002319,-0.16389778233213198,1739141164.9786265,4.489995718002319,0.00868932061414714,1739141164.978628,4.489995718002319,0.35707939297683433,1739141164.978629,4.489995718002319,0.044904920968222,1739141164.9786303,4.489995718002319,2.1672497657567162,1739141164.978632,4.489995718002319,0.0,1739141164.9786332,4.489995718002319,-0.023721612635906553,1739141164.9786348,4.489995718002319,6.246164101633525,1739141164.978636,4.489995718002319,2.190971378392623 +1739141164.9989066,4.509995698928833,7.150064773155345,1739141164.9989102,4.509995698928833,-0.2317994083469035,1739141164.998915,4.509995698928833,6.397257049055639,1739141164.9989214,4.509995698928833,14.964244968195178,1739141164.998925,4.509995698928833,-0.16389778233213198,1739141164.9989295,4.509995698928833,0.00868932061414714,1739141164.9989324,4.509995698928833,0.35707939297683433,1739141164.9989357,4.509995698928833,0.044904920968222,1739141164.9989386,4.509995698928833,2.1672497657567162,1739141164.9989421,4.509995698928833,0.0,1739141164.998947,4.509995698928833,-0.023721612635906553,1739141164.998952,4.509995698928833,6.246164101633525,1739141164.9989548,4.509995698928833,2.190971378392623 +1739141165.0182574,4.529995679855347,7.150064773155345,1739141165.0182602,4.529995679855347,-0.2317994083469035,1739141165.018263,4.529995679855347,6.397257049055639,1739141165.0182662,4.529995679855347,14.964244968195178,1739141165.0182679,4.529995679855347,-0.16389778233213198,1739141165.0182695,4.529995679855347,0.00868932061414714,1739141165.018271,4.529995679855347,0.35707939297683433,1739141165.0182722,4.529995679855347,0.044904920968222,1739141165.0182736,4.529995679855347,2.1672497657567162,1739141165.0182757,4.529995679855347,0.0,1739141165.0182774,4.529995679855347,-0.023721612635906553,1739141165.0182784,4.529995679855347,6.246164101633525,1739141165.0182798,4.529995679855347,2.190971378392623 +1739141165.0388074,4.54999566078186,7.150064773155345,1739141165.0388095,4.54999566078186,-0.2317994083469035,1739141165.0388124,4.54999566078186,6.397257049055639,1739141165.0388153,4.54999566078186,14.964244968195178,1739141165.0388167,4.54999566078186,-0.16389778233213198,1739141165.0388184,4.54999566078186,0.00868932061414714,1739141165.0388196,4.54999566078186,0.35707939297683433,1739141165.0388212,4.54999566078186,0.044904920968222,1739141165.0388224,4.54999566078186,2.1672497657567162,1739141165.0388238,4.54999566078186,0.0,1739141165.0388253,4.54999566078186,-0.023721612635906553,1739141165.0388265,4.54999566078186,6.246164101633525,1739141165.0388277,4.54999566078186,2.190971378392623 +1739141165.058494,4.569995641708374,7.150064773155345,1739141165.0584981,4.569995641708374,-0.2317994083469035,1739141165.0585017,4.569995641708374,6.397257049055639,1739141165.0585043,4.569995641708374,14.964244968195178,1739141165.058506,4.569995641708374,-0.16389778233213198,1739141165.0585077,4.569995641708374,0.00868932061414714,1739141165.058509,4.569995641708374,0.35707939297683433,1739141165.0585105,4.569995641708374,0.044904920968222,1739141165.0585122,4.569995641708374,2.1672497657567162,1739141165.058514,4.569995641708374,0.0,1739141165.0585155,4.569995641708374,-0.023721612635906553,1739141165.058517,4.569995641708374,6.246164101633525,1739141165.0585182,4.569995641708374,2.190971378392623 +1739141165.0790925,4.589995622634888,7.390763738003251,1739141165.079096,4.589995622634888,-0.24068342911881402,1739141165.079099,4.589995622634888,6.93529777792868,1739141165.0791018,4.589995622634888,15.49405715133807,1739141165.0791032,4.589995622634888,-0.1640597683856112,1739141165.0791047,4.589995622634888,0.00945558468881229,1739141165.0791063,4.589995622634888,0.3742039507931769,1739141165.0791075,4.589995622634888,0.04375995089477528,1739141165.0791087,4.589995622634888,2.152455216061318,1739141165.0791101,4.589995622634888,0.0,1739141165.0791116,4.589995622634888,-0.04672980173472575,1739141165.079113,4.589995622634888,6.246447287238248,1739141165.0791144,4.589995622634888,2.188228731799653 +1739141165.0998702,4.609995603561401,7.390763738003251,1739141165.0998743,4.609995603561401,-0.24068342911881402,1739141165.099879,4.609995603561401,6.93529777792868,1739141165.099884,4.609995603561401,15.49405715133807,1739141165.0998871,4.609995603561401,-0.1640597683856112,1739141165.099891,4.609995603561401,0.00945558468881229,1739141165.0998945,4.609995603561401,0.3742039507931769,1739141165.0998979,4.609995603561401,0.04375995089477528,1739141165.0999012,4.609995603561401,2.152455216061318,1739141165.099905,4.609995603561401,0.0,1739141165.0999086,4.609995603561401,-0.03577351573833498,1739141165.099912,4.609995603561401,6.246447287238248,1739141165.0999155,4.609995603561401,2.188228731799653 +1739141165.118921,4.629995584487915,7.390763738003251,1739141165.1189234,4.629995584487915,-0.24068342911881402,1739141165.1189263,4.629995584487915,6.93529777792868,1739141165.118929,4.629995584487915,15.49405715133807,1739141165.11893,4.629995584487915,-0.1640597683856112,1739141165.118932,4.629995584487915,0.00945558468881229,1739141165.1189334,4.629995584487915,0.3742039507931769,1739141165.1189349,4.629995584487915,0.04375995089477528,1739141165.118936,4.629995584487915,2.152455216061318,1739141165.1189375,4.629995584487915,0.0,1739141165.1189392,4.629995584487915,-0.03577351573833498,1739141165.1189406,4.629995584487915,6.246447287238248,1739141165.118942,4.629995584487915,2.188228731799653 +1739141165.1407256,4.649995565414429,7.390763738003251,1739141165.1407301,4.649995565414429,-0.24068342911881402,1739141165.140735,4.649995565414429,6.93529777792868,1739141165.140741,4.649995565414429,15.49405715133807,1739141165.1407442,4.649995565414429,-0.1640597683856112,1739141165.140748,4.649995565414429,0.00945558468881229,1739141165.1407518,4.649995565414429,0.3742039507931769,1739141165.1407554,4.649995565414429,0.04375995089477528,1739141165.140759,4.649995565414429,2.152455216061318,1739141165.1407626,4.649995565414429,0.0,1739141165.1407664,4.649995565414429,-0.03577351573833498,1739141165.1407702,4.649995565414429,6.246447287238248,1739141165.1407735,4.649995565414429,2.188228731799653 +1739141165.1593328,4.669995546340942,7.390763738003251,1739141165.159336,4.669995546340942,-0.24068342911881402,1739141165.1593392,4.669995546340942,6.93529777792868,1739141165.159342,4.669995546340942,15.49405715133807,1739141165.1593437,4.669995546340942,-0.1640597683856112,1739141165.1593454,4.669995546340942,0.00945558468881229,1739141165.159347,4.669995546340942,0.3742039507931769,1739141165.1593485,4.669995546340942,0.04375995089477528,1739141165.1593497,4.669995546340942,2.152455216061318,1739141165.1593516,4.669995546340942,0.0,1739141165.159353,4.669995546340942,-0.03577351573833498,1739141165.1593544,4.669995546340942,6.246447287238248,1739141165.159356,4.669995546340942,2.188228731799653 +1739141165.1798716,4.689995527267456,7.631105244815879,1739141165.1798763,4.689995527267456,-0.24948610669785953,1739141165.1798816,4.689995527267456,6.949727071015017,1739141165.1798878,4.689995527267456,15.496449993929929,1739141165.179891,4.689995527267456,-0.16407270266989152,1739141165.179896,4.689995527267456,0.010859034085473361,1739141165.1799002,4.689995527267456,0.3720229905729261,1739141165.1799042,4.689995527267456,0.04617532526167078,1739141165.179908,4.689995527267456,2.1543338030477135,1739141165.1799126,4.689995527267456,0.0,1739141165.1799164,4.689995527267456,-0.024527580133502758,1739141165.17992,4.689995527267456,6.2467304728429704,1739141165.1799238,4.689995527267456,2.18421659328725 +1739141165.1987357,4.70999550819397,7.631105244815879,1739141165.198739,4.70999550819397,-0.24948610669785953,1739141165.198742,4.70999550819397,6.949727071015017,1739141165.1987453,4.70999550819397,15.496449993929929,1739141165.1987467,4.70999550819397,-0.16407270266989152,1739141165.1987484,4.70999550819397,0.010859034085473361,1739141165.1987498,4.70999550819397,0.3720229905729261,1739141165.1987512,4.70999550819397,0.04617532526167078,1739141165.1987524,4.70999550819397,2.1543338030477135,1739141165.198755,4.70999550819397,0.0,1739141165.1987567,4.70999550819397,-0.02988279023953666,1739141165.198758,4.70999550819397,6.2467304728429704,1739141165.198759,4.70999550819397,2.18421659328725 +1739141165.2190938,4.729995489120483,7.631105244815879,1739141165.219097,4.729995489120483,-0.24948610669785953,1739141165.2191,4.729995489120483,6.949727071015017,1739141165.2191026,4.729995489120483,15.496449993929929,1739141165.219104,4.729995489120483,-0.16407270266989152,1739141165.219106,4.729995489120483,0.010859034085473361,1739141165.2191076,4.729995489120483,0.3720229905729261,1739141165.2191086,4.729995489120483,0.04617532526167078,1739141165.2191098,4.729995489120483,2.1543338030477135,1739141165.2191114,4.729995489120483,0.0,1739141165.219113,4.729995489120483,-0.02988279023953666,1739141165.2191148,4.729995489120483,6.2467304728429704,1739141165.219116,4.729995489120483,2.18421659328725 +1739141165.246054,4.749995470046997,7.631105244815879,1739141165.246064,4.749995470046997,-0.24948610669785953,1739141165.2460747,4.749995470046997,6.949727071015017,1739141165.246085,4.749995470046997,15.496449993929929,1739141165.2460897,4.749995470046997,-0.16407270266989152,1739141165.2460961,4.749995470046997,0.010859034085473361,1739141165.246101,4.749995470046997,0.3720229905729261,1739141165.2461057,4.749995470046997,0.04617532526167078,1739141165.2461104,4.749995470046997,2.1543338030477135,1739141165.2461164,4.749995470046997,0.0,1739141165.2461214,4.749995470046997,-0.02988279023953666,1739141165.2461264,4.749995470046997,6.2467304728429704,1739141165.2461317,4.749995470046997,2.18421659328725 +1739141165.2669334,4.769995450973511,7.631105244815879,1739141165.2669384,4.769995450973511,-0.24948610669785953,1739141165.2669442,4.769995450973511,6.949727071015017,1739141165.2669497,4.769995450973511,15.496449993929929,1739141165.2669523,4.769995450973511,-0.16407270266989152,1739141165.2669556,4.769995450973511,0.010859034085473361,1739141165.266958,4.769995450973511,0.3720229905729261,1739141165.2669609,4.769995450973511,0.04617532526167078,1739141165.2669632,4.769995450973511,2.1543338030477135,1739141165.2669663,4.769995450973511,0.0,1739141165.2669692,4.769995450973511,-0.02988279023953666,1739141165.2669713,4.769995450973511,6.2467304728429704,1739141165.2669737,4.769995450973511,2.18421659328725 +1739141165.2875378,4.789995431900024,7.631105244815879,1739141165.2875433,4.789995431900024,-0.24948610669785953,1739141165.287549,4.789995431900024,6.949727071015017,1739141165.287554,4.789995431900024,15.496449993929929,1739141165.287557,4.789995431900024,-0.16407270266989152,1739141165.28756,4.789995431900024,0.010859034085473361,1739141165.2875628,4.789995431900024,0.3720229905729261,1739141165.2875652,4.789995431900024,0.04617532526167078,1739141165.2875676,4.789995431900024,2.1543338030477135,1739141165.287571,4.789995431900024,0.0,1739141165.2875738,4.789995431900024,-0.02988279023953666,1739141165.2875764,4.789995431900024,6.2467304728429704,1739141165.2875788,4.789995431900024,2.18421659328725 +1739141165.3064523,4.819995403289795,7.87105690340838,1739141165.3064559,4.819995403289795,-0.2582064622383502,1739141165.3064597,4.819995403289795,6.964132890886107,1739141165.306463,4.819995403289795,15.501358939377909,1739141165.3064644,4.819995403289795,-0.16409923751015085,1739141165.3064668,4.819995403289795,0.012332729834066563,1739141165.3064845,4.819995403289795,0.36998608996326987,1739141165.3064861,4.819995403289795,0.04879314421111337,1739141165.3064876,4.819995403289795,2.1560897838369737,1739141165.3064897,4.819995403289795,0.0,1739141165.3064911,4.819995403289795,-0.020487039106325843,1739141165.3064926,4.819995403289795,6.247013658447693,1739141165.3064945,4.819995403289795,2.1810509923846335 +1739141165.3259873,4.839995384216309,7.87105690340838,1739141165.3259933,4.839995384216309,-0.2582064622383502,1739141165.3259969,4.839995384216309,6.964132890886107,1739141165.3260007,4.839995384216309,15.501358939377909,1739141165.3260024,4.839995384216309,-0.16409923751015085,1739141165.3260045,4.839995384216309,0.012332729834066563,1739141165.3260062,4.839995384216309,0.36998608996326987,1739141165.3260083,4.839995384216309,0.04879314421111337,1739141165.3260105,4.839995384216309,2.1560897838369737,1739141165.3260124,4.839995384216309,0.0,1739141165.3260143,4.839995384216309,-0.02496120854765982,1739141165.3260157,4.839995384216309,6.247013658447693,1739141165.3260174,4.839995384216309,2.1810509923846335 +1739141165.3448615,4.859995365142822,7.87105690340838,1739141165.3448637,4.859995365142822,-0.2582064622383502,1739141165.3448663,4.859995365142822,6.964132890886107,1739141165.3448691,4.859995365142822,15.501358939377909,1739141165.3448703,4.859995365142822,-0.16409923751015085,1739141165.344872,4.859995365142822,0.012332729834066563,1739141165.3448734,4.859995365142822,0.36998608996326987,1739141165.3448749,4.859995365142822,0.04879314421111337,1739141165.344876,4.859995365142822,2.1560897838369737,1739141165.3448777,4.859995365142822,0.0,1739141165.3448792,4.859995365142822,-0.02496120854765982,1739141165.3448803,4.859995365142822,6.247013658447693,1739141165.3448818,4.859995365142822,2.1810509923846335 +1739141165.3671036,4.879995346069336,7.87105690340838,1739141165.367107,4.879995346069336,-0.2582064622383502,1739141165.3671098,4.879995346069336,6.964132890886107,1739141165.3671124,4.879995346069336,15.501358939377909,1739141165.367114,4.879995346069336,-0.16409923751015085,1739141165.3671157,4.879995346069336,0.012332729834066563,1739141165.3671174,4.879995346069336,0.36998608996326987,1739141165.3671186,4.879995346069336,0.04879314421111337,1739141165.3671198,4.879995346069336,2.1560897838369737,1739141165.3671215,4.879995346069336,0.0,1739141165.367123,4.879995346069336,-0.02496120854765982,1739141165.3671243,4.879995346069336,6.247013658447693,1739141165.3671255,4.879995346069336,2.1810509923846335 +1739141165.3862424,4.89999532699585,7.87105690340838,1739141165.386245,4.89999532699585,-0.2582064622383502,1739141165.3862479,4.89999532699585,6.964132890886107,1739141165.3862507,4.89999532699585,15.501358939377909,1739141165.386252,4.89999532699585,-0.16409923751015085,1739141165.3862538,4.89999532699585,0.012332729834066563,1739141165.3862553,4.89999532699585,0.36998608996326987,1739141165.3862565,4.89999532699585,0.04879314421111337,1739141165.3862576,4.89999532699585,2.1560897838369737,1739141165.3862593,4.89999532699585,0.0,1739141165.3862607,4.89999532699585,-0.02496120854765982,1739141165.3862617,4.89999532699585,6.247013658447693,1739141165.3862631,4.89999532699585,2.1810509923846335 +1739141165.4067743,4.919995307922363,8.110678101814068,1739141165.4067776,4.919995307922363,-0.2668389696071882,1739141165.4067805,4.919995307922363,7.298765501609922,1739141165.4067829,4.919995307922363,15.82778188265599,1739141165.4067848,4.919995307922363,-0.165,1739141165.4067864,4.919995307922363,0.01319576118467702,1739141165.4067879,4.919995307922363,0.3778149448540856,1739141165.406789,4.919995307922363,0.04870997198379565,1739141165.4067905,4.919995307922363,2.149348459097011,1739141165.406792,4.919995307922363,0.0,1739141165.4067934,4.919995307922363,-0.032608229179238224,1739141165.4067945,4.919995307922363,6.2474076301212085,1739141165.4067957,4.919995307922363,2.178315248061201 +1739141165.4247596,4.939995288848877,8.110678101814068,1739141165.424763,4.939995288848877,-0.2668389696071882,1739141165.424766,4.939995288848877,7.298765501609922,1739141165.424769,4.939995288848877,15.82778188265599,1739141165.4247706,4.939995288848877,-0.165,1739141165.424773,4.939995288848877,0.01319576118467702,1739141165.4247746,4.939995288848877,0.3778149448540856,1739141165.4247758,4.939995288848877,0.04870997198379565,1739141165.424777,4.939995288848877,2.149348459097011,1739141165.4247787,4.939995288848877,0.0,1739141165.4247804,4.939995288848877,-0.028966788964190027,1739141165.4247818,4.939995288848877,6.2474076301212085,1739141165.424783,4.939995288848877,2.178315248061201 +1739141165.4446964,4.959995269775391,8.110678101814068,1739141165.444699,4.959995269775391,-0.2668389696071882,1739141165.444702,4.959995269775391,7.298765501609922,1739141165.4447043,4.959995269775391,15.82778188265599,1739141165.4447057,4.959995269775391,-0.165,1739141165.4447074,4.959995269775391,0.01319576118467702,1739141165.4447086,4.959995269775391,0.3778149448540856,1739141165.4447098,4.959995269775391,0.04870997198379565,1739141165.4447112,4.959995269775391,2.149348459097011,1739141165.4447129,4.959995269775391,0.0,1739141165.4447143,4.959995269775391,-0.028966788964190027,1739141165.4447155,4.959995269775391,6.2474076301212085,1739141165.4447167,4.959995269775391,2.178315248061201 +1739141165.4665182,4.979995250701904,8.110678101814068,1739141165.4665222,4.979995250701904,-0.2668389696071882,1739141165.4665265,4.979995250701904,7.298765501609922,1739141165.4665318,4.979995250701904,15.82778188265599,1739141165.4665349,4.979995250701904,-0.165,1739141165.4665387,4.979995250701904,0.01319576118467702,1739141165.466542,4.979995250701904,0.3778149448540856,1739141165.4665453,4.979995250701904,0.04870997198379565,1739141165.466549,4.979995250701904,2.149348459097011,1739141165.4665525,4.979995250701904,0.0,1739141165.4665558,4.979995250701904,-0.028966788964190027,1739141165.4665592,4.979995250701904,6.2474076301212085,1739141165.4665627,4.979995250701904,2.178315248061201 +1739141165.4846373,4.999995231628418,8.110678101814068,1739141165.4846396,4.999995231628418,-0.2668389696071882,1739141165.4846423,4.999995231628418,7.298765501609922,1739141165.484645,4.999995231628418,15.82778188265599,1739141165.484646,4.999995231628418,-0.165,1739141165.4846478,4.999995231628418,0.01319576118467702,1739141165.484649,4.999995231628418,0.3778149448540856,1739141165.4846501,4.999995231628418,0.04870997198379565,1739141165.4846513,4.999995231628418,2.149348459097011,1739141165.484653,4.999995231628418,0.0,1739141165.4846544,4.999995231628418,-0.028966788964190027,1739141165.4846556,4.999995231628418,6.2474076301212085,1739141165.4846566,4.999995231628418,2.178315248061201 +1739141165.504897,5.019995212554932,8.349980471711715,1739141165.504899,5.019995212554932,-0.2753557813843859,1739141165.504902,5.019995212554932,7.505444508155094,1739141165.5049047,5.019995212554932,16.024856336661422,1739141165.504906,5.019995212554932,-0.165,1739141165.5049076,5.019995212554932,0.01437784517727904,1739141165.5049088,5.019995212554932,0.38139924456007684,1739141165.50491,5.019995212554932,0.049712865025086844,1739141165.5049114,5.019995212554932,2.1462691034711794,1739141165.5049129,5.019995212554932,0.0,1739141165.5049143,5.019995212554932,-0.02873357070957412,1739141165.5049155,5.019995212554932,6.247853302133855,1739141165.5049167,5.019995212554932,2.175113730547953 +1739141165.5246975,5.039995193481445,8.349980471711715,1739141165.5247,5.039995193481445,-0.2753557813843859,1739141165.524703,5.039995193481445,7.505444508155094,1739141165.5247056,5.039995193481445,16.024856336661422,1739141165.5247068,5.039995193481445,-0.165,1739141165.5247083,5.039995193481445,0.01437784517727904,1739141165.52471,5.039995193481445,0.38139924456007684,1739141165.524711,5.039995193481445,0.049712865025086844,1739141165.524712,5.039995193481445,2.1462691034711794,1739141165.5247135,5.039995193481445,0.0,1739141165.524715,5.039995193481445,-0.028844627076773488,1739141165.5247161,5.039995193481445,6.247853302133855,1739141165.5247173,5.039995193481445,2.175113730547953 +1739141165.5447109,5.059995174407959,8.349980471711715,1739141165.5447135,5.059995174407959,-0.2753557813843859,1739141165.5447161,5.059995174407959,7.505444508155094,1739141165.5447185,5.059995174407959,16.024856336661422,1739141165.5447202,5.059995174407959,-0.165,1739141165.5447216,5.059995174407959,0.01437784517727904,1739141165.544723,5.059995174407959,0.38139924456007684,1739141165.5447242,5.059995174407959,0.049712865025086844,1739141165.5447254,5.059995174407959,2.1462691034711794,1739141165.5447268,5.059995174407959,0.0,1739141165.5447283,5.059995174407959,-0.028844627076773488,1739141165.5447297,5.059995174407959,6.247853302133855,1739141165.5447307,5.059995174407959,2.175113730547953 +1739141165.5647304,5.079995155334473,8.349980471711715,1739141165.564733,5.079995155334473,-0.2753557813843859,1739141165.564736,5.079995155334473,7.505444508155094,1739141165.5647385,5.079995155334473,16.024856336661422,1739141165.56474,5.079995155334473,-0.165,1739141165.5647414,5.079995155334473,0.01437784517727904,1739141165.5647426,5.079995155334473,0.38139924456007684,1739141165.5647442,5.079995155334473,0.049712865025086844,1739141165.5647452,5.079995155334473,2.1462691034711794,1739141165.5647469,5.079995155334473,0.0,1739141165.5647483,5.079995155334473,-0.028844627076773488,1739141165.5647492,5.079995155334473,6.247853302133855,1739141165.5647507,5.079995155334473,2.175113730547953 +1739141165.5847545,5.099995136260986,8.349980471711715,1739141165.584757,5.099995136260986,-0.2753557813843859,1739141165.5847597,5.099995136260986,7.505444508155094,1739141165.5847626,5.099995136260986,16.024856336661422,1739141165.5847645,5.099995136260986,-0.165,1739141165.584766,5.099995136260986,0.01437784517727904,1739141165.5847676,5.099995136260986,0.38139924456007684,1739141165.5847688,5.099995136260986,0.049712865025086844,1739141165.5847697,5.099995136260986,2.1462691034711794,1739141165.5847716,5.099995136260986,0.0,1739141165.5847728,5.099995136260986,-0.028844627076773488,1739141165.5847743,5.099995136260986,6.247853302133855,1739141165.5847754,5.099995136260986,2.175113730547953 +1739141165.6047027,5.1199951171875,8.349980471711715,1739141165.6047053,5.1199951171875,-0.2753557813843859,1739141165.6047082,5.1199951171875,7.505444508155094,1739141165.6047106,5.1199951171875,16.024856336661422,1739141165.604712,5.1199951171875,-0.165,1739141165.6047137,5.1199951171875,0.01437784517727904,1739141165.604715,5.1199951171875,0.38139924456007684,1739141165.6047165,5.1199951171875,0.049712865025086844,1739141165.6047177,5.1199951171875,2.1462691034711794,1739141165.6047194,5.1199951171875,0.0,1739141165.6047206,5.1199951171875,-0.028844627076773488,1739141165.604722,5.1199951171875,6.247853302133855,1739141165.6047237,5.1199951171875,2.175113730547953 +1739141165.6248143,5.139995098114014,8.588937467014777,1739141165.6248167,5.139995098114014,-0.28375367130164353,1739141165.6248195,5.139995098114014,7.7140523878783815,1739141165.6248224,5.139995098114014,16.22399646090475,1739141165.6248238,5.139995098114014,-0.165,1739141165.6248257,5.139995098114014,0.015552479233628085,1739141165.6248271,5.139995098114014,0.38498659873555174,1739141165.6248283,5.139995098114014,0.05070323069517527,1739141165.6248298,5.139995098114014,2.1431915410884934,1739141165.6248314,5.139995098114014,0.0,1739141165.624833,5.139995098114014,-0.028695038070357195,1739141165.6248343,5.139995098114014,6.248298974146501,1739141165.6248355,5.139995098114014,2.171957812054633 +1739141165.6447525,5.159995079040527,8.588937467014777,1739141165.6447546,5.159995079040527,-0.28375367130164353,1739141165.6447575,5.159995079040527,7.7140523878783815,1739141165.6447604,5.159995079040527,16.22399646090475,1739141165.6447616,5.159995079040527,-0.165,1739141165.6447635,5.159995079040527,0.015552479233628085,1739141165.6447647,5.159995079040527,0.38498659873555174,1739141165.6447659,5.159995079040527,0.05070323069517527,1739141165.644767,5.159995079040527,2.1431915410884934,1739141165.6447687,5.159995079040527,0.0,1739141165.6447701,5.159995079040527,-0.028766270966139373,1739141165.644771,5.159995079040527,6.248298974146501,1739141165.6447725,5.159995079040527,2.171957812054633 +1739141165.6652775,5.179995059967041,8.588937467014777,1739141165.66528,5.179995059967041,-0.28375367130164353,1739141165.665283,5.179995059967041,7.7140523878783815,1739141165.6652856,5.179995059967041,16.22399646090475,1739141165.665287,5.179995059967041,-0.165,1739141165.6652884,5.179995059967041,0.015552479233628085,1739141165.6652899,5.179995059967041,0.38498659873555174,1739141165.6652913,5.179995059967041,0.05070323069517527,1739141165.6652923,5.179995059967041,2.1431915410884934,1739141165.6652942,5.179995059967041,0.0,1739141165.6652954,5.179995059967041,-0.028766270966139373,1739141165.6652966,5.179995059967041,6.248298974146501,1739141165.665298,5.179995059967041,2.171957812054633 +1739141165.6847105,5.199995040893555,8.588937467014777,1739141165.6847134,5.199995040893555,-0.28375367130164353,1739141165.6847162,5.199995040893555,7.7140523878783815,1739141165.6847188,5.199995040893555,16.22399646090475,1739141165.6847203,5.199995040893555,-0.165,1739141165.6847222,5.199995040893555,0.015552479233628085,1739141165.6847234,5.199995040893555,0.38498659873555174,1739141165.6847248,5.199995040893555,0.05070323069517527,1739141165.684726,5.199995040893555,2.1431915410884934,1739141165.6847277,5.199995040893555,0.0,1739141165.684729,5.199995040893555,-0.028766270966139373,1739141165.6847303,5.199995040893555,6.248298974146501,1739141165.6847317,5.199995040893555,2.171957812054633 +1739141165.7052512,5.219995021820068,8.588937467014777,1739141165.7052546,5.219995021820068,-0.28375367130164353,1739141165.7052574,5.219995021820068,7.7140523878783815,1739141165.7052605,5.219995021820068,16.22399646090475,1739141165.7052622,5.219995021820068,-0.165,1739141165.7052636,5.219995021820068,0.015552479233628085,1739141165.705265,5.219995021820068,0.38498659873555174,1739141165.7052665,5.219995021820068,0.05070323069517527,1739141165.7052674,5.219995021820068,2.1431915410884934,1739141165.705269,5.219995021820068,0.0,1739141165.7052703,5.219995021820068,-0.028766270966139373,1739141165.7052717,5.219995021820068,6.248298974146501,1739141165.705273,5.219995021820068,2.171957812054633 +1739141165.7248528,5.239995002746582,8.827551993934565,1739141165.7248557,5.239995002746582,-0.29202727261906425,1739141165.7248583,5.239995002746582,8.109108649863375,1739141165.724861,5.239995002746582,16.609614748795046,1739141165.724862,5.239995002746582,-0.165,1739141165.724864,5.239995002746582,0.016321635609517278,1739141165.7248654,5.239995002746582,0.39440104629603373,1739141165.7248669,5.239995002746582,0.049998147070321186,1739141165.724868,5.239995002746582,2.1351359326785984,1739141165.7248697,5.239995002746582,0.0,1739141165.724871,5.239995002746582,-0.03813918049038734,1739141165.724872,5.239995002746582,6.248811196219665,1739141165.7248735,5.239995002746582,2.168811820689734 +1739141165.7448537,5.259994983673096,8.827551993934565,1739141165.7448564,5.259994983673096,-0.29202727261906425,1739141165.744859,5.259994983673096,8.109108649863375,1739141165.7448616,5.259994983673096,16.609614748795046,1739141165.7448633,5.259994983673096,-0.165,1739141165.7448647,5.259994983673096,0.016321635609517278,1739141165.7448664,5.259994983673096,0.39440104629603373,1739141165.7448678,5.259994983673096,0.049998147070321186,1739141165.7448688,5.259994983673096,2.1351359326785984,1739141165.7448707,5.259994983673096,0.0,1739141165.7448719,5.259994983673096,-0.03367588801113586,1739141165.7448733,5.259994983673096,6.248811196219665,1739141165.7448745,5.259994983673096,2.168811820689734 +1739141165.7647371,5.279994964599609,8.827551993934565,1739141165.7647398,5.279994964599609,-0.29202727261906425,1739141165.7647426,5.279994964599609,8.109108649863375,1739141165.7647452,5.279994964599609,16.609614748795046,1739141165.7647467,5.279994964599609,-0.165,1739141165.7647483,5.279994964599609,0.016321635609517278,1739141165.7647498,5.279994964599609,0.39440104629603373,1739141165.7647512,5.279994964599609,0.049998147070321186,1739141165.7647524,5.279994964599609,2.1351359326785984,1739141165.7647538,5.279994964599609,0.0,1739141165.7647555,5.279994964599609,-0.03367588801113586,1739141165.7647564,5.279994964599609,6.248811196219665,1739141165.764758,5.279994964599609,2.168811820689734 +1739141165.785034,5.299994945526123,8.827551993934565,1739141165.7850366,5.299994945526123,-0.29202727261906425,1739141165.7850392,5.299994945526123,8.109108649863375,1739141165.7850418,5.299994945526123,16.609614748795046,1739141165.7850432,5.299994945526123,-0.165,1739141165.785045,5.299994945526123,0.016321635609517278,1739141165.7850463,5.299994945526123,0.39440104629603373,1739141165.7850475,5.299994945526123,0.049998147070321186,1739141165.7850485,5.299994945526123,2.1351359326785984,1739141165.7850504,5.299994945526123,0.0,1739141165.7850516,5.299994945526123,-0.03367588801113586,1739141165.7850533,5.299994945526123,6.248811196219665,1739141165.7850544,5.299994945526123,2.168811820689734 +1739141165.8047295,5.319994926452637,8.827551993934565,1739141165.8047318,5.319994926452637,-0.29202727261906425,1739141165.8047347,5.319994926452637,8.109108649863375,1739141165.8047373,5.319994926452637,16.609614748795046,1739141165.8047385,5.319994926452637,-0.165,1739141165.8047402,5.319994926452637,0.016321635609517278,1739141165.8047414,5.319994926452637,0.39440104629603373,1739141165.8047426,5.319994926452637,0.049998147070321186,1739141165.804744,5.319994926452637,2.1351359326785984,1739141165.8047457,5.319994926452637,0.0,1739141165.8047473,5.319994926452637,-0.03367588801113586,1739141165.8047485,5.319994926452637,6.248811196219665,1739141165.8047497,5.319994926452637,2.168811820689734 +1739141165.8247232,5.33999490737915,8.827551993934565,1739141165.8247259,5.33999490737915,-0.29202727261906425,1739141165.8247285,5.33999490737915,8.109108649863375,1739141165.824731,5.33999490737915,16.609614748795046,1739141165.8247328,5.33999490737915,-0.165,1739141165.8247342,5.33999490737915,0.016321635609517278,1739141165.8247354,5.33999490737915,0.39440104629603373,1739141165.824737,5.33999490737915,0.049998147070321186,1739141165.824738,5.33999490737915,2.1351359326785984,1739141165.82474,5.33999490737915,0.0,1739141165.8247411,5.33999490737915,-0.03367588801113586,1739141165.824742,5.33999490737915,6.248811196219665,1739141165.8247435,5.33999490737915,2.168811820689734 +1739141165.8447943,5.359994888305664,9.065789284002436,1739141165.844797,5.359994888305664,-0.30016257569721105,1739141165.8447998,5.359994888305664,8.414990658865992,1739141165.8448024,5.359994888305664,16.9041700089846,1739141165.8448036,5.359994888305664,-0.165,1739141165.8448055,5.359994888305664,0.01724197716380142,1739141165.8448067,5.359994888305664,0.4003409622084683,1739141165.8448079,5.359994888305664,0.05002293533333689,1739141165.844809,5.359994888305664,2.130068943399643,1739141165.8448107,5.359994888305664,0.0,1739141165.8448124,5.359994888305664,-0.03614130123681466,1739141165.8448133,5.359994888305664,6.249338207195166,1739141165.8448145,5.359994888305664,2.1650362377520476 +1739141165.8647451,5.379994869232178,9.065789284002436,1739141165.8647478,5.379994869232178,-0.30016257569721105,1739141165.8647509,5.379994869232178,8.414990658865992,1739141165.8647537,5.379994869232178,16.9041700089846,1739141165.864755,5.379994869232178,-0.165,1739141165.8647568,5.379994869232178,0.01724197716380142,1739141165.864758,5.379994869232178,0.4003409622084683,1739141165.8647592,5.379994869232178,0.05002293533333689,1739141165.8647606,5.379994869232178,2.130068943399643,1739141165.864762,5.379994869232178,0.0,1739141165.8647637,5.379994869232178,-0.03496729435240464,1739141165.864765,5.379994869232178,6.249338207195166,1739141165.864766,5.379994869232178,2.1650362377520476 +1739141165.884683,5.399994850158691,9.065789284002436,1739141165.8846855,5.399994850158691,-0.30016257569721105,1739141165.8846886,5.399994850158691,8.414990658865992,1739141165.8846912,5.399994850158691,16.9041700089846,1739141165.8846927,5.399994850158691,-0.165,1739141165.8846943,5.399994850158691,0.01724197716380142,1739141165.8846958,5.399994850158691,0.4003409622084683,1739141165.8846972,5.399994850158691,0.05002293533333689,1739141165.8846984,5.399994850158691,2.130068943399643,1739141165.8846998,5.399994850158691,0.0,1739141165.8847013,5.399994850158691,-0.03496729435240464,1739141165.8847024,5.399994850158691,6.249338207195166,1739141165.884704,5.399994850158691,2.1650362377520476 +1739141165.9047253,5.419994831085205,9.065789284002436,1739141165.9047277,5.419994831085205,-0.30016257569721105,1739141165.9047306,5.419994831085205,8.414990658865992,1739141165.9047334,5.419994831085205,16.9041700089846,1739141165.9047353,5.419994831085205,-0.165,1739141165.904737,5.419994831085205,0.01724197716380142,1739141165.9047387,5.419994831085205,0.4003409622084683,1739141165.9047399,5.419994831085205,0.05002293533333689,1739141165.9047408,5.419994831085205,2.130068943399643,1739141165.904743,5.419994831085205,0.0,1739141165.9047441,5.419994831085205,-0.03496729435240464,1739141165.9047456,5.419994831085205,6.249338207195166,1739141165.9047468,5.419994831085205,2.1650362377520476 +1739141165.9246397,5.439994812011719,9.065789284002436,1739141165.9246423,5.439994812011719,-0.30016257569721105,1739141165.9246452,5.439994812011719,8.414990658865992,1739141165.9246476,5.439994812011719,16.9041700089846,1739141165.9246492,5.439994812011719,-0.165,1739141165.924651,5.439994812011719,0.01724197716380142,1739141165.9246523,5.439994812011719,0.4003409622084683,1739141165.9246538,5.439994812011719,0.05002293533333689,1739141165.9246552,5.439994812011719,2.130068943399643,1739141165.9246564,5.439994812011719,0.0,1739141165.9246578,5.439994812011719,-0.03496729435240464,1739141165.9246595,5.439994812011719,6.249338207195166,1739141165.9246604,5.439994812011719,2.1650362377520476 +1739141165.9448395,5.459994792938232,9.30361675957803,1739141165.9448416,5.459994792938232,-0.30815840336672373,1739141165.9448445,5.459994792938232,8.4399705396291,1739141165.944847,5.459994792938232,16.917643321448864,1739141165.9448485,5.459994792938232,-0.165,1739141165.9448504,5.459994792938232,0.018799716069666485,1739141165.9448516,5.459994792938232,0.3967320426623629,1739141165.944853,5.459994792938232,0.052532954762906196,1739141165.9448543,5.459994792938232,2.1331460628583456,1739141165.9448557,5.459994792938232,0.0,1739141165.9448574,5.459994792938232,-0.0217704259297827,1739141165.9448586,5.459994792938232,6.249865218170666,1739141165.94486,5.459994792938232,2.1612007149857653 +1739141165.9654772,5.479994773864746,9.30361675957803,1739141165.9654796,5.479994773864746,-0.30815840336672373,1739141165.9654822,5.479994773864746,8.4399705396291,1739141165.9654849,5.479994773864746,16.917643321448864,1739141165.965486,5.479994773864746,-0.165,1739141165.9654872,5.479994773864746,0.018799716069666485,1739141165.965489,5.479994773864746,0.3967320426623629,1739141165.96549,5.479994773864746,0.052532954762906196,1739141165.9654913,5.479994773864746,2.1331460628583456,1739141165.965493,5.479994773864746,0.0,1739141165.9654942,5.479994773864746,-0.028054652127419644,1739141165.9654956,5.479994773864746,6.249865218170666,1739141165.9654968,5.479994773864746,2.1612007149857653 +1739141165.985587,5.49999475479126,9.30361675957803,1739141165.9855905,5.49999475479126,-0.30815840336672373,1739141165.9855933,5.49999475479126,8.4399705396291,1739141165.9855962,5.49999475479126,16.917643321448864,1739141165.9855976,5.49999475479126,-0.165,1739141165.9855995,5.49999475479126,0.018799716069666485,1739141165.9856007,5.49999475479126,0.3967320426623629,1739141165.9856021,5.49999475479126,0.052532954762906196,1739141165.9856033,5.49999475479126,2.1331460628583456,1739141165.9856055,5.49999475479126,0.0,1739141165.9856071,5.49999475479126,-0.028054652127419644,1739141165.9856083,5.49999475479126,6.249865218170666,1739141165.9856098,5.49999475479126,2.1612007149857653 +1739141166.0060816,5.519994735717773,9.30361675957803,1739141166.0060844,5.519994735717773,-0.30815840336672373,1739141166.0060875,5.519994735717773,8.4399705396291,1739141166.0060902,5.519994735717773,16.917643321448864,1739141166.0060916,5.519994735717773,-0.165,1739141166.0060933,5.519994735717773,0.018799716069666485,1739141166.006095,5.519994735717773,0.3967320426623629,1739141166.0060961,5.519994735717773,0.052532954762906196,1739141166.0060973,5.519994735717773,2.1331460628583456,1739141166.006099,5.519994735717773,0.0,1739141166.0061004,5.519994735717773,-0.028054652127419644,1739141166.0061018,5.519994735717773,6.249865218170666,1739141166.006103,5.519994735717773,2.1612007149857653 +1739141166.0250044,5.539994716644287,9.30361675957803,1739141166.025007,5.539994716644287,-0.30815840336672373,1739141166.02501,5.539994716644287,8.4399705396291,1739141166.025013,5.539994716644287,16.917643321448864,1739141166.0250146,5.539994716644287,-0.165,1739141166.025016,5.539994716644287,0.018799716069666485,1739141166.0250175,5.539994716644287,0.3967320426623629,1739141166.0250187,5.539994716644287,0.052532954762906196,1739141166.0250204,5.539994716644287,2.1331460628583456,1739141166.025022,5.539994716644287,0.0,1739141166.0250235,5.539994716644287,-0.028054652127419644,1739141166.0250247,5.539994716644287,6.249865218170666,1739141166.0250263,5.539994716644287,2.1612007149857653 +1739141166.0450685,5.559994697570801,9.30361675957803,1739141166.0450754,5.559994697570801,-0.30815840336672373,1739141166.0450804,5.559994697570801,8.4399705396291,1739141166.0450842,5.559994697570801,16.917643321448864,1739141166.045086,5.559994697570801,-0.165,1739141166.0450888,5.559994697570801,0.018799716069666485,1739141166.0450912,5.559994697570801,0.3967320426623629,1739141166.0450935,5.559994697570801,0.052532954762906196,1739141166.0450962,5.559994697570801,2.1331460628583456,1739141166.0450983,5.559994697570801,0.0,1739141166.0451005,5.559994697570801,-0.028054652127419644,1739141166.0451021,5.559994697570801,6.249865218170666,1739141166.045105,5.559994697570801,2.1612007149857653 +1739141166.0647216,5.5799946784973145,9.541077106556024,1739141166.064724,5.5799946784973145,-0.31600940351208084,1739141166.0647268,5.5799946784973145,8.748628565965276,1739141166.0647295,5.5799946784973145,17.217459025153843,1739141166.064731,5.5799946784973145,-0.16475244516677442,1739141166.0647323,5.5799946784973145,0.019701649691356994,1739141166.064734,5.5799946784973145,0.4022951186859019,1739141166.0647352,5.5799946784973145,0.05240588655696597,1739141166.0647366,5.5799946784973145,2.12840459875311,1739141166.064738,5.5799946784973145,0.0,1739141166.0647392,5.5799946784973145,-0.031480269018328705,1739141166.0647407,5.5799946784973145,6.250466256751839,1739141166.0647418,5.5799946784973145,2.1582536208180314 +1739141166.0848436,5.599994659423828,9.541077106556024,1739141166.084846,5.599994659423828,-0.31600940351208084,1739141166.0848486,5.599994659423828,8.748628565965276,1739141166.0848515,5.599994659423828,17.217459025153843,1739141166.084853,5.599994659423828,-0.16475244516677442,1739141166.0848548,5.599994659423828,0.019701649691356994,1739141166.084856,5.599994659423828,0.4022951186859019,1739141166.0848577,5.599994659423828,0.05240588655696597,1739141166.084859,5.599994659423828,2.12840459875311,1739141166.0848603,5.599994659423828,0.0,1739141166.084862,5.599994659423828,-0.02984902206492146,1739141166.084863,5.599994659423828,6.250466256751839,1739141166.0848641,5.599994659423828,2.1582536208180314 +1739141166.1049113,5.619994640350342,9.541077106556024,1739141166.1049137,5.619994640350342,-0.31600940351208084,1739141166.1049166,5.619994640350342,8.748628565965276,1739141166.1049192,5.619994640350342,17.217459025153843,1739141166.1049206,5.619994640350342,-0.16475244516677442,1739141166.1049225,5.619994640350342,0.019701649691356994,1739141166.104924,5.619994640350342,0.4022951186859019,1739141166.1049252,5.619994640350342,0.05240588655696597,1739141166.104926,5.619994640350342,2.12840459875311,1739141166.104928,5.619994640350342,0.0,1739141166.1049292,5.619994640350342,-0.02984902206492146,1739141166.1049306,5.619994640350342,6.250466256751839,1739141166.1049318,5.619994640350342,2.1582536208180314 +1739141166.1247907,5.6399946212768555,9.541077106556024,1739141166.124793,5.6399946212768555,-0.31600940351208084,1739141166.124796,5.6399946212768555,8.748628565965276,1739141166.1247988,5.6399946212768555,17.217459025153843,1739141166.1248,5.6399946212768555,-0.16475244516677442,1739141166.1248019,5.6399946212768555,0.019701649691356994,1739141166.1248033,5.6399946212768555,0.4022951186859019,1739141166.1248045,5.6399946212768555,0.05240588655696597,1739141166.124806,5.6399946212768555,2.12840459875311,1739141166.1248076,5.6399946212768555,0.0,1739141166.124809,5.6399946212768555,-0.02984902206492146,1739141166.1248102,5.6399946212768555,6.250466256751839,1739141166.1248114,5.6399946212768555,2.1582536208180314 +1739141166.1447685,5.659994602203369,9.541077106556024,1739141166.144771,5.659994602203369,-0.31600940351208084,1739141166.1447737,5.659994602203369,8.748628565965276,1739141166.1447763,5.659994602203369,17.217459025153843,1739141166.144778,5.659994602203369,-0.16475244516677442,1739141166.1447794,5.659994602203369,0.019701649691356994,1739141166.144781,5.659994602203369,0.4022951186859019,1739141166.1447825,5.659994602203369,0.05240588655696597,1739141166.1447835,5.659994602203369,2.12840459875311,1739141166.1447852,5.659994602203369,0.0,1739141166.1447866,5.659994602203369,-0.02984902206492146,1739141166.144788,5.659994602203369,6.250466256751839,1739141166.1447892,5.659994602203369,2.1582536208180314 +1739141166.164986,5.679994583129883,9.77819574568042,1739141166.164988,5.679994583129883,-0.32370483994905896,1739141166.1649911,5.679994583129883,9.155324353919772,1739141166.1649942,5.679994583129883,17.61431161302632,1739141166.1649954,5.679994583129883,-0.164,1739141166.164997,5.679994583129883,0.020377791241950702,1739141166.1649983,5.679994583129883,0.4112017265425903,1739141166.165,5.679994583129883,0.05140336997494012,1739141166.1650012,5.679994583129883,2.1208353439873324,1739141166.165003,5.679994583129883,0.0,1739141166.1650043,5.679994583129883,-0.038037578497845614,1739141166.165006,5.679994583129883,6.2510746980935785,1739141166.1650069,5.679994583129883,2.1549736079501933 +1739141166.1847365,5.6999945640563965,9.77819574568042,1739141166.1847389,5.6999945640563965,-0.32370483994905896,1739141166.184742,5.6999945640563965,9.155324353919772,1739141166.1847446,5.6999945640563965,17.61431161302632,1739141166.184746,5.6999945640563965,-0.164,1739141166.1847477,5.6999945640563965,0.020377791241950702,1739141166.1847491,5.6999945640563965,0.4112017265425903,1739141166.1847503,5.6999945640563965,0.05140336997494012,1739141166.1847515,5.6999945640563965,2.1208353439873324,1739141166.1847532,5.6999945640563965,0.0,1739141166.1847546,5.6999945640563965,-0.034138263962860904,1739141166.184756,5.6999945640563965,6.2510746980935785,1739141166.1847572,5.6999945640563965,2.1549736079501933 +1739141166.2047603,5.71999454498291,9.77819574568042,1739141166.204763,5.71999454498291,-0.32370483994905896,1739141166.2047658,5.71999454498291,9.155324353919772,1739141166.2047682,5.71999454498291,17.61431161302632,1739141166.2047696,5.71999454498291,-0.164,1739141166.2047713,5.71999454498291,0.020377791241950702,1739141166.2047727,5.71999454498291,0.4112017265425903,1739141166.204774,5.71999454498291,0.05140336997494012,1739141166.204775,5.71999454498291,2.1208353439873324,1739141166.2047768,5.71999454498291,0.0,1739141166.2047782,5.71999454498291,-0.034138263962860904,1739141166.2047799,5.71999454498291,6.2510746980935785,1739141166.204781,5.71999454498291,2.1549736079501933 +1739141166.2248237,5.739994525909424,9.77819574568042,1739141166.224826,5.739994525909424,-0.32370483994905896,1739141166.224829,5.739994525909424,9.155324353919772,1739141166.2248316,5.739994525909424,17.61431161302632,1739141166.224833,5.739994525909424,-0.164,1739141166.224835,5.739994525909424,0.020377791241950702,1739141166.224836,5.739994525909424,0.4112017265425903,1739141166.2248373,5.739994525909424,0.05140336997494012,1739141166.2248385,5.739994525909424,2.1208353439873324,1739141166.22484,5.739994525909424,0.0,1739141166.2248418,5.739994525909424,-0.034138263962860904,1739141166.224843,5.739994525909424,6.2510746980935785,1739141166.2248442,5.739994525909424,2.1549736079501933 +1739141166.244834,5.7599945068359375,9.77819574568042,1739141166.2448366,5.7599945068359375,-0.32370483994905896,1739141166.2448392,5.7599945068359375,9.155324353919772,1739141166.2448423,5.7599945068359375,17.61431161302632,1739141166.2448435,5.7599945068359375,-0.164,1739141166.2448452,5.7599945068359375,0.020377791241950702,1739141166.2448463,5.7599945068359375,0.4112017265425903,1739141166.2448475,5.7599945068359375,0.05140336997494012,1739141166.244849,5.7599945068359375,2.1208353439873324,1739141166.2448504,5.7599945068359375,0.0,1739141166.244852,5.7599945068359375,-0.034138263962860904,1739141166.244853,5.7599945068359375,6.2510746980935785,1739141166.2448542,5.7599945068359375,2.1549736079501933 +1739141166.2647188,5.779994487762451,9.77819574568042,1739141166.2647214,5.779994487762451,-0.32370483994905896,1739141166.2647245,5.779994487762451,9.155324353919772,1739141166.2647274,5.779994487762451,17.61431161302632,1739141166.2647288,5.779994487762451,-0.164,1739141166.2647305,5.779994487762451,0.020377791241950702,1739141166.2647316,5.779994487762451,0.4112017265425903,1739141166.2647328,5.779994487762451,0.05140336997494012,1739141166.2647343,5.779994487762451,2.1208353439873324,1739141166.264736,5.779994487762451,0.0,1739141166.2647374,5.779994487762451,-0.034138263962860904,1739141166.2647386,5.779994487762451,6.2510746980935785,1739141166.2647398,5.779994487762451,2.1549736079501933 +1739141166.2847655,5.799994468688965,10.014928218008727,1739141166.2847676,5.799994468688965,-0.3312435598417425,1739141166.2847703,5.799994468688965,9.180662267178793,1739141166.2847733,5.799994468688965,17.628204282124997,1739141166.2847745,5.799994468688965,-0.164,1739141166.2847762,5.799994468688965,0.021963825331915255,1739141166.2847776,5.799994468688965,0.4069556150735968,1739141166.284779,5.799994468688965,0.053890084920232534,1739141166.28478,5.799994468688965,2.1244405260328194,1739141166.284782,5.799994468688965,0.0,1739141166.2847831,5.799994468688965,-0.019972300068054998,1739141166.2847843,5.799994468688965,6.251683139435318,1739141166.284786,5.799994468688965,2.151158526563411 +1739141166.3048096,5.8199944496154785,10.014928218008727,1739141166.3048124,5.8199944496154785,-0.3312435598417425,1739141166.3048153,5.8199944496154785,9.180662267178793,1739141166.3048182,5.8199944496154785,17.628204282124997,1739141166.3048193,5.8199944496154785,-0.164,1739141166.3048213,5.8199944496154785,0.021963825331915255,1739141166.3048224,5.8199944496154785,0.4069556150735968,1739141166.3048239,5.8199944496154785,0.053890084920232534,1739141166.304825,5.8199944496154785,2.1244405260328194,1739141166.3048267,5.8199944496154785,0.0,1739141166.3048282,5.8199944496154785,-0.026718000530591812,1739141166.3048294,5.8199944496154785,6.251683139435318,1739141166.304831,5.8199944496154785,2.151158526563411 +1739141166.3248518,5.839994430541992,10.014928218008727,1739141166.3248544,5.839994430541992,-0.3312435598417425,1739141166.324857,5.839994430541992,9.180662267178793,1739141166.32486,5.839994430541992,17.628204282124997,1739141166.3248618,5.839994430541992,-0.164,1739141166.3248634,5.839994430541992,0.021963825331915255,1739141166.324865,5.839994430541992,0.4069556150735968,1739141166.3248665,5.839994430541992,0.053890084920232534,1739141166.3248677,5.839994430541992,2.1244405260328194,1739141166.3248696,5.839994430541992,0.0,1739141166.324871,5.839994430541992,-0.026718000530591812,1739141166.3248725,5.839994430541992,6.251683139435318,1739141166.3248737,5.839994430541992,2.151158526563411 +1739141166.345005,5.859994411468506,10.014928218008727,1739141166.3450081,5.859994411468506,-0.3312435598417425,1739141166.3450117,5.859994411468506,9.180662267178793,1739141166.3450148,5.859994411468506,17.628204282124997,1739141166.3450162,5.859994411468506,-0.164,1739141166.3450184,5.859994411468506,0.021963825331915255,1739141166.34502,5.859994411468506,0.4069556150735968,1739141166.3450217,5.859994411468506,0.053890084920232534,1739141166.3450232,5.859994411468506,2.1244405260328194,1739141166.345025,5.859994411468506,0.0,1739141166.3450265,5.859994411468506,-0.026718000530591812,1739141166.345028,5.859994411468506,6.251683139435318,1739141166.3450294,5.859994411468506,2.151158526563411 +1739141166.3658524,5.869994401931763,10.014928218008727,1739141166.3658555,5.869994401931763,-0.3312435598417425,1739141166.365859,5.869994401931763,9.180662267178793,1739141166.3658621,5.869994401931763,17.628204282124997,1739141166.365864,5.869994401931763,-0.164,1739141166.365866,5.869994401931763,0.021963825331915255,1739141166.3658676,5.869994401931763,0.4069556150735968,1739141166.365869,5.869994401931763,0.053890084920232534,1739141166.3658705,5.869994401931763,2.1244405260328194,1739141166.3658726,5.869994401931763,0.0,1739141166.3658745,5.869994401931763,-0.026718000530591812,1739141166.365876,5.869994401931763,6.251683139435318,1739141166.3658779,5.869994401931763,2.151158526563411 +1739141166.3850374,5.899994373321533,10.25129822224381,1739141166.3850403,5.899994373321533,-0.3386267712720672,1739141166.3850436,5.899994373321533,9.854541929286478,1739141166.3850472,5.899994373321533,18.293409893095358,1739141166.3850489,5.899994373321533,-0.15417165554309034,1739141166.3850508,5.899994373321533,0.022932133775512193,1739141166.3850524,5.899994373321533,0.4327783770679122,1739141166.3850539,5.899994373321533,0.051358902722375574,1739141166.3850555,5.899994373321533,2.1026098967247315,1739141166.3850572,5.899994373321533,0.0,1739141166.385059,5.899994373321533,-0.0629318134220148,1739141166.3850605,5.899994373321533,6.252291580777058,1739141166.3850625,5.899994373321533,2.148297028726835 +1739141166.405406,5.919994354248047,10.25129822224381,1739141166.405409,5.919994354248047,-0.3386267712720672,1739141166.4054127,5.919994354248047,9.854541929286478,1739141166.4054158,5.919994354248047,18.293409893095358,1739141166.4054172,5.919994354248047,-0.15417165554309034,1739141166.4054193,5.919994354248047,0.022932133775512193,1739141166.4054208,5.919994354248047,0.4327783770679122,1739141166.4054224,5.919994354248047,0.051358902722375574,1739141166.4054239,5.919994354248047,2.1026098967247315,1739141166.4054255,5.919994354248047,0.0,1739141166.4054275,5.919994354248047,-0.0456871320021035,1739141166.4054286,5.919994354248047,6.252291580777058,1739141166.4054303,5.919994354248047,2.148297028726835 +1739141166.4250891,5.9399943351745605,10.25129822224381,1739141166.4250917,5.9399943351745605,-0.3386267712720672,1739141166.425095,5.9399943351745605,9.854541929286478,1739141166.4250982,5.9399943351745605,18.293409893095358,1739141166.4251,5.9399943351745605,-0.15417165554309034,1739141166.425102,5.9399943351745605,0.022932133775512193,1739141166.4251037,5.9399943351745605,0.4327783770679122,1739141166.425105,5.9399943351745605,0.051358902722375574,1739141166.4251068,5.9399943351745605,2.1026098967247315,1739141166.4251087,5.9399943351745605,0.0,1739141166.4251103,5.9399943351745605,-0.0456871320021035,1739141166.4251118,5.9399943351745605,6.252291580777058,1739141166.4251134,5.9399943351745605,2.148297028726835 +1739141166.4451501,5.959994316101074,10.25129822224381,1739141166.445153,5.959994316101074,-0.3386267712720672,1739141166.4451566,5.959994316101074,9.854541929286478,1739141166.44516,5.959994316101074,18.293409893095358,1739141166.4451616,5.959994316101074,-0.15417165554309034,1739141166.4451635,5.959994316101074,0.022932133775512193,1739141166.4451654,5.959994316101074,0.4327783770679122,1739141166.4451668,5.959994316101074,0.051358902722375574,1739141166.445168,5.959994316101074,2.1026098967247315,1739141166.4451702,5.959994316101074,0.0,1739141166.4451723,5.959994316101074,-0.0456871320021035,1739141166.4451737,5.959994316101074,6.252291580777058,1739141166.4451754,5.959994316101074,2.148297028726835 +1739141166.4654586,5.979994297027588,10.25129822224381,1739141166.4654617,5.979994297027588,-0.3386267712720672,1739141166.465465,5.979994297027588,9.854541929286478,1739141166.4654684,5.979994297027588,18.293409893095358,1739141166.4654703,5.979994297027588,-0.15417165554309034,1739141166.4654722,5.979994297027588,0.022932133775512193,1739141166.465474,5.979994297027588,0.4327783770679122,1739141166.4654756,5.979994297027588,0.051358902722375574,1739141166.4654768,5.979994297027588,2.1026098967247315,1739141166.465479,5.979994297027588,0.0,1739141166.4654806,5.979994297027588,-0.0456871320021035,1739141166.465482,5.979994297027588,6.252291580777058,1739141166.4654834,5.979994297027588,2.148297028726835 +1739141166.4849927,5.999994277954102,10.25129822224381,1739141166.4849956,5.999994277954102,-0.3386267712720672,1739141166.4849987,5.999994277954102,9.854541929286478,1739141166.485002,5.999994277954102,18.293409893095358,1739141166.485004,5.999994277954102,-0.15417165554309034,1739141166.4850059,5.999994277954102,0.022932133775512193,1739141166.4850073,5.999994277954102,0.4327783770679122,1739141166.485009,5.999994277954102,0.051358902722375574,1739141166.4850104,5.999994277954102,2.1026098967247315,1739141166.4850123,5.999994277954102,0.0,1739141166.485014,5.999994277954102,-0.0456871320021035,1739141166.4850156,5.999994277954102,6.252291580777058,1739141166.485017,5.999994277954102,2.148297028726835 +1739141166.505865,6.019994258880615,10.48721705600599,1739141166.5058682,6.019994258880615,-0.3458522233447985,1739141166.5058715,6.019994258880615,9.864929583424086,1739141166.5058749,6.019994258880615,18.287766805688616,1739141166.5058768,6.019994258880615,-0.15431156680110875,1739141166.5058787,6.019994258880615,0.024549830588394342,1739141166.5058804,6.019994258880615,0.4276585838647198,1739141166.5058818,6.019994258880615,0.05393856868282945,1739141166.5058837,6.019994258880615,2.106920280015767,1739141166.5058856,6.019994258880615,0.0,1739141166.5058873,6.019994258880615,-0.027255725530327075,1739141166.5058887,6.019994258880615,6.252900022118798,1739141166.5058904,6.019994258880615,2.142952870155177 +1739141166.525031,6.039994239807129,10.48721705600599,1739141166.525034,6.039994239807129,-0.3458522233447985,1739141166.525037,6.039994239807129,9.864929583424086,1739141166.5250404,6.039994239807129,18.287766805688616,1739141166.5250418,6.039994239807129,-0.15431156680110875,1739141166.525044,6.039994239807129,0.024549830588394342,1739141166.5250459,6.039994239807129,0.4276585838647198,1739141166.5250473,6.039994239807129,0.05393856868282945,1739141166.5250487,6.039994239807129,2.106920280015767,1739141166.5250506,6.039994239807129,0.0,1739141166.525052,6.039994239807129,-0.03603259013940985,1739141166.5250537,6.039994239807129,6.252900022118798,1739141166.525056,6.039994239807129,2.142952870155177 +1739141166.5463762,6.059994220733643,10.48721705600599,1739141166.546379,6.059994220733643,-0.3458522233447985,1739141166.546383,6.059994220733643,9.864929583424086,1739141166.546386,6.059994220733643,18.287766805688616,1739141166.5463877,6.059994220733643,-0.15431156680110875,1739141166.5463896,6.059994220733643,0.024549830588394342,1739141166.5463912,6.059994220733643,0.4276585838647198,1739141166.546393,6.059994220733643,0.05393856868282945,1739141166.5463943,6.059994220733643,2.106920280015767,1739141166.5463963,6.059994220733643,0.0,1739141166.546398,6.059994220733643,-0.03603259013940985,1739141166.546399,6.059994220733643,6.252900022118798,1739141166.5464008,6.059994220733643,2.142952870155177 +1739141166.5653965,6.079994201660156,10.48721705600599,1739141166.5654006,6.079994201660156,-0.3458522233447985,1739141166.5654044,6.079994201660156,9.864929583424086,1739141166.5654078,6.079994201660156,18.287766805688616,1739141166.5654094,6.079994201660156,-0.15431156680110875,1739141166.5654116,6.079994201660156,0.024549830588394342,1739141166.5654135,6.079994201660156,0.4276585838647198,1739141166.565415,6.079994201660156,0.05393856868282945,1739141166.5654168,6.079994201660156,2.106920280015767,1739141166.5654187,6.079994201660156,0.0,1739141166.5654209,6.079994201660156,-0.03603259013940985,1739141166.5654225,6.079994201660156,6.252900022118798,1739141166.5654242,6.079994201660156,2.142952870155177 +1739141166.585114,6.09999418258667,10.48721705600599,1739141166.585117,6.09999418258667,-0.3458522233447985,1739141166.5851207,6.09999418258667,9.864929583424086,1739141166.5851238,6.09999418258667,18.287766805688616,1739141166.5851257,6.09999418258667,-0.15431156680110875,1739141166.5851274,6.09999418258667,0.024549830588394342,1739141166.585129,6.09999418258667,0.4276585838647198,1739141166.5851305,6.09999418258667,0.05393856868282945,1739141166.5851324,6.09999418258667,2.106920280015767,1739141166.585134,6.09999418258667,0.0,1739141166.585136,6.09999418258667,-0.03603259013940985,1739141166.5851374,6.09999418258667,6.252900022118798,1739141166.585139,6.09999418258667,2.142952870155177 +1739141166.605396,6.119994163513184,10.722643944495465,1739141166.6053996,6.119994163513184,-0.35291922564699707,1739141166.6054037,6.119994163513184,9.875295433519927,1739141166.6054072,6.119994163513184,18.286547586755205,1739141166.6054087,6.119994163513184,-0.15434179536970566,1739141166.605411,6.119994163513184,0.026247270761615545,1739141166.6054127,6.119994163513184,0.42292982995014616,1739141166.6054144,6.119994163513184,0.05672657594245395,1739141166.6054158,6.119994163513184,2.1109092944487005,1739141166.6054177,6.119994163513184,0.0,1739141166.6054196,6.119994163513184,-0.021044637057136627,1739141166.6054213,6.119994163513184,6.253508463460538,1739141166.6054227,6.119994163513184,2.1390910555865106 +1739141166.6249928,6.139994144439697,10.722643944495465,1739141166.6249955,6.139994144439697,-0.35291922564699707,1739141166.6249986,6.139994144439697,9.875295433519927,1739141166.6250017,6.139994144439697,18.286547586755205,1739141166.6250033,6.139994144439697,-0.15434179536970566,1739141166.625005,6.139994144439697,0.026247270761615545,1739141166.625007,6.139994144439697,0.42292982995014616,1739141166.6250083,6.139994144439697,0.05672657594245395,1739141166.62501,6.139994144439697,2.1109092944487005,1739141166.625012,6.139994144439697,0.0,1739141166.6250136,6.139994144439697,-0.028181761137810124,1739141166.625015,6.139994144439697,6.253508463460538,1739141166.6250162,6.139994144439697,2.1390910555865106 +1739141166.6448975,6.159994125366211,10.722643944495465,1739141166.6449003,6.159994125366211,-0.35291922564699707,1739141166.6449037,6.159994125366211,9.875295433519927,1739141166.644907,6.159994125366211,18.286547586755205,1739141166.6449084,6.159994125366211,-0.15434179536970566,1739141166.6449106,6.159994125366211,0.026247270761615545,1739141166.6449127,6.159994125366211,0.42292982995014616,1739141166.6449142,6.159994125366211,0.05672657594245395,1739141166.6449153,6.159994125366211,2.1109092944487005,1739141166.6449172,6.159994125366211,0.0,1739141166.6449192,6.159994125366211,-0.028181761137810124,1739141166.6449206,6.159994125366211,6.253508463460538,1739141166.644922,6.159994125366211,2.1390910555865106 +1739141166.6654038,6.179994106292725,10.722643944495465,1739141166.66541,6.179994106292725,-0.35291922564699707,1739141166.665417,6.179994106292725,9.875295433519927,1739141166.6654248,6.179994106292725,18.286547586755205,1739141166.6654294,6.179994106292725,-0.15434179536970566,1739141166.6654348,6.179994106292725,0.026247270761615545,1739141166.6654403,6.179994106292725,0.42292982995014616,1739141166.665445,6.179994106292725,0.05672657594245395,1739141166.66545,6.179994106292725,2.1109092944487005,1739141166.6654553,6.179994106292725,0.0,1739141166.6654606,6.179994106292725,-0.028181761137810124,1739141166.6654627,6.179994106292725,6.253508463460538,1739141166.6654644,6.179994106292725,2.1390910555865106 +1739141166.6849747,6.199994087219238,10.722643944495465,1739141166.6849773,6.199994087219238,-0.35291922564699707,1739141166.684981,6.199994087219238,9.875295433519927,1739141166.6849842,6.199994087219238,18.286547586755205,1739141166.6849859,6.199994087219238,-0.15434179536970566,1739141166.684988,6.199994087219238,0.026247270761615545,1739141166.6849897,6.199994087219238,0.42292982995014616,1739141166.684991,6.199994087219238,0.05672657594245395,1739141166.6849926,6.199994087219238,2.1109092944487005,1739141166.6849945,6.199994087219238,0.0,1739141166.6849961,6.199994087219238,-0.028181761137810124,1739141166.6849973,6.199994087219238,6.253508463460538,1739141166.684999,6.199994087219238,2.1390910555865106 +1739141166.7051852,6.219994068145752,10.722643944495465,1739141166.7051885,6.219994068145752,-0.35291922564699707,1739141166.7051926,6.219994068145752,9.875295433519927,1739141166.7051969,6.219994068145752,18.286547586755205,1739141166.7051985,6.219994068145752,-0.15434179536970566,1739141166.7052007,6.219994068145752,0.026247270761615545,1739141166.7052023,6.219994068145752,0.42292982995014616,1739141166.7052045,6.219994068145752,0.05672657594245395,1739141166.705206,6.219994068145752,2.1109092944487005,1739141166.705208,6.219994068145752,0.0,1739141166.70521,6.219994068145752,-0.028181761137810124,1739141166.7052116,6.219994068145752,6.253508463460538,1739141166.705213,6.219994068145752,2.1390910555865106 +1739141166.7250335,6.239994049072266,10.957701644172095,1739141166.7250364,6.239994049072266,-0.35981914304728146,1739141166.7250397,6.239994049072266,10.155883542907787,1739141166.725043,6.239994049072266,18.558249556190994,1739141166.7250445,6.239994049072266,-0.14904584073015012,1739141166.7250462,6.239994049072266,0.027724224565982152,1739141166.725048,6.239994049072266,0.43051847418398487,1739141166.7250495,6.239994049072266,0.057184292416313495,1739141166.7250512,6.239994049072266,2.104511433720787,1739141166.7250528,6.239994049072266,0.0,1739141166.7250547,6.239994049072266,-0.034775181590409925,1739141166.7250564,6.239994049072266,6.2542579170276715,1739141166.7250578,6.239994049072266,2.136146889717719 +1739141166.7452493,6.259994029998779,10.957701644172095,1739141166.7452526,6.259994029998779,-0.35981914304728146,1739141166.7452562,6.259994029998779,10.155883542907787,1739141166.7452595,6.259994029998779,18.558249556190994,1739141166.745261,6.259994029998779,-0.14904584073015012,1739141166.7452629,6.259994029998779,0.027724224565982152,1739141166.7452645,6.259994029998779,0.43051847418398487,1739141166.7452662,6.259994029998779,0.057184292416313495,1739141166.7452676,6.259994029998779,2.104511433720787,1739141166.7452695,6.259994029998779,0.0,1739141166.7452712,6.259994029998779,-0.031635455996932293,1739141166.7452729,6.259994029998779,6.2542579170276715,1739141166.7452743,6.259994029998779,2.136146889717719 +1739141166.7652698,6.279994010925293,10.957701644172095,1739141166.7652733,6.279994010925293,-0.35981914304728146,1739141166.7652767,6.279994010925293,10.155883542907787,1739141166.76528,6.279994010925293,18.558249556190994,1739141166.7652814,6.279994010925293,-0.14904584073015012,1739141166.7652836,6.279994010925293,0.027724224565982152,1739141166.7652855,6.279994010925293,0.43051847418398487,1739141166.765287,6.279994010925293,0.057184292416313495,1739141166.765288,6.279994010925293,2.104511433720787,1739141166.7652905,6.279994010925293,0.0,1739141166.765292,6.279994010925293,-0.031635455996932293,1739141166.7652936,6.279994010925293,6.2542579170276715,1739141166.765295,6.279994010925293,2.136146889717719 +1739141166.784939,6.299993991851807,10.957701644172095,1739141166.784942,6.299993991851807,-0.35981914304728146,1739141166.7849452,6.299993991851807,10.155883542907787,1739141166.784948,6.299993991851807,18.558249556190994,1739141166.78495,6.299993991851807,-0.14904584073015012,1739141166.784952,6.299993991851807,0.027724224565982152,1739141166.7849534,6.299993991851807,0.43051847418398487,1739141166.784955,6.299993991851807,0.057184292416313495,1739141166.7849567,6.299993991851807,2.104511433720787,1739141166.7849584,6.299993991851807,0.0,1739141166.78496,6.299993991851807,-0.031635455996932293,1739141166.7849617,6.299993991851807,6.2542579170276715,1739141166.7849636,6.299993991851807,2.136146889717719 +1739141166.8052294,6.31999397277832,10.957701644172095,1739141166.805233,6.31999397277832,-0.35981914304728146,1739141166.8052373,6.31999397277832,10.155883542907787,1739141166.8052409,6.31999397277832,18.558249556190994,1739141166.8052425,6.31999397277832,-0.14904584073015012,1739141166.8052447,6.31999397277832,0.027724224565982152,1739141166.8052464,6.31999397277832,0.43051847418398487,1739141166.805248,6.31999397277832,0.057184292416313495,1739141166.8052495,6.31999397277832,2.104511433720787,1739141166.8052518,6.31999397277832,0.0,1739141166.8052533,6.31999397277832,-0.031635455996932293,1739141166.805255,6.31999397277832,6.2542579170276715,1739141166.8052566,6.31999397277832,2.136146889717719 +1739141166.8250153,6.339993953704834,11.192406810504824,1739141166.825018,6.339993953704834,-0.3665280717413859,1739141166.8250215,6.339993953704834,10.95160525613892,1739141166.8250248,6.339993953704834,19.343357813543463,1739141166.8250263,6.339993953704834,-0.135,1739141166.8250284,6.339993953704834,0.02839740204584895,1739141166.82503,6.339993953704834,0.46090148292246863,1739141166.8250318,6.339993953704834,0.05323005485573851,1739141166.8250332,6.339993953704834,2.079089668848785,1739141166.8250353,6.339993953704834,0.0,1739141166.8250368,6.339993953704834,-0.07350674812971436,1739141166.8250382,6.339993953704834,6.255029635945174,1739141166.8250396,6.339993953704834,2.1326576964788173 +1739141166.8449032,6.359993934631348,11.192406810504824,1739141166.8449075,6.359993934631348,-0.3665280717413859,1739141166.8449118,6.359993934631348,10.95160525613892,1739141166.8449159,6.359993934631348,19.343357813543463,1739141166.844918,6.359993934631348,-0.135,1739141166.8449206,6.359993934631348,0.02839740204584895,1739141166.8449228,6.359993934631348,0.46090148292246863,1739141166.844925,6.359993934631348,0.05323005485573851,1739141166.8449268,6.359993934631348,2.079089668848785,1739141166.8449292,6.359993934631348,0.0,1739141166.8449316,6.359993934631348,-0.05356802763003232,1739141166.8449333,6.359993934631348,6.255029635945174,1739141166.8449357,6.359993934631348,2.1326576964788173 +1739141166.8653128,6.379993915557861,11.192406810504824,1739141166.8653166,6.379993915557861,-0.3665280717413859,1739141166.86532,6.379993915557861,10.95160525613892,1739141166.865323,6.379993915557861,19.343357813543463,1739141166.8653245,6.379993915557861,-0.135,1739141166.8653266,6.379993915557861,0.02839740204584895,1739141166.865328,6.379993915557861,0.46090148292246863,1739141166.86533,6.379993915557861,0.05323005485573851,1739141166.8653312,6.379993915557861,2.079089668848785,1739141166.8653336,6.379993915557861,0.0,1739141166.8653352,6.379993915557861,-0.05356802763003232,1739141166.865337,6.379993915557861,6.255029635945174,1739141166.8653383,6.379993915557861,2.1326576964788173 +1739141166.8850424,6.399993896484375,11.192406810504824,1739141166.8850455,6.399993896484375,-0.3665280717413859,1739141166.8850489,6.399993896484375,10.95160525613892,1739141166.885052,6.399993896484375,19.343357813543463,1739141166.8850536,6.399993896484375,-0.135,1739141166.8850558,6.399993896484375,0.02839740204584895,1739141166.8850574,6.399993896484375,0.46090148292246863,1739141166.885059,6.399993896484375,0.05323005485573851,1739141166.8850605,6.399993896484375,2.079089668848785,1739141166.8850625,6.399993896484375,0.0,1739141166.8850641,6.399993896484375,-0.05356802763003232,1739141166.8850658,6.399993896484375,6.255029635945174,1739141166.885067,6.399993896484375,2.1326576964788173 +1739141166.9054675,6.419993877410889,11.192406810504824,1739141166.9054713,6.419993877410889,-0.3665280717413859,1739141166.9054754,6.419993877410889,10.95160525613892,1739141166.9054792,6.419993877410889,19.343357813543463,1739141166.905481,6.419993877410889,-0.135,1739141166.9054835,6.419993877410889,0.02839740204584895,1739141166.9054854,6.419993877410889,0.46090148292246863,1739141166.9054868,6.419993877410889,0.05323005485573851,1739141166.905489,6.419993877410889,2.079089668848785,1739141166.905491,6.419993877410889,0.0,1739141166.9054933,6.419993877410889,-0.05356802763003232,1739141166.905495,6.419993877410889,6.255029635945174,1739141166.905497,6.419993877410889,2.1326576964788173 +1739141166.9256842,6.439993858337402,11.192406810504824,1739141166.925688,6.439993858337402,-0.3665280717413859,1739141166.925693,6.439993858337402,10.95160525613892,1739141166.925697,6.439993858337402,19.343357813543463,1739141166.9256992,6.439993858337402,-0.135,1739141166.9257019,6.439993858337402,0.02839740204584895,1739141166.925704,6.439993858337402,0.46090148292246863,1739141166.925706,6.439993858337402,0.05323005485573851,1739141166.9257078,6.439993858337402,2.079089668848785,1739141166.92571,6.439993858337402,0.0,1739141166.925712,6.439993858337402,-0.05356802763003232,1739141166.9257143,6.439993858337402,6.255029635945174,1739141166.925716,6.439993858337402,2.1326576964788173 +1739141166.946028,6.459993839263916,11.426577059761073,1739141166.946033,6.459993839263916,-0.37304087130804486,1739141166.9460385,6.459993839263916,10.956763514422125,1739141166.9460425,6.459993839263916,19.32973481197174,1739141166.9460447,6.459993839263916,-0.13509466544561566,1739141166.9460473,6.459993839263916,0.03009864599671951,1739141166.9460495,6.459993839263916,0.45424964367620835,1739141166.9460514,6.459993839263916,0.055797010774156774,1739141166.9460533,6.459993839263916,2.084628942955314,1739141166.946056,6.459993839263916,0.0,1739141166.946058,6.459993839263916,-0.031041075631644103,1739141166.9460597,6.459993839263916,6.255801354862678,1739141166.9460618,6.459993839263916,2.1263971439448586 +1739141166.966084,6.47999382019043,11.426577059761073,1739141166.9660876,6.47999382019043,-0.37304087130804486,1739141166.966092,6.47999382019043,10.956763514422125,1739141166.9660962,6.47999382019043,19.32973481197174,1739141166.9660978,6.47999382019043,-0.13509466544561566,1739141166.9661002,6.47999382019043,0.03009864599671951,1739141166.9661024,6.47999382019043,0.45424964367620835,1739141166.9661043,6.47999382019043,0.055797010774156774,1739141166.9661062,6.47999382019043,2.084628942955314,1739141166.9661083,6.47999382019043,0.0,1739141166.9661107,6.47999382019043,-0.04176820098954437,1739141166.9661129,6.47999382019043,6.255801354862678,1739141166.9661145,6.47999382019043,2.1263971439448586 +1739141166.985772,6.499993801116943,11.426577059761073,1739141166.9857762,6.499993801116943,-0.37304087130804486,1739141166.9857805,6.499993801116943,10.956763514422125,1739141166.9857845,6.499993801116943,19.32973481197174,1739141166.9857867,6.499993801116943,-0.13509466544561566,1739141166.9857893,6.499993801116943,0.03009864599671951,1739141166.9857912,6.499993801116943,0.45424964367620835,1739141166.9857934,6.499993801116943,0.055797010774156774,1739141166.985795,6.499993801116943,2.084628942955314,1739141166.9857976,6.499993801116943,0.0,1739141166.9857998,6.499993801116943,-0.04176820098954437,1739141166.9858015,6.499993801116943,6.255801354862678,1739141166.9858036,6.499993801116943,2.1263971439448586 +1739141167.0064647,6.519993782043457,11.426577059761073,1739141167.0064845,6.519993782043457,-0.37304087130804486,1739141167.0064898,6.519993782043457,10.956763514422125,1739141167.0064945,6.519993782043457,19.32973481197174,1739141167.0064964,6.519993782043457,-0.13509466544561566,1739141167.0064988,6.519993782043457,0.03009864599671951,1739141167.006501,6.519993782043457,0.45424964367620835,1739141167.0065026,6.519993782043457,0.055797010774156774,1739141167.0065045,6.519993782043457,2.084628942955314,1739141167.006507,6.519993782043457,0.0,1739141167.006509,6.519993782043457,-0.04176820098954437,1739141167.0065112,6.519993782043457,6.255801354862678,1739141167.0065129,6.519993782043457,2.1263971439448586 +1739141167.0257363,6.539993762969971,11.426577059761073,1739141167.025744,6.539993762969971,-0.37304087130804486,1739141167.0257533,6.539993762969971,10.956763514422125,1739141167.0257633,6.539993762969971,19.32973481197174,1739141167.025769,6.539993762969971,-0.13509466544561566,1739141167.0257761,6.539993762969971,0.03009864599671951,1739141167.0257828,6.539993762969971,0.45424964367620835,1739141167.0257883,6.539993762969971,0.055797010774156774,1739141167.025791,6.539993762969971,2.084628942955314,1739141167.0257933,6.539993762969971,0.0,1739141167.0257957,6.539993762969971,-0.04176820098954437,1739141167.0257978,6.539993762969971,6.255801354862678,1739141167.0258,6.539993762969971,2.1263971439448586 +1739141167.0458794,6.559993743896484,11.660173268276314,1739141167.0458837,6.559993743896484,-0.37935728721462336,1739141167.045888,6.559993743896484,10.961908947425368,1739141167.045892,6.559993743896484,19.321465683092114,1739141167.045894,6.559993743896484,-0.13516415392359568,1739141167.0458965,6.559993743896484,0.03186283413446246,1739141167.0458984,6.559993743896484,0.44796670551020923,1739141167.0459006,6.559993743896484,0.05854728370927527,1739141167.0459023,6.559993743896484,2.089874569683075,1739141167.0459046,6.559993743896484,0.0,1739141167.0459068,6.559993743896484,-0.02321708909166399,1739141167.0459087,6.559993743896484,6.2565730737801815,1739141167.0459106,6.559993743896484,2.121925525996156 +1739141167.0658116,6.579993724822998,11.660173268276314,1739141167.0658152,6.579993724822998,-0.37935728721462336,1739141167.0658197,6.579993724822998,10.961908947425368,1739141167.0658238,6.579993724822998,19.321465683092114,1739141167.0658257,6.579993724822998,-0.13516415392359568,1739141167.0658283,6.579993724822998,0.03186283413446246,1739141167.0658305,6.579993724822998,0.44796670551020923,1739141167.0658321,6.579993724822998,0.05854728370927527,1739141167.065834,6.579993724822998,2.089874569683075,1739141167.0658362,6.579993724822998,0.0,1739141167.0658386,6.579993724822998,-0.03205095631308108,1739141167.0658405,6.579993724822998,6.2565730737801815,1739141167.0658422,6.579993724822998,2.121925525996156 +1739141167.0858374,6.599993705749512,11.660173268276314,1739141167.0858414,6.599993705749512,-0.37935728721462336,1739141167.0858457,6.599993705749512,10.961908947425368,1739141167.0858495,6.599993705749512,19.321465683092114,1739141167.0858517,6.599993705749512,-0.13516415392359568,1739141167.0858543,6.599993705749512,0.03186283413446246,1739141167.0858562,6.599993705749512,0.44796670551020923,1739141167.085858,6.599993705749512,0.05854728370927527,1739141167.08586,6.599993705749512,2.089874569683075,1739141167.0858624,6.599993705749512,0.0,1739141167.0858645,6.599993705749512,-0.03205095631308108,1739141167.0858665,6.599993705749512,6.2565730737801815,1739141167.0858686,6.599993705749512,2.121925525996156 +1739141167.1063113,6.619993686676025,11.660173268276314,1739141167.1063154,6.619993686676025,-0.37935728721462336,1739141167.1063194,6.619993686676025,10.961908947425368,1739141167.1063237,6.619993686676025,19.321465683092114,1739141167.106326,6.619993686676025,-0.13516415392359568,1739141167.1063285,6.619993686676025,0.03186283413446246,1739141167.1063304,6.619993686676025,0.44796670551020923,1739141167.1063323,6.619993686676025,0.05854728370927527,1739141167.1063342,6.619993686676025,2.089874569683075,1739141167.1063368,6.619993686676025,0.0,1739141167.1063387,6.619993686676025,-0.03205095631308108,1739141167.106341,6.619993686676025,6.2565730737801815,1739141167.1063426,6.619993686676025,2.121925525996156 +1739141167.1268954,6.639993667602539,11.660173268276314,1739141167.1268997,6.639993667602539,-0.37935728721462336,1739141167.1269045,6.639993667602539,10.961908947425368,1739141167.1269088,6.639993667602539,19.321465683092114,1739141167.1269104,6.639993667602539,-0.13516415392359568,1739141167.126913,6.639993667602539,0.03186283413446246,1739141167.126915,6.639993667602539,0.44796670551020923,1739141167.1269171,6.639993667602539,0.05854728370927527,1739141167.126919,6.639993667602539,2.089874569683075,1739141167.1269217,6.639993667602539,0.0,1739141167.1269238,6.639993667602539,-0.03205095631308108,1739141167.1269257,6.639993667602539,6.2565730737801815,1739141167.1269279,6.639993667602539,2.121925525996156 +1739141167.1457613,6.659993648529053,11.660173268276314,1739141167.145765,6.659993648529053,-0.37935728721462336,1739141167.1457698,6.659993648529053,10.961908947425368,1739141167.145774,6.659993648529053,19.321465683092114,1739141167.1457758,6.659993648529053,-0.13516415392359568,1739141167.1457784,6.659993648529053,0.03186283413446246,1739141167.1457806,6.659993648529053,0.44796670551020923,1739141167.1457825,6.659993648529053,0.05854728370927527,1739141167.1457844,6.659993648529053,2.089874569683075,1739141167.1457865,6.659993648529053,0.0,1739141167.1457887,6.659993648529053,-0.03205095631308108,1739141167.1457908,6.659993648529053,6.2565730737801815,1739141167.1457927,6.659993648529053,2.121925525996156 +1739141167.1665916,6.679993629455566,11.893345752174335,1739141167.1665952,6.679993629455566,-0.38547507684147053,1739141167.1665995,6.679993629455566,10.967044859860751,1739141167.1666033,6.679993629455566,19.316599087462787,1739141167.1666052,6.679993629455566,-0.13520504968518668,1739141167.1666079,6.679993629455566,0.03370156679498722,1739141167.16661,6.679993629455566,0.44143489776499323,1739141167.1666117,6.679993629455566,0.06144481230491186,1739141167.1666136,6.679993629455566,2.0953419725380646,1739141167.1666157,6.679993629455566,0.0,1739141167.1666183,6.679993629455566,-0.01524783784562484,1739141167.1666203,6.679993629455566,6.257419096954155,1739141167.166622,6.679993629455566,2.118591299365286 +1739141167.1857874,6.69999361038208,11.893345752174335,1739141167.1857922,6.69999361038208,-0.38547507684147053,1739141167.1857965,6.69999361038208,10.967044859860751,1739141167.1858008,6.69999361038208,19.316599087462787,1739141167.1858027,6.69999361038208,-0.13520504968518668,1739141167.1858053,6.69999361038208,0.03370156679498722,1739141167.1858075,6.69999361038208,0.44143489776499323,1739141167.1858094,6.69999361038208,0.06144481230491186,1739141167.1858113,6.69999361038208,2.0953419725380646,1739141167.1858134,6.69999361038208,0.0,1739141167.1858156,6.69999361038208,-0.02324932682722114,1739141167.1858172,6.69999361038208,6.257419096954155,1739141167.1858194,6.69999361038208,2.118591299365286 +1739141167.2058785,6.719993591308594,11.893345752174335,1739141167.205882,6.719993591308594,-0.38547507684147053,1739141167.2058866,6.719993591308594,10.967044859860751,1739141167.2058911,6.719993591308594,19.316599087462787,1739141167.2058928,6.719993591308594,-0.13520504968518668,1739141167.2058954,6.719993591308594,0.03370156679498722,1739141167.2058978,6.719993591308594,0.44143489776499323,1739141167.2058995,6.719993591308594,0.06144481230491186,1739141167.2059014,6.719993591308594,2.0953419725380646,1739141167.2059038,6.719993591308594,0.0,1739141167.205906,6.719993591308594,-0.02324932682722114,1739141167.2059078,6.719993591308594,6.257419096954155,1739141167.2059097,6.719993591308594,2.118591299365286 +1739141167.2254694,6.739993572235107,11.893345752174335,1739141167.225473,6.739993572235107,-0.38547507684147053,1739141167.2254772,6.739993572235107,10.967044859860751,1739141167.225481,6.739993572235107,19.316599087462787,1739141167.2254825,6.739993572235107,-0.13520504968518668,1739141167.2254848,6.739993572235107,0.03370156679498722,1739141167.2254865,6.739993572235107,0.44143489776499323,1739141167.2254884,6.739993572235107,0.06144481230491186,1739141167.2254899,6.739993572235107,2.0953419725380646,1739141167.225492,6.739993572235107,0.0,1739141167.2254937,6.739993572235107,-0.02324932682722114,1739141167.2254953,6.739993572235107,6.257419096954155,1739141167.225497,6.739993572235107,2.118591299365286 +1739141167.2453449,6.759993553161621,11.893345752174335,1739141167.2453477,6.759993553161621,-0.38547507684147053,1739141167.2453513,6.759993553161621,10.967044859860751,1739141167.2453547,6.759993553161621,19.316599087462787,1739141167.2453566,6.759993553161621,-0.13520504968518668,1739141167.2453587,6.759993553161621,0.03370156679498722,1739141167.2453604,6.759993553161621,0.44143489776499323,1739141167.2453618,6.759993553161621,0.06144481230491186,1739141167.2453635,6.759993553161621,2.0953419725380646,1739141167.2453656,6.759993553161621,0.0,1739141167.2453673,6.759993553161621,-0.02324932682722114,1739141167.2453687,6.759993553161621,6.257419096954155,1739141167.2453704,6.759993553161621,2.118591299365286 +1739141167.2654257,6.779993534088135,12.126193505958138,1739141167.2654293,6.779993534088135,-0.39137996479429393,1739141167.2654335,6.779993534088135,11.376471828140128,1739141167.2654378,6.779993534088135,19.71860136755612,1739141167.2654397,6.779993534088135,-0.13282832193703237,1739141167.2654424,6.779993534088135,0.03404081708123689,1739141167.2654443,6.779993534088135,0.4470916025508449,1739141167.2654462,6.779993534088135,0.059489236516349825,1739141167.2654476,6.779993534088135,2.0906062399012106,1739141167.2654498,6.779993534088135,0.0,1739141167.2654514,6.779993534088135,-0.027572861268331327,1739141167.265453,6.779993534088135,6.258339544130755,1739141167.2654548,6.779993534088135,2.1161202742167298 +1739141167.2852585,6.799993515014648,12.126193505958138,1739141167.2852619,6.799993515014648,-0.39137996479429393,1739141167.2852654,6.799993515014648,11.376471828140128,1739141167.2852688,6.799993515014648,19.71860136755612,1739141167.2852705,6.799993515014648,-0.13282832193703237,1739141167.2852726,6.799993515014648,0.03404081708123689,1739141167.2852743,6.799993515014648,0.4470916025508449,1739141167.2852762,6.799993515014648,0.059489236516349825,1739141167.2852778,6.799993515014648,2.0906062399012106,1739141167.28528,6.799993515014648,0.0,1739141167.285282,6.799993515014648,-0.02551403431551913,1739141167.2852833,6.799993515014648,6.258339544130755,1739141167.2852848,6.799993515014648,2.1161202742167298 +1739141167.305319,6.819993495941162,12.126193505958138,1739141167.3053236,6.819993495941162,-0.39137996479429393,1739141167.3053274,6.819993495941162,11.376471828140128,1739141167.3053315,6.819993495941162,19.71860136755612,1739141167.3053336,6.819993495941162,-0.13282832193703237,1739141167.3053358,6.819993495941162,0.03404081708123689,1739141167.3053377,6.819993495941162,0.4470916025508449,1739141167.3053393,6.819993495941162,0.059489236516349825,1739141167.3053412,6.819993495941162,2.0906062399012106,1739141167.3053434,6.819993495941162,0.0,1739141167.305346,6.819993495941162,-0.02551403431551913,1739141167.305348,6.819993495941162,6.258339544130755,1739141167.3053498,6.819993495941162,2.1161202742167298 +1739141167.3252037,6.839993476867676,12.126193505958138,1739141167.3252068,6.839993476867676,-0.39137996479429393,1739141167.32521,6.839993476867676,11.376471828140128,1739141167.3252137,6.839993476867676,19.71860136755612,1739141167.3252156,6.839993476867676,-0.13282832193703237,1739141167.3252175,6.839993476867676,0.03404081708123689,1739141167.3252196,6.839993476867676,0.4470916025508449,1739141167.3252213,6.839993476867676,0.059489236516349825,1739141167.325223,6.839993476867676,2.0906062399012106,1739141167.3252249,6.839993476867676,0.0,1739141167.3252268,6.839993476867676,-0.02551403431551913,1739141167.3252282,6.839993476867676,6.258339544130755,1739141167.3252304,6.839993476867676,2.1161202742167298 +1739141167.3452013,6.8599934577941895,12.126193505958138,1739141167.3452046,6.8599934577941895,-0.39137996479429393,1739141167.3452082,6.8599934577941895,11.376471828140128,1739141167.3452117,6.8599934577941895,19.71860136755612,1739141167.3452132,6.8599934577941895,-0.13282832193703237,1739141167.3452153,6.8599934577941895,0.03404081708123689,1739141167.345217,6.8599934577941895,0.4470916025508449,1739141167.3452191,6.8599934577941895,0.059489236516349825,1739141167.3452206,6.8599934577941895,2.0906062399012106,1739141167.3452227,6.8599934577941895,0.0,1739141167.3452244,6.8599934577941895,-0.02551403431551913,1739141167.3452263,6.8599934577941895,6.258339544130755,1739141167.3452277,6.8599934577941895,2.1161202742167298 +1739141167.365273,6.879993438720703,12.126193505958138,1739141167.3652773,6.879993438720703,-0.39137996479429393,1739141167.3652823,6.879993438720703,11.376471828140128,1739141167.3652864,6.879993438720703,19.71860136755612,1739141167.3652883,6.879993438720703,-0.13282832193703237,1739141167.3652904,6.879993438720703,0.03404081708123689,1739141167.3652923,6.879993438720703,0.4470916025508449,1739141167.365294,6.879993438720703,0.059489236516349825,1739141167.3652956,6.879993438720703,2.0906062399012106,1739141167.3652976,6.879993438720703,0.0,1739141167.3652997,6.879993438720703,-0.02551403431551913,1739141167.3653011,6.879993438720703,6.258339544130755,1739141167.365303,6.879993438720703,2.1161202742167298 +1739141167.3848834,6.899993419647217,12.35875352870449,1739141167.3848863,6.899993419647217,-0.3970603758862996,1739141167.3848894,6.899993419647217,11.501945929017877,1739141167.3848922,6.899993419647217,19.835568065884782,1739141167.3848937,6.899993419647217,-0.13185236919424553,1739141167.3848956,6.899993419647217,0.03545585670107533,1739141167.3848972,6.899993419647217,0.4438890042514415,1739141167.3848987,6.899993419647217,0.06089710694848117,1739141167.3848999,6.899993419647217,2.0932861048363542,1739141167.3849015,6.899993419647217,0.0,1739141167.3849032,6.899993419647217,-0.0149867131251637,1739141167.3849046,6.899993419647217,6.259274878768905,1739141167.3849063,6.899993419647217,2.113285830556382 +1739141167.4051158,6.9199934005737305,12.35875352870449,1739141167.4051194,6.9199934005737305,-0.3970603758862996,1739141167.4051225,6.9199934005737305,11.501945929017877,1739141167.4051256,6.9199934005737305,19.835568065884782,1739141167.4051273,6.9199934005737305,-0.13185236919424553,1739141167.405129,6.9199934005737305,0.03545585670107533,1739141167.4051304,6.9199934005737305,0.4438890042514415,1739141167.4051318,6.9199934005737305,0.06089710694848117,1739141167.4051332,6.9199934005737305,2.0932861048363542,1739141167.405135,6.9199934005737305,0.0,1739141167.4051363,6.9199934005737305,-0.01999972572002795,1739141167.405138,6.9199934005737305,6.259274878768905,1739141167.4051392,6.9199934005737305,2.113285830556382 +1739141167.424967,6.939993381500244,12.35875352870449,1739141167.4249697,6.939993381500244,-0.3970603758862996,1739141167.4249728,6.939993381500244,11.501945929017877,1739141167.4249756,6.939993381500244,19.835568065884782,1739141167.424977,6.939993381500244,-0.13185236919424553,1739141167.424979,6.939993381500244,0.03545585670107533,1739141167.4249804,6.939993381500244,0.4438890042514415,1739141167.4249818,6.939993381500244,0.06089710694848117,1739141167.4249833,6.939993381500244,2.0932861048363542,1739141167.4249852,6.939993381500244,0.0,1739141167.4249866,6.939993381500244,-0.01999972572002795,1739141167.4249878,6.939993381500244,6.259274878768905,1739141167.4249897,6.939993381500244,2.113285830556382 +1739141167.4448447,6.959993362426758,12.35875352870449,1739141167.4448473,6.959993362426758,-0.3970603758862996,1739141167.4448504,6.959993362426758,11.501945929017877,1739141167.4448535,6.959993362426758,19.835568065884782,1739141167.4448552,6.959993362426758,-0.13185236919424553,1739141167.4448571,6.959993362426758,0.03545585670107533,1739141167.4448586,6.959993362426758,0.4438890042514415,1739141167.44486,6.959993362426758,0.06089710694848117,1739141167.4448612,6.959993362426758,2.0932861048363542,1739141167.444863,6.959993362426758,0.0,1739141167.4448645,6.959993362426758,-0.01999972572002795,1739141167.4448657,6.959993362426758,6.259274878768905,1739141167.4448674,6.959993362426758,2.113285830556382 +1739141167.465145,6.9799933433532715,12.35875352870449,1739141167.4651484,6.9799933433532715,-0.3970603758862996,1739141167.4651518,6.9799933433532715,11.501945929017877,1739141167.4651551,6.9799933433532715,19.835568065884782,1739141167.4651566,6.9799933433532715,-0.13185236919424553,1739141167.4651585,6.9799933433532715,0.03545585670107533,1739141167.4651597,6.9799933433532715,0.4438890042514415,1739141167.4651613,6.9799933433532715,0.06089710694848117,1739141167.4651625,6.9799933433532715,2.0932861048363542,1739141167.4651642,6.9799933433532715,0.0,1739141167.4651659,6.9799933433532715,-0.01999972572002795,1739141167.4651673,6.9799933433532715,6.259274878768905,1739141167.465169,6.9799933433532715,2.113285830556382 +1739141167.4849224,6.999993324279785,12.591044452554264,1739141167.4849253,6.999993324279785,-0.40251681359486646,1739141167.4849286,6.999993324279785,11.824564933107883,1739141167.4849312,6.999993324279785,20.151752910076727,1739141167.484933,6.999993324279785,-0.13020205908269394,1739141167.4849348,6.999993324279785,0.036001532909485066,1739141167.4849365,6.999993324279785,0.44593559042900693,1739141167.4849377,6.999993324279785,0.05982569888631464,1739141167.4849393,6.999993324279785,2.0915731699026683,1739141167.484941,6.999993324279785,0.0,1739141167.4849427,6.999993324279785,-0.01917980320524891,1739141167.484944,6.999993324279785,6.260210213407055,1739141167.4849453,6.999993324279785,2.1111434125957107 +1739141167.5051847,7.019993305206299,12.591044452554264,1739141167.505188,7.019993305206299,-0.40251681359486646,1739141167.5051916,7.019993305206299,11.824564933107883,1739141167.5051947,7.019993305206299,20.151752910076727,1739141167.5051963,7.019993305206299,-0.13020205908269394,1739141167.505198,7.019993305206299,0.036001532909485066,1739141167.5051997,7.019993305206299,0.44593559042900693,1739141167.5052013,7.019993305206299,0.05982569888631464,1739141167.505203,7.019993305206299,2.0915731699026683,1739141167.5052044,7.019993305206299,0.0,1739141167.5052063,7.019993305206299,-0.019570242693042417,1739141167.505208,7.019993305206299,6.260210213407055,1739141167.5052094,7.019993305206299,2.1111434125957107 +1739141167.5248322,7.0399932861328125,12.591044452554264,1739141167.5248346,7.0399932861328125,-0.40251681359486646,1739141167.524838,7.0399932861328125,11.824564933107883,1739141167.524841,7.0399932861328125,20.151752910076727,1739141167.5248425,7.0399932861328125,-0.13020205908269394,1739141167.5248442,7.0399932861328125,0.036001532909485066,1739141167.5248458,7.0399932861328125,0.44593559042900693,1739141167.5248473,7.0399932861328125,0.05982569888631464,1739141167.5248487,7.0399932861328125,2.0915731699026683,1739141167.5248504,7.0399932861328125,0.0,1739141167.524852,7.0399932861328125,-0.019570242693042417,1739141167.5248535,7.0399932861328125,6.260210213407055,1739141167.5248551,7.0399932861328125,2.1111434125957107 +1739141167.544934,7.059993267059326,12.591044452554264,1739141167.5449367,7.059993267059326,-0.40251681359486646,1739141167.54494,7.059993267059326,11.824564933107883,1739141167.544943,7.059993267059326,20.151752910076727,1739141167.5449445,7.059993267059326,-0.13020205908269394,1739141167.5449464,7.059993267059326,0.036001532909485066,1739141167.5449479,7.059993267059326,0.44593559042900693,1739141167.5449495,7.059993267059326,0.05982569888631464,1739141167.5449507,7.059993267059326,2.0915731699026683,1739141167.5449526,7.059993267059326,0.0,1739141167.544954,7.059993267059326,-0.019570242693042417,1739141167.5449557,7.059993267059326,6.260210213407055,1739141167.5449572,7.059993267059326,2.1111434125957107 +1739141167.5650194,7.07999324798584,12.591044452554264,1739141167.5650227,7.07999324798584,-0.40251681359486646,1739141167.565026,7.07999324798584,11.824564933107883,1739141167.5650291,7.07999324798584,20.151752910076727,1739141167.5650306,7.07999324798584,-0.13020205908269394,1739141167.5650327,7.07999324798584,0.036001532909485066,1739141167.5650342,7.07999324798584,0.44593559042900693,1739141167.5650356,7.07999324798584,0.05982569888631464,1739141167.565037,7.07999324798584,2.0915731699026683,1739141167.565039,7.07999324798584,0.0,1739141167.5650403,7.07999324798584,-0.019570242693042417,1739141167.565042,7.07999324798584,6.260210213407055,1739141167.5650432,7.07999324798584,2.1111434125957107 +1739141167.5851426,7.0999932289123535,12.591044452554264,1739141167.5851457,7.0999932289123535,-0.40251681359486646,1739141167.58515,7.0999932289123535,11.824564933107883,1739141167.5851533,7.0999932289123535,20.151752910076727,1739141167.5851548,7.0999932289123535,-0.13020205908269394,1739141167.585157,7.0999932289123535,0.036001532909485066,1739141167.5851586,7.0999932289123535,0.44593559042900693,1739141167.5851603,7.0999932289123535,0.05982569888631464,1739141167.5851617,7.0999932289123535,2.0915731699026683,1739141167.5851636,7.0999932289123535,0.0,1739141167.5851655,7.0999932289123535,-0.019570242693042417,1739141167.5851672,7.0999932289123535,6.260210213407055,1739141167.5851686,7.0999932289123535,2.1111434125957107 +1739141167.6055846,7.119993209838867,12.823104605163135,1739141167.6055892,7.119993209838867,-0.407750661850538,1739141167.605595,7.119993209838867,12.231860219556122,1739141167.6056015,7.119993209838867,20.55263978535247,1739141167.6056051,7.119993209838867,-0.129,1739141167.60561,7.119993209838867,0.03604743455611538,1739141167.6056144,7.119993209838867,0.44902626495983733,1739141167.6056185,7.119993209838867,0.05763792208098374,1739141167.6056225,7.119993209838867,2.0889890188155507,1739141167.605627,7.119993209838867,0.0,1739141167.6056316,7.119993209838867,-0.020427544614752255,1739141167.6056356,7.119993209838867,6.261145548045206,1739141167.60564,7.119993209838867,2.1090083242160316 +1739141167.6249998,7.139993190765381,12.823104605163135,1739141167.6250024,7.139993190765381,-0.407750661850538,1739141167.6250062,7.139993190765381,12.231860219556122,1739141167.6250093,7.139993190765381,20.55263978535247,1739141167.6250112,7.139993190765381,-0.129,1739141167.6250134,7.139993190765381,0.03604743455611538,1739141167.6250148,7.139993190765381,0.44902626495983733,1739141167.6250162,7.139993190765381,0.05763792208098374,1739141167.625018,7.139993190765381,2.0889890188155507,1739141167.6250196,7.139993190765381,0.0,1739141167.6250217,7.139993190765381,-0.020019305400480913,1739141167.6250231,7.139993190765381,6.261145548045206,1739141167.6250248,7.139993190765381,2.1090083242160316 +1739141167.6450374,7.1599931716918945,12.823104605163135,1739141167.64504,7.1599931716918945,-0.407750661850538,1739141167.6450436,7.1599931716918945,12.231860219556122,1739141167.6450467,7.1599931716918945,20.55263978535247,1739141167.6450486,7.1599931716918945,-0.129,1739141167.6450503,7.1599931716918945,0.03604743455611538,1739141167.6450522,7.1599931716918945,0.44902626495983733,1739141167.6450536,7.1599931716918945,0.05763792208098374,1739141167.6450553,7.1599931716918945,2.0889890188155507,1739141167.6450572,7.1599931716918945,0.0,1739141167.6450589,7.1599931716918945,-0.020019305400480913,1739141167.6450603,7.1599931716918945,6.261145548045206,1739141167.645062,7.1599931716918945,2.1090083242160316 +1739141167.665155,7.179993152618408,12.823104605163135,1739141167.6651585,7.179993152618408,-0.407750661850538,1739141167.6651623,7.179993152618408,12.231860219556122,1739141167.665166,7.179993152618408,20.55263978535247,1739141167.6651676,7.179993152618408,-0.129,1739141167.6651695,7.179993152618408,0.03604743455611538,1739141167.6651711,7.179993152618408,0.44902626495983733,1739141167.6651728,7.179993152618408,0.05763792208098374,1739141167.6651742,7.179993152618408,2.0889890188155507,1739141167.6651762,7.179993152618408,0.0,1739141167.6651778,7.179993152618408,-0.020019305400480913,1739141167.6651797,7.179993152618408,6.261145548045206,1739141167.6651814,7.179993152618408,2.1090083242160316 +1739141167.6852484,7.199993133544922,12.823104605163135,1739141167.6852515,7.199993133544922,-0.407750661850538,1739141167.685255,7.199993133544922,12.231860219556122,1739141167.6852584,7.199993133544922,20.55263978535247,1739141167.6852603,7.199993133544922,-0.129,1739141167.6852624,7.199993133544922,0.03604743455611538,1739141167.685264,7.199993133544922,0.44902626495983733,1739141167.6852658,7.199993133544922,0.05763792208098374,1739141167.6852672,7.199993133544922,2.0889890188155507,1739141167.6852689,7.199993133544922,0.0,1739141167.6852708,7.199993133544922,-0.020019305400480913,1739141167.6852722,7.199993133544922,6.261145548045206,1739141167.685274,7.199993133544922,2.1090083242160316 +1739141167.7057207,7.2199931144714355,13.05493149711031,1739141167.705724,7.2199931144714355,-0.4127623082022316,1739141167.7057273,7.2199931144714355,12.27800379434631,1739141167.7057307,7.2199931144714355,20.592202246182246,1739141167.7057323,7.2199931144714355,-0.129,1739141167.7057345,7.2199931144714355,0.037630113973564715,1739141167.7057362,7.2199931144714355,0.44275707064753306,1739141167.7057378,7.2199931144714355,0.05976211009007314,1739141167.705739,7.2199931144714355,2.0942341037883963,1739141167.7057412,7.2199931144714355,0.0,1739141167.7057428,7.2199931144714355,-0.005817973300977465,1739141167.7057443,7.2199931144714355,6.262080882683356,1739141167.705746,7.2199931144714355,2.1068146195625608 +1739141167.7251728,7.239993095397949,13.05493149711031,1739141167.7251759,7.239993095397949,-0.4127623082022316,1739141167.7251792,7.239993095397949,12.27800379434631,1739141167.7251825,7.239993095397949,20.592202246182246,1739141167.725184,7.239993095397949,-0.129,1739141167.7251863,7.239993095397949,0.037630113973564715,1739141167.725188,7.239993095397949,0.44275707064753306,1739141167.7251897,7.239993095397949,0.05976211009007314,1739141167.725191,7.239993095397949,2.0942341037883963,1739141167.7251933,7.239993095397949,0.0,1739141167.725195,7.239993095397949,-0.012580515774164525,1739141167.7251966,7.239993095397949,6.262080882683356,1739141167.725198,7.239993095397949,2.1068146195625608 +1739141167.7452102,7.259993076324463,13.05493149711031,1739141167.7452142,7.259993076324463,-0.4127623082022316,1739141167.7452185,7.259993076324463,12.27800379434631,1739141167.7452228,7.259993076324463,20.592202246182246,1739141167.7452252,7.259993076324463,-0.129,1739141167.7452283,7.259993076324463,0.037630113973564715,1739141167.7452307,7.259993076324463,0.44275707064753306,1739141167.7452328,7.259993076324463,0.05976211009007314,1739141167.7452345,7.259993076324463,2.0942341037883963,1739141167.7452369,7.259993076324463,0.0,1739141167.745239,7.259993076324463,-0.012580515774164525,1739141167.7452412,7.259993076324463,6.262080882683356,1739141167.7452433,7.259993076324463,2.1068146195625608 +1739141167.7669816,7.279993057250977,13.05493149711031,1739141167.7669861,7.279993057250977,-0.4127623082022316,1739141167.7669919,7.279993057250977,12.27800379434631,1739141167.7669985,7.279993057250977,20.592202246182246,1739141167.767002,7.279993057250977,-0.129,1739141167.7670066,7.279993057250977,0.037630113973564715,1739141167.7670112,7.279993057250977,0.44275707064753306,1739141167.7670152,7.279993057250977,0.05976211009007314,1739141167.7670193,7.279993057250977,2.0942341037883963,1739141167.7670236,7.279993057250977,0.0,1739141167.7670279,7.279993057250977,-0.012580515774164525,1739141167.7670324,7.279993057250977,6.262080882683356,1739141167.7670364,7.279993057250977,2.1068146195625608 +1739141167.784999,7.29999303817749,13.05493149711031,1739141167.7850018,7.29999303817749,-0.4127623082022316,1739141167.7850053,7.29999303817749,12.27800379434631,1739141167.7850084,7.29999303817749,20.592202246182246,1739141167.78501,7.29999303817749,-0.129,1739141167.7850122,7.29999303817749,0.037630113973564715,1739141167.785014,7.29999303817749,0.44275707064753306,1739141167.7850156,7.29999303817749,0.05976211009007314,1739141167.785017,7.29999303817749,2.0942341037883963,1739141167.7850192,7.29999303817749,0.0,1739141167.7850206,7.29999303817749,-0.012580515774164525,1739141167.7850223,7.29999303817749,6.262080882683356,1739141167.7850237,7.29999303817749,2.1068146195625608 +1739141167.8052173,7.319993019104004,13.05493149711031,1739141167.8052208,7.319993019104004,-0.4127623082022316,1739141167.8052244,7.319993019104004,12.27800379434631,1739141167.805228,7.319993019104004,20.592202246182246,1739141167.80523,7.319993019104004,-0.129,1739141167.8052318,7.319993019104004,0.037630113973564715,1739141167.8052337,7.319993019104004,0.44275707064753306,1739141167.8052354,7.319993019104004,0.05976211009007314,1739141167.8052368,7.319993019104004,2.0942341037883963,1739141167.805239,7.319993019104004,0.0,1739141167.8052409,7.319993019104004,-0.012580515774164525,1739141167.8052423,7.319993019104004,6.262080882683356,1739141167.8052442,7.319993019104004,2.1068146195625608 +1739141167.8250582,7.339993000030518,13.286575355171792,1739141167.825061,7.339993000030518,-0.4175532285016672,1739141167.8250644,7.339993000030518,12.689471128800372,1739141167.8250682,7.339993000030518,20.99993187513421,1739141167.82507,7.339993000030518,-0.12718908299070322,1739141167.8250718,7.339993000030518,0.03762656417329653,1739141167.8250737,7.339993000030518,0.44586592201635744,1739141167.8250751,7.339993000030518,0.05746594668090029,1739141167.8250768,7.339993000030518,2.0916314573478987,1739141167.8250785,7.339993000030518,0.0,1739141167.8250804,7.339993000030518,-0.015175388625331018,1739141167.8250816,7.339993000030518,6.263016217321506,1739141167.825083,7.339993000030518,2.1055711916173157 +1739141167.8449757,7.359992980957031,13.286575355171792,1739141167.844979,7.359992980957031,-0.4175532285016672,1739141167.8449826,7.359992980957031,12.689471128800372,1739141167.844986,7.359992980957031,20.99993187513421,1739141167.8449874,7.359992980957031,-0.12718908299070322,1739141167.8449895,7.359992980957031,0.03762656417329653,1739141167.8449912,7.359992980957031,0.44586592201635744,1739141167.8449929,7.359992980957031,0.05746594668090029,1739141167.8449943,7.359992980957031,2.0916314573478987,1739141167.8449965,7.359992980957031,0.0,1739141167.844998,7.359992980957031,-0.01393973426941697,1739141167.8449993,7.359992980957031,6.263016217321506,1739141167.845001,7.359992980957031,2.1055711916173157 +1739141167.8652866,7.379992961883545,13.286575355171792,1739141167.8652904,7.379992961883545,-0.4175532285016672,1739141167.8652942,7.379992961883545,12.689471128800372,1739141167.8652976,7.379992961883545,20.99993187513421,1739141167.8652995,7.379992961883545,-0.12718908299070322,1739141167.8653016,7.379992961883545,0.03762656417329653,1739141167.865303,7.379992961883545,0.44586592201635744,1739141167.865305,7.379992961883545,0.05746594668090029,1739141167.8653061,7.379992961883545,2.0916314573478987,1739141167.8653085,7.379992961883545,0.0,1739141167.8653104,7.379992961883545,-0.01393973426941697,1739141167.865312,7.379992961883545,6.263016217321506,1739141167.8653138,7.379992961883545,2.1055711916173157 +1739141167.8850536,7.399992942810059,13.286575355171792,1739141167.8850567,7.399992942810059,-0.4175532285016672,1739141167.8850603,7.399992942810059,12.689471128800372,1739141167.8850636,7.399992942810059,20.99993187513421,1739141167.8850656,7.399992942810059,-0.12718908299070322,1739141167.8850675,7.399992942810059,0.03762656417329653,1739141167.8850694,7.399992942810059,0.44586592201635744,1739141167.885071,7.399992942810059,0.05746594668090029,1739141167.8850727,7.399992942810059,2.0916314573478987,1739141167.8850746,7.399992942810059,0.0,1739141167.8850768,7.399992942810059,-0.01393973426941697,1739141167.8850782,7.399992942810059,6.263016217321506,1739141167.8850799,7.399992942810059,2.1055711916173157 +1739141167.9050062,7.419992923736572,13.286575355171792,1739141167.9050095,7.419992923736572,-0.4175532285016672,1739141167.9050136,7.419992923736572,12.689471128800372,1739141167.9050167,7.419992923736572,20.99993187513421,1739141167.9050183,7.419992923736572,-0.12718908299070322,1739141167.9050202,7.419992923736572,0.03762656417329653,1739141167.905022,7.419992923736572,0.44586592201635744,1739141167.9050233,7.419992923736572,0.05746594668090029,1739141167.9050245,7.419992923736572,2.0916314573478987,1739141167.9050267,7.419992923736572,0.0,1739141167.905028,7.419992923736572,-0.01393973426941697,1739141167.9050295,7.419992923736572,6.263016217321506,1739141167.905031,7.419992923736572,2.1055711916173157 +1739141167.9246986,7.439992904663086,13.518065967346864,1739141167.924701,7.439992904663086,-0.42212437187532537,1739141167.9247038,7.439992904663086,12.715171157895181,1739141167.924706,7.439992904663086,21.02102245554249,1739141167.9247077,7.439992904663086,-0.12701620938079927,1739141167.924709,7.439992904663086,0.03931198642388933,1739141167.9247105,7.439992904663086,0.4393547094859417,1739141167.9247117,7.439992904663086,0.0598387763709753,1739141167.924713,7.439992904663086,2.0970861804183407,1739141167.9247146,7.439992904663086,0.0,1739141167.9247158,7.439992904663086,-0.000593331310270514,1739141167.924717,7.439992904663086,6.263951551959657,1739141167.9247181,7.439992904663086,2.1040349448839737 +1739141167.9446235,7.4599928855896,13.518065967346864,1739141167.9446259,7.4599928855896,-0.42212437187532537,1739141167.9446285,7.4599928855896,12.715171157895181,1739141167.9446313,7.4599928855896,21.02102245554249,1739141167.9446325,7.4599928855896,-0.12701620938079927,1739141167.9446342,7.4599928855896,0.03931198642388933,1739141167.9446354,7.4599928855896,0.4393547094859417,1739141167.9446363,7.4599928855896,0.0598387763709753,1739141167.9446378,7.4599928855896,2.0970861804183407,1739141167.9446392,7.4599928855896,0.0,1739141167.9446404,7.4599928855896,-0.006948764465632973,1739141167.9446418,7.4599928855896,6.263951551959657,1739141167.9446428,7.4599928855896,2.1040349448839737 +1739141167.9647958,7.479992866516113,13.518065967346864,1739141167.9647982,7.479992866516113,-0.42212437187532537,1739141167.964801,7.479992866516113,12.715171157895181,1739141167.964804,7.479992866516113,21.02102245554249,1739141167.9648054,7.479992866516113,-0.12701620938079927,1739141167.9648073,7.479992866516113,0.03931198642388933,1739141167.9648085,7.479992866516113,0.4393547094859417,1739141167.9648097,7.479992866516113,0.0598387763709753,1739141167.9648113,7.479992866516113,2.0970861804183407,1739141167.9648128,7.479992866516113,0.0,1739141167.9648144,7.479992866516113,-0.006948764465632973,1739141167.9648159,7.479992866516113,6.263951551959657,1739141167.964817,7.479992866516113,2.1040349448839737 +1739141167.9847069,7.499992847442627,13.518065967346864,1739141167.984709,7.499992847442627,-0.42212437187532537,1739141167.984712,7.499992847442627,12.715171157895181,1739141167.9847145,7.499992847442627,21.02102245554249,1739141167.9847157,7.499992847442627,-0.12701620938079927,1739141167.9847174,7.499992847442627,0.03931198642388933,1739141167.9847186,7.499992847442627,0.4393547094859417,1739141167.9847198,7.499992847442627,0.0598387763709753,1739141167.9847212,7.499992847442627,2.0970861804183407,1739141167.9847224,7.499992847442627,0.0,1739141167.984724,7.499992847442627,-0.006948764465632973,1739141167.9847252,7.499992847442627,6.263951551959657,1739141167.9847264,7.499992847442627,2.1040349448839737 +1739141168.004916,7.519992828369141,13.518065967346864,1739141168.0049188,7.519992828369141,-0.42212437187532537,1739141168.0049217,7.519992828369141,12.715171157895181,1739141168.0049238,7.519992828369141,21.02102245554249,1739141168.0049255,7.519992828369141,-0.12701620938079927,1739141168.004927,7.519992828369141,0.03931198642388933,1739141168.0049284,7.519992828369141,0.4393547094859417,1739141168.0049295,7.519992828369141,0.0598387763709753,1739141168.0049307,7.519992828369141,2.0970861804183407,1739141168.0049324,7.519992828369141,0.0,1739141168.0049336,7.519992828369141,-0.006948764465632973,1739141168.004935,7.519992828369141,6.263951551959657,1739141168.0049362,7.519992828369141,2.1040349448839737 +1739141168.024679,7.539992809295654,13.518065967346864,1739141168.0246813,7.539992809295654,-0.42212437187532537,1739141168.024684,7.539992809295654,12.715171157895181,1739141168.0246868,7.539992809295654,21.02102245554249,1739141168.0246885,7.539992809295654,-0.12701620938079927,1739141168.02469,7.539992809295654,0.03931198642388933,1739141168.0246913,7.539992809295654,0.4393547094859417,1739141168.0246925,7.539992809295654,0.0598387763709753,1739141168.0246937,7.539992809295654,2.0970861804183407,1739141168.0246954,7.539992809295654,0.0,1739141168.0246968,7.539992809295654,-0.006948764465632973,1739141168.0246978,7.539992809295654,6.263951551959657,1739141168.0246992,7.539992809295654,2.1040349448839737 +1739141168.0446956,7.559992790222168,13.74944278563942,1739141168.044698,7.559992790222168,-0.4264767655976467,1739141168.0447006,7.559992790222168,12.937330841532484,1739141168.0447035,7.559992790222168,21.241277511871086,1739141168.0447047,7.559992790222168,-0.127,1739141168.0447066,7.559992790222168,0.03995248398753828,1739141168.0447078,7.559992790222168,0.4365077223554712,1739141168.0447092,7.559992790222168,0.059624696362112414,1739141168.0447106,7.559992790222168,2.0994756916885255,1739141168.0447118,7.559992790222168,0.0,1739141168.0447135,7.559992790222168,-0.0011749743145391556,1739141168.0447147,7.559992790222168,6.264886886597807,1739141168.0447161,7.559992790222168,2.103400091257996 +1739141168.0647721,7.579992771148682,13.74944278563942,1739141168.0647748,7.579992771148682,-0.4264767655976467,1739141168.0647774,7.579992771148682,12.937330841532484,1739141168.06478,7.579992771148682,21.241277511871086,1739141168.0647814,7.579992771148682,-0.127,1739141168.0647829,7.579992771148682,0.03995248398753828,1739141168.064784,7.579992771148682,0.4365077223554712,1739141168.0647855,7.579992771148682,0.059624696362112414,1739141168.0647864,7.579992771148682,2.0994756916885255,1739141168.0647879,7.579992771148682,0.0,1739141168.0647895,7.579992771148682,-0.003924399569470438,1739141168.0647907,7.579992771148682,6.264886886597807,1739141168.0647922,7.579992771148682,2.103400091257996 +1739141168.084671,7.599992752075195,13.74944278563942,1739141168.0846732,7.599992752075195,-0.4264767655976467,1739141168.084676,7.599992752075195,12.937330841532484,1739141168.084679,7.599992752075195,21.241277511871086,1739141168.08468,7.599992752075195,-0.127,1739141168.084682,7.599992752075195,0.03995248398753828,1739141168.0846834,7.599992752075195,0.4365077223554712,1739141168.0846848,7.599992752075195,0.059624696362112414,1739141168.084686,7.599992752075195,2.0994756916885255,1739141168.0846877,7.599992752075195,0.0,1739141168.084689,7.599992752075195,-0.003924399569470438,1739141168.08469,7.599992752075195,6.264886886597807,1739141168.0846915,7.599992752075195,2.103400091257996 +1739141168.1048164,7.619992733001709,13.74944278563942,1739141168.1048195,7.619992733001709,-0.4264767655976467,1739141168.1048222,7.619992733001709,12.937330841532484,1739141168.1048248,7.619992733001709,21.241277511871086,1739141168.1048262,7.619992733001709,-0.127,1739141168.104828,7.619992733001709,0.03995248398753828,1739141168.104829,7.619992733001709,0.4365077223554712,1739141168.1048307,7.619992733001709,0.059624696362112414,1739141168.104832,7.619992733001709,2.0994756916885255,1739141168.1048336,7.619992733001709,0.0,1739141168.1048348,7.619992733001709,-0.003924399569470438,1739141168.104836,7.619992733001709,6.264886886597807,1739141168.1048374,7.619992733001709,2.103400091257996 +1739141168.1246572,7.639992713928223,13.74944278563942,1739141168.12466,7.639992713928223,-0.4264767655976467,1739141168.1246629,7.639992713928223,12.937330841532484,1739141168.1246655,7.639992713928223,21.241277511871086,1739141168.124667,7.639992713928223,-0.127,1739141168.1246684,7.639992713928223,0.03995248398753828,1739141168.12467,7.639992713928223,0.4365077223554712,1739141168.1246712,7.639992713928223,0.059624696362112414,1739141168.1246722,7.639992713928223,2.0994756916885255,1739141168.124674,7.639992713928223,0.0,1739141168.1246755,7.639992713928223,-0.003924399569470438,1739141168.1246767,7.639992713928223,6.264886886597807,1739141168.124678,7.639992713928223,2.103400091257996 +1739141168.1450872,7.659992694854736,13.980760014271201,1739141168.1450903,7.659992694854736,-0.4306116041256489,1739141168.145094,7.659992694854736,13.160372693162252,1739141168.1450973,7.659992694854736,21.463101675881855,1739141168.1450987,7.659992694854736,-0.126,1739141168.1451008,7.659992694854736,0.040688263243174226,1739141168.1451023,7.659992694854736,0.4344757022461481,1739141168.145104,7.659992694854736,0.059494321513973714,1739141168.1451054,7.659992694854736,2.1011828561228487,1739141168.1451073,7.659992694854736,0.0,1739141168.145109,7.659992694854736,0.00010701848050486654,1739141168.1451104,7.659992694854736,6.265822221235958,1739141168.1451118,7.659992694854736,2.1029955614822704 +1739141168.1666448,7.67999267578125,13.980760014271201,1739141168.1666484,7.67999267578125,-0.4306116041256489,1739141168.1666524,7.67999267578125,13.160372693162252,1739141168.1666563,7.67999267578125,21.463101675881855,1739141168.1666584,7.67999267578125,-0.126,1739141168.1666608,7.67999267578125,0.040688263243174226,1739141168.1666627,7.67999267578125,0.4344757022461481,1739141168.1666646,7.67999267578125,0.059494321513973714,1739141168.1666665,7.67999267578125,2.1011828561228487,1739141168.1666691,7.67999267578125,0.0,1739141168.166671,7.67999267578125,-0.0018127053594216846,1739141168.1666734,7.67999267578125,6.265822221235958,1739141168.166675,7.67999267578125,2.1029955614822704 +1739141168.1855874,7.699992656707764,13.980760014271201,1739141168.1855922,7.699992656707764,-0.4306116041256489,1739141168.1855962,7.699992656707764,13.160372693162252,1739141168.1856,7.699992656707764,21.463101675881855,1739141168.185602,7.699992656707764,-0.126,1739141168.1856046,7.699992656707764,0.040688263243174226,1739141168.1856067,7.699992656707764,0.4344757022461481,1739141168.1856086,7.699992656707764,0.059494321513973714,1739141168.1856105,7.699992656707764,2.1011828561228487,1739141168.1856132,7.699992656707764,0.0,1739141168.185615,7.699992656707764,-0.0018127053594216846,1739141168.1856172,7.699992656707764,6.265822221235958,1739141168.1856189,7.699992656707764,2.1029955614822704 +1739141168.206837,7.719992637634277,13.980760014271201,1739141168.2068405,7.719992637634277,-0.4306116041256489,1739141168.2068446,7.719992637634277,13.160372693162252,1739141168.2068486,7.719992637634277,21.463101675881855,1739141168.2068508,7.719992637634277,-0.126,1739141168.2068532,7.719992637634277,0.040688263243174226,1739141168.206855,7.719992637634277,0.4344757022461481,1739141168.2068572,7.719992637634277,0.059494321513973714,1739141168.206859,7.719992637634277,2.1011828561228487,1739141168.2068615,7.719992637634277,0.0,1739141168.2068639,7.719992637634277,-0.0018127053594216846,1739141168.2068655,7.719992637634277,6.265822221235958,1739141168.2068677,7.719992637634277,2.1029955614822704 +1739141168.225716,7.739992618560791,13.980760014271201,1739141168.225721,7.739992618560791,-0.4306116041256489,1739141168.2257254,7.739992618560791,13.160372693162252,1739141168.2257292,7.739992618560791,21.463101675881855,1739141168.2257316,7.739992618560791,-0.126,1739141168.2257342,7.739992618560791,0.040688263243174226,1739141168.2257361,7.739992618560791,0.4344757022461481,1739141168.225738,7.739992618560791,0.059494321513973714,1739141168.22574,7.739992618560791,2.1011828561228487,1739141168.2257423,7.739992618560791,0.0,1739141168.2257447,7.739992618560791,-0.0018127053594216846,1739141168.2257464,7.739992618560791,6.265822221235958,1739141168.2257488,7.739992618560791,2.1029955614822704 +1739141168.2458198,7.759992599487305,13.980760014271201,1739141168.2458239,7.759992599487305,-0.4306116041256489,1739141168.2458286,7.759992599487305,13.160372693162252,1739141168.2458327,7.759992599487305,21.463101675881855,1739141168.2458348,7.759992599487305,-0.126,1739141168.245837,7.759992599487305,0.040688263243174226,1739141168.245839,7.759992599487305,0.4344757022461481,1739141168.2458413,7.759992599487305,0.059494321513973714,1739141168.245843,7.759992599487305,2.1011828561228487,1739141168.2458453,7.759992599487305,0.0,1739141168.2458475,7.759992599487305,-0.0018127053594216846,1739141168.2458494,7.759992599487305,6.265822221235958,1739141168.2458513,7.759992599487305,2.1029955614822704 +1739141168.2662828,7.779992580413818,14.212050026665914,1739141168.2662864,7.779992580413818,-0.43452955520093717,1739141168.2662907,7.779992580413818,13.483807844475711,1739141168.2662947,7.779992580413818,21.78605146201984,1739141168.2662969,7.779992580413818,-0.125,1739141168.2662995,7.779992580413818,0.04084464610213848,1739141168.2663016,7.779992580413818,0.4339060052590791,1739141168.2663035,7.779992580413818,0.05798655348532991,1739141168.2663052,7.779992580413818,2.101661725699853,1739141168.2663078,7.779992580413818,0.0,1739141168.26631,7.779992580413818,-0.0005922385049278547,1739141168.2663116,7.779992580413818,6.266757555874108,1739141168.2663136,7.779992580413818,2.1028351391877194 +1739141168.2858238,7.799992561340332,14.212050026665914,1739141168.2858279,7.799992561340332,-0.43452955520093717,1739141168.285832,7.799992561340332,13.483807844475711,1739141168.2858357,7.799992561340332,21.78605146201984,1739141168.285838,7.799992561340332,-0.125,1739141168.2858403,7.799992561340332,0.04084464610213848,1739141168.2858427,7.799992561340332,0.4339060052590791,1739141168.2858448,7.799992561340332,0.05798655348532991,1739141168.2858465,7.799992561340332,2.101661725699853,1739141168.2858489,7.799992561340332,0.0,1739141168.2858508,7.799992561340332,-0.0011734134878662594,1739141168.285853,7.799992561340332,6.266757555874108,1739141168.2858548,7.799992561340332,2.1028351391877194 +1739141168.3062654,7.819992542266846,14.212050026665914,1739141168.306269,7.819992542266846,-0.43452955520093717,1739141168.306273,7.819992542266846,13.483807844475711,1739141168.306277,7.819992542266846,21.78605146201984,1739141168.3062792,7.819992542266846,-0.125,1739141168.3062818,7.819992542266846,0.04084464610213848,1739141168.3062837,7.819992542266846,0.4339060052590791,1739141168.3062856,7.819992542266846,0.05798655348532991,1739141168.3062873,7.819992542266846,2.101661725699853,1739141168.3062897,7.819992542266846,0.0,1739141168.3062918,7.819992542266846,-0.0011734134878662594,1739141168.3062935,7.819992542266846,6.266757555874108,1739141168.3062956,7.819992542266846,2.1028351391877194 +1739141168.3256404,7.839992523193359,14.212050026665914,1739141168.3256447,7.839992523193359,-0.43452955520093717,1739141168.3256495,7.839992523193359,13.483807844475711,1739141168.3256538,7.839992523193359,21.78605146201984,1739141168.3256557,7.839992523193359,-0.125,1739141168.325658,7.839992523193359,0.04084464610213848,1739141168.3256602,7.839992523193359,0.4339060052590791,1739141168.3256621,7.839992523193359,0.05798655348532991,1739141168.325664,7.839992523193359,2.101661725699853,1739141168.325667,7.839992523193359,0.0,1739141168.3256688,7.839992523193359,-0.0011734134878662594,1739141168.325671,7.839992523193359,6.266757555874108,1739141168.3256729,7.839992523193359,2.1028351391877194 +1739141168.3455372,7.859992504119873,14.212050026665914,1739141168.3455412,7.859992504119873,-0.43452955520093717,1739141168.3455455,7.859992504119873,13.483807844475711,1739141168.3455496,7.859992504119873,21.78605146201984,1739141168.345552,7.859992504119873,-0.125,1739141168.3455544,7.859992504119873,0.04084464610213848,1739141168.3455565,7.859992504119873,0.4339060052590791,1739141168.3455582,7.859992504119873,0.05798655348532991,1739141168.34556,7.859992504119873,2.101661725699853,1739141168.3455627,7.859992504119873,0.0,1739141168.3455646,7.859992504119873,-0.0011734134878662594,1739141168.3455665,7.859992504119873,6.266757555874108,1739141168.3455682,7.859992504119873,2.1028351391877194 +1739141168.365932,7.86999249458313,14.212050026665914,1739141168.3659358,7.86999249458313,-0.43452955520093717,1739141168.3659399,7.86999249458313,13.483807844475711,1739141168.3659444,7.86999249458313,21.78605146201984,1739141168.3659465,7.86999249458313,-0.125,1739141168.3659492,7.86999249458313,0.04084464610213848,1739141168.3659513,7.86999249458313,0.4339060052590791,1739141168.365953,7.86999249458313,0.05798655348532991,1739141168.3659549,7.86999249458313,2.101661725699853,1739141168.365957,7.86999249458313,0.0,1739141168.3659594,7.86999249458313,-0.0011734134878662594,1739141168.3659613,7.86999249458313,6.266757555874108,1739141168.365963,7.86999249458313,2.1028351391877194 +1739141168.3856657,7.8999924659729,14.443326194123742,1739141168.3856697,7.8999924659729,-0.4382308919841851,1739141168.385674,7.8999924659729,13.80969526695864,1739141168.3856783,7.8999924659729,22.1115660454861,1739141168.3856804,7.8999924659729,-0.124,1739141168.385683,7.8999924659729,0.04095531542634554,1739141168.385685,7.8999924659729,0.43298799733889815,1739141168.3856869,7.8999924659729,0.056450237990197265,1739141168.3856888,7.8999924659729,2.1024336042531986,1739141168.385691,7.8999924659729,0.0,1739141168.3856928,7.8999924659729,0.0005352555076732265,1739141168.3856952,7.8999924659729,6.267692890512258,1739141168.3856974,7.8999924659729,2.102712001054618 +1739141168.4062493,7.919992446899414,14.443326194123742,1739141168.4062529,7.919992446899414,-0.4382308919841851,1739141168.406257,7.919992446899414,13.80969526695864,1739141168.406261,7.919992446899414,22.1115660454861,1739141168.406263,7.919992446899414,-0.124,1739141168.4062653,7.919992446899414,0.04095531542634554,1739141168.4062674,7.919992446899414,0.43298799733889815,1739141168.4062696,7.919992446899414,0.056450237990197265,1739141168.4062712,7.919992446899414,2.1024336042531986,1739141168.4062738,7.919992446899414,0.0,1739141168.4062757,7.919992446899414,-0.0002783968014195004,1739141168.4062777,7.919992446899414,6.267692890512258,1739141168.4062793,7.919992446899414,2.102712001054618 +1739141168.4256887,7.939992427825928,14.443326194123742,1739141168.425693,7.939992427825928,-0.4382308919841851,1739141168.425697,7.939992427825928,13.80969526695864,1739141168.4257011,7.939992427825928,22.1115660454861,1739141168.4257033,7.939992427825928,-0.124,1739141168.425706,7.939992427825928,0.04095531542634554,1739141168.425708,7.939992427825928,0.43298799733889815,1739141168.42571,7.939992427825928,0.056450237990197265,1739141168.4257119,7.939992427825928,2.1024336042531986,1739141168.4257143,7.939992427825928,0.0,1739141168.4257162,7.939992427825928,-0.0002783968014195004,1739141168.425718,7.939992427825928,6.267692890512258,1739141168.42572,7.939992427825928,2.102712001054618 +1739141168.445658,7.959992408752441,14.443326194123742,1739141168.4456625,7.959992408752441,-0.4382308919841851,1739141168.4456666,7.959992408752441,13.80969526695864,1739141168.4456706,7.959992408752441,22.1115660454861,1739141168.4456728,7.959992408752441,-0.124,1739141168.445675,7.959992408752441,0.04095531542634554,1739141168.445677,7.959992408752441,0.43298799733889815,1739141168.445679,7.959992408752441,0.056450237990197265,1739141168.4456809,7.959992408752441,2.1024336042531986,1739141168.4456832,7.959992408752441,0.0,1739141168.4456851,7.959992408752441,-0.0002783968014195004,1739141168.4456873,7.959992408752441,6.267692890512258,1739141168.4456897,7.959992408752441,2.102712001054618 +1739141168.4657273,7.979992389678955,14.443326194123742,1739141168.4657314,7.979992389678955,-0.4382308919841851,1739141168.4657357,7.979992389678955,13.80969526695864,1739141168.4657397,7.979992389678955,22.1115660454861,1739141168.4657419,7.979992389678955,-0.124,1739141168.4657445,7.979992389678955,0.04095531542634554,1739141168.4657464,7.979992389678955,0.43298799733889815,1739141168.4657483,7.979992389678955,0.056450237990197265,1739141168.46575,7.979992389678955,2.1024336042531986,1739141168.4657524,7.979992389678955,0.0,1739141168.4657543,7.979992389678955,-0.0002783968014195004,1739141168.4657564,7.979992389678955,6.267692890512258,1739141168.4657583,7.979992389678955,2.102712001054618 +1739141168.4856586,7.999992370605469,14.674596269073763,1739141168.485663,7.999992370605469,-0.44171576329096585,1739141168.485668,7.999992370605469,13.8358322702993,1739141168.485672,7.999992370605469,22.137607523661913,1739141168.485674,7.999992370605469,-0.124,1739141168.4856765,7.999992370605469,0.04254636906129173,1739141168.4856787,7.999992370605469,0.4263179306392895,1739141168.4856806,7.999992370605469,0.05867118465365998,1739141168.4856825,7.999992370605469,2.108050442807613,1739141168.4856846,7.999992370605469,0.0,1739141168.4856868,7.999992370605469,0.010505452259189174,1739141168.485689,7.999992370605469,6.268628225150408,1739141168.4856906,7.999992370605469,2.1026801593330022 +1739141168.5060678,8.019992351531982,14.674596269073763,1739141168.5060713,8.019992351531982,-0.44171576329096585,1739141168.5060756,8.019992351531982,13.8358322702993,1739141168.50608,8.019992351531982,22.137607523661913,1739141168.5060823,8.019992351531982,-0.124,1739141168.506085,8.019992351531982,0.04254636906129173,1739141168.5060868,8.019992351531982,0.4263179306392895,1739141168.5060887,8.019992351531982,0.05867118465365998,1739141168.5060906,8.019992351531982,2.108050442807613,1739141168.506093,8.019992351531982,0.0,1739141168.5060952,8.019992351531982,0.005370283474610549,1739141168.506097,8.019992351531982,6.268628225150408,1739141168.506099,8.019992351531982,2.1026801593330022 +1739141168.525676,8.039992332458496,14.674596269073763,1739141168.5256798,8.039992332458496,-0.44171576329096585,1739141168.5256846,8.039992332458496,13.8358322702993,1739141168.5256891,8.039992332458496,22.137607523661913,1739141168.5256908,8.039992332458496,-0.124,1739141168.5256934,8.039992332458496,0.04254636906129173,1739141168.5256958,8.039992332458496,0.4263179306392895,1739141168.5256975,8.039992332458496,0.05867118465365998,1739141168.5256994,8.039992332458496,2.108050442807613,1739141168.525702,8.039992332458496,0.0,1739141168.525704,8.039992332458496,0.005370283474610549,1739141168.5257063,8.039992332458496,6.268628225150408,1739141168.525708,8.039992332458496,2.1026801593330022 +1739141168.5455883,8.05999231338501,14.674596269073763,1739141168.5455925,8.05999231338501,-0.44171576329096585,1739141168.545597,8.05999231338501,13.8358322702993,1739141168.5456014,8.05999231338501,22.137607523661913,1739141168.545603,8.05999231338501,-0.124,1739141168.5456057,8.05999231338501,0.04254636906129173,1739141168.5456076,8.05999231338501,0.4263179306392895,1739141168.5456097,8.05999231338501,0.05867118465365998,1739141168.5456119,8.05999231338501,2.108050442807613,1739141168.545614,8.05999231338501,0.0,1739141168.5456161,8.05999231338501,0.005370283474610549,1739141168.5456178,8.05999231338501,6.268628225150408,1739141168.5456197,8.05999231338501,2.1026801593330022 +1739141168.5662723,8.069992303848267,14.674596269073763,1739141168.566276,8.069992303848267,-0.44171576329096585,1739141168.5662804,8.069992303848267,13.8358322702993,1739141168.5662847,8.069992303848267,22.137607523661913,1739141168.5662866,8.069992303848267,-0.124,1739141168.5662892,8.069992303848267,0.04254636906129173,1739141168.566291,8.069992303848267,0.4263179306392895,1739141168.5662932,8.069992303848267,0.05867118465365998,1739141168.5662951,8.069992303848267,2.108050442807613,1739141168.5662975,8.069992303848267,0.0,1739141168.5662997,8.069992303848267,0.005370283474610549,1739141168.5663013,8.069992303848267,6.268628225150408,1739141168.5663033,8.069992303848267,2.1026801593330022 +1739141168.585786,8.099992275238037,14.90590051165626,1739141168.5857902,8.099992275238037,-0.44498475058173703,1739141168.5857944,8.099992275238037,14.264520920323097,1739141168.5857987,8.099992275238037,22.56819140513971,1739141168.5858006,8.099992275238037,-0.12234803735658772,1739141168.5858033,8.099992275238037,0.04208222336015445,1739141168.5858054,8.099992275238037,0.4269773439671991,1739141168.585807,8.099992275238037,0.055748021826231,1739141168.5858092,8.099992275238037,2.107494485508809,1739141168.5858114,8.099992275238037,0.0,1739141168.5858138,8.099992275238037,0.003098579739028877,1739141168.585816,8.099992275238037,6.269563559788558,1739141168.5858176,8.099992275238037,2.1033141415457814 +1739141168.6064916,8.11999225616455,14.90590051165626,1739141168.6064951,8.11999225616455,-0.44498475058173703,1739141168.6064997,8.11999225616455,14.264520920323097,1739141168.606504,8.11999225616455,22.56819140513971,1739141168.6065056,8.11999225616455,-0.12234803735658772,1739141168.606508,8.11999225616455,0.04208222336015445,1739141168.6065102,8.11999225616455,0.4269773439671991,1739141168.606512,8.11999225616455,0.055748021826231,1739141168.606514,8.11999225616455,2.107494485508809,1739141168.6065164,8.11999225616455,0.0,1739141168.6065185,8.11999225616455,0.004180343963027688,1739141168.6065207,8.11999225616455,6.269563559788558,1739141168.6065223,8.11999225616455,2.1033141415457814 +1739141168.625648,8.139992237091064,14.90590051165626,1739141168.6256523,8.139992237091064,-0.44498475058173703,1739141168.6256568,8.139992237091064,14.264520920323097,1739141168.625661,8.139992237091064,22.56819140513971,1739141168.6256628,8.139992237091064,-0.12234803735658772,1739141168.6256652,8.139992237091064,0.04208222336015445,1739141168.6256676,8.139992237091064,0.4269773439671991,1739141168.6256695,8.139992237091064,0.055748021826231,1739141168.6256711,8.139992237091064,2.107494485508809,1739141168.6256738,8.139992237091064,0.0,1739141168.625676,8.139992237091064,0.004180343963027688,1739141168.625678,8.139992237091064,6.269563559788558,1739141168.62568,8.139992237091064,2.1033141415457814 +1739141168.6456525,8.159992218017578,14.90590051165626,1739141168.6456566,8.159992218017578,-0.44498475058173703,1739141168.6456606,8.159992218017578,14.264520920323097,1739141168.6456647,8.159992218017578,22.56819140513971,1739141168.6456668,8.159992218017578,-0.12234803735658772,1739141168.6456692,8.159992218017578,0.04208222336015445,1739141168.6456711,8.159992218017578,0.4269773439671991,1739141168.645673,8.159992218017578,0.055748021826231,1739141168.6456747,8.159992218017578,2.107494485508809,1739141168.645677,8.159992218017578,0.0,1739141168.6456797,8.159992218017578,0.004180343963027688,1739141168.6456816,8.159992218017578,6.269563559788558,1739141168.6456835,8.159992218017578,2.1033141415457814 +1739141168.6657255,8.179992198944092,14.90590051165626,1739141168.665729,8.179992198944092,-0.44498475058173703,1739141168.6657333,8.179992198944092,14.264520920323097,1739141168.6657376,8.179992198944092,22.56819140513971,1739141168.6657395,8.179992198944092,-0.12234803735658772,1739141168.6657424,8.179992198944092,0.04208222336015445,1739141168.665744,8.179992198944092,0.4269773439671991,1739141168.6657462,8.179992198944092,0.055748021826231,1739141168.665748,8.179992198944092,2.107494485508809,1739141168.6657503,8.179992198944092,0.0,1739141168.665753,8.179992198944092,0.004180343963027688,1739141168.6657546,8.179992198944092,6.269563559788558,1739141168.6657565,8.179992198944092,2.1033141415457814 +1739141168.6856542,8.199992179870605,14.90590051165626,1739141168.6856587,8.199992179870605,-0.44498475058173703,1739141168.685663,8.199992179870605,14.264520920323097,1739141168.685667,8.199992179870605,22.56819140513971,1739141168.6856692,8.199992179870605,-0.12234803735658772,1739141168.6856716,8.199992179870605,0.04208222336015445,1739141168.6856737,8.199992179870605,0.4269773439671991,1739141168.6856756,8.199992179870605,0.055748021826231,1739141168.6856775,8.199992179870605,2.107494485508809,1739141168.6856802,8.199992179870605,0.0,1739141168.685682,8.199992179870605,0.004180343963027688,1739141168.685684,8.199992179870605,6.269563559788558,1739141168.6856863,8.199992179870605,2.1033141415457814 +1739141168.705971,8.21999216079712,15.13726579250321,1739141168.7059748,8.21999216079712,-0.44803815804116365,1739141168.7059786,8.21999216079712,14.29089961574711,1739141168.7059827,8.21999216079712,22.59587802567896,1739141168.7059846,8.21999216079712,-0.12212294288065888,1739141168.705987,8.21999216079712,0.04366871609547158,1739141168.7059891,8.21999216079712,0.4205094834779985,1739141168.705991,8.21999216079712,0.057934667588572776,1739141168.7059927,8.21999216079712,2.112953936783107,1739141168.705995,8.21999216079712,0.0,1739141168.705997,8.21999216079712,0.01377003885728233,1739141168.7059991,8.21999216079712,6.270498894426709,1739141168.706001,8.21999216079712,2.1037504215852194 +1739141168.7256417,8.239992141723633,15.13726579250321,1739141168.7256463,8.239992141723633,-0.44803815804116365,1739141168.725651,8.239992141723633,14.29089961574711,1739141168.7256553,8.239992141723633,22.59587802567896,1739141168.7256575,8.239992141723633,-0.12212294288065888,1739141168.7256596,8.239992141723633,0.04366871609547158,1739141168.7256618,8.239992141723633,0.4205094834779985,1739141168.7256634,8.239992141723633,0.057934667588572776,1739141168.7256656,8.239992141723633,2.112953936783107,1739141168.725668,8.239992141723633,0.0,1739141168.7256699,8.239992141723633,0.009203515197887757,1739141168.725672,8.239992141723633,6.270498894426709,1739141168.7256737,8.239992141723633,2.1037504215852194 +1739141168.7459333,8.259992122650146,15.13726579250321,1739141168.7459376,8.259992122650146,-0.44803815804116365,1739141168.7459424,8.259992122650146,14.29089961574711,1739141168.7459464,8.259992122650146,22.59587802567896,1739141168.7459483,8.259992122650146,-0.12212294288065888,1739141168.7459507,8.259992122650146,0.04366871609547158,1739141168.7459528,8.259992122650146,0.4205094834779985,1739141168.7459548,8.259992122650146,0.057934667588572776,1739141168.745957,8.259992122650146,2.112953936783107,1739141168.7459593,8.259992122650146,0.0,1739141168.7459612,8.259992122650146,0.009203515197887757,1739141168.7459633,8.259992122650146,6.270498894426709,1739141168.7459652,8.259992122650146,2.1037504215852194 +1739141168.7655907,8.27999210357666,15.13726579250321,1739141168.765596,8.27999210357666,-0.44803815804116365,1739141168.7656014,8.27999210357666,14.29089961574711,1739141168.7656062,8.27999210357666,22.59587802567896,1739141168.7656088,8.27999210357666,-0.12212294288065888,1739141168.7656121,8.27999210357666,0.04366871609547158,1739141168.7656145,8.27999210357666,0.4205094834779985,1739141168.765617,8.27999210357666,0.057934667588572776,1739141168.7656195,8.27999210357666,2.112953936783107,1739141168.7656226,8.27999210357666,0.0,1739141168.765625,8.27999210357666,0.009203515197887757,1739141168.7656279,8.27999210357666,6.270498894426709,1739141168.7656302,8.27999210357666,2.1037504215852194 +1739141168.785689,8.299992084503174,15.13726579250321,1739141168.7856932,8.299992084503174,-0.44803815804116365,1739141168.7856977,8.299992084503174,14.29089961574711,1739141168.7857015,8.299992084503174,22.59587802567896,1739141168.7857037,8.299992084503174,-0.12212294288065888,1739141168.785706,8.299992084503174,0.04366871609547158,1739141168.785708,8.299992084503174,0.4205094834779985,1739141168.78571,8.299992084503174,0.057934667588572776,1739141168.7857118,8.299992084503174,2.112953936783107,1739141168.7857141,8.299992084503174,0.0,1739141168.7857165,8.299992084503174,0.009203515197887757,1739141168.7857184,8.299992084503174,6.270498894426709,1739141168.7857203,8.299992084503174,2.1037504215852194 +1739141168.8062313,8.30999207496643,15.13726579250321,1739141168.806235,8.30999207496643,-0.44803815804116365,1739141168.8062396,8.30999207496643,14.29089961574711,1739141168.8062437,8.30999207496643,22.59587802567896,1739141168.8062453,8.30999207496643,-0.12212294288065888,1739141168.806248,8.30999207496643,0.04366871609547158,1739141168.8062496,8.30999207496643,0.4205094834779985,1739141168.8062518,8.30999207496643,0.057934667588572776,1739141168.8062537,8.30999207496643,2.112953936783107,1739141168.8062558,8.30999207496643,0.0,1739141168.806258,8.30999207496643,0.009203515197887757,1739141168.8062599,8.30999207496643,6.270498894426709,1739141168.806262,8.30999207496643,2.1037504215852194 +1739141168.8257732,8.339992046356201,15.368714105317284,1739141168.8257778,8.339992046356201,-0.4508761391801688,1739141168.8257825,8.339992046356201,14.719288371691894,1739141168.8257868,8.339992046356201,23.027406981318425,1739141168.825789,8.339992046356201,-0.12044273421203221,1739141168.8257916,8.339992046356201,0.04311814133103498,1739141168.8257933,8.339992046356201,0.4204064178013216,1739141168.8257954,8.339992046356201,0.054937010179749605,1739141168.825797,8.339992046356201,2.113041047789639,1739141168.8257995,8.339992046356201,0.0,1739141168.8258016,8.339992046356201,0.007368732110349532,1739141168.8258038,8.339992046356201,6.271434229064859,1739141168.8258057,8.339992046356201,2.1047986090106736 +1739141168.845704,8.359992027282715,15.368714105317284,1739141168.8457088,8.359992027282715,-0.4508761391801688,1739141168.8457131,8.359992027282715,14.719288371691894,1739141168.8457174,8.359992027282715,23.027406981318425,1739141168.8457196,8.359992027282715,-0.12044273421203221,1739141168.8457222,8.359992027282715,0.04311814133103498,1739141168.845724,8.359992027282715,0.4204064178013216,1739141168.845726,8.359992027282715,0.054937010179749605,1739141168.845728,8.359992027282715,2.113041047789639,1739141168.8457303,8.359992027282715,0.0,1739141168.8457325,8.359992027282715,0.008242438778965244,1739141168.8457341,8.359992027282715,6.271434229064859,1739141168.845736,8.359992027282715,2.1047986090106736 +1739141168.8656428,8.379992008209229,15.368714105317284,1739141168.8656464,8.379992008209229,-0.4508761391801688,1739141168.8656507,8.379992008209229,14.719288371691894,1739141168.8656547,8.379992008209229,23.027406981318425,1739141168.865657,8.379992008209229,-0.12044273421203221,1739141168.8656597,8.379992008209229,0.04311814133103498,1739141168.8656616,8.379992008209229,0.4204064178013216,1739141168.8656638,8.379992008209229,0.054937010179749605,1739141168.8656654,8.379992008209229,2.113041047789639,1739141168.8656678,8.379992008209229,0.0,1739141168.86567,8.379992008209229,0.008242438778965244,1739141168.8656716,8.379992008209229,6.271434229064859,1739141168.8656735,8.379992008209229,2.1047986090106736 +1739141168.8857467,8.399991989135742,15.368714105317284,1739141168.885751,8.399991989135742,-0.4508761391801688,1739141168.885756,8.399991989135742,14.719288371691894,1739141168.8857596,8.399991989135742,23.027406981318425,1739141168.8857615,8.399991989135742,-0.12044273421203221,1739141168.885764,8.399991989135742,0.04311814133103498,1739141168.8857658,8.399991989135742,0.4204064178013216,1739141168.885768,8.399991989135742,0.054937010179749605,1739141168.8857698,8.399991989135742,2.113041047789639,1739141168.8857722,8.399991989135742,0.0,1739141168.8857746,8.399991989135742,0.008242438778965244,1739141168.8857763,8.399991989135742,6.271434229064859,1739141168.8857784,8.399991989135742,2.1047986090106736 +1739141168.9059947,8.409991979598999,15.368714105317284,1739141168.9059982,8.409991979598999,-0.4508761391801688,1739141168.906003,8.409991979598999,14.719288371691894,1739141168.906007,8.409991979598999,23.027406981318425,1739141168.9060092,8.409991979598999,-0.12044273421203221,1739141168.9060116,8.409991979598999,0.04311814133103498,1739141168.9060137,8.409991979598999,0.4204064178013216,1739141168.9060154,8.409991979598999,0.054937010179749605,1739141168.9060173,8.409991979598999,2.113041047789639,1739141168.90602,8.409991979598999,0.0,1739141168.906022,8.409991979598999,0.008242438778965244,1739141168.906024,8.409991979598999,6.271434229064859,1739141168.9060256,8.409991979598999,2.1047986090106736 +1739141168.925682,8.43999195098877,15.600272629439562,1739141168.9256866,8.43999195098877,-0.4534988584488344,1739141168.9256911,8.43999195098877,14.952229163954671,1739141168.925695,8.43999195098877,23.263052175774902,1739141168.925697,8.43999195098877,-0.11970689287987885,1739141168.9256992,8.43999195098877,0.04353264784361422,1739141168.9257019,8.43999195098877,0.41664948425435255,1739141168.925704,8.43999195098877,0.054386177703279706,1739141168.9257057,8.43999195098877,2.1162188568745313,1739141168.925708,8.43999195098877,0.0,1739141168.92571,8.43999195098877,0.01258661149200648,1739141168.925712,8.43999195098877,6.272369563703009,1739141168.9257143,8.43999195098877,2.105700900088785 +1739141168.945662,8.459991931915283,15.600272629439562,1739141168.9456663,8.459991931915283,-0.4534988584488344,1739141168.9456708,8.459991931915283,14.952229163954671,1739141168.9456756,8.459991931915283,23.263052175774902,1739141168.9456775,8.459991931915283,-0.11970689287987885,1739141168.94568,8.459991931915283,0.04353264784361422,1739141168.9456818,8.459991931915283,0.41664948425435255,1739141168.9456837,8.459991931915283,0.054386177703279706,1739141168.9456854,8.459991931915283,2.1162188568745313,1739141168.9456878,8.459991931915283,0.0,1739141168.9456902,8.459991931915283,0.010517956785746296,1739141168.9456923,8.459991931915283,6.272369563703009,1739141168.9456944,8.459991931915283,2.105700900088785 +1739141168.9660926,8.46999192237854,15.600272629439562,1739141168.9660964,8.46999192237854,-0.4534988584488344,1739141168.966101,8.46999192237854,14.952229163954671,1739141168.966105,8.46999192237854,23.263052175774902,1739141168.966107,8.46999192237854,-0.11970689287987885,1739141168.9661095,8.46999192237854,0.04353264784361422,1739141168.9661114,8.46999192237854,0.41664948425435255,1739141168.9661136,8.46999192237854,0.054386177703279706,1739141168.9661152,8.46999192237854,2.1162188568745313,1739141168.9661176,8.46999192237854,0.0,1739141168.96612,8.46999192237854,0.010517956785746296,1739141168.9661217,8.46999192237854,6.272369563703009,1739141168.9661238,8.46999192237854,2.105700900088785 +1739141168.985636,8.49999189376831,15.600272629439562,1739141168.9856403,8.49999189376831,-0.4534988584488344,1739141168.985645,8.49999189376831,14.952229163954671,1739141168.985649,8.49999189376831,23.263052175774902,1739141168.9856513,8.49999189376831,-0.11970689287987885,1739141168.9856534,8.49999189376831,0.04353264784361422,1739141168.9856555,8.49999189376831,0.41664948425435255,1739141168.9856577,8.49999189376831,0.054386177703279706,1739141168.9856594,8.49999189376831,2.1162188568745313,1739141168.9856617,8.49999189376831,0.0,1739141168.985664,8.49999189376831,0.010517956785746296,1739141168.985666,8.49999189376831,6.272369563703009,1739141168.9856684,8.49999189376831,2.105700900088785 +1739141169.005926,8.519991874694824,15.600272629439562,1739141169.0059292,8.519991874694824,-0.4534988584488344,1739141169.0059335,8.519991874694824,14.952229163954671,1739141169.0059376,8.519991874694824,23.263052175774902,1739141169.00594,8.519991874694824,-0.11970689287987885,1739141169.0059426,8.519991874694824,0.04353264784361422,1739141169.0059445,8.519991874694824,0.41664948425435255,1739141169.0059464,8.519991874694824,0.054386177703279706,1739141169.005948,8.519991874694824,2.1162188568745313,1739141169.0059507,8.519991874694824,0.0,1739141169.0059528,8.519991874694824,0.010517956785746296,1739141169.0059545,8.519991874694824,6.272369563703009,1739141169.0059566,8.519991874694824,2.105700900088785 +1739141169.0257275,8.539991855621338,15.83194605823353,1739141169.0257318,8.539991855621338,-0.45590615894776665,1739141169.025736,8.539991855621338,14.978874015566475,1739141169.0257401,8.539991855621338,23.293204054590653,1739141169.0257423,8.539991855621338,-0.11946175565373453,1739141169.025745,8.539991855621338,0.04506165714959865,1739141169.025747,8.539991855621338,0.4101470611587539,1739141169.025749,8.539991855621338,0.05646031196109457,1739141169.0257509,8.539991855621338,2.12173024138637,1739141169.025753,8.539991855621338,0.0,1739141169.0257554,8.539991855621338,0.018807315912631063,1739141169.025757,8.539991855621338,6.273304898341159,1739141169.0257592,8.539991855621338,2.1068702413155407 +1739141169.0456128,8.559991836547852,15.83194605823353,1739141169.0456169,8.559991836547852,-0.45590615894776665,1739141169.0456214,8.559991836547852,14.978874015566475,1739141169.0456262,8.559991836547852,23.293204054590653,1739141169.045628,8.559991836547852,-0.11946175565373453,1739141169.0456307,8.559991836547852,0.04506165714959865,1739141169.0456328,8.559991836547852,0.4101470611587539,1739141169.0456347,8.559991836547852,0.05646031196109457,1739141169.0456367,8.559991836547852,2.12173024138637,1739141169.0456393,8.559991836547852,0.0,1739141169.0456412,8.559991836547852,0.014860000070829216,1739141169.0456433,8.559991836547852,6.273304898341159,1739141169.0456452,8.559991836547852,2.1068702413155407 +1739141169.0661576,8.569991827011108,15.83194605823353,1739141169.0661612,8.569991827011108,-0.45590615894776665,1739141169.0661654,8.569991827011108,14.978874015566475,1739141169.0661697,8.569991827011108,23.293204054590653,1739141169.066172,8.569991827011108,-0.11946175565373453,1739141169.0661745,8.569991827011108,0.04506165714959865,1739141169.0661764,8.569991827011108,0.4101470611587539,1739141169.0661783,8.569991827011108,0.05646031196109457,1739141169.06618,8.569991827011108,2.12173024138637,1739141169.0661826,8.569991827011108,0.0,1739141169.0661848,8.569991827011108,0.014860000070829216,1739141169.0661864,8.569991827011108,6.273304898341159,1739141169.0661886,8.569991827011108,2.1068702413155407 +1739141169.0856562,8.599991798400879,15.83194605823353,1739141169.0856602,8.599991798400879,-0.45590615894776665,1739141169.085665,8.599991798400879,14.978874015566475,1739141169.085669,8.599991798400879,23.293204054590653,1739141169.0856712,8.599991798400879,-0.11946175565373453,1739141169.0856738,8.599991798400879,0.04506165714959865,1739141169.0856757,8.599991798400879,0.4101470611587539,1739141169.0856779,8.599991798400879,0.05646031196109457,1739141169.0856795,8.599991798400879,2.12173024138637,1739141169.0856822,8.599991798400879,0.0,1739141169.0856843,8.599991798400879,0.014860000070829216,1739141169.085686,8.599991798400879,6.273304898341159,1739141169.085688,8.599991798400879,2.1068702413155407 +1739141169.1059165,8.609991788864136,15.83194605823353,1739141169.1059206,8.609991788864136,-0.45590615894776665,1739141169.1059246,8.609991788864136,14.978874015566475,1739141169.1059284,8.609991788864136,23.293204054590653,1739141169.1059306,8.609991788864136,-0.11946175565373453,1739141169.1059327,8.609991788864136,0.04506165714959865,1739141169.1059346,8.609991788864136,0.4101470611587539,1739141169.1059365,8.609991788864136,0.05646031196109457,1739141169.1059384,8.609991788864136,2.12173024138637,1739141169.1059408,8.609991788864136,0.0,1739141169.1059427,8.609991788864136,0.014860000070829216,1739141169.1059446,8.609991788864136,6.273304898341159,1739141169.1059465,8.609991788864136,2.1068702413155407 +1739141169.125698,8.639991760253906,15.83194605823353,1739141169.1257021,8.639991760253906,-0.45590615894776665,1739141169.1257067,8.639991760253906,14.978874015566475,1739141169.1257112,8.639991760253906,23.293204054590653,1739141169.125713,8.639991760253906,-0.11946175565373453,1739141169.1257157,8.639991760253906,0.04506165714959865,1739141169.1257179,8.639991760253906,0.4101470611587539,1739141169.1257198,8.639991760253906,0.05646031196109457,1739141169.1257217,8.639991760253906,2.12173024138637,1739141169.1257246,8.639991760253906,0.0,1739141169.1257267,8.639991760253906,0.014860000070829216,1739141169.1257288,8.639991760253906,6.273304898341159,1739141169.1257308,8.639991760253906,2.1068702413155407 +1739141169.1456578,8.65999174118042,16.063780387925064,1739141169.1456623,8.65999174118042,-0.458098263074854,1739141169.1456668,8.65999174118042,15.596665130483782,1739141169.1456711,8.65999174118042,23.916101237584797,1739141169.1456735,8.65999174118042,-0.117,1739141169.1456761,8.65999174118042,0.043411873482599714,1739141169.1456783,8.65999174118042,0.4113232727399408,1739141169.1456802,8.65999174118042,0.051131395851411035,1739141169.145682,8.65999174118042,2.1207322347053537,1739141169.1456845,8.65999174118042,0.0,1739141169.1456866,8.65999174118042,0.009699048984122733,1739141169.1456883,8.65999174118042,6.274240232979309,1739141169.1456902,8.65999174118042,2.1085755887379793 +1739141169.1661417,8.679991722106934,16.063780387925064,1739141169.1661453,8.679991722106934,-0.458098263074854,1739141169.1661496,8.679991722106934,15.596665130483782,1739141169.1661534,8.679991722106934,23.916101237584797,1739141169.1661556,8.679991722106934,-0.117,1739141169.166158,8.679991722106934,0.043411873482599714,1739141169.16616,8.679991722106934,0.4113232727399408,1739141169.166162,8.679991722106934,0.051131395851411035,1739141169.1661637,8.679991722106934,2.1207322347053537,1739141169.1661663,8.679991722106934,0.0,1739141169.1661682,8.679991722106934,0.012156645967374313,1739141169.1661701,8.679991722106934,6.274240232979309,1739141169.1661718,8.679991722106934,2.1085755887379793 +1739141169.1856065,8.699991703033447,16.063780387925064,1739141169.1856108,8.699991703033447,-0.458098263074854,1739141169.1856153,8.699991703033447,15.596665130483782,1739141169.1856194,8.699991703033447,23.916101237584797,1739141169.1856217,8.699991703033447,-0.117,1739141169.1856241,8.699991703033447,0.043411873482599714,1739141169.1856263,8.699991703033447,0.4113232727399408,1739141169.1856284,8.699991703033447,0.051131395851411035,1739141169.1856306,8.699991703033447,2.1207322347053537,1739141169.1856334,8.699991703033447,0.0,1739141169.1856358,8.699991703033447,0.012156645967374313,1739141169.185638,8.699991703033447,6.274240232979309,1739141169.1856399,8.699991703033447,2.1085755887379793 +1739141169.2072842,8.709991693496704,16.063780387925064,1739141169.207288,8.709991693496704,-0.458098263074854,1739141169.2072926,8.709991693496704,15.596665130483782,1739141169.2072968,8.709991693496704,23.916101237584797,1739141169.2072988,8.709991693496704,-0.117,1739141169.2073014,8.709991693496704,0.043411873482599714,1739141169.2073035,8.709991693496704,0.4113232727399408,1739141169.2073052,8.709991693496704,0.051131395851411035,1739141169.2073073,8.709991693496704,2.1207322347053537,1739141169.2073095,8.709991693496704,0.0,1739141169.2073116,8.709991693496704,0.012156645967374313,1739141169.2073138,8.709991693496704,6.274240232979309,1739141169.2073157,8.709991693496704,2.1085755887379793 +1739141169.2252975,8.739991664886475,16.063780387925064,1739141169.2253015,8.739991664886475,-0.458098263074854,1739141169.2253056,8.739991664886475,15.596665130483782,1739141169.2253094,8.739991664886475,23.916101237584797,1739141169.2253113,8.739991664886475,-0.117,1739141169.2253132,8.739991664886475,0.043411873482599714,1739141169.2253156,8.739991664886475,0.4113232727399408,1739141169.225317,8.739991664886475,0.051131395851411035,1739141169.2253187,8.739991664886475,2.1207322347053537,1739141169.225321,8.739991664886475,0.0,1739141169.225323,8.739991664886475,0.012156645967374313,1739141169.2253246,8.739991664886475,6.274240232979309,1739141169.2253263,8.739991664886475,2.1085755887379793 +1739141169.2450302,8.759991645812988,16.295780323024722,1739141169.2450328,8.759991645812988,-0.4600749212810298,1739141169.2450354,8.759991645812988,15.639587095135425,1739141169.2450385,8.759991645812988,23.962945836884426,1739141169.2450402,8.759991645812988,-0.117,1739141169.2450418,8.759991645812988,0.04471616358142727,1739141169.2450435,8.759991645812988,0.40447525848545984,1739141169.245045,8.759991645812988,0.05273149666884689,1739141169.2450464,8.759991645812988,2.1265493199939765,1739141169.2450483,8.759991645812988,0.0,1739141169.24505,8.759991645812988,0.020765772470244186,1739141169.2450511,8.759991645812988,6.27517556761746,1739141169.2450526,8.759991645812988,2.1098831336206403 +1739141169.2649999,8.779991626739502,16.295780323024722,1739141169.2650032,8.779991626739502,-0.4600749212810298,1739141169.2650077,8.779991626739502,15.639587095135425,1739141169.2650106,8.779991626739502,23.962945836884426,1739141169.2650125,8.779991626739502,-0.117,1739141169.2650142,8.779991626739502,0.04471616358142727,1739141169.265016,8.779991626739502,0.40447525848545984,1739141169.2650177,8.779991626739502,0.05273149666884689,1739141169.2650192,8.779991626739502,2.1265493199939765,1739141169.2650208,8.779991626739502,0.0,1739141169.2650228,8.779991626739502,0.016666186373336167,1739141169.265024,8.779991626739502,6.27517556761746,1739141169.2650256,8.779991626739502,2.1098831336206403 +1739141169.2882504,8.799991607666016,16.295780323024722,1739141169.2882588,8.799991607666016,-0.4600749212810298,1739141169.288269,8.799991607666016,15.639587095135425,1739141169.2882786,8.799991607666016,23.962945836884426,1739141169.2882833,8.799991607666016,-0.117,1739141169.2882898,8.799991607666016,0.04471616358142727,1739141169.288295,8.799991607666016,0.40447525848545984,1739141169.2882993,8.799991607666016,0.05273149666884689,1739141169.2883039,8.799991607666016,2.1265493199939765,1739141169.2883096,8.799991607666016,0.0,1739141169.2883148,8.799991607666016,0.016666186373336167,1739141169.2883196,8.799991607666016,6.27517556761746,1739141169.288324,8.799991607666016,2.1098831336206403 +1739141169.3107462,8.81999158859253,16.295780323024722,1739141169.3107543,8.81999158859253,-0.4600749212810298,1739141169.3107646,8.81999158859253,15.639587095135425,1739141169.3107746,8.81999158859253,23.962945836884426,1739141169.310779,8.81999158859253,-0.117,1739141169.310785,8.81999158859253,0.04471616358142727,1739141169.3107898,8.81999158859253,0.40447525848545984,1739141169.3107944,8.81999158859253,0.05273149666884689,1739141169.3107986,8.81999158859253,2.1265493199939765,1739141169.3108044,8.81999158859253,0.0,1739141169.3108094,8.81999158859253,0.016666186373336167,1739141169.310814,8.81999158859253,6.27517556761746,1739141169.3108182,8.81999158859253,2.1098831336206403 +1739141169.3303163,8.839991569519043,16.295780323024722,1739141169.3303246,8.839991569519043,-0.4600749212810298,1739141169.3303351,8.839991569519043,15.639587095135425,1739141169.3303444,8.839991569519043,23.962945836884426,1739141169.3303492,8.839991569519043,-0.117,1739141169.3303552,8.839991569519043,0.04471616358142727,1739141169.3303602,8.839991569519043,0.40447525848545984,1739141169.3303647,8.839991569519043,0.05273149666884689,1739141169.330369,8.839991569519043,2.1265493199939765,1739141169.330375,8.839991569519043,0.0,1739141169.3303797,8.839991569519043,0.016666186373336167,1739141169.3303845,8.839991569519043,6.27517556761746,1739141169.3303888,8.839991569519043,2.1098831336206403 +1739141169.3495805,8.859991550445557,16.295780323024722,1739141169.3495893,8.859991550445557,-0.4600749212810298,1739141169.3495991,8.859991550445557,15.639587095135425,1739141169.3496084,8.859991550445557,23.962945836884426,1739141169.3496134,8.859991550445557,-0.117,1739141169.3496192,8.859991550445557,0.04471616358142727,1739141169.3496244,8.859991550445557,0.40447525848545984,1739141169.3496292,8.859991550445557,0.05273149666884689,1739141169.3496332,8.859991550445557,2.1265493199939765,1739141169.349639,8.859991550445557,0.0,1739141169.3496437,8.859991550445557,0.016666186373336167,1739141169.3496482,8.859991550445557,6.27517556761746,1739141169.349653,8.859991550445557,2.1098831336206403 +1739141169.3712811,8.869991540908813,16.52795995070897,1739141169.3712902,8.869991540908813,-0.4618359257345075,1739141169.371301,8.869991540908813,15.773684717419773,1739141169.371311,8.869991540908813,24.10276184257284,1739141169.3713157,8.869991540908813,-0.117,1739141169.3713214,8.869991540908813,0.045492675440122136,1739141169.3713262,8.869991540908813,0.39841406555469233,1739141169.3713307,8.869991540908813,0.053211886668032116,1739141169.3713355,8.869991540908813,2.1317113453538403,1739141169.3713412,8.869991540908813,0.0,1739141169.3713467,8.869991540908813,0.022881993626006993,1739141169.3713512,8.869991540908813,6.27611090225561,1739141169.371356,8.869991540908813,2.111789261421995 +1739141169.3903112,8.899991512298584,16.52795995070897,1739141169.3903208,8.899991512298584,-0.4618359257345075,1739141169.3903317,8.899991512298584,15.773684717419773,1739141169.3903415,8.899991512298584,24.10276184257284,1739141169.3903465,8.899991512298584,-0.117,1739141169.3903525,8.899991512298584,0.045492675440122136,1739141169.3903575,8.899991512298584,0.39841406555469233,1739141169.3903623,8.899991512298584,0.053211886668032116,1739141169.3903668,8.899991512298584,2.1317113453538403,1739141169.3903725,8.899991512298584,0.0,1739141169.3903775,8.899991512298584,0.019922083931845247,1739141169.390382,8.899991512298584,6.27611090225561,1739141169.3903863,8.899991512298584,2.111789261421995 +1739141169.4158483,8.919991493225098,16.52795995070897,1739141169.4158525,8.919991493225098,-0.4618359257345075,1739141169.4158573,8.919991493225098,15.773684717419773,1739141169.415862,8.919991493225098,24.10276184257284,1739141169.415864,8.919991493225098,-0.117,1739141169.415867,8.919991493225098,0.045492675440122136,1739141169.4158692,8.919991493225098,0.39841406555469233,1739141169.4158711,8.919991493225098,0.053211886668032116,1739141169.4158733,8.919991493225098,2.1317113453538403,1739141169.4158762,8.919991493225098,0.0,1739141169.4158788,8.919991493225098,0.019922083931845247,1739141169.4158807,8.919991493225098,6.27611090225561,1739141169.4158826,8.919991493225098,2.111789261421995 +1739141169.435381,8.939991474151611,16.52795995070897,1739141169.435384,8.939991474151611,-0.4618359257345075,1739141169.4353871,8.939991474151611,15.773684717419773,1739141169.4353902,8.939991474151611,24.10276184257284,1739141169.4353917,8.939991474151611,-0.117,1739141169.4353938,8.939991474151611,0.045492675440122136,1739141169.4353952,8.939991474151611,0.39841406555469233,1739141169.435397,8.939991474151611,0.053211886668032116,1739141169.435398,8.939991474151611,2.1317113453538403,1739141169.4354,8.939991474151611,0.0,1739141169.4354017,8.939991474151611,0.019922083931845247,1739141169.4354033,8.939991474151611,6.27611090225561,1739141169.4354048,8.939991474151611,2.111789261421995 +1739141169.4553702,8.959991455078125,16.52795995070897,1739141169.4553728,8.959991455078125,-0.4618359257345075,1739141169.4553761,8.959991455078125,15.773684717419773,1739141169.4553792,8.959991455078125,24.10276184257284,1739141169.4553807,8.959991455078125,-0.117,1739141169.4553826,8.959991455078125,0.045492675440122136,1739141169.4553843,8.959991455078125,0.39841406555469233,1739141169.4553857,8.959991455078125,0.053211886668032116,1739141169.455387,8.959991455078125,2.1317113453538403,1739141169.455389,8.959991455078125,0.0,1739141169.4553905,8.959991455078125,0.019922083931845247,1739141169.455392,8.959991455078125,6.27611090225561,1739141169.4553933,8.959991455078125,2.111789261421995 +1739141169.4749253,8.979991436004639,16.7603688542531,1739141169.4749284,8.979991436004639,-0.46338127486092784,1739141169.4749315,8.979991436004639,15.904164519085146,1739141169.4749346,8.979991436004639,24.24004901914551,1739141169.4749362,8.979991436004639,-0.11678821935654057,1739141169.4749382,8.979991436004639,0.04630482829576319,1739141169.4749396,8.979991436004639,0.3925045181123495,1739141169.4749413,8.979991436004639,0.05376031607118939,1739141169.4749424,8.979991436004639,2.1367562853987385,1739141169.4749444,8.979991436004639,0.0,1739141169.474946,8.979991436004639,0.025220821830245745,1739141169.4749477,8.979991436004639,6.27704623689376,1739141169.4749491,8.979991436004639,2.114058673351994 +1739141169.495512,8.999991416931152,16.7603688542531,1739141169.4955149,8.999991416931152,-0.46338127486092784,1739141169.4955182,8.999991416931152,15.904164519085146,1739141169.4955213,8.999991416931152,24.24004901914551,1739141169.495523,8.999991416931152,-0.11678821935654057,1739141169.4955251,8.999991416931152,0.04630482829576319,1739141169.4955266,8.999991416931152,0.3925045181123495,1739141169.495528,8.999991416931152,0.05376031607118939,1739141169.4955294,8.999991416931152,2.1367562853987385,1739141169.4955313,8.999991416931152,0.0,1739141169.4955328,8.999991416931152,0.022697612046744364,1739141169.4955344,8.999991416931152,6.27704623689376,1739141169.4955359,8.999991416931152,2.114058673351994 +1739141169.5152023,9.019991397857666,16.7603688542531,1739141169.5152054,9.019991397857666,-0.46338127486092784,1739141169.515209,9.019991397857666,15.904164519085146,1739141169.5152125,9.019991397857666,24.24004901914551,1739141169.515214,9.019991397857666,-0.11678821935654057,1739141169.5152164,9.019991397857666,0.04630482829576319,1739141169.515218,9.019991397857666,0.3925045181123495,1739141169.5152197,9.019991397857666,0.05376031607118939,1739141169.5152214,9.019991397857666,2.1367562853987385,1739141169.5152233,9.019991397857666,0.0,1739141169.5152252,9.019991397857666,0.022697612046744364,1739141169.5152266,9.019991397857666,6.27704623689376,1739141169.5152283,9.019991397857666,2.114058673351994 +1739141169.5408711,9.049991369247437,16.7603688542531,1739141169.54088,9.049991369247437,-0.46338127486092784,1739141169.5408902,9.049991369247437,15.904164519085146,1739141169.5408995,9.049991369247437,24.24004901914551,1739141169.540904,9.049991369247437,-0.11678821935654057,1739141169.5409098,9.049991369247437,0.04630482829576319,1739141169.5409148,9.049991369247437,0.3925045181123495,1739141169.5409193,9.049991369247437,0.05376031607118939,1739141169.5409236,9.049991369247437,2.1367562853987385,1739141169.5409296,9.049991369247437,0.0,1739141169.5409346,9.049991369247437,0.022697612046744364,1739141169.5409393,9.049991369247437,6.27704623689376,1739141169.5409439,9.049991369247437,2.114058673351994 +1739141169.5751007,9.079991340637207,16.7603688542531,1739141169.5751073,9.079991340637207,-0.46338127486092784,1739141169.5751145,9.079991340637207,15.904164519085146,1739141169.5751219,9.079991340637207,24.24004901914551,1739141169.5751255,9.079991340637207,-0.11678821935654057,1739141169.5751297,9.079991340637207,0.04630482829576319,1739141169.5751338,9.079991340637207,0.3925045181123495,1739141169.5751376,9.079991340637207,0.05376031607118939,1739141169.5751429,9.079991340637207,2.1367562853987385,1739141169.5751493,9.079991340637207,0.0,1739141169.5751534,9.079991340637207,0.022697612046744364,1739141169.5751572,9.079991340637207,6.27704623689376,1739141169.5751607,9.079991340637207,2.114058673351994 +1739141169.5943692,9.09999132156372,16.99304278090828,1739141169.5943744,9.09999132156372,-0.46471074741430574,1739141169.594379,9.09999132156372,16.11467738454291,1739141169.5943837,9.09999132156372,24.458235688793955,1739141169.5943859,9.09999132156372,-0.1150222928323068,1739141169.594389,9.09999132156372,0.0468083049449976,1739141169.5943916,9.09999132156372,0.3885304351396753,1739141169.5943942,9.09999132156372,0.05342030888945147,1739141169.5943964,9.09999132156372,2.14015564525876,1739141169.5943992,9.09999132156372,0.0,1739141169.5944016,9.09999132156372,0.024299422134684626,1739141169.5944045,9.09999132156372,6.27798157153191,1739141169.5944066,9.09999132156372,2.1166189902136536 +1739141169.6146123,9.119991302490234,16.99304278090828,1739141169.6146173,9.119991302490234,-0.46471074741430574,1739141169.6146228,9.119991302490234,16.11467738454291,1739141169.6146288,9.119991302490234,24.458235688793955,1739141169.614632,9.119991302490234,-0.1150222928323068,1739141169.6146362,9.119991302490234,0.0468083049449976,1739141169.6146398,9.119991302490234,0.3885304351396753,1739141169.614643,9.119991302490234,0.05342030888945147,1739141169.6146464,9.119991302490234,2.14015564525876,1739141169.6146507,9.119991302490234,0.0,1739141169.6146543,9.119991302490234,0.02353665504510616,1739141169.6146584,9.119991302490234,6.27798157153191,1739141169.6146617,9.119991302490234,2.1166189902136536 +1739141169.6365948,9.139991283416748,16.99304278090828,1739141169.6366026,9.139991283416748,-0.46471074741430574,1739141169.6366124,9.139991283416748,16.11467738454291,1739141169.6366186,9.139991283416748,24.458235688793955,1739141169.6366205,9.139991283416748,-0.1150222928323068,1739141169.6366231,9.139991283416748,0.0468083049449976,1739141169.6366265,9.139991283416748,0.3885304351396753,1739141169.6366286,9.139991283416748,0.05342030888945147,1739141169.6366305,9.139991283416748,2.14015564525876,1739141169.6366339,9.139991283416748,0.0,1739141169.6366365,9.139991283416748,0.02353665504510616,1739141169.6366389,9.139991283416748,6.27798157153191,1739141169.6366415,9.139991283416748,2.1166189902136536 +1739141169.6543198,9.159991264343262,16.99304278090828,1739141169.6543267,9.159991264343262,-0.46471074741430574,1739141169.6543348,9.159991264343262,16.11467738454291,1739141169.6543415,9.159991264343262,24.458235688793955,1739141169.6543438,9.159991264343262,-0.1150222928323068,1739141169.654347,9.159991264343262,0.0468083049449976,1739141169.6543496,9.159991264343262,0.3885304351396753,1739141169.6543527,9.159991264343262,0.05342030888945147,1739141169.6543553,9.159991264343262,2.14015564525876,1739141169.6543586,9.159991264343262,0.0,1739141169.6543612,9.159991264343262,0.02353665504510616,1739141169.6543639,9.159991264343262,6.27798157153191,1739141169.6543672,9.159991264343262,2.1166189902136536 +1739141169.6744335,9.179991245269775,16.99304278090828,1739141169.6744406,9.179991245269775,-0.46471074741430574,1739141169.6744485,9.179991245269775,16.11467738454291,1739141169.674453,9.179991245269775,24.458235688793955,1739141169.6744564,9.179991245269775,-0.1150222928323068,1739141169.6744606,9.179991245269775,0.0468083049449976,1739141169.6744633,9.179991245269775,0.3885304351396753,1739141169.6744661,9.179991245269775,0.05342030888945147,1739141169.6744883,9.179991245269775,2.14015564525876,1739141169.6744921,9.179991245269775,0.0,1739141169.6744947,9.179991245269775,0.02353665504510616,1739141169.6744988,9.179991245269775,6.27798157153191,1739141169.6745024,9.179991245269775,2.1166189902136536 +1739141169.702027,9.199991226196289,17.225997516672084,1739141169.7020338,9.199991226196289,-0.46582392753943314,1739141169.702041,9.199991226196289,16.371004072588164,1739141169.702048,9.199991226196289,24.722302996585782,1739141169.7020512,9.199991226196289,-0.114,1739141169.702057,9.199991226196289,0.04689856196405254,1739141169.7020614,9.199991226196289,0.38381786327808565,1739141169.702065,9.199991226196289,0.05233499920458569,1739141169.7020688,9.199991226196289,2.144193704901603,1739141169.7020733,9.199991226196289,0.0,1739141169.7020774,9.199991226196289,0.026317186329320855,1739141169.7020812,9.199991226196289,6.2789169061700605,1739141169.702086,9.199991226196289,2.119200581750002 +1739141169.714518,9.219991207122803,17.225997516672084,1739141169.7145236,9.219991207122803,-0.46582392753943314,1739141169.714529,9.219991207122803,16.371004072588164,1739141169.7145338,9.219991207122803,24.722302996585782,1739141169.7145371,9.219991207122803,-0.114,1739141169.7145412,9.219991207122803,0.04689856196405254,1739141169.7145452,9.219991207122803,0.38381786327808565,1739141169.7145488,9.219991207122803,0.05233499920458569,1739141169.7145526,9.219991207122803,2.144193704901603,1739141169.7145567,9.219991207122803,0.0,1739141169.7145605,9.219991207122803,0.024993123151600738,1739141169.7145646,9.219991207122803,6.2789169061700605,1739141169.7145686,9.219991207122803,2.119200581750002 +1739141169.7357898,9.239991188049316,17.225997516672084,1739141169.7357953,9.239991188049316,-0.46582392753943314,1739141169.7358,9.239991188049316,16.371004072588164,1739141169.735806,9.239991188049316,24.722302996585782,1739141169.7358098,9.239991188049316,-0.114,1739141169.7358136,9.239991188049316,0.04689856196405254,1739141169.7358172,9.239991188049316,0.38381786327808565,1739141169.73582,9.239991188049316,0.05233499920458569,1739141169.7358232,9.239991188049316,2.144193704901603,1739141169.7358267,9.239991188049316,0.0,1739141169.7358308,9.239991188049316,0.024993123151600738,1739141169.7358341,9.239991188049316,6.2789169061700605,1739141169.7358377,9.239991188049316,2.119200581750002 +1739141169.7541263,9.25999116897583,17.225997516672084,1739141169.7541304,9.25999116897583,-0.46582392753943314,1739141169.7541351,9.25999116897583,16.371004072588164,1739141169.7541401,9.25999116897583,24.722302996585782,1739141169.7541437,9.25999116897583,-0.114,1739141169.7541473,9.25999116897583,0.04689856196405254,1739141169.7541506,9.25999116897583,0.38381786327808565,1739141169.754154,9.25999116897583,0.05233499920458569,1739141169.7541573,9.25999116897583,2.144193704901603,1739141169.7541606,9.25999116897583,0.0,1739141169.7541642,9.25999116897583,0.024993123151600738,1739141169.7541676,9.25999116897583,6.2789169061700605,1739141169.7541873,9.25999116897583,2.119200581750002 +1739141169.7741506,9.279991149902344,17.225997516672084,1739141169.7741532,9.279991149902344,-0.46582392753943314,1739141169.774156,9.279991149902344,16.371004072588164,1739141169.7741592,9.279991149902344,24.722302996585782,1739141169.7741604,9.279991149902344,-0.114,1739141169.7741618,9.279991149902344,0.04689856196405254,1739141169.7741635,9.279991149902344,0.38381786327808565,1739141169.7741647,9.279991149902344,0.05233499920458569,1739141169.7741659,9.279991149902344,2.144193704901603,1739141169.7741673,9.279991149902344,0.0,1739141169.7741685,9.279991149902344,0.024993123151600738,1739141169.77417,9.279991149902344,6.2789169061700605,1739141169.7741709,9.279991149902344,2.119200581750002 +1739141169.7937832,9.299991130828857,17.225997516672084,1739141169.7937868,9.299991130828857,-0.46582392753943314,1739141169.79379,9.299991130828857,16.371004072588164,1739141169.793793,9.299991130828857,24.722302996585782,1739141169.7937944,9.299991130828857,-0.114,1739141169.7937958,9.299991130828857,0.04689856196405254,1739141169.7937975,9.299991130828857,0.38381786327808565,1739141169.793799,9.299991130828857,0.05233499920458569,1739141169.7937999,9.299991130828857,2.144193704901603,1739141169.7938018,9.299991130828857,0.0,1739141169.7938035,9.299991130828857,0.024993123151600738,1739141169.793805,9.299991130828857,6.2789169061700605,1739141169.793806,9.299991130828857,2.119200581750002 +1739141169.8142884,9.319991111755371,17.459244430960013,1739141169.814291,9.319991111755371,-0.46672033459030704,1739141169.8142939,9.319991111755371,16.604032961559852,1739141169.8142967,9.319991111755371,24.963530315245844,1739141169.8142982,9.319991111755371,-0.11392251776222892,1739141169.8142998,9.319991111755371,0.046978253176773226,1739141169.8143013,9.319991111755371,0.3778080937664561,1739141169.8143024,9.319991111755371,0.05140583361470205,1739141169.8143036,9.319991111755371,2.1493543492549376,1739141169.8143055,9.319991111755371,0.0,1739141169.8143067,9.319991111755371,0.02962788151626975,1739141169.814308,9.319991111755371,6.279852240808211,1739141169.8143091,9.319991111755371,2.1219334966338748 +1739141169.8335133,9.339991092681885,17.459244430960013,1739141169.8335161,9.339991092681885,-0.46672033459030704,1739141169.8335192,9.339991092681885,16.604032961559852,1739141169.833522,9.339991092681885,24.963530315245844,1739141169.8335235,9.339991092681885,-0.11392251776222892,1739141169.8335252,9.339991092681885,0.046978253176773226,1739141169.8335268,9.339991092681885,0.3778080937664561,1739141169.833528,9.339991092681885,0.05140583361470205,1739141169.8335292,9.339991092681885,2.1493543492549376,1739141169.833531,9.339991092681885,0.0,1739141169.833532,9.339991092681885,0.027420852621062863,1739141169.8335335,9.339991092681885,6.279852240808211,1739141169.833535,9.339991092681885,2.1219334966338748 +1739141169.853412,9.359991073608398,17.459244430960013,1739141169.8534143,9.359991073608398,-0.46672033459030704,1739141169.8534174,9.359991073608398,16.604032961559852,1739141169.8534205,9.359991073608398,24.963530315245844,1739141169.853422,9.359991073608398,-0.11392251776222892,1739141169.8534236,9.359991073608398,0.046978253176773226,1739141169.8534253,9.359991073608398,0.3778080937664561,1739141169.8534267,9.359991073608398,0.05140583361470205,1739141169.853428,9.359991073608398,2.1493543492549376,1739141169.8534296,9.359991073608398,0.0,1739141169.853431,9.359991073608398,0.027420852621062863,1739141169.8534324,9.359991073608398,6.279852240808211,1739141169.8534336,9.359991073608398,2.1219334966338748 +1739141169.873978,9.379991054534912,17.459244430960013,1739141169.8739812,9.379991054534912,-0.46672033459030704,1739141169.873985,9.379991054534912,16.604032961559852,1739141169.8739886,9.379991054534912,24.963530315245844,1739141169.87399,9.379991054534912,-0.11392251776222892,1739141169.8739924,9.379991054534912,0.046978253176773226,1739141169.8739944,9.379991054534912,0.3778080937664561,1739141169.8739958,9.379991054534912,0.05140583361470205,1739141169.8739972,9.379991054534912,2.1493543492549376,1739141169.8739996,9.379991054534912,0.0,1739141169.8740015,9.379991054534912,0.027420852621062863,1739141169.8740034,9.379991054534912,6.279852240808211,1739141169.874005,9.379991054534912,2.1219334966338748 +1739141169.894578,9.399991035461426,17.459244430960013,1739141169.8945856,9.399991035461426,-0.46672033459030704,1739141169.8945951,9.399991035461426,16.604032961559852,1739141169.8946028,9.399991035461426,24.963530315245844,1739141169.8946073,9.399991035461426,-0.11392251776222892,1739141169.894614,9.399991035461426,0.046978253176773226,1739141169.894621,9.399991035461426,0.3778080937664561,1739141169.8946285,9.399991035461426,0.05140583361470205,1739141169.894636,9.399991035461426,2.1493543492549376,1739141169.8946414,9.399991035461426,0.0,1739141169.8946476,9.399991035461426,0.027420852621062863,1739141169.8946548,9.399991035461426,6.279852240808211,1739141169.8946595,9.399991035461426,2.1219334966338748 +1739141169.9150329,9.41999101638794,17.692807586640953,1739141169.9150367,9.41999101638794,-0.4673994923158924,1739141169.915041,9.41999101638794,16.9019058942024,1739141169.915045,9.41999101638794,25.27045837954769,1739141169.915047,9.41999101638794,-0.113,1739141169.9150496,9.41999101638794,0.04673498987606855,1739141169.9150512,9.41999101638794,0.3725676299342333,1739141169.9150534,9.41999101638794,0.04971740913005945,1739141169.915055,9.41999101638794,2.1538645201729407,1739141169.9150574,9.41999101638794,0.0,1739141169.9150596,9.41999101638794,0.03026643733072076,1739141169.9150615,9.41999101638794,6.280787575446361,1739141169.9150634,9.41999101638794,2.1249531238570545 +1739141169.9351358,9.439990997314453,17.692807586640953,1739141169.935143,9.439990997314453,-0.4673994923158924,1739141169.9351518,9.439990997314453,16.9019058942024,1739141169.9351604,9.439990997314453,25.27045837954769,1739141169.9351652,9.439990997314453,-0.113,1739141169.935171,9.439990997314453,0.04673498987606855,1739141169.9351757,9.439990997314453,0.3725676299342333,1739141169.9351811,9.439990997314453,0.04971740913005945,1739141169.9351861,9.439990997314453,2.1538645201729407,1739141169.9351914,9.439990997314453,0.0,1739141169.9351964,9.439990997314453,0.02891139631588624,1739141169.9352012,9.439990997314453,6.280787575446361,1739141169.935206,9.439990997314453,2.1249531238570545 +1739141169.9551947,9.459990978240967,17.692807586640953,1739141169.9551995,9.459990978240967,-0.4673994923158924,1739141169.9552038,9.459990978240967,16.9019058942024,1739141169.9552076,9.459990978240967,25.27045837954769,1739141169.9552095,9.459990978240967,-0.113,1739141169.955212,9.459990978240967,0.04673498987606855,1739141169.9552138,9.459990978240967,0.3725676299342333,1739141169.9552157,9.459990978240967,0.04971740913005945,1739141169.9552176,9.459990978240967,2.1538645201729407,1739141169.9552197,9.459990978240967,0.0,1739141169.9552217,9.459990978240967,0.02891139631588624,1739141169.9552236,9.459990978240967,6.280787575446361,1739141169.9552252,9.459990978240967,2.1249531238570545 +1739141169.9748955,9.47999095916748,17.692807586640953,1739141169.9748995,9.47999095916748,-0.4673994923158924,1739141169.9749038,9.47999095916748,16.9019058942024,1739141169.9749076,9.47999095916748,25.27045837954769,1739141169.97491,9.47999095916748,-0.113,1739141169.9749122,9.47999095916748,0.04673498987606855,1739141169.9749143,9.47999095916748,0.3725676299342333,1739141169.974916,9.47999095916748,0.04971740913005945,1739141169.974918,9.47999095916748,2.1538645201729407,1739141169.9749203,9.47999095916748,0.0,1739141169.9749222,9.47999095916748,0.02891139631588624,1739141169.974924,9.47999095916748,6.280787575446361,1739141169.9749258,9.47999095916748,2.1249531238570545 +1739141169.9950244,9.499990940093994,17.692807586640953,1739141169.995028,9.499990940093994,-0.4673994923158924,1739141169.995032,9.499990940093994,16.9019058942024,1739141169.9950356,9.499990940093994,25.27045837954769,1739141169.9950378,9.499990940093994,-0.113,1739141169.9950402,9.499990940093994,0.04673498987606855,1739141169.9950423,9.499990940093994,0.3725676299342333,1739141169.995044,9.499990940093994,0.04971740913005945,1739141169.995046,9.499990940093994,2.1538645201729407,1739141169.995048,9.499990940093994,0.0,1739141169.9950504,9.499990940093994,0.02891139631588624,1739141169.9950523,9.499990940093994,6.280787575446361,1739141169.9950542,9.499990940093994,2.1249531238570545 +1739141170.0150974,9.519990921020508,17.692807586640953,1739141170.0151026,9.519990921020508,-0.4673994923158924,1739141170.0151112,9.519990921020508,16.9019058942024,1739141170.0151248,9.519990921020508,25.27045837954769,1739141170.0151303,9.519990921020508,-0.113,1739141170.0151362,9.519990921020508,0.04673498987606855,1739141170.0151405,9.519990921020508,0.3725676299342333,1739141170.0151465,9.519990921020508,0.04971740913005945,1739141170.0151536,9.519990921020508,2.1538645201729407,1739141170.0151584,9.519990921020508,0.0,1739141170.0151637,9.519990921020508,0.02891139631588624,1739141170.0151682,9.519990921020508,6.280787575446361,1739141170.015173,9.519990921020508,2.1249531238570545 +1739141170.0346954,9.539990901947021,17.926713103407845,1739141170.0347,9.539990901947021,-0.4678608630821577,1739141170.0347044,9.539990901947021,17.177047796236252,1739141170.0347085,9.539990901947021,25.55517404502219,1739141170.0347102,9.539990901947021,-0.11212053621933178,1739141170.0347128,9.539990901947021,0.046599542624869546,1739141170.0347147,9.539990901947021,0.3668957816134178,1739141170.0347166,9.539990901947021,0.04831134412953787,1739141170.0347185,9.539990901947021,2.1587566246743064,1739141170.0347207,9.539990901947021,0.0,1739141170.034723,9.539990901947021,0.03215620010450104,1739141170.034725,9.539990901947021,6.281722910084511,1739141170.0347269,9.539990901947021,2.128145570002918 +1739141170.0548127,9.559990882873535,17.926713103407845,1739141170.0548165,9.559990882873535,-0.4678608630821577,1739141170.0548208,9.559990882873535,17.177047796236252,1739141170.0548246,9.559990882873535,25.55517404502219,1739141170.0548265,9.559990882873535,-0.11212053621933178,1739141170.054829,9.559990882873535,0.046599542624869546,1739141170.0548308,9.559990882873535,0.3668957816134178,1739141170.054833,9.559990882873535,0.04831134412953787,1739141170.0548346,9.559990882873535,2.1587566246743064,1739141170.054837,9.559990882873535,0.0,1739141170.0548391,9.559990882873535,0.03061105467138825,1739141170.0548408,9.559990882873535,6.281722910084511,1739141170.0548427,9.559990882873535,2.128145570002918 +1739141170.0750701,9.579990863800049,17.926713103407845,1739141170.0750742,9.579990863800049,-0.4678608630821577,1739141170.0750792,9.579990863800049,17.177047796236252,1739141170.0750837,9.579990863800049,25.55517404502219,1739141170.0750859,9.579990863800049,-0.11212053621933178,1739141170.0750887,9.579990863800049,0.046599542624869546,1739141170.0750906,9.579990863800049,0.3668957816134178,1739141170.0750928,9.579990863800049,0.04831134412953787,1739141170.0750947,9.579990863800049,2.1587566246743064,1739141170.0750973,9.579990863800049,0.0,1739141170.0751,9.579990863800049,0.03061105467138825,1739141170.0751019,9.579990863800049,6.281722910084511,1739141170.075104,9.579990863800049,2.128145570002918 +1739141170.0963166,9.599990844726562,17.926713103407845,1739141170.0963213,9.599990844726562,-0.4678608630821577,1739141170.0963268,9.599990844726562,17.177047796236252,1739141170.096332,9.599990844726562,25.55517404502219,1739141170.0963347,9.599990844726562,-0.11212053621933178,1739141170.0963373,9.599990844726562,0.046599542624869546,1739141170.0963397,9.599990844726562,0.3668957816134178,1739141170.0963423,9.599990844726562,0.04831134412953787,1739141170.0963442,9.599990844726562,2.1587566246743064,1739141170.096347,9.599990844726562,0.0,1739141170.0963497,9.599990844726562,0.03061105467138825,1739141170.096352,9.599990844726562,6.281722910084511,1739141170.096354,9.599990844726562,2.128145570002918 +1739141170.1152356,9.619990825653076,17.926713103407845,1739141170.115241,9.619990825653076,-0.4678608630821577,1739141170.1152465,9.619990825653076,17.177047796236252,1739141170.1152515,9.619990825653076,25.55517404502219,1739141170.1152542,9.619990825653076,-0.11212053621933178,1739141170.1152575,9.619990825653076,0.046599542624869546,1739141170.11526,9.619990825653076,0.3668957816134178,1739141170.115262,9.619990825653076,0.04831134412953787,1739141170.1152642,9.619990825653076,2.1587566246743064,1739141170.115267,9.619990825653076,0.0,1739141170.11527,9.619990825653076,0.03061105467138825,1739141170.1152725,9.619990825653076,6.281722910084511,1739141170.1152747,9.619990825653076,2.128145570002918 +1739141170.13446,9.63999080657959,18.160975410755086,1739141170.1344652,9.63999080657959,-0.4681038219552409,1739141170.1344895,9.63999080657959,17.41370266321313,1739141170.1344945,9.63999080657959,25.801851798769754,1739141170.1344962,9.63999080657959,-0.113,1739141170.134499,9.63999080657959,0.0464408108826713,1739141170.134501,9.63999080657959,0.3591309915279114,1739141170.134503,9.63999080657959,0.04713624861313819,1739141170.1345048,9.63999080657959,2.16547196473159,1739141170.1345067,9.63999080657959,0.0,1739141170.1345088,9.63999080657959,0.03704952589882247,1739141170.1345105,9.63999080657959,6.282658244722661,1739141170.1345127,9.63999080657959,2.131488379044069 +1739141170.155637,9.659990787506104,18.160975410755086,1739141170.155643,9.659990787506104,-0.4681038219552409,1739141170.1556475,9.659990787506104,17.41370266321313,1739141170.155652,9.659990787506104,25.801851798769754,1739141170.1556542,9.659990787506104,-0.113,1739141170.1556568,9.659990787506104,0.0464408108826713,1739141170.1556587,9.659990787506104,0.3591309915279114,1739141170.1556606,9.659990787506104,0.04713624861313819,1739141170.1556623,9.659990787506104,2.16547196473159,1739141170.155665,9.659990787506104,0.0,1739141170.1556678,9.659990787506104,0.0339835856875208,1739141170.1556697,9.659990787506104,6.282658244722661,1739141170.1556716,9.659990787506104,2.131488379044069 +1739141170.17551,9.679990768432617,18.160975410755086,1739141170.1755152,9.679990768432617,-0.4681038219552409,1739141170.1755207,9.679990768432617,17.41370266321313,1739141170.1755257,9.679990768432617,25.801851798769754,1739141170.1755276,9.679990768432617,-0.113,1739141170.1755304,9.679990768432617,0.0464408108826713,1739141170.1755333,9.679990768432617,0.3591309915279114,1739141170.1755362,9.679990768432617,0.04713624861313819,1739141170.1755388,9.679990768432617,2.16547196473159,1739141170.1755424,9.679990768432617,0.0,1739141170.1755443,9.679990768432617,0.0339835856875208,1739141170.1755464,9.679990768432617,6.282658244722661,1739141170.1755483,9.679990768432617,2.131488379044069 +1739141170.1934977,9.69999074935913,18.160975410755086,1739141170.193501,9.69999074935913,-0.4681038219552409,1739141170.1935046,9.69999074935913,17.41370266321313,1739141170.193508,9.69999074935913,25.801851798769754,1739141170.1935096,9.69999074935913,-0.113,1739141170.1935115,9.69999074935913,0.0464408108826713,1739141170.1935132,9.69999074935913,0.3591309915279114,1739141170.193515,9.69999074935913,0.04713624861313819,1739141170.1935165,9.69999074935913,2.16547196473159,1739141170.1935186,9.69999074935913,0.0,1739141170.1935203,9.69999074935913,0.0339835856875208,1739141170.193522,9.69999074935913,6.282658244722661,1739141170.1935234,9.69999074935913,2.131488379044069 +1739141170.2147746,9.719990730285645,18.160975410755086,1739141170.2147784,9.719990730285645,-0.4681038219552409,1739141170.2147834,9.719990730285645,17.41370266321313,1739141170.2147872,9.719990730285645,25.801851798769754,1739141170.2147896,9.719990730285645,-0.113,1739141170.2147918,9.719990730285645,0.0464408108826713,1739141170.2147937,9.719990730285645,0.3591309915279114,1739141170.2147954,9.719990730285645,0.04713624861313819,1739141170.2147975,9.719990730285645,2.16547196473159,1739141170.2148,9.719990730285645,0.0,1739141170.214802,9.719990730285645,0.0339835856875208,1739141170.214804,9.719990730285645,6.282658244722661,1739141170.2148058,9.719990730285645,2.131488379044069 +1739141170.23491,9.739990711212158,18.160975410755086,1739141170.2349145,9.739990711212158,-0.4681038219552409,1739141170.2349184,9.739990711212158,17.41370266321313,1739141170.2349224,9.739990711212158,25.801851798769754,1739141170.234924,9.739990711212158,-0.113,1739141170.2349262,9.739990711212158,0.0464408108826713,1739141170.2349284,9.739990711212158,0.3591309915279114,1739141170.23493,9.739990711212158,0.04713624861313819,1739141170.2349317,9.739990711212158,2.16547196473159,1739141170.2349339,9.739990711212158,0.0,1739141170.2349355,9.739990711212158,0.0339835856875208,1739141170.2349372,9.739990711212158,6.282658244722661,1739141170.2349389,9.739990711212158,2.131488379044069 +1739141170.2551208,9.759990692138672,18.395633761078443,1739141170.2551243,9.759990692138672,-0.4681277037448792,1739141170.2551281,9.759990692138672,17.545468348551285,1739141170.2551315,9.759990692138672,25.945053899820003,1739141170.2551332,9.759990692138672,-0.113,1739141170.255135,9.759990692138672,0.047005743806036414,1739141170.2551365,9.759990692138672,0.3520454560060381,1739141170.2551384,9.759990692138672,0.04733003147998846,1739141170.2551398,9.759990692138672,2.1716180817345547,1739141170.2551422,9.759990692138672,0.0,1739141170.255144,9.759990692138672,0.038439364718080835,1739141170.2551455,9.759990692138672,0.0004082721812252206,1739141170.2551475,9.759990692138672,2.135300517614768 +1739141170.27501,9.779990673065186,18.395633761078443,1739141170.275014,9.779990673065186,-0.4681277037448792,1739141170.2750175,9.779990673065186,17.545468348551285,1739141170.2750216,9.779990673065186,25.945053899820003,1739141170.2750232,9.779990673065186,-0.113,1739141170.2750254,9.779990673065186,0.047005743806036414,1739141170.275027,9.779990673065186,0.3520454560060381,1739141170.2750287,9.779990673065186,0.04733003147998846,1739141170.2750306,9.779990673065186,2.1716180817345547,1739141170.2750325,9.779990673065186,0.0,1739141170.2750342,9.779990673065186,0.036317564119786816,1739141170.2750356,9.779990673065186,0.0004082721812252206,1739141170.2750378,9.779990673065186,2.135300517614768 +1739141170.2954807,9.7999906539917,18.395633761078443,1739141170.2954862,9.7999906539917,-0.4681277037448792,1739141170.2954924,9.7999906539917,17.545468348551285,1739141170.295499,9.7999906539917,25.945053899820003,1739141170.2955027,9.7999906539917,-0.113,1739141170.295507,9.7999906539917,0.047005743806036414,1739141170.295511,9.7999906539917,0.3520454560060381,1739141170.2955153,9.7999906539917,0.04733003147998846,1739141170.2955196,9.7999906539917,2.1716180817345547,1739141170.295524,9.7999906539917,0.0,1739141170.2955282,9.7999906539917,0.036317564119786816,1739141170.2955325,9.7999906539917,0.0004082721812252206,1739141170.2955363,9.7999906539917,2.135300517614768 +1739141170.3143027,9.819990634918213,18.395633761078443,1739141170.3143084,9.819990634918213,-0.4681277037448792,1739141170.3143146,9.819990634918213,17.545468348551285,1739141170.3143208,9.819990634918213,25.945053899820003,1739141170.3143244,9.819990634918213,-0.113,1739141170.3143296,9.819990634918213,0.047005743806036414,1739141170.3143337,9.819990634918213,0.3520454560060381,1739141170.3143377,9.819990634918213,0.04733003147998846,1739141170.3143415,9.819990634918213,2.1716180817345547,1739141170.3143463,9.819990634918213,0.0,1739141170.3143506,9.819990634918213,0.036317564119786816,1739141170.3143551,9.819990634918213,0.0004082721812252206,1739141170.3143592,9.819990634918213,2.135300517614768 +1739141170.3340046,9.839990615844727,18.395633761078443,1739141170.3340123,9.839990615844727,-0.4681277037448792,1739141170.3340216,9.839990615844727,17.545468348551285,1739141170.3340306,9.839990615844727,25.945053899820003,1739141170.3340347,9.839990615844727,-0.113,1739141170.3340404,9.839990615844727,0.047005743806036414,1739141170.3340452,9.839990615844727,0.3520454560060381,1739141170.334051,9.839990615844727,0.04733003147998846,1739141170.334055,9.839990615844727,2.1716180817345547,1739141170.3340592,9.839990615844727,0.0,1739141170.3340635,9.839990615844727,0.036317564119786816,1739141170.3340678,9.839990615844727,0.0004082721812252206,1739141170.3340719,9.839990615844727,2.135300517614768 +1739141170.3543124,9.85999059677124,18.630714007293086,1739141170.3543184,9.85999059677124,-0.46793174813382343,1739141170.3543243,9.85999059677124,17.80733090252556,1739141170.3543313,9.85999059677124,26.218808376599114,1739141170.3543348,9.85999059677124,-0.112,1739141170.3543396,9.85999059677124,0.0468722489517875,1739141170.354344,9.85999059677124,0.34573601458269687,1739141170.354348,9.85999059677124,0.04600995880452654,1739141170.3543522,9.85999059677124,2.177105682393017,1739141170.3543565,9.85999059677124,0.0,1739141170.354361,9.85999059677124,0.03922371992860627,1739141170.3543653,9.85999059677124,0.00134360681937545,1739141170.3543696,9.85999059677124,2.1392658468742067 +1739141170.3742225,9.879990577697754,18.630714007293086,1739141170.374227,9.879990577697754,-0.46793174813382343,1739141170.3742309,9.879990577697754,17.80733090252556,1739141170.3742347,9.879990577697754,26.218808376599114,1739141170.374236,9.879990577697754,-0.112,1739141170.3742383,9.879990577697754,0.0468722489517875,1739141170.3742404,9.879990577697754,0.34573601458269687,1739141170.3742423,9.879990577697754,0.04600995880452654,1739141170.3742437,9.879990577697754,2.177105682393017,1739141170.374246,9.879990577697754,0.0,1739141170.3742478,9.879990577697754,0.037839835518810094,1739141170.3742495,9.879990577697754,0.00134360681937545,1739141170.374251,9.879990577697754,2.1392658468742067 +1739141170.3960392,9.899990558624268,18.630714007293086,1739141170.3960469,9.899990558624268,-0.46793174813382343,1739141170.3960512,9.899990558624268,17.80733090252556,1739141170.3960588,9.899990558624268,26.218808376599114,1739141170.396064,9.899990558624268,-0.112,1739141170.3960695,9.899990558624268,0.0468722489517875,1739141170.3960743,9.899990558624268,0.34573601458269687,1739141170.3960793,9.899990558624268,0.04600995880452654,1739141170.3960814,9.899990558624268,2.177105682393017,1739141170.3960836,9.899990558624268,0.0,1739141170.3960888,9.899990558624268,0.037839835518810094,1739141170.3960938,9.899990558624268,0.00134360681937545,1739141170.3960984,9.899990558624268,2.1392658468742067 +1739141170.4139838,9.919990539550781,18.630714007293086,1739141170.4139876,9.919990539550781,-0.46793174813382343,1739141170.413992,9.919990539550781,17.80733090252556,1739141170.4139953,9.919990539550781,26.218808376599114,1739141170.4139972,9.919990539550781,-0.112,1739141170.413999,9.919990539550781,0.0468722489517875,1739141170.4140012,9.919990539550781,0.34573601458269687,1739141170.414003,9.919990539550781,0.04600995880452654,1739141170.4140048,9.919990539550781,2.177105682393017,1739141170.4140065,9.919990539550781,0.0,1739141170.4140084,9.919990539550781,0.037839835518810094,1739141170.4140098,9.919990539550781,0.00134360681937545,1739141170.4140117,9.919990539550781,2.1392658468742067 +1739141170.4341488,9.939990520477295,18.630714007293086,1739141170.4341552,9.939990520477295,-0.46793174813382343,1739141170.4341626,9.939990520477295,17.80733090252556,1739141170.4341679,9.939990520477295,26.218808376599114,1739141170.4341726,9.939990520477295,-0.112,1739141170.4341757,9.939990520477295,0.0468722489517875,1739141170.4341798,9.939990520477295,0.34573601458269687,1739141170.4341853,9.939990520477295,0.04600995880452654,1739141170.4341903,9.939990520477295,2.177105682393017,1739141170.4341955,9.939990520477295,0.0,1739141170.434198,9.939990520477295,0.037839835518810094,1739141170.4342003,9.939990520477295,0.00134360681937545,1739141170.4342027,9.939990520477295,2.1392658468742067 +1739141170.4535756,9.959990501403809,18.630714007293086,1739141170.453579,9.959990501403809,-0.46793174813382343,1739141170.4535825,9.959990501403809,17.80733090252556,1739141170.4535856,9.959990501403809,26.218808376599114,1739141170.4535878,9.959990501403809,-0.112,1739141170.4535894,9.959990501403809,0.0468722489517875,1739141170.4535913,9.959990501403809,0.34573601458269687,1739141170.453593,9.959990501403809,0.04600995880452654,1739141170.4535944,9.959990501403809,2.177105682393017,1739141170.4535964,9.959990501403809,0.0,1739141170.4535983,9.959990501403809,0.037839835518810094,1739141170.4535997,9.959990501403809,0.00134360681937545,1739141170.4536014,9.959990501403809,2.1392658468742067 +1739141170.4742644,9.979990482330322,18.86624413669995,1739141170.4742694,9.979990482330322,-0.4675151161319455,1739141170.4742756,9.979990482330322,18.126892961736136,1739141170.4742823,9.979990482330322,26.550914343619127,1739141170.474286,9.979990482330322,-0.11001887471837896,1739141170.4742908,9.979990482330322,0.04648718439142047,1739141170.4742954,9.979990482330322,0.3399824147094843,1739141170.4742994,9.979990482330322,0.044116091135302564,1739141170.4743035,9.979990482330322,2.182121930467049,1739141170.4743078,9.979990482330322,0.0,1739141170.4743123,9.979990482330322,0.039428118567264525,1739141170.4743161,9.979990482330322,0.0022789414575256797,1739141170.4743204,9.979990482330322,2.143450137538771 +1739141170.4938529,9.999990463256836,18.86624413669995,1739141170.4938576,9.999990463256836,-0.4675151161319455,1739141170.493862,9.999990463256836,18.126892961736136,1739141170.4938655,9.999990463256836,26.550914343619127,1739141170.4938672,9.999990463256836,-0.11001887471837896,1739141170.4938695,9.999990463256836,0.04648718439142047,1739141170.4938715,9.999990463256836,0.3399824147094843,1739141170.4938731,9.999990463256836,0.044116091135302564,1739141170.4938748,9.999990463256836,2.182121930467049,1739141170.4938767,9.999990463256836,0.0,1739141170.4938788,9.999990463256836,0.03867179292827805,1739141170.49388,9.999990463256836,0.0022789414575256797,1739141170.493882,9.999990463256836,2.143450137538771 +1739141170.5160713,10.01999044418335,18.86624413669995,1739141170.5160778,10.01999044418335,-0.4675151161319455,1739141170.5160837,10.01999044418335,18.126892961736136,1739141170.5160906,10.01999044418335,26.550914343619127,1739141170.5160942,10.01999044418335,-0.11001887471837896,1739141170.5160987,10.01999044418335,0.04648718439142047,1739141170.516103,10.01999044418335,0.3399824147094843,1739141170.5161073,10.01999044418335,0.044116091135302564,1739141170.5161114,10.01999044418335,2.182121930467049,1739141170.5161157,10.01999044418335,0.0,1739141170.51612,10.01999044418335,0.03867179292827805,1739141170.5161242,10.01999044418335,0.0022789414575256797,1739141170.5161283,10.01999044418335,2.143450137538771 +1739141170.5351443,10.039990425109863,18.86624413669995,1739141170.5351496,10.039990425109863,-0.4675151161319455,1739141170.535156,10.039990425109863,18.126892961736136,1739141170.5351624,10.039990425109863,26.550914343619127,1739141170.535166,10.039990425109863,-0.11001887471837896,1739141170.5351706,10.039990425109863,0.04648718439142047,1739141170.535175,10.039990425109863,0.3399824147094843,1739141170.5351794,10.039990425109863,0.044116091135302564,1739141170.5351837,10.039990425109863,2.182121930467049,1739141170.5351884,10.039990425109863,0.0,1739141170.5351927,10.039990425109863,0.03867179292827805,1739141170.5351973,10.039990425109863,0.0022789414575256797,1739141170.5352015,10.039990425109863,2.143450137538771 +1739141170.5540695,10.059990406036377,18.86624413669995,1739141170.5540736,10.059990406036377,-0.4675151161319455,1739141170.5540776,10.059990406036377,18.126892961736136,1739141170.5540812,10.059990406036377,26.550914343619127,1739141170.5540829,10.059990406036377,-0.11001887471837896,1739141170.5540857,10.059990406036377,0.04648718439142047,1739141170.5540876,10.059990406036377,0.3399824147094843,1739141170.5540895,10.059990406036377,0.044116091135302564,1739141170.5540907,10.059990406036377,2.182121930467049,1739141170.5540931,10.059990406036377,0.0,1739141170.5540948,10.059990406036377,0.03867179292827805,1739141170.5540965,10.059990406036377,0.0022789414575256797,1739141170.554098,10.059990406036377,2.143450137538771 +1739141170.5752854,10.07999038696289,19.102234949637214,1739141170.5752902,10.07999038696289,-0.46687693723426715,1739141170.5752943,10.07999038696289,18.47296847966738,1739141170.5752976,10.07999038696289,26.90967712534239,1739141170.5752993,10.07999038696289,-0.10610018597282611,1739141170.5753016,10.07999038696289,0.04617649191632199,1739141170.5753043,10.07999038696289,0.33567965602627253,1739141170.5753057,10.07999038696289,0.042200119500762745,1739141170.5753076,10.07999038696289,2.1858808218933703,1739141170.5753093,10.07999038696289,0.0,1739141170.5753112,10.07999038696289,0.03775882915983445,1739141170.5753129,10.07999038696289,0.0032142760956759076,1739141170.5753145,10.07999038696289,2.147687247864722 +1739141170.5935595,10.099990367889404,19.102234949637214,1739141170.5935626,10.099990367889404,-0.46687693723426715,1739141170.5935664,10.099990367889404,18.47296847966738,1739141170.5935695,10.099990367889404,26.90967712534239,1739141170.5935714,10.099990367889404,-0.10610018597282611,1739141170.5935736,10.099990367889404,0.04617649191632199,1739141170.5935755,10.099990367889404,0.33567965602627253,1739141170.593577,10.099990367889404,0.042200119500762745,1739141170.5935786,10.099990367889404,2.1858808218933703,1739141170.5935802,10.099990367889404,0.0,1739141170.5935822,10.099990367889404,0.038193574028648314,1739141170.5935836,10.099990367889404,0.0032142760956759076,1739141170.5935857,10.099990367889404,2.147687247864722 +1739141170.6134672,10.119990348815918,19.102234949637214,1739141170.6134698,10.119990348815918,-0.46687693723426715,1739141170.613474,10.119990348815918,18.47296847966738,1739141170.6134772,10.119990348815918,26.90967712534239,1739141170.6134791,10.119990348815918,-0.10610018597282611,1739141170.6134813,10.119990348815918,0.04617649191632199,1739141170.6134832,10.119990348815918,0.33567965602627253,1739141170.6134849,10.119990348815918,0.042200119500762745,1739141170.6134863,10.119990348815918,2.1858808218933703,1739141170.6134884,10.119990348815918,0.0,1739141170.6134899,10.119990348815918,0.038193574028648314,1739141170.6134918,10.119990348815918,0.0032142760956759076,1739141170.6134934,10.119990348815918,2.147687247864722 +1739141170.6345327,10.139990329742432,19.102234949637214,1739141170.6345358,10.139990329742432,-0.46687693723426715,1739141170.6345398,10.139990329742432,18.47296847966738,1739141170.6345432,10.139990329742432,26.90967712534239,1739141170.6345446,10.139990329742432,-0.10610018597282611,1739141170.6345475,10.139990329742432,0.04617649191632199,1739141170.634549,10.139990329742432,0.33567965602627253,1739141170.6345508,10.139990329742432,0.042200119500762745,1739141170.634552,10.139990329742432,2.1858808218933703,1739141170.6345544,10.139990329742432,0.0,1739141170.6345565,10.139990329742432,0.038193574028648314,1739141170.6345582,10.139990329742432,0.0032142760956759076,1739141170.6345594,10.139990329742432,2.147687247864722 +1739141170.653457,10.159990310668945,19.102234949637214,1739141170.6534605,10.159990310668945,-0.46687693723426715,1739141170.653464,10.159990310668945,18.47296847966738,1739141170.6534677,10.159990310668945,26.90967712534239,1739141170.653469,10.159990310668945,-0.10610018597282611,1739141170.6534712,10.159990310668945,0.04617649191632199,1739141170.6534731,10.159990310668945,0.33567965602627253,1739141170.6534746,10.159990310668945,0.042200119500762745,1739141170.653476,10.159990310668945,2.1858808218933703,1739141170.653478,10.159990310668945,0.0,1739141170.6534796,10.159990310668945,0.038193574028648314,1739141170.653481,10.159990310668945,0.0032142760956759076,1739141170.6534827,10.159990310668945,2.147687247864722 +1739141170.674304,10.179990291595459,19.102234949637214,1739141170.6743088,10.179990291595459,-0.46687693723426715,1739141170.6743138,10.179990291595459,18.47296847966738,1739141170.6743186,10.179990291595459,26.90967712534239,1739141170.6743207,10.179990291595459,-0.10610018597282611,1739141170.6743236,10.179990291595459,0.04617649191632199,1739141170.6743257,10.179990291595459,0.33567965602627253,1739141170.6743279,10.179990291595459,0.042200119500762745,1739141170.6743295,10.179990291595459,2.1858808218933703,1739141170.6743321,10.179990291595459,0.0,1739141170.6743348,10.179990291595459,0.038193574028648314,1739141170.6743367,10.179990291595459,0.0032142760956759076,1739141170.6743388,10.179990291595459,2.147687247864722 +1739141170.694698,10.199990272521973,19.338688146461575,1739141170.6947033,10.199990272521973,-0.46601634345588483,1739141170.69471,10.199990272521973,18.501344584473863,1739141170.6947172,10.199990272521973,26.950567710898586,1739141170.6947212,10.199990272521973,-0.1049677130235422,1739141170.6947265,10.199990272521973,0.04739673396048433,1739141170.6947315,10.199990272521973,0.3294592754436976,1739141170.6947362,10.199990272521973,0.043568501376055786,1739141170.6947405,10.199990272521973,2.1913263980433118,1739141170.6947458,10.199990272521973,0.0,1739141170.6947505,10.199990272521973,0.04061284025815785,1739141170.6947556,10.199990272521973,0.004149610733826137,1739141170.69476,10.199990272521973,2.151865589898506 +1739141170.7157753,10.219990253448486,19.338688146461575,1739141170.7157865,10.219990253448486,-0.46601634345588483,1739141170.7157974,10.219990253448486,18.501344584473863,1739141170.7158053,10.219990253448486,26.950567710898586,1739141170.7158093,10.219990253448486,-0.1049677130235422,1739141170.7158144,10.219990253448486,0.04739673396048433,1739141170.7158196,10.219990253448486,0.3294592754436976,1739141170.715824,10.219990253448486,0.043568501376055786,1739141170.7158284,10.219990253448486,2.1913263980433118,1739141170.7158344,10.219990253448486,0.0,1739141170.7158408,10.219990253448486,0.03946080814480579,1739141170.715845,10.219990253448486,0.004149610733826137,1739141170.7158506,10.219990253448486,2.151865589898506 +1739141170.7355058,10.239990234375,19.338688146461575,1739141170.7355113,10.239990234375,-0.46601634345588483,1739141170.7355192,10.239990234375,18.501344584473863,1739141170.7355263,10.239990234375,26.950567710898586,1739141170.7355292,10.239990234375,-0.1049677130235422,1739141170.735533,10.239990234375,0.04739673396048433,1739141170.7355359,10.239990234375,0.3294592754436976,1739141170.7355394,10.239990234375,0.043568501376055786,1739141170.735542,10.239990234375,2.1913263980433118,1739141170.7355459,10.239990234375,0.0,1739141170.7355485,10.239990234375,0.03946080814480579,1739141170.7355509,10.239990234375,0.004149610733826137,1739141170.735554,10.239990234375,2.151865589898506 +1739141170.7553654,10.259990215301514,19.338688146461575,1739141170.7553713,10.259990215301514,-0.46601634345588483,1739141170.7553768,10.259990215301514,18.501344584473863,1739141170.7553823,10.259990215301514,26.950567710898586,1739141170.7553854,10.259990215301514,-0.1049677130235422,1739141170.7553887,10.259990215301514,0.04739673396048433,1739141170.755392,10.259990215301514,0.3294592754436976,1739141170.7553954,10.259990215301514,0.043568501376055786,1739141170.7553988,10.259990215301514,2.1913263980433118,1739141170.7554023,10.259990215301514,0.0,1739141170.7554057,10.259990215301514,0.03946080814480579,1739141170.7554085,10.259990215301514,0.004149610733826137,1739141170.7554119,10.259990215301514,2.151865589898506 +1739141170.7758114,10.279990196228027,19.338688146461575,1739141170.7758174,10.279990196228027,-0.46601634345588483,1739141170.775823,10.279990196228027,18.501344584473863,1739141170.7758276,10.279990196228027,26.950567710898586,1739141170.7758305,10.279990196228027,-0.1049677130235422,1739141170.7758338,10.279990196228027,0.04739673396048433,1739141170.7758367,10.279990196228027,0.3294592754436976,1739141170.7758396,10.279990196228027,0.043568501376055786,1739141170.775842,10.279990196228027,2.1913263980433118,1739141170.775845,10.279990196228027,0.0,1739141170.775848,10.279990196228027,0.03946080814480579,1739141170.775851,10.279990196228027,0.004149610733826137,1739141170.775854,10.279990196228027,2.151865589898506 +1739141170.7939222,10.299990177154541,19.575607605812003,1739141170.793927,10.299990177154541,-0.4649324486652411,1739141170.7939324,10.299990177154541,19.375138837123544,1739141170.7939389,10.299990177154541,27.8372936542402,1739141170.7939425,10.299990177154541,-0.09613343651641952,1739141170.7939472,10.299990177154541,0.044610063097331794,1739141170.7939513,10.299990177154541,0.3267842030058499,1739141170.7939556,10.299990177154541,0.0366943063893654,1739141170.7939594,10.299990177154541,2.1936724357235087,1739141170.7939637,10.299990177154541,0.0,1739141170.793968,10.299990177154541,0.035678966703880564,1739141170.793972,10.299990177154541,0.005084945371976369,1739141170.7939768,10.299990177154541,2.15619259124338 +1739141170.8149993,10.319990158081055,19.575607605812003,1739141170.8150032,10.319990158081055,-0.4649324486652411,1739141170.815007,10.319990158081055,19.375138837123544,1739141170.81501,10.319990158081055,27.8372936542402,1739141170.8150125,10.319990158081055,-0.09613343651641952,1739141170.8150141,10.319990158081055,0.044610063097331794,1739141170.815016,10.319990158081055,0.3267842030058499,1739141170.8150175,10.319990158081055,0.0366943063893654,1739141170.815019,10.319990158081055,2.1936724357235087,1739141170.815021,10.319990158081055,0.0,1739141170.8150227,10.319990158081055,0.037479844480128754,1739141170.8150241,10.319990158081055,0.005084945371976369,1739141170.8150256,10.319990158081055,2.15619259124338 +1739141170.8344395,10.339990139007568,19.575607605812003,1739141170.8344443,10.339990139007568,-0.4649324486652411,1739141170.834449,10.339990139007568,19.375138837123544,1739141170.8344543,10.339990139007568,27.8372936542402,1739141170.8344572,10.339990139007568,-0.09613343651641952,1739141170.8344607,10.339990139007568,0.044610063097331794,1739141170.8344638,10.339990139007568,0.3267842030058499,1739141170.834467,10.339990139007568,0.0366943063893654,1739141170.834482,10.339990139007568,2.1936724357235087,1739141170.8344853,10.339990139007568,0.0,1739141170.8345046,10.339990139007568,0.037479844480128754,1739141170.8345072,10.339990139007568,0.005084945371976369,1739141170.8345098,10.339990139007568,2.15619259124338 +1739141170.853601,10.359990119934082,19.575607605812003,1739141170.8536036,10.359990119934082,-0.4649324486652411,1739141170.8536065,10.359990119934082,19.375138837123544,1739141170.8536096,10.359990119934082,27.8372936542402,1739141170.8536108,10.359990119934082,-0.09613343651641952,1739141170.8536127,10.359990119934082,0.044610063097331794,1739141170.853614,10.359990119934082,0.3267842030058499,1739141170.8536155,10.359990119934082,0.0366943063893654,1739141170.853617,10.359990119934082,2.1936724357235087,1739141170.8536184,10.359990119934082,0.0,1739141170.85362,10.359990119934082,0.037479844480128754,1739141170.8536217,10.359990119934082,0.005084945371976369,1739141170.8536232,10.359990119934082,2.15619259124338 +1739141170.8733914,10.379990100860596,19.575607605812003,1739141170.8733943,10.379990100860596,-0.4649324486652411,1739141170.8733976,10.379990100860596,19.375138837123544,1739141170.8734002,10.379990100860596,27.8372936542402,1739141170.8734024,10.379990100860596,-0.09613343651641952,1739141170.8734045,10.379990100860596,0.044610063097331794,1739141170.873406,10.379990100860596,0.3267842030058499,1739141170.8734076,10.379990100860596,0.0366943063893654,1739141170.8734267,10.379990100860596,2.1936724357235087,1739141170.873428,10.379990100860596,0.0,1739141170.8734298,10.379990100860596,0.037479844480128754,1739141170.873431,10.379990100860596,0.005084945371976369,1739141170.8734326,10.379990100860596,2.15619259124338 +1739141170.8944316,10.39999008178711,19.575607605812003,1739141170.8944373,10.39999008178711,-0.4649324486652411,1739141170.894443,10.39999008178711,19.375138837123544,1739141170.8944483,10.39999008178711,27.8372936542402,1739141170.8944507,10.39999008178711,-0.09613343651641952,1739141170.8944542,10.39999008178711,0.044610063097331794,1739141170.8944573,10.39999008178711,0.3267842030058499,1739141170.8944607,10.39999008178711,0.0366943063893654,1739141170.8944635,10.39999008178711,2.1936724357235087,1739141170.8944669,10.39999008178711,0.0,1739141170.8944845,10.39999008178711,0.037479844480128754,1739141170.8944874,10.39999008178711,0.005084945371976369,1739141170.89449,10.39999008178711,2.15619259124338 +1739141170.9132748,10.419990062713623,19.81298733456196,1739141170.9132776,10.419990062713623,-0.4636244152839266,1739141170.9132802,10.419990062713623,19.403387024844786,1739141170.9132829,10.419990062713623,27.87774029907414,1739141170.9132843,10.419990062713623,-0.09547576749472941,1739141170.913286,10.419990062713623,0.045617422846612396,1739141170.9132874,10.419990062713623,0.31959019848726544,1739141170.9132886,10.419990062713623,0.03765699539909614,1739141170.9132898,10.419990062713623,2.199994042661019,1739141170.9132912,10.419990062713623,0.0,1739141170.9132931,10.419990062713623,0.041782311893478793,1739141170.9132943,10.419990062713623,0.006020280010126602,1739141170.9132953,10.419990062713623,2.16026052579736 +1739141170.9331071,10.439990043640137,19.81298733456196,1739141170.9331098,10.439990043640137,-0.4636244152839266,1739141170.9331126,10.439990043640137,19.403387024844786,1739141170.9331152,10.439990043640137,27.87774029907414,1739141170.9331164,10.439990043640137,-0.09547576749472941,1739141170.933118,10.439990043640137,0.045617422846612396,1739141170.9331198,10.439990043640137,0.31959019848726544,1739141170.933121,10.439990043640137,0.03765699539909614,1739141170.9331224,10.439990043640137,2.199994042661019,1739141170.9331238,10.439990043640137,0.0,1739141170.9331253,10.439990043640137,0.039733516863659,1739141170.9331267,10.439990043640137,0.006020280010126602,1739141170.933128,10.439990043640137,2.16026052579736 +1739141170.9531784,10.45999002456665,19.81298733456196,1739141170.953181,10.45999002456665,-0.4636244152839266,1739141170.9531837,10.45999002456665,19.403387024844786,1739141170.9531865,10.45999002456665,27.87774029907414,1739141170.9531882,10.45999002456665,-0.09547576749472941,1739141170.9531896,10.45999002456665,0.045617422846612396,1739141170.9531908,10.45999002456665,0.31959019848726544,1739141170.9531922,10.45999002456665,0.03765699539909614,1739141170.9531934,10.45999002456665,2.199994042661019,1739141170.953195,10.45999002456665,0.0,1739141170.9531965,10.45999002456665,0.039733516863659,1739141170.9531975,10.45999002456665,0.006020280010126602,1739141170.953199,10.45999002456665,2.16026052579736 +1739141170.973277,10.479990005493164,19.81298733456196,1739141170.9732797,10.479990005493164,-0.4636244152839266,1739141170.9732828,10.479990005493164,19.403387024844786,1739141170.9732857,10.479990005493164,27.87774029907414,1739141170.973287,10.479990005493164,-0.09547576749472941,1739141170.973289,10.479990005493164,0.045617422846612396,1739141170.9732907,10.479990005493164,0.31959019848726544,1739141170.973292,10.479990005493164,0.03765699539909614,1739141170.9732935,10.479990005493164,2.199994042661019,1739141170.9732955,10.479990005493164,0.0,1739141170.9732969,10.479990005493164,0.039733516863659,1739141170.973298,10.479990005493164,0.006020280010126602,1739141170.9732997,10.479990005493164,2.16026052579736 +1739141170.9933896,10.499989986419678,19.81298733456196,1739141170.9933925,10.499989986419678,-0.4636244152839266,1739141170.993396,10.499989986419678,19.403387024844786,1739141170.9933987,10.499989986419678,27.87774029907414,1739141170.9934003,10.499989986419678,-0.09547576749472941,1739141170.9934018,10.499989986419678,0.045617422846612396,1739141170.9934034,10.499989986419678,0.31959019848726544,1739141170.9934049,10.499989986419678,0.03765699539909614,1739141170.9934063,10.499989986419678,2.199994042661019,1739141170.9934082,10.499989986419678,0.0,1739141170.9934096,10.499989986419678,0.039733516863659,1739141170.993411,10.499989986419678,0.006020280010126602,1739141170.9934123,10.499989986419678,2.16026052579736 +1739141171.0134609,10.519989967346191,20.050829816463132,1739141171.0134637,10.519989967346191,-0.46209135922034594,1739141171.013467,10.519989967346191,19.431690280191024,1739141171.0134706,10.519989967346191,27.919134103357504,1739141171.013472,10.519989967346191,-0.09490134875319103,1739141171.013474,10.519989967346191,0.046633148453304685,1739141171.0134757,10.519989967346191,0.3124526768174814,1739141171.0134768,10.519989967346191,0.03867357644198995,1739141171.0134785,10.519989967346191,2.2062840194187516,1739141171.0134802,10.519989967346191,0.0,1739141171.013482,10.519989967346191,0.043408590154455064,1739141171.0134835,10.519989967346191,0.006955614648276835,1739141171.0134847,10.519989967346191,2.164625465038895 +1739141171.0333712,10.539989948272705,20.050829816463132,1739141171.0333743,10.539989948272705,-0.46209135922034594,1739141171.033377,10.539989948272705,19.431690280191024,1739141171.03338,10.539989948272705,27.919134103357504,1739141171.0333817,10.539989948272705,-0.09490134875319103,1739141171.0333834,10.539989948272705,0.046633148453304685,1739141171.033385,10.539989948272705,0.3124526768174814,1739141171.0333865,10.539989948272705,0.03867357644198995,1739141171.0333877,10.539989948272705,2.2062840194187516,1739141171.0333893,10.539989948272705,0.0,1739141171.033391,10.539989948272705,0.04165855437985666,1739141171.0333924,10.539989948272705,0.006955614648276835,1739141171.0333939,10.539989948272705,2.164625465038895 +1739141171.0533981,10.559989929199219,20.050829816463132,1739141171.0534012,10.559989929199219,-0.46209135922034594,1739141171.0534046,10.559989929199219,19.431690280191024,1739141171.0534077,10.559989929199219,27.919134103357504,1739141171.0534093,10.559989929199219,-0.09490134875319103,1739141171.0534112,10.559989929199219,0.046633148453304685,1739141171.0534127,10.559989929199219,0.3124526768174814,1739141171.053414,10.559989929199219,0.03867357644198995,1739141171.0534155,10.559989929199219,2.2062840194187516,1739141171.0534172,10.559989929199219,0.0,1739141171.0534186,10.559989929199219,0.04165855437985666,1739141171.0534203,10.559989929199219,0.006955614648276835,1739141171.0534217,10.559989929199219,2.164625465038895 +1739141171.0733547,10.579989910125732,20.050829816463132,1739141171.073358,10.579989910125732,-0.46209135922034594,1739141171.0733612,10.579989910125732,19.431690280191024,1739141171.0733643,10.579989910125732,27.919134103357504,1739141171.0733657,10.579989910125732,-0.09490134875319103,1739141171.0733676,10.579989910125732,0.046633148453304685,1739141171.073369,10.579989910125732,0.3124526768174814,1739141171.0733705,10.579989910125732,0.03867357644198995,1739141171.073372,10.579989910125732,2.2062840194187516,1739141171.0733738,10.579989910125732,0.0,1739141171.0733752,10.579989910125732,0.04165855437985666,1739141171.0733764,10.579989910125732,0.006955614648276835,1739141171.073378,10.579989910125732,2.164625465038895 +1739141171.093419,10.599989891052246,20.050829816463132,1739141171.0934222,10.599989891052246,-0.46209135922034594,1739141171.093425,10.599989891052246,19.431690280191024,1739141171.093428,10.599989891052246,27.919134103357504,1739141171.0934296,10.599989891052246,-0.09490134875319103,1739141171.0934315,10.599989891052246,0.046633148453304685,1739141171.093433,10.599989891052246,0.3124526768174814,1739141171.0934343,10.599989891052246,0.03867357644198995,1739141171.0934362,10.599989891052246,2.2062840194187516,1739141171.093438,10.599989891052246,0.0,1739141171.0934393,10.599989891052246,0.04165855437985666,1739141171.0934408,10.599989891052246,0.006955614648276835,1739141171.0934422,10.599989891052246,2.164625465038895 +1739141171.1133702,10.61998987197876,20.050829816463132,1739141171.1133733,10.61998987197876,-0.46209135922034594,1739141171.1133761,10.61998987197876,19.431690280191024,1739141171.1133792,10.61998987197876,27.919134103357504,1739141171.113381,10.61998987197876,-0.09490134875319103,1739141171.1133826,10.61998987197876,0.046633148453304685,1739141171.1133842,10.61998987197876,0.3124526768174814,1739141171.1133854,10.61998987197876,0.03867357644198995,1739141171.113387,10.61998987197876,2.2062840194187516,1739141171.1133888,10.61998987197876,0.0,1739141171.1133904,10.61998987197876,0.04165855437985666,1739141171.1133916,10.61998987197876,0.006955614648276835,1739141171.113393,10.61998987197876,2.164625465038895 +1739141171.1334498,10.639989852905273,20.28916391056593,1739141171.1334531,10.639989852905273,-0.46033219991037555,1739141171.1334562,10.639989852905273,19.460052037389257,1739141171.133459,10.639989852905273,27.961281898479918,1739141171.1334608,10.639989852905273,-0.09455868375219581,1739141171.1334627,10.639989852905273,0.047639617007465794,1739141171.1334646,10.639989852905273,0.3052224627065809,1739141171.133466,10.639989852905273,0.03973157254190611,1739141171.1334677,10.639989852905273,2.212674017515663,1739141171.133469,10.639989852905273,0.0,1739141171.1334708,10.639989852905273,0.045083823580550235,1739141171.1334727,10.639989852905273,0.007890949286427067,1739141171.133474,10.639989852905273,2.169221275321668 +1739141171.1535218,10.659989833831787,20.28916391056593,1739141171.1535249,10.659989833831787,-0.46033219991037555,1739141171.1535282,10.659989833831787,19.460052037389257,1739141171.1535316,10.659989833831787,27.961281898479918,1739141171.1535332,10.659989833831787,-0.09455868375219581,1739141171.1535351,10.659989833831787,0.047639617007465794,1739141171.1535368,10.659989833831787,0.3052224627065809,1739141171.1535382,10.659989833831787,0.03973157254190611,1739141171.1535397,10.659989833831787,2.212674017515663,1739141171.1535413,10.659989833831787,0.0,1739141171.153543,10.659989833831787,0.043452742193994975,1739141171.1535444,10.659989833831787,0.007890949286427067,1739141171.1535456,10.659989833831787,2.169221275321668 +1739141171.1734095,10.6799898147583,20.28916391056593,1739141171.1734123,10.6799898147583,-0.46033219991037555,1739141171.1734154,10.6799898147583,19.460052037389257,1739141171.1734188,10.6799898147583,27.961281898479918,1739141171.173421,10.6799898147583,-0.09455868375219581,1739141171.1734226,10.6799898147583,0.047639617007465794,1739141171.1734242,10.6799898147583,0.3052224627065809,1739141171.1734254,10.6799898147583,0.03973157254190611,1739141171.1734269,10.6799898147583,2.212674017515663,1739141171.1734285,10.6799898147583,0.0,1739141171.17343,10.6799898147583,0.043452742193994975,1739141171.1734316,10.6799898147583,0.007890949286427067,1739141171.173433,10.6799898147583,2.169221275321668 +1739141171.1934092,10.699989795684814,20.28916391056593,1739141171.1934123,10.699989795684814,-0.46033219991037555,1739141171.1934159,10.699989795684814,19.460052037389257,1739141171.1934187,10.699989795684814,27.961281898479918,1739141171.1934202,10.699989795684814,-0.09455868375219581,1739141171.1934223,10.699989795684814,0.047639617007465794,1739141171.193424,10.699989795684814,0.3052224627065809,1739141171.1934254,10.699989795684814,0.03973157254190611,1739141171.1934266,10.699989795684814,2.212674017515663,1739141171.1934288,10.699989795684814,0.0,1739141171.1934304,10.699989795684814,0.043452742193994975,1739141171.193432,10.699989795684814,0.007890949286427067,1739141171.1934333,10.699989795684814,2.169221275321668 +1739141171.2133815,10.719989776611328,20.28916391056593,1739141171.213386,10.719989776611328,-0.46033219991037555,1739141171.213391,10.719989776611328,19.460052037389257,1739141171.213395,10.719989776611328,27.961281898479918,1739141171.213398,10.719989776611328,-0.09455868375219581,1739141171.2134006,10.719989776611328,0.047639617007465794,1739141171.213403,10.719989776611328,0.3052224627065809,1739141171.2134056,10.719989776611328,0.03973157254190611,1739141171.2134078,10.719989776611328,2.212674017515663,1739141171.2134101,10.719989776611328,0.0,1739141171.213412,10.719989776611328,0.043452742193994975,1739141171.2134228,10.719989776611328,0.007890949286427067,1739141171.2134247,10.719989776611328,2.169221275321668 +1739141171.2334745,10.739989757537842,20.528008853587618,1739141171.2334774,10.739989757537842,-0.45834585468701583,1739141171.2334805,10.739989757537842,20.013568989699113,1739141171.2334836,10.739989757537842,28.529071052287737,1739141171.233485,10.739989757537842,-0.08892625160741677,1739141171.233487,10.739989757537842,0.04613855269880768,1739141171.2334883,10.739989757537842,0.29878648392177376,1739141171.23349,10.739989757537842,0.03576691291102907,1739141171.2334912,10.739989757537842,2.218377645264809,1739141171.233493,10.739989757537842,0.0,1739141171.2334948,10.739989757537842,0.045239175027454566,1739141171.2334964,10.739989757537842,0.00882628392457729,1739141171.2334976,10.739989757537842,2.173989152963955 +1739141171.2549434,10.759989738464355,20.528008853587618,1739141171.2549474,10.759989738464355,-0.45834585468701583,1739141171.254952,10.759989738464355,20.013568989699113,1739141171.2549558,10.759989738464355,28.529071052287737,1739141171.2549582,10.759989738464355,-0.08892625160741677,1739141171.2549603,10.759989738464355,0.04613855269880768,1739141171.2549627,10.759989738464355,0.29878648392177376,1739141171.254965,10.759989738464355,0.03576691291102907,1739141171.2549667,10.759989738464355,2.218377645264809,1739141171.2549696,10.759989738464355,0.0,1739141171.254972,10.759989738464355,0.044388492300853954,1739141171.2549736,10.759989738464355,0.00882628392457729,1739141171.2549758,10.759989738464355,2.173989152963955 +1739141171.2757416,10.77998971939087,20.528008853587618,1739141171.2757466,10.77998971939087,-0.45834585468701583,1739141171.2757525,10.77998971939087,20.013568989699113,1739141171.275758,10.77998971939087,28.529071052287737,1739141171.275761,10.77998971939087,-0.08892625160741677,1739141171.2757642,10.77998971939087,0.04613855269880768,1739141171.275767,10.77998971939087,0.29878648392177376,1739141171.2757697,10.77998971939087,0.03576691291102907,1739141171.275772,10.77998971939087,2.218377645264809,1739141171.2757754,10.77998971939087,0.0,1739141171.2757785,10.77998971939087,0.044388492300853954,1739141171.2757812,10.77998971939087,0.00882628392457729,1739141171.2757838,10.77998971939087,2.173989152963955 +1739141171.2961586,10.799989700317383,20.528008853587618,1739141171.2961633,10.799989700317383,-0.45834585468701583,1739141171.2961698,10.799989700317383,20.013568989699113,1739141171.2961752,10.799989700317383,28.529071052287737,1739141171.2961779,10.799989700317383,-0.08892625160741677,1739141171.2961814,10.799989700317383,0.04613855269880768,1739141171.2961843,10.799989700317383,0.29878648392177376,1739141171.296187,10.799989700317383,0.03576691291102907,1739141171.2961898,10.799989700317383,2.218377645264809,1739141171.296193,10.799989700317383,0.0,1739141171.2961957,10.799989700317383,0.044388492300853954,1739141171.2961986,10.799989700317383,0.00882628392457729,1739141171.2962012,10.799989700317383,2.173989152963955 +1739141171.3150961,10.819989681243896,20.528008853587618,1739141171.3151014,10.819989681243896,-0.45834585468701583,1739141171.3151073,10.819989681243896,20.013568989699113,1739141171.3151133,10.819989681243896,28.529071052287737,1739141171.3151157,10.819989681243896,-0.08892625160741677,1739141171.3151193,10.819989681243896,0.04613855269880768,1739141171.3151221,10.819989681243896,0.29878648392177376,1739141171.3151248,10.819989681243896,0.03576691291102907,1739141171.3151274,10.819989681243896,2.218377645264809,1739141171.3151307,10.819989681243896,0.0,1739141171.3151333,10.819989681243896,0.044388492300853954,1739141171.315136,10.819989681243896,0.00882628392457729,1739141171.3151388,10.819989681243896,2.173989152963955 +1739141171.3352747,10.83998966217041,20.528008853587618,1739141171.335279,10.83998966217041,-0.45834585468701583,1739141171.3352838,10.83998966217041,20.013568989699113,1739141171.3352883,10.83998966217041,28.529071052287737,1739141171.3352904,10.83998966217041,-0.08892625160741677,1739141171.3352935,10.83998966217041,0.04613855269880768,1739141171.3352954,10.83998966217041,0.29878648392177376,1739141171.3352978,10.83998966217041,0.03576691291102907,1739141171.3352997,10.83998966217041,2.218377645264809,1739141171.3353026,10.83998966217041,0.0,1739141171.3353052,10.83998966217041,0.044388492300853954,1739141171.3353074,10.83998966217041,0.00882628392457729,1739141171.3353093,10.83998966217041,2.173989152963955 +1739141171.3549826,10.859989643096924,20.767383148459054,1739141171.3549855,10.859989643096924,-0.45613119399564095,1739141171.354989,10.859989643096924,20.04205453078881,1739141171.3549922,10.859989643096924,28.572210993046138,1739141171.3549936,10.859989643096924,-0.0885755203817387,1739141171.3549955,10.859989643096924,0.047058605519955006,1739141171.354997,10.859989643096924,0.2913516193163832,1739141171.3549986,10.859989643096924,0.03664951979552797,1739141171.355,10.859989643096924,2.2249848000298305,1739141171.3550022,10.859989643096924,0.0,1739141171.3550036,10.859989643096924,0.047675718556648636,1739141171.3550053,10.859989643096924,0.009761618562727514,1739141171.3550067,10.859989643096924,2.1788744280912336 +1739141171.3735383,10.879989624023438,20.767383148459054,1739141171.373541,10.879989624023438,-0.45613119399564095,1739141171.3735445,10.879989624023438,20.04205453078881,1739141171.3735478,10.879989624023438,28.572210993046138,1739141171.3735495,10.879989624023438,-0.0885755203817387,1739141171.3735516,10.879989624023438,0.047058605519955006,1739141171.373553,10.879989624023438,0.2913516193163832,1739141171.373555,10.879989624023438,0.03664951979552797,1739141171.3735564,10.879989624023438,2.2249848000298305,1739141171.3735583,10.879989624023438,0.0,1739141171.37356,10.879989624023438,0.046110371938596906,1739141171.3735616,10.879989624023438,0.009761618562727514,1739141171.373563,10.879989624023438,2.1788744280912336 +1739141171.393459,10.899989604949951,20.767383148459054,1739141171.3934622,10.899989604949951,-0.45613119399564095,1739141171.393466,10.899989604949951,20.04205453078881,1739141171.3934693,10.899989604949951,28.572210993046138,1739141171.3934712,10.899989604949951,-0.0885755203817387,1739141171.3934734,10.899989604949951,0.047058605519955006,1739141171.393475,10.899989604949951,0.2913516193163832,1739141171.3934767,10.899989604949951,0.03664951979552797,1739141171.3934782,10.899989604949951,2.2249848000298305,1739141171.3934798,10.899989604949951,0.0,1739141171.3934817,10.899989604949951,0.046110371938596906,1739141171.3934836,10.899989604949951,0.009761618562727514,1739141171.393485,10.899989604949951,2.1788744280912336 +1739141171.413481,10.919989585876465,20.767383148459054,1739141171.4134839,10.919989585876465,-0.45613119399564095,1739141171.4134874,10.919989585876465,20.04205453078881,1739141171.4134908,10.919989585876465,28.572210993046138,1739141171.4134922,10.919989585876465,-0.0885755203817387,1739141171.4134943,10.919989585876465,0.047058605519955006,1739141171.413496,10.919989585876465,0.2913516193163832,1739141171.4134977,10.919989585876465,0.03664951979552797,1739141171.413499,10.919989585876465,2.2249848000298305,1739141171.4135013,10.919989585876465,0.0,1739141171.4135027,10.919989585876465,0.046110371938596906,1739141171.4135046,10.919989585876465,0.009761618562727514,1739141171.413506,10.919989585876465,2.1788744280912336 +1739141171.433884,10.939989566802979,20.767383148459054,1739141171.4338872,10.939989566802979,-0.45613119399564095,1739141171.4338908,10.939989566802979,20.04205453078881,1739141171.4338942,10.939989566802979,28.572210993046138,1739141171.4338958,10.939989566802979,-0.0885755203817387,1739141171.433898,10.939989566802979,0.047058605519955006,1739141171.4339,10.939989566802979,0.2913516193163832,1739141171.4339015,10.939989566802979,0.03664951979552797,1739141171.4339032,10.939989566802979,2.2249848000298305,1739141171.433905,10.939989566802979,0.0,1739141171.4339068,10.939989566802979,0.046110371938596906,1739141171.4339082,10.939989566802979,0.009761618562727514,1739141171.4339097,10.939989566802979,2.1788744280912336 +1739141171.4537575,10.959989547729492,21.00730025609969,1739141171.4537609,10.959989547729492,-0.45368708576295713,1739141171.453765,10.959989547729492,20.202194308862907,1739141171.4537683,10.959989547729492,28.747515796687544,1739141171.45377,10.959989547729492,-0.08686702455739703,1739141171.4537718,10.959989547729492,0.04735602115256649,1739141171.453774,10.959989547729492,0.28400393033662996,1739141171.4537756,10.959989547729492,0.03632318548440877,1739141171.453777,10.959989547729492,2.2315338178628905,1739141171.453779,10.959989547729492,0.0,1739141171.4537807,10.959989547729492,0.0489569740117143,1739141171.4537823,10.959989547729492,0.010696953200877737,1739141171.4537838,10.959989547729492,2.183932369325043 +1739141171.4735882,10.979989528656006,21.00730025609969,1739141171.4735913,10.979989528656006,-0.45368708576295713,1739141171.473595,10.979989528656006,20.202194308862907,1739141171.4735982,10.979989528656006,28.747515796687544,1739141171.4736,10.979989528656006,-0.08686702455739703,1739141171.473602,10.979989528656006,0.04735602115256649,1739141171.4736037,10.979989528656006,0.28400393033662996,1739141171.4736056,10.979989528656006,0.03632318548440877,1739141171.473607,10.979989528656006,2.2315338178628905,1739141171.4736092,10.979989528656006,0.0,1739141171.4736106,10.979989528656006,0.047601448537847535,1739141171.4736125,10.979989528656006,0.010696953200877737,1739141171.473614,10.979989528656006,2.183932369325043 +1739141171.4935427,10.99998950958252,21.00730025609969,1739141171.4935455,10.99998950958252,-0.45368708576295713,1739141171.493549,10.99998950958252,20.202194308862907,1739141171.4935524,10.99998950958252,28.747515796687544,1739141171.4935539,10.99998950958252,-0.08686702455739703,1739141171.493556,10.99998950958252,0.04735602115256649,1739141171.4935577,10.99998950958252,0.28400393033662996,1739141171.4935594,10.99998950958252,0.03632318548440877,1739141171.4935608,10.99998950958252,2.2315338178628905,1739141171.4935627,10.99998950958252,0.0,1739141171.4935644,10.99998950958252,0.047601448537847535,1739141171.4935665,10.99998950958252,0.010696953200877737,1739141171.493568,10.99998950958252,2.183932369325043 +1739141171.514425,11.019989490509033,21.00730025609969,1739141171.5144284,11.019989490509033,-0.45368708576295713,1739141171.514432,11.019989490509033,20.202194308862907,1739141171.5144353,11.019989490509033,28.747515796687544,1739141171.514437,11.019989490509033,-0.08686702455739703,1739141171.5144389,11.019989490509033,0.04735602115256649,1739141171.5144408,11.019989490509033,0.28400393033662996,1739141171.5144422,11.019989490509033,0.03632318548440877,1739141171.5144439,11.019989490509033,2.2315338178628905,1739141171.5144458,11.019989490509033,0.0,1739141171.514448,11.019989490509033,0.047601448537847535,1739141171.5144494,11.019989490509033,0.010696953200877737,1739141171.5144515,11.019989490509033,2.183932369325043 +1739141171.5336788,11.039989471435547,21.00730025609969,1739141171.5336823,11.039989471435547,-0.45368708576295713,1739141171.5336862,11.039989471435547,20.202194308862907,1739141171.5336902,11.039989471435547,28.747515796687544,1739141171.5336916,11.039989471435547,-0.08686702455739703,1739141171.5336938,11.039989471435547,0.04735602115256649,1739141171.5336957,11.039989471435547,0.28400393033662996,1739141171.5336974,11.039989471435547,0.03632318548440877,1739141171.5336988,11.039989471435547,2.2315338178628905,1739141171.5337007,11.039989471435547,0.0,1739141171.5337024,11.039989471435547,0.047601448537847535,1739141171.533704,11.039989471435547,0.010696953200877737,1739141171.5337055,11.039989471435547,2.183932369325043 +1739141171.553587,11.05998945236206,21.00730025609969,1739141171.5535903,11.05998945236206,-0.45368708576295713,1739141171.5535934,11.05998945236206,20.202194308862907,1739141171.5535972,11.05998945236206,28.747515796687544,1739141171.5535986,11.05998945236206,-0.08686702455739703,1739141171.5536008,11.05998945236206,0.04735602115256649,1739141171.5536025,11.05998945236206,0.28400393033662996,1739141171.5536044,11.05998945236206,0.03632318548440877,1739141171.5536058,11.05998945236206,2.2315338178628905,1739141171.5536077,11.05998945236206,0.0,1739141171.5536094,11.05998945236206,0.047601448537847535,1739141171.5536115,11.05998945236206,0.010696953200877737,1739141171.5536127,11.05998945236206,2.183932369325043 +1739141171.5741446,11.079989433288574,21.24778157146911,1739141171.5741484,11.079989433288574,-0.45101227245899267,1739141171.5741525,11.079989433288574,20.52293919542804,1739141171.5741558,11.079989433288574,29.08395803781018,1739141171.5741572,11.079989433288574,-0.08386104104221556,1739141171.5741594,11.079989433288574,0.04681912472098629,1739141171.574161,11.079989433288574,0.2759757874766389,1739141171.5741627,11.079989433288574,0.034439145978761826,1739141171.5741642,11.079989433288574,2.2387113650844603,1739141171.574166,11.079989433288574,0.0,1739141171.5741677,11.079989433288574,0.051303145972478065,1739141171.5741694,11.079989433288574,0.01163228783902796,1739141171.5741708,11.079989433288574,2.1891709330566447 +1739141171.5937319,11.099989414215088,21.24778157146911,1739141171.5937352,11.099989414215088,-0.45101227245899267,1739141171.5937388,11.099989414215088,20.52293919542804,1739141171.5937421,11.099989414215088,29.08395803781018,1739141171.5937436,11.099989414215088,-0.08386104104221556,1739141171.593746,11.099989414215088,0.04681912472098629,1739141171.5937483,11.099989414215088,0.2759757874766389,1739141171.59375,11.099989414215088,0.034439145978761826,1739141171.5937517,11.099989414215088,2.2387113650844603,1739141171.5937536,11.099989414215088,0.0,1739141171.5937555,11.099989414215088,0.04954043202781566,1739141171.5937572,11.099989414215088,0.01163228783902796,1739141171.5937588,11.099989414215088,2.1891709330566447 +1739141171.613787,11.119989395141602,21.24778157146911,1739141171.6137905,11.119989395141602,-0.45101227245899267,1739141171.613794,11.119989395141602,20.52293919542804,1739141171.6137972,11.119989395141602,29.08395803781018,1739141171.6137986,11.119989395141602,-0.08386104104221556,1739141171.613801,11.119989395141602,0.04681912472098629,1739141171.6138024,11.119989395141602,0.2759757874766389,1739141171.613804,11.119989395141602,0.034439145978761826,1739141171.6138058,11.119989395141602,2.2387113650844603,1739141171.6138077,11.119989395141602,0.0,1739141171.6138093,11.119989395141602,0.04954043202781566,1739141171.613811,11.119989395141602,0.01163228783902796,1739141171.613813,11.119989395141602,2.1891709330566447 +1739141171.6335955,11.139989376068115,21.24778157146911,1739141171.6335988,11.139989376068115,-0.45101227245899267,1739141171.6336021,11.139989376068115,20.52293919542804,1739141171.6336055,11.139989376068115,29.08395803781018,1739141171.633607,11.139989376068115,-0.08386104104221556,1739141171.633609,11.139989376068115,0.04681912472098629,1739141171.6336107,11.139989376068115,0.2759757874766389,1739141171.6336126,11.139989376068115,0.034439145978761826,1739141171.633614,11.139989376068115,2.2387113650844603,1739141171.6336162,11.139989376068115,0.0,1739141171.6336179,11.139989376068115,0.04954043202781566,1739141171.6336195,11.139989376068115,0.01163228783902796,1739141171.633621,11.139989376068115,2.1891709330566447 +1739141171.653599,11.159989356994629,21.24778157146911,1739141171.6536021,11.159989356994629,-0.45101227245899267,1739141171.6536055,11.159989356994629,20.52293919542804,1739141171.6536088,11.159989356994629,29.08395803781018,1739141171.6536102,11.159989356994629,-0.08386104104221556,1739141171.6536124,11.159989356994629,0.04681912472098629,1739141171.6536143,11.159989356994629,0.2759757874766389,1739141171.653616,11.159989356994629,0.034439145978761826,1739141171.6536171,11.159989356994629,2.2387113650844603,1739141171.653619,11.159989356994629,0.0,1739141171.6536207,11.159989356994629,0.04954043202781566,1739141171.6536226,11.159989356994629,0.01163228783902796,1739141171.6536243,11.159989356994629,2.1891709330566447 +1739141171.6736782,11.179989337921143,21.488845113930182,1739141171.6736813,11.179989337921143,-0.4481054760519907,1739141171.6736846,11.179989337921143,20.6584186656373,1739141171.6736877,11.179989337921143,29.235740064523238,1739141171.6736894,11.179989337921143,-0.08307865946122042,1739141171.6736915,11.179989337921143,0.047084287669258706,1739141171.673693,11.179989337921143,0.2676405016600772,1739141171.6736944,11.179989337921143,0.03417242359314961,1739141171.673696,11.179989337921143,2.2461879416745285,1739141171.673698,11.179989337921143,0.0,1739141171.6736999,11.179989337921143,0.05343826087311629,1739141171.6737015,11.179989337921143,0.012567622477178183,1739141171.6737032,11.179989337921143,2.194605790702573 +1739141171.693826,11.199989318847656,21.488845113930182,1739141171.693831,11.199989318847656,-0.4481054760519907,1739141171.6938362,11.199989318847656,20.6584186656373,1739141171.6938426,11.199989318847656,29.235740064523238,1739141171.6938462,11.199989318847656,-0.08307865946122042,1739141171.693851,11.199989318847656,0.047084287669258706,1739141171.693855,11.199989318847656,0.2676405016600772,1739141171.693859,11.199989318847656,0.03417242359314961,1739141171.6938632,11.199989318847656,2.2461879416745285,1739141171.6938672,11.199989318847656,0.0,1739141171.6938715,11.199989318847656,0.05158215097195562,1739141171.6938756,11.199989318847656,0.012567622477178183,1739141171.6938796,11.199989318847656,2.194605790702573 +1739141171.71369,11.21998929977417,21.488845113930182,1739141171.7136936,11.21998929977417,-0.4481054760519907,1739141171.7136984,11.21998929977417,20.6584186656373,1739141171.7137017,11.21998929977417,29.235740064523238,1739141171.7137034,11.21998929977417,-0.08307865946122042,1739141171.7137058,11.21998929977417,0.047084287669258706,1739141171.7137074,11.21998929977417,0.2676405016600772,1739141171.713709,11.21998929977417,0.03417242359314961,1739141171.7137105,11.21998929977417,2.2461879416745285,1739141171.7137127,11.21998929977417,0.0,1739141171.7137144,11.21998929977417,0.05158215097195562,1739141171.7137163,11.21998929977417,0.012567622477178183,1739141171.7137177,11.21998929977417,2.194605790702573 +1739141171.7341883,11.239989280700684,21.488845113930182,1739141171.7341921,11.239989280700684,-0.4481054760519907,1739141171.734196,11.239989280700684,20.6584186656373,1739141171.7341998,11.239989280700684,29.235740064523238,1739141171.7342017,11.239989280700684,-0.08307865946122042,1739141171.7342036,11.239989280700684,0.047084287669258706,1739141171.7342055,11.239989280700684,0.2676405016600772,1739141171.7342072,11.239989280700684,0.03417242359314961,1739141171.7342088,11.239989280700684,2.2461879416745285,1739141171.7342107,11.239989280700684,0.0,1739141171.7342126,11.239989280700684,0.05158215097195562,1739141171.7342143,11.239989280700684,0.012567622477178183,1739141171.734216,11.239989280700684,2.194605790702573 +1739141171.754928,11.259989261627197,21.488845113930182,1739141171.7549329,11.259989261627197,-0.4481054760519907,1739141171.7549384,11.259989261627197,20.6584186656373,1739141171.7549434,11.259989261627197,29.235740064523238,1739141171.7549455,11.259989261627197,-0.08307865946122042,1739141171.7549486,11.259989261627197,0.047084287669258706,1739141171.754951,11.259989261627197,0.2676405016600772,1739141171.7549531,11.259989261627197,0.03417242359314961,1739141171.7549555,11.259989261627197,2.2461879416745285,1739141171.7549584,11.259989261627197,0.0,1739141171.7549605,11.259989261627197,0.05158215097195562,1739141171.754963,11.259989261627197,0.012567622477178183,1739141171.754965,11.259989261627197,2.194605790702573 +1739141171.7748742,11.279989242553711,21.488845113930182,1739141171.7748785,11.279989242553711,-0.4481054760519907,1739141171.7748828,11.279989242553711,20.6584186656373,1739141171.7748876,11.279989242553711,29.235740064523238,1739141171.77489,11.279989242553711,-0.08307865946122042,1739141171.7748928,11.279989242553711,0.047084287669258706,1739141171.7748952,11.279989242553711,0.2676405016600772,1739141171.774897,11.279989242553711,0.03417242359314961,1739141171.7748995,11.279989242553711,2.2461879416745285,1739141171.774902,11.279989242553711,0.0,1739141171.7749045,11.279989242553711,0.05158215097195562,1739141171.7749066,11.279989242553711,0.012567622477178183,1739141171.774909,11.279989242553711,2.194605790702573 +1739141171.7959228,11.299989223480225,21.730517757973427,1739141171.7959273,11.299989223480225,-0.4449652528973722,1739141171.7959325,11.299989223480225,20.901262153858347,1739141171.7959373,11.299989223480225,29.495627693799975,1739141171.7959397,11.299989223480225,-0.08096976921833356,1739141171.7959425,11.299989223480225,0.04684147818265841,1739141171.7959452,11.299989223480225,0.25911354034707595,1739141171.7959473,11.299989223480225,0.03292952179793111,1739141171.7959495,11.299989223480225,2.253862285072612,1739141171.795952,11.299989223480225,0.0,1739141171.7959547,11.299989223480225,0.055381410139438765,1739141171.795957,11.299989223480225,0.013502957115328406,1739141171.7959592,11.299989223480225,2.2002900468690685 +1739141171.8152423,11.319989204406738,21.730517757973427,1739141171.8152468,11.319989204406738,-0.4449652528973722,1739141171.8152523,11.319989204406738,20.901262153858347,1739141171.815257,11.319989204406738,29.495627693799975,1739141171.8152592,11.319989204406738,-0.08096976921833356,1739141171.8152623,11.319989204406738,0.04684147818265841,1739141171.8152645,11.319989204406738,0.25911354034707595,1739141171.8152666,11.319989204406738,0.03292952179793111,1739141171.8152688,11.319989204406738,2.253862285072612,1739141171.8152716,11.319989204406738,0.0,1739141171.815274,11.319989204406738,0.05357223820354351,1739141171.8152764,11.319989204406738,0.013502957115328406,1739141171.8152785,11.319989204406738,2.2002900468690685 +1739141171.8345246,11.339989185333252,21.730517757973427,1739141171.8345292,11.339989185333252,-0.4449652528973722,1739141171.8345344,11.339989185333252,20.901262153858347,1739141171.8345392,11.339989185333252,29.495627693799975,1739141171.8345416,11.339989185333252,-0.08096976921833356,1739141171.8345447,11.339989185333252,0.04684147818265841,1739141171.8345473,11.339989185333252,0.25911354034707595,1739141171.8345497,11.339989185333252,0.03292952179793111,1739141171.834552,11.339989185333252,2.253862285072612,1739141171.8345547,11.339989185333252,0.0,1739141171.8345573,11.339989185333252,0.05357223820354351,1739141171.8345597,11.339989185333252,0.013502957115328406,1739141171.8345618,11.339989185333252,2.2002900468690685 +1739141171.8551126,11.359989166259766,21.730517757973427,1739141171.8551168,11.359989166259766,-0.4449652528973722,1739141171.8551223,11.359989166259766,20.901262153858347,1739141171.8551273,11.359989166259766,29.495627693799975,1739141171.8551297,11.359989166259766,-0.08096976921833356,1739141171.8551323,11.359989166259766,0.04684147818265841,1739141171.855135,11.359989166259766,0.25911354034707595,1739141171.855137,11.359989166259766,0.03292952179793111,1739141171.8551393,11.359989166259766,2.253862285072612,1739141171.855142,11.359989166259766,0.0,1739141171.8551447,11.359989166259766,0.05357223820354351,1739141171.8551471,11.359989166259766,0.013502957115328406,1739141171.8551493,11.359989166259766,2.2002900468690685 +1739141171.8745928,11.37998914718628,21.730517757973427,1739141171.8745968,11.37998914718628,-0.4449652528973722,1739141171.874602,11.37998914718628,20.901262153858347,1739141171.8746068,11.37998914718628,29.495627693799975,1739141171.8746092,11.37998914718628,-0.08096976921833356,1739141171.8746119,11.37998914718628,0.04684147818265841,1739141171.8746142,11.37998914718628,0.25911354034707595,1739141171.8746164,11.37998914718628,0.03292952179793111,1739141171.8746188,11.37998914718628,2.253862285072612,1739141171.8746216,11.37998914718628,0.0,1739141171.874624,11.37998914718628,0.05357223820354351,1739141171.8746264,11.37998914718628,0.013502957115328406,1739141171.8746283,11.37998914718628,2.2002900468690685 +1739141171.8960102,11.399989128112793,21.972817896073458,1739141171.896015,11.399989128112793,-0.44159020186231146,1739141171.89602,11.399989128112793,21.144181568860272,1739141171.896025,11.399989128112793,29.756091627005524,1739141171.8960273,11.399989128112793,-0.07879090310828729,1739141171.8960302,11.399989128112793,0.0465789713694627,1739141171.8960326,11.399989128112793,0.2503882115382772,1739141171.8960347,11.399989128112793,0.03167318708162176,1739141171.896037,11.399989128112793,2.261742304035824,1739141171.89604,11.399989128112793,0.0,1739141171.8960426,11.399989128112793,0.05744541964962396,1739141171.8960445,11.399989128112793,0.014438291753478629,1739141171.8960469,11.399989128112793,2.206141257424726 +1739141171.914534,11.419989109039307,21.972817896073458,1739141171.9145384,11.419989109039307,-0.44159020186231146,1739141171.9145434,11.419989109039307,21.144181568860272,1739141171.9145482,11.419989109039307,29.756091627005524,1739141171.9145505,11.419989109039307,-0.07879090310828729,1739141171.9145534,11.419989109039307,0.0465789713694627,1739141171.9145558,11.419989109039307,0.2503882115382772,1739141171.914558,11.419989109039307,0.03167318708162176,1739141171.91456,11.419989109039307,2.261742304035824,1739141171.9145627,11.419989109039307,0.0,1739141171.9145653,11.419989109039307,0.05560104661109788,1739141171.9145677,11.419989109039307,0.014438291753478629,1739141171.9145696,11.419989109039307,2.206141257424726 +1739141171.9334471,11.43998908996582,21.972817896073458,1739141171.9334521,11.43998908996582,-0.44159020186231146,1739141171.933456,11.43998908996582,21.144181568860272,1739141171.9334595,11.43998908996582,29.756091627005524,1739141171.933461,11.43998908996582,-0.07879090310828729,1739141171.9334633,11.43998908996582,0.0465789713694627,1739141171.933465,11.43998908996582,0.2503882115382772,1739141171.933467,11.43998908996582,0.03167318708162176,1739141171.9334683,11.43998908996582,2.261742304035824,1739141171.9334705,11.43998908996582,0.0,1739141171.9334724,11.43998908996582,0.05560104661109788,1739141171.933474,11.43998908996582,0.014438291753478629,1739141171.9334755,11.43998908996582,2.206141257424726 +1739141171.9535263,11.459989070892334,21.972817896073458,1739141171.9535291,11.459989070892334,-0.44159020186231146,1739141171.9535327,11.459989070892334,21.144181568860272,1739141171.953536,11.459989070892334,29.756091627005524,1739141171.9535377,11.459989070892334,-0.07879090310828729,1739141171.95354,11.459989070892334,0.0465789713694627,1739141171.953542,11.459989070892334,0.2503882115382772,1739141171.9535434,11.459989070892334,0.03167318708162176,1739141171.9535449,11.459989070892334,2.261742304035824,1739141171.953547,11.459989070892334,0.0,1739141171.9535491,11.459989070892334,0.05560104661109788,1739141171.9535508,11.459989070892334,0.014438291753478629,1739141171.9535522,11.459989070892334,2.206141257424726 +1739141171.9736817,11.479989051818848,21.972817896073458,1739141171.9736848,11.479989051818848,-0.44159020186231146,1739141171.9736886,11.479989051818848,21.144181568860272,1739141171.9736922,11.479989051818848,29.756091627005524,1739141171.9736938,11.479989051818848,-0.07879090310828729,1739141171.9736958,11.479989051818848,0.0465789713694627,1739141171.9736974,11.479989051818848,0.2503882115382772,1739141171.973699,11.479989051818848,0.03167318708162176,1739141171.9737005,11.479989051818848,2.261742304035824,1739141171.9737027,11.479989051818848,0.0,1739141171.9737043,11.479989051818848,0.05560104661109788,1739141171.9737065,11.479989051818848,0.014438291753478629,1739141171.973708,11.479989051818848,2.206141257424726 +1739141171.9937165,11.499989032745361,21.972817896073458,1739141171.9937205,11.499989032745361,-0.44159020186231146,1739141171.993724,11.499989032745361,21.144181568860272,1739141171.9937274,11.499989032745361,29.756091627005524,1739141171.9937294,11.499989032745361,-0.07879090310828729,1739141171.9937313,11.499989032745361,0.0465789713694627,1739141171.9937332,11.499989032745361,0.2503882115382772,1739141171.993735,11.499989032745361,0.03167318708162176,1739141171.993737,11.499989032745361,2.261742304035824,1739141171.9937387,11.499989032745361,0.0,1739141171.9937406,11.499989032745361,0.05560104661109788,1739141171.993742,11.499989032745361,0.014438291753478629,1739141171.993744,11.499989032745361,2.206141257424726 +1739141172.0138385,11.519989013671875,22.215770614596643,1739141172.0138416,11.519989013671875,-0.4379787699974864,1739141172.0138457,11.519989013671875,21.41314819647753,1739141172.013849,11.519989013671875,30.043290625641625,1739141172.013851,11.519989013671875,-0.076764997076441,1739141172.0138528,11.519989013671875,0.04611392834762673,1739141172.0138547,11.519989013671875,0.24083845959357122,1739141172.0138562,11.519989013671875,0.030123139950175036,1739141172.0138578,11.519989013671875,2.270398457520473,1739141172.01386,11.519989013671875,0.0,1739141172.013862,11.519989013671875,0.060518894636135474,1739141172.0138636,11.519989013671875,0.015373626391628852,1739141172.0138652,11.519989013671875,2.212221396447061 +1739141172.0336976,11.539988994598389,22.215770614596643,1739141172.033701,11.539988994598389,-0.4379787699974864,1739141172.0337045,11.539988994598389,21.41314819647753,1739141172.0337079,11.539988994598389,30.043290625641625,1739141172.0337095,11.539988994598389,-0.076764997076441,1739141172.033712,11.539988994598389,0.04611392834762673,1739141172.0337136,11.539988994598389,0.24083845959357122,1739141172.0337152,11.539988994598389,0.030123139950175036,1739141172.0337167,11.539988994598389,2.270398457520473,1739141172.0337188,11.539988994598389,0.0,1739141172.0337205,11.539988994598389,0.05817706107341225,1739141172.0337224,11.539988994598389,0.015373626391628852,1739141172.0337238,11.539988994598389,2.212221396447061 +1739141172.0537133,11.559988975524902,22.215770614596643,1739141172.0537171,11.559988975524902,-0.4379787699974864,1739141172.053721,11.559988975524902,21.41314819647753,1739141172.0537245,11.559988975524902,30.043290625641625,1739141172.0537262,11.559988975524902,-0.076764997076441,1739141172.0537283,11.559988975524902,0.04611392834762673,1739141172.05373,11.559988975524902,0.24083845959357122,1739141172.0537317,11.559988975524902,0.030123139950175036,1739141172.053733,11.559988975524902,2.270398457520473,1739141172.0537353,11.559988975524902,0.0,1739141172.0537367,11.559988975524902,0.05817706107341225,1739141172.053739,11.559988975524902,0.015373626391628852,1739141172.0537405,11.559988975524902,2.212221396447061 +1739141172.073707,11.579988956451416,22.215770614596643,1739141172.07371,11.579988956451416,-0.4379787699974864,1739141172.073714,11.579988956451416,21.41314819647753,1739141172.0737176,11.579988956451416,30.043290625641625,1739141172.0737193,11.579988956451416,-0.076764997076441,1739141172.0737212,11.579988956451416,0.04611392834762673,1739141172.0737228,11.579988956451416,0.24083845959357122,1739141172.0737245,11.579988956451416,0.030123139950175036,1739141172.073726,11.579988956451416,2.270398457520473,1739141172.073728,11.579988956451416,0.0,1739141172.0737302,11.579988956451416,0.05817706107341225,1739141172.073732,11.579988956451416,0.015373626391628852,1739141172.0737336,11.579988956451416,2.212221396447061 +1739141172.0936692,11.59998893737793,22.215770614596643,1739141172.0936725,11.59998893737793,-0.4379787699974864,1739141172.093676,11.59998893737793,21.41314819647753,1739141172.09368,11.59998893737793,30.043290625641625,1739141172.0936816,11.59998893737793,-0.076764997076441,1739141172.093684,11.59998893737793,0.04611392834762673,1739141172.0936854,11.59998893737793,0.24083845959357122,1739141172.0936873,11.59998893737793,0.030123139950175036,1739141172.0936887,11.59998893737793,2.270398457520473,1739141172.0936906,11.59998893737793,0.0,1739141172.0936928,11.59998893737793,0.05817706107341225,1739141172.0936942,11.59998893737793,0.015373626391628852,1739141172.0936956,11.59998893737793,2.212221396447061 +1739141172.114182,11.619988918304443,22.459404451964115,1739141172.1141849,11.619988918304443,-0.43412927821047553,1739141172.1141884,11.619988918304443,21.828489436311507,1739141172.1141918,11.619988918304443,30.477779870631167,1739141172.1141937,11.619988918304443,-0.075,1739141172.1141958,11.619988918304443,0.04475837204612402,1739141172.1141973,11.619988918304443,0.2283159431103932,1739141172.1141987,11.619988918304443,0.027217137891327185,1739141172.1142004,11.619988918304443,2.2817994282947756,1739141172.114202,11.619988918304443,0.0,1739141172.114204,11.619988918304443,0.06775364972787419,1739141172.1142054,11.619988918304443,0.016308961029779075,1739141172.114207,11.619988918304443,2.2186060611566103 +1739141172.133642,11.639988899230957,22.459404451964115,1739141172.1336477,11.639988899230957,-0.43412927821047553,1739141172.133654,11.639988899230957,21.828489436311507,1739141172.133658,11.639988899230957,30.477779870631167,1739141172.1336594,11.639988899230957,-0.075,1739141172.1336617,11.639988899230957,0.04475837204612402,1739141172.1336632,11.639988899230957,0.2283159431103932,1739141172.1336648,11.639988899230957,0.027217137891327185,1739141172.1336663,11.639988899230957,2.2817994282947756,1739141172.1336682,11.639988899230957,0.0,1739141172.1336699,11.639988899230957,0.06319336713816526,1739141172.1336715,11.639988899230957,0.016308961029779075,1739141172.1336732,11.639988899230957,2.2186060611566103 +1739141172.1597757,11.65998888015747,22.459404451964115,1739141172.159785,11.65998888015747,-0.43412927821047553,1739141172.159795,11.65998888015747,21.828489436311507,1739141172.1598046,11.65998888015747,30.477779870631167,1739141172.1598096,11.65998888015747,-0.075,1739141172.159816,11.65998888015747,0.04475837204612402,1739141172.1598206,11.65998888015747,0.2283159431103932,1739141172.1598253,11.65998888015747,0.027217137891327185,1739141172.1598299,11.65998888015747,2.2817994282947756,1739141172.1598356,11.65998888015747,0.0,1739141172.1598403,11.65998888015747,0.06319336713816526,1739141172.1598446,11.65998888015747,0.016308961029779075,1739141172.1598494,11.65998888015747,2.2186060611566103 +1739141172.1785815,11.679988861083984,22.459404451964115,1739141172.1785905,11.679988861083984,-0.43412927821047553,1739141172.1786005,11.679988861083984,21.828489436311507,1739141172.17861,11.679988861083984,30.477779870631167,1739141172.178615,11.679988861083984,-0.075,1739141172.1786213,11.679988861083984,0.04475837204612402,1739141172.1786258,11.679988861083984,0.2283159431103932,1739141172.1786304,11.679988861083984,0.027217137891327185,1739141172.1786351,11.679988861083984,2.2817994282947756,1739141172.1786406,11.679988861083984,0.0,1739141172.1786458,11.679988861083984,0.06319336713816526,1739141172.1786506,11.679988861083984,0.016308961029779075,1739141172.1786551,11.679988861083984,2.2186060611566103 +1739141172.2066104,11.699988842010498,22.459404451964115,1739141172.206619,11.699988842010498,-0.43412927821047553,1739141172.2066295,11.699988842010498,21.828489436311507,1739141172.2066393,11.699988842010498,30.477779870631167,1739141172.2066443,11.699988842010498,-0.075,1739141172.2066498,11.699988842010498,0.04475837204612402,1739141172.2066548,11.699988842010498,0.2283159431103932,1739141172.206659,11.699988842010498,0.027217137891327185,1739141172.2066636,11.699988842010498,2.2817994282947756,1739141172.2066698,11.699988842010498,0.0,1739141172.2066746,11.699988842010498,0.06319336713816526,1739141172.206679,11.699988842010498,0.016308961029779075,1739141172.2066836,11.699988842010498,2.2186060611566103 +1739141172.223477,11.719988822937012,22.459404451964115,1739141172.2234857,11.719988822937012,-0.43412927821047553,1739141172.223496,11.719988822937012,21.828489436311507,1739141172.223506,11.719988822937012,30.477779870631167,1739141172.223511,11.719988822937012,-0.075,1739141172.223517,11.719988822937012,0.04475837204612402,1739141172.2235217,11.719988822937012,0.2283159431103932,1739141172.2235262,11.719988822937012,0.027217137891327185,1739141172.2235305,11.719988822937012,2.2817994282947756,1739141172.2235365,11.719988822937012,0.0,1739141172.2235415,11.719988822937012,0.06319336713816526,1739141172.2235458,11.719988822937012,0.016308961029779075,1739141172.2235503,11.719988822937012,2.2186060611566103 +1739141172.245903,11.749988794326782,22.703761966296103,1739141172.245912,11.749988794326782,-0.4300397312092139,1739141172.2459223,11.749988794326782,21.852436472716043,1739141172.2459323,11.749988794326782,30.52245080088225,1739141172.2459369,11.749988794326782,-0.07483802765488165,1739141172.245943,11.749988794326782,0.04539861476841009,1739141172.2459478,11.749988794326782,0.2203277925507636,1739141172.2459524,11.749988794326782,0.027621990278846487,1739141172.245957,11.749988794326782,2.28910203189311,1739141172.2459629,11.749988794326782,0.0,1739141172.2459679,11.749988794326782,0.06394649504544975,1739141172.2459722,11.749988794326782,0.0172442956679293,1739141172.245977,11.749988794326782,2.225514169363615 +1739141172.2775977,11.779988765716553,22.703761966296103,1739141172.277602,11.779988765716553,-0.4300397312092139,1739141172.2776067,11.779988765716553,21.852436472716043,1739141172.2776108,11.779988765716553,30.52245080088225,1739141172.2776127,11.779988765716553,-0.07483802765488165,1739141172.2776153,11.779988765716553,0.04539861476841009,1739141172.277618,11.779988765716553,0.2203277925507636,1739141172.27762,11.779988765716553,0.027621990278846487,1739141172.2776217,11.779988765716553,2.28910203189311,1739141172.2776246,11.779988765716553,0.0,1739141172.277627,11.779988765716553,0.063587862529495,1739141172.2776287,11.779988765716553,0.0172442956679293,1739141172.2776308,11.779988765716553,2.225514169363615 +1739141172.2961257,11.799988746643066,22.703761966296103,1739141172.2961283,11.799988746643066,-0.4300397312092139,1739141172.2961311,11.799988746643066,21.852436472716043,1739141172.296134,11.799988746643066,30.52245080088225,1739141172.2961354,11.799988746643066,-0.07483802765488165,1739141172.2961369,11.799988746643066,0.04539861476841009,1739141172.2961385,11.799988746643066,0.2203277925507636,1739141172.29614,11.799988746643066,0.027621990278846487,1739141172.2961416,11.799988746643066,2.28910203189311,1739141172.296143,11.799988746643066,0.0,1739141172.2961447,11.799988746643066,0.063587862529495,1739141172.296146,11.799988746643066,0.0172442956679293,1739141172.296147,11.799988746643066,2.225514169363615 +1739141172.3176203,11.81998872756958,22.703761966296103,1739141172.3176239,11.81998872756958,-0.4300397312092139,1739141172.3176289,11.81998872756958,21.852436472716043,1739141172.3176343,11.81998872756958,30.52245080088225,1739141172.3176374,11.81998872756958,-0.07483802765488165,1739141172.3176415,11.81998872756958,0.04539861476841009,1739141172.3176448,11.81998872756958,0.2203277925507636,1739141172.3176482,11.81998872756958,0.027621990278846487,1739141172.3176517,11.81998872756958,2.28910203189311,1739141172.3176553,11.81998872756958,0.0,1739141172.317659,11.81998872756958,0.063587862529495,1739141172.3176625,11.81998872756958,0.0172442956679293,1739141172.3176658,11.81998872756958,2.225514169363615 +1739141172.33732,11.839988708496094,22.948877938284667,1739141172.3373241,11.839988708496094,-0.4257081572740091,1739141172.3373277,11.839988708496094,22.12034621104541,1739141172.3373303,11.839988708496094,30.811219625584993,1739141172.3373322,11.839988708496094,-0.073,1739141172.3373346,11.839988708496094,0.044830389333267516,1739141172.337336,11.839988708496094,0.20972328197667672,1739141172.3373375,11.839988708496094,0.02600279547523901,1739141172.337339,11.839988708496094,2.2988325775187963,1739141172.3373408,11.839988708496094,0.0,1739141172.3373427,11.839988708496094,0.0688862593060067,1739141172.3373442,11.839988708496094,0.01817963030607952,1739141172.3373458,11.839988708496094,2.232469365557215 +1739141172.3577795,11.859988689422607,22.948877938284667,1739141172.3577838,11.859988689422607,-0.4257081572740091,1739141172.3577905,11.859988689422607,22.12034621104541,1739141172.3577976,11.859988689422607,30.811219625584993,1739141172.3578017,11.859988689422607,-0.073,1739141172.357805,11.859988689422607,0.044830389333267516,1739141172.3578074,11.859988689422607,0.20972328197667672,1739141172.357812,11.859988689422607,0.02600279547523901,1739141172.3578143,11.859988689422607,2.2988325775187963,1739141172.357817,11.859988689422607,0.0,1739141172.3578193,11.859988689422607,0.06636321196158113,1739141172.3578217,11.859988689422607,0.01817963030607952,1739141172.3578238,11.859988689422607,2.232469365557215 +1739141172.3767347,11.879988670349121,22.948877938284667,1739141172.3767388,11.879988670349121,-0.4257081572740091,1739141172.3767428,11.879988670349121,22.12034621104541,1739141172.3767462,11.879988670349121,30.811219625584993,1739141172.3767483,11.879988670349121,-0.073,1739141172.3767502,11.879988670349121,0.044830389333267516,1739141172.3767521,11.879988670349121,0.20972328197667672,1739141172.3767538,11.879988670349121,0.02600279547523901,1739141172.3767555,11.879988670349121,2.2988325775187963,1739141172.3767576,11.879988670349121,0.0,1739141172.3767595,11.879988670349121,0.06636321196158113,1739141172.3767614,11.879988670349121,0.01817963030607952,1739141172.3767629,11.879988670349121,2.232469365557215 +1739141172.3963728,11.899988651275635,22.948877938284667,1739141172.3963757,11.899988651275635,-0.4257081572740091,1739141172.3963792,11.899988651275635,22.12034621104541,1739141172.396382,11.899988651275635,30.811219625584993,1739141172.396384,11.899988651275635,-0.073,1739141172.3963861,11.899988651275635,0.044830389333267516,1739141172.3963878,11.899988651275635,0.20972328197667672,1739141172.3963897,11.899988651275635,0.02600279547523901,1739141172.396391,11.899988651275635,2.2988325775187963,1739141172.3963933,11.899988651275635,0.0,1739141172.396395,11.899988651275635,0.06636321196158113,1739141172.3963966,11.899988651275635,0.01817963030607952,1739141172.396398,11.899988651275635,2.232469365557215 +1739141172.418618,11.919988632202148,22.948877938284667,1739141172.4186242,11.919988632202148,-0.4257081572740091,1739141172.418632,11.919988632202148,22.12034621104541,1739141172.4186406,11.919988632202148,30.811219625584993,1739141172.4186442,11.919988632202148,-0.073,1739141172.4186466,11.919988632202148,0.044830389333267516,1739141172.4186482,11.919988632202148,0.20972328197667672,1739141172.41865,11.919988632202148,0.02600279547523901,1739141172.4186513,11.919988632202148,2.2988325775187963,1739141172.4186535,11.919988632202148,0.0,1739141172.418655,11.919988632202148,0.06636321196158113,1739141172.4186566,11.919988632202148,0.01817963030607952,1739141172.4186583,11.919988632202148,2.232469365557215 +1739141172.438513,11.939988613128662,22.948877938284667,1739141172.4385178,11.939988613128662,-0.4257081572740091,1739141172.4385233,11.939988613128662,22.12034621104541,1739141172.43853,11.939988613128662,30.811219625584993,1739141172.4385335,11.939988613128662,-0.073,1739141172.4385386,11.939988613128662,0.044830389333267516,1739141172.4385426,11.939988613128662,0.20972328197667672,1739141172.438547,11.939988613128662,0.02600279547523901,1739141172.438551,11.939988613128662,2.2988325775187963,1739141172.4385555,11.939988613128662,0.0,1739141172.4385598,11.939988613128662,0.06636321196158113,1739141172.438564,11.939988613128662,0.01817963030607952,1739141172.438568,11.939988613128662,2.232469365557215 +1739141172.4578502,11.959988594055176,23.194769802507214,1739141172.4578545,11.959988594055176,-0.4211328028697192,1739141172.4578605,11.959988594055176,22.36545591034478,1739141172.4578671,11.959988594055176,31.078094502311245,1739141172.457871,11.959988594055176,-0.072,1739141172.457876,11.959988594055176,0.044258586740728335,1739141172.45788,11.959988594055176,0.19838872249672482,1739141172.4578843,11.959988594055176,0.02446801610962166,1739141172.4578886,11.959988594055176,2.309278741993157,1739141172.457893,11.959988594055176,0.0,1739141172.4578972,11.959988594055176,0.07245258201060528,1739141172.4579015,11.959988594055176,0.019114964944229745,1739141172.4579058,11.959988594055176,2.239725861454424 +1739141172.4787595,11.97998857498169,23.194769802507214,1739141172.4787643,11.97998857498169,-0.4211328028697192,1739141172.4787703,11.97998857498169,22.36545591034478,1739141172.478777,11.97998857498169,31.078094502311245,1739141172.4787807,11.97998857498169,-0.072,1739141172.4787855,11.97998857498169,0.044258586740728335,1739141172.4787896,11.97998857498169,0.19838872249672482,1739141172.478794,11.97998857498169,0.02446801610962166,1739141172.4787982,11.97998857498169,2.309278741993157,1739141172.4788027,11.97998857498169,0.0,1739141172.478807,11.97998857498169,0.06955288053873288,1739141172.478811,11.97998857498169,0.019114964944229745,1739141172.4788153,11.97998857498169,2.239725861454424 +1739141172.5020716,12.00998854637146,23.194769802507214,1739141172.5020776,12.00998854637146,-0.4211328028697192,1739141172.5020845,12.00998854637146,22.36545591034478,1739141172.5020912,12.00998854637146,31.078094502311245,1739141172.5020945,12.00998854637146,-0.072,1739141172.5020988,12.00998854637146,0.044258586740728335,1739141172.502102,12.00998854637146,0.19838872249672482,1739141172.5021052,12.00998854637146,0.02446801610962166,1739141172.5021086,12.00998854637146,2.309278741993157,1739141172.5021129,12.00998854637146,0.0,1739141172.5021164,12.00998854637146,0.06955288053873288,1739141172.5021195,12.00998854637146,0.019114964944229745,1739141172.5021226,12.00998854637146,2.239725861454424 +1739141172.5409226,12.049988508224487,23.194769802507214,1739141172.5409262,12.049988508224487,-0.4211328028697192,1739141172.5409298,12.049988508224487,22.36545591034478,1739141172.5409331,12.049988508224487,31.078094502311245,1739141172.5409346,12.049988508224487,-0.072,1739141172.5409367,12.049988508224487,0.044258586740728335,1739141172.5409381,12.049988508224487,0.19838872249672482,1739141172.5409398,12.049988508224487,0.02446801610962166,1739141172.5409412,12.049988508224487,2.309278741993157,1739141172.5409431,12.049988508224487,0.0,1739141172.5409448,12.049988508224487,0.06955288053873288,1739141172.5409462,12.049988508224487,0.019114964944229745,1739141172.5409477,12.049988508224487,2.239725861454424 +1739141172.560143,12.069988489151001,23.441475037590873,1739141172.560146,12.069988489151001,-0.4163114749283876,1739141172.5601492,12.069988489151001,22.637204755485538,1739141172.560152,12.069988489151001,31.37274219930487,1739141172.5601532,12.069988489151001,-0.0729987424356335,1739141172.5601552,12.069988489151001,0.04325898336299357,1739141172.5601566,12.069988489151001,0.18423009859121858,1739141172.560158,12.069988489151001,0.02244996008474926,1739141172.5601592,12.069988489151001,2.322394330353595,1739141172.5601609,12.069988489151001,0.0,1739141172.560162,12.069988489151001,0.08001818901866566,1739141172.5601633,12.069988489151001,0.020050299582379968,1739141172.560165,12.069988489151001,2.2473596240529363 +1739141172.5801983,12.089988470077515,23.441475037590873,1739141172.5802011,12.089988470077515,-0.4163114749283876,1739141172.580204,12.089988470077515,22.637204755485538,1739141172.5802066,12.089988470077515,31.37274219930487,1739141172.580208,12.089988470077515,-0.0729987424356335,1739141172.5802097,12.089988470077515,0.04325898336299357,1739141172.5802112,12.089988470077515,0.18423009859121858,1739141172.5802126,12.089988470077515,0.02244996008474926,1739141172.5802135,12.089988470077515,2.322394330353595,1739141172.5802152,12.089988470077515,0.0,1739141172.5802166,12.089988470077515,0.0750347063006589,1739141172.5802176,12.089988470077515,0.020050299582379968,1739141172.5802188,12.089988470077515,2.2473596240529363 +1739141172.600124,12.109988451004028,23.441475037590873,1739141172.600127,12.109988451004028,-0.4163114749283876,1739141172.6001298,12.109988451004028,22.637204755485538,1739141172.6001325,12.109988451004028,31.37274219930487,1739141172.600134,12.109988451004028,-0.0729987424356335,1739141172.6001353,12.109988451004028,0.04325898336299357,1739141172.600137,12.109988451004028,0.18423009859121858,1739141172.6001382,12.109988451004028,0.02244996008474926,1739141172.6001394,12.109988451004028,2.322394330353595,1739141172.6001408,12.109988451004028,0.0,1739141172.600142,12.109988451004028,0.0750347063006589,1739141172.6001434,12.109988451004028,0.020050299582379968,1739141172.6001446,12.109988451004028,2.2473596240529363 +1739141172.6204655,12.129988431930542,23.441475037590873,1739141172.6204681,12.129988431930542,-0.4163114749283876,1739141172.6204712,12.129988431930542,22.637204755485538,1739141172.6204739,12.129988431930542,31.37274219930487,1739141172.6204753,12.129988431930542,-0.0729987424356335,1739141172.620477,12.129988431930542,0.04325898336299357,1739141172.6204782,12.129988431930542,0.18423009859121858,1739141172.6204796,12.129988431930542,0.02244996008474926,1739141172.6204808,12.129988431930542,2.322394330353595,1739141172.6204822,12.129988431930542,0.0,1739141172.620484,12.129988431930542,0.0750347063006589,1739141172.6204853,12.129988431930542,0.020050299582379968,1739141172.620487,12.129988431930542,2.2473596240529363 +1739141172.6406236,12.149988412857056,23.441475037590873,1739141172.640627,12.149988412857056,-0.4163114749283876,1739141172.6406298,12.149988412857056,22.637204755485538,1739141172.6406326,12.149988412857056,31.37274219930487,1739141172.6406338,12.149988412857056,-0.0729987424356335,1739141172.6406355,12.149988412857056,0.04325898336299357,1739141172.6406372,12.149988412857056,0.18423009859121858,1739141172.6406384,12.149988412857056,0.02244996008474926,1739141172.6406398,12.149988412857056,2.322394330353595,1739141172.640641,12.149988412857056,0.0,1739141172.6406426,12.149988412857056,0.0750347063006589,1739141172.6406438,12.149988412857056,0.020050299582379968,1739141172.640646,12.149988412857056,2.2473596240529363 +1739141172.6604736,12.16998839378357,23.689046459574964,1739141172.660476,12.16998839378357,-0.4112415591947727,1739141172.6604788,12.16998839378357,22.92484704483273,1739141172.6604812,12.16998839378357,31.685133375667984,1739141172.6604826,12.16998839378357,-0.07481442817662674,1739141172.660484,12.16998839378357,0.042049170870448585,1739141172.6604853,12.16998839378357,0.168562414174277,1739141172.6604867,12.16998839378357,0.020211207600491384,1739141172.660488,12.16998839378357,2.3369946497898537,1739141172.6604896,12.16998839378357,0.0,1739141172.660491,12.16998839378357,0.08715400568194963,1739141172.660492,12.16998839378357,0.02098563422053019,1739141172.6604934,12.16998839378357,2.2556117419342914 +1739141172.679826,12.189988374710083,23.689046459574964,1739141172.679828,12.189988374710083,-0.4112415591947727,1739141172.6798306,12.189988374710083,22.92484704483273,1739141172.679833,12.189988374710083,31.685133375667984,1739141172.6798341,12.189988374710083,-0.07481442817662674,1739141172.6798356,12.189988374710083,0.042049170870448585,1739141172.6798372,12.189988374710083,0.168562414174277,1739141172.6798384,12.189988374710083,0.020211207600491384,1739141172.6798394,12.189988374710083,2.3369946497898537,1739141172.679841,12.189988374710083,0.0,1739141172.6798422,12.189988374710083,0.08138290785556235,1739141172.6798434,12.189988374710083,0.02098563422053019,1739141172.6798449,12.189988374710083,2.2556117419342914 +1739141172.6997948,12.209988355636597,23.689046459574964,1739141172.6997986,12.209988355636597,-0.4112415591947727,1739141172.6998024,12.209988355636597,22.92484704483273,1739141172.699806,12.209988355636597,31.685133375667984,1739141172.6998076,12.209988355636597,-0.07481442817662674,1739141172.69981,12.209988355636597,0.042049170870448585,1739141172.6998122,12.209988355636597,0.168562414174277,1739141172.6998138,12.209988355636597,0.020211207600491384,1739141172.6998155,12.209988355636597,2.3369946497898537,1739141172.6998174,12.209988355636597,0.0,1739141172.6998193,12.209988355636597,0.08138290785556235,1739141172.6998212,12.209988355636597,0.02098563422053019,1739141172.6998227,12.209988355636597,2.2556117419342914 +1739141172.7203214,12.22998833656311,23.689046459574964,1739141172.7203238,12.22998833656311,-0.4112415591947727,1739141172.7203264,12.22998833656311,22.92484704483273,1739141172.7203288,12.22998833656311,31.685133375667984,1739141172.72033,12.22998833656311,-0.07481442817662674,1739141172.7203314,12.22998833656311,0.042049170870448585,1739141172.7203329,12.22998833656311,0.168562414174277,1739141172.720334,12.22998833656311,0.020211207600491384,1739141172.720335,12.22998833656311,2.3369946497898537,1739141172.720337,12.22998833656311,0.0,1739141172.7203379,12.22998833656311,0.08138290785556235,1739141172.7203393,12.22998833656311,0.02098563422053019,1739141172.7203403,12.22998833656311,2.2556117419342914 +1739141172.7398438,12.249988317489624,23.689046459574964,1739141172.739846,12.249988317489624,-0.4112415591947727,1739141172.7398484,12.249988317489624,22.92484704483273,1739141172.7398508,12.249988317489624,31.685133375667984,1739141172.739852,12.249988317489624,-0.07481442817662674,1739141172.7398536,12.249988317489624,0.042049170870448585,1739141172.7398548,12.249988317489624,0.168562414174277,1739141172.7398562,12.249988317489624,0.020211207600491384,1739141172.7398572,12.249988317489624,2.3369946497898537,1739141172.7398586,12.249988317489624,0.0,1739141172.73986,12.249988317489624,0.08138290785556235,1739141172.739861,12.249988317489624,0.02098563422053019,1739141172.7398622,12.249988317489624,2.2556117419342914 +1739141172.760261,12.269988298416138,23.689046459574964,1739141172.7602634,12.269988298416138,-0.4112415591947727,1739141172.760266,12.269988298416138,22.92484704483273,1739141172.7602687,12.269988298416138,31.685133375667984,1739141172.76027,12.269988298416138,-0.07481442817662674,1739141172.7602718,12.269988298416138,0.042049170870448585,1739141172.7602732,12.269988298416138,0.168562414174277,1739141172.7602744,12.269988298416138,0.020211207600491384,1739141172.760276,12.269988298416138,2.3369946497898537,1739141172.7602775,12.269988298416138,0.0,1739141172.7602787,12.269988298416138,0.08138290785556235,1739141172.76028,12.269988298416138,0.02098563422053019,1739141172.760281,12.269988298416138,2.2556117419342914 +1739141172.7802105,12.289988279342651,23.937564018144847,1739141172.7802129,12.289988279342651,-0.4059197131292027,1739141172.7802155,12.289988279342651,23.212806871205267,1739141172.7802181,12.289988279342651,32.00015297248969,1739141172.7802196,12.289988279342651,-0.0775959727251323,1739141172.7802212,12.289988279342651,0.040699388169190984,1739141172.7802224,12.289988279342651,0.1515192520751425,1739141172.7802238,12.289988279342651,0.017871264422085233,1739141172.780225,12.289988279342651,2.3529809908930317,1739141172.7802265,12.289988279342651,0.0,1739141172.7802281,12.289988279342651,0.09467460777890584,1739141172.780229,12.289988279342651,0.021920968858680414,1739141172.7802303,12.289988279342651,2.2646357671918076 +1739141172.8000574,12.309988260269165,23.937564018144847,1739141172.8000598,12.309988260269165,-0.4059197131292027,1739141172.8000624,12.309988260269165,23.212806871205267,1739141172.800065,12.309988260269165,32.00015297248969,1739141172.8000662,12.309988260269165,-0.0775959727251323,1739141172.800068,12.309988260269165,0.040699388169190984,1739141172.800069,12.309988260269165,0.1515192520751425,1739141172.80007,12.309988260269165,0.017871264422085233,1739141172.8000715,12.309988260269165,2.3529809908930317,1739141172.8000727,12.309988260269165,0.0,1739141172.8000743,12.309988260269165,0.08834522370122411,1739141172.8000755,12.309988260269165,0.021920968858680414,1739141172.800077,12.309988260269165,2.2646357671918076 +1739141172.8201606,12.329988241195679,23.937564018144847,1739141172.820163,12.329988241195679,-0.4059197131292027,1739141172.8201656,12.329988241195679,23.212806871205267,1739141172.8201683,12.329988241195679,32.00015297248969,1739141172.8201694,12.329988241195679,-0.0775959727251323,1739141172.8201714,12.329988241195679,0.040699388169190984,1739141172.8201725,12.329988241195679,0.1515192520751425,1739141172.8201737,12.329988241195679,0.017871264422085233,1739141172.820175,12.329988241195679,2.3529809908930317,1739141172.8201766,12.329988241195679,0.0,1739141172.820178,12.329988241195679,0.08834522370122411,1739141172.820179,12.329988241195679,0.021920968858680414,1739141172.8201802,12.329988241195679,2.2646357671918076 +1739141172.8399944,12.349988222122192,23.937564018144847,1739141172.8399966,12.349988222122192,-0.4059197131292027,1739141172.8399994,12.349988222122192,23.212806871205267,1739141172.840002,12.349988222122192,32.00015297248969,1739141172.8400033,12.349988222122192,-0.0775959727251323,1739141172.840005,12.349988222122192,0.040699388169190984,1739141172.840006,12.349988222122192,0.1515192520751425,1739141172.8400073,12.349988222122192,0.017871264422085233,1739141172.8400085,12.349988222122192,2.3529809908930317,1739141172.84001,12.349988222122192,0.0,1739141172.8400114,12.349988222122192,0.08834522370122411,1739141172.8400126,12.349988222122192,0.021920968858680414,1739141172.8400137,12.349988222122192,2.2646357671918076 +1739141172.8601334,12.369988203048706,23.937564018144847,1739141172.8601358,12.369988203048706,-0.4059197131292027,1739141172.8601384,12.369988203048706,23.212806871205267,1739141172.860141,12.369988203048706,32.00015297248969,1739141172.860142,12.369988203048706,-0.0775959727251323,1739141172.860144,12.369988203048706,0.040699388169190984,1739141172.860145,12.369988203048706,0.1515192520751425,1739141172.8601465,12.369988203048706,0.017871264422085233,1739141172.8601475,12.369988203048706,2.3529809908930317,1739141172.860149,12.369988203048706,0.0,1739141172.8601503,12.369988203048706,0.08834522370122411,1739141172.8601515,12.369988203048706,0.021920968858680414,1739141172.8601527,12.369988203048706,2.2646357671918076 +1739141172.8799336,12.38998818397522,24.187099071242688,1739141172.879936,12.38998818397522,-0.40034256122035217,1739141172.8799388,12.38998818397522,23.460082846781024,1739141172.8799415,12.38998818397522,32.27657776291501,1739141172.8799427,12.38998818397522,-0.08,1739141172.879944,12.38998818397522,0.03957922162427494,1739141172.8799455,12.38998818397522,0.13537940772696702,1739141172.8799467,12.38998818397522,0.0158631052227247,1739141172.8799477,12.38998818397522,2.3682208304677452,1739141172.8799493,12.38998818397522,0.0,1739141172.8799505,12.38998818397522,0.09888335644262206,1739141172.879952,12.38998818397522,0.022856303496830637,1739141172.8799531,12.38998818397522,2.2743556349801985 +1739141172.8999572,12.409988164901733,24.187099071242688,1739141172.8999596,12.409988164901733,-0.40034256122035217,1739141172.8999624,12.409988164901733,23.460082846781024,1739141172.8999653,12.409988164901733,32.27657776291501,1739141172.8999665,12.409988164901733,-0.08,1739141172.8999677,12.409988164901733,0.03957922162427494,1739141172.899969,12.409988164901733,0.13537940772696702,1739141172.8999703,12.409988164901733,0.0158631052227247,1739141172.8999712,12.409988164901733,2.3682208304677452,1739141172.899973,12.409988164901733,0.0,1739141172.8999743,12.409988164901733,0.09386519548754668,1739141172.8999755,12.409988164901733,0.022856303496830637,1739141172.8999767,12.409988164901733,2.2743556349801985 +1739141172.919907,12.429988145828247,24.187099071242688,1739141172.9199095,12.429988145828247,-0.40034256122035217,1739141172.919912,12.429988145828247,23.460082846781024,1739141172.9199147,12.429988145828247,32.27657776291501,1739141172.919916,12.429988145828247,-0.08,1739141172.9199178,12.429988145828247,0.03957922162427494,1739141172.919919,12.429988145828247,0.13537940772696702,1739141172.9199204,12.429988145828247,0.0158631052227247,1739141172.9199214,12.429988145828247,2.3682208304677452,1739141172.9199228,12.429988145828247,0.0,1739141172.9199243,12.429988145828247,0.09386519548754668,1739141172.9199255,12.429988145828247,0.022856303496830637,1739141172.919927,12.429988145828247,2.2743556349801985 +1739141172.9399986,12.44998812675476,24.187099071242688,1739141172.940001,12.44998812675476,-0.40034256122035217,1739141172.9400039,12.44998812675476,23.460082846781024,1739141172.9400065,12.44998812675476,32.27657776291501,1739141172.9400077,12.44998812675476,-0.08,1739141172.940009,12.44998812675476,0.03957922162427494,1739141172.9400105,12.44998812675476,0.13537940772696702,1739141172.9400115,12.44998812675476,0.0158631052227247,1739141172.9400127,12.44998812675476,2.3682208304677452,1739141172.9400144,12.44998812675476,0.0,1739141172.9400158,12.44998812675476,0.09386519548754668,1739141172.940017,12.44998812675476,0.022856303496830637,1739141172.9400182,12.44998812675476,2.2743556349801985 +1739141172.959774,12.469988107681274,24.187099071242688,1739141172.9597762,12.469988107681274,-0.40034256122035217,1739141172.959779,12.469988107681274,23.460082846781024,1739141172.9597816,12.469988107681274,32.27657776291501,1739141172.9597828,12.469988107681274,-0.08,1739141172.9597845,12.469988107681274,0.03957922162427494,1739141172.9597857,12.469988107681274,0.13537940772696702,1739141172.959787,12.469988107681274,0.0158631052227247,1739141172.9597883,12.469988107681274,2.3682208304677452,1739141172.9597898,12.469988107681274,0.0,1739141172.9597912,12.469988107681274,0.09386519548754668,1739141172.9597924,12.469988107681274,0.022856303496830637,1739141172.9597936,12.469988107681274,2.2743556349801985 +1739141172.9803903,12.489988088607788,24.187099071242688,1739141172.9803927,12.489988088607788,-0.40034256122035217,1739141172.9803956,12.489988088607788,23.460082846781024,1739141172.980398,12.489988088607788,32.27657776291501,1739141172.9803991,12.489988088607788,-0.08,1739141172.9804006,12.489988088607788,0.03957922162427494,1739141172.980402,12.489988088607788,0.13537940772696702,1739141172.980403,12.489988088607788,0.0158631052227247,1739141172.980404,12.489988088607788,2.3682208304677452,1739141172.9804056,12.489988088607788,0.0,1739141172.9804068,12.489988088607788,0.09386519548754668,1739141172.980408,12.489988088607788,0.022856303496830637,1739141172.9804096,12.489988088607788,2.2743556349801985 +1739141173.0000768,12.509988069534302,24.43773451669617,1739141173.0000794,12.509988069534302,-0.39450626069405725,1739141173.0000823,12.509988069534302,23.598821907500565,1739141173.0000849,12.509988069534302,32.446443138372544,1739141173.0000868,12.509988069534302,-0.08,1739141173.000089,12.509988069534302,0.03925036487568585,1739141173.0000901,12.509988069534302,0.12389493068161854,1739141173.0000916,12.509988069534302,0.01481211242166245,1739141173.000093,12.509988069534302,2.3791249680619044,1739141173.0000944,12.509988069534302,0.0,1739141173.000096,12.509988069534302,0.09487453106513064,1739141173.0000973,12.509988069534302,0.02379163813498086,1739141173.0000987,12.509988069534302,2.2847310732261983 +1739141173.0199525,12.529988050460815,24.43773451669617,1739141173.019956,12.529988050460815,-0.39450626069405725,1739141173.019959,12.529988050460815,23.598821907500565,1739141173.0199618,12.529988050460815,32.446443138372544,1739141173.019963,12.529988050460815,-0.08,1739141173.0199647,12.529988050460815,0.03925036487568585,1739141173.019966,12.529988050460815,0.12389493068161854,1739141173.0199673,12.529988050460815,0.01481211242166245,1739141173.0199687,12.529988050460815,2.3791249680619044,1739141173.019971,12.529988050460815,0.0,1739141173.019972,12.529988050460815,0.09439389483570615,1739141173.0199733,12.529988050460815,0.02379163813498086,1739141173.0199747,12.529988050460815,2.2847310732261983 +1739141173.0475144,12.549988031387329,24.43773451669617,1739141173.047519,12.549988031387329,-0.39450626069405725,1739141173.0475235,12.549988031387329,23.598821907500565,1739141173.047529,12.549988031387329,32.446443138372544,1739141173.047532,12.549988031387329,-0.08,1739141173.0475357,12.549988031387329,0.03925036487568585,1739141173.047539,12.549988031387329,0.12389493068161854,1739141173.0475423,12.549988031387329,0.01481211242166245,1739141173.0475457,12.549988031387329,2.3791249680619044,1739141173.0475495,12.549988031387329,0.0,1739141173.047553,12.549988031387329,0.09439389483570615,1739141173.0475562,12.549988031387329,0.02379163813498086,1739141173.0475595,12.549988031387329,2.2847310732261983 +1739141173.0839436,12.589987993240356,24.43773451669617,1739141173.0839467,12.589987993240356,-0.39450626069405725,1739141173.0839505,12.589987993240356,23.598821907500565,1739141173.0839534,12.589987993240356,32.446443138372544,1739141173.0839553,12.589987993240356,-0.08,1739141173.0839572,12.589987993240356,0.03925036487568585,1739141173.083959,12.589987993240356,0.12389493068161854,1739141173.08396,12.589987993240356,0.01481211242166245,1739141173.0839612,12.589987993240356,2.3791249680619044,1739141173.083964,12.589987993240356,0.0,1739141173.0839665,12.589987993240356,0.09439389483570615,1739141173.083968,12.589987993240356,0.02379163813498086,1739141173.0839696,12.589987993240356,2.2847310732261983 +1739141173.1087449,12.60998797416687,24.689498060017133,1739141173.108749,12.60998797416687,-0.38840807568776015,1739141173.1087534,12.60998797416687,23.871428110613348,1739141173.1087582,12.60998797416687,32.750032512033826,1739141173.1087615,12.60998797416687,-0.07938597766319888,1739141173.1087654,12.60998797416687,0.038318902474285224,1739141173.1087687,12.60998797416687,0.10963532537349664,1739141173.1087718,12.60998797416687,0.012940275182317352,1739141173.1087751,12.60998797416687,2.3927338959634756,1739141173.1087787,12.60998797416687,0.0,1739141173.108782,12.60998797416687,0.10065704796707214,1739141173.1087854,12.60998797416687,0.024726972773131083,1739141173.1087887,12.60998797416687,2.2950593033583493 +1739141173.128004,12.629987955093384,24.689498060017133,1739141173.1280081,12.629987955093384,-0.38840807568776015,1739141173.128013,12.629987955093384,23.871428110613348,1739141173.1280177,12.629987955093384,32.750032512033826,1739141173.1280208,12.629987955093384,-0.07938597766319888,1739141173.128024,12.629987955093384,0.038318902474285224,1739141173.1280274,12.629987955093384,0.10963532537349664,1739141173.1280305,12.629987955093384,0.012940275182317352,1739141173.1280339,12.629987955093384,2.3927338959634756,1739141173.1280372,12.629987955093384,0.0,1739141173.1280406,12.629987955093384,0.09767459260512634,1739141173.1280434,12.629987955093384,0.024726972773131083,1739141173.1280468,12.629987955093384,2.2950593033583493 +1739141173.1475015,12.649987936019897,24.689498060017133,1739141173.1475043,12.649987936019897,-0.38840807568776015,1739141173.1475072,12.649987936019897,23.871428110613348,1739141173.1475098,12.649987936019897,32.750032512033826,1739141173.147511,12.649987936019897,-0.07938597766319888,1739141173.1475127,12.649987936019897,0.038318902474285224,1739141173.1475139,12.649987936019897,0.10963532537349664,1739141173.1475153,12.649987936019897,0.012940275182317352,1739141173.1475165,12.649987936019897,2.3927338959634756,1739141173.147518,12.649987936019897,0.0,1739141173.1475196,12.649987936019897,0.09767459260512634,1739141173.1475208,12.649987936019897,0.024726972773131083,1739141173.1475222,12.649987936019897,2.2950593033583493 +1739141173.1666808,12.669987916946411,24.689498060017133,1739141173.1666832,12.669987916946411,-0.38840807568776015,1739141173.1666856,12.669987916946411,23.871428110613348,1739141173.1666882,12.669987916946411,32.750032512033826,1739141173.1666894,12.669987916946411,-0.07938597766319888,1739141173.166691,12.669987916946411,0.038318902474285224,1739141173.166692,12.669987916946411,0.10963532537349664,1739141173.1666934,12.669987916946411,0.012940275182317352,1739141173.1666944,12.669987916946411,2.3927338959634756,1739141173.1666958,12.669987916946411,0.0,1739141173.1666973,12.669987916946411,0.09767459260512634,1739141173.1666985,12.669987916946411,0.024726972773131083,1739141173.1667,12.669987916946411,2.2950593033583493 +1739141173.18639,12.689987897872925,24.689498060017133,1739141173.186392,12.689987897872925,-0.38840807568776015,1739141173.1863952,12.689987897872925,23.871428110613348,1739141173.1863978,12.689987897872925,32.750032512033826,1739141173.186399,12.689987897872925,-0.07938597766319888,1739141173.1864004,12.689987897872925,0.038318902474285224,1739141173.1864018,12.689987897872925,0.10963532537349664,1739141173.186403,12.689987897872925,0.012940275182317352,1739141173.1864045,12.689987897872925,2.3927338959634756,1739141173.186406,12.689987897872925,0.0,1739141173.1864073,12.689987897872925,0.09767459260512634,1739141173.1864085,12.689987897872925,0.024726972773131083,1739141173.1864097,12.689987897872925,2.2950593033583493 +1739141173.2070756,12.709987878799438,24.689498060017133,1739141173.207079,12.709987878799438,-0.38840807568776015,1739141173.2070832,12.709987878799438,23.871428110613348,1739141173.2070882,12.709987878799438,32.750032512033826,1739141173.2070909,12.709987878799438,-0.07938597766319888,1739141173.2070944,12.709987878799438,0.038318902474285224,1739141173.2070978,12.709987878799438,0.10963532537349664,1739141173.207101,12.709987878799438,0.012940275182317352,1739141173.2071042,12.709987878799438,2.3927338959634756,1739141173.2071075,12.709987878799438,0.0,1739141173.207111,12.709987878799438,0.09767459260512634,1739141173.207114,12.709987878799438,0.024726972773131083,1739141173.2071173,12.709987878799438,2.2950593033583493 +1739141173.2263718,12.729987859725952,24.94241585963284,1739141173.2263756,12.729987859725952,-0.38204522244989914,1739141173.2263784,12.729987859725952,24.202014809847757,1739141173.226381,12.729987859725952,33.11287397046943,1739141173.2263825,12.729987859725952,-0.079,1739141173.2263842,12.729987859725952,0.03707336443436647,1739141173.2263854,12.729987859725952,0.09329564709038567,1739141173.226387,12.729987859725952,0.010718422987015495,1739141173.2263882,12.729987859725952,2.4084237142583893,1739141173.2263896,12.729987859725952,0.0,1739141173.226391,12.729987859725952,0.10710152253109644,1739141173.226392,12.729987859725952,0.025662307411281306,1739141173.2263935,12.729987859725952,2.3058112082202147 +1739141173.246418,12.749987840652466,24.94241585963284,1739141173.2464204,12.749987840652466,-0.38204522244989914,1739141173.246423,12.749987840652466,24.202014809847757,1739141173.2464256,12.749987840652466,33.11287397046943,1739141173.2464268,12.749987840652466,-0.079,1739141173.2464285,12.749987840652466,0.03707336443436647,1739141173.2464297,12.749987840652466,0.09329564709038567,1739141173.2464309,12.749987840652466,0.010718422987015495,1739141173.2464323,12.749987840652466,2.4084237142583893,1739141173.2464335,12.749987840652466,0.0,1739141173.246435,12.749987840652466,0.10261250603817462,1739141173.246436,12.749987840652466,0.025662307411281306,1739141173.2464373,12.749987840652466,2.3058112082202147 +1739141173.2678835,12.76998782157898,24.94241585963284,1739141173.267887,12.76998782157898,-0.38204522244989914,1739141173.2678916,12.76998782157898,24.202014809847757,1739141173.267897,12.76998782157898,33.11287397046943,1739141173.2679,12.76998782157898,-0.079,1739141173.2679038,12.76998782157898,0.03707336443436647,1739141173.2679071,12.76998782157898,0.09329564709038567,1739141173.2679105,12.76998782157898,0.010718422987015495,1739141173.2679138,12.76998782157898,2.4084237142583893,1739141173.2679174,12.76998782157898,0.0,1739141173.2679207,12.76998782157898,0.10261250603817462,1739141173.2679243,12.76998782157898,0.025662307411281306,1739141173.2679276,12.76998782157898,2.3058112082202147 +1739141173.286561,12.789987802505493,24.94241585963284,1739141173.286564,12.789987802505493,-0.38204522244989914,1739141173.2865672,12.789987802505493,24.202014809847757,1739141173.2865703,12.789987802505493,33.11287397046943,1739141173.2865715,12.789987802505493,-0.079,1739141173.286574,12.789987802505493,0.03707336443436647,1739141173.286575,12.789987802505493,0.09329564709038567,1739141173.2865763,12.789987802505493,0.010718422987015495,1739141173.2865777,12.789987802505493,2.4084237142583893,1739141173.2865794,12.789987802505493,0.0,1739141173.2865813,12.789987802505493,0.10261250603817462,1739141173.2865825,12.789987802505493,0.025662307411281306,1739141173.286584,12.789987802505493,2.3058112082202147 +1739141173.3078752,12.809987783432007,24.94241585963284,1739141173.3078792,12.809987783432007,-0.38204522244989914,1739141173.307884,12.809987783432007,24.202014809847757,1739141173.3078897,12.809987783432007,33.11287397046943,1739141173.3078926,12.809987783432007,-0.079,1739141173.3078964,12.809987783432007,0.03707336443436647,1739141173.3078997,12.809987783432007,0.09329564709038567,1739141173.307903,12.809987783432007,0.010718422987015495,1739141173.3079064,12.809987783432007,2.4084237142583893,1739141173.30791,12.809987783432007,0.0,1739141173.3079143,12.809987783432007,0.10261250603817462,1739141173.307917,12.809987783432007,0.025662307411281306,1739141173.3079207,12.809987783432007,2.3058112082202147 +1739141173.3274114,12.82998776435852,25.1965329889279,1739141173.327415,12.82998776435852,-0.37541435171288473,1739141173.3274198,12.82998776435852,24.665644378890523,1739141173.3274238,12.82998776435852,33.610275024916085,1739141173.3274257,12.82998776435852,-0.07607459225589085,1739141173.3274283,12.82998776435852,0.03556248300101617,1739141173.3274307,12.82998776435852,0.07547456977322844,1739141173.3274324,12.82998776435852,0.008177735161544195,1739141173.3274345,12.82998776435852,2.4256533334637815,1739141173.3274367,12.82998776435852,0.0,1739141173.327439,12.82998776435852,0.11400301424818385,1739141173.3274412,12.82998776435852,0.02659764204943153,1739141173.3274431,12.82998776435852,2.3170743734537256 +1739141173.3474646,12.849987745285034,25.1965329889279,1739141173.3474689,12.849987745285034,-0.37541435171288473,1739141173.3474736,12.849987745285034,24.665644378890523,1739141173.347478,12.849987745285034,33.610275024916085,1739141173.3474805,12.849987745285034,-0.07607459225589085,1739141173.3474839,12.849987745285034,0.03556248300101617,1739141173.3474865,12.849987745285034,0.07547456977322844,1739141173.3474889,12.849987745285034,0.008177735161544195,1739141173.347491,12.849987745285034,2.4256533334637815,1739141173.347494,12.849987745285034,0.0,1739141173.3474963,12.849987745285034,0.10857896001005596,1739141173.3474984,12.849987745285034,0.02659764204943153,1739141173.3475006,12.849987745285034,2.3170743734537256 +1739141173.3675425,12.869987726211548,25.1965329889279,1739141173.3675466,12.869987726211548,-0.37541435171288473,1739141173.3675513,12.869987726211548,24.665644378890523,1739141173.3675559,12.869987726211548,33.610275024916085,1739141173.3675582,12.869987726211548,-0.07607459225589085,1739141173.3675616,12.869987726211548,0.03556248300101617,1739141173.3675637,12.869987726211548,0.07547456977322844,1739141173.3675663,12.869987726211548,0.008177735161544195,1739141173.3675692,12.869987726211548,2.4256533334637815,1739141173.3675718,12.869987726211548,0.0,1739141173.3675742,12.869987726211548,0.10857896001005596,1739141173.3675768,12.869987726211548,0.02659764204943153,1739141173.3675795,12.869987726211548,2.3170743734537256 +1739141173.387375,12.889987707138062,25.1965329889279,1739141173.3873794,12.889987707138062,-0.37541435171288473,1739141173.3873837,12.889987707138062,24.665644378890523,1739141173.3873885,12.889987707138062,33.610275024916085,1739141173.3873906,12.889987707138062,-0.07607459225589085,1739141173.3873935,12.889987707138062,0.03556248300101617,1739141173.3873956,12.889987707138062,0.07547456977322844,1739141173.3873982,12.889987707138062,0.008177735161544195,1739141173.3874004,12.889987707138062,2.4256533334637815,1739141173.3874032,12.889987707138062,0.0,1739141173.3874056,12.889987707138062,0.10857896001005596,1739141173.3874078,12.889987707138062,0.02659764204943153,1739141173.3874104,12.889987707138062,2.3170743734537256 +1739141173.4077168,12.909987688064575,25.1965329889279,1739141173.4077208,12.909987688064575,-0.37541435171288473,1739141173.4077253,12.909987688064575,24.665644378890523,1739141173.40773,12.909987688064575,33.610275024916085,1739141173.4077332,12.909987688064575,-0.07607459225589085,1739141173.4077368,12.909987688064575,0.03556248300101617,1739141173.4077399,12.909987688064575,0.07547456977322844,1739141173.4077432,12.909987688064575,0.008177735161544195,1739141173.4077463,12.909987688064575,2.4256533334637815,1739141173.40775,12.909987688064575,0.0,1739141173.407753,12.909987688064575,0.10857896001005596,1739141173.4077563,12.909987688064575,0.02659764204943153,1739141173.4077594,12.909987688064575,2.3170743734537256 +1739141173.4263926,12.929987668991089,25.1965329889279,1739141173.4263957,12.929987668991089,-0.37541435171288473,1739141173.4263985,12.929987668991089,24.665644378890523,1739141173.4264011,12.929987668991089,33.610275024916085,1739141173.4264026,12.929987668991089,-0.07607459225589085,1739141173.426404,12.929987668991089,0.03556248300101617,1739141173.4264057,12.929987668991089,0.07547456977322844,1739141173.4264069,12.929987668991089,0.008177735161544195,1739141173.426408,12.929987668991089,2.4256533334637815,1739141173.4264097,12.929987668991089,0.0,1739141173.426411,12.929987668991089,0.10857896001005596,1739141173.4264123,12.929987668991089,0.02659764204943153,1739141173.4264135,12.929987668991089,2.3170743734537256 +1739141173.4464512,12.949987649917603,25.451923606583026,1739141173.4464538,12.949987649917603,-0.36851120147408256,1739141173.4464564,12.949987649917603,24.697057424862102,1739141173.4464588,12.949987649917603,33.67766605770143,1739141173.4464602,12.949987649917603,-0.07542294561611362,1739141173.4464614,12.949987649917603,0.03561554751268899,1739141173.4464629,12.949987649917603,0.06652661101582058,1739141173.4464643,12.949987649917603,0.0075414435665063385,1739141173.4464653,12.949987649917603,2.4343507473941624,1739141173.446467,12.949987649917603,0.0,1739141173.4465,12.949987649917603,0.10228592528900401,1739141173.4465015,12.949987649917603,0.027532976687581753,1739141173.4465027,12.949987649917603,2.3290681374076825 +1739141173.466433,12.969987630844116,25.451923606583026,1739141173.466436,12.969987630844116,-0.36851120147408256,1739141173.4664388,12.969987630844116,24.697057424862102,1739141173.4664414,12.969987630844116,33.67766605770143,1739141173.466443,12.969987630844116,-0.07542294561611362,1739141173.4664445,12.969987630844116,0.03561554751268899,1739141173.466446,12.969987630844116,0.06652661101582058,1739141173.466447,12.969987630844116,0.0075414435665063385,1739141173.4664483,12.969987630844116,2.4343507473941624,1739141173.4664502,12.969987630844116,0.0,1739141173.4664514,12.969987630844116,0.10528260998647987,1739141173.4664528,12.969987630844116,0.027532976687581753,1739141173.466454,12.969987630844116,2.3290681374076825 +1739141173.4863594,12.98998761177063,25.451923606583026,1739141173.4863615,12.98998761177063,-0.36851120147408256,1739141173.4863644,12.98998761177063,24.697057424862102,1739141173.486367,12.98998761177063,33.67766605770143,1739141173.4863684,12.98998761177063,-0.07542294561611362,1739141173.48637,12.98998761177063,0.03561554751268899,1739141173.4863715,12.98998761177063,0.06652661101582058,1739141173.486373,12.98998761177063,0.0075414435665063385,1739141173.4863741,12.98998761177063,2.4343507473941624,1739141173.4863756,12.98998761177063,0.0,1739141173.486377,12.98998761177063,0.10528260998647987,1739141173.4863782,12.98998761177063,0.027532976687581753,1739141173.4863796,12.98998761177063,2.3290681374076825 +1739141173.5064342,13.009987592697144,25.451923606583026,1739141173.5064366,13.009987592697144,-0.36851120147408256,1739141173.5064394,13.009987592697144,24.697057424862102,1739141173.506442,13.009987592697144,33.67766605770143,1739141173.5064435,13.009987592697144,-0.07542294561611362,1739141173.5064452,13.009987592697144,0.03561554751268899,1739141173.5064464,13.009987592697144,0.06652661101582058,1739141173.5064476,13.009987592697144,0.0075414435665063385,1739141173.506449,13.009987592697144,2.4343507473941624,1739141173.5064504,13.009987592697144,0.0,1739141173.506452,13.009987592697144,0.10528260998647987,1739141173.506453,13.009987592697144,0.027532976687581753,1739141173.5064542,13.009987592697144,2.3290681374076825 +1739141173.5265908,13.029987573623657,25.451923606583026,1739141173.5265942,13.029987573623657,-0.36851120147408256,1739141173.5265968,13.029987573623657,24.697057424862102,1739141173.5265996,13.029987573623657,33.67766605770143,1739141173.5266013,13.029987573623657,-0.07542294561611362,1739141173.526603,13.029987573623657,0.03561554751268899,1739141173.5266047,13.029987573623657,0.06652661101582058,1739141173.526606,13.029987573623657,0.0075414435665063385,1739141173.5266073,13.029987573623657,2.4343507473941624,1739141173.526609,13.029987573623657,0.0,1739141173.5266101,13.029987573623657,0.10528260998647987,1739141173.5266116,13.029987573623657,0.027532976687581753,1739141173.5266128,13.029987573623657,2.3290681374076825 +1739141173.5463855,13.049987554550171,25.708595175622126,1739141173.5463877,13.049987554550171,-0.3613331767218142,1739141173.5463905,13.049987554550171,24.945247027853913,1739141173.5463932,13.049987554550171,33.96031069153458,1739141173.5463943,13.049987554550171,-0.07411700263645657,1739141173.546396,13.049987554550171,0.034792797781119926,1739141173.5463974,13.049987554550171,0.052219118548959456,1739141173.5463986,13.049987554550171,0.005882688738331482,1739141173.5464,13.049987554550171,2.4483224713188587,1739141173.5464015,13.049987554550171,0.0,1739141173.5464032,13.049987554550171,0.11002612629634748,1739141173.5464044,13.049987554550171,0.028468311325731976,1739141173.5464056,13.049987554550171,2.340555163441303 +1739141173.5664613,13.069987535476685,25.708595175622126,1739141173.5664644,13.069987535476685,-0.3613331767218142,1739141173.5664778,13.069987535476685,24.945247027853913,1739141173.5664818,13.069987535476685,33.96031069153458,1739141173.5664833,13.069987535476685,-0.07411700263645657,1739141173.5664852,13.069987535476685,0.034792797781119926,1739141173.5664866,13.069987535476685,0.052219118548959456,1739141173.566488,13.069987535476685,0.005882688738331482,1739141173.566489,13.069987535476685,2.4483224713188587,1739141173.5664911,13.069987535476685,0.0,1739141173.5664923,13.069987535476685,0.10776730787755584,1739141173.5664937,13.069987535476685,0.028468311325731976,1739141173.566495,13.069987535476685,2.340555163441303 +1739141173.5862834,13.089987516403198,25.708595175622126,1739141173.5862858,13.089987516403198,-0.3613331767218142,1739141173.5862885,13.089987516403198,24.945247027853913,1739141173.5862913,13.089987516403198,33.96031069153458,1739141173.5862925,13.089987516403198,-0.07411700263645657,1739141173.586294,13.089987516403198,0.034792797781119926,1739141173.5862954,13.089987516403198,0.052219118548959456,1739141173.5862966,13.089987516403198,0.005882688738331482,1739141173.5862978,13.089987516403198,2.4483224713188587,1739141173.5862994,13.089987516403198,0.0,1739141173.5863008,13.089987516403198,0.10776730787755584,1739141173.5863023,13.089987516403198,0.028468311325731976,1739141173.5863035,13.089987516403198,2.340555163441303 +1739141173.6063893,13.109987497329712,25.708595175622126,1739141173.606392,13.109987497329712,-0.3613331767218142,1739141173.6063948,13.109987497329712,24.945247027853913,1739141173.6063974,13.109987497329712,33.96031069153458,1739141173.6063993,13.109987497329712,-0.07411700263645657,1739141173.6064007,13.109987497329712,0.034792797781119926,1739141173.6064024,13.109987497329712,0.052219118548959456,1739141173.6064036,13.109987497329712,0.005882688738331482,1739141173.6064048,13.109987497329712,2.4483224713188587,1739141173.6064065,13.109987497329712,0.0,1739141173.6064079,13.109987497329712,0.10776730787755584,1739141173.6064093,13.109987497329712,0.028468311325731976,1739141173.6064105,13.109987497329712,2.340555163441303 +1739141173.6272206,13.129987478256226,25.708595175622126,1739141173.6272237,13.129987478256226,-0.3613331767218142,1739141173.6272268,13.129987478256226,24.945247027853913,1739141173.62723,13.129987478256226,33.96031069153458,1739141173.6272316,13.129987478256226,-0.07411700263645657,1739141173.6272335,13.129987478256226,0.034792797781119926,1739141173.6272352,13.129987478256226,0.052219118548959456,1739141173.6272364,13.129987478256226,0.005882688738331482,1739141173.6272378,13.129987478256226,2.4483224713188587,1739141173.6272395,13.129987478256226,0.0,1739141173.6272411,13.129987478256226,0.10776730787755584,1739141173.6272426,13.129987478256226,0.028468311325731976,1739141173.6272442,13.129987478256226,2.340555163441303 +1739141173.6464198,13.14998745918274,25.708595175622126,1739141173.6464226,13.14998745918274,-0.3613331767218142,1739141173.6464255,13.14998745918274,24.945247027853913,1739141173.6464283,13.14998745918274,33.96031069153458,1739141173.64643,13.14998745918274,-0.07411700263645657,1739141173.6464322,13.14998745918274,0.034792797781119926,1739141173.6464338,13.14998745918274,0.052219118548959456,1739141173.646435,13.14998745918274,0.005882688738331482,1739141173.6464365,13.14998745918274,2.4483224713188587,1739141173.6464381,13.14998745918274,0.0,1739141173.64644,13.14998745918274,0.10776730787755584,1739141173.6464412,13.14998745918274,0.028468311325731976,1739141173.6464424,13.14998745918274,2.340555163441303 +1739141173.6669347,13.169987440109253,25.966543797168576,1739141173.6669378,13.169987440109253,-0.35387797228759155,1739141173.6669407,13.169987440109253,25.72663366509133,1739141173.6669438,13.169987440109253,34.77720411545491,1739141173.666945,13.169987440109253,-0.06920178326371665,1739141173.666947,13.169987440109253,0.03229918949156391,1739141173.6669483,13.169987440109253,0.02552492793557568,1739141173.66695,13.169987440109253,0.0025226417271699327,1739141173.6669512,13.169987440109253,2.47460493411527,1739141173.6669528,13.169987440109253,0.0,1739141173.6669545,13.169987440109253,0.13533565601859282,1739141173.6669557,13.169987440109253,0.0294036459638822,1739141173.6669574,13.169987440109253,2.3523970694836476 +1739141173.6864328,13.189987421035767,25.966543797168576,1739141173.6864357,13.189987421035767,-0.35387797228759155,1739141173.6864388,13.189987421035767,25.72663366509133,1739141173.686442,13.189987421035767,34.77720411545491,1739141173.6864433,13.189987421035767,-0.06920178326371665,1739141173.686445,13.189987421035767,0.03229918949156391,1739141173.6864464,13.189987421035767,0.02552492793557568,1739141173.6864479,13.189987421035767,0.0025226417271699327,1739141173.686449,13.189987421035767,2.47460493411527,1739141173.686451,13.189987421035767,0.0,1739141173.6864524,13.189987421035767,0.12220786463162225,1739141173.6864538,13.189987421035767,0.0294036459638822,1739141173.686455,13.189987421035767,2.3523970694836476 +1739141173.7064607,13.20998740196228,25.966543797168576,1739141173.7064633,13.20998740196228,-0.35387797228759155,1739141173.7064662,13.20998740196228,25.72663366509133,1739141173.7064807,13.20998740196228,34.77720411545491,1739141173.7064822,13.20998740196228,-0.06920178326371665,1739141173.706484,13.20998740196228,0.03229918949156391,1739141173.7064855,13.20998740196228,0.02552492793557568,1739141173.706487,13.20998740196228,0.0025226417271699327,1739141173.7064884,13.20998740196228,2.47460493411527,1739141173.70649,13.20998740196228,0.0,1739141173.7064917,13.20998740196228,0.12220786463162225,1739141173.706493,13.20998740196228,0.0294036459638822,1739141173.706494,13.20998740196228,2.3523970694836476 +1739141173.7265198,13.229987382888794,25.966543797168576,1739141173.7265227,13.229987382888794,-0.35387797228759155,1739141173.7265258,13.229987382888794,25.72663366509133,1739141173.726529,13.229987382888794,34.77720411545491,1739141173.72653,13.229987382888794,-0.06920178326371665,1739141173.7265317,13.229987382888794,0.03229918949156391,1739141173.7265334,13.229987382888794,0.02552492793557568,1739141173.7265346,13.229987382888794,0.0025226417271699327,1739141173.7265363,13.229987382888794,2.47460493411527,1739141173.7265377,13.229987382888794,0.0,1739141173.7265394,13.229987382888794,0.12220786463162225,1739141173.7265408,13.229987382888794,0.0294036459638822,1739141173.726542,13.229987382888794,2.3523970694836476 +1739141173.7464662,13.249987363815308,25.966543797168576,1739141173.7464776,13.249987363815308,-0.35387797228759155,1739141173.7464814,13.249987363815308,25.72663366509133,1739141173.7464848,13.249987363815308,34.77720411545491,1739141173.7464862,13.249987363815308,-0.06920178326371665,1739141173.746488,13.249987363815308,0.03229918949156391,1739141173.7464895,13.249987363815308,0.02552492793557568,1739141173.7464912,13.249987363815308,0.0025226417271699327,1739141173.7464926,13.249987363815308,2.47460493411527,1739141173.7464943,13.249987363815308,0.0,1739141173.746496,13.249987363815308,0.12220786463162225,1739141173.7464976,13.249987363815308,0.0294036459638822,1739141173.7464988,13.249987363815308,2.3523970694836476 +1739141173.766757,13.269987344741821,26.225868955271178,1739141173.7667599,13.269987344741821,-0.34614020396431755,1739141173.766763,13.269987344741821,25.752299117975163,1739141173.766766,13.269987344741821,34.84332047329154,1739141173.7667673,13.269987344741821,-0.069,1739141173.7667692,13.269987344741821,0.03214926304671573,1739141173.7667706,13.269987344741821,0.015608078046263517,1739141173.7667723,13.269987344741821,0.0016125157136698274,1739141173.7667735,13.269987344741821,2.4844405431367456,1739141173.7667756,13.269987344741821,0.0,1739141173.7667768,13.269987344741821,0.11524315906235762,1739141173.7667785,13.269987344741821,0.030338980602032422,1739141173.7667797,13.269987344741821,2.3658808559560827 +1739141173.786429,13.289987325668335,26.225868955271178,1739141173.7864318,13.289987325668335,-0.34614020396431755,1739141173.786435,13.289987325668335,25.752299117975163,1739141173.786438,13.289987325668335,34.84332047329154,1739141173.78644,13.289987325668335,-0.069,1739141173.7864418,13.289987325668335,0.03214926304671573,1739141173.7864432,13.289987325668335,0.015608078046263517,1739141173.786445,13.289987325668335,0.0016125157136698274,1739141173.7864459,13.289987325668335,2.4844405431367456,1739141173.7864482,13.289987325668335,0.0,1739141173.7864497,13.289987325668335,0.1185596871806629,1739141173.7864509,13.289987325668335,0.030338980602032422,1739141173.7864525,13.289987325668335,2.3658808559560827 +1739141173.8063235,13.309987306594849,26.225868955271178,1739141173.806326,13.309987306594849,-0.34614020396431755,1739141173.8063288,13.309987306594849,25.752299117975163,1739141173.8063319,13.309987306594849,34.84332047329154,1739141173.8063335,13.309987306594849,-0.069,1739141173.8063352,13.309987306594849,0.03214926304671573,1739141173.8063369,13.309987306594849,0.015608078046263517,1739141173.806338,13.309987306594849,0.0016125157136698274,1739141173.8063393,13.309987306594849,2.4844405431367456,1739141173.8063412,13.309987306594849,0.0,1739141173.8063428,13.309987306594849,0.1185596871806629,1739141173.8063443,13.309987306594849,0.030338980602032422,1739141173.8063457,13.309987306594849,2.3658808559560827 +1739141173.8265984,13.329987287521362,26.225868955271178,1739141173.8266013,13.329987287521362,-0.34614020396431755,1739141173.8266044,13.329987287521362,25.752299117975163,1739141173.8266077,13.329987287521362,34.84332047329154,1739141173.826609,13.329987287521362,-0.069,1739141173.8266108,13.329987287521362,0.03214926304671573,1739141173.8266122,13.329987287521362,0.015608078046263517,1739141173.8266134,13.329987287521362,0.0016125157136698274,1739141173.8266149,13.329987287521362,2.4844405431367456,1739141173.8266165,13.329987287521362,0.0,1739141173.8266182,13.329987287521362,0.1185596871806629,1739141173.8266194,13.329987287521362,0.030338980602032422,1739141173.8266208,13.329987287521362,2.3658808559560827 +1739141173.8496308,13.349987268447876,26.225868955271178,1739141173.8496401,13.349987268447876,-0.34614020396431755,1739141173.849651,13.349987268447876,25.752299117975163,1739141173.8496614,13.349987268447876,34.84332047329154,1739141173.8496666,13.349987268447876,-0.069,1739141173.8496745,13.349987268447876,0.03214926304671573,1739141173.84968,13.349987268447876,0.015608078046263517,1739141173.8496852,13.349987268447876,0.0016125157136698274,1739141173.84969,13.349987268447876,2.4844405431367456,1739141173.849696,13.349987268447876,0.0,1739141173.8497012,13.349987268447876,0.1185596871806629,1739141173.8497062,13.349987268447876,0.030338980602032422,1739141173.849711,13.349987268447876,2.3658808559560827 +1739141173.8888085,13.389987230300903,26.486636290438295,1739141173.8888123,13.389987230300903,-0.338115281181917,1739141173.8888166,13.389987230300903,25.778107059233925,1739141173.888821,13.389987230300903,34.907865511126424,1739141173.888823,13.389987230300903,-0.06881567244436788,1739141173.8888257,13.389987230300903,0.03196776380319057,1739141173.8888276,13.389987230300903,0.005842674004656462,1739141173.8888297,13.389987230300903,0.0006320886525059339,1739141173.8888319,13.389987230300903,2.4941641480476764,1739141173.888834,13.389987230300903,0.0,1739141173.8888364,13.389987230300903,0.11247175726909153,1739141173.8888383,13.389987230300903,0.03127431524018265,1739141173.8888404,13.389987230300903,2.3787933750867944 +1739141173.907228,13.409987211227417,26.486636290438295,1739141173.9072306,13.409987211227417,-0.338115281181917,1739141173.9072337,13.409987211227417,25.778107059233925,1739141173.9072366,13.409987211227417,34.907865511126424,1739141173.9072382,13.409987211227417,-0.06881567244436788,1739141173.90724,13.409987211227417,0.03196776380319057,1739141173.907241,13.409987211227417,0.005842674004656462,1739141173.9072428,13.409987211227417,0.0006320886525059339,1739141173.9072437,13.409987211227417,2.4941641480476764,1739141173.9072454,13.409987211227417,0.0,1739141173.9072468,13.409987211227417,0.11537077296088194,1739141173.907248,13.409987211227417,0.03127431524018265,1739141173.9072495,13.409987211227417,2.3787933750867944 +1739141173.9285893,13.42998719215393,26.486636290438295,1739141173.9285924,13.42998719215393,-0.338115281181917,1739141173.9285958,13.42998719215393,25.778107059233925,1739141173.9285986,13.42998719215393,34.907865511126424,1739141173.9285998,13.42998719215393,-0.06881567244436788,1739141173.9286015,13.42998719215393,0.03196776380319057,1739141173.928603,13.42998719215393,0.005842674004656462,1739141173.9286044,13.42998719215393,0.0006320886525059339,1739141173.9286058,13.42998719215393,2.4941641480476764,1739141173.9286072,13.42998719215393,0.0,1739141173.9286087,13.42998719215393,0.11537077296088194,1739141173.92861,13.42998719215393,0.03127431524018265,1739141173.9286113,13.42998719215393,2.3787933750867944 +1739141173.9482245,13.449987173080444,26.486636290438295,1739141173.948227,13.449987173080444,-0.338115281181917,1739141173.9482293,13.449987173080444,25.778107059233925,1739141173.948232,13.449987173080444,34.907865511126424,1739141173.9482331,13.449987173080444,-0.06881567244436788,1739141173.9482348,13.449987173080444,0.03196776380319057,1739141173.948236,13.449987173080444,0.005842674004656462,1739141173.948237,13.449987173080444,0.0006320886525059339,1739141173.9482384,13.449987173080444,2.4941641480476764,1739141173.9482398,13.449987173080444,0.0,1739141173.9482412,13.449987173080444,0.11537077296088194,1739141173.9482422,13.449987173080444,0.03127431524018265,1739141173.9482434,13.449987173080444,2.3787933750867944 +1739141173.968471,13.469987154006958,26.486636290438295,1739141173.9684753,13.469987154006958,-0.338115281181917,1739141173.9684808,13.469987154006958,25.778107059233925,1739141173.968487,13.469987154006958,34.907865511126424,1739141173.96849,13.469987154006958,-0.06881567244436788,1739141173.9684944,13.469987154006958,0.03196776380319057,1739141173.9684982,13.469987154006958,0.005842674004656462,1739141173.968502,13.469987154006958,0.0006320886525059339,1739141173.9685056,13.469987154006958,2.4941641480476764,1739141173.9685097,13.469987154006958,0.0,1739141173.9685135,13.469987154006958,0.11537077296088194,1739141173.9685173,13.469987154006958,0.03127431524018265,1739141173.9685209,13.469987154006958,2.3787933750867944 +1739141173.9876971,13.489987134933472,26.74880147072861,1739141173.9877,13.489987134933472,-0.329801892813923,1739141173.9877028,13.489987134933472,25.938965817772687,1739141173.9877057,13.489987134933472,35.10649408277057,1739141173.9877071,13.489987134933472,-0.068,1739141173.9877086,13.489987134933472,0.031314422013879836,1739141173.98771,13.489987134933472,-0.00748570822617911,1739141173.9877112,13.489987134933472,-0.0008222339039421682,1739141173.9877126,13.489987134933472,2.492525487761909,1739141173.9877138,13.489987134933472,0.0,1739141173.9877162,13.489987134933472,0.08820577590466444,1739141173.9877172,13.489987134933472,0.03220964987833287,1739141173.9877186,13.489987134933472,2.3913839925113747 +1739141174.0137155,13.509987115859985,26.74880147072861,1739141174.0137243,13.509987115859985,-0.329801892813923,1739141174.013734,13.509987115859985,25.938965817772687,1739141174.013744,13.509987115859985,35.10649408277057,1739141174.0137494,13.509987115859985,-0.068,1739141174.0137553,13.509987115859985,0.031314422013879836,1739141174.0137606,13.509987115859985,-0.00748570822617911,1739141174.013765,13.509987115859985,-0.0008222339039421682,1739141174.0137694,13.509987115859985,2.492525487761909,1739141174.013775,13.509987115859985,0.0,1739141174.0137806,13.509987115859985,0.10114149525053451,1739141174.013785,13.509987115859985,0.03220964987833287,1739141174.0137894,13.509987115859985,2.3913839925113747 +1739141174.0367754,13.529987096786499,26.74880147072861,1739141174.0367835,13.529987096786499,-0.329801892813923,1739141174.0367916,13.529987096786499,25.938965817772687,1739141174.0367987,13.529987096786499,35.10649408277057,1739141174.0368025,13.529987096786499,-0.068,1739141174.0368068,13.529987096786499,0.031314422013879836,1739141174.0368106,13.529987096786499,-0.00748570822617911,1739141174.036814,13.529987096786499,-0.0008222339039421682,1739141174.036817,13.529987096786499,2.492525487761909,1739141174.0368218,13.529987096786499,0.0,1739141174.0368257,13.529987096786499,0.10114149525053451,1739141174.036829,13.529987096786499,0.03220964987833287,1739141174.0368323,13.529987096786499,2.3913839925113747 +1739141174.053755,13.549987077713013,26.74880147072861,1739141174.0537593,13.549987077713013,-0.329801892813923,1739141174.0537643,13.549987077713013,25.938965817772687,1739141174.0537708,13.549987077713013,35.10649408277057,1739141174.053774,13.549987077713013,-0.068,1739141174.0537784,13.549987077713013,0.031314422013879836,1739141174.0537825,13.549987077713013,-0.00748570822617911,1739141174.0537863,13.549987077713013,-0.0008222339039421682,1739141174.05379,13.549987077713013,2.492525487761909,1739141174.0537949,13.549987077713013,0.0,1739141174.053799,13.549987077713013,0.10114149525053451,1739141174.0538027,13.549987077713013,0.03220964987833287,1739141174.0538068,13.549987077713013,2.3913839925113747 +1739141174.071535,13.569987058639526,26.74880147072861,1739141174.071538,13.569987058639526,-0.329801892813923,1739141174.0715408,13.569987058639526,25.938965817772687,1739141174.071543,13.569987058639526,35.10649408277057,1739141174.0715444,13.569987058639526,-0.068,1739141174.0715463,13.569987058639526,0.031314422013879836,1739141174.0715477,13.569987058639526,-0.00748570822617911,1739141174.071549,13.569987058639526,-0.0008222339039421682,1739141174.0715501,13.569987058639526,2.492525487761909,1739141174.0715518,13.569987058639526,0.0,1739141174.0715532,13.569987058639526,0.10114149525053451,1739141174.0715547,13.569987058639526,0.03220964987833287,1739141174.0715559,13.569987058639526,2.3913839925113747 +1739141174.091205,13.58998703956604,26.74880147072861,1739141174.0912077,13.58998703956604,-0.329801892813923,1739141174.0912106,13.58998703956604,25.938965817772687,1739141174.0912132,13.58998703956604,35.10649408277057,1739141174.0912147,13.58998703956604,-0.068,1739141174.0912163,13.58998703956604,0.031314422013879836,1739141174.0912178,13.58998703956604,-0.00748570822617911,1739141174.091219,13.58998703956604,-0.0008222339039421682,1739141174.0912201,13.58998703956604,2.492525487761909,1739141174.0912218,13.58998703956604,0.0,1739141174.0912232,13.58998703956604,0.10114149525053451,1739141174.0912247,13.58998703956604,0.03220964987833287,1739141174.0912259,13.58998703956604,2.3913839925113747 +1739141174.1109855,13.609987020492554,27.012243520644866,1739141174.1109877,13.609987020492554,-0.32120136750626394,1739141174.1109905,13.609987020492554,26.292243776067735,1739141174.1109934,13.609987020492554,35.49221232790977,1739141174.1109946,13.609987020492554,-0.06667277265186225,1739141174.1109965,13.609987020492554,0.03000626601023687,1739141174.1109977,13.609987020492554,-0.02662817811271843,1739141174.110999,13.609987020492554,-0.0028413383092613246,1739141174.111,13.609987020492554,2.47351313170646,1739141174.1110015,13.609987020492554,0.0,1739141174.1110032,13.609987020492554,0.044198434002915954,1739141174.1110044,13.609987020492554,0.033144984516483095,1739141174.1110055,13.609987020492554,2.402198940706792 +1739141174.1311712,13.629987001419067,27.012243520644866,1739141174.1311746,13.629987001419067,-0.32120136750626394,1739141174.1311774,13.629987001419067,26.292243776067735,1739141174.1311803,13.629987001419067,35.49221232790977,1739141174.1311815,13.629987001419067,-0.06667277265186225,1739141174.1311831,13.629987001419067,0.03000626601023687,1739141174.1311843,13.629987001419067,-0.02662817811271843,1739141174.131186,13.629987001419067,-0.0028413383092613246,1739141174.1311872,13.629987001419067,2.47351313170646,1739141174.1311886,13.629987001419067,0.0,1739141174.1311903,13.629987001419067,0.07131419099966818,1739141174.1311915,13.629987001419067,0.033144984516483095,1739141174.1311934,13.629987001419067,2.402198940706792 +1739141174.1508644,13.649986982345581,27.012243520644866,1739141174.150867,13.649986982345581,-0.32120136750626394,1739141174.15087,13.649986982345581,26.292243776067735,1739141174.150873,13.649986982345581,35.49221232790977,1739141174.1508741,13.649986982345581,-0.06667277265186225,1739141174.1508758,13.649986982345581,0.03000626601023687,1739141174.1508772,13.649986982345581,-0.02662817811271843,1739141174.1508784,13.649986982345581,-0.0028413383092613246,1739141174.15088,13.649986982345581,2.47351313170646,1739141174.1508815,13.649986982345581,0.0,1739141174.1508827,13.649986982345581,0.07131419099966818,1739141174.1508842,13.649986982345581,0.033144984516483095,1739141174.1508853,13.649986982345581,2.402198940706792 +1739141174.1711886,13.669986963272095,27.012243520644866,1739141174.1711907,13.669986963272095,-0.32120136750626394,1739141174.1711936,13.669986963272095,26.292243776067735,1739141174.1711962,13.669986963272095,35.49221232790977,1739141174.1711974,13.669986963272095,-0.06667277265186225,1739141174.1711993,13.669986963272095,0.03000626601023687,1739141174.1712005,13.669986963272095,-0.02662817811271843,1739141174.1712017,13.669986963272095,-0.0028413383092613246,1739141174.1712031,13.669986963272095,2.47351313170646,1739141174.1712043,13.669986963272095,0.0,1739141174.171206,13.669986963272095,0.07131419099966818,1739141174.1712072,13.669986963272095,0.033144984516483095,1739141174.1712084,13.669986963272095,2.402198940706792 +1739141174.1908507,13.689986944198608,27.012243520644866,1739141174.1908534,13.689986944198608,-0.32120136750626394,1739141174.190856,13.689986944198608,26.292243776067735,1739141174.1908588,13.689986944198608,35.49221232790977,1739141174.19086,13.689986944198608,-0.06667277265186225,1739141174.190862,13.689986944198608,0.03000626601023687,1739141174.1908631,13.689986944198608,-0.02662817811271843,1739141174.1908643,13.689986944198608,-0.0028413383092613246,1739141174.1908658,13.689986944198608,2.47351313170646,1739141174.1908672,13.689986944198608,0.0,1739141174.1908684,13.689986944198608,0.07131419099966818,1739141174.1908698,13.689986944198608,0.033144984516483095,1739141174.1908712,13.689986944198608,2.402198940706792 +1739141174.2109559,13.709986925125122,27.276710092404013,1739141174.210959,13.709986925125122,-0.3123197891145679,1739141174.2109618,13.709986925125122,26.337562818859166,1739141174.2109647,13.709986925125122,35.56018911304757,1739141174.210966,13.709986925125122,-0.06614582082908861,1739141174.2109675,13.709986925125122,0.029709924114860863,1739141174.210969,13.709986925125122,-0.036217943622689826,1739141174.2109704,13.709986925125122,-0.004050193682778749,1739141174.2109716,13.709986925125122,2.464043141947057,1739141174.2109733,13.709986925125122,0.0,1739141174.2109747,13.709986925125122,0.03881524185000961,1739141174.210976,13.709986925125122,0.03408031915463332,1739141174.2109773,13.709986925125122,2.409752202294994 +1739141174.230781,13.729986906051636,27.276710092404013,1739141174.2307837,13.729986906051636,-0.3123197891145679,1739141174.2307866,13.729986906051636,26.337562818859166,1739141174.2307894,13.729986906051636,35.56018911304757,1739141174.2307906,13.729986906051636,-0.06614582082908861,1739141174.2307923,13.729986906051636,0.029709924114860863,1739141174.2307937,13.729986906051636,-0.036217943622689826,1739141174.230795,13.729986906051636,-0.004050193682778749,1739141174.2307963,13.729986906051636,2.464043141947057,1739141174.230798,13.729986906051636,0.0,1739141174.2307994,13.729986906051636,0.054290939652062775,1739141174.2308006,13.729986906051636,0.03408031915463332,1739141174.2308018,13.729986906051636,2.409752202294994 +1739141174.2774458,13.739986896514893,27.276710092404013,1739141174.2774513,13.739986896514893,-0.3123197891145679,1739141174.277458,13.739986896514893,26.337562818859166,1739141174.2774646,13.739986896514893,35.56018911304757,1739141174.2774677,13.739986896514893,-0.06614582082908861,1739141174.2774718,13.739986896514893,0.029709924114860863,1739141174.2774754,13.739986896514893,-0.036217943622689826,1739141174.2774792,13.739986896514893,-0.004050193682778749,1739141174.2775016,13.739986896514893,2.464043141947057,1739141174.2775056,13.739986896514893,0.0,1739141174.2775097,13.739986896514893,0.054290939652062775,1739141174.277513,13.739986896514893,0.03408031915463332,1739141174.277517,13.739986896514893,2.409752202294994 +1739141174.2825718,13.759986877441406,27.276710092404013,1739141174.2825747,13.759986877441406,-0.3123197891145679,1739141174.2825778,13.759986877441406,26.337562818859166,1739141174.2825804,13.759986877441406,35.56018911304757,1739141174.282582,13.759986877441406,-0.06614582082908861,1739141174.2825835,13.759986877441406,0.029709924114860863,1739141174.2825851,13.759986877441406,-0.036217943622689826,1739141174.2825863,13.759986877441406,-0.004050193682778749,1739141174.2825878,13.759986877441406,2.464043141947057,1739141174.2825892,13.759986877441406,0.0,1739141174.2825906,13.759986877441406,0.054290939652062775,1739141174.282592,13.759986877441406,0.03408031915463332,1739141174.2825933,13.759986877441406,2.409752202294994 +1739141174.3016086,13.77998685836792,27.276710092404013,1739141174.3016114,13.77998685836792,-0.3123197891145679,1739141174.3016145,13.77998685836792,26.337562818859166,1739141174.3016179,13.77998685836792,35.56018911304757,1739141174.3016195,13.77998685836792,-0.06614582082908861,1739141174.3016212,13.77998685836792,0.029709924114860863,1739141174.3016226,13.77998685836792,-0.036217943622689826,1739141174.3016238,13.77998685836792,-0.004050193682778749,1739141174.3016253,13.77998685836792,2.464043141947057,1739141174.3016274,13.77998685836792,0.0,1739141174.3016286,13.77998685836792,0.054290939652062775,1739141174.30163,13.77998685836792,0.03408031915463332,1739141174.3016312,13.77998685836792,2.409752202294994 +1739141174.322112,13.799986839294434,27.276710092404013,1739141174.3221161,13.799986839294434,-0.3123197891145679,1739141174.322121,13.799986839294434,26.337562818859166,1739141174.3221264,13.799986839294434,35.56018911304757,1739141174.3221292,13.799986839294434,-0.06614582082908861,1739141174.322133,13.799986839294434,0.029709924114860863,1739141174.3221364,13.799986839294434,-0.036217943622689826,1739141174.32214,13.799986839294434,-0.004050193682778749,1739141174.3221433,13.799986839294434,2.464043141947057,1739141174.3221476,13.799986839294434,0.0,1739141174.3221512,13.799986839294434,0.054290939652062775,1739141174.3221529,13.799986839294434,0.03408031915463332,1739141174.3221555,13.799986839294434,2.409752202294994 +1739141174.3417428,13.819986820220947,27.541893318829885,1739141174.3417454,13.819986820220947,-0.30316583489440596,1739141174.3417482,13.819986820220947,26.680769828518724,1739141174.3417509,13.819986820220947,35.920299718523864,1739141174.341752,13.819986820220947,-0.06486459464821119,1739141174.3417535,13.819986820220947,0.028434645077821393,1739141174.3417554,13.819986820220947,-0.05516026536640743,1739141174.3417563,13.819986820220947,-0.006029939440248382,1739141174.3417575,13.819986820220947,2.44544381462343,1739141174.3417592,13.819986820220947,0.0,1739141174.3417604,13.819986820220947,0.008023245936013054,1739141174.3417618,13.819986820220947,0.03501565379278354,1739141174.341763,13.819986820220947,2.4153883225784667 +1739141174.3608937,13.839986801147461,27.541893318829885,1739141174.3608973,13.839986801147461,-0.30316583489440596,1739141174.3609002,13.839986801147461,26.680769828518724,1739141174.3609033,13.839986801147461,35.920299718523864,1739141174.3609042,13.839986801147461,-0.06486459464821119,1739141174.360906,13.839986801147461,0.028434645077821393,1739141174.3609073,13.839986801147461,-0.05516026536640743,1739141174.3609085,13.839986801147461,-0.006029939440248382,1739141174.36091,13.839986801147461,2.44544381462343,1739141174.3609135,13.839986801147461,0.0,1739141174.3609176,13.839986801147461,0.030055492044963383,1739141174.3609214,13.839986801147461,0.03501565379278354,1739141174.3609254,13.839986801147461,2.4153883225784667 +1739141174.3860085,13.859986782073975,27.541893318829885,1739141174.3860207,13.859986782073975,-0.30316583489440596,1739141174.3860312,13.859986782073975,26.680769828518724,1739141174.3860402,13.859986782073975,35.920299718523864,1739141174.3860452,13.859986782073975,-0.06486459464821119,1739141174.3860528,13.859986782073975,0.028434645077821393,1739141174.3860729,13.859986782073975,-0.05516026536640743,1739141174.3860774,13.859986782073975,-0.006029939440248382,1739141174.3860824,13.859986782073975,2.44544381462343,1739141174.3860881,13.859986782073975,0.0,1739141174.3860922,13.859986782073975,0.030055492044963383,1739141174.3860962,13.859986782073975,0.03501565379278354,1739141174.3860998,13.859986782073975,2.4153883225784667 +1739141174.405209,13.869986772537231,27.541893318829885,1739141174.4052215,13.869986772537231,-0.30316583489440596,1739141174.4052334,13.869986772537231,26.680769828518724,1739141174.4052474,13.869986772537231,35.920299718523864,1739141174.4052558,13.869986772537231,-0.06486459464821119,1739141174.4052653,13.869986772537231,0.028434645077821393,1739141174.4052742,13.869986772537231,-0.05516026536640743,1739141174.405282,13.869986772537231,-0.006029939440248382,1739141174.40529,13.869986772537231,2.44544381462343,1739141174.4052982,13.869986772537231,0.0,1739141174.4053066,13.869986772537231,0.030055492044963383,1739141174.4053142,13.869986772537231,0.03501565379278354,1739141174.4053228,13.869986772537231,2.4153883225784667 +1739141174.4254026,13.889986753463745,27.541893318829885,1739141174.42541,13.889986753463745,-0.30316583489440596,1739141174.42542,13.889986753463745,26.680769828518724,1739141174.4254305,13.889986753463745,35.920299718523864,1739141174.4254363,13.889986753463745,-0.06486459464821119,1739141174.425444,13.889986753463745,0.028434645077821393,1739141174.4254506,13.889986753463745,-0.05516026536640743,1739141174.4254572,13.889986753463745,-0.006029939440248382,1739141174.4254634,13.889986753463745,2.44544381462343,1739141174.425471,13.889986753463745,0.0,1739141174.4254777,13.889986753463745,0.030055492044963383,1739141174.4254847,13.889986753463745,0.03501565379278354,1739141174.425491,13.889986753463745,2.4153883225784667 +1739141174.4414697,13.919986724853516,27.541893318829885,1739141174.441473,13.919986724853516,-0.30316583489440596,1739141174.4414768,13.919986724853516,26.680769828518724,1739141174.4414809,13.919986724853516,35.920299718523864,1739141174.4414828,13.919986724853516,-0.06486459464821119,1739141174.4414847,13.919986724853516,0.028434645077821393,1739141174.441487,13.919986724853516,-0.05516026536640743,1739141174.4414892,13.919986724853516,-0.006029939440248382,1739141174.4414907,13.919986724853516,2.44544381462343,1739141174.441493,13.919986724853516,0.0,1739141174.441495,13.919986724853516,0.030055492044963383,1739141174.4414966,13.919986724853516,0.03501565379278354,1739141174.4414983,13.919986724853516,2.4153883225784667 +1739141174.4621496,13.93998670578003,27.807542234529354,1739141174.4621525,13.93998670578003,-0.29374705400888157,1739141174.4621556,13.93998670578003,27.550875916650014,1739141174.462158,13.93998670578003,36.79895917324988,1739141174.4621594,13.93998670578003,-0.06276896139365766,1739141174.462161,13.93998670578003,0.02568308265270374,1739141174.4621627,13.93998670578003,-0.09235185660597706,1739141174.462164,13.93998670578003,-0.008767238879996999,1739141174.4621649,13.93998670578003,2.4093331048560036,1739141174.4621668,13.93998670578003,0.0,1739141174.462168,13.93998670578003,-0.044330478097630924,1739141174.4621694,13.93998670578003,0.035950988430933764,1739141174.4621706,13.93998670578003,2.4182416747147513 +1739141174.4806745,13.959986686706543,27.807542234529354,1739141174.4806767,13.959986686706543,-0.29374705400888157,1739141174.4806793,13.959986686706543,27.550875916650014,1739141174.4806814,13.959986686706543,36.79895917324988,1739141174.4806826,13.959986686706543,-0.06276896139365766,1739141174.480684,13.959986686706543,0.02568308265270374,1739141174.480685,13.959986686706543,-0.09235185660597706,1739141174.4806864,13.959986686706543,-0.008767238879996999,1739141174.4806874,13.959986686706543,2.4093331048560036,1739141174.4806888,13.959986686706543,0.0,1739141174.48069,13.959986686706543,-0.008908569858747661,1739141174.4806912,13.959986686706543,0.035950988430933764,1739141174.4806921,13.959986686706543,2.4182416747147513 +1739141174.5013385,13.979986667633057,27.807542234529354,1739141174.5013406,13.979986667633057,-0.29374705400888157,1739141174.5013433,13.979986667633057,27.550875916650014,1739141174.5013459,13.979986667633057,36.79895917324988,1739141174.5013473,13.979986667633057,-0.06276896139365766,1739141174.501349,13.979986667633057,0.02568308265270374,1739141174.5013502,13.979986667633057,-0.09235185660597706,1739141174.5013514,13.979986667633057,-0.008767238879996999,1739141174.5013525,13.979986667633057,2.4093331048560036,1739141174.501354,13.979986667633057,0.0,1739141174.5013552,13.979986667633057,-0.008908569858747661,1739141174.5013566,13.979986667633057,0.035950988430933764,1739141174.5013576,13.979986667633057,2.4182416747147513 +1739141174.5261078,13.989986658096313,27.807542234529354,1739141174.5261168,13.989986658096313,-0.29374705400888157,1739141174.5261269,13.989986658096313,27.550875916650014,1739141174.5261366,13.989986658096313,36.79895917324988,1739141174.5261412,13.989986658096313,-0.06276896139365766,1739141174.5261471,13.989986658096313,0.02568308265270374,1739141174.5261517,13.989986658096313,-0.09235185660597706,1739141174.526156,13.989986658096313,-0.008767238879996999,1739141174.5261605,13.989986658096313,2.4093331048560036,1739141174.526166,13.989986658096313,0.0,1739141174.5261712,13.989986658096313,-0.008908569858747661,1739141174.5261757,13.989986658096313,0.035950988430933764,1739141174.5261803,13.989986658096313,2.4182416747147513 +1739141174.5486515,14.009986639022827,27.807542234529354,1739141174.548665,14.009986639022827,-0.29374705400888157,1739141174.548682,14.009986639022827,27.550875916650014,1739141174.5487018,14.009986639022827,36.79895917324988,1739141174.5487132,14.009986639022827,-0.06276896139365766,1739141174.5487313,14.009986639022827,0.02568308265270374,1739141174.5487444,14.009986639022827,-0.09235185660597706,1739141174.5487568,14.009986639022827,-0.008767238879996999,1739141174.548769,14.009986639022827,2.4093331048560036,1739141174.548782,14.009986639022827,0.0,1739141174.548795,14.009986639022827,-0.008908569858747661,1739141174.5488071,14.009986639022827,0.035950988430933764,1739141174.5488195,14.009986639022827,2.4182416747147513 +1739141174.574073,14.039986610412598,28.073302547565916,1739141174.574079,14.039986610412598,-0.2840754662043494,1739141174.5740876,14.039986610412598,27.557254164162888,1739141174.5740972,14.039986610412598,36.80145346634531,1739141174.5741022,14.039986610412598,-0.0627503472660798,1739141174.5741084,14.039986610412598,0.02535218527851999,1739141174.5741138,14.039986610412598,-0.10070182367765458,1739141174.574119,14.039986610412598,-0.01014549498237799,1739141174.5741248,14.039986610412598,2.401299387742926,1739141174.5741308,14.039986610412598,0.0,1739141174.574136,14.039986610412598,-0.0217741088500785,1739141174.5741415,14.039986610412598,0.03688632306908399,1739141174.5741467,14.039986610412598,2.416947046393846 +1739141174.5912142,14.059986591339111,28.073302547565916,1739141174.591218,14.059986591339111,-0.2840754662043494,1739141174.591222,14.059986591339111,27.557254164162888,1739141174.591226,14.059986591339111,36.80145346634531,1739141174.591228,14.059986591339111,-0.0627503472660798,1739141174.5912306,14.059986591339111,0.02535218527851999,1739141174.5912328,14.059986591339111,-0.10070182367765458,1739141174.5912342,14.059986591339111,-0.01014549498237799,1739141174.591236,14.059986591339111,2.401299387742926,1739141174.5912385,14.059986591339111,0.0,1739141174.5912402,14.059986591339111,-0.015647658650919993,1739141174.5912423,14.059986591339111,0.03688632306908399,1739141174.5912437,14.059986591339111,2.416947046393846 +1739141174.6176524,14.079986572265625,28.073302547565916,1739141174.6176667,14.079986572265625,-0.2840754662043494,1739141174.6176827,14.079986572265625,27.557254164162888,1739141174.617699,14.079986572265625,36.80145346634531,1739141174.6177075,14.079986572265625,-0.0627503472660798,1739141174.6177185,14.079986572265625,0.02535218527851999,1739141174.617728,14.079986572265625,-0.10070182367765458,1739141174.6177373,14.079986572265625,-0.01014549498237799,1739141174.617746,14.079986572265625,2.401299387742926,1739141174.6177564,14.079986572265625,0.0,1739141174.617766,14.079986572265625,-0.015647658650919993,1739141174.617775,14.079986572265625,0.03688632306908399,1739141174.6177838,14.079986572265625,2.416947046393846 +1739141174.6354568,14.099986553192139,28.073302547565916,1739141174.635466,14.099986553192139,-0.2840754662043494,1739141174.635476,14.099986553192139,27.557254164162888,1739141174.6354861,14.099986553192139,36.80145346634531,1739141174.6354916,14.099986553192139,-0.0627503472660798,1739141174.6354973,14.099986553192139,0.02535218527851999,1739141174.6355019,14.099986553192139,-0.10070182367765458,1739141174.6355062,14.099986553192139,-0.01014549498237799,1739141174.6355104,14.099986553192139,2.401299387742926,1739141174.6355162,14.099986553192139,0.0,1739141174.6355212,14.099986553192139,-0.015647658650919993,1739141174.6355257,14.099986553192139,0.03688632306908399,1739141174.6355305,14.099986553192139,2.416947046393846 +1739141174.6546261,14.119986534118652,28.073302547565916,1739141174.6546323,14.119986534118652,-0.2840754662043494,1739141174.6546392,14.119986534118652,27.557254164162888,1739141174.6546462,14.119986534118652,36.80145346634531,1739141174.6546495,14.119986534118652,-0.0627503472660798,1739141174.6546543,14.119986534118652,0.02535218527851999,1739141174.6546576,14.119986534118652,-0.10070182367765458,1739141174.6546607,14.119986534118652,-0.01014549498237799,1739141174.6546633,14.119986534118652,2.401299387742926,1739141174.6546676,14.119986534118652,0.0,1739141174.6546712,14.119986534118652,-0.015647658650919993,1739141174.6546743,14.119986534118652,0.03688632306908399,1739141174.6546772,14.119986534118652,2.416947046393846 +1739141174.678394,14.139986515045166,28.073302547565916,1739141174.6784039,14.139986515045166,-0.2840754662043494,1739141174.6784148,14.139986515045166,27.557254164162888,1739141174.6784263,14.139986515045166,36.80145346634531,1739141174.6784327,14.139986515045166,-0.0627503472660798,1739141174.67844,14.139986515045166,0.02535218527851999,1739141174.6784465,14.139986515045166,-0.10070182367765458,1739141174.678453,14.139986515045166,-0.01014549498237799,1739141174.6784592,14.139986515045166,2.401299387742926,1739141174.678466,14.139986515045166,0.0,1739141174.6784947,14.139986515045166,-0.015647658650919993,1739141174.678506,14.139986515045166,0.03688632306908399,1739141174.6785173,14.139986515045166,2.416947046393846 +1739141174.69576,14.15998649597168,28.338884341672497,1739141174.6957664,14.15998649597168,-0.27416163205062993,1739141174.6957736,14.15998649597168,27.56362812722145,1739141174.6957803,14.15998649597168,36.802324822036624,1739141174.6957836,14.15998649597168,-0.06274384461166697,1739141174.6957874,14.15998649597168,0.0249749294065691,1739141174.6957908,14.15998649597168,-0.1087584467813894,1739141174.6957946,14.15998649597168,-0.011653522672963289,1739141174.6957977,14.15998649597168,2.3935732980176,1739141174.695802,14.15998649597168,0.0,1739141174.6958055,14.15998649597168,-0.026895827623084158,1739141174.6958084,14.15998649597168,0.03782165770723421,1739141174.6958117,14.15998649597168,2.4151128520258656 +1739141174.716215,14.179986476898193,28.338884341672497,1739141174.716221,14.179986476898193,-0.27416163205062993,1739141174.716229,14.179986476898193,27.56362812722145,1739141174.7162359,14.179986476898193,36.802324822036624,1739141174.7162392,14.179986476898193,-0.06274384461166697,1739141174.7162437,14.179986476898193,0.0249749294065691,1739141174.716247,14.179986476898193,-0.1087584467813894,1739141174.7162502,14.179986476898193,-0.011653522672963289,1739141174.7162533,14.179986476898193,2.3935732980176,1739141174.7162573,14.179986476898193,0.0,1739141174.716261,14.179986476898193,-0.021539554008265682,1739141174.7162638,14.179986476898193,0.03782165770723421,1739141174.716267,14.179986476898193,2.4151128520258656 +1739141174.735828,14.199986457824707,28.338884341672497,1739141174.7358353,14.199986457824707,-0.27416163205062993,1739141174.7358446,14.199986457824707,27.56362812722145,1739141174.735855,14.199986457824707,36.802324822036624,1739141174.7358608,14.199986457824707,-0.06274384461166697,1739141174.7358685,14.199986457824707,0.0249749294065691,1739141174.7358751,14.199986457824707,-0.1087584467813894,1739141174.7358818,14.199986457824707,-0.011653522672963289,1739141174.7358887,14.199986457824707,2.3935732980176,1739141174.7358956,14.199986457824707,0.0,1739141174.7359025,14.199986457824707,-0.021539554008265682,1739141174.7359092,14.199986457824707,0.03782165770723421,1739141174.7359157,14.199986457824707,2.4151128520258656 +1739141174.753318,14.21998643875122,28.338884341672497,1739141174.753323,14.21998643875122,-0.27416163205062993,1739141174.7533286,14.21998643875122,27.56362812722145,1739141174.7533338,14.21998643875122,36.802324822036624,1739141174.7533364,14.21998643875122,-0.06274384461166697,1739141174.7533393,14.21998643875122,0.0249749294065691,1739141174.7533422,14.21998643875122,-0.1087584467813894,1739141174.7533445,14.21998643875122,-0.011653522672963289,1739141174.753347,14.21998643875122,2.3935732980176,1739141174.7533498,14.21998643875122,0.0,1739141174.7533524,14.21998643875122,-0.021539554008265682,1739141174.753355,14.21998643875122,0.03782165770723421,1739141174.7533576,14.21998643875122,2.4151128520258656 +1739141174.7742014,14.239986419677734,28.338884341672497,1739141174.7742083,14.239986419677734,-0.27416163205062993,1739141174.7742171,14.239986419677734,27.56362812722145,1739141174.7742274,14.239986419677734,36.802324822036624,1739141174.7742336,14.239986419677734,-0.06274384461166697,1739141174.7742426,14.239986419677734,0.0249749294065691,1739141174.7742503,14.239986419677734,-0.1087584467813894,1739141174.774257,14.239986419677734,-0.011653522672963289,1739141174.7742636,14.239986419677734,2.3935732980176,1739141174.7742705,14.239986419677734,0.0,1739141174.7742774,14.239986419677734,-0.021539554008265682,1739141174.774284,14.239986419677734,0.03782165770723421,1739141174.7742903,14.239986419677734,2.4151128520258656 +1739141174.7946594,14.259986400604248,28.604237907626064,1739141174.7946641,14.259986400604248,-0.26400777364038497,1739141174.79467,14.259986400604248,28.204277302464384,1739141174.7946758,14.259986400604248,37.435934194064686,1739141174.7946782,14.259986400604248,-0.06001680085097235,1739141174.7946815,14.259986400604248,0.023093492060007513,1739141174.7946842,14.259986400604248,-0.13836651516222787,1739141174.794687,14.259986400604248,-0.013616621185014749,1739141174.7946894,14.259986400604248,2.36539286826916,1739141174.7946925,14.259986400604248,0.0,1739141174.7946951,14.259986400604248,-0.0708641196855102,1739141174.7946978,14.259986400604248,0.03875699234538443,1739141174.7947001,14.259986400604248,2.4127690878037025 +1739141174.8150055,14.279986381530762,28.604237907626064,1739141174.815011,14.279986381530762,-0.26400777364038497,1739141174.8150163,14.279986381530762,28.204277302464384,1739141174.8150215,14.279986381530762,37.435934194064686,1739141174.8150244,14.279986381530762,-0.06001680085097235,1739141174.8150275,14.279986381530762,0.023093492060007513,1739141174.81503,14.279986381530762,-0.13836651516222787,1739141174.8150322,14.279986381530762,-0.013616621185014749,1739141174.8150349,14.279986381530762,2.36539286826916,1739141174.815038,14.279986381530762,0.0,1739141174.8150408,14.279986381530762,-0.04737621953454241,1739141174.8150432,14.279986381530762,0.03875699234538443,1739141174.8150456,14.279986381530762,2.4127690878037025 +1739141174.8337035,14.299986362457275,28.604237907626064,1739141174.8337083,14.299986362457275,-0.26400777364038497,1739141174.8337138,14.299986362457275,28.204277302464384,1739141174.8337188,14.299986362457275,37.435934194064686,1739141174.8337214,14.299986362457275,-0.06001680085097235,1739141174.8337245,14.299986362457275,0.023093492060007513,1739141174.833727,14.299986362457275,-0.13836651516222787,1739141174.8337293,14.299986362457275,-0.013616621185014749,1739141174.8337317,14.299986362457275,2.36539286826916,1739141174.8337348,14.299986362457275,0.0,1739141174.8337374,14.299986362457275,-0.04737621953454241,1739141174.83374,14.299986362457275,0.03875699234538443,1739141174.8337426,14.299986362457275,2.4127690878037025 +1739141174.8536856,14.319986343383789,28.604237907626064,1739141174.8536901,14.319986343383789,-0.26400777364038497,1739141174.8536956,14.319986343383789,28.204277302464384,1739141174.853701,14.319986343383789,37.435934194064686,1739141174.8537037,14.319986343383789,-0.06001680085097235,1739141174.8537068,14.319986343383789,0.023093492060007513,1739141174.8537095,14.319986343383789,-0.13836651516222787,1739141174.8537118,14.319986343383789,-0.013616621185014749,1739141174.8537142,14.319986343383789,2.36539286826916,1739141174.8537173,14.319986343383789,0.0,1739141174.8537197,14.319986343383789,-0.04737621953454241,1739141174.8537223,14.319986343383789,0.03875699234538443,1739141174.8537247,14.319986343383789,2.4127690878037025 +1739141174.872752,14.339986324310303,28.604237907626064,1739141174.872755,14.339986324310303,-0.26400777364038497,1739141174.8727586,14.339986324310303,28.204277302464384,1739141174.8727622,14.339986324310303,37.435934194064686,1739141174.8727639,14.339986324310303,-0.06001680085097235,1739141174.872766,14.339986324310303,0.023093492060007513,1739141174.872768,14.339986324310303,-0.13836651516222787,1739141174.8727696,14.339986324310303,-0.013616621185014749,1739141174.872771,14.339986324310303,2.36539286826916,1739141174.8727732,14.339986324310303,0.0,1739141174.8727748,14.339986324310303,-0.04737621953454241,1739141174.8727767,14.339986324310303,0.03875699234538443,1739141174.8727784,14.339986324310303,2.4127690878037025 +1739141174.8922212,14.359986305236816,28.604237907626064,1739141174.8922238,14.359986305236816,-0.26400777364038497,1739141174.8922262,14.359986305236816,28.204277302464384,1739141174.8922293,14.359986305236816,37.435934194064686,1739141174.8922307,14.359986305236816,-0.06001680085097235,1739141174.8922322,14.359986305236816,0.023093492060007513,1739141174.8922336,14.359986305236816,-0.13836651516222787,1739141174.892235,14.359986305236816,-0.013616621185014749,1739141174.892236,14.359986305236816,2.36539286826916,1739141174.8922377,14.359986305236816,0.0,1739141174.892239,14.359986305236816,-0.04737621953454241,1739141174.89224,14.359986305236816,0.03875699234538443,1739141174.8922415,14.359986305236816,2.4127690878037025 +1739141174.9123154,14.37998628616333,28.869165372851498,1739141174.912318,14.37998628616333,-0.25362207924080504,1739141174.9123209,14.37998628616333,28.243232025546924,1739141174.9123235,14.37998628616333,37.4587080950579,1739141174.912325,14.37998628616333,-0.06,1739141174.9123263,14.37998628616333,0.022537788194782225,1739141174.9123278,14.37998628616333,-0.1473798462992244,1739141174.912329,14.37998628616333,-0.015333271653532522,1739141174.9123302,14.37998628616333,2.3568801953218084,1739141174.9123318,14.37998628616333,0.0,1739141174.9123333,14.37998628616333,-0.05333082408012917,1739141174.9123347,14.37998628616333,0.039692326983534656,1739141174.9123359,14.37998628616333,2.407375492011379 +1739141174.932782,14.399986267089844,28.869165372851498,1739141174.9327843,14.399986267089844,-0.25362207924080504,1739141174.9327874,14.399986267089844,28.243232025546924,1739141174.93279,14.399986267089844,37.4587080950579,1739141174.9327915,14.399986267089844,-0.06,1739141174.9327931,14.399986267089844,0.022537788194782225,1739141174.9327943,14.399986267089844,-0.1473798462992244,1739141174.932796,14.399986267089844,-0.015333271653532522,1739141174.9327974,14.399986267089844,2.3568801953218084,1739141174.9327989,14.399986267089844,0.0,1739141174.9328005,14.399986267089844,-0.050495296689570424,1739141174.9328017,14.399986267089844,0.039692326983534656,1739141174.9328032,14.399986267089844,2.407375492011379 +1739141174.9520915,14.419986248016357,28.869165372851498,1739141174.9520946,14.419986248016357,-0.25362207924080504,1739141174.9520972,14.419986248016357,28.243232025546924,1739141174.9521003,14.419986248016357,37.4587080950579,1739141174.9521017,14.419986248016357,-0.06,1739141174.9521034,14.419986248016357,0.022537788194782225,1739141174.952105,14.419986248016357,-0.1473798462992244,1739141174.9521062,14.419986248016357,-0.015333271653532522,1739141174.9521074,14.419986248016357,2.3568801953218084,1739141174.9521096,14.419986248016357,0.0,1739141174.9521108,14.419986248016357,-0.050495296689570424,1739141174.9521124,14.419986248016357,0.039692326983534656,1739141174.9521136,14.419986248016357,2.407375492011379 +1739141174.9720182,14.439986228942871,28.869165372851498,1739141174.9720204,14.439986228942871,-0.25362207924080504,1739141174.9720235,14.439986228942871,28.243232025546924,1739141174.972026,14.439986228942871,37.4587080950579,1739141174.9720275,14.439986228942871,-0.06,1739141174.9720292,14.439986228942871,0.022537788194782225,1739141174.9720304,14.439986228942871,-0.1473798462992244,1739141174.9720323,14.439986228942871,-0.015333271653532522,1739141174.9720333,14.439986228942871,2.3568801953218084,1739141174.9720352,14.439986228942871,0.0,1739141174.9720364,14.439986228942871,-0.050495296689570424,1739141174.9720376,14.439986228942871,0.039692326983534656,1739141174.972039,14.439986228942871,2.407375492011379 +1739141174.991998,14.459986209869385,28.869165372851498,1739141174.9920003,14.459986209869385,-0.25362207924080504,1739141174.9920034,14.459986209869385,28.243232025546924,1739141174.9920058,14.459986209869385,37.4587080950579,1739141174.9920073,14.459986209869385,-0.06,1739141174.992009,14.459986209869385,0.022537788194782225,1739141174.9920104,14.459986209869385,-0.1473798462992244,1739141174.9920115,14.459986209869385,-0.015333271653532522,1739141174.9920127,14.459986209869385,2.3568801953218084,1739141174.9920144,14.459986209869385,0.0,1739141174.9920156,14.459986209869385,-0.050495296689570424,1739141174.9920168,14.459986209869385,0.039692326983534656,1739141174.9920182,14.459986209869385,2.407375492011379 +1739141175.0156817,14.479986190795898,29.13348377077363,1739141175.0156913,14.479986190795898,-0.24301264689890179,1739141175.015702,14.479986190795898,28.601769587676237,1739141175.015712,14.479986190795898,37.80051517338015,1739141175.0157168,14.479986190795898,-0.059,1739141175.015723,14.479986190795898,0.021228145685236687,1739141175.0157278,14.479986190795898,-0.16816355661652957,1739141175.0157325,14.479986190795898,-0.017185093160707814,1739141175.0157368,14.479986190795898,2.3373675307257322,1739141175.0157428,14.479986190795898,0.0,1739141175.0157478,14.479986190795898,-0.07710246230975003,1739141175.0157526,14.479986190795898,0.04062766162168488,1739141175.0157568,14.479986190795898,2.401799907839469 +1739141175.0374284,14.499986171722412,29.13348377077363,1739141175.0374377,14.499986171722412,-0.24301264689890179,1739141175.0374482,14.499986171722412,28.601769587676237,1739141175.037458,14.499986171722412,37.80051517338015,1739141175.037463,14.499986171722412,-0.059,1739141175.0374691,14.499986171722412,0.021228145685236687,1739141175.0374742,14.499986171722412,-0.16816355661652957,1739141175.0374784,14.499986171722412,-0.017185093160707814,1739141175.0374827,14.499986171722412,2.3373675307257322,1739141175.0374885,14.499986171722412,0.0,1739141175.0374935,14.499986171722412,-0.06443237711373673,1739141175.037498,14.499986171722412,0.04062766162168488,1739141175.0375028,14.499986171722412,2.401799907839469 +1739141175.068014,14.519986152648926,29.13348377077363,1739141175.068021,14.519986152648926,-0.24301264689890179,1739141175.0680287,14.519986152648926,28.601769587676237,1739141175.0680356,14.519986152648926,37.80051517338015,1739141175.068039,14.519986152648926,-0.059,1739141175.068043,14.519986152648926,0.021228145685236687,1739141175.0680466,14.519986152648926,-0.16816355661652957,1739141175.06805,14.519986152648926,-0.017185093160707814,1739141175.0680532,14.519986152648926,2.3373675307257322,1739141175.0680573,14.519986152648926,0.0,1739141175.068061,14.519986152648926,-0.06443237711373673,1739141175.0680642,14.519986152648926,0.04062766162168488,1739141175.0680676,14.519986152648926,2.401799907839469 +1739141175.0839329,14.549986124038696,29.13348377077363,1739141175.0839381,14.549986124038696,-0.24301264689890179,1739141175.0839436,14.549986124038696,28.601769587676237,1739141175.0839493,14.549986124038696,37.80051517338015,1739141175.083952,14.549986124038696,-0.059,1739141175.0839553,14.549986124038696,0.021228145685236687,1739141175.0839577,14.549986124038696,-0.16816355661652957,1739141175.0839603,14.549986124038696,-0.017185093160707814,1739141175.083963,14.549986124038696,2.3373675307257322,1739141175.083966,14.549986124038696,0.0,1739141175.0839689,14.549986124038696,-0.06443237711373673,1739141175.0839715,14.549986124038696,0.04062766162168488,1739141175.083974,14.549986124038696,2.401799907839469 +1739141175.1030319,14.56998610496521,29.13348377077363,1739141175.1030364,14.56998610496521,-0.24301264689890179,1739141175.1030421,14.56998610496521,28.601769587676237,1739141175.1030471,14.56998610496521,37.80051517338015,1739141175.1030498,14.56998610496521,-0.059,1739141175.103053,14.56998610496521,0.021228145685236687,1739141175.1030557,14.56998610496521,-0.16816355661652957,1739141175.103058,14.56998610496521,-0.017185093160707814,1739141175.1030605,14.56998610496521,2.3373675307257322,1739141175.1030636,14.56998610496521,0.0,1739141175.1030664,14.56998610496521,-0.06443237711373673,1739141175.1030688,14.56998610496521,0.04062766162168488,1739141175.1030712,14.56998610496521,2.401799907839469 +1739141175.1227067,14.589986085891724,29.3970720680638,1739141175.1227098,14.589986085891724,-0.23218558533154,1739141175.1227136,14.589986085891724,29.034121057915595,1739141175.1227171,14.589986085891724,38.210573777433446,1739141175.122719,14.589986085891724,-0.058,1739141175.1227212,14.589986085891724,0.019760921104412403,1739141175.122723,14.589986085891724,-0.19217492470198375,1739141175.1227245,14.589986085891724,-0.018992649375724154,1739141175.1227264,14.589986085891724,2.3150256375056655,1739141175.1227283,14.589986085891724,0.0,1739141175.1227303,14.589986085891724,-0.09290111820013953,1739141175.122732,14.589986085891724,0.0415629962598351,1739141175.122734,14.589986085891724,2.3943702055592384 +1739141175.142178,14.609986066818237,29.3970720680638,1739141175.1421807,14.609986066818237,-0.23218558533154,1739141175.1421838,14.609986066818237,29.034121057915595,1739141175.1421864,14.609986066818237,38.210573777433446,1739141175.1421878,14.609986066818237,-0.058,1739141175.1421895,14.609986066818237,0.019760921104412403,1739141175.142191,14.609986066818237,-0.19217492470198375,1739141175.1421921,14.609986066818237,-0.018992649375724154,1739141175.1421933,14.609986066818237,2.3150256375056655,1739141175.142195,14.609986066818237,0.0,1739141175.1421962,14.609986066818237,-0.07934456805357293,1739141175.1421976,14.609986066818237,0.0415629962598351,1739141175.1421988,14.609986066818237,2.3943702055592384 +1739141175.1630378,14.629986047744751,29.3970720680638,1739141175.1630402,14.629986047744751,-0.23218558533154,1739141175.163043,14.629986047744751,29.034121057915595,1739141175.163046,14.629986047744751,38.210573777433446,1739141175.1630473,14.629986047744751,-0.058,1739141175.1630492,14.629986047744751,0.019760921104412403,1739141175.1630504,14.629986047744751,-0.19217492470198375,1739141175.163052,14.629986047744751,-0.018992649375724154,1739141175.163053,14.629986047744751,2.3150256375056655,1739141175.163055,14.629986047744751,0.0,1739141175.1630561,14.629986047744751,-0.07934456805357293,1739141175.1630573,14.629986047744751,0.0415629962598351,1739141175.1630588,14.629986047744751,2.3943702055592384 +1739141175.1823537,14.649986028671265,29.3970720680638,1739141175.1823559,14.649986028671265,-0.23218558533154,1739141175.1823587,14.649986028671265,29.034121057915595,1739141175.1823616,14.649986028671265,38.210573777433446,1739141175.1823628,14.649986028671265,-0.058,1739141175.1823647,14.649986028671265,0.019760921104412403,1739141175.1823661,14.649986028671265,-0.19217492470198375,1739141175.1823676,14.649986028671265,-0.018992649375724154,1739141175.1823685,14.649986028671265,2.3150256375056655,1739141175.1823702,14.649986028671265,0.0,1739141175.1823716,14.649986028671265,-0.07934456805357293,1739141175.1823728,14.649986028671265,0.0415629962598351,1739141175.1823742,14.649986028671265,2.3943702055592384 +1739141175.2019389,14.669986009597778,29.3970720680638,1739141175.2019413,14.669986009597778,-0.23218558533154,1739141175.201944,14.669986009597778,29.034121057915595,1739141175.2019467,14.669986009597778,38.210573777433446,1739141175.2019482,14.669986009597778,-0.058,1739141175.2019496,14.669986009597778,0.019760921104412403,1739141175.2019513,14.669986009597778,-0.19217492470198375,1739141175.2019525,14.669986009597778,-0.018992649375724154,1739141175.201954,14.669986009597778,2.3150256375056655,1739141175.2019553,14.669986009597778,0.0,1739141175.2019567,14.669986009597778,-0.07934456805357293,1739141175.2019582,14.669986009597778,0.0415629962598351,1739141175.2019594,14.669986009597778,2.3943702055592384 +1739141175.221833,14.689985990524292,29.3970720680638,1739141175.2218354,14.689985990524292,-0.23218558533154,1739141175.221838,14.689985990524292,29.034121057915595,1739141175.2218409,14.689985990524292,38.210573777433446,1739141175.2218423,14.689985990524292,-0.058,1739141175.221844,14.689985990524292,0.019760921104412403,1739141175.2218451,14.689985990524292,-0.19217492470198375,1739141175.2218466,14.689985990524292,-0.018992649375724154,1739141175.2218478,14.689985990524292,2.3150256375056655,1739141175.2218497,14.689985990524292,0.0,1739141175.2218509,14.689985990524292,-0.07934456805357293,1739141175.221852,14.689985990524292,0.0415629962598351,1739141175.2218535,14.689985990524292,2.3943702055592384 +1739141175.2419837,14.709985971450806,29.65976061553092,1739141175.2419865,14.709985971450806,-0.22115717123300715,1739141175.2419894,14.709985971450806,29.046730108194016,1739141175.2419922,14.709985971450806,38.196320957670025,1739141175.2419934,14.709985971450806,-0.058,1739141175.2419953,14.709985971450806,0.019110426458416322,1739141175.2419965,14.709985971450806,-0.19905137022789796,1739141175.2419977,14.709985971450806,-0.02096982816005454,1739141175.2419991,14.709985971450806,2.3086667277790953,1739141175.2420008,14.709985971450806,0.0,1739141175.2420022,14.709985971450806,-0.07439038525509685,1739141175.2420034,14.709985971450806,0.042425795630445254,1739141175.2420046,14.709985971450806,2.3854162488786246 +1739141175.2638247,14.72998595237732,29.65976061553092,1739141175.263829,14.72998595237732,-0.22115717123300715,1739141175.263834,14.72998595237732,29.046730108194016,1739141175.26384,14.72998595237732,38.196320957670025,1739141175.2638433,14.72998595237732,-0.058,1739141175.2638474,14.72998595237732,0.019110426458416322,1739141175.2638512,14.72998595237732,-0.19905137022789796,1739141175.2638552,14.72998595237732,-0.02096982816005454,1739141175.263859,14.72998595237732,2.3086667277790953,1739141175.2638628,14.72998595237732,0.0,1739141175.2638667,14.72998595237732,-0.07674952109952926,1739141175.2638705,14.72998595237732,0.042425795630445254,1739141175.2638743,14.72998595237732,2.3854162488786246 +1739141175.2844083,14.749985933303833,29.65976061553092,1739141175.2844124,14.749985933303833,-0.22115717123300715,1739141175.2844176,14.749985933303833,29.046730108194016,1739141175.2844234,14.749985933303833,38.196320957670025,1739141175.2844267,14.749985933303833,-0.058,1739141175.2844307,14.749985933303833,0.019110426458416322,1739141175.2844348,14.749985933303833,-0.19905137022789796,1739141175.2844384,14.749985933303833,-0.02096982816005454,1739141175.2844422,14.749985933303833,2.3086667277790953,1739141175.284446,14.749985933303833,0.0,1739141175.28445,14.749985933303833,-0.07674952109952926,1739141175.2844536,14.749985933303833,0.042425795630445254,1739141175.2844574,14.749985933303833,2.3854162488786246 +1739141175.308995,14.769985914230347,29.65976061553092,1739141175.309002,14.769985914230347,-0.22115717123300715,1739141175.309011,14.769985914230347,29.046730108194016,1739141175.3090212,14.769985914230347,38.196320957670025,1739141175.309027,14.769985914230347,-0.058,1739141175.3090348,14.769985914230347,0.019110426458416322,1739141175.3090413,14.769985914230347,-0.19905137022789796,1739141175.3090477,14.769985914230347,-0.02096982816005454,1739141175.3090544,14.769985914230347,2.3086667277790953,1739141175.3090613,14.769985914230347,0.0,1739141175.3090684,14.769985914230347,-0.07674952109952926,1739141175.3090749,14.769985914230347,0.042425795630445254,1739141175.3090816,14.769985914230347,2.3854162488786246 +1739141175.3248518,14.78998589515686,29.65976061553092,1739141175.3248563,14.78998589515686,-0.22115717123300715,1739141175.3248615,14.78998589515686,29.046730108194016,1739141175.3248675,14.78998589515686,38.196320957670025,1739141175.324871,14.78998589515686,-0.058,1739141175.3248756,14.78998589515686,0.019110426458416322,1739141175.3248794,14.78998589515686,-0.19905137022789796,1739141175.3248835,14.78998589515686,-0.02096982816005454,1739141175.3248873,14.78998589515686,2.3086667277790953,1739141175.3248913,14.78998589515686,0.0,1739141175.3248954,14.78998589515686,-0.07674952109952926,1739141175.3248994,14.78998589515686,0.042425795630445254,1739141175.3249032,14.78998589515686,2.3854162488786246 +1739141175.3422332,14.809985876083374,29.92149798315181,1739141175.342236,14.809985876083374,-0.20995040837208467,1739141175.3422403,14.809985876083374,29.059293501839818,1739141175.3422449,14.809985876083374,38.18376961282447,1739141175.3422475,14.809985876083374,-0.058,1739141175.342251,14.809985876083374,0.018388802444510702,1739141175.342254,14.809985876083374,-0.2051425791465014,1739141175.3422568,14.809985876083374,-0.023070800744954593,1739141175.34226,14.809985876083374,2.303048546316907,1739141175.342263,14.809985876083374,0.0,1739141175.342266,14.809985876083374,-0.0714930315547979,1739141175.3422692,14.809985876083374,0.04321599012382982,1739141175.3422723,14.809985876083374,2.377044669381504 +1739141175.362729,14.829985857009888,29.92149798315181,1739141175.3627312,14.829985857009888,-0.20995040837208467,1739141175.3627338,14.829985857009888,29.059293501839818,1739141175.3627362,14.829985857009888,38.18376961282447,1739141175.3627374,14.829985857009888,-0.058,1739141175.3627386,14.829985857009888,0.018388802444510702,1739141175.36274,14.829985857009888,-0.2051425791465014,1739141175.362741,14.829985857009888,-0.023070800744954593,1739141175.362742,14.829985857009888,2.303048546316907,1739141175.3627436,14.829985857009888,0.0,1739141175.3627448,14.829985857009888,-0.07399612306459735,1739141175.3627458,14.829985857009888,0.04321599012382982,1739141175.3627472,14.829985857009888,2.377044669381504 +1739141175.3822477,14.849985837936401,29.92149798315181,1739141175.38225,14.849985837936401,-0.20995040837208467,1739141175.3822525,14.849985837936401,29.059293501839818,1739141175.382255,14.849985837936401,38.18376961282447,1739141175.3822563,14.849985837936401,-0.058,1739141175.382258,14.849985837936401,0.018388802444510702,1739141175.3822591,14.849985837936401,-0.2051425791465014,1739141175.3822606,14.849985837936401,-0.023070800744954593,1739141175.3822618,14.849985837936401,2.303048546316907,1739141175.3822632,14.849985837936401,0.0,1739141175.3822646,14.849985837936401,-0.07399612306459735,1739141175.3822656,14.849985837936401,0.04321599012382982,1739141175.382267,14.849985837936401,2.377044669381504 +1739141175.40194,14.869985818862915,29.92149798315181,1739141175.4019427,14.869985818862915,-0.20995040837208467,1739141175.4019458,14.869985818862915,29.059293501839818,1739141175.4019487,14.869985818862915,38.18376961282447,1739141175.4019501,14.869985818862915,-0.058,1739141175.4019518,14.869985818862915,0.018388802444510702,1739141175.4019532,14.869985818862915,-0.2051425791465014,1739141175.4019547,14.869985818862915,-0.023070800744954593,1739141175.4019558,14.869985818862915,2.303048546316907,1739141175.4019573,14.869985818862915,0.0,1739141175.401959,14.869985818862915,-0.07399612306459735,1739141175.4019604,14.869985818862915,0.04321599012382982,1739141175.4019618,14.869985818862915,2.377044669381504 +1739141175.422225,14.889985799789429,29.92149798315181,1739141175.4222276,14.889985799789429,-0.20995040837208467,1739141175.4222312,14.889985799789429,29.059293501839818,1739141175.4222345,14.889985799789429,38.18376961282447,1739141175.4222362,14.889985799789429,-0.058,1739141175.422238,14.889985799789429,0.018388802444510702,1739141175.42224,14.889985799789429,-0.2051425791465014,1739141175.4222414,14.889985799789429,-0.023070800744954593,1739141175.422243,14.889985799789429,2.303048546316907,1739141175.4222448,14.889985799789429,0.0,1739141175.4222467,14.889985799789429,-0.07399612306459735,1739141175.4222481,14.889985799789429,0.04321599012382982,1739141175.4222498,14.889985799789429,2.377044669381504 +1739141175.4459927,14.899985790252686,29.92149798315181,1739141175.446002,14.899985790252686,-0.20995040837208467,1739141175.4460123,14.899985790252686,29.059293501839818,1739141175.4460225,14.899985790252686,38.18376961282447,1739141175.4460275,14.899985790252686,-0.058,1739141175.4460337,14.899985790252686,0.018388802444510702,1739141175.4460385,14.899985790252686,-0.2051425791465014,1739141175.4460433,14.899985790252686,-0.023070800744954593,1739141175.4460475,14.899985790252686,2.303048546316907,1739141175.4460533,14.899985790252686,0.0,1739141175.4460585,14.899985790252686,-0.07399612306459735,1739141175.446063,14.899985790252686,0.04321599012382982,1739141175.4460678,14.899985790252686,2.377044669381504 +1739141175.474197,14.929985761642456,30.18232442878285,1739141175.47421,14.929985761642456,-0.19858720059817347,1739141175.474227,14.929985761642456,29.981404672969834,1739141175.4742465,14.929985761642456,39.08168562554933,1739141175.4742572,14.929985761642456,-0.0629291416739911,1739141175.4742713,14.929985761642456,0.01524239211406233,1739141175.4742835,14.929985761642456,-0.2551978597381154,1739141175.474296,14.929985761642456,-0.02474057738604663,1739141175.4743083,14.929985761642456,2.257395213051848,1739141175.4743214,14.929985761642456,0.0,1739141175.4743342,14.929985761642456,-0.14578354880974256,1739141175.4743464,14.929985761642456,0.04391896626987345,1739141175.4743588,14.929985761642456,2.3689942563348674 +1739141175.4916785,14.94998574256897,30.18232442878285,1739141175.4916878,14.94998574256897,-0.19858720059817347,1739141175.4916975,14.94998574256897,29.981404672969834,1739141175.4917076,14.94998574256897,39.08168562554933,1739141175.4917128,14.94998574256897,-0.0629291416739911,1739141175.4917188,14.94998574256897,0.01524239211406233,1739141175.491724,14.94998574256897,-0.2551978597381154,1739141175.4917285,14.94998574256897,-0.02474057738604663,1739141175.491734,14.94998574256897,2.257395213051848,1739141175.491749,14.94998574256897,0.0,1739141175.4917622,14.94998574256897,-0.1115990432830194,1739141175.4917722,14.94998574256897,0.04391896626987345,1739141175.4917793,14.94998574256897,2.3689942563348674 +1739141175.5119784,14.969985723495483,30.18232442878285,1739141175.511988,14.969985723495483,-0.19858720059817347,1739141175.511998,14.969985723495483,29.981404672969834,1739141175.5120077,14.969985723495483,39.08168562554933,1739141175.5120132,14.969985723495483,-0.0629291416739911,1739141175.5120196,14.969985723495483,0.01524239211406233,1739141175.512025,14.969985723495483,-0.2551978597381154,1739141175.5120294,14.969985723495483,-0.02474057738604663,1739141175.5120337,14.969985723495483,2.257395213051848,1739141175.5120394,14.969985723495483,0.0,1739141175.5120444,14.969985723495483,-0.1115990432830194,1739141175.512049,14.969985723495483,0.04391896626987345,1739141175.5120535,14.969985723495483,2.3689942563348674 +1739141175.5309632,14.989985704421997,30.18232442878285,1739141175.5309696,14.989985704421997,-0.19858720059817347,1739141175.5309765,14.989985704421997,29.981404672969834,1739141175.5309837,14.989985704421997,39.08168562554933,1739141175.530987,14.989985704421997,-0.0629291416739911,1739141175.5309913,14.989985704421997,0.01524239211406233,1739141175.530995,14.989985704421997,-0.2551978597381154,1739141175.530998,14.989985704421997,-0.02474057738604663,1739141175.531001,14.989985704421997,2.257395213051848,1739141175.5310054,14.989985704421997,0.0,1739141175.5310087,14.989985704421997,-0.1115990432830194,1739141175.5310118,14.989985704421997,0.04391896626987345,1739141175.531015,14.989985704421997,2.3689942563348674 +1739141175.5522249,15.00998568534851,30.18232442878285,1739141175.55223,15.00998568534851,-0.19858720059817347,1739141175.5522356,15.00998568534851,29.981404672969834,1739141175.5522408,15.00998568534851,39.08168562554933,1739141175.5522435,15.00998568534851,-0.0629291416739911,1739141175.5522466,15.00998568534851,0.01524239211406233,1739141175.5522494,15.00998568534851,-0.2551978597381154,1739141175.5522516,15.00998568534851,-0.02474057738604663,1739141175.5522542,15.00998568534851,2.257395213051848,1739141175.5522573,15.00998568534851,0.0,1739141175.5522602,15.00998568534851,-0.1115990432830194,1739141175.5522625,15.00998568534851,0.04391896626987345,1739141175.552265,15.00998568534851,2.3689942563348674 +1739141175.5729578,15.029985666275024,30.442093023748306,1739141175.5729666,15.029985666275024,-0.1870936753764152,1739141175.5729766,15.029985666275024,29.98737935065404,1739141175.5729864,15.029985666275024,39.05227835508126,1739141175.5729918,15.029985666275024,-0.06253704473441686,1739141175.5729976,15.029985666275024,0.014465187246271919,1739141175.5730023,15.029985666275024,-0.25907947169271583,1739141175.5730066,15.029985666275024,-0.02683284775405515,1739141175.5730112,15.029985666275024,2.2538929997039587,1739141175.5730171,15.029985666275024,0.0,1739141175.5730221,15.029985666275024,-0.09576763120218593,1739141175.5730267,15.029985666275024,0.044556463552950225,1739141175.5730317,15.029985666275024,2.35719940232963 +1739141175.5911865,15.049985647201538,30.442093023748306,1739141175.591191,15.049985647201538,-0.1870936753764152,1739141175.5911968,15.049985647201538,29.98737935065404,1739141175.5912018,15.049985647201538,39.05227835508126,1739141175.5912044,15.049985647201538,-0.06253704473441686,1739141175.591208,15.049985647201538,0.014465187246271919,1739141175.5912106,15.049985647201538,-0.25907947169271583,1739141175.5912132,15.049985647201538,-0.02683284775405515,1739141175.5912158,15.049985647201538,2.2538929997039587,1739141175.591219,15.049985647201538,0.0,1739141175.5912218,15.049985647201538,-0.10330640262567137,1739141175.5912244,15.049985647201538,0.044556463552950225,1739141175.5912266,15.049985647201538,2.35719940232963 +1739141175.6082585,15.069985628128052,30.442093023748306,1739141175.6082616,15.069985628128052,-0.1870936753764152,1739141175.6082654,15.069985628128052,29.98737935065404,1739141175.608269,15.069985628128052,39.05227835508126,1739141175.608271,15.069985628128052,-0.06253704473441686,1739141175.6082733,15.069985628128052,0.014465187246271919,1739141175.608275,15.069985628128052,-0.25907947169271583,1739141175.6082768,15.069985628128052,-0.02683284775405515,1739141175.6082783,15.069985628128052,2.2538929997039587,1739141175.6082804,15.069985628128052,0.0,1739141175.608282,15.069985628128052,-0.10330640262567137,1739141175.608284,15.069985628128052,0.044556463552950225,1739141175.6082857,15.069985628128052,2.35719940232963 +1739141175.6287127,15.089985609054565,30.442093023748306,1739141175.6287155,15.089985609054565,-0.1870936753764152,1739141175.6287186,15.089985609054565,29.98737935065404,1739141175.6287222,15.089985609054565,39.05227835508126,1739141175.6287236,15.089985609054565,-0.06253704473441686,1739141175.6287255,15.089985609054565,0.014465187246271919,1739141175.628727,15.089985609054565,-0.25907947169271583,1739141175.6287286,15.089985609054565,-0.02683284775405515,1739141175.6287298,15.089985609054565,2.2538929997039587,1739141175.628732,15.089985609054565,0.0,1739141175.6287334,15.089985609054565,-0.10330640262567137,1739141175.6287348,15.089985609054565,0.044556463552950225,1739141175.6287363,15.089985609054565,2.35719940232963 +1739141175.6480846,15.109985589981079,30.442093023748306,1739141175.6480875,15.109985589981079,-0.1870936753764152,1739141175.6480908,15.109985589981079,29.98737935065404,1739141175.648094,15.109985589981079,39.05227835508126,1739141175.6480954,15.109985589981079,-0.06253704473441686,1739141175.6480973,15.109985589981079,0.014465187246271919,1739141175.6480987,15.109985589981079,-0.25907947169271583,1739141175.6481001,15.109985589981079,-0.02683284775405515,1739141175.6481016,15.109985589981079,2.2538929997039587,1739141175.6481035,15.109985589981079,0.0,1739141175.648105,15.109985589981079,-0.10330640262567137,1739141175.6481066,15.109985589981079,0.044556463552950225,1739141175.648108,15.109985589981079,2.35719940232963 +1739141175.6682386,15.129985570907593,30.442093023748306,1739141175.6682422,15.129985570907593,-0.1870936753764152,1739141175.668246,15.129985570907593,29.98737935065404,1739141175.6682494,15.129985570907593,39.05227835508126,1739141175.668251,15.129985570907593,-0.06253704473441686,1739141175.668253,15.129985570907593,0.014465187246271919,1739141175.6682546,15.129985570907593,-0.25907947169271583,1739141175.6682563,15.129985570907593,-0.02683284775405515,1739141175.6682575,15.129985570907593,2.2538929997039587,1739141175.6682596,15.129985570907593,0.0,1739141175.6682613,15.129985570907593,-0.10330640262567137,1739141175.668263,15.129985570907593,0.044556463552950225,1739141175.6682644,15.129985570907593,2.35719940232963 +1739141175.6879463,15.149985551834106,30.700573005996397,1739141175.687949,15.149985551834106,-0.1755043871136328,1739141175.687952,15.149985551834106,29.993324390245746,1739141175.6879554,15.149985551834106,39.02474788648507,1739141175.687957,15.149985551834106,-0.06216997181980101,1739141175.6879587,15.149985551834106,0.013614251831264985,1739141175.6879604,15.149985551834106,-0.26206792225909825,1739141175.6879616,15.149985551834106,-0.02904013500567037,1739141175.6879632,15.149985551834106,2.2512003502699267,1739141175.687965,15.149985551834106,0.0,1739141175.6879668,15.149985551834106,-0.08714275451174634,1739141175.687968,15.149985551834106,0.04509928654533487,1739141175.6879694,15.149985551834106,2.3460400839189957 +1739141175.7082694,15.16998553276062,30.700573005996397,1739141175.7082722,15.16998553276062,-0.1755043871136328,1739141175.7082756,15.16998553276062,29.993324390245746,1739141175.708279,15.16998553276062,39.02474788648507,1739141175.7082803,15.16998553276062,-0.06216997181980101,1739141175.708282,15.16998553276062,0.013614251831264985,1739141175.7082837,15.16998553276062,-0.26206792225909825,1739141175.708285,15.16998553276062,-0.02904013500567037,1739141175.7082865,15.16998553276062,2.2512003502699267,1739141175.7082882,15.16998553276062,0.0,1739141175.7082899,15.16998553276062,-0.09483973364906895,1739141175.708291,15.16998553276062,0.04509928654533487,1739141175.7082927,15.16998553276062,2.3460400839189957 +1739141175.7283056,15.189985513687134,30.700573005996397,1739141175.7283115,15.189985513687134,-0.1755043871136328,1739141175.7283156,15.189985513687134,29.993324390245746,1739141175.7283187,15.189985513687134,39.02474788648507,1739141175.7283204,15.189985513687134,-0.06216997181980101,1739141175.7283223,15.189985513687134,0.013614251831264985,1739141175.7283237,15.189985513687134,-0.26206792225909825,1739141175.7283251,15.189985513687134,-0.02904013500567037,1739141175.7283263,15.189985513687134,2.2512003502699267,1739141175.7283282,15.189985513687134,0.0,1739141175.72833,15.189985513687134,-0.09483973364906895,1739141175.7283313,15.189985513687134,0.04509928654533487,1739141175.7283332,15.189985513687134,2.3460400839189957 +1739141175.7486038,15.209985494613647,30.700573005996397,1739141175.748607,15.209985494613647,-0.1755043871136328,1739141175.7486105,15.209985494613647,29.993324390245746,1739141175.748614,15.209985494613647,39.02474788648507,1739141175.748616,15.209985494613647,-0.06216997181980101,1739141175.748618,15.209985494613647,0.013614251831264985,1739141175.7486198,15.209985494613647,-0.26206792225909825,1739141175.7486215,15.209985494613647,-0.02904013500567037,1739141175.7486231,15.209985494613647,2.2512003502699267,1739141175.748625,15.209985494613647,0.0,1739141175.748627,15.209985494613647,-0.09483973364906895,1739141175.7486284,15.209985494613647,0.04509928654533487,1739141175.74863,15.209985494613647,2.3460400839189957 +1739141175.7680697,15.229985475540161,30.700573005996397,1739141175.7680736,15.229985475540161,-0.1755043871136328,1739141175.7680776,15.229985475540161,29.993324390245746,1739141175.7680812,15.229985475540161,39.02474788648507,1739141175.768083,15.229985475540161,-0.06216997181980101,1739141175.7680852,15.229985475540161,0.013614251831264985,1739141175.7680876,15.229985475540161,-0.26206792225909825,1739141175.7680893,15.229985475540161,-0.02904013500567037,1739141175.768091,15.229985475540161,2.2512003502699267,1739141175.7680929,15.229985475540161,0.0,1739141175.7680948,15.229985475540161,-0.09483973364906895,1739141175.7680962,15.229985475540161,0.04509928654533487,1739141175.768098,15.229985475540161,2.3460400839189957 +1739141175.788057,15.249985456466675,30.95785856235377,1739141175.7880607,15.249985456466675,-0.16383655787327367,1739141175.7880645,15.249985456466675,29.999241958041967,1739141175.788068,15.249985456466675,38.99976079327057,1739141175.78807,15.249985456466675,-0.06180572687731062,1739141175.788072,15.249985456466675,0.012686719380151895,1739141175.7880743,15.249985456466675,-0.26441118398376606,1739141175.788076,15.249985456466675,-0.031393353290665255,1739141175.7880776,15.249985456466675,2.249091278199768,1739141175.7880795,15.249985456466675,0.0,1739141175.7880812,15.249985456466675,-0.07919783222386839,1739141175.7880833,15.249985456466675,0.04556918292758674,1739141175.7880847,15.249985456466675,2.3357376386326925 +1739141175.8083577,15.269985437393188,30.95785856235377,1739141175.808361,15.269985437393188,-0.16383655787327367,1739141175.8083649,15.269985437393188,29.999241958041967,1739141175.8083684,15.269985437393188,38.99976079327057,1739141175.80837,15.269985437393188,-0.06180572687731062,1739141175.8083723,15.269985437393188,0.012686719380151895,1739141175.808375,15.269985437393188,-0.26441118398376606,1739141175.8083763,15.269985437393188,-0.031393353290665255,1739141175.8083782,15.269985437393188,2.249091278199768,1739141175.8083801,15.269985437393188,0.0,1739141175.8083825,15.269985437393188,-0.0866463604329244,1739141175.808384,15.269985437393188,0.04556918292758674,1739141175.8083858,15.269985437393188,2.3357376386326925 +1739141175.8280678,15.289985418319702,30.95785856235377,1739141175.828071,15.289985418319702,-0.16383655787327367,1739141175.828075,15.289985418319702,29.999241958041967,1739141175.8280783,15.289985418319702,38.99976079327057,1739141175.8280802,15.289985418319702,-0.06180572687731062,1739141175.828082,15.289985418319702,0.012686719380151895,1739141175.828084,15.289985418319702,-0.26441118398376606,1739141175.8280857,15.289985418319702,-0.031393353290665255,1739141175.8280873,15.289985418319702,2.249091278199768,1739141175.8280892,15.289985418319702,0.0,1739141175.8280911,15.289985418319702,-0.0866463604329244,1739141175.8280926,15.289985418319702,0.04556918292758674,1739141175.8280942,15.289985418319702,2.3357376386326925 +1739141175.8540754,15.309985399246216,30.95785856235377,1739141175.8540866,15.309985399246216,-0.16383655787327367,1739141175.8540976,15.309985399246216,29.999241958041967,1739141175.8541071,15.309985399246216,38.99976079327057,1739141175.8541117,15.309985399246216,-0.06180572687731062,1739141175.854118,15.309985399246216,0.012686719380151895,1739141175.8541226,15.309985399246216,-0.26441118398376606,1739141175.8541272,15.309985399246216,-0.031393353290665255,1739141175.8541315,15.309985399246216,2.249091278199768,1739141175.8541374,15.309985399246216,0.0,1739141175.8541424,15.309985399246216,-0.0866463604329244,1739141175.8541467,15.309985399246216,0.04556918292758674,1739141175.8541515,15.309985399246216,2.3357376386326925 +1739141175.8719373,15.32998538017273,30.95785856235377,1739141175.8719463,15.32998538017273,-0.16383655787327367,1739141175.8719559,15.32998538017273,29.999241958041967,1739141175.871966,15.32998538017273,38.99976079327057,1739141175.8719711,15.32998538017273,-0.06180572687731062,1739141175.8719766,15.32998538017273,0.012686719380151895,1739141175.8719816,15.32998538017273,-0.26441118398376606,1739141175.871986,15.32998538017273,-0.031393353290665255,1739141175.8719902,15.32998538017273,2.249091278199768,1739141175.871996,15.32998538017273,0.0,1739141175.8720012,15.32998538017273,-0.0866463604329244,1739141175.8720057,15.32998538017273,0.04556918292758674,1739141175.8720102,15.32998538017273,2.3357376386326925 +1739141175.8917484,15.349985361099243,30.95785856235377,1739141175.891755,15.349985361099243,-0.16383655787327367,1739141175.8917623,15.349985361099243,29.999241958041967,1739141175.8917692,15.349985361099243,38.99976079327057,1739141175.8917727,15.349985361099243,-0.06180572687731062,1739141175.8917768,15.349985361099243,0.012686719380151895,1739141175.8917806,15.349985361099243,-0.26441118398376606,1739141175.8917837,15.349985361099243,-0.031393353290665255,1739141175.8917868,15.349985361099243,2.249091278199768,1739141175.891791,15.349985361099243,0.0,1739141175.8917944,15.349985361099243,-0.0866463604329244,1739141175.8917975,15.349985361099243,0.04556918292758674,1739141175.8918009,15.349985361099243,2.3357376386326925 +1739141175.911537,15.3599853515625,31.214060588193384,1739141175.9115434,15.3599853515625,-0.15211425210473006,1739141175.9115503,15.3599853515625,30.43820695914519,1739141175.9115567,15.3599853515625,39.41067275593968,1739141175.9115603,15.3599853515625,-0.06749045877586245,1739141175.911564,15.3599853515625,0.010323873462322351,1739141175.9115674,15.3599853515625,-0.291440867631012,1739141175.9115705,15.3599853515625,-0.033310316664927064,1739141175.9115734,15.3599853515625,2.2249053709902293,1739141175.9115777,15.3599853515625,0.0,1739141175.911581,15.3599853515625,-0.11499321218481692,1739141175.9115841,15.3599853515625,0.0458857329980996,1739141175.9115872,15.3599853515625,2.3264000755977174 +1739141175.9289267,15.38998532295227,31.214060588193384,1739141175.928932,15.38998532295227,-0.15211425210473006,1739141175.9289367,15.38998532295227,30.43820695914519,1739141175.9289412,15.38998532295227,39.41067275593968,1739141175.9289436,15.38998532295227,-0.06749045877586245,1739141175.9289467,15.38998532295227,0.010323873462322351,1739141175.9289489,15.38998532295227,-0.291440867631012,1739141175.9289515,15.38998532295227,-0.033310316664927064,1739141175.9289534,15.38998532295227,2.2249053709902293,1739141175.9289565,15.38998532295227,0.0,1739141175.928959,15.38998532295227,-0.1014947046074881,1739141175.9289613,15.38998532295227,0.0458857329980996,1739141175.9289637,15.38998532295227,2.3264000755977174 +1739141175.947658,15.409985303878784,31.214060588193384,1739141175.9476604,15.409985303878784,-0.15211425210473006,1739141175.947663,15.409985303878784,30.43820695914519,1739141175.9476657,15.409985303878784,39.41067275593968,1739141175.947667,15.409985303878784,-0.06749045877586245,1739141175.9476686,15.409985303878784,0.010323873462322351,1739141175.9476697,15.409985303878784,-0.291440867631012,1739141175.947671,15.409985303878784,-0.033310316664927064,1739141175.9476721,15.409985303878784,2.2249053709902293,1739141175.9476736,15.409985303878784,0.0,1739141175.947675,15.409985303878784,-0.1014947046074881,1739141175.947676,15.409985303878784,0.0458857329980996,1739141175.9476771,15.409985303878784,2.3264000755977174 +1739141175.9678888,15.429985284805298,31.214060588193384,1739141175.9678917,15.429985284805298,-0.15211425210473006,1739141175.9678943,15.429985284805298,30.43820695914519,1739141175.967897,15.429985284805298,39.41067275593968,1739141175.9678981,15.429985284805298,-0.06749045877586245,1739141175.9678996,15.429985284805298,0.010323873462322351,1739141175.967901,15.429985284805298,-0.291440867631012,1739141175.967902,15.429985284805298,-0.033310316664927064,1739141175.9679034,15.429985284805298,2.2249053709902293,1739141175.967905,15.429985284805298,0.0,1739141175.9679062,15.429985284805298,-0.1014947046074881,1739141175.9679074,15.429985284805298,0.0458857329980996,1739141175.9679089,15.429985284805298,2.3264000755977174 +1739141175.9878223,15.449985265731812,31.214060588193384,1739141175.987825,15.449985265731812,-0.15211425210473006,1739141175.987828,15.449985265731812,30.43820695914519,1739141175.9878306,15.449985265731812,39.41067275593968,1739141175.9878318,15.449985265731812,-0.06749045877586245,1739141175.9878333,15.449985265731812,0.010323873462322351,1739141175.9878347,15.449985265731812,-0.291440867631012,1739141175.987836,15.449985265731812,-0.033310316664927064,1739141175.9878368,15.449985265731812,2.2249053709902293,1739141175.9878385,15.449985265731812,0.0,1739141175.9878397,15.449985265731812,-0.1014947046074881,1739141175.9878411,15.449985265731812,0.0458857329980996,1739141175.987842,15.449985265731812,2.3264000755977174 +1739141176.0077038,15.469985246658325,31.469101733117185,1739141176.0077066,15.469985246658325,-0.14037671939947138,1739141176.0077095,15.469985246658325,31.39046830396833,1739141176.007712,15.469985246658325,40.3283279084124,1739141176.0077136,15.469985246658325,-0.0779587405439595,1739141176.0077147,15.469985246658325,0.007045417381963405,1739141176.0077164,15.469985246658325,-0.34597832797842365,1739141176.0077174,15.469985246658325,-0.03385154902234573,1739141176.0077193,15.469985246658325,2.1768946758708205,1739141176.007721,15.469985246658325,0.0,1739141176.0077221,15.469985246658325,-0.17117371208510465,1739141176.0077236,15.469985246658325,0.04610726451456504,1739141176.0077248,15.469985246658325,2.3148878916295716 +1739141176.02787,15.489985227584839,31.469101733117185,1739141176.027873,15.489985227584839,-0.14037671939947138,1739141176.027876,15.489985227584839,31.39046830396833,1739141176.0278783,15.489985227584839,40.3283279084124,1739141176.0278797,15.489985227584839,-0.0779587405439595,1739141176.0278814,15.489985227584839,0.007045417381963405,1739141176.0278828,15.489985227584839,-0.34597832797842365,1739141176.0278838,15.489985227584839,-0.03385154902234573,1739141176.027885,15.489985227584839,2.1768946758708205,1739141176.0278866,15.489985227584839,0.0,1739141176.0278878,15.489985227584839,-0.13799321575875112,1739141176.0278893,15.489985227584839,0.04610726451456504,1739141176.0278902,15.489985227584839,2.3148878916295716 +1739141176.049274,15.509985208511353,31.469101733117185,1739141176.0492766,15.509985208511353,-0.14037671939947138,1739141176.0492795,15.509985208511353,31.39046830396833,1739141176.0492823,15.509985208511353,40.3283279084124,1739141176.0492837,15.509985208511353,-0.0779587405439595,1739141176.0492854,15.509985208511353,0.007045417381963405,1739141176.0492866,15.509985208511353,-0.34597832797842365,1739141176.049288,15.509985208511353,-0.03385154902234573,1739141176.0492892,15.509985208511353,2.1768946758708205,1739141176.0492907,15.509985208511353,0.0,1739141176.049292,15.509985208511353,-0.13799321575875112,1739141176.0492933,15.509985208511353,0.04610726451456504,1739141176.049295,15.509985208511353,2.3148878916295716 +1739141176.0685554,15.529985189437866,31.469101733117185,1739141176.0685577,15.529985189437866,-0.14037671939947138,1739141176.0685606,15.529985189437866,31.39046830396833,1739141176.0685635,15.529985189437866,40.3283279084124,1739141176.0685647,15.529985189437866,-0.0779587405439595,1739141176.0685663,15.529985189437866,0.007045417381963405,1739141176.0685678,15.529985189437866,-0.34597832797842365,1739141176.0685692,15.529985189437866,-0.03385154902234573,1739141176.0685704,15.529985189437866,2.1768946758708205,1739141176.0685718,15.529985189437866,0.0,1739141176.0685732,15.529985189437866,-0.13799321575875112,1739141176.068575,15.529985189437866,0.04610726451456504,1739141176.0685763,15.529985189437866,2.3148878916295716 +1739141176.0877407,15.54998517036438,31.469101733117185,1739141176.0877442,15.54998517036438,-0.14037671939947138,1739141176.0877478,15.54998517036438,31.39046830396833,1739141176.0877507,15.54998517036438,40.3283279084124,1739141176.087752,15.54998517036438,-0.0779587405439595,1739141176.087754,15.54998517036438,0.007045417381963405,1739141176.0877554,15.54998517036438,-0.34597832797842365,1739141176.0877569,15.54998517036438,-0.03385154902234573,1739141176.087758,15.54998517036438,2.1768946758708205,1739141176.0877602,15.54998517036438,0.0,1739141176.0877616,15.54998517036438,-0.13799321575875112,1739141176.0877628,15.54998517036438,0.04610726451456504,1739141176.0877643,15.54998517036438,2.3148878916295716 +1739141176.107811,15.569985151290894,31.469101733117185,1739141176.107814,15.569985151290894,-0.14037671939947138,1739141176.1078172,15.569985151290894,31.39046830396833,1739141176.1078203,15.569985151290894,40.3283279084124,1739141176.107822,15.569985151290894,-0.0779587405439595,1739141176.1078236,15.569985151290894,0.007045417381963405,1739141176.1078248,15.569985151290894,-0.34597832797842365,1739141176.1078265,15.569985151290894,-0.03385154902234573,1739141176.1078277,15.569985151290894,2.1768946758708205,1739141176.1078293,15.569985151290894,0.0,1739141176.1078312,15.569985151290894,-0.13799321575875112,1739141176.1078327,15.569985151290894,0.04610726451456504,1739141176.107834,15.569985151290894,2.3148878916295716 +1739141176.1275742,15.589985132217407,31.722648955230014,1739141176.1275766,15.589985132217407,-0.12865334844112564,1739141176.1275795,15.589985132217407,31.41910741669612,1739141176.1275823,15.589985132217407,40.30967612372749,1739141176.1275835,15.589985132217407,-0.0777491699295224,1739141176.127585,15.589985132217407,0.005927963338304824,1739141176.1275864,15.589985132217407,-0.3467720443755709,1739141176.1275876,15.589985132217407,-0.0361146477757156,1739141176.1275887,15.589985132217407,2.176203650772575,1739141176.1275902,15.589985132217407,0.0,1739141176.1275916,15.589985132217407,-0.10921747577202053,1739141176.127593,15.589985132217407,0.04632148509647488,1739141176.1275942,15.589985132217407,2.2991238667167275 +1739141176.1484318,15.609985113143921,31.722648955230014,1739141176.148436,15.609985113143921,-0.12865334844112564,1739141176.1484406,15.609985113143921,31.41910741669612,1739141176.1484458,15.609985113143921,40.30967612372749,1739141176.148449,15.609985113143921,-0.0777491699295224,1739141176.1484528,15.609985113143921,0.005927963338304824,1739141176.1484563,15.609985113143921,-0.3467720443755709,1739141176.1484606,15.609985113143921,-0.0361146477757156,1739141176.1484632,15.609985113143921,2.176203650772575,1739141176.1484656,15.609985113143921,0.0,1739141176.1484692,15.609985113143921,-0.12292021594415248,1739141176.1484735,15.609985113143921,0.04632148509647488,1739141176.148477,15.609985113143921,2.2991238667167275 +1739141176.167889,15.629985094070435,31.722648955230014,1739141176.167892,15.629985094070435,-0.12865334844112564,1739141176.167895,15.629985094070435,31.41910741669612,1739141176.167898,15.629985094070435,40.30967612372749,1739141176.1678994,15.629985094070435,-0.0777491699295224,1739141176.1679013,15.629985094070435,0.005927963338304824,1739141176.1679027,15.629985094070435,-0.3467720443755709,1739141176.167904,15.629985094070435,-0.0361146477757156,1739141176.1679053,15.629985094070435,2.176203650772575,1739141176.1679068,15.629985094070435,0.0,1739141176.1679087,15.629985094070435,-0.12292021594415248,1739141176.1679099,15.629985094070435,0.04632148509647488,1739141176.167911,15.629985094070435,2.2991238667167275 +1739141176.1894517,15.649985074996948,31.722648955230014,1739141176.1894562,15.649985074996948,-0.12865334844112564,1739141176.1894615,15.649985074996948,31.41910741669612,1739141176.1894684,15.649985074996948,40.30967612372749,1739141176.1894715,15.649985074996948,-0.0777491699295224,1739141176.1894763,15.649985074996948,0.005927963338304824,1739141176.1894794,15.649985074996948,-0.3467720443755709,1739141176.189484,15.649985074996948,-0.0361146477757156,1739141176.1894875,15.649985074996948,2.176203650772575,1739141176.189491,15.649985074996948,0.0,1739141176.189495,15.649985074996948,-0.12292021594415248,1739141176.1894982,15.649985074996948,0.04632148509647488,1739141176.1895025,15.649985074996948,2.2991238667167275 +1739141176.2078056,15.669985055923462,31.722648955230014,1739141176.2078083,15.669985055923462,-0.12865334844112564,1739141176.2078109,15.669985055923462,31.41910741669612,1739141176.207813,15.669985055923462,40.30967612372749,1739141176.2078145,15.669985055923462,-0.0777491699295224,1739141176.207816,15.669985055923462,0.005927963338304824,1739141176.2078173,15.669985055923462,-0.3467720443755709,1739141176.2078183,15.669985055923462,-0.0361146477757156,1739141176.2078192,15.669985055923462,2.176203650772575,1739141176.207821,15.669985055923462,0.0,1739141176.207822,15.669985055923462,-0.12292021594415248,1739141176.2078233,15.669985055923462,0.04632148509647488,1739141176.2078245,15.669985055923462,2.2991238667167275 +1739141176.227662,15.689985036849976,31.974616751354084,1739141176.2276645,15.689985036849976,-0.11695495212789364,1739141176.227667,15.689985036849976,31.447568079261824,1739141176.22767,15.689985036849976,40.29818042800362,1739141176.2276714,15.689985036849976,-0.07762000480902938,1739141176.2276733,15.689985036849976,0.004725698755261376,1739141176.227675,15.689985036849976,-0.34736266965266116,1739141176.2276762,15.689985036849976,-0.03850279049225916,1739141176.2276776,15.689985036849976,2.1756895831455356,1739141176.2276793,15.689985036849976,0.0,1739141176.2276807,15.689985036849976,-0.09847437145834118,1739141176.2276826,15.689985036849976,0.04646980113969472,1739141176.2276838,15.689985036849976,2.285804838745584 +1739141176.247623,15.70998501777649,31.974616751354084,1739141176.2476258,15.70998501777649,-0.11695495212789364,1739141176.2476296,15.70998501777649,31.447568079261824,1739141176.2476332,15.70998501777649,40.29818042800362,1739141176.247635,15.70998501777649,-0.07762000480902938,1739141176.247637,15.70998501777649,0.004725698755261376,1739141176.2476387,15.70998501777649,-0.34736266965266116,1739141176.2476408,15.70998501777649,-0.03850279049225916,1739141176.2476432,15.70998501777649,2.1756895831455356,1739141176.2476447,15.70998501777649,0.0,1739141176.2476473,15.70998501777649,-0.1101152556000482,1739141176.247657,15.70998501777649,0.04646980113969472,1739141176.2476587,15.70998501777649,2.285804838745584 +1739141176.2676444,15.729984998703003,31.974616751354084,1739141176.2676473,15.729984998703003,-0.11695495212789364,1739141176.2676504,15.729984998703003,31.447568079261824,1739141176.2676528,15.729984998703003,40.29818042800362,1739141176.2676542,15.729984998703003,-0.07762000480902938,1739141176.267656,15.729984998703003,0.004725698755261376,1739141176.2676575,15.729984998703003,-0.34736266965266116,1739141176.2676587,15.729984998703003,-0.03850279049225916,1739141176.2676601,15.729984998703003,2.1756895831455356,1739141176.2676613,15.729984998703003,0.0,1739141176.2676628,15.729984998703003,-0.1101152556000482,1739141176.2676642,15.729984998703003,0.04646980113969472,1739141176.2676654,15.729984998703003,2.285804838745584 +1739141176.2876716,15.749984979629517,31.974616751354084,1739141176.2876742,15.749984979629517,-0.11695495212789364,1739141176.2876768,15.749984979629517,31.447568079261824,1739141176.28768,15.749984979629517,40.29818042800362,1739141176.2876816,15.749984979629517,-0.07762000480902938,1739141176.2876832,15.749984979629517,0.004725698755261376,1739141176.287685,15.749984979629517,-0.34736266965266116,1739141176.2876863,15.749984979629517,-0.03850279049225916,1739141176.2876875,15.749984979629517,2.1756895831455356,1739141176.287689,15.749984979629517,0.0,1739141176.2876904,15.749984979629517,-0.1101152556000482,1739141176.287692,15.749984979629517,0.04646980113969472,1739141176.2876935,15.749984979629517,2.285804838745584 +1739141176.3076587,15.76998496055603,31.974616751354084,1739141176.307661,15.76998496055603,-0.11695495212789364,1739141176.307664,15.76998496055603,31.447568079261824,1739141176.3076665,15.76998496055603,40.29818042800362,1739141176.307668,15.76998496055603,-0.07762000480902938,1739141176.3076694,15.76998496055603,0.004725698755261376,1739141176.307671,15.76998496055603,-0.34736266965266116,1739141176.3076723,15.76998496055603,-0.03850279049225916,1739141176.3076737,15.76998496055603,2.1756895831455356,1739141176.3076754,15.76998496055603,0.0,1739141176.3076766,15.76998496055603,-0.1101152556000482,1739141176.307678,15.76998496055603,0.04646980113969472,1739141176.3076792,15.76998496055603,2.285804838745584 +1739141176.327552,15.789984941482544,31.974616751354084,1739141176.3275542,15.789984941482544,-0.11695495212789364,1739141176.3275568,15.789984941482544,31.447568079261824,1739141176.3275592,15.789984941482544,40.29818042800362,1739141176.3275607,15.789984941482544,-0.07762000480902938,1739141176.3275623,15.789984941482544,0.004725698755261376,1739141176.3275635,15.789984941482544,-0.34736266965266116,1739141176.3275645,15.789984941482544,-0.03850279049225916,1739141176.327566,15.789984941482544,2.1756895831455356,1739141176.3275673,15.789984941482544,0.0,1739141176.3275685,15.789984941482544,-0.1101152556000482,1739141176.3275697,15.789984941482544,0.04646980113969472,1739141176.3275712,15.789984941482544,2.285804838745584 +1739141176.347737,15.809984922409058,32.225202247332085,1739141176.3477397,15.809984922409058,-0.10529418580812333,1739141176.3477428,15.809984922409058,31.475872579541022,1739141176.347746,15.809984922409058,40.2910127518363,1739141176.3477476,15.809984922409058,-0.07753946912175616,1739141176.3477497,15.809984922409058,0.003441018993256428,1739141176.3477514,15.809984922409058,-0.3474432321094312,1739141176.347753,15.809984922409058,-0.04101255712347307,1739141176.3477542,15.809984922409058,2.1756194727160008,1739141176.3477561,15.809984922409058,0.0,1739141176.3477578,15.809984922409058,-0.0876756014877723,1739141176.3477592,15.809984922409058,0.04653014343129663,1739141176.347761,15.809984922409058,2.273980629118949 +1739141176.367872,15.829984903335571,32.225202247332085,1739141176.367875,15.829984903335571,-0.10529418580812333,1739141176.367879,15.829984903335571,31.475872579541022,1739141176.3678823,15.829984903335571,40.2910127518363,1739141176.3678837,15.829984903335571,-0.07753946912175616,1739141176.3678856,15.829984903335571,0.003441018993256428,1739141176.3678873,15.829984903335571,-0.3474432321094312,1739141176.367889,15.829984903335571,-0.04101255712347307,1739141176.3678901,15.829984903335571,2.1756194727160008,1739141176.3678923,15.829984903335571,0.0,1739141176.367894,15.829984903335571,-0.09836115640294807,1739141176.3678956,15.829984903335571,0.04653014343129663,1739141176.367897,15.829984903335571,2.273980629118949 +1739141176.3878515,15.849984884262085,32.225202247332085,1739141176.3878543,15.849984884262085,-0.10529418580812333,1739141176.3878577,15.849984884262085,31.475872579541022,1739141176.3878608,15.849984884262085,40.2910127518363,1739141176.3878622,15.849984884262085,-0.07753946912175616,1739141176.3878646,15.849984884262085,0.003441018993256428,1739141176.387866,15.849984884262085,-0.3474432321094312,1739141176.3878677,15.849984884262085,-0.04101255712347307,1739141176.387869,15.849984884262085,2.1756194727160008,1739141176.387871,15.849984884262085,0.0,1739141176.3878725,15.849984884262085,-0.09836115640294807,1739141176.3878741,15.849984884262085,0.04653014343129663,1739141176.3878756,15.849984884262085,2.273980629118949 +1739141176.4079587,15.869984865188599,32.225202247332085,1739141176.4079623,15.869984865188599,-0.10529418580812333,1739141176.4079661,15.869984865188599,31.475872579541022,1739141176.4079695,15.869984865188599,40.2910127518363,1739141176.4079714,15.869984865188599,-0.07753946912175616,1739141176.4079733,15.869984865188599,0.003441018993256428,1739141176.4079752,15.869984865188599,-0.3474432321094312,1739141176.4079769,15.869984865188599,-0.04101255712347307,1739141176.4079783,15.869984865188599,2.1756194727160008,1739141176.4079802,15.869984865188599,0.0,1739141176.4079819,15.869984865188599,-0.09836115640294807,1739141176.4079838,15.869984865188599,0.04653014343129663,1739141176.4079854,15.869984865188599,2.273980629118949 +1739141176.42778,15.889984846115112,32.225202247332085,1739141176.4277828,15.889984846115112,-0.10529418580812333,1739141176.4277856,15.889984846115112,31.475872579541022,1739141176.427789,15.889984846115112,40.2910127518363,1739141176.4277904,15.889984846115112,-0.07753946912175616,1739141176.4277923,15.889984846115112,0.003441018993256428,1739141176.4277937,15.889984846115112,-0.3474432321094312,1739141176.4277952,15.889984846115112,-0.04101255712347307,1739141176.4277968,15.889984846115112,2.1756194727160008,1739141176.4277985,15.889984846115112,0.0,1739141176.4278002,15.889984846115112,-0.09836115640294807,1739141176.4278016,15.889984846115112,0.04653014343129663,1739141176.427803,15.889984846115112,2.273980629118949 +1739141176.4477649,15.909984827041626,32.47453825749975,1739141176.4477677,15.909984827041626,-0.09368881325875744,1739141176.447771,15.909984827041626,32.00057495117938,1739141176.4477742,15.909984827041626,40.78369237541504,1739141176.447776,15.909984827041626,-0.08247789271980348,1739141176.4477777,15.909984827041626,0.0013492244309165327,1739141176.4477794,15.909984827041626,-0.3746916050131124,1739141176.4477808,15.909984827041626,-0.041676652001994455,1739141176.4477825,15.909984827041626,2.1520353954603726,1739141176.4477842,15.909984827041626,0.0,1739141176.4477856,15.909984827041626,-0.12303153857181971,1739141176.447787,15.909984827041626,0.04645831267052329,1739141176.4477885,15.909984827041626,2.2633191271308535 +1739141176.4679818,15.92998480796814,32.47453825749975,1739141176.4679852,15.92998480796814,-0.09368881325875744,1739141176.4679885,15.92998480796814,32.00057495117938,1739141176.4679916,15.92998480796814,40.78369237541504,1739141176.4679933,15.92998480796814,-0.08247789271980348,1739141176.4679952,15.92998480796814,0.0013492244309165327,1739141176.4679966,15.92998480796814,-0.3746916050131124,1739141176.467998,15.92998480796814,-0.041676652001994455,1739141176.4679995,15.92998480796814,2.1520353954603726,1739141176.4680016,15.92998480796814,0.0,1739141176.468003,15.92998480796814,-0.11128373167048089,1739141176.468005,15.92998480796814,0.04645831267052329,1739141176.4680064,15.92998480796814,2.2633191271308535 +1739141176.4876826,15.949984788894653,32.47453825749975,1739141176.4876854,15.949984788894653,-0.09368881325875744,1739141176.4876888,15.949984788894653,32.00057495117938,1739141176.4876919,15.949984788894653,40.78369237541504,1739141176.4876933,15.949984788894653,-0.08247789271980348,1739141176.4876952,15.949984788894653,0.0013492244309165327,1739141176.487697,15.949984788894653,-0.3746916050131124,1739141176.487698,15.949984788894653,-0.041676652001994455,1739141176.4876997,15.949984788894653,2.1520353954603726,1739141176.4877014,15.949984788894653,0.0,1739141176.487703,15.949984788894653,-0.11128373167048089,1739141176.4877045,15.949984788894653,0.04645831267052329,1739141176.487706,15.949984788894653,2.2633191271308535 +1739141176.5078654,15.969984769821167,32.47453825749975,1739141176.5078688,15.969984769821167,-0.09368881325875744,1739141176.507872,15.969984769821167,32.00057495117938,1739141176.507875,15.969984769821167,40.78369237541504,1739141176.5078766,15.969984769821167,-0.08247789271980348,1739141176.5078783,15.969984769821167,0.0013492244309165327,1739141176.50788,15.969984769821167,-0.3746916050131124,1739141176.5078814,15.969984769821167,-0.041676652001994455,1739141176.507883,15.969984769821167,2.1520353954603726,1739141176.5078847,15.969984769821167,0.0,1739141176.5078866,15.969984769821167,-0.11128373167048089,1739141176.5078883,15.969984769821167,0.04645831267052329,1739141176.50789,15.969984769821167,2.2633191271308535 +1739141176.5277214,15.98998475074768,32.47453825749975,1739141176.5277243,15.98998475074768,-0.09368881325875744,1739141176.5277276,15.98998475074768,32.00057495117938,1739141176.5277307,15.98998475074768,40.78369237541504,1739141176.5277321,15.98998475074768,-0.08247789271980348,1739141176.5277343,15.98998475074768,0.0013492244309165327,1739141176.5277357,15.98998475074768,-0.3746916050131124,1739141176.5277371,15.98998475074768,-0.041676652001994455,1739141176.5277386,15.98998475074768,2.1520353954603726,1739141176.5277405,15.98998475074768,0.0,1739141176.5277421,15.98998475074768,-0.11128373167048089,1739141176.5277436,15.98998475074768,0.04645831267052329,1739141176.527745,15.98998475074768,2.2633191271308535 +1739141176.5479033,16.009984731674194,32.47453825749975,1739141176.5479062,16.009984731674194,-0.09368881325875744,1739141176.5479097,16.009984731674194,32.00057495117938,1739141176.5479126,16.009984731674194,40.78369237541504,1739141176.5479143,16.009984731674194,-0.08247789271980348,1739141176.547916,16.009984731674194,0.0013492244309165327,1739141176.5479176,16.009984731674194,-0.3746916050131124,1739141176.547919,16.009984731674194,-0.041676652001994455,1739141176.5479205,16.009984731674194,2.1520353954603726,1739141176.5479221,16.009984731674194,0.0,1739141176.5479238,16.009984731674194,-0.11128373167048089,1739141176.5479252,16.009984731674194,0.04645831267052329,1739141176.547927,16.009984731674194,2.2633191271308535 +1739141176.5681756,16.029984712600708,32.722603434277964,1739141176.568179,16.029984712600708,-0.08216807883211796,1739141176.5681827,16.029984712600708,31.929427804304865,1739141176.5681858,16.029984712600708,40.675312439390105,1739141176.5681875,16.029984712600708,-0.08087793975035545,1739141176.5681891,16.029984712600708,0.00016222636457784208,1739141176.568191,16.029984712600708,-0.36718546818916753,1739141176.5681925,16.029984712600708,-0.04458456517362232,1739141176.5681942,16.029984712600708,2.158506494040692,1739141176.5681958,16.029984712600708,0.0,1739141176.5681975,16.029984712600708,-0.07522661016101218,1739141176.568199,16.029984712600708,0.046349764185698555,1739141176.5682,16.029984712600708,2.2509031706405542 +1739141176.5878046,16.04998469352722,32.722603434277964,1739141176.5878077,16.04998469352722,-0.08216807883211796,1739141176.5878108,16.04998469352722,31.929427804304865,1739141176.587814,16.04998469352722,40.675312439390105,1739141176.5878158,16.04998469352722,-0.08087793975035545,1739141176.5878174,16.04998469352722,0.00016222636457784208,1739141176.5878193,16.04998469352722,-0.36718546818916753,1739141176.5878208,16.04998469352722,-0.04458456517362232,1739141176.5878224,16.04998469352722,2.158506494040692,1739141176.587824,16.04998469352722,0.0,1739141176.5878258,16.04998469352722,-0.09239667659986228,1739141176.5878272,16.04998469352722,0.046349764185698555,1739141176.5878286,16.04998469352722,2.2509031706405542 +1739141176.6079247,16.069984674453735,32.722603434277964,1739141176.607928,16.069984674453735,-0.08216807883211796,1739141176.6079314,16.069984674453735,31.929427804304865,1739141176.6079347,16.069984674453735,40.675312439390105,1739141176.6079361,16.069984674453735,-0.08087793975035545,1739141176.6079383,16.069984674453735,0.00016222636457784208,1739141176.60794,16.069984674453735,-0.36718546818916753,1739141176.6079419,16.069984674453735,-0.04458456517362232,1739141176.607943,16.069984674453735,2.158506494040692,1739141176.607945,16.069984674453735,0.0,1739141176.607947,16.069984674453735,-0.09239667659986228,1739141176.6079485,16.069984674453735,0.046349764185698555,1739141176.6079497,16.069984674453735,2.2509031706405542 +1739141176.627742,16.08998465538025,32.722603434277964,1739141176.6277444,16.08998465538025,-0.08216807883211796,1739141176.627748,16.08998465538025,31.929427804304865,1739141176.627751,16.08998465538025,40.675312439390105,1739141176.6277528,16.08998465538025,-0.08087793975035545,1739141176.627755,16.08998465538025,0.00016222636457784208,1739141176.6277568,16.08998465538025,-0.36718546818916753,1739141176.627758,16.08998465538025,-0.04458456517362232,1739141176.6277595,16.08998465538025,2.158506494040692,1739141176.6277611,16.08998465538025,0.0,1739141176.627763,16.08998465538025,-0.09239667659986228,1739141176.6277642,16.08998465538025,0.046349764185698555,1739141176.6277657,16.08998465538025,2.2509031706405542 +1739141176.6477258,16.109984636306763,32.722603434277964,1739141176.6477284,16.109984636306763,-0.08216807883211796,1739141176.6477323,16.109984636306763,31.929427804304865,1739141176.647735,16.109984636306763,40.675312439390105,1739141176.6477365,16.109984636306763,-0.08087793975035545,1739141176.6477387,16.109984636306763,0.00016222636457784208,1739141176.6477401,16.109984636306763,-0.36718546818916753,1739141176.6477416,16.109984636306763,-0.04458456517362232,1739141176.647743,16.109984636306763,2.158506494040692,1739141176.6477447,16.109984636306763,0.0,1739141176.6477463,16.109984636306763,-0.09239667659986228,1739141176.6477478,16.109984636306763,0.046349764185698555,1739141176.6477494,16.109984636306763,2.2509031706405542 +1739141176.6679296,16.129984617233276,32.969443174229674,1739141176.667933,16.129984617233276,-0.07074169021225885,1739141176.6679366,16.129984617233276,32.701956768310794,1739141176.66794,16.129984617233276,41.4179100059145,1739141176.6679416,16.129984617233276,-0.09083638106503811,1739141176.6679437,16.129984617233276,-0.0023784969935436305,1739141176.6679454,16.129984617233276,-0.40954569065155727,1739141176.667947,16.129984617233276,-0.04406300233892627,1739141176.6679485,16.129984617233276,2.122240681173154,1739141176.6679504,16.129984617233276,0.0,1739141176.667952,16.129984617233276,-0.14263547981090685,1739141176.6679537,16.129984617233276,0.04611611241299203,1739141176.6679552,16.129984617233276,2.2409529094090446 +1739141176.6877744,16.14998459815979,32.969443174229674,1739141176.6877773,16.14998459815979,-0.07074169021225885,1739141176.6877806,16.14998459815979,32.701956768310794,1739141176.6877837,16.14998459815979,41.4179100059145,1739141176.6877854,16.14998459815979,-0.09083638106503811,1739141176.6877873,16.14998459815979,-0.0023784969935436305,1739141176.6877887,16.14998459815979,-0.40954569065155727,1739141176.6877906,16.14998459815979,-0.04406300233892627,1739141176.6877918,16.14998459815979,2.122240681173154,1739141176.6877937,16.14998459815979,0.0,1739141176.6877954,16.14998459815979,-0.11871222823589056,1739141176.6877973,16.14998459815979,0.04611611241299203,1739141176.6877985,16.14998459815979,2.2409529094090446 +1739141176.7078445,16.169984579086304,32.969443174229674,1739141176.7078478,16.169984579086304,-0.07074169021225885,1739141176.7078512,16.169984579086304,32.701956768310794,1739141176.7078543,16.169984579086304,41.4179100059145,1739141176.707856,16.169984579086304,-0.09083638106503811,1739141176.7078576,16.169984579086304,-0.0023784969935436305,1739141176.7078595,16.169984579086304,-0.40954569065155727,1739141176.7078607,16.169984579086304,-0.04406300233892627,1739141176.7078624,16.169984579086304,2.122240681173154,1739141176.707864,16.169984579086304,0.0,1739141176.7078657,16.169984579086304,-0.11871222823589056,1739141176.7078671,16.169984579086304,0.04611611241299203,1739141176.7078686,16.169984579086304,2.2409529094090446 +1739141176.7277215,16.189984560012817,32.969443174229674,1739141176.7277243,16.189984560012817,-0.07074169021225885,1739141176.7277274,16.189984560012817,32.701956768310794,1739141176.7277305,16.189984560012817,41.4179100059145,1739141176.727732,16.189984560012817,-0.09083638106503811,1739141176.727734,16.189984560012817,-0.0023784969935436305,1739141176.7277353,16.189984560012817,-0.40954569065155727,1739141176.727737,16.189984560012817,-0.04406300233892627,1739141176.7277384,16.189984560012817,2.122240681173154,1739141176.72774,16.189984560012817,0.0,1739141176.727742,16.189984560012817,-0.11871222823589056,1739141176.7277434,16.189984560012817,0.04611611241299203,1739141176.7277453,16.189984560012817,2.2409529094090446 +1739141176.7478178,16.20998454093933,32.969443174229674,1739141176.7478206,16.20998454093933,-0.07074169021225885,1739141176.7478242,16.20998454093933,32.701956768310794,1739141176.747827,16.20998454093933,41.4179100059145,1739141176.7478285,16.20998454093933,-0.09083638106503811,1739141176.7478306,16.20998454093933,-0.0023784969935436305,1739141176.747832,16.20998454093933,-0.40954569065155727,1739141176.7478333,16.20998454093933,-0.04406300233892627,1739141176.747835,16.20998454093933,2.122240681173154,1739141176.7478366,16.20998454093933,0.0,1739141176.7478385,16.20998454093933,-0.11871222823589056,1739141176.74784,16.20998454093933,0.04611611241299203,1739141176.7478416,16.20998454093933,2.2409529094090446 +1739141176.767835,16.229984521865845,32.969443174229674,1739141176.767838,16.229984521865845,-0.07074169021225885,1739141176.7678413,16.229984521865845,32.701956768310794,1739141176.7678444,16.229984521865845,41.4179100059145,1739141176.767846,16.229984521865845,-0.09083638106503811,1739141176.7678483,16.229984521865845,-0.0023784969935436305,1739141176.76785,16.229984521865845,-0.40954569065155727,1739141176.7678514,16.229984521865845,-0.04406300233892627,1739141176.7678528,16.229984521865845,2.122240681173154,1739141176.7678547,16.229984521865845,0.0,1739141176.7678561,16.229984521865845,-0.11871222823589056,1739141176.7678576,16.229984521865845,0.04611611241299203,1739141176.7678592,16.229984521865845,2.2409529094090446 +1739141176.787884,16.24998450279236,33.214991713828304,1739141176.787887,16.24998450279236,-0.05944012862180781,1739141176.7878904,16.24998450279236,32.7515688748713,1739141176.7878935,16.24998450279236,41.42710791058382,1739141176.787895,16.24998450279236,-0.0910115792492156,1739141176.7878969,16.24998450279236,-0.0038444773951988955,1739141176.7878985,16.24998450279236,-0.40789633748087795,1739141176.7879,16.24998450279236,-0.04644722077965239,1739141176.7879014,16.24998450279236,2.123641272895007,1739141176.7879035,16.24998450279236,0.0,1739141176.787905,16.24998450279236,-0.0903212916538299,1739141176.7879064,16.24998450279236,0.0458456654764928,1739141176.787908,16.24998450279236,2.227482064912923 +1739141176.807937,16.269984483718872,33.214991713828304,1739141176.80794,16.269984483718872,-0.05944012862180781,1739141176.807943,16.269984483718872,32.7515688748713,1739141176.8079464,16.269984483718872,41.42710791058382,1739141176.807948,16.269984483718872,-0.0910115792492156,1739141176.80795,16.269984483718872,-0.0038444773951988955,1739141176.8079517,16.269984483718872,-0.40789633748087795,1739141176.8079531,16.269984483718872,-0.04644722077965239,1739141176.8079548,16.269984483718872,2.123641272895007,1739141176.8079565,16.269984483718872,0.0,1739141176.8079584,16.269984483718872,-0.10384079201791607,1739141176.8079596,16.269984483718872,0.0458456654764928,1739141176.8079612,16.269984483718872,2.227482064912923 +1739141176.82774,16.289984464645386,33.214991713828304,1739141176.8277426,16.289984464645386,-0.05944012862180781,1739141176.8277457,16.289984464645386,32.7515688748713,1739141176.8277488,16.289984464645386,41.42710791058382,1739141176.8277507,16.289984464645386,-0.0910115792492156,1739141176.8277524,16.289984464645386,-0.0038444773951988955,1739141176.827754,16.289984464645386,-0.40789633748087795,1739141176.8277552,16.289984464645386,-0.04644722077965239,1739141176.827757,16.289984464645386,2.123641272895007,1739141176.8277583,16.289984464645386,0.0,1739141176.82776,16.289984464645386,-0.10384079201791607,1739141176.8277614,16.289984464645386,0.0458456654764928,1739141176.8277628,16.289984464645386,2.227482064912923 +1739141176.847707,16.3099844455719,33.214991713828304,1739141176.84771,16.3099844455719,-0.05944012862180781,1739141176.847713,16.3099844455719,32.7515688748713,1739141176.847716,16.3099844455719,41.42710791058382,1739141176.8477175,16.3099844455719,-0.0910115792492156,1739141176.8477194,16.3099844455719,-0.0038444773951988955,1739141176.8477209,16.3099844455719,-0.40789633748087795,1739141176.8477225,16.3099844455719,-0.04644722077965239,1739141176.847724,16.3099844455719,2.123641272895007,1739141176.8477259,16.3099844455719,0.0,1739141176.8477273,16.3099844455719,-0.10384079201791607,1739141176.847729,16.3099844455719,0.0458456654764928,1739141176.8477302,16.3099844455719,2.227482064912923 +1739141176.8678792,16.329984426498413,33.214991713828304,1739141176.8678825,16.329984426498413,-0.05944012862180781,1739141176.8678863,16.329984426498413,32.7515688748713,1739141176.8678894,16.329984426498413,41.42710791058382,1739141176.8678908,16.329984426498413,-0.0910115792492156,1739141176.867893,16.329984426498413,-0.0038444773951988955,1739141176.8678944,16.329984426498413,-0.40789633748087795,1739141176.867896,16.329984426498413,-0.04644722077965239,1739141176.8678975,16.329984426498413,2.123641272895007,1739141176.8678994,16.329984426498413,0.0,1739141176.8679008,16.329984426498413,-0.10384079201791607,1739141176.8679023,16.329984426498413,0.0458456654764928,1739141176.8679037,16.329984426498413,2.227482064912923 +1739141176.889295,16.349984407424927,33.45919937384081,1739141176.8892992,16.349984407424927,-0.04827236476842778,1739141176.8893044,16.349984407424927,32.80090998995769,1739141176.8893104,16.349984407424927,41.44274078493438,1739141176.8893144,16.349984407424927,-0.09130934828446438,1739141176.8893187,16.349984407424927,-0.005390661164679561,1739141176.8893225,16.349984407424927,-0.4061893193032839,1739141176.8893263,16.349984407424927,-0.04893813442465798,1739141176.8893301,16.349984407424927,2.125091805758052,1739141176.8893342,16.349984407424927,0.0,1739141176.8893383,16.349984407424927,-0.07962268776463718,1739141176.8893423,16.349984407424927,0.04550891302022853,1739141176.8893461,16.349984407424927,2.2162469298804446 +1739141176.9077833,16.36998438835144,33.45919937384081,1739141176.907786,16.36998438835144,-0.04827236476842778,1739141176.9077888,16.36998438835144,32.80090998995769,1739141176.9077916,16.36998438835144,41.44274078493438,1739141176.907793,16.36998438835144,-0.09130934828446438,1739141176.9077947,16.36998438835144,-0.005390661164679561,1739141176.9077961,16.36998438835144,-0.4061893193032839,1739141176.9077976,16.36998438835144,-0.04893813442465798,1739141176.9077988,16.36998438835144,2.125091805758052,1739141176.9078007,16.36998438835144,0.0,1739141176.907802,16.36998438835144,-0.09115512412239246,1739141176.9078033,16.36998438835144,0.04550891302022853,1739141176.9078047,16.36998438835144,2.2162469298804446 +1739141176.927585,16.389984369277954,33.45919937384081,1739141176.9275873,16.389984369277954,-0.04827236476842778,1739141176.9275901,16.389984369277954,32.80090998995769,1739141176.927593,16.389984369277954,41.44274078493438,1739141176.9275944,16.389984369277954,-0.09130934828446438,1739141176.927596,16.389984369277954,-0.005390661164679561,1739141176.9275975,16.389984369277954,-0.4061893193032839,1739141176.9275985,16.389984369277954,-0.04893813442465798,1739141176.9276,16.389984369277954,2.125091805758052,1739141176.9276013,16.389984369277954,0.0,1739141176.927603,16.389984369277954,-0.09115512412239246,1739141176.9276044,16.389984369277954,0.04550891302022853,1739141176.9276059,16.389984369277954,2.2162469298804446 +1739141176.947856,16.409984350204468,33.45919937384081,1739141176.947859,16.409984350204468,-0.04827236476842778,1739141176.9478626,16.409984350204468,32.80090998995769,1739141176.947866,16.409984350204468,41.44274078493438,1739141176.9478676,16.409984350204468,-0.09130934828446438,1739141176.9478698,16.409984350204468,-0.005390661164679561,1739141176.9478712,16.409984350204468,-0.4061893193032839,1739141176.947873,16.409984350204468,-0.04893813442465798,1739141176.9478743,16.409984350204468,2.125091805758052,1739141176.9478765,16.409984350204468,0.0,1739141176.947878,16.409984350204468,-0.09115512412239246,1739141176.9478798,16.409984350204468,0.04550891302022853,1739141176.947881,16.409984350204468,2.2162469298804446 +1739141176.9682193,16.42998433113098,33.45919937384081,1739141176.9682226,16.42998433113098,-0.04827236476842778,1739141176.9682267,16.42998433113098,32.80090998995769,1739141176.9682302,16.42998433113098,41.44274078493438,1739141176.968232,16.42998433113098,-0.09130934828446438,1739141176.9682343,16.42998433113098,-0.005390661164679561,1739141176.968236,16.42998433113098,-0.4061893193032839,1739141176.9682379,16.42998433113098,-0.04893813442465798,1739141176.9682393,16.42998433113098,2.125091805758052,1739141176.9682417,16.42998433113098,0.0,1739141176.9682434,16.42998433113098,-0.09115512412239246,1739141176.9682453,16.42998433113098,0.04550891302022853,1739141176.9682467,16.42998433113098,2.2162469298804446 +1739141176.9880998,16.449984312057495,33.45919937384081,1739141176.9881036,16.449984312057495,-0.04827236476842778,1739141176.9881074,16.449984312057495,32.80090998995769,1739141176.9881108,16.449984312057495,41.44274078493438,1739141176.9881127,16.449984312057495,-0.09130934828446438,1739141176.9881148,16.449984312057495,-0.005390661164679561,1739141176.988117,16.449984312057495,-0.4061893193032839,1739141176.988119,16.449984312057495,-0.04893813442465798,1739141176.9881203,16.449984312057495,2.125091805758052,1739141176.9881227,16.449984312057495,0.0,1739141176.9881246,16.449984312057495,-0.09115512412239246,1739141176.988127,16.449984312057495,0.04550891302022853,1739141176.9881287,16.449984312057495,2.2162469298804446 +1739141177.0101678,16.46998429298401,33.702258606183236,1739141177.0101726,16.46998429298401,-0.03724958696623304,1739141177.010179,16.46998429298401,33.415446237610794,1739141177.0101867,16.46998429298401,42.02793182696177,1739141177.010191,16.46998429298401,-0.10119961538543433,1739141177.010196,16.46998429298401,-0.007680912895670259,1739141177.0102007,16.46998429298401,-0.43910959160379703,1739141177.0102057,16.46998429298401,-0.048644275101649946,1739141177.0102103,16.46998429298401,2.0972918038278583,1739141177.0102153,16.46998429298401,0.0,1739141177.01022,16.46998429298401,-0.1256116639473336,1739141177.0102246,16.46998429298401,0.04508364335233661,1739141177.0102296,16.46998429298401,2.206495583471622 +1739141177.0281162,16.489984273910522,33.702258606183236,1739141177.0281196,16.489984273910522,-0.03724958696623304,1739141177.0281236,16.489984273910522,33.415446237610794,1739141177.0281274,16.489984273910522,42.02793182696177,1739141177.0281293,16.489984273910522,-0.10119961538543433,1739141177.0281317,16.489984273910522,-0.007680912895670259,1739141177.0281336,16.489984273910522,-0.43910959160379703,1739141177.0281355,16.489984273910522,-0.048644275101649946,1739141177.0281372,16.489984273910522,2.0972918038278583,1739141177.0281394,16.489984273910522,0.0,1739141177.028141,16.489984273910522,-0.10920377964376371,1739141177.028143,16.489984273910522,0.04508364335233661,1739141177.0281448,16.489984273910522,2.206495583471622 +1739141177.0483298,16.509984254837036,33.702258606183236,1739141177.048334,16.509984254837036,-0.03724958696623304,1739141177.048338,16.509984254837036,33.415446237610794,1739141177.0483418,16.509984254837036,42.02793182696177,1739141177.0483437,16.509984254837036,-0.10119961538543433,1739141177.0483458,16.509984254837036,-0.007680912895670259,1739141177.0483477,16.509984254837036,-0.43910959160379703,1739141177.0483494,16.509984254837036,-0.048644275101649946,1739141177.0483513,16.509984254837036,2.0972918038278583,1739141177.0483532,16.509984254837036,0.0,1739141177.0483556,16.509984254837036,-0.10920377964376371,1739141177.0483575,16.509984254837036,0.04508364335233661,1739141177.0483592,16.509984254837036,2.206495583471622 +1739141177.0686147,16.52998423576355,33.702258606183236,1739141177.0686183,16.52998423576355,-0.03724958696623304,1739141177.068622,16.52998423576355,33.415446237610794,1739141177.0686257,16.52998423576355,42.02793182696177,1739141177.0686274,16.52998423576355,-0.10119961538543433,1739141177.0686297,16.52998423576355,-0.007680912895670259,1739141177.068632,16.52998423576355,-0.43910959160379703,1739141177.0686336,16.52998423576355,-0.048644275101649946,1739141177.0686355,16.52998423576355,2.0972918038278583,1739141177.0686376,16.52998423576355,0.0,1739141177.0686395,16.52998423576355,-0.10920377964376371,1739141177.0686412,16.52998423576355,0.04508364335233661,1739141177.068643,16.52998423576355,2.206495583471622 +1739141177.088055,16.549984216690063,33.702258606183236,1739141177.0880585,16.549984216690063,-0.03724958696623304,1739141177.0880623,16.549984216690063,33.415446237610794,1739141177.0880663,16.549984216690063,42.02793182696177,1739141177.088068,16.549984216690063,-0.10119961538543433,1739141177.0880704,16.549984216690063,-0.007680912895670259,1739141177.0880725,16.549984216690063,-0.43910959160379703,1739141177.088074,16.549984216690063,-0.048644275101649946,1739141177.0880759,16.549984216690063,2.0972918038278583,1739141177.0880778,16.549984216690063,0.0,1739141177.08808,16.549984216690063,-0.10920377964376371,1739141177.0880816,16.549984216690063,0.04508364335233661,1739141177.0880835,16.549984216690063,2.206495583471622 +1739141177.1082861,16.569984197616577,33.9441214177006,1739141177.1082895,16.569984197616577,-0.026385749199189235,1739141177.1082933,16.569984197616577,33.42634092796684,1739141177.1082969,16.569984197616577,42.00255101085599,1739141177.108299,16.569984197616577,-0.10066245525621148,1739141177.1083012,16.569984197616577,-0.009217007090283913,1739141177.108303,16.569984197616577,-0.433900028125954,1739141177.1083047,16.569984197616577,-0.05130631549974293,1739141177.1083064,16.569984197616577,2.1016667504706272,1739141177.1083086,16.569984197616577,0.0,1739141177.1083102,16.569984197616577,-0.07776356446437928,1739141177.1083121,16.569984197616577,0.0446509954192767,1739141177.1083136,16.569984197616577,2.194401853451746 +1739141177.128142,16.58998417854309,33.9441214177006,1739141177.1281457,16.58998417854309,-0.026385749199189235,1739141177.12815,16.58998417854309,33.42634092796684,1739141177.1281538,16.58998417854309,42.00255101085599,1739141177.1281557,16.58998417854309,-0.10066245525621148,1739141177.128158,16.58998417854309,-0.009217007090283913,1739141177.12816,16.58998417854309,-0.433900028125954,1739141177.128162,16.58998417854309,-0.05130631549974293,1739141177.1281633,16.58998417854309,2.1016667504706272,1739141177.1281657,16.58998417854309,0.0,1739141177.1281674,16.58998417854309,-0.09273510298111898,1739141177.1281693,16.58998417854309,0.0446509954192767,1739141177.1281712,16.58998417854309,2.194401853451746 +1739141177.1480742,16.609984159469604,33.9441214177006,1739141177.148078,16.609984159469604,-0.026385749199189235,1739141177.1480823,16.609984159469604,33.42634092796684,1739141177.148086,16.609984159469604,42.00255101085599,1739141177.1480877,16.609984159469604,-0.10066245525621148,1739141177.1480901,16.609984159469604,-0.009217007090283913,1739141177.1480923,16.609984159469604,-0.433900028125954,1739141177.148094,16.609984159469604,-0.05130631549974293,1739141177.1480954,16.609984159469604,2.1016667504706272,1739141177.1480978,16.609984159469604,0.0,1739141177.1481,16.609984159469604,-0.09273510298111898,1739141177.1481016,16.609984159469604,0.0446509954192767,1739141177.1481035,16.609984159469604,2.194401853451746 +1739141177.1701658,16.629984140396118,33.9441214177006,1739141177.1701705,16.629984140396118,-0.026385749199189235,1739141177.170177,16.629984140396118,33.42634092796684,1739141177.1701844,16.629984140396118,42.00255101085599,1739141177.1701884,16.629984140396118,-0.10066245525621148,1739141177.170194,16.629984140396118,-0.009217007090283913,1739141177.1701987,16.629984140396118,-0.433900028125954,1739141177.1702037,16.629984140396118,-0.05130631549974293,1739141177.1702082,16.629984140396118,2.1016667504706272,1739141177.1702132,16.629984140396118,0.0,1739141177.170218,16.629984140396118,-0.09273510298111898,1739141177.1702225,16.629984140396118,0.0446509954192767,1739141177.1702273,16.629984140396118,2.194401853451746 +1739141177.1880612,16.649984121322632,33.9441214177006,1739141177.1880646,16.649984121322632,-0.026385749199189235,1739141177.1880684,16.649984121322632,33.42634092796684,1739141177.1880722,16.649984121322632,42.00255101085599,1739141177.1880744,16.649984121322632,-0.10066245525621148,1739141177.1880765,16.649984121322632,-0.009217007090283913,1739141177.1880784,16.649984121322632,-0.433900028125954,1739141177.18808,16.649984121322632,-0.05130631549974293,1739141177.188082,16.649984121322632,2.1016667504706272,1739141177.188084,16.649984121322632,0.0,1739141177.1880858,16.649984121322632,-0.09273510298111898,1739141177.1880875,16.649984121322632,0.0446509954192767,1739141177.1880894,16.649984121322632,2.194401853451746 +1739141177.2100825,16.669984102249146,33.9441214177006,1739141177.2100878,16.669984102249146,-0.026385749199189235,1739141177.210094,16.669984102249146,33.42634092796684,1739141177.2101014,16.669984102249146,42.00255101085599,1739141177.2101057,16.669984102249146,-0.10066245525621148,1739141177.2101107,16.669984102249146,-0.009217007090283913,1739141177.2101157,16.669984102249146,-0.433900028125954,1739141177.2101202,16.669984102249146,-0.05130631549974293,1739141177.210125,16.669984102249146,2.1016667504706272,1739141177.2101302,16.669984102249146,0.0,1739141177.210135,16.669984102249146,-0.09273510298111898,1739141177.2101398,16.669984102249146,0.0446509954192767,1739141177.2101443,16.669984102249146,2.194401853451746 +1739141177.228128,16.68998408317566,34.184787666454284,1739141177.2281318,16.68998408317566,-0.015687280282308258,1739141177.2281358,16.68998408317566,33.437181607629675,1739141177.2281396,16.68998408317566,41.98382677880337,1739141177.2281415,16.68998408317566,-0.10026617521276972,1739141177.2281437,16.68998408317566,-0.010844358925508025,1739141177.2281454,16.68998408317566,-0.4286690544952484,1739141177.2281473,16.68998408317566,-0.054113170257134025,1739141177.2281487,16.68998408317566,2.106068859668881,1739141177.228151,16.68998408317566,0.0,1739141177.228153,16.68998408317566,-0.06551436098638426,1739141177.228155,16.68998408317566,0.044144459454231885,1739141177.2281566,16.68998408317566,2.1845454852232136 +1739141177.2480433,16.709984064102173,34.184787666454284,1739141177.2480466,16.709984064102173,-0.015687280282308258,1739141177.2480507,16.709984064102173,33.437181607629675,1739141177.2480545,16.709984064102173,41.98382677880337,1739141177.2480564,16.709984064102173,-0.10026617521276972,1739141177.2480586,16.709984064102173,-0.010844358925508025,1739141177.2480605,16.709984064102173,-0.4286690544952484,1739141177.2480621,16.709984064102173,-0.054113170257134025,1739141177.2480638,16.709984064102173,2.106068859668881,1739141177.248066,16.709984064102173,0.0,1739141177.2480679,16.709984064102173,-0.07847662555433255,1739141177.2480695,16.709984064102173,0.044144459454231885,1739141177.2480714,16.709984064102173,2.1845454852232136 +1739141177.2684944,16.729984045028687,34.184787666454284,1739141177.268498,16.729984045028687,-0.015687280282308258,1739141177.268502,16.729984045028687,33.437181607629675,1739141177.2685056,16.729984045028687,41.98382677880337,1739141177.2685077,16.729984045028687,-0.10026617521276972,1739141177.2685099,16.729984045028687,-0.010844358925508025,1739141177.268512,16.729984045028687,-0.4286690544952484,1739141177.2685137,16.729984045028687,-0.054113170257134025,1739141177.2685153,16.729984045028687,2.106068859668881,1739141177.2685177,16.729984045028687,0.0,1739141177.2685196,16.729984045028687,-0.07847662555433255,1739141177.2685215,16.729984045028687,0.044144459454231885,1739141177.2685232,16.729984045028687,2.1845454852232136 +1739141177.2881508,16.7499840259552,34.184787666454284,1739141177.2881541,16.7499840259552,-0.015687280282308258,1739141177.288158,16.7499840259552,33.437181607629675,1739141177.2881615,16.7499840259552,41.98382677880337,1739141177.2881634,16.7499840259552,-0.10026617521276972,1739141177.2881656,16.7499840259552,-0.010844358925508025,1739141177.2881675,16.7499840259552,-0.4286690544952484,1739141177.2881691,16.7499840259552,-0.054113170257134025,1739141177.2881708,16.7499840259552,2.106068859668881,1739141177.288173,16.7499840259552,0.0,1739141177.288175,16.7499840259552,-0.07847662555433255,1739141177.288177,16.7499840259552,0.044144459454231885,1739141177.2881784,16.7499840259552,2.1845454852232136 +1739141177.30889,16.769984006881714,34.184787666454284,1739141177.308894,16.769984006881714,-0.015687280282308258,1739141177.308898,16.769984006881714,33.437181607629675,1739141177.3089018,16.769984006881714,41.98382677880337,1739141177.3089037,16.769984006881714,-0.10026617521276972,1739141177.308906,16.769984006881714,-0.010844358925508025,1739141177.3089077,16.769984006881714,-0.4286690544952484,1739141177.3089094,16.769984006881714,-0.054113170257134025,1739141177.308911,16.769984006881714,2.106068859668881,1739141177.3089135,16.769984006881714,0.0,1739141177.3089151,16.769984006881714,-0.07847662555433255,1739141177.3089173,16.769984006881714,0.044144459454231885,1739141177.3089187,16.769984006881714,2.1845454852232136 +1739141177.3281448,16.789983987808228,34.42443516092936,1739141177.3281484,16.789983987808228,-0.005167675169223784,1739141177.3281524,16.789983987808228,33.70510397932172,1739141177.328156,16.789983987808228,42.22631154466432,1739141177.328158,16.789983987808228,-0.10422711084547115,1739141177.32816,16.789983987808228,-0.012696191041196188,1739141177.328162,16.789983987808228,-0.43827701159306215,1739141177.3281639,16.789983987808228,-0.05528312844460884,1739141177.3281653,16.789983987808228,2.097990385439437,1739141177.3281674,16.789983987808228,0.0,1739141177.3281696,16.789983987808228,-0.07773482872347863,1739141177.328171,16.789983987808228,0.04350470892508082,1739141177.3281727,16.789983987808228,2.176078450925494 +1739141177.348142,16.80998396873474,34.42443516092936,1739141177.3481455,16.80998396873474,-0.005167675169223784,1739141177.3481493,16.80998396873474,33.70510397932172,1739141177.348153,16.80998396873474,42.22631154466432,1739141177.348155,16.80998396873474,-0.10422711084547115,1739141177.3481572,16.80998396873474,-0.012696191041196188,1739141177.3481593,16.80998396873474,-0.43827701159306215,1739141177.3481607,16.80998396873474,-0.05528312844460884,1739141177.3481627,16.80998396873474,2.097990385439437,1739141177.3481648,16.80998396873474,0.0,1739141177.3481667,16.80998396873474,-0.07808806548605673,1739141177.3481686,16.80998396873474,0.04350470892508082,1739141177.3481705,16.80998396873474,2.176078450925494 +1739141177.3683352,16.829983949661255,34.42443516092936,1739141177.368339,16.829983949661255,-0.005167675169223784,1739141177.3683426,16.829983949661255,33.70510397932172,1739141177.3683462,16.829983949661255,42.22631154466432,1739141177.368348,16.829983949661255,-0.10422711084547115,1739141177.3683503,16.829983949661255,-0.012696191041196188,1739141177.368352,16.829983949661255,-0.43827701159306215,1739141177.3683538,16.829983949661255,-0.05528312844460884,1739141177.3683553,16.829983949661255,2.097990385439437,1739141177.368358,16.829983949661255,0.0,1739141177.3683596,16.829983949661255,-0.07808806548605673,1739141177.3683612,16.829983949661255,0.04350470892508082,1739141177.368363,16.829983949661255,2.176078450925494 +1739141177.388246,16.84998393058777,34.42443516092936,1739141177.3882496,16.84998393058777,-0.005167675169223784,1739141177.3882537,16.84998393058777,33.70510397932172,1739141177.3882577,16.84998393058777,42.22631154466432,1739141177.3882604,16.84998393058777,-0.10422711084547115,1739141177.388263,16.84998393058777,-0.012696191041196188,1739141177.3882654,16.84998393058777,-0.43827701159306215,1739141177.3882673,16.84998393058777,-0.05528312844460884,1739141177.388269,16.84998393058777,2.097990385439437,1739141177.388271,16.84998393058777,0.0,1739141177.3882735,16.84998393058777,-0.07808806548605673,1739141177.3882754,16.84998393058777,0.04350470892508082,1739141177.3882778,16.84998393058777,2.176078450925494 +1739141177.4084246,16.869983911514282,34.42443516092936,1739141177.408429,16.869983911514282,-0.005167675169223784,1739141177.4084332,16.869983911514282,33.70510397932172,1739141177.408437,16.869983911514282,42.22631154466432,1739141177.4084387,16.869983911514282,-0.10422711084547115,1739141177.408441,16.869983911514282,-0.012696191041196188,1739141177.4084435,16.869983911514282,-0.43827701159306215,1739141177.4084451,16.869983911514282,-0.05528312844460884,1739141177.4084468,16.869983911514282,2.097990385439437,1739141177.408449,16.869983911514282,0.0,1739141177.408451,16.869983911514282,-0.07808806548605673,1739141177.4084527,16.869983911514282,0.04350470892508082,1739141177.4084547,16.869983911514282,2.176078450925494 +1739141177.4280202,16.889983892440796,34.42443516092936,1739141177.4280236,16.889983892440796,-0.005167675169223784,1739141177.4280274,16.889983892440796,33.70510397932172,1739141177.428031,16.889983892440796,42.22631154466432,1739141177.428033,16.889983892440796,-0.10422711084547115,1739141177.428035,16.889983892440796,-0.012696191041196188,1739141177.428037,16.889983892440796,-0.43827701159306215,1739141177.4280386,16.889983892440796,-0.05528312844460884,1739141177.4280403,16.889983892440796,2.097990385439437,1739141177.4280422,16.889983892440796,0.0,1739141177.4280443,16.889983892440796,-0.07808806548605673,1739141177.4280457,16.889983892440796,0.04350470892508082,1739141177.428048,16.889983892440796,2.176078450925494 +1739141177.4480546,16.90998387336731,34.66315327413841,1739141177.448058,16.90998387336731,0.0051507244229309634,1739141177.448062,16.90998387336731,33.95799813701776,1739141177.4480658,16.90998387336731,42.45355005530556,1739141177.4480677,16.90998387336731,-0.10761862853540319,1739141177.4480698,16.90998387336731,-0.014474420318190583,1739141177.4480717,16.90998387336731,-0.44621068605364883,1739141177.4480734,16.90998387336731,-0.05644685952953073,1739141177.448075,16.90998387336731,2.0913430295139603,1739141177.448077,16.90998387336731,0.0,1739141177.448079,16.90998387336731,-0.07446976630506172,1739141177.4480808,16.90998387336731,0.04282795056778081,1739141177.4480827,16.90998387336731,2.1675357962897337 +1739141177.468114,16.929983854293823,34.66315327413841,1739141177.4681184,16.929983854293823,0.0051507244229309634,1739141177.4681225,16.929983854293823,33.95799813701776,1739141177.468126,16.929983854293823,42.45355005530556,1739141177.468128,16.929983854293823,-0.10761862853540319,1739141177.46813,16.929983854293823,-0.014474420318190583,1739141177.4681318,16.929983854293823,-0.44621068605364883,1739141177.4681337,16.929983854293823,-0.05644685952953073,1739141177.4681354,16.929983854293823,2.0913430295139603,1739141177.4681373,16.929983854293823,0.0,1739141177.468139,16.929983854293823,-0.07619276677577336,1739141177.4681408,16.929983854293823,0.04282795056778081,1739141177.4681423,16.929983854293823,2.1675357962897337 +1739141177.487999,16.949983835220337,34.66315327413841,1739141177.4880023,16.949983835220337,0.0051507244229309634,1739141177.488006,16.949983835220337,33.95799813701776,1739141177.48801,16.949983835220337,42.45355005530556,1739141177.488012,16.949983835220337,-0.10761862853540319,1739141177.4880142,16.949983835220337,-0.014474420318190583,1739141177.4880164,16.949983835220337,-0.44621068605364883,1739141177.488018,16.949983835220337,-0.05644685952953073,1739141177.4880195,16.949983835220337,2.0913430295139603,1739141177.4880211,16.949983835220337,0.0,1739141177.4880235,16.949983835220337,-0.07619276677577336,1739141177.4880254,16.949983835220337,0.04282795056778081,1739141177.488027,16.949983835220337,2.1675357962897337 +1739141177.5079937,16.96998381614685,34.66315327413841,1739141177.5079966,16.96998381614685,0.0051507244229309634,1739141177.5080006,16.96998381614685,33.95799813701776,1739141177.5080035,16.96998381614685,42.45355005530556,1739141177.5080051,16.96998381614685,-0.10761862853540319,1739141177.508007,16.96998381614685,-0.014474420318190583,1739141177.508009,16.96998381614685,-0.44621068605364883,1739141177.5080104,16.96998381614685,-0.05644685952953073,1739141177.508012,16.96998381614685,2.0913430295139603,1739141177.508014,16.96998381614685,0.0,1739141177.5080159,16.96998381614685,-0.07619276677577336,1739141177.5080178,16.96998381614685,0.04282795056778081,1739141177.5080192,16.96998381614685,2.1675357962897337 +1739141177.5278327,16.989983797073364,34.66315327413841,1739141177.5278356,16.989983797073364,0.0051507244229309634,1739141177.527839,16.989983797073364,33.95799813701776,1739141177.5278425,16.989983797073364,42.45355005530556,1739141177.5278444,16.989983797073364,-0.10761862853540319,1739141177.5278463,16.989983797073364,-0.014474420318190583,1739141177.527848,16.989983797073364,-0.44621068605364883,1739141177.5278494,16.989983797073364,-0.05644685952953073,1739141177.5278509,16.989983797073364,2.0913430295139603,1739141177.5278525,16.989983797073364,0.0,1739141177.5278544,16.989983797073364,-0.07619276677577336,1739141177.5278556,16.989983797073364,0.04282795056778081,1739141177.527857,16.989983797073364,2.1675357962897337 +1739141177.5479867,17.009983777999878,34.90095125752977,1739141177.5479898,17.009983777999878,0.015262349468032177,1739141177.5479937,17.009983777999878,34.1958409902474,1739141177.5479975,17.009983777999878,42.66639475898146,1739141177.5479994,17.009983777999878,-0.11181969819765265,1739141177.5480018,17.009983777999878,-0.016363612021996553,1739141177.548004,17.009983777999878,-0.45367772868987666,1739141177.5480056,17.009983777999878,-0.05775720834831673,1739141177.548007,17.009983777999878,2.085105889721201,1739141177.5480087,17.009983777999878,0.0,1739141177.5480108,17.009983777999878,-0.0722184999834821,1739141177.5480125,17.009983777999878,0.04208448120555008,1739141177.5480146,17.009983777999878,2.1592168986464033 +1739141177.568022,17.02998375892639,34.90095125752977,1739141177.5680256,17.02998375892639,0.015262349468032177,1739141177.5680296,17.02998375892639,34.1958409902474,1739141177.5680327,17.02998375892639,42.66639475898146,1739141177.5680344,17.02998375892639,-0.11181969819765265,1739141177.5680363,17.02998375892639,-0.016363612021996553,1739141177.568038,17.02998375892639,-0.45367772868987666,1739141177.5680394,17.02998375892639,-0.05775720834831673,1739141177.5680408,17.02998375892639,2.085105889721201,1739141177.568043,17.02998375892639,0.0,1739141177.568045,17.02998375892639,-0.07411100892520217,1739141177.5680463,17.02998375892639,0.04208448120555008,1739141177.5680475,17.02998375892639,2.1592168986464033 +1739141177.5879242,17.049983739852905,34.90095125752977,1739141177.5879276,17.049983739852905,0.015262349468032177,1739141177.5879312,17.049983739852905,34.1958409902474,1739141177.587935,17.049983739852905,42.66639475898146,1739141177.5879374,17.049983739852905,-0.11181969819765265,1739141177.5879397,17.049983739852905,-0.016363612021996553,1739141177.587942,17.049983739852905,-0.45367772868987666,1739141177.587944,17.049983739852905,-0.05775720834831673,1739141177.5879457,17.049983739852905,2.085105889721201,1739141177.5879478,17.049983739852905,0.0,1739141177.5879498,17.049983739852905,-0.07411100892520217,1739141177.5879517,17.049983739852905,0.04208448120555008,1739141177.5879536,17.049983739852905,2.1592168986464033 +1739141177.6079555,17.06998372077942,34.90095125752977,1739141177.607959,17.06998372077942,0.015262349468032177,1739141177.6079628,17.06998372077942,34.1958409902474,1739141177.6079662,17.06998372077942,42.66639475898146,1739141177.607968,17.06998372077942,-0.11181969819765265,1739141177.60797,17.06998372077942,-0.016363612021996553,1739141177.6079717,17.06998372077942,-0.45367772868987666,1739141177.6079733,17.06998372077942,-0.05775720834831673,1739141177.6079748,17.06998372077942,2.085105889721201,1739141177.6079767,17.06998372077942,0.0,1739141177.6079783,17.06998372077942,-0.07411100892520217,1739141177.6079798,17.06998372077942,0.04208448120555008,1739141177.6079817,17.06998372077942,2.1592168986464033 +1739141177.6280534,17.089983701705933,34.90095125752977,1739141177.6280563,17.089983701705933,0.015262349468032177,1739141177.6280599,17.089983701705933,34.1958409902474,1739141177.628063,17.089983701705933,42.66639475898146,1739141177.628065,17.089983701705933,-0.11181969819765265,1739141177.6280668,17.089983701705933,-0.016363612021996553,1739141177.6280687,17.089983701705933,-0.45367772868987666,1739141177.62807,17.089983701705933,-0.05775720834831673,1739141177.6280718,17.089983701705933,2.085105889721201,1739141177.6280735,17.089983701705933,0.0,1739141177.6280751,17.089983701705933,-0.07411100892520217,1739141177.6280766,17.089983701705933,0.04208448120555008,1739141177.628078,17.089983701705933,2.1592168986464033 +1739141177.647692,17.109983682632446,34.90095125752977,1739141177.6476946,17.109983682632446,0.015262349468032177,1739141177.6476982,17.109983682632446,34.1958409902474,1739141177.6477015,17.109983682632446,42.66639475898146,1739141177.647703,17.109983682632446,-0.11181969819765265,1739141177.6477048,17.109983682632446,-0.016363612021996553,1739141177.6477063,17.109983682632446,-0.45367772868987666,1739141177.647708,17.109983682632446,-0.05775720834831673,1739141177.6477094,17.109983682632446,2.085105889721201,1739141177.6477113,17.109983682632446,0.0,1739141177.647713,17.109983682632446,-0.07411100892520217,1739141177.6477146,17.109983682632446,0.04208448120555008,1739141177.647716,17.109983682632446,2.1592168986464033 +1739141177.668214,17.12998366355896,35.137855996334935,1739141177.6682177,17.12998366355896,0.025149312224258757,1739141177.6682215,17.12998366355896,34.33073645472713,1739141177.6682248,17.12998366355896,42.777045521691505,1739141177.6682262,17.12998366355896,-0.11350540120486641,1739141177.6682286,17.12998366355896,-0.018148455395501934,1739141177.66823,17.12998366355896,-0.45357924218937445,1739141177.6682315,17.12998366355896,-0.0596649807979212,1739141177.668233,17.12998366355896,2.0851880332520984,1739141177.6682348,17.12998366355896,0.0,1739141177.6682367,17.12998366355896,-0.05853476385290607,1739141177.6682384,17.12998366355896,0.04125200163687805,1739141177.6682398,17.12998366355896,2.151140060368488 +1739141177.6877828,17.149983644485474,35.137855996334935,1739141177.6877854,17.149983644485474,0.025149312224258757,1739141177.687789,17.149983644485474,34.33073645472713,1739141177.6877923,17.149983644485474,42.777045521691505,1739141177.687794,17.149983644485474,-0.11350540120486641,1739141177.6877959,17.149983644485474,-0.018148455395501934,1739141177.6877975,17.149983644485474,-0.45357924218937445,1739141177.687799,17.149983644485474,-0.0596649807979212,1739141177.6878006,17.149983644485474,2.0851880332520984,1739141177.6878023,17.149983644485474,0.0,1739141177.6878042,17.149983644485474,-0.06595202711638937,1739141177.6878057,17.149983644485474,0.04125200163687805,1739141177.6878076,17.149983644485474,2.151140060368488 +1739141177.7079062,17.169983625411987,35.137855996334935,1739141177.7079096,17.169983625411987,0.025149312224258757,1739141177.7079134,17.169983625411987,34.33073645472713,1739141177.7079167,17.169983625411987,42.777045521691505,1739141177.707919,17.169983625411987,-0.11350540120486641,1739141177.7079213,17.169983625411987,-0.018148455395501934,1739141177.7079227,17.169983625411987,-0.45357924218937445,1739141177.7079244,17.169983625411987,-0.0596649807979212,1739141177.7079258,17.169983625411987,2.0851880332520984,1739141177.7079282,17.169983625411987,0.0,1739141177.7079296,17.169983625411987,-0.06595202711638937,1739141177.7079313,17.169983625411987,0.04125200163687805,1739141177.707933,17.169983625411987,2.151140060368488 +1739141177.7280552,17.1899836063385,35.137855996334935,1739141177.7280583,17.1899836063385,0.025149312224258757,1739141177.7280622,17.1899836063385,34.33073645472713,1739141177.7280653,17.1899836063385,42.777045521691505,1739141177.7280672,17.1899836063385,-0.11350540120486641,1739141177.728069,17.1899836063385,-0.018148455395501934,1739141177.7280707,17.1899836063385,-0.45357924218937445,1739141177.7280722,17.1899836063385,-0.0596649807979212,1739141177.7280738,17.1899836063385,2.0851880332520984,1739141177.7280755,17.1899836063385,0.0,1739141177.7280774,17.1899836063385,-0.06595202711638937,1739141177.7280788,17.1899836063385,0.04125200163687805,1739141177.7280803,17.1899836063385,2.151140060368488 +1739141177.747788,17.209983587265015,35.137855996334935,1739141177.7477908,17.209983587265015,0.025149312224258757,1739141177.7477944,17.209983587265015,34.33073645472713,1739141177.7477977,17.209983587265015,42.777045521691505,1739141177.7477994,17.209983587265015,-0.11350540120486641,1739141177.7478013,17.209983587265015,-0.018148455395501934,1739141177.7478032,17.209983587265015,-0.45357924218937445,1739141177.7478046,17.209983587265015,-0.0596649807979212,1739141177.7478058,17.209983587265015,2.0851880332520984,1739141177.747808,17.209983587265015,0.0,1739141177.74781,17.209983587265015,-0.06595202711638937,1739141177.747811,17.209983587265015,0.04125200163687805,1739141177.7478125,17.209983587265015,2.151140060368488 +1739141177.7680511,17.22998356819153,35.37392778875864,1739141177.7680545,17.22998356819153,0.034797307200562955,1739141177.7680583,17.22998356819153,34.572951849554975,1739141177.7680619,17.22998356819153,42.99776519483951,1739141177.7680635,17.22998356819153,-0.11782483748352783,1739141177.7680655,17.22998356819153,-0.020016397649870003,1739141177.7680671,17.22998356819153,-0.46000018395997,1739141177.7680686,17.22998356819153,-0.060748924527593215,1739141177.7680702,17.22998356819153,2.0798393565237996,1739141177.7680724,17.22998356819153,0.0,1739141177.7680745,17.22998356819153,-0.06251829442137835,1739141177.7680762,17.22998356819153,0.04034525642661168,1739141177.768078,17.22998356819153,2.1439927625691357 +1739141177.787989,17.249983549118042,35.37392778875864,1739141177.7879922,17.249983549118042,0.034797307200562955,1739141177.7879958,17.249983549118042,34.572951849554975,1739141177.7879996,17.249983549118042,42.99776519483951,1739141177.788002,17.249983549118042,-0.11782483748352783,1739141177.7880044,17.249983549118042,-0.020016397649870003,1739141177.7880065,17.249983549118042,-0.46000018395997,1739141177.7880082,17.249983549118042,-0.060748924527593215,1739141177.78801,17.249983549118042,2.0798393565237996,1739141177.7880118,17.249983549118042,0.0,1739141177.788014,17.249983549118042,-0.06415340604533615,1739141177.7880156,17.249983549118042,0.04034525642661168,1739141177.7880177,17.249983549118042,2.1439927625691357 +1739141177.8088248,17.269983530044556,35.37392778875864,1739141177.8088276,17.269983530044556,0.034797307200562955,1739141177.8088312,17.269983530044556,34.572951849554975,1739141177.8088346,17.269983530044556,42.99776519483951,1739141177.8088365,17.269983530044556,-0.11782483748352783,1739141177.8088381,17.269983530044556,-0.020016397649870003,1739141177.8088398,17.269983530044556,-0.46000018395997,1739141177.8088415,17.269983530044556,-0.060748924527593215,1739141177.8088427,17.269983530044556,2.0798393565237996,1739141177.8088448,17.269983530044556,0.0,1739141177.8088465,17.269983530044556,-0.06415340604533615,1739141177.8088481,17.269983530044556,0.04034525642661168,1739141177.8088493,17.269983530044556,2.1439927625691357 +1739141177.8277931,17.28998351097107,35.37392778875864,1739141177.8277962,17.28998351097107,0.034797307200562955,1739141177.8277996,17.28998351097107,34.572951849554975,1739141177.8278027,17.28998351097107,42.99776519483951,1739141177.8278043,17.28998351097107,-0.11782483748352783,1739141177.8278065,17.28998351097107,-0.020016397649870003,1739141177.8278086,17.28998351097107,-0.46000018395997,1739141177.82781,17.28998351097107,-0.060748924527593215,1739141177.8278115,17.28998351097107,2.0798393565237996,1739141177.8278134,17.28998351097107,0.0,1739141177.827815,17.28998351097107,-0.06415340604533615,1739141177.8278165,17.28998351097107,0.04034525642661168,1739141177.827818,17.28998351097107,2.1439927625691357 +1739141177.847872,17.309983491897583,35.37392778875864,1739141177.847875,17.309983491897583,0.034797307200562955,1739141177.8478785,17.309983491897583,34.572951849554975,1739141177.8478818,17.309983491897583,42.99776519483951,1739141177.8478832,17.309983491897583,-0.11782483748352783,1739141177.8478854,17.309983491897583,-0.020016397649870003,1739141177.8478873,17.309983491897583,-0.46000018395997,1739141177.8478887,17.309983491897583,-0.060748924527593215,1739141177.8478901,17.309983491897583,2.0798393565237996,1739141177.847892,17.309983491897583,0.0,1739141177.8478937,17.309983491897583,-0.06415340604533615,1739141177.8478954,17.309983491897583,0.04034525642661168,1739141177.8478968,17.309983491897583,2.1439927625691357 +1739141177.8680227,17.329983472824097,35.37392778875864,1739141177.8680263,17.329983472824097,0.034797307200562955,1739141177.8680305,17.329983472824097,34.572951849554975,1739141177.8680341,17.329983472824097,42.99776519483951,1739141177.868036,17.329983472824097,-0.11782483748352783,1739141177.8680382,17.329983472824097,-0.020016397649870003,1739141177.8680396,17.329983472824097,-0.46000018395997,1739141177.8680413,17.329983472824097,-0.060748924527593215,1739141177.868043,17.329983472824097,2.0798393565237996,1739141177.868045,17.329983472824097,0.0,1739141177.8680468,17.329983472824097,-0.06415340604533615,1739141177.8680484,17.329983472824097,0.04034525642661168,1739141177.8680499,17.329983472824097,2.1439927625691357 +1739141177.8880177,17.34998345375061,35.60923053948027,1739141177.8880208,17.34998345375061,0.04419714057631374,1739141177.888024,17.34998345375061,35.24434695167783,1739141177.888028,17.34998345375061,43.64810699370895,1739141177.88803,17.34998345375061,-0.12734213987417897,1739141177.888032,17.34998345375061,-0.02133547545687775,1739141177.888034,17.34998345375061,-0.48824580659667005,1739141177.8880358,17.34998345375061,-0.05799055024585715,1739141177.8880374,17.34998345375061,2.056473061151647,1739141177.8880394,17.34998345375061,0.0,1739141177.8880415,17.34998345375061,-0.09541383118190128,1739141177.8880434,17.34998345375061,0.03942365630796166,1739141177.8880453,17.34998345375061,2.137000968165681 +1739141177.9080765,17.369983434677124,35.60923053948027,1739141177.9080799,17.369983434677124,0.04419714057631374,1739141177.908084,17.369983434677124,35.24434695167783,1739141177.9080875,17.369983434677124,43.64810699370895,1739141177.9080894,17.369983434677124,-0.12734213987417897,1739141177.9080915,17.369983434677124,-0.02133547545687775,1739141177.9080932,17.369983434677124,-0.48824580659667005,1739141177.908095,17.369983434677124,-0.05799055024585715,1739141177.9080963,17.369983434677124,2.056473061151647,1739141177.9080982,17.369983434677124,0.0,1739141177.9081001,17.369983434677124,-0.08052790701403412,1739141177.9081016,17.369983434677124,0.03942365630796166,1739141177.9081032,17.369983434677124,2.137000968165681 +1739141177.9278822,17.389983415603638,35.60923053948027,1739141177.9278874,17.389983415603638,0.04419714057631374,1739141177.9279788,17.389983415603638,35.24434695167783,1739141177.9279847,17.389983415603638,43.64810699370895,1739141177.9279869,17.389983415603638,-0.12734213987417897,1739141177.9279897,17.389983415603638,-0.02133547545687775,1739141177.9279916,17.389983415603638,-0.48824580659667005,1739141177.927993,17.389983415603638,-0.05799055024585715,1739141177.927995,17.389983415603638,2.056473061151647,1739141177.9279964,17.389983415603638,0.0,1739141177.9279985,17.389983415603638,-0.08052790701403412,1739141177.9280002,17.389983415603638,0.03942365630796166,1739141177.9280019,17.389983415603638,2.137000968165681 +1739141177.947809,17.40998339653015,35.60923053948027,1739141177.947812,17.40998339653015,0.04419714057631374,1739141177.9478154,17.40998339653015,35.24434695167783,1739141177.9478185,17.40998339653015,43.64810699370895,1739141177.94782,17.40998339653015,-0.12734213987417897,1739141177.947822,17.40998339653015,-0.02133547545687775,1739141177.9478235,17.40998339653015,-0.48824580659667005,1739141177.9478252,17.40998339653015,-0.05799055024585715,1739141177.9478266,17.40998339653015,2.056473061151647,1739141177.9478285,17.40998339653015,0.0,1739141177.9478302,17.40998339653015,-0.08052790701403412,1739141177.9478316,17.40998339653015,0.03942365630796166,1739141177.947833,17.40998339653015,2.137000968165681 +1739141177.9680293,17.429983377456665,35.60923053948027,1739141177.9680328,17.429983377456665,0.04419714057631374,1739141177.9680364,17.429983377456665,35.24434695167783,1739141177.9680395,17.429983377456665,43.64810699370895,1739141177.9680412,17.429983377456665,-0.12734213987417897,1739141177.9680433,17.429983377456665,-0.02133547545687775,1739141177.9680448,17.429983377456665,-0.48824580659667005,1739141177.9680467,17.429983377456665,-0.05799055024585715,1739141177.9680483,17.429983377456665,2.056473061151647,1739141177.9680502,17.429983377456665,0.0,1739141177.9680517,17.429983377456665,-0.08052790701403412,1739141177.9680536,17.429983377456665,0.03942365630796166,1739141177.968055,17.429983377456665,2.137000968165681 +1739141177.9879165,17.44998335838318,35.84367224590362,1739141177.9879193,17.44998335838318,0.0533461960548145,1739141177.9879231,17.44998335838318,35.27999124010965,1739141177.9879267,17.44998335838318,43.65691796224972,1739141177.9879289,17.44998335838318,-0.12751835924499444,1739141177.9879313,17.44998335838318,-0.023144320141602875,1739141177.9879332,17.44998335838318,-0.48148222089724735,1739141177.987935,17.44998335838318,-0.060532263215871754,1739141177.987937,17.44998335838318,2.0620442467067654,1739141177.9879391,17.44998335838318,0.0,1739141177.987941,17.44998335838318,-0.05281736699598391,1739141177.9879432,17.44998335838318,0.038502056189311636,1739141177.9879453,17.44998335838318,2.1280571155411696 +1739141178.008242,17.469983339309692,35.84367224590362,1739141178.0082455,17.469983339309692,0.0533461960548145,1739141178.0082493,17.469983339309692,35.27999124010965,1739141178.0082529,17.469983339309692,43.65691796224972,1739141178.0082545,17.469983339309692,-0.12751835924499444,1739141178.0082564,17.469983339309692,-0.023144320141602875,1739141178.0082583,17.469983339309692,-0.48148222089724735,1739141178.0082598,17.469983339309692,-0.060532263215871754,1739141178.0082614,17.469983339309692,2.0620442467067654,1739141178.008263,17.469983339309692,0.0,1739141178.008265,17.469983339309692,-0.06601286883440416,1739141178.0082664,17.469983339309692,0.038502056189311636,1739141178.008268,17.469983339309692,2.1280571155411696 +1739141178.0278983,17.489983320236206,35.84367224590362,1739141178.0279012,17.489983320236206,0.0533461960548145,1739141178.0279045,17.489983320236206,35.27999124010965,1739141178.0279078,17.489983320236206,43.65691796224972,1739141178.0279093,17.489983320236206,-0.12751835924499444,1739141178.0279112,17.489983320236206,-0.023144320141602875,1739141178.0279126,17.489983320236206,-0.48148222089724735,1739141178.027914,17.489983320236206,-0.060532263215871754,1739141178.0279155,17.489983320236206,2.0620442467067654,1739141178.0279176,17.489983320236206,0.0,1739141178.027919,17.489983320236206,-0.06601286883440416,1739141178.0279207,17.489983320236206,0.038502056189311636,1739141178.0279224,17.489983320236206,2.1280571155411696 +1739141178.0480373,17.50998330116272,35.84367224590362,1739141178.0480404,17.50998330116272,0.0533461960548145,1739141178.0480442,17.50998330116272,35.27999124010965,1739141178.0480485,17.50998330116272,43.65691796224972,1739141178.0480502,17.50998330116272,-0.12751835924499444,1739141178.0480528,17.50998330116272,-0.023144320141602875,1739141178.0480545,17.50998330116272,-0.48148222089724735,1739141178.0480564,17.50998330116272,-0.060532263215871754,1739141178.0480578,17.50998330116272,2.0620442467067654,1739141178.0480595,17.50998330116272,0.0,1739141178.0480614,17.50998330116272,-0.06601286883440416,1739141178.0480635,17.50998330116272,0.038502056189311636,1739141178.0480652,17.50998330116272,2.1280571155411696 +1739141178.068108,17.529983282089233,35.84367224590362,1739141178.068115,17.529983282089233,0.0533461960548145,1739141178.0681224,17.529983282089233,35.27999124010965,1739141178.0681295,17.529983282089233,43.65691796224972,1739141178.0681317,17.529983282089233,-0.12751835924499444,1739141178.0681336,17.529983282089233,-0.023144320141602875,1739141178.0681355,17.529983282089233,-0.48148222089724735,1739141178.068137,17.529983282089233,-0.060532263215871754,1739141178.0681386,17.529983282089233,2.0620442467067654,1739141178.0681405,17.529983282089233,0.0,1739141178.0681424,17.529983282089233,-0.06601286883440416,1739141178.0681436,17.529983282089233,0.038502056189311636,1739141178.0681455,17.529983282089233,2.1280571155411696 +1739141178.0878701,17.549983263015747,35.84367224590362,1739141178.087873,17.549983263015747,0.0533461960548145,1739141178.0878763,17.549983263015747,35.27999124010965,1739141178.0878797,17.549983263015747,43.65691796224972,1739141178.0878813,17.549983263015747,-0.12751835924499444,1739141178.0878832,17.549983263015747,-0.023144320141602875,1739141178.087885,17.549983263015747,-0.48148222089724735,1739141178.0878863,17.549983263015747,-0.060532263215871754,1739141178.0878878,17.549983263015747,2.0620442467067654,1739141178.0878897,17.549983263015747,0.0,1739141178.0878913,17.549983263015747,-0.06601286883440416,1739141178.087893,17.549983263015747,0.038502056189311636,1739141178.0878944,17.549983263015747,2.1280571155411696 +1739141178.1081572,17.56998324394226,36.07725194036916,1739141178.1081607,17.56998324394226,0.06224600793666646,1739141178.108164,17.56998324394226,35.3155042534803,1739141178.1081676,17.56998324394226,43.67152909739135,1739141178.1081693,17.56998324394226,-0.12781058194782702,1739141178.1081712,17.56998324394226,-0.025021068156120152,1739141178.1081731,17.56998324394226,-0.47525162482269295,1739141178.1081743,17.56998324394226,-0.06323764583609034,1739141178.1081758,17.56998324394226,2.0671897618843937,1739141178.108178,17.56998324394226,0.0,1739141178.1081796,17.56998324394226,-0.04289026626196494,1739141178.108181,17.56998324394226,0.037580456070661614,1739141178.1081824,17.56998324394226,2.1210907967764516 +1739141178.127867,17.589983224868774,36.07725194036916,1739141178.1278696,17.589983224868774,0.06224600793666646,1739141178.127873,17.589983224868774,35.3155042534803,1739141178.127876,17.589983224868774,43.67152909739135,1739141178.127878,17.589983224868774,-0.12781058194782702,1739141178.1278796,17.589983224868774,-0.025021068156120152,1739141178.1278815,17.589983224868774,-0.47525162482269295,1739141178.127883,17.589983224868774,-0.06323764583609034,1739141178.1278846,17.589983224868774,2.0671897618843937,1739141178.1278863,17.589983224868774,0.0,1739141178.1278882,17.589983224868774,-0.053901034892057886,1739141178.1278896,17.589983224868774,0.037580456070661614,1739141178.1278908,17.589983224868774,2.1210907967764516 +1739141178.1480246,17.609983205795288,36.07725194036916,1739141178.148028,17.609983205795288,0.06224600793666646,1739141178.1480312,17.609983205795288,35.3155042534803,1739141178.1480343,17.609983205795288,43.67152909739135,1739141178.148036,17.609983205795288,-0.12781058194782702,1739141178.148038,17.609983205795288,-0.025021068156120152,1739141178.1480393,17.609983205795288,-0.47525162482269295,1739141178.1480412,17.609983205795288,-0.06323764583609034,1739141178.1480427,17.609983205795288,2.0671897618843937,1739141178.1480446,17.609983205795288,0.0,1739141178.1480463,17.609983205795288,-0.053901034892057886,1739141178.148048,17.609983205795288,0.037580456070661614,1739141178.1480494,17.609983205795288,2.1210907967764516 +1739141178.168118,17.6299831867218,36.07725194036916,1739141178.1681216,17.6299831867218,0.06224600793666646,1739141178.1681254,17.6299831867218,35.3155042534803,1739141178.1681287,17.6299831867218,43.67152909739135,1739141178.1681306,17.6299831867218,-0.12781058194782702,1739141178.1681325,17.6299831867218,-0.025021068156120152,1739141178.1681347,17.6299831867218,-0.47525162482269295,1739141178.1681361,17.6299831867218,-0.06323764583609034,1739141178.1681378,17.6299831867218,2.0671897618843937,1739141178.1681397,17.6299831867218,0.0,1739141178.1681416,17.6299831867218,-0.053901034892057886,1739141178.168143,17.6299831867218,0.037580456070661614,1739141178.1681447,17.6299831867218,2.1210907967764516 +1739141178.187903,17.649983167648315,36.07725194036916,1739141178.1879058,17.649983167648315,0.06224600793666646,1739141178.1879094,17.649983167648315,35.3155042534803,1739141178.1879125,17.649983167648315,43.67152909739135,1739141178.1879141,17.649983167648315,-0.12781058194782702,1739141178.187916,17.649983167648315,-0.025021068156120152,1739141178.1879175,17.649983167648315,-0.47525162482269295,1739141178.1879191,17.649983167648315,-0.06323764583609034,1739141178.1879206,17.649983167648315,2.0671897618843937,1739141178.187923,17.649983167648315,0.0,1739141178.1879246,17.649983167648315,-0.053901034892057886,1739141178.1879263,17.649983167648315,0.037580456070661614,1739141178.1879277,17.649983167648315,2.1210907967764516 +1739141178.2081387,17.66998314857483,36.31012283783255,1739141178.2081418,17.66998314857483,0.07089820741417707,1739141178.2081456,17.66998314857483,35.56772074626215,1739141178.2081487,17.66998314857483,43.906323388073844,1739141178.2081506,17.66998314857483,-0.13147175025888802,1739141178.2081525,17.66998314857483,-0.026634644521682946,1739141178.2081544,17.66998314857483,-0.4801315882182604,1739141178.2081559,17.66998314857483,-0.06384912464379844,1739141178.2081575,17.66998314857483,2.0631585734269264,1739141178.2081594,17.66998314857483,0.0,1739141178.2081614,17.66998314857483,-0.050530073266901926,1739141178.2081628,17.66998314857483,0.03659186221863315,1739141178.2081645,17.66998314857483,2.115293867317209 +1739141178.2280045,17.689983129501343,36.31012283783255,1739141178.2280073,17.689983129501343,0.07089820741417707,1739141178.2280107,17.689983129501343,35.56772074626215,1739141178.2280138,17.689983129501343,43.906323388073844,1739141178.2280154,17.689983129501343,-0.13147175025888802,1739141178.2280173,17.689983129501343,-0.026634644521682946,1739141178.228019,17.689983129501343,-0.4801315882182604,1739141178.2280204,17.689983129501343,-0.06384912464379844,1739141178.228022,17.689983129501343,2.0631585734269264,1739141178.2280238,17.689983129501343,0.0,1739141178.2280254,17.689983129501343,-0.0521352938902826,1739141178.2280269,17.689983129501343,0.03659186221863315,1739141178.2280283,17.689983129501343,2.115293867317209 +1739141178.2478428,17.709983110427856,36.31012283783255,1739141178.247846,17.709983110427856,0.07089820741417707,1739141178.2478492,17.709983110427856,35.56772074626215,1739141178.2478523,17.709983110427856,43.906323388073844,1739141178.247854,17.709983110427856,-0.13147175025888802,1739141178.2478561,17.709983110427856,-0.026634644521682946,1739141178.2478576,17.709983110427856,-0.4801315882182604,1739141178.2478592,17.709983110427856,-0.06384912464379844,1739141178.2478607,17.709983110427856,2.0631585734269264,1739141178.2478628,17.709983110427856,0.0,1739141178.2478645,17.709983110427856,-0.0521352938902826,1739141178.2478662,17.709983110427856,0.03659186221863315,1739141178.2478676,17.709983110427856,2.115293867317209 +1739141178.2694807,17.72998309135437,36.31012283783255,1739141178.2694852,17.72998309135437,0.07089820741417707,1739141178.2694905,17.72998309135437,35.56772074626215,1739141178.2694962,17.72998309135437,43.906323388073844,1739141178.2694993,17.72998309135437,-0.13147175025888802,1739141178.269503,17.72998309135437,-0.026634644521682946,1739141178.2695065,17.72998309135437,-0.4801315882182604,1739141178.2695096,17.72998309135437,-0.06384912464379844,1739141178.2695122,17.72998309135437,2.0631585734269264,1739141178.2695153,17.72998309135437,0.0,1739141178.2695186,17.72998309135437,-0.0521352938902826,1739141178.2695217,17.72998309135437,0.03659186221863315,1739141178.2695246,17.72998309135437,2.115293867317209 +1739141178.2891324,17.749983072280884,36.31012283783255,1739141178.2891366,17.749983072280884,0.07089820741417707,1739141178.289141,17.749983072280884,35.56772074626215,1739141178.289145,17.749983072280884,43.906323388073844,1739141178.2891471,17.749983072280884,-0.13147175025888802,1739141178.2891498,17.749983072280884,-0.026634644521682946,1739141178.2891521,17.749983072280884,-0.4801315882182604,1739141178.2891545,17.749983072280884,-0.06384912464379844,1739141178.289157,17.749983072280884,2.0631585734269264,1739141178.2891595,17.749983072280884,0.0,1739141178.2891617,17.749983072280884,-0.0521352938902826,1739141178.2891638,17.749983072280884,0.03659186221863315,1739141178.2891665,17.749983072280884,2.115293867317209 +1739141178.309236,17.769983053207397,36.31012283783255,1739141178.3092437,17.769983053207397,0.07089820741417707,1739141178.309251,17.769983053207397,35.56772074626215,1739141178.3092604,17.769983053207397,43.906323388073844,1739141178.3092647,17.769983053207397,-0.13147175025888802,1739141178.3092687,17.769983053207397,-0.026634644521682946,1739141178.309273,17.769983053207397,-0.4801315882182604,1739141178.3092768,17.769983053207397,-0.06384912464379844,1739141178.3092804,17.769983053207397,2.0631585734269264,1739141178.3092847,17.769983053207397,0.0,1739141178.3092885,17.769983053207397,-0.0521352938902826,1739141178.3092928,17.769983053207397,0.03659186221863315,1739141178.3092957,17.769983053207397,2.115293867317209 +1739141178.3286614,17.78998303413391,36.542370775809765,1739141178.3286653,17.78998303413391,0.07928728324775225,1739141178.3286695,17.78998303413391,35.710050995247805,1739141178.328674,17.78998303413391,44.03161364031222,1739141178.328676,17.78998303413391,-0.13286388615727715,1739141178.328679,17.78998303413391,-0.028319878795722158,1739141178.328682,17.78998303413391,-0.4779337873088654,1739141178.3286843,17.78998303413391,-0.0653786587912239,1739141178.3286862,17.78998303413391,2.0649731356349164,1739141178.3286889,17.78998303413391,0.0,1739141178.3286912,17.78998303413391,-0.037833837356345525,1739141178.3286934,17.78998303413391,0.03551390984611595,1739141178.3286958,17.78998303413391,2.1096171937903776 +1739141178.3479002,17.809983015060425,36.542370775809765,1739141178.3479033,17.809983015060425,0.07928728324775225,1739141178.347906,17.809983015060425,35.710050995247805,1739141178.347909,17.809983015060425,44.03161364031222,1739141178.3479102,17.809983015060425,-0.13286388615727715,1739141178.3479116,17.809983015060425,-0.028319878795722158,1739141178.3479133,17.809983015060425,-0.4779337873088654,1739141178.3479142,17.809983015060425,-0.0653786587912239,1739141178.3479154,17.809983015060425,2.0649731356349164,1739141178.347917,17.809983015060425,0.0,1739141178.3479185,17.809983015060425,-0.04464405815546124,1739141178.34792,17.809983015060425,0.03551390984611595,1739141178.3479211,17.809983015060425,2.1096171937903776 +1739141178.3684866,17.82998299598694,36.542370775809765,1739141178.3684893,17.82998299598694,0.07928728324775225,1739141178.3684921,17.82998299598694,35.710050995247805,1739141178.368495,17.82998299598694,44.03161364031222,1739141178.3684964,17.82998299598694,-0.13286388615727715,1739141178.368498,17.82998299598694,-0.028319878795722158,1739141178.3684998,17.82998299598694,-0.4779337873088654,1739141178.368501,17.82998299598694,-0.0653786587912239,1739141178.3685024,17.82998299598694,2.0649731356349164,1739141178.3685038,17.82998299598694,0.0,1739141178.368505,17.82998299598694,-0.04464405815546124,1739141178.3685067,17.82998299598694,0.03551390984611595,1739141178.3685079,17.82998299598694,2.1096171937903776 +1739141178.3896542,17.849982976913452,36.542370775809765,1739141178.3896594,17.849982976913452,0.07928728324775225,1739141178.3896646,17.849982976913452,35.710050995247805,1739141178.3896723,17.849982976913452,44.03161364031222,1739141178.3896754,17.849982976913452,-0.13286388615727715,1739141178.3896792,17.849982976913452,-0.028319878795722158,1739141178.3896823,17.849982976913452,-0.4779337873088654,1739141178.389685,17.849982976913452,-0.0653786587912239,1739141178.3896878,17.849982976913452,2.0649731356349164,1739141178.389693,17.849982976913452,0.0,1739141178.3896964,17.849982976913452,-0.04464405815546124,1739141178.3897,17.849982976913452,0.03551390984611595,1739141178.389704,17.849982976913452,2.1096171937903776 +1739141178.4080296,17.869982957839966,36.542370775809765,1739141178.4080317,17.869982957839966,0.07928728324775225,1739141178.408034,17.869982957839966,35.710050995247805,1739141178.4080367,17.869982957839966,44.03161364031222,1739141178.408038,17.869982957839966,-0.13286388615727715,1739141178.4080393,17.869982957839966,-0.028319878795722158,1739141178.4080408,17.869982957839966,-0.4779337873088654,1739141178.4080417,17.869982957839966,-0.0653786587912239,1739141178.4080427,17.869982957839966,2.0649731356349164,1739141178.4080446,17.869982957839966,0.0,1739141178.4080458,17.869982957839966,-0.04464405815546124,1739141178.4080472,17.869982957839966,0.03551390984611595,1739141178.4080482,17.869982957839966,2.1096171937903776 +1739141178.4277213,17.88998293876648,36.77404644390967,1739141178.4277232,17.88998293876648,0.08739840151077871,1739141178.427726,17.88998293876648,36.31261472156817,1739141178.427729,17.88998293876648,44.619665428678765,1739141178.42773,17.88998293876648,-0.13981692974326856,1739141178.4277318,17.88998293876648,-0.02895269828097701,1739141178.427733,17.88998293876648,-0.4966147634191309,1739141178.427734,17.88998293876648,-0.06190142936806528,1739141178.4277353,17.88998293876648,2.049600357339941,1739141178.4277368,17.88998293876648,0.0,1739141178.4277382,17.88998293876648,-0.06478612948654361,1739141178.4277394,17.88998293876648,0.03436141931081716,1739141178.4277406,17.88998293876648,2.104795019496517 +1739141178.4477015,17.909982919692993,36.77404644390967,1739141178.4477038,17.909982919692993,0.08739840151077871,1739141178.4477065,17.909982919692993,36.31261472156817,1739141178.447709,17.909982919692993,44.619665428678765,1739141178.4477105,17.909982919692993,-0.13981692974326856,1739141178.447712,17.909982919692993,-0.02895269828097701,1739141178.4477131,17.909982919692993,-0.4966147634191309,1739141178.4477143,17.909982919692993,-0.06190142936806528,1739141178.4477153,17.909982919692993,2.049600357339941,1739141178.447717,17.909982919692993,0.0,1739141178.4477181,17.909982919692993,-0.05519466215657598,1739141178.4477193,17.909982919692993,0.03436141931081716,1739141178.4477205,17.909982919692993,2.104795019496517 +1739141178.467976,17.929982900619507,36.77404644390967,1739141178.4679794,17.929982900619507,0.08739840151077871,1739141178.4679823,17.929982900619507,36.31261472156817,1739141178.4679852,17.929982900619507,44.619665428678765,1739141178.467986,17.929982900619507,-0.13981692974326856,1739141178.467988,17.929982900619507,-0.02895269828097701,1739141178.4679892,17.929982900619507,-0.4966147634191309,1739141178.4679906,17.929982900619507,-0.06190142936806528,1739141178.4679918,17.929982900619507,2.049600357339941,1739141178.4679933,17.929982900619507,0.0,1739141178.467995,17.929982900619507,-0.05519466215657598,1739141178.467996,17.929982900619507,0.03436141931081716,1739141178.467997,17.929982900619507,2.104795019496517 +1739141178.4876938,17.94998288154602,36.77404644390967,1739141178.4876962,17.94998288154602,0.08739840151077871,1739141178.487699,17.94998288154602,36.31261472156817,1739141178.4877017,17.94998288154602,44.619665428678765,1739141178.487703,17.94998288154602,-0.13981692974326856,1739141178.4877048,17.94998288154602,-0.02895269828097701,1739141178.4877062,17.94998288154602,-0.4966147634191309,1739141178.4877071,17.94998288154602,-0.06190142936806528,1739141178.4877083,17.94998288154602,2.049600357339941,1739141178.48771,17.94998288154602,0.0,1739141178.4877114,17.94998288154602,-0.05519466215657598,1739141178.4877129,17.94998288154602,0.03436141931081716,1739141178.487714,17.94998288154602,2.104795019496517 +1739141178.5116212,17.969982862472534,36.77404644390967,1739141178.5116298,17.969982862472534,0.08739840151077871,1739141178.5116398,17.969982862472534,36.31261472156817,1739141178.5116496,17.969982862472534,44.619665428678765,1739141178.5116544,17.969982862472534,-0.13981692974326856,1739141178.5116603,17.969982862472534,-0.02895269828097701,1739141178.5116649,17.969982862472534,-0.4966147634191309,1739141178.5116694,17.969982862472534,-0.06190142936806528,1739141178.511674,17.969982862472534,2.049600357339941,1739141178.5116796,17.969982862472534,0.0,1739141178.511685,17.969982862472534,-0.05519466215657598,1739141178.5116894,17.969982862472534,0.03436141931081716,1739141178.5116937,17.969982862472534,2.104795019496517 +1739141178.5353148,17.989982843399048,36.77404644390967,1739141178.5353239,17.989982843399048,0.08739840151077871,1739141178.535334,17.989982843399048,36.31261472156817,1739141178.5353444,17.989982843399048,44.619665428678765,1739141178.535349,17.989982843399048,-0.13981692974326856,1739141178.5353549,17.989982843399048,-0.02895269828097701,1739141178.5353594,17.989982843399048,-0.4966147634191309,1739141178.5353642,17.989982843399048,-0.06190142936806528,1739141178.5353684,17.989982843399048,2.049600357339941,1739141178.5353742,17.989982843399048,0.0,1739141178.535379,17.989982843399048,-0.05519466215657598,1739141178.5353837,17.989982843399048,0.03436141931081716,1739141178.5353887,17.989982843399048,2.104795019496517 +1739141178.552936,18.00998282432556,37.00512069680972,1739141178.552945,18.00998282432556,0.0952188738226587,1739141178.5529554,18.00998282432556,36.34335541767619,1739141178.552965,18.00998282432556,44.63170461220219,1739141178.5529695,18.00998282432556,-0.13991561157542778,1739141178.5529754,18.00998282432556,-0.030821142010643496,1739141178.5529802,18.00998282432556,-0.48811544570312404,1739141178.5529847,18.00998282432556,-0.06437902127519596,1739141178.5529895,18.00998282432556,2.0565802974138276,1739141178.552995,18.00998282432556,0.0,1739141178.553,18.00998282432556,-0.029968605368352434,1739141178.5530045,18.00998282432556,0.03319401965099318,1739141178.553009,18.00998282432556,2.098561316777298 +1739141178.573035,18.029982805252075,37.00512069680972,1739141178.5730438,18.029982805252075,0.0952188738226587,1739141178.5730543,18.029982805252075,36.34335541767619,1739141178.5730646,18.029982805252075,44.63170461220219,1739141178.5730693,18.029982805252075,-0.13991561157542778,1739141178.5730755,18.029982805252075,-0.030821142010643496,1739141178.5730803,18.029982805252075,-0.48811544570312404,1739141178.5730848,18.029982805252075,-0.06437902127519596,1739141178.5730896,18.029982805252075,2.0565802974138276,1739141178.573095,18.029982805252075,0.0,1739141178.5731003,18.029982805252075,-0.04198101936347021,1739141178.5731049,18.029982805252075,0.03319401965099318,1739141178.5731094,18.029982805252075,2.098561316777298 +1739141178.592486,18.04998278617859,37.00512069680972,1739141178.5924923,18.04998278617859,0.0952188738226587,1739141178.5925,18.04998278617859,36.34335541767619,1739141178.592507,18.04998278617859,44.63170461220219,1739141178.5925105,18.04998278617859,-0.13991561157542778,1739141178.5925148,18.04998278617859,-0.030821142010643496,1739141178.592518,18.04998278617859,-0.48811544570312404,1739141178.5925214,18.04998278617859,-0.06437902127519596,1739141178.5925245,18.04998278617859,2.0565802974138276,1739141178.5925283,18.04998278617859,0.0,1739141178.5925322,18.04998278617859,-0.04198101936347021,1739141178.5925355,18.04998278617859,0.03319401965099318,1739141178.5925386,18.04998278617859,2.098561316777298 +1739141178.6104286,18.069982767105103,37.00512069680972,1739141178.6104333,18.069982767105103,0.0952188738226587,1739141178.6104386,18.069982767105103,36.34335541767619,1739141178.6104436,18.069982767105103,44.63170461220219,1739141178.610446,18.069982767105103,-0.13991561157542778,1739141178.610449,18.069982767105103,-0.030821142010643496,1739141178.610452,18.069982767105103,-0.48811544570312404,1739141178.6104546,18.069982767105103,-0.06437902127519596,1739141178.610457,18.069982767105103,2.0565802974138276,1739141178.6104598,18.069982767105103,0.0,1739141178.6104627,18.069982767105103,-0.04198101936347021,1739141178.610465,18.069982767105103,0.03319401965099318,1739141178.610484,18.069982767105103,2.098561316777298 +1739141178.6301296,18.089982748031616,37.00512069680972,1739141178.630134,18.089982748031616,0.0952188738226587,1739141178.6301384,18.089982748031616,36.34335541767619,1739141178.6301427,18.089982748031616,44.63170461220219,1739141178.6301446,18.089982748031616,-0.13991561157542778,1739141178.6301472,18.089982748031616,-0.030821142010643496,1739141178.6301496,18.089982748031616,-0.48811544570312404,1739141178.6301517,18.089982748031616,-0.06437902127519596,1739141178.6301537,18.089982748031616,2.0565802974138276,1739141178.6301563,18.089982748031616,0.0,1739141178.6301587,18.089982748031616,-0.04198101936347021,1739141178.6301606,18.089982748031616,0.03319401965099318,1739141178.6301625,18.089982748031616,2.098561316777298 +1739141178.649128,18.10998272895813,37.2356169175898,1739141178.6491306,18.10998272895813,0.10275038571894779,1739141178.6491332,18.10998272895813,36.837467322814796,1739141178.649136,18.10998272895813,45.11233022829504,1739141178.649138,18.10998272895813,-0.14056116286174936,1739141178.6491394,18.10998272895813,-0.030880164694254728,1739141178.649141,18.10998272895813,-0.4954081577761767,1739141178.6491423,18.10998272895813,-0.06125756498351531,1739141178.6491435,18.10998272895813,2.0505898198417283,1739141178.6491451,18.10998272895813,0.0,1739141178.6491466,18.10998272895813,-0.04485777525055627,1739141178.649148,18.10998272895813,0.0320266199911692,1739141178.6491492,18.10998272895813,2.094077710652212 +1739141178.6726415,18.129982709884644,37.2356169175898,1739141178.6726463,18.129982709884644,0.10275038571894779,1739141178.672652,18.129982709884644,36.837467322814796,1739141178.6726575,18.129982709884644,45.11233022829504,1739141178.6726599,18.129982709884644,-0.14056116286174936,1739141178.6726632,18.129982709884644,-0.030880164694254728,1739141178.6726658,18.129982709884644,-0.4954081577761767,1739141178.6726685,18.129982709884644,-0.06125756498351531,1739141178.672671,18.129982709884644,2.0505898198417283,1739141178.6726737,18.129982709884644,0.0,1739141178.6726766,18.129982709884644,-0.043487890810483876,1739141178.672679,18.129982709884644,0.0320266199911692,1739141178.6726816,18.129982709884644,2.094077710652212 +1739141178.6915455,18.149982690811157,37.2356169175898,1739141178.6915498,18.149982690811157,0.10275038571894779,1739141178.6915543,18.149982690811157,36.837467322814796,1739141178.6915588,18.149982690811157,45.11233022829504,1739141178.691561,18.149982690811157,-0.14056116286174936,1739141178.6915638,18.149982690811157,-0.030880164694254728,1739141178.691566,18.149982690811157,-0.4954081577761767,1739141178.691568,18.149982690811157,-0.06125756498351531,1739141178.6915698,18.149982690811157,2.0505898198417283,1739141178.6915727,18.149982690811157,0.0,1739141178.691575,18.149982690811157,-0.043487890810483876,1739141178.6915774,18.149982690811157,0.0320266199911692,1739141178.6915796,18.149982690811157,2.094077710652212 +1739141178.7095506,18.16998267173767,37.2356169175898,1739141178.7095532,18.16998267173767,0.10275038571894779,1739141178.7095563,18.16998267173767,36.837467322814796,1739141178.709559,18.16998267173767,45.11233022829504,1739141178.7095604,18.16998267173767,-0.14056116286174936,1739141178.709562,18.16998267173767,-0.030880164694254728,1739141178.7095637,18.16998267173767,-0.4954081577761767,1739141178.709565,18.16998267173767,-0.06125756498351531,1739141178.709566,18.16998267173767,2.0505898198417283,1739141178.709568,18.16998267173767,0.0,1739141178.7095692,18.16998267173767,-0.043487890810483876,1739141178.709571,18.16998267173767,0.0320266199911692,1739141178.709572,18.16998267173767,2.094077710652212 +1739141178.7297564,18.189982652664185,37.2356169175898,1739141178.7297587,18.189982652664185,0.10275038571894779,1739141178.7297616,18.189982652664185,36.837467322814796,1739141178.729764,18.189982652664185,45.11233022829504,1739141178.7297654,18.189982652664185,-0.14056116286174936,1739141178.7297668,18.189982652664185,-0.030880164694254728,1739141178.7297683,18.189982652664185,-0.4954081577761767,1739141178.7297692,18.189982652664185,-0.06125756498351531,1739141178.7297704,18.189982652664185,2.0505898198417283,1739141178.729772,18.189982652664185,0.0,1739141178.7297733,18.189982652664185,-0.043487890810483876,1739141178.7297745,18.189982652664185,0.0320266199911692,1739141178.7297757,18.189982652664185,2.094077710652212 +1739141178.7490027,18.2099826335907,37.2356169175898,1739141178.7490048,18.2099826335907,0.10275038571894779,1739141178.7490075,18.2099826335907,36.837467322814796,1739141178.7490098,18.2099826335907,45.11233022829504,1739141178.7490113,18.2099826335907,-0.14056116286174936,1739141178.7490125,18.2099826335907,-0.030880164694254728,1739141178.7490137,18.2099826335907,-0.4954081577761767,1739141178.749015,18.2099826335907,-0.06125756498351531,1739141178.749016,18.2099826335907,2.0505898198417283,1739141178.7490177,18.2099826335907,0.0,1739141178.7490187,18.2099826335907,-0.043487890810483876,1739141178.7490199,18.2099826335907,0.0320266199911692,1739141178.7490213,18.2099826335907,2.094077710652212 +1739141178.769065,18.229982614517212,37.465610209625275,1739141178.7690675,18.229982614517212,0.10999669774757503,1739141178.7690704,18.229982614517212,36.868293670259575,1739141178.769073,18.229982614517212,45.128787533944966,1739141178.7690742,18.229982614517212,-0.14028687443425056,1739141178.7690756,18.229982614517212,-0.03264894247657424,1739141178.7690773,18.229982614517212,-0.48660655652817303,1739141178.7690783,18.229982614517212,-0.06356139425207742,1739141178.7690794,18.229982614517212,2.0578219327734404,1739141178.7690816,18.229982614517212,0.0,1739141178.7690828,18.229982614517212,-0.020538638108281708,1739141178.7690842,18.229982614517212,0.030859220331345208,1739141178.7690854,18.229982614517212,2.089288791913323 +1739141178.788926,18.249982595443726,37.465610209625275,1739141178.7889283,18.249982595443726,0.10999669774757503,1739141178.788931,18.249982595443726,36.868293670259575,1739141178.7889335,18.249982595443726,45.128787533944966,1739141178.788935,18.249982595443726,-0.14028687443425056,1739141178.7889361,18.249982595443726,-0.03264894247657424,1739141178.7889378,18.249982595443726,-0.48660655652817303,1739141178.788939,18.249982595443726,-0.06356139425207742,1739141178.7889404,18.249982595443726,2.0578219327734404,1739141178.788942,18.249982595443726,0.0,1739141178.7889433,18.249982595443726,-0.031466859139882786,1739141178.7889445,18.249982595443726,0.030859220331345208,1739141178.7889457,18.249982595443726,2.089288791913323 +1739141178.8090737,18.26998257637024,37.465610209625275,1739141178.809076,18.26998257637024,0.10999669774757503,1739141178.809079,18.26998257637024,36.868293670259575,1739141178.8090818,18.26998257637024,45.128787533944966,1739141178.8090832,18.26998257637024,-0.14028687443425056,1739141178.8090851,18.26998257637024,-0.03264894247657424,1739141178.8090866,18.26998257637024,-0.48660655652817303,1739141178.8090878,18.26998257637024,-0.06356139425207742,1739141178.8090887,18.26998257637024,2.0578219327734404,1739141178.8090906,18.26998257637024,0.0,1739141178.8090918,18.26998257637024,-0.031466859139882786,1739141178.8090928,18.26998257637024,0.030859220331345208,1739141178.8090942,18.26998257637024,2.089288791913323 +1739141178.8289344,18.289982557296753,37.465610209625275,1739141178.828937,18.289982557296753,0.10999669774757503,1739141178.8289394,18.289982557296753,36.868293670259575,1739141178.828942,18.289982557296753,45.128787533944966,1739141178.8289437,18.289982557296753,-0.14028687443425056,1739141178.8289452,18.289982557296753,-0.03264894247657424,1739141178.8289464,18.289982557296753,-0.48660655652817303,1739141178.8289478,18.289982557296753,-0.06356139425207742,1739141178.828949,18.289982557296753,2.0578219327734404,1739141178.8289506,18.289982557296753,0.0,1739141178.8289518,18.289982557296753,-0.031466859139882786,1739141178.8289528,18.289982557296753,0.030859220331345208,1739141178.8289542,18.289982557296753,2.089288791913323 +1739141178.8489006,18.309982538223267,37.465610209625275,1739141178.8489032,18.309982538223267,0.10999669774757503,1739141178.848906,18.309982538223267,36.868293670259575,1739141178.8489087,18.309982538223267,45.128787533944966,1739141178.8489099,18.309982538223267,-0.14028687443425056,1739141178.8489113,18.309982538223267,-0.03264894247657424,1739141178.848913,18.309982538223267,-0.48660655652817303,1739141178.8489141,18.309982538223267,-0.06356139425207742,1739141178.8489153,18.309982538223267,2.0578219327734404,1739141178.848917,18.309982538223267,0.0,1739141178.8489182,18.309982538223267,-0.031466859139882786,1739141178.8489196,18.309982538223267,0.030859220331345208,1739141178.8489208,18.309982538223267,2.089288791913323 +1739141178.8692071,18.32998251914978,37.69516073760308,1739141178.8692095,18.32998251914978,0.11696081040166195,1739141178.8692129,18.32998251914978,36.899060405121254,1739141178.8692157,18.32998251914978,45.14952148658732,1739141178.8692174,18.32998251914978,-0.13996478513412686,1739141178.869219,18.32998251914978,-0.03445284436512419,1739141178.8692205,18.32998251914978,-0.4781133730944906,1739141178.869222,18.32998251914978,-0.0659911405512209,1739141178.869223,18.32998251914978,2.0648248050334503,1739141178.8692253,18.32998251914978,0.0,1739141178.8692267,18.32998251914978,-0.011714865867531364,1739141178.8692281,18.32998251914978,0.02969182067152119,1739141178.8692293,18.32998251914978,2.0859453866816198 +1739141178.889147,18.349982500076294,37.69516073760308,1739141178.88915,18.349982500076294,0.11696081040166195,1739141178.889153,18.349982500076294,36.899060405121254,1739141178.8891559,18.349982500076294,45.14952148658732,1739141178.8891573,18.349982500076294,-0.13996478513412686,1739141178.8891592,18.349982500076294,-0.03445284436512419,1739141178.8891606,18.349982500076294,-0.4781133730944906,1739141178.889162,18.349982500076294,-0.0659911405512209,1739141178.8891635,18.349982500076294,2.0648248050334503,1739141178.8891652,18.349982500076294,0.0,1739141178.8891666,18.349982500076294,-0.021120581648169434,1739141178.8891678,18.349982500076294,0.02969182067152119,1739141178.8891695,18.349982500076294,2.0859453866816198 +1739141178.9094915,18.369982481002808,37.69516073760308,1739141178.9094946,18.369982481002808,0.11696081040166195,1739141178.9094982,18.369982481002808,36.899060405121254,1739141178.9095018,18.369982481002808,45.14952148658732,1739141178.9095035,18.369982481002808,-0.13996478513412686,1739141178.9095056,18.369982481002808,-0.03445284436512419,1739141178.909507,18.369982481002808,-0.4781133730944906,1739141178.9095087,18.369982481002808,-0.0659911405512209,1739141178.9095101,18.369982481002808,2.0648248050334503,1739141178.9095123,18.369982481002808,0.0,1739141178.9095137,18.369982481002808,-0.021120581648169434,1739141178.9095156,18.369982481002808,0.02969182067152119,1739141178.909517,18.369982481002808,2.0859453866816198 +1739141178.9292643,18.38998246192932,37.69516073760308,1739141178.9292674,18.38998246192932,0.11696081040166195,1739141178.929271,18.38998246192932,36.899060405121254,1739141178.9292743,18.38998246192932,45.14952148658732,1739141178.929276,18.38998246192932,-0.13996478513412686,1739141178.929278,18.38998246192932,-0.03445284436512419,1739141178.92928,18.38998246192932,-0.4781133730944906,1739141178.9292815,18.38998246192932,-0.0659911405512209,1739141178.9292831,18.38998246192932,2.0648248050334503,1739141178.9292848,18.38998246192932,0.0,1739141178.9292867,18.38998246192932,-0.021120581648169434,1739141178.929288,18.38998246192932,0.02969182067152119,1739141178.9292896,18.38998246192932,2.0859453866816198 +1739141178.9492211,18.409982442855835,37.69516073760308,1739141178.949224,18.409982442855835,0.11696081040166195,1739141178.9492276,18.409982442855835,36.899060405121254,1739141178.9492307,18.409982442855835,45.14952148658732,1739141178.9492323,18.409982442855835,-0.13996478513412686,1739141178.9492342,18.409982442855835,-0.03445284436512419,1739141178.949236,18.409982442855835,-0.4781133730944906,1739141178.9492376,18.409982442855835,-0.0659911405512209,1739141178.9492388,18.409982442855835,2.0648248050334503,1739141178.9492407,18.409982442855835,0.0,1739141178.9492424,18.409982442855835,-0.021120581648169434,1739141178.949244,18.409982442855835,0.02969182067152119,1739141178.9492455,18.409982442855835,2.0859453866816198 +1739141178.9693906,18.42998242378235,37.69516073760308,1739141178.9693942,18.42998242378235,0.11696081040166195,1739141178.9693978,18.42998242378235,36.899060405121254,1739141178.969401,18.42998242378235,45.14952148658732,1739141178.9694023,18.42998242378235,-0.13996478513412686,1739141178.9694045,18.42998242378235,-0.03445284436512419,1739141178.9694061,18.42998242378235,-0.4781133730944906,1739141178.9694076,18.42998242378235,-0.0659911405512209,1739141178.969409,18.42998242378235,2.0648248050334503,1739141178.9694114,18.42998242378235,0.0,1739141178.9694128,18.42998242378235,-0.021120581648169434,1739141178.9694145,18.42998242378235,0.02969182067152119,1739141178.969416,18.42998242378235,2.0859453866816198 +1739141178.9892983,18.449982404708862,37.92441916118116,1739141178.9893014,18.449982404708862,0.12364817645637594,1739141178.989305,18.449982404708862,37.62779022229789,1739141178.9893086,18.449982404708862,45.87142184363252,1739141178.9893105,18.449982404708862,-0.11624378348813683,1739141178.989313,18.449982404708862,-0.030177306377825782,1739141178.9893148,18.449982404708862,-0.4664472850368658,1739141178.9893165,18.449982404708862,-0.05666434340488333,1739141178.989318,18.449982404708862,2.0744826926610562,1739141178.98932,18.449982404708862,0.0,1739141178.9893217,18.449982404708862,0.0013762440461054948,1739141178.9893236,18.449982404708862,0.028524421011697172,1739141178.9893253,18.449982404708862,2.083819228106583 +1739141179.009362,18.469982385635376,37.92441916118116,1739141179.009365,18.469982385635376,0.12364817645637594,1739141179.0093684,18.469982385635376,37.62779022229789,1739141179.0093718,18.469982385635376,45.87142184363252,1739141179.0093732,18.469982385635376,-0.11624378348813683,1739141179.0093753,18.469982385635376,-0.030177306377825782,1739141179.009377,18.469982385635376,-0.4664472850368658,1739141179.0093782,18.469982385635376,-0.05666434340488333,1739141179.0093799,18.469982385635376,2.0744826926610562,1739141179.0093818,18.469982385635376,0.0,1739141179.0093834,18.469982385635376,-0.009336535445526817,1739141179.0093849,18.469982385635376,0.028524421011697172,1739141179.0093868,18.469982385635376,2.083819228106583 +1739141179.0295255,18.48998236656189,37.92441916118116,1739141179.029529,18.48998236656189,0.12364817645637594,1739141179.0295331,18.48998236656189,37.62779022229789,1739141179.029537,18.48998236656189,45.87142184363252,1739141179.0295389,18.48998236656189,-0.11624378348813683,1739141179.029541,18.48998236656189,-0.030177306377825782,1739141179.029543,18.48998236656189,-0.4664472850368658,1739141179.0295444,18.48998236656189,-0.05666434340488333,1739141179.029546,18.48998236656189,2.0744826926610562,1739141179.029548,18.48998236656189,0.0,1739141179.02955,18.48998236656189,-0.009336535445526817,1739141179.0295515,18.48998236656189,0.028524421011697172,1739141179.0295534,18.48998236656189,2.083819228106583 +1739141179.0493634,18.509982347488403,37.92441916118116,1739141179.0493665,18.509982347488403,0.12364817645637594,1739141179.0493698,18.509982347488403,37.62779022229789,1739141179.0493736,18.509982347488403,45.87142184363252,1739141179.0493753,18.509982347488403,-0.11624378348813683,1739141179.0493772,18.509982347488403,-0.030177306377825782,1739141179.0493789,18.509982347488403,-0.4664472850368658,1739141179.0493803,18.509982347488403,-0.05666434340488333,1739141179.0493817,18.509982347488403,2.0744826926610562,1739141179.0493836,18.509982347488403,0.0,1739141179.0493855,18.509982347488403,-0.009336535445526817,1739141179.0493867,18.509982347488403,0.028524421011697172,1739141179.0493882,18.509982347488403,2.083819228106583 +1739141179.0693862,18.529982328414917,37.92441916118116,1739141179.0693893,18.529982328414917,0.12364817645637594,1739141179.069393,18.529982328414917,37.62779022229789,1739141179.0693963,18.529982328414917,45.87142184363252,1739141179.0693977,18.529982328414917,-0.11624378348813683,1739141179.0693998,18.529982328414917,-0.030177306377825782,1739141179.0694013,18.529982328414917,-0.4664472850368658,1739141179.069403,18.529982328414917,-0.05666434340488333,1739141179.0694041,18.529982328414917,2.0744826926610562,1739141179.0694063,18.529982328414917,0.0,1739141179.0694077,18.529982328414917,-0.009336535445526817,1739141179.0694091,18.529982328414917,0.028524421011697172,1739141179.0694106,18.529982328414917,2.083819228106583 +1739141179.0892437,18.54998230934143,38.15350486968687,1739141179.0892467,18.54998230934143,0.13006283727990642,1739141179.08925,18.54998230934143,37.65849412189848,1739141179.0892532,18.54998230934143,45.89931576554579,1739141179.0892549,18.54998230934143,-0.11482062420684727,1739141179.0892568,18.54998230934143,-0.03160442802266365,1739141179.0892584,18.54998230934143,-0.4566677145391566,1739141179.08926,18.54998230934143,-0.058390076072797455,1739141179.0892615,18.54998230934143,2.0826136055553532,1739141179.0892637,18.54998230934143,0.0,1739141179.089265,18.54998230934143,0.007951203693965235,1739141179.0892665,18.54998230934143,0.027357021351873154,1739141179.089268,18.54998230934143,2.0828946627068534 +1739141179.1094823,18.569982290267944,38.15350486968687,1739141179.1094856,18.569982290267944,0.13006283727990642,1739141179.109489,18.569982290267944,37.65849412189848,1739141179.1094918,18.569982290267944,45.89931576554579,1739141179.1094935,18.569982290267944,-0.11482062420684727,1739141179.1094954,18.569982290267944,-0.03160442802266365,1739141179.1094968,18.569982290267944,-0.4566677145391566,1739141179.1094983,18.569982290267944,-0.058390076072797455,1739141179.1095,18.569982290267944,2.0826136055553532,1739141179.1095018,18.569982290267944,0.0,1739141179.1095037,18.569982290267944,-0.00028105715150017474,1739141179.1095052,18.569982290267944,0.027357021351873154,1739141179.1095068,18.569982290267944,2.0828946627068534 +1739141179.1294527,18.589982271194458,38.15350486968687,1739141179.1294563,18.589982271194458,0.13006283727990642,1739141179.1294596,18.589982271194458,37.65849412189848,1739141179.129463,18.589982271194458,45.89931576554579,1739141179.1294649,18.589982271194458,-0.11482062420684727,1739141179.1294668,18.589982271194458,-0.03160442802266365,1739141179.1294687,18.589982271194458,-0.4566677145391566,1739141179.12947,18.589982271194458,-0.058390076072797455,1739141179.1294718,18.589982271194458,2.0826136055553532,1739141179.1294737,18.589982271194458,0.0,1739141179.1294754,18.589982271194458,-0.00028105715150017474,1739141179.1294765,18.589982271194458,0.027357021351873154,1739141179.1294782,18.589982271194458,2.0828946627068534 +1739141179.1491978,18.60998225212097,38.15350486968687,1739141179.1492007,18.60998225212097,0.13006283727990642,1739141179.149204,18.60998225212097,37.65849412189848,1739141179.1492074,18.60998225212097,45.89931576554579,1739141179.149209,18.60998225212097,-0.11482062420684727,1739141179.1492114,18.60998225212097,-0.03160442802266365,1739141179.1492128,18.60998225212097,-0.4566677145391566,1739141179.1492145,18.60998225212097,-0.058390076072797455,1739141179.149216,18.60998225212097,2.0826136055553532,1739141179.149218,18.60998225212097,0.0,1739141179.1492195,18.60998225212097,-0.00028105715150017474,1739141179.1492212,18.60998225212097,0.027357021351873154,1739141179.1492226,18.60998225212097,2.0828946627068534 +1739141179.169403,18.629982233047485,38.15350486968687,1739141179.1694067,18.629982233047485,0.13006283727990642,1739141179.1694102,18.629982233047485,37.65849412189848,1739141179.1694136,18.629982233047485,45.89931576554579,1739141179.1694155,18.629982233047485,-0.11482062420684727,1739141179.1694171,18.629982233047485,-0.03160442802266365,1739141179.169419,18.629982233047485,-0.4566677145391566,1739141179.1694205,18.629982233047485,-0.058390076072797455,1739141179.1694221,18.629982233047485,2.0826136055553532,1739141179.169424,18.629982233047485,0.0,1739141179.169426,18.629982233047485,-0.00028105715150017474,1739141179.1694274,18.629982233047485,0.027357021351873154,1739141179.169429,18.629982233047485,2.0828946627068534 +1739141179.1892195,18.649982213974,38.15350486968687,1739141179.1892223,18.649982213974,0.13006283727990642,1739141179.189226,18.649982213974,37.65849412189848,1739141179.189229,18.649982213974,45.89931576554579,1739141179.189231,18.649982213974,-0.11482062420684727,1739141179.1892326,18.649982213974,-0.03160442802266365,1739141179.1892345,18.649982213974,-0.4566677145391566,1739141179.189236,18.649982213974,-0.058390076072797455,1739141179.1892374,18.649982213974,2.0826136055553532,1739141179.1892393,18.649982213974,0.0,1739141179.1892412,18.649982213974,-0.00028105715150017474,1739141179.1892424,18.649982213974,0.027357021351873154,1739141179.1892443,18.649982213974,2.0828946627068534 +1739141179.2094252,18.669982194900513,38.38255486524887,1739141179.2094285,18.669982194900513,0.13620889421487004,1739141179.2094321,18.669982194900513,37.68919296736072,1739141179.2094355,18.669982194900513,45.930371543354106,1739141179.2094371,18.669982194900513,-0.1132361457472396,1739141179.2094393,18.669982194900513,-0.03303661103839841,1739141179.209441,18.669982194900513,-0.4470113649507911,1739141179.2094424,18.669982194900513,-0.06018728341625312,1739141179.2094438,18.669982194900513,2.090673339068919,1739141179.2094457,18.669982194900513,0.0,1739141179.2094474,18.669982194900513,0.014852869600529114,1739141179.209449,18.669982194900513,0.026189621692049136,1739141179.2094505,18.669982194900513,2.0830271048550997 +1739141179.229283,18.689982175827026,38.38255486524887,1739141179.229286,18.689982175827026,0.13620889421487004,1739141179.2292893,18.689982175827026,37.68919296736072,1739141179.2292924,18.689982175827026,45.930371543354106,1739141179.229294,18.689982175827026,-0.1132361457472396,1739141179.2292962,18.689982175827026,-0.03303661103839841,1739141179.2292979,18.689982175827026,-0.4470113649507911,1739141179.2292993,18.689982175827026,-0.06018728341625312,1739141179.2293007,18.689982175827026,2.090673339068919,1739141179.229303,18.689982175827026,0.0,1739141179.2293043,18.689982175827026,0.00764623421381927,1739141179.2293057,18.689982175827026,0.026189621692049136,1739141179.2293074,18.689982175827026,2.0830271048550997 +1739141179.2492929,18.70998215675354,38.38255486524887,1739141179.2492957,18.70998215675354,0.13620889421487004,1739141179.2492993,18.70998215675354,37.68919296736072,1739141179.2493024,18.70998215675354,45.930371543354106,1739141179.249304,18.70998215675354,-0.1132361457472396,1739141179.249306,18.70998215675354,-0.03303661103839841,1739141179.2493076,18.70998215675354,-0.4470113649507911,1739141179.2493093,18.70998215675354,-0.06018728341625312,1739141179.2493107,18.70998215675354,2.090673339068919,1739141179.2493124,18.70998215675354,0.0,1739141179.2493143,18.70998215675354,0.00764623421381927,1739141179.2493155,18.70998215675354,0.026189621692049136,1739141179.2493172,18.70998215675354,2.0830271048550997 +1739141179.2694938,18.729982137680054,38.38255486524887,1739141179.2694979,18.729982137680054,0.13620889421487004,1739141179.269502,18.729982137680054,37.68919296736072,1739141179.2695053,18.729982137680054,45.930371543354106,1739141179.2695072,18.729982137680054,-0.1132361457472396,1739141179.2695088,18.729982137680054,-0.03303661103839841,1739141179.2695107,18.729982137680054,-0.4470113649507911,1739141179.269513,18.729982137680054,-0.06018728341625312,1739141179.2695181,18.729982137680054,2.090673339068919,1739141179.2695234,18.729982137680054,0.0,1739141179.2695267,18.729982137680054,0.00764623421381927,1739141179.2695312,18.729982137680054,0.026189621692049136,1739141179.2695363,18.729982137680054,2.0830271048550997 +1739141179.2892625,18.749982118606567,38.38255486524887,1739141179.2892654,18.749982118606567,0.13620889421487004,1739141179.289269,18.749982118606567,37.68919296736072,1739141179.2892723,18.749982118606567,45.930371543354106,1739141179.2892742,18.749982118606567,-0.1132361457472396,1739141179.2892761,18.749982118606567,-0.03303661103839841,1739141179.289278,18.749982118606567,-0.4470113649507911,1739141179.2892795,18.749982118606567,-0.06018728341625312,1739141179.2892811,18.749982118606567,2.090673339068919,1739141179.2892828,18.749982118606567,0.0,1739141179.2892847,18.749982118606567,0.00764623421381927,1739141179.2892861,18.749982118606567,0.026189621692049136,1739141179.2892876,18.749982118606567,2.0830271048550997 +1739141179.3096914,18.76998209953308,38.61165863554302,1739141179.3096945,18.76998209953308,0.14208874491566537,1739141179.3096979,18.76998209953308,37.95121982508663,1739141179.3097012,18.76998209953308,46.194884073521635,1739141179.3097026,18.76998209953308,-0.10249963339306532,1739141179.3097048,18.76998209953308,-0.03224269370825946,1739141179.3097064,18.76998209953308,-0.4342411630526751,1739141179.309708,18.76998209953308,-0.0579266922679839,1739141179.3097095,18.76998209953308,2.1013799892627594,1739141179.3097117,18.76998209953308,0.0,1739141179.3097134,18.76998209953308,0.026365002788325122,1739141179.309715,18.76998209953308,0.02502222203222512,1739141179.3097165,18.76998209953308,2.083928690248412 +1739141179.3292775,18.789982080459595,38.61165863554302,1739141179.3292801,18.789982080459595,0.14208874491566537,1739141179.3292835,18.789982080459595,37.95121982508663,1739141179.3292868,18.789982080459595,46.194884073521635,1739141179.3292885,18.789982080459595,-0.10249963339306532,1739141179.3292904,18.789982080459595,-0.03224269370825946,1739141179.329292,18.789982080459595,-0.4342411630526751,1739141179.3292935,18.789982080459595,-0.0579266922679839,1739141179.329295,18.789982080459595,2.1013799892627594,1739141179.3292968,18.789982080459595,0.0,1739141179.3292985,18.789982080459595,0.017451299014347388,1739141179.3293,18.789982080459595,0.02502222203222512,1739141179.3293016,18.789982080459595,2.083928690248412 +1739141179.3492777,18.80998206138611,38.61165863554302,1739141179.3492806,18.80998206138611,0.14208874491566537,1739141179.3492842,18.80998206138611,37.95121982508663,1739141179.3492875,18.80998206138611,46.194884073521635,1739141179.3492892,18.80998206138611,-0.10249963339306532,1739141179.349291,18.80998206138611,-0.03224269370825946,1739141179.3492925,18.80998206138611,-0.4342411630526751,1739141179.3492942,18.80998206138611,-0.0579266922679839,1739141179.3492954,18.80998206138611,2.1013799892627594,1739141179.3492975,18.80998206138611,0.0,1739141179.349299,18.80998206138611,0.017451299014347388,1739141179.3493004,18.80998206138611,0.02502222203222512,1739141179.3493018,18.80998206138611,2.083928690248412 +1739141179.3694801,18.829982042312622,38.61165863554302,1739141179.3694842,18.829982042312622,0.14208874491566537,1739141179.3694878,18.829982042312622,37.95121982508663,1739141179.3694913,18.829982042312622,46.194884073521635,1739141179.369493,18.829982042312622,-0.10249963339306532,1739141179.3694954,18.829982042312622,-0.03224269370825946,1739141179.369497,18.829982042312622,-0.4342411630526751,1739141179.369499,18.829982042312622,-0.0579266922679839,1739141179.3695004,18.829982042312622,2.1013799892627594,1739141179.3695025,18.829982042312622,0.0,1739141179.3695042,18.829982042312622,0.017451299014347388,1739141179.3695056,18.829982042312622,0.02502222203222512,1739141179.3695073,18.829982042312622,2.083928690248412 +1739141179.389263,18.849982023239136,38.61165863554302,1739141179.3892658,18.849982023239136,0.14208874491566537,1739141179.3892689,18.849982023239136,37.95121982508663,1739141179.3892727,18.849982023239136,46.194884073521635,1739141179.3892744,18.849982023239136,-0.10249963339306532,1739141179.3892763,18.849982023239136,-0.03224269370825946,1739141179.389278,18.849982023239136,-0.4342411630526751,1739141179.3892796,18.849982023239136,-0.0579266922679839,1739141179.389281,18.849982023239136,2.1013799892627594,1739141179.3892827,18.849982023239136,0.0,1739141179.3892846,18.849982023239136,0.017451299014347388,1739141179.3892858,18.849982023239136,0.02502222203222512,1739141179.3892875,18.849982023239136,2.083928690248412 +1739141179.4094229,18.86998200416565,38.61165863554302,1739141179.4094262,18.86998200416565,0.14208874491566537,1739141179.4094296,18.86998200416565,37.95121982508663,1739141179.4094331,18.86998200416565,46.194884073521635,1739141179.4094348,18.86998200416565,-0.10249963339306532,1739141179.4094367,18.86998200416565,-0.03224269370825946,1739141179.4094384,18.86998200416565,-0.4342411630526751,1739141179.4094403,18.86998200416565,-0.0579266922679839,1739141179.4094415,18.86998200416565,2.1013799892627594,1739141179.4094436,18.86998200416565,0.0,1739141179.409445,18.86998200416565,0.017451299014347388,1739141179.4094467,18.86998200416565,0.02502222203222512,1739141179.4094481,18.86998200416565,2.083928690248412 +1739141179.4291995,18.889981985092163,38.84093458630885,1739141179.429202,18.889981985092163,0.1477051779709342,1739141179.4292052,18.889981985092163,38.439425033144296,1739141179.4292085,18.889981985092163,46.68862250510949,1739141179.4292102,18.889981985092163,-0.07600273164271186,1739141179.429212,18.889981985092163,-0.028498501227635118,1739141179.4292138,18.889981985092163,-0.41083170876303765,1739141179.4292152,18.889981985092163,-0.05118548429951396,1739141179.4292166,18.889981985092163,2.121149265932011,1739141179.4292185,18.889981985092163,0.0,1739141179.4292202,18.889981985092163,0.05120725499007948,1739141179.4292214,18.889981985092163,0.0238548223724011,1739141179.4292228,18.889981985092163,2.0860162837220817 +1739141179.4492908,18.909981966018677,38.84093458630885,1739141179.4492934,18.909981966018677,0.1477051779709342,1739141179.4492967,18.909981966018677,38.439425033144296,1739141179.4493,18.909981966018677,46.68862250510949,1739141179.4493017,18.909981966018677,-0.07600273164271186,1739141179.4493039,18.909981966018677,-0.028498501227635118,1739141179.4493053,18.909981966018677,-0.41083170876303765,1739141179.449307,18.909981966018677,-0.05118548429951396,1739141179.4493084,18.909981966018677,2.121149265932011,1739141179.4493105,18.909981966018677,0.0,1739141179.449312,18.909981966018677,0.03513298220992933,1739141179.4493136,18.909981966018677,0.0238548223724011,1739141179.4493153,18.909981966018677,2.0860162837220817 +1739141179.4694486,18.92998194694519,38.84093458630885,1739141179.4694517,18.92998194694519,0.1477051779709342,1739141179.469455,18.92998194694519,38.439425033144296,1739141179.4694583,18.92998194694519,46.68862250510949,1739141179.46946,18.92998194694519,-0.07600273164271186,1739141179.4694622,18.92998194694519,-0.028498501227635118,1739141179.4694638,18.92998194694519,-0.41083170876303765,1739141179.4694655,18.92998194694519,-0.05118548429951396,1739141179.4694672,18.92998194694519,2.121149265932011,1739141179.4694688,18.92998194694519,0.0,1739141179.4694707,18.92998194694519,0.03513298220992933,1739141179.4694722,18.92998194694519,0.0238548223724011,1739141179.4694738,18.92998194694519,2.0860162837220817 +1739141179.4892368,18.949981927871704,38.84093458630885,1739141179.4892395,18.949981927871704,0.1477051779709342,1739141179.4892426,18.949981927871704,38.439425033144296,1739141179.489246,18.949981927871704,46.68862250510949,1739141179.4892476,18.949981927871704,-0.07600273164271186,1739141179.4892495,18.949981927871704,-0.028498501227635118,1739141179.4892511,18.949981927871704,-0.41083170876303765,1739141179.4892526,18.949981927871704,-0.05118548429951396,1739141179.4892542,18.949981927871704,2.121149265932011,1739141179.4892561,18.949981927871704,0.0,1739141179.4892578,18.949981927871704,0.03513298220992933,1739141179.4892592,18.949981927871704,0.0238548223724011,1739141179.489261,18.949981927871704,2.0860162837220817 +1739141179.5097694,18.969981908798218,38.84093458630885,1739141179.509773,18.969981908798218,0.1477051779709342,1739141179.5097768,18.969981908798218,38.439425033144296,1739141179.5097802,18.969981908798218,46.68862250510949,1739141179.509782,18.969981908798218,-0.07600273164271186,1739141179.509785,18.969981908798218,-0.028498501227635118,1739141179.509787,18.969981908798218,-0.41083170876303765,1739141179.509789,18.969981908798218,-0.05118548429951396,1739141179.5097904,18.969981908798218,2.121149265932011,1739141179.5097928,18.969981908798218,0.0,1739141179.5097947,18.969981908798218,0.03513298220992933,1739141179.5097966,18.969981908798218,0.0238548223724011,1739141179.5097983,18.969981908798218,2.0860162837220817 +1739141179.5295353,18.98998188972473,39.07053603095351,1739141179.5295384,18.98998188972473,0.15306137265925734,1739141179.5295424,18.98998188972473,38.46950817858744,1739141179.529546,18.98998188972473,46.73058483497206,1739141179.5295477,18.98998188972473,-0.07330110578328691,1739141179.52955,18.98998188972473,-0.02954245166004083,1739141179.5295522,18.98998188972473,-0.4000760814268998,1739141179.5295537,18.98998188972473,-0.052313963185879775,1739141179.529555,18.98998188972473,2.130294641086637,1739141179.5295575,18.98998188972473,0.0,1739141179.5295594,18.98998188972473,0.04497728604438392,1739141179.529561,18.98998188972473,0.022687422712577083,1739141179.5295627,18.98998188972473,2.0900051211146895 +1739141179.5498073,19.009981870651245,39.07053603095351,1739141179.5498114,19.009981870651245,0.15306137265925734,1739141179.5498166,19.009981870651245,38.46950817858744,1739141179.5498207,19.009981870651245,46.73058483497206,1739141179.5498228,19.009981870651245,-0.07330110578328691,1739141179.549825,19.009981870651245,-0.02954245166004083,1739141179.549827,19.009981870651245,-0.4000760814268998,1739141179.5498285,19.009981870651245,-0.052313963185879775,1739141179.5498304,19.009981870651245,2.130294641086637,1739141179.5498328,19.009981870651245,0.0,1739141179.5498347,19.009981870651245,0.040289519971947296,1739141179.5498364,19.009981870651245,0.022687422712577083,1739141179.549838,19.009981870651245,2.0900051211146895 +1739141179.5696647,19.02998185157776,39.07053603095351,1739141179.5696697,19.02998185157776,0.15306137265925734,1739141179.569674,19.02998185157776,38.46950817858744,1739141179.5696776,19.02998185157776,46.73058483497206,1739141179.5696793,19.02998185157776,-0.07330110578328691,1739141179.5696814,19.02998185157776,-0.02954245166004083,1739141179.5696836,19.02998185157776,-0.4000760814268998,1739141179.5696852,19.02998185157776,-0.052313963185879775,1739141179.569687,19.02998185157776,2.130294641086637,1739141179.569689,19.02998185157776,0.0,1739141179.569691,19.02998185157776,0.040289519971947296,1739141179.5696924,19.02998185157776,0.022687422712577083,1739141179.5696943,19.02998185157776,2.0900051211146895 +1739141179.5894656,19.049981832504272,39.07053603095351,1739141179.589469,19.049981832504272,0.15306137265925734,1739141179.5894728,19.049981832504272,38.46950817858744,1739141179.5894763,19.049981832504272,46.73058483497206,1739141179.5894783,19.049981832504272,-0.07330110578328691,1739141179.5894804,19.049981832504272,-0.02954245166004083,1739141179.5894823,19.049981832504272,-0.4000760814268998,1739141179.589484,19.049981832504272,-0.052313963185879775,1739141179.5894856,19.049981832504272,2.130294641086637,1739141179.5894878,19.049981832504272,0.0,1739141179.58949,19.049981832504272,0.040289519971947296,1739141179.5894914,19.049981832504272,0.022687422712577083,1739141179.5894933,19.049981832504272,2.0900051211146895 +1739141179.6097357,19.069981813430786,39.07053603095351,1739141179.6097395,19.069981813430786,0.15306137265925734,1739141179.6097434,19.069981813430786,38.46950817858744,1739141179.609747,19.069981813430786,46.73058483497206,1739141179.6097488,19.069981813430786,-0.07330110578328691,1739141179.609751,19.069981813430786,-0.02954245166004083,1739141179.6097531,19.069981813430786,-0.4000760814268998,1739141179.609755,19.069981813430786,-0.052313963185879775,1739141179.6097567,19.069981813430786,2.130294641086637,1739141179.6097586,19.069981813430786,0.0,1739141179.6097608,19.069981813430786,0.040289519971947296,1739141179.6097622,19.069981813430786,0.022687422712577083,1739141179.609764,19.069981813430786,2.0900051211146895 +1739141179.6294622,19.0899817943573,39.07053603095351,1739141179.6294656,19.0899817943573,0.15306137265925734,1739141179.6294694,19.0899817943573,38.46950817858744,1739141179.629473,19.0899817943573,46.73058483497206,1739141179.6294749,19.0899817943573,-0.07330110578328691,1739141179.6294773,19.0899817943573,-0.02954245166004083,1739141179.6294794,19.0899817943573,-0.4000760814268998,1739141179.629481,19.0899817943573,-0.052313963185879775,1739141179.6294827,19.0899817943573,2.130294641086637,1739141179.629485,19.0899817943573,0.0,1739141179.6294866,19.0899817943573,0.040289519971947296,1739141179.6294887,19.0899817943573,0.022687422712577083,1739141179.6294901,19.0899817943573,2.0900051211146895 +1739141179.6497252,19.109981775283813,39.300609951550165,1739141179.6497285,19.109981775283813,0.15815985821557277,1739141179.6497326,19.109981775283813,38.49965296067115,1739141179.649736,19.109981775283813,46.77412750133348,1739141179.6497378,19.109981775283813,-0.07012611969443346,1739141179.64974,19.109981775283813,-0.03053649299761195,1739141179.6497421,19.109981775283813,-0.38905097555372603,1739141179.6497436,19.109981775283813,-0.05344002333198341,1739141179.6497455,19.109981775283813,2.139710076645377,1739141179.6497474,19.109981775283813,0.0,1739141179.6497493,19.109981775283813,0.049664955871799955,1739141179.649751,19.109981775283813,0.021520023052753065,1739141179.6497533,19.109981775283813,2.094509616289432 +1739141179.6696806,19.129981756210327,39.300609951550165,1739141179.669684,19.129981756210327,0.15815985821557277,1739141179.6696882,19.129981756210327,38.49965296067115,1739141179.6696923,19.129981756210327,46.77412750133348,1739141179.6696942,19.129981756210327,-0.07012611969443346,1739141179.6696968,19.129981756210327,-0.03053649299761195,1739141179.669699,19.129981756210327,-0.38905097555372603,1739141179.6697009,19.129981756210327,-0.05344002333198341,1739141179.6697023,19.129981756210327,2.139710076645377,1739141179.6697047,19.129981756210327,0.0,1739141179.6697068,19.129981756210327,0.04520046035594527,1739141179.6697083,19.129981756210327,0.021520023052753065,1739141179.6697104,19.129981756210327,2.094509616289432 +1739141179.689427,19.14998173713684,39.300609951550165,1739141179.6894302,19.14998173713684,0.15815985821557277,1739141179.6894343,19.14998173713684,38.49965296067115,1739141179.6894379,19.14998173713684,46.77412750133348,1739141179.6894398,19.14998173713684,-0.07012611969443346,1739141179.6894422,19.14998173713684,-0.03053649299761195,1739141179.6894438,19.14998173713684,-0.38905097555372603,1739141179.6894457,19.14998173713684,-0.05344002333198341,1739141179.6894476,19.14998173713684,2.139710076645377,1739141179.68945,19.14998173713684,0.0,1739141179.6894517,19.14998173713684,0.04520046035594527,1739141179.6894534,19.14998173713684,0.021520023052753065,1739141179.689455,19.14998173713684,2.094509616289432 +1739141179.7096977,19.169981718063354,39.300609951550165,1739141179.7097015,19.169981718063354,0.15815985821557277,1739141179.7097056,19.169981718063354,38.49965296067115,1739141179.7097094,19.169981718063354,46.77412750133348,1739141179.7097113,19.169981718063354,-0.07012611969443346,1739141179.709714,19.169981718063354,-0.03053649299761195,1739141179.709716,19.169981718063354,-0.38905097555372603,1739141179.7097178,19.169981718063354,-0.05344002333198341,1739141179.7097192,19.169981718063354,2.139710076645377,1739141179.7097218,19.169981718063354,0.0,1739141179.7097237,19.169981718063354,0.04520046035594527,1739141179.7097254,19.169981718063354,0.021520023052753065,1739141179.7097273,19.169981718063354,2.094509616289432 +1739141179.7323444,19.189981698989868,39.300609951550165,1739141179.7323537,19.189981698989868,0.15815985821557277,1739141179.7323642,19.189981698989868,38.49965296067115,1739141179.7323742,19.189981698989868,46.77412750133348,1739141179.7323792,19.189981698989868,-0.07012611969443346,1739141179.732385,19.189981698989868,-0.03053649299761195,1739141179.7323897,19.189981698989868,-0.38905097555372603,1739141179.7323942,19.189981698989868,-0.05344002333198341,1739141179.7323985,19.189981698989868,2.139710076645377,1739141179.7324045,19.189981698989868,0.0,1739141179.7324092,19.189981698989868,0.04520046035594527,1739141179.732414,19.189981698989868,0.021520023052753065,1739141179.7324185,19.189981698989868,2.094509616289432 +1739141179.7563484,19.209981679916382,39.53120537227767,1739141179.7563572,19.209981679916382,0.16300057232920473,1739141179.7563674,19.209981679916382,39.17009781705233,1739141179.756377,19.209981679916382,47.455691664045816,1739141179.7563818,19.209981679916382,0.0010966537028702286,1739141179.756388,19.209981679916382,-0.02042799886770105,1739141179.7563925,19.209981679916382,-0.3231433376564565,1739141179.756397,19.209981679916382,-0.039500977739942184,1739141179.7564013,19.209981679916382,2.196869509565173,1739141179.756407,19.209981679916382,0.0,1739141179.7564123,19.209981679916382,0.14480605597231488,1739141179.7564168,19.209981679916382,0.020352623392929047,1739141179.7564216,19.209981679916382,2.0994947132946398 +1739141179.7789483,19.229981660842896,39.53120537227767,1739141179.7789533,19.229981660842896,0.16300057232920473,1739141179.7789586,19.229981660842896,39.17009781705233,1739141179.7789638,19.229981660842896,47.455691664045816,1739141179.7789662,19.229981660842896,0.0010966537028702286,1739141179.7789695,19.229981660842896,-0.02042799886770105,1739141179.7789724,19.229981660842896,-0.3231433376564565,1739141179.7789748,19.229981660842896,-0.039500977739942184,1739141179.7789774,19.229981660842896,2.196869509565173,1739141179.7789803,19.229981660842896,0.0,1739141179.778983,19.229981660842896,0.09737479627053336,1739141179.7789857,19.229981660842896,0.020352623392929047,1739141179.7789884,19.229981660842896,2.0994947132946398 +1739141179.7986238,19.259981632232666,39.53120537227767,1739141179.79863,19.259981632232666,0.16300057232920473,1739141179.798638,19.259981632232666,39.17009781705233,1739141179.7986434,19.259981632232666,47.455691664045816,1739141179.7986462,19.259981632232666,0.0010966537028702286,1739141179.798651,19.259981632232666,-0.02042799886770105,1739141179.7986557,19.259981632232666,-0.3231433376564565,1739141179.7986605,19.259981632232666,-0.039500977739942184,1739141179.7986634,19.259981632232666,2.196869509565173,1739141179.7986677,19.259981632232666,0.0,1739141179.798671,19.259981632232666,0.09737479627053336,1739141179.798677,19.259981632232666,0.020352623392929047,1739141179.7986825,19.259981632232666,2.0994947132946398 +1739141179.8400512,19.289981603622437,39.53120537227767,1739141179.8400548,19.289981603622437,0.16300057232920473,1739141179.8400593,19.289981603622437,39.17009781705233,1739141179.8400633,19.289981603622437,47.455691664045816,1739141179.8400648,19.289981603622437,0.0010966537028702286,1739141179.840067,19.289981603622437,-0.02042799886770105,1739141179.840069,19.289981603622437,-0.3231433376564565,1739141179.8400712,19.289981603622437,-0.039500977739942184,1739141179.8400724,19.289981603622437,2.196869509565173,1739141179.8400748,19.289981603622437,0.0,1739141179.8400762,19.289981603622437,0.09737479627053336,1739141179.840078,19.289981603622437,0.020352623392929047,1739141179.8400795,19.289981603622437,2.0994947132946398 +1739141179.859928,19.319981575012207,39.76272814048737,1739141179.8599322,19.319981575012207,0.1675902946392025,1739141179.8599386,19.319981575012207,39.21014207650798,1739141179.8599443,19.319981575012207,47.52980963104521,1739141179.8599474,19.319981575012207,0.011524838666308464,1739141179.8599503,19.319981575012207,-0.020090488061699358,1739141179.8599522,19.319981575012207,-0.3050407901619639,1739141179.8599539,19.319981575012207,-0.0388153828087259,1739141179.8599555,19.319981575012207,2.2128348162058016,1739141179.859958,19.319981575012207,0.0,1739141179.859961,19.319981575012207,0.10570395179563685,1739141179.859964,19.319981575012207,0.01918522373310503,1739141179.8599658,19.319981575012207,2.1110971309272517 +1739141179.8805418,19.33998155593872,39.76272814048737,1739141179.8805447,19.33998155593872,0.1675902946392025,1739141179.8805482,19.33998155593872,39.21014207650798,1739141179.880551,19.33998155593872,47.52980963104521,1739141179.880553,19.33998155593872,0.011524838666308464,1739141179.8805544,19.33998155593872,-0.020090488061699358,1739141179.880556,19.33998155593872,-0.3050407901619639,1739141179.880557,19.33998155593872,-0.0388153828087259,1739141179.8805583,19.33998155593872,2.2128348162058016,1739141179.8805602,19.33998155593872,0.0,1739141179.8805614,19.33998155593872,0.10173768527854987,1739141179.8805628,19.33998155593872,0.01918522373310503,1739141179.880564,19.33998155593872,2.1110971309272517 +1739141179.8980963,19.359981536865234,39.76272814048737,1739141179.8980997,19.359981536865234,0.1675902946392025,1739141179.8981037,19.359981536865234,39.21014207650798,1739141179.898107,19.359981536865234,47.52980963104521,1739141179.8981087,19.359981536865234,0.011524838666308464,1739141179.8981109,19.359981536865234,-0.020090488061699358,1739141179.8981128,19.359981536865234,-0.3050407901619639,1739141179.898114,19.359981536865234,-0.0388153828087259,1739141179.8981156,19.359981536865234,2.2128348162058016,1739141179.8981173,19.359981536865234,0.0,1739141179.898119,19.359981536865234,0.10173768527854987,1739141179.8981206,19.359981536865234,0.01918522373310503,1739141179.8981225,19.359981536865234,2.1110971309272517 +1739141179.919734,19.379981517791748,39.76272814048737,1739141179.9197392,19.379981517791748,0.1675902946392025,1739141179.9197443,19.379981517791748,39.21014207650798,1739141179.9197507,19.379981517791748,47.52980963104521,1739141179.9197536,19.379981517791748,0.011524838666308464,1739141179.9197576,19.379981517791748,-0.020090488061699358,1739141179.9197614,19.379981517791748,-0.3050407901619639,1739141179.9197648,19.379981517791748,-0.0388153828087259,1739141179.9197683,19.379981517791748,2.2128348162058016,1739141179.9197724,19.379981517791748,0.0,1739141179.919776,19.379981517791748,0.10173768527854987,1739141179.9197798,19.379981517791748,0.01918522373310503,1739141179.919783,19.379981517791748,2.1110971309272517 +1739141179.9378319,19.39998149871826,39.76272814048737,1739141179.937835,19.39998149871826,0.1675902946392025,1739141179.9378383,19.39998149871826,39.21014207650798,1739141179.9378412,19.39998149871826,47.52980963104521,1739141179.9378426,19.39998149871826,0.011524838666308464,1739141179.9378445,19.39998149871826,-0.020090488061699358,1739141179.937846,19.39998149871826,-0.3050407901619639,1739141179.9378474,19.39998149871826,-0.0388153828087259,1739141179.9378486,19.39998149871826,2.2128348162058016,1739141179.9378505,19.39998149871826,0.0,1739141179.937852,19.39998149871826,0.10173768527854987,1739141179.9378533,19.39998149871826,0.01918522373310503,1739141179.9378545,19.39998149871826,2.1110971309272517 +1739141179.9577677,19.419981479644775,39.76272814048737,1739141179.9577708,19.419981479644775,0.1675902946392025,1739141179.9577737,19.419981479644775,39.21014207650798,1739141179.9577763,19.419981479644775,47.52980963104521,1739141179.9577777,19.419981479644775,0.011524838666308464,1739141179.9577792,19.419981479644775,-0.020090488061699358,1739141179.9577808,19.419981479644775,-0.3050407901619639,1739141179.957782,19.419981479644775,-0.0388153828087259,1739141179.9577832,19.419981479644775,2.2128348162058016,1739141179.957785,19.419981479644775,0.0,1739141179.9577866,19.419981479644775,0.10173768527854987,1739141179.9577878,19.419981479644775,0.01918522373310503,1739141179.957789,19.419981479644775,2.1110971309272517 +1739141179.977722,19.43998146057129,39.99547382860511,1739141179.9777248,19.43998146057129,0.1719324542772105,1739141179.9777274,19.43998146057129,39.74899575389076,1739141179.9777303,19.43998146057129,48.09377071927965,1739141179.9777315,19.43998146057129,0.1097022331832597,1739141179.9777334,19.43998146057129,-0.00768420781458399,1739141179.9777346,19.43998146057129,-0.20812591394194044,1739141179.977736,19.43998146057129,-0.02437051977257735,1739141179.9777372,19.43998146057129,2.300301879542642,1739141179.9777389,19.43998146057129,0.0,1739141179.9777403,19.43998146057129,0.24730361599444473,1739141179.9777412,19.43998146057129,0.01801782407328101,1739141179.9777427,19.43998146057129,2.122315408039851 +1739141179.9976003,19.459981441497803,39.99547382860511,1739141179.9976032,19.459981441497803,0.1719324542772105,1739141179.9976058,19.459981441497803,39.74899575389076,1739141179.9976087,19.459981441497803,48.09377071927965,1739141179.9976103,19.459981441497803,0.1097022331832597,1739141179.9976118,19.459981441497803,-0.00768420781458399,1739141179.997613,19.459981441497803,-0.20812591394194044,1739141179.9976144,19.459981441497803,-0.02437051977257735,1739141179.9976158,19.459981441497803,2.300301879542642,1739141179.9976177,19.459981441497803,0.0,1739141179.997619,19.459981441497803,0.1779864715027908,1739141179.99762,19.459981441497803,0.01801782407328101,1739141179.9976215,19.459981441497803,2.122315408039851 +1739141180.0175154,19.479981422424316,39.99547382860511,1739141180.0175183,19.479981422424316,0.1719324542772105,1739141180.0175211,19.479981422424316,39.74899575389076,1739141180.017524,19.479981422424316,48.09377071927965,1739141180.0175252,19.479981422424316,0.1097022331832597,1739141180.0175269,19.479981422424316,-0.00768420781458399,1739141180.017528,19.479981422424316,-0.20812591394194044,1739141180.0175295,19.479981422424316,-0.02437051977257735,1739141180.017531,19.479981422424316,2.300301879542642,1739141180.0175323,19.479981422424316,0.0,1739141180.017534,19.479981422424316,0.1779864715027908,1739141180.0175352,19.479981422424316,0.01801782407328101,1739141180.0175364,19.479981422424316,2.122315408039851 +1739141180.038407,19.49998140335083,39.99547382860511,1739141180.038411,19.49998140335083,0.1719324542772105,1739141180.0384152,19.49998140335083,39.74899575389076,1739141180.038419,19.49998140335083,48.09377071927965,1739141180.0384207,19.49998140335083,0.1097022331832597,1739141180.0384233,19.49998140335083,-0.00768420781458399,1739141180.0384252,19.49998140335083,-0.20812591394194044,1739141180.038427,19.49998140335083,-0.02437051977257735,1739141180.0384288,19.49998140335083,2.300301879542642,1739141180.038431,19.49998140335083,0.0,1739141180.038433,19.49998140335083,0.1779864715027908,1739141180.0384347,19.49998140335083,0.01801782407328101,1739141180.0384364,19.49998140335083,2.122315408039851 +1739141180.058968,19.519981384277344,39.99547382860511,1739141180.0589724,19.519981384277344,0.1719324542772105,1739141180.0589774,19.519981384277344,39.74899575389076,1739141180.0589817,19.519981384277344,48.09377071927965,1739141180.0589836,19.519981384277344,0.1097022331832597,1739141180.0589862,19.519981384277344,-0.00768420781458399,1739141180.0589886,19.519981384277344,-0.20812591394194044,1739141180.0589905,19.519981384277344,-0.02437051977257735,1739141180.0589924,19.519981384277344,2.300301879542642,1739141180.0589952,19.519981384277344,0.0,1739141180.0589974,19.519981384277344,0.1779864715027908,1739141180.0589995,19.519981384277344,0.01801782407328101,1739141180.0590014,19.519981384277344,2.122315408039851 +1739141180.079586,19.539981365203857,40.22990934287443,1739141180.07959,19.539981365203857,0.1760322718425753,1739141180.0795949,19.539981365203857,39.75462220623322,1739141180.0795991,19.539981365203857,48.158278357187044,1739141180.079601,19.539981365203857,0.12327205790450382,1739141180.0796037,19.539981365203857,-0.006654513060003809,1739141180.079606,19.539981365203857,-0.18634278456452005,1739141180.0796077,19.539981365203857,-0.02276556963518204,1739141180.0796099,19.539981365203857,2.3204325634193568,1739141180.0796125,19.539981365203857,0.0,1739141180.0796146,19.539981365203857,0.1780490820626597,1739141180.0796168,19.539981365203857,0.016850424413456994,1739141180.0796185,19.539981365203857,2.1424132959239093 +1739141180.0985315,19.55998134613037,40.22990934287443,1739141180.0985358,19.55998134613037,0.1760322718425753,1739141180.0985403,19.55998134613037,39.75462220623322,1739141180.0985444,19.55998134613037,48.158278357187044,1739141180.0985465,19.55998134613037,0.12327205790450382,1739141180.0985487,19.55998134613037,-0.006654513060003809,1739141180.0985508,19.55998134613037,-0.18634278456452005,1739141180.0985525,19.55998134613037,-0.02276556963518204,1739141180.0985544,19.55998134613037,2.3204325634193568,1739141180.098557,19.55998134613037,0.0,1739141180.098559,19.55998134613037,0.1780192674954475,1739141180.0985608,19.55998134613037,0.016850424413456994,1739141180.0985625,19.55998134613037,2.1424132959239093 +1739141180.1192412,19.579981327056885,40.22990934287443,1739141180.119245,19.579981327056885,0.1760322718425753,1739141180.119249,19.579981327056885,39.75462220623322,1739141180.119253,19.579981327056885,48.158278357187044,1739141180.119255,19.579981327056885,0.12327205790450382,1739141180.1192577,19.579981327056885,-0.006654513060003809,1739141180.1192596,19.579981327056885,-0.18634278456452005,1739141180.1192615,19.579981327056885,-0.02276556963518204,1739141180.1192632,19.579981327056885,2.3204325634193568,1739141180.1192656,19.579981327056885,0.0,1739141180.1192677,19.579981327056885,0.1780192674954475,1739141180.1192696,19.579981327056885,0.016850424413456994,1739141180.1192715,19.579981327056885,2.1424132959239093 +1739141180.1385581,19.5999813079834,40.22990934287443,1739141180.138562,19.5999813079834,0.1760322718425753,1739141180.1385667,19.5999813079834,39.75462220623322,1739141180.1385708,19.5999813079834,48.158278357187044,1739141180.1385732,19.5999813079834,0.12327205790450382,1739141180.1385753,19.5999813079834,-0.006654513060003809,1739141180.1385775,19.5999813079834,-0.18634278456452005,1739141180.1385794,19.5999813079834,-0.02276556963518204,1739141180.1385813,19.5999813079834,2.3204325634193568,1739141180.138584,19.5999813079834,0.0,1739141180.138586,19.5999813079834,0.1780192674954475,1739141180.1385882,19.5999813079834,0.016850424413456994,1739141180.13859,19.5999813079834,2.1424132959239093 +1739141180.1587827,19.619981288909912,40.22990934287443,1739141180.1587873,19.619981288909912,0.1760322718425753,1739141180.1587927,19.619981288909912,39.75462220623322,1739141180.1587975,19.619981288909912,48.158278357187044,1739141180.1587996,19.619981288909912,0.12327205790450382,1739141180.1588025,19.619981288909912,-0.006654513060003809,1739141180.158805,19.619981288909912,-0.18634278456452005,1739141180.158807,19.619981288909912,-0.02276556963518204,1739141180.1588092,19.619981288909912,2.3204325634193568,1739141180.1588116,19.619981288909912,0.0,1739141180.1588142,19.619981288909912,0.1780192674954475,1739141180.1588163,19.619981288909912,0.016850424413456994,1739141180.1588187,19.619981288909912,2.1424132959239093 +1739141180.1785262,19.639981269836426,40.22990934287443,1739141180.1785302,19.639981269836426,0.1760322718425753,1739141180.178534,19.639981269836426,39.75462220623322,1739141180.1785386,19.639981269836426,48.158278357187044,1739141180.1785405,19.639981269836426,0.12327205790450382,1739141180.1785429,19.639981269836426,-0.006654513060003809,1739141180.178545,19.639981269836426,-0.18634278456452005,1739141180.1785467,19.639981269836426,-0.02276556963518204,1739141180.1785488,19.639981269836426,2.3204325634193568,1739141180.178551,19.639981269836426,0.0,1739141180.178553,19.639981269836426,0.1780192674954475,1739141180.1785553,19.639981269836426,0.016850424413456994,1739141180.178557,19.639981269836426,2.1424132959239093 +1739141180.198517,19.65998125076294,40.46651972071541,1739141180.1985207,19.65998125076294,0.1798938389602709,1739141180.1985252,19.65998125076294,39.76030085530141,1739141180.1985292,19.65998125076294,48.22092057815418,1739141180.1985319,19.65998125076294,0.1371192856972383,1739141180.1985345,19.65998125076294,-0.005516108879104922,1739141180.1985362,19.65998125076294,-0.16437676842817975,1739141180.1985383,19.65998125076294,-0.020993500461157583,1739141180.1985402,19.65998125076294,2.3409106597670117,1739141180.1985426,19.65998125076294,0.0,1739141180.1985447,19.65998125076294,0.1799019420552564,1739141180.1985466,19.65998125076294,0.015683024753632976,1739141180.1985486,19.65998125076294,2.1619052298547494 +1739141180.2187064,19.679981231689453,40.46651972071541,1739141180.2187104,19.679981231689453,0.1798938389602709,1739141180.2187152,19.679981231689453,39.76030085530141,1739141180.2187195,19.679981231689453,48.22092057815418,1739141180.2187216,19.679981231689453,0.1371192856972383,1739141180.218724,19.679981231689453,-0.005516108879104922,1739141180.2187262,19.679981231689453,-0.16437676842817975,1739141180.2187283,19.679981231689453,-0.020993500461157583,1739141180.21873,19.679981231689453,2.3409106597670117,1739141180.2187326,19.679981231689453,0.0,1739141180.2187347,19.679981231689453,0.17900542991226231,1739141180.2187366,19.679981231689453,0.015683024753632976,1739141180.2187388,19.679981231689453,2.1619052298547494 +1739141180.2376425,19.699981212615967,40.46651972071541,1739141180.2376454,19.699981212615967,0.1798938389602709,1739141180.237648,19.699981212615967,39.76030085530141,1739141180.2376506,19.699981212615967,48.22092057815418,1739141180.2376523,19.699981212615967,0.1371192856972383,1739141180.237654,19.699981212615967,-0.005516108879104922,1739141180.2376554,19.699981212615967,-0.16437676842817975,1739141180.2376568,19.699981212615967,-0.020993500461157583,1739141180.237658,19.699981212615967,2.3409106597670117,1739141180.2376597,19.699981212615967,0.0,1739141180.2376611,19.699981212615967,0.17900542991226231,1739141180.2376626,19.699981212615967,0.015683024753632976,1739141180.2376642,19.699981212615967,2.1619052298547494 +1739141180.2576106,19.71998119354248,40.46651972071541,1739141180.257613,19.71998119354248,0.1798938389602709,1739141180.2576163,19.71998119354248,39.76030085530141,1739141180.2576191,19.71998119354248,48.22092057815418,1739141180.2576208,19.71998119354248,0.1371192856972383,1739141180.2576222,19.71998119354248,-0.005516108879104922,1739141180.2576234,19.71998119354248,-0.16437676842817975,1739141180.2576249,19.71998119354248,-0.020993500461157583,1739141180.257626,19.71998119354248,2.3409106597670117,1739141180.257628,19.71998119354248,0.0,1739141180.2576292,19.71998119354248,0.17900542991226231,1739141180.2576308,19.71998119354248,0.015683024753632976,1739141180.257632,19.71998119354248,2.1619052298547494 +1739141180.2777212,19.739981174468994,40.46651972071541,1739141180.2777243,19.739981174468994,0.1798938389602709,1739141180.2777271,19.739981174468994,39.76030085530141,1739141180.2777297,19.739981174468994,48.22092057815418,1739141180.2777312,19.739981174468994,0.1371192856972383,1739141180.2777328,19.739981174468994,-0.005516108879104922,1739141180.277734,19.739981174468994,-0.16437676842817975,1739141180.2777355,19.739981174468994,-0.020993500461157583,1739141180.2777364,19.739981174468994,2.3409106597670117,1739141180.2777383,19.739981174468994,0.0,1739141180.2777398,19.739981174468994,0.17900542991226231,1739141180.277741,19.739981174468994,0.015683024753632976,1739141180.2777424,19.739981174468994,2.1619052298547494 +1739141180.2978508,19.759981155395508,40.70528238293877,1739141180.2978537,19.759981155395508,0.18351173232013718,1739141180.2978566,19.759981155395508,39.76603115919477,1739141180.2978594,19.759981155395508,48.28396758318688,1739141180.2978606,19.759981155395508,0.15071221996485068,1739141180.297862,19.759981155395508,-0.004327836123059799,1739141180.2978637,19.759981155395508,-0.1428015468199291,1739141180.297865,19.759981155395508,-0.01909380123409528,1739141180.2978659,19.759981155395508,2.3612003512563557,1739141180.2978678,19.759981155395508,0.0,1739141180.297869,19.759981155395508,0.18034313946498245,1739141180.2978704,19.759981155395508,0.014515625093808958,1739141180.2978716,19.759981155395508,2.1814942166584994 +1739141180.31779,19.77998113632202,40.70528238293877,1739141180.3177934,19.77998113632202,0.18351173232013718,1739141180.3177967,19.77998113632202,39.76603115919477,1739141180.3177993,19.77998113632202,48.28396758318688,1739141180.3178012,19.77998113632202,0.15071221996485068,1739141180.317808,19.77998113632202,-0.004327836123059799,1739141180.3178122,19.77998113632202,-0.1428015468199291,1739141180.317817,19.77998113632202,-0.01909380123409528,1739141180.3178198,19.77998113632202,2.3612003512563557,1739141180.3178225,19.77998113632202,0.0,1739141180.3178258,19.77998113632202,0.17970613459785634,1739141180.3178294,19.77998113632202,0.014515625093808958,1739141180.3178337,19.77998113632202,2.1814942166584994 +1739141180.3392982,19.799981117248535,40.70528238293877,1739141180.3393042,19.799981117248535,0.18351173232013718,1739141180.33931,19.799981117248535,39.76603115919477,1739141180.339314,19.799981117248535,48.28396758318688,1739141180.339316,19.799981117248535,0.15071221996485068,1739141180.3393188,19.799981117248535,-0.004327836123059799,1739141180.339321,19.799981117248535,-0.1428015468199291,1739141180.3393228,19.799981117248535,-0.01909380123409528,1739141180.3393252,19.799981117248535,2.3612003512563557,1739141180.339328,19.799981117248535,0.0,1739141180.339331,19.799981117248535,0.17970613459785634,1739141180.3393333,19.799981117248535,0.014515625093808958,1739141180.3393357,19.799981117248535,2.1814942166584994 +1739141180.3593764,19.81998109817505,40.70528238293877,1739141180.3593807,19.81998109817505,0.18351173232013718,1739141180.3593867,19.81998109817505,39.76603115919477,1739141180.359393,19.81998109817505,48.28396758318688,1739141180.3593957,19.81998109817505,0.15071221996485068,1739141180.3594,19.81998109817505,-0.004327836123059799,1739141180.3594036,19.81998109817505,-0.1428015468199291,1739141180.359407,19.81998109817505,-0.01909380123409528,1739141180.3594105,19.81998109817505,2.3612003512563557,1739141180.359414,19.81998109817505,0.0,1739141180.3594177,19.81998109817505,0.17970613459785634,1739141180.3594215,19.81998109817505,0.014515625093808958,1739141180.359425,19.81998109817505,2.1814942166584994 +1739141180.3786192,19.839981079101562,40.70528238293877,1739141180.3786228,19.839981079101562,0.18351173232013718,1739141180.378626,19.839981079101562,39.76603115919477,1739141180.3786292,19.839981079101562,48.28396758318688,1739141180.3786309,19.839981079101562,0.15071221996485068,1739141180.3786325,19.839981079101562,-0.004327836123059799,1739141180.378634,19.839981079101562,-0.1428015468199291,1739141180.378636,19.839981079101562,-0.01909380123409528,1739141180.378637,19.839981079101562,2.3612003512563557,1739141180.3786385,19.839981079101562,0.0,1739141180.3786411,19.839981079101562,0.17970613459785634,1739141180.3786445,19.839981079101562,0.014515625093808958,1739141180.378646,19.839981079101562,2.1814942166584994 +1739141180.3983035,19.859981060028076,40.70528238293877,1739141180.3983088,19.859981060028076,0.18351173232013718,1739141180.3983123,19.859981060028076,39.76603115919477,1739141180.3983161,19.859981060028076,48.28396758318688,1739141180.3983173,19.859981060028076,0.15071221996485068,1739141180.3983192,19.859981060028076,-0.004327836123059799,1739141180.398321,19.859981060028076,-0.1428015468199291,1739141180.398322,19.859981060028076,-0.01909380123409528,1739141180.3983235,19.859981060028076,2.3612003512563557,1739141180.3983254,19.859981060028076,0.0,1739141180.398327,19.859981060028076,0.17970613459785634,1739141180.3983295,19.859981060028076,0.014515625093808958,1739141180.3983314,19.859981060028076,2.1814942166584994 +1739141180.4192848,19.87998104095459,40.94620998940349,1739141180.4192889,19.87998104095459,0.18688111287635056,1739141180.4192922,19.87998104095459,40.23826234394437,1739141180.419295,19.87998104095459,48.79504622463893,1739141180.4192963,19.87998104095459,0.29501540821297584,1739141180.419298,19.87998104095459,0.013776240357287741,1739141180.4192994,19.87998104095459,0.003359737745201252,1739141180.4193008,19.87998104095459,0.00041876814214200837,1739141180.4193022,19.87998104095459,2.4966425188113703,1739141180.419304,19.87998104095459,0.0,1739141180.4193056,19.87998104095459,0.4006916630459423,1739141180.4193068,19.87998104095459,0.01334822543398494,1739141180.419308,19.87998104095459,2.2011821123559363 +1739141180.4400015,19.899981021881104,40.94620998940349,1739141180.4400058,19.899981021881104,0.18688111287635056,1739141180.440011,19.899981021881104,40.23826234394437,1739141180.4400163,19.899981021881104,48.79504622463893,1739141180.4400194,19.899981021881104,0.29501540821297584,1739141180.440023,19.899981021881104,0.013776240357287741,1739141180.4400265,19.899981021881104,0.003359737745201252,1739141180.4400299,19.899981021881104,0.00041876814214200837,1739141180.4400334,19.899981021881104,2.4966425188113703,1739141180.4400375,19.899981021881104,0.0,1739141180.440041,19.899981021881104,0.29546040645543403,1739141180.4400444,19.899981021881104,0.01334822543398494,1739141180.4400475,19.899981021881104,2.2011821123559363 +1739141180.45873,19.919981002807617,40.94620998940349,1739141180.458734,19.919981002807617,0.18688111287635056,1739141180.4587393,19.919981002807617,40.23826234394437,1739141180.4587445,19.919981002807617,48.79504622463893,1739141180.4587476,19.919981002807617,0.29501540821297584,1739141180.4587517,19.919981002807617,0.013776240357287741,1739141180.458755,19.919981002807617,0.003359737745201252,1739141180.4587586,19.919981002807617,0.00041876814214200837,1739141180.458762,19.919981002807617,2.4966425188113703,1739141180.4587655,19.919981002807617,0.0,1739141180.4587688,19.919981002807617,0.29546040645543403,1739141180.4587724,19.919981002807617,0.01334822543398494,1739141180.458776,19.919981002807617,2.2011821123559363 +1739141180.4797747,19.93998098373413,40.94620998940349,1739141180.479778,19.93998098373413,0.18688111287635056,1739141180.479782,19.93998098373413,40.23826234394437,1739141180.4797857,19.93998098373413,48.79504622463893,1739141180.4797876,19.93998098373413,0.29501540821297584,1739141180.479789,19.93998098373413,0.013776240357287741,1739141180.4797907,19.93998098373413,0.003359737745201252,1739141180.4797919,19.93998098373413,0.00041876814214200837,1739141180.4797935,19.93998098373413,2.4966425188113703,1739141180.4797955,19.93998098373413,0.0,1739141180.4797974,19.93998098373413,0.29546040645543403,1739141180.4797995,19.93998098373413,0.01334822543398494,1739141180.4798021,19.93998098373413,2.2011821123559363 +1739141180.4994504,19.959980964660645,40.94620998940349,1739141180.4994557,19.959980964660645,0.18688111287635056,1739141180.4994605,19.959980964660645,40.23826234394437,1739141180.4994648,19.959980964660645,48.79504622463893,1739141180.4994662,19.959980964660645,0.29501540821297584,1739141180.4994678,19.959980964660645,0.013776240357287741,1739141180.4994693,19.959980964660645,0.003359737745201252,1739141180.4994714,19.959980964660645,0.00041876814214200837,1739141180.499473,19.959980964660645,2.4966425188113703,1739141180.4994757,19.959980964660645,0.0,1739141180.4994774,19.959980964660645,0.29546040645543403,1739141180.4994793,19.959980964660645,0.01334822543398494,1739141180.4994807,19.959980964660645,2.2011821123559363 +1739141180.519477,19.979980945587158,41.19000159018385,1739141180.5194814,19.979980945587158,0.19000574397160985,1739141180.5194857,19.979980945587158,40.24947675758027,1739141180.519489,19.979980945587158,48.8996653863004,1739141180.5194905,19.979980945587158,0.3321745993886315,1739141180.5194926,19.979980945587158,0.018438254611208158,1739141180.5194943,19.979980945587158,0.04825055935586087,1739141180.5194957,19.979980945587158,0.00623224349709163,1739141180.5194974,19.979980945587158,2.452212082793232,1739141180.519499,19.979980945587158,0.0,1739141180.5195012,19.979980945587158,0.14712165077652134,1739141180.519503,19.979980945587158,0.012180825774160922,1739141180.5195043,19.979980945587158,2.2344528940259303 +1739141180.5397708,19.999980926513672,41.19000159018385,1739141180.5397754,19.999980926513672,0.19000574397160985,1739141180.53978,19.999980926513672,40.24947675758027,1739141180.5397842,19.999980926513672,48.8996653863004,1739141180.5397866,19.999980926513672,0.3321745993886315,1739141180.5397892,19.999980926513672,0.018438254611208158,1739141180.5397918,19.999980926513672,0.04825055935586087,1739141180.5397944,19.999980926513672,0.00623224349709163,1739141180.5397966,19.999980926513672,2.452212082793232,1739141180.5397992,19.999980926513672,0.0,1739141180.5398023,19.999980926513672,0.21775918876730183,1739141180.5398045,19.999980926513672,0.012180825774160922,1739141180.5398066,19.999980926513672,2.2344528940259303 +1739141180.5582557,20.019980907440186,41.19000159018385,1739141180.5582614,20.019980907440186,0.19000574397160985,1739141180.5582662,20.019980907440186,40.24947675758027,1739141180.5582705,20.019980907440186,48.8996653863004,1739141180.5582728,20.019980907440186,0.3321745993886315,1739141180.5582757,20.019980907440186,0.018438254611208158,1739141180.5582788,20.019980907440186,0.04825055935586087,1739141180.558281,20.019980907440186,0.00623224349709163,1739141180.5582833,20.019980907440186,2.452212082793232,1739141180.5582855,20.019980907440186,0.0,1739141180.5582876,20.019980907440186,0.21775918876730183,1739141180.55829,20.019980907440186,0.012180825774160922,1739141180.5582922,20.019980907440186,2.2344528940259303 +1739141180.5782073,20.0399808883667,41.19000159018385,1739141180.578211,20.0399808883667,0.19000574397160985,1739141180.578215,20.0399808883667,40.24947675758027,1739141180.5782185,20.0399808883667,48.8996653863004,1739141180.5782201,20.0399808883667,0.3321745993886315,1739141180.5782228,20.0399808883667,0.018438254611208158,1739141180.5782247,20.0399808883667,0.04825055935586087,1739141180.578226,20.0399808883667,0.00623224349709163,1739141180.5782278,20.0399808883667,2.452212082793232,1739141180.57823,20.0399808883667,0.0,1739141180.5782318,20.0399808883667,0.21775918876730183,1739141180.5782337,20.0399808883667,0.012180825774160922,1739141180.5782354,20.0399808883667,2.2344528940259303 +1739141180.5980275,20.059980869293213,41.19000159018385,1739141180.598031,20.059980869293213,0.19000574397160985,1739141180.598035,20.059980869293213,40.24947675758027,1739141180.5980384,20.059980869293213,48.8996653863004,1739141180.5980406,20.059980869293213,0.3321745993886315,1739141180.5980427,20.059980869293213,0.018438254611208158,1739141180.5980442,20.059980869293213,0.04825055935586087,1739141180.5980456,20.059980869293213,0.00623224349709163,1739141180.598047,20.059980869293213,2.452212082793232,1739141180.598049,20.059980869293213,0.0,1739141180.5980508,20.059980869293213,0.21775918876730183,1739141180.5980523,20.059980869293213,0.012180825774160922,1739141180.5980537,20.059980869293213,2.2344528940259303 +1739141180.6184602,20.079980850219727,41.19000159018385,1739141180.618465,20.079980850219727,0.19000574397160985,1739141180.6184874,20.079980850219727,40.24947675758027,1739141180.6184943,20.079980850219727,48.8996653863004,1739141180.6184971,20.079980850219727,0.3321745993886315,1739141180.618501,20.079980850219727,0.018438254611208158,1739141180.618504,20.079980850219727,0.04825055935586087,1739141180.6185067,20.079980850219727,0.00623224349709163,1739141180.6185093,20.079980850219727,2.452212082793232,1739141180.6185122,20.079980850219727,0.0,1739141180.6185157,20.079980850219727,0.21775918876730183,1739141180.6185198,20.079980850219727,0.012180825774160922,1739141180.618523,20.079980850219727,2.2344528940259303 +1739141180.6383584,20.09998083114624,41.43683525146994,1739141180.6383622,20.09998083114624,0.19288129023154,1739141180.638366,20.09998083114624,41.08269290064259,1739141180.6383698,20.09998083114624,49.712854439373885,1739141180.638372,20.09998083114624,0.71604258699845,1739141180.6383736,20.09998083114624,0.06313012278835255,1739141180.6383767,20.09998083114624,0.43198408528734167,1739141180.6383781,20.09998083114624,0.04824102876677733,1739141180.63838,20.09998083114624,2.103278037162289,1739141180.6383824,20.09998083114624,0.0,1739141180.6383853,20.09998083114624,-0.49122829557203085,1739141180.6383874,20.09998083114624,0.011013426114336904,1739141180.6383893,20.09998083114624,2.2568930763011132 +1739141180.6589043,20.119980812072754,41.43683525146994,1739141180.6589139,20.119980812072754,0.19288129023154,1739141180.658921,20.119980812072754,41.08269290064259,1739141180.6589262,20.119980812072754,49.712854439373885,1739141180.6589339,20.119980812072754,0.71604258699845,1739141180.6589437,20.119980812072754,0.06313012278835255,1739141180.6589663,20.119980812072754,0.43198408528734167,1739141180.6589718,20.119980812072754,0.04824102876677733,1739141180.6589737,20.119980812072754,2.103278037162289,1739141180.6589773,20.119980812072754,0.0,1739141180.6589797,20.119980812072754,-0.15361503913882446,1739141180.6589854,20.119980812072754,0.011013426114336904,1739141180.6589878,20.119980812072754,2.2568930763011132 +1739141180.6804004,20.139980792999268,41.43683525146994,1739141180.6804073,20.139980792999268,0.19288129023154,1739141180.6804154,20.139980792999268,41.08269290064259,1739141180.6804209,20.139980792999268,49.712854439373885,1739141180.680423,20.139980792999268,0.71604258699845,1739141180.6804266,20.139980792999268,0.06313012278835255,1739141180.6804287,20.139980792999268,0.43198408528734167,1739141180.6804314,20.139980792999268,0.04824102876677733,1739141180.6804335,20.139980792999268,2.103278037162289,1739141180.6804364,20.139980792999268,0.0,1739141180.680439,20.139980792999268,-0.15361503913882446,1739141180.6804416,20.139980792999268,0.011013426114336904,1739141180.680444,20.139980792999268,2.2568930763011132 +1739141180.6997836,20.15998077392578,41.43683525146994,1739141180.6997888,20.15998077392578,0.19288129023154,1739141180.6997948,20.15998077392578,41.08269290064259,1739141180.6998,20.15998077392578,49.712854439373885,1739141180.6998034,20.15998077392578,0.71604258699845,1739141180.6998072,20.15998077392578,0.06313012278835255,1739141180.6998107,20.15998077392578,0.43198408528734167,1739141180.6998146,20.15998077392578,0.04824102876677733,1739141180.6998181,20.15998077392578,2.103278037162289,1739141180.699823,20.15998077392578,0.0,1739141180.6998265,20.15998077392578,-0.15361503913882446,1739141180.6998303,20.15998077392578,0.011013426114336904,1739141180.6998339,20.15998077392578,2.2568930763011132 +1739141180.7194512,20.179980754852295,41.43683525146994,1739141180.7194583,20.179980754852295,0.19288129023154,1739141180.7194655,20.179980754852295,41.08269290064259,1739141180.7194722,20.179980754852295,49.712854439373885,1739141180.7194748,20.179980754852295,0.71604258699845,1739141180.7194786,20.179980754852295,0.06313012278835255,1739141180.719482,20.179980754852295,0.43198408528734167,1739141180.719485,20.179980754852295,0.04824102876677733,1739141180.71949,20.179980754852295,2.103278037162289,1739141180.7194936,20.179980754852295,0.0,1739141180.7194982,20.179980754852295,-0.15361503913882446,1739141180.7195008,20.179980754852295,0.011013426114336904,1739141180.7195046,20.179980754852295,2.2568930763011132 +1739141180.7401428,20.19998073577881,41.68403298454367,1739141180.7401474,20.19998073577881,0.1954928085688481,1739141180.7401533,20.19998073577881,41.09307520543169,1739141180.740159,20.19998073577881,49.670047467997286,1739141180.7401621,20.19998073577881,0.691806287027875,1739141180.7401664,20.19998073577881,0.06206800362357047,1739141180.7401702,20.19998073577881,0.4150042601885681,1739141180.740174,20.19998073577881,0.04977824276082294,1739141180.7401779,20.19998073577881,2.11761197689989,1739141180.7401817,20.19998073577881,0.0,1739141180.740185,20.19998073577881,-0.08833940954421725,1739141180.7401886,20.19998073577881,0.010178407907698594,1739141180.7401922,20.19998073577881,2.237035035112037 +1739141180.7600236,20.209980726242065,41.68403298454367,1739141180.7600296,20.209980726242065,0.1954928085688481,1739141180.7600353,20.209980726242065,41.09307520543169,1739141180.7600408,20.209980726242065,49.670047467997286,1739141180.760043,20.209980726242065,0.691806287027875,1739141180.760046,20.209980726242065,0.06206800362357047,1739141180.7600486,20.209980726242065,0.4150042601885681,1739141180.7600515,20.209980726242065,0.04977824276082294,1739141180.760054,20.209980726242065,2.11761197689989,1739141180.760057,20.209980726242065,0.0,1739141180.7600594,20.209980726242065,-0.11942305821214694,1739141180.760062,20.209980726242065,0.010178407907698594,1739141180.7600646,20.209980726242065,2.237035035112037 +1739141180.7805052,20.239980697631836,41.68403298454367,1739141180.7805107,20.239980697631836,0.1954928085688481,1739141180.780516,20.239980697631836,41.09307520543169,1739141180.7805219,20.239980697631836,49.670047467997286,1739141180.7805247,20.239980697631836,0.691806287027875,1739141180.7805283,20.239980697631836,0.06206800362357047,1739141180.7805336,20.239980697631836,0.4150042601885681,1739141180.7805374,20.239980697631836,0.04977824276082294,1739141180.7805393,20.239980697631836,2.11761197689989,1739141180.780543,20.239980697631836,0.0,1739141180.7805452,20.239980697631836,-0.11942305821214694,1739141180.780548,20.239980697631836,0.010178407907698594,1739141180.7805507,20.239980697631836,2.237035035112037 +1739141180.8005145,20.249980688095093,41.68403298454367,1739141180.80052,20.249980688095093,0.1954928085688481,1739141180.8005254,20.249980688095093,41.09307520543169,1739141180.80053,20.249980688095093,49.670047467997286,1739141180.8005323,20.249980688095093,0.691806287027875,1739141180.8005352,20.249980688095093,0.06206800362357047,1739141180.800538,20.249980688095093,0.4150042601885681,1739141180.8005407,20.249980688095093,0.04977824276082294,1739141180.8005428,20.249980688095093,2.11761197689989,1739141180.8005455,20.249980688095093,0.0,1739141180.8005478,20.249980688095093,-0.11942305821214694,1739141180.8005505,20.249980688095093,0.010178407907698594,1739141180.8005526,20.249980688095093,2.237035035112037 +1739141180.820147,20.279980659484863,41.68403298454367,1739141180.8201544,20.279980659484863,0.1954928085688481,1739141180.8201606,20.279980659484863,41.09307520543169,1739141180.8201654,20.279980659484863,49.670047467997286,1739141180.8201683,20.279980659484863,0.691806287027875,1739141180.820171,20.279980659484863,0.06206800362357047,1739141180.8201747,20.279980659484863,0.4150042601885681,1739141180.8201773,20.279980659484863,0.04977824276082294,1739141180.8201804,20.279980659484863,2.11761197689989,1739141180.8201838,20.279980659484863,0.0,1739141180.8201866,20.279980659484863,-0.11942305821214694,1739141180.8201902,20.279980659484863,0.010178407907698594,1739141180.820193,20.279980659484863,2.237035035112037 +1739141180.8387284,20.299980640411377,41.68403298454367,1739141180.8387315,20.299980640411377,0.1954928085688481,1739141180.8387346,20.299980640411377,41.09307520543169,1739141180.8387372,20.299980640411377,49.670047467997286,1739141180.8387384,20.299980640411377,0.691806287027875,1739141180.83874,20.299980640411377,0.06206800362357047,1739141180.8387418,20.299980640411377,0.4150042601885681,1739141180.838743,20.299980640411377,0.04977824276082294,1739141180.8387444,20.299980640411377,2.11761197689989,1739141180.838746,20.299980640411377,0.0,1739141180.838748,20.299980640411377,-0.11942305821214694,1739141180.8387492,20.299980640411377,0.010178407907698594,1739141180.8387506,20.299980640411377,2.237035035112037 +1739141180.8598673,20.309980630874634,41.92949810509002,1739141180.8598707,20.309980630874634,0.19797893424576785,1739141180.8598742,20.309980630874634,41.10338474049463,1739141180.8598773,20.309980630874634,49.64649470684065,1739141180.859879,20.309980630874634,0.6784712678436026,1739141180.8598807,20.309980630874634,0.06218388711643635,1739141180.859883,20.309980630874634,0.40152502143853563,1739141180.8598845,20.309980630874634,0.05157675273182901,1739141180.8598862,20.309980630874634,2.129060331152581,1739141180.8598876,20.309980630874634,0.0,1739141180.8598895,20.309980630874634,-0.07378281059979516,1739141180.859891,20.309980630874634,0.01022982796699298,1739141180.8598924,20.309980630874634,2.224576603853167 +1739141180.8787978,20.339980602264404,41.92949810509002,1739141180.8788068,20.339980602264404,0.19797893424576785,1739141180.8788128,20.339980602264404,41.10338474049463,1739141180.8788185,20.339980602264404,49.64649470684065,1739141180.8788211,20.339980602264404,0.6784712678436026,1739141180.8788252,20.339980602264404,0.06218388711643635,1739141180.8788283,20.339980602264404,0.40152502143853563,1739141180.8788307,20.339980602264404,0.05157675273182901,1739141180.878834,20.339980602264404,2.129060331152581,1739141180.8788385,20.339980602264404,0.0,1739141180.878844,20.339980602264404,-0.09551627270058605,1739141180.8788495,20.339980602264404,0.01022982796699298,1739141180.8788512,20.339980602264404,2.224576603853167 +1739141180.898921,20.359980583190918,41.92949810509002,1739141180.8989253,20.359980583190918,0.19797893424576785,1739141180.898929,20.359980583190918,41.10338474049463,1739141180.8989325,20.359980583190918,49.64649470684065,1739141180.8989346,20.359980583190918,0.6784712678436026,1739141180.8989363,20.359980583190918,0.06218388711643635,1739141180.898938,20.359980583190918,0.40152502143853563,1739141180.8989394,20.359980583190918,0.05157675273182901,1739141180.8989403,20.359980583190918,2.129060331152581,1739141180.898943,20.359980583190918,0.0,1739141180.898945,20.359980583190918,-0.09551627270058605,1739141180.8989468,20.359980583190918,0.01022982796699298,1739141180.8989487,20.359980583190918,2.224576603853167 +1739141180.9191031,20.37998056411743,41.92949810509002,1739141180.9191074,20.37998056411743,0.19797893424576785,1739141180.9191108,20.37998056411743,41.10338474049463,1739141180.9191136,20.37998056411743,49.64649470684065,1739141180.9191153,20.37998056411743,0.6784712678436026,1739141180.919117,20.37998056411743,0.06218388711643635,1739141180.9191184,20.37998056411743,0.40152502143853563,1739141180.9191196,20.37998056411743,0.05157675273182901,1739141180.9191208,20.37998056411743,2.129060331152581,1739141180.9191232,20.37998056411743,0.0,1739141180.9191248,20.37998056411743,-0.09551627270058605,1739141180.9191263,20.37998056411743,0.01022982796699298,1739141180.9191275,20.37998056411743,2.224576603853167 +1739141180.9380922,20.399980545043945,41.92949810509002,1739141180.9380953,20.399980545043945,0.19797893424576785,1739141180.938099,20.399980545043945,41.10338474049463,1739141180.938102,20.399980545043945,49.64649470684065,1739141180.9381034,20.399980545043945,0.6784712678436026,1739141180.9381053,20.399980545043945,0.06218388711643635,1739141180.9381065,20.399980545043945,0.40152502143853563,1739141180.938108,20.399980545043945,0.05157675273182901,1739141180.9381092,20.399980545043945,2.129060331152581,1739141180.9381108,20.399980545043945,0.0,1739141180.9381125,20.399980545043945,-0.09551627270058605,1739141180.9381137,20.399980545043945,0.01022982796699298,1739141180.9381151,20.399980545043945,2.224576603853167 +1739141180.9598644,20.41998052597046,42.17367849529681,1739141180.959868,20.41998052597046,0.2005336324623661,1739141180.9598722,20.41998052597046,41.37059447238876,1739141180.9598753,20.41998052597046,49.85075500877871,1739141180.959877,20.41998052597046,0.7975375916557506,1739141180.9598792,20.41998052597046,0.07760830336144935,1739141180.959881,20.41998052597046,0.514409676579156,1739141180.9598823,20.41998052597046,0.0666175739754073,1739141180.9598837,20.41998052597046,2.0350631721585475,1739141180.9598858,20.41998052597046,0.0,1739141180.9598873,20.41998052597046,-0.2553948522726225,1739141180.9598887,20.41998052597046,0.010754269698850917,1739141180.9598901,20.41998052597046,2.2143253294604976 +1739141180.984124,20.439980506896973,42.17367849529681,1739141180.9841337,20.439980506896973,0.2005336324623661,1739141180.9841444,20.439980506896973,41.37059447238876,1739141180.9841554,20.439980506896973,49.85075500877871,1739141180.98416,20.439980506896973,0.7975375916557506,1739141180.9841666,20.439980506896973,0.07760830336144935,1739141180.9841719,20.439980506896973,0.514409676579156,1739141180.9841764,20.439980506896973,0.0666175739754073,1739141180.9841807,20.439980506896973,2.0350631721585475,1739141180.9841864,20.439980506896973,0.0,1739141180.9841912,20.439980506896973,-0.17926215730195016,1739141180.984196,20.439980506896973,0.010754269698850917,1739141180.9842005,20.439980506896973,2.2143253294604976 +1739141181.0102787,20.459980487823486,42.17367849529681,1739141181.0102873,20.459980487823486,0.2005336324623661,1739141181.010298,20.459980487823486,41.37059447238876,1739141181.010308,20.459980487823486,49.85075500877871,1739141181.010313,20.459980487823486,0.7975375916557506,1739141181.010319,20.459980487823486,0.07760830336144935,1739141181.010324,20.459980487823486,0.514409676579156,1739141181.0103285,20.459980487823486,0.0666175739754073,1739141181.0103328,20.459980487823486,2.0350631721585475,1739141181.010339,20.459980487823486,0.0,1739141181.0103443,20.459980487823486,-0.17926215730195016,1739141181.0103488,20.459980487823486,0.010754269698850917,1739141181.0103536,20.459980487823486,2.2143253294604976 +1739141181.040777,20.489980459213257,42.17367849529681,1739141181.0407827,20.489980459213257,0.2005336324623661,1739141181.0407884,20.489980459213257,41.37059447238876,1739141181.040794,20.489980459213257,49.85075500877871,1739141181.0407965,20.489980459213257,0.7975375916557506,1739141181.0408,20.489980459213257,0.07760830336144935,1739141181.0408027,20.489980459213257,0.514409676579156,1739141181.0408053,20.489980459213257,0.0666175739754073,1739141181.0408082,20.489980459213257,2.0350631721585475,1739141181.0408113,20.489980459213257,0.0,1739141181.0408146,20.489980459213257,-0.17926215730195016,1739141181.0408175,20.489980459213257,0.010754269698850917,1739141181.0408206,20.489980459213257,2.2143253294604976 +1739141181.0602498,20.519980430603027,42.17367849529681,1739141181.0602555,20.519980430603027,0.2005336324623661,1739141181.060261,20.519980430603027,41.37059447238876,1739141181.0602665,20.519980430603027,49.85075500877871,1739141181.060269,20.519980430603027,0.7975375916557506,1739141181.060272,20.519980430603027,0.07760830336144935,1739141181.0602744,20.519980430603027,0.514409676579156,1739141181.0602767,20.519980430603027,0.0666175739754073,1739141181.0602791,20.519980430603027,2.0350631721585475,1739141181.0602825,20.519980430603027,0.0,1739141181.0602849,20.519980430603027,-0.17926215730195016,1739141181.0602875,20.519980430603027,0.010754269698850917,1739141181.0602903,20.519980430603027,2.2143253294604976 +1739141181.0818381,20.53998041152954,42.4161120764978,1739141181.0818427,20.53998041152954,0.20322717712698957,1739141181.081848,20.53998041152954,41.920753240922934,1739141181.0818522,20.53998041152954,50.25289113288976,1739141181.0818546,20.53998041152954,1.0714884822017219,1739141181.0818572,20.53998041152954,0.11034310999183038,1739141181.0818596,20.53998041152954,0.7766568978351229,1739141181.0818617,20.53998041152954,0.0959110523644616,1739141181.0818636,20.53998041152954,1.8324025465057427,1739141181.081866,20.53998041152954,0.0,1739141181.0818691,20.53998041152954,-0.5258105437333274,1739141181.081871,20.53998041152954,0.011681744061430518,1739141181.0818734,20.53998041152954,2.1931899666450114 +1739141181.0989735,20.559980392456055,42.4161120764978,1739141181.098977,20.559980392456055,0.20322717712698957,1739141181.0989804,20.559980392456055,41.920753240922934,1739141181.0989838,20.559980392456055,50.25289113288976,1739141181.098985,20.559980392456055,1.0714884822017219,1739141181.098987,20.559980392456055,0.11034310999183038,1739141181.0989888,20.559980392456055,0.7766568978351229,1739141181.0989907,20.559980392456055,0.0959110523644616,1739141181.0989919,20.559980392456055,1.8324025465057427,1739141181.098994,20.559980392456055,0.0,1739141181.0989957,20.559980392456055,-0.3607874201392687,1739141181.0989978,20.559980392456055,0.011681744061430518,1739141181.098999,20.559980392456055,2.1931899666450114 +1739141181.118968,20.57998037338257,42.4161120764978,1739141181.1189728,20.57998037338257,0.20322717712698957,1739141181.1189773,20.57998037338257,41.920753240922934,1739141181.1189806,20.57998037338257,50.25289113288976,1739141181.118982,20.57998037338257,1.0714884822017219,1739141181.1189837,20.57998037338257,0.11034310999183038,1739141181.1189854,20.57998037338257,0.7766568978351229,1739141181.118987,20.57998037338257,0.0959110523644616,1739141181.1189885,20.57998037338257,1.8324025465057427,1739141181.1189904,20.57998037338257,0.0,1739141181.1189919,20.57998037338257,-0.3607874201392687,1739141181.1189935,20.57998037338257,0.011681744061430518,1739141181.1189947,20.57998037338257,2.1931899666450114 +1739141181.138895,20.599980354309082,42.4161120764978,1739141181.138898,20.599980354309082,0.20322717712698957,1739141181.1389015,20.599980354309082,41.920753240922934,1739141181.1389043,20.599980354309082,50.25289113288976,1739141181.1389055,20.599980354309082,1.0714884822017219,1739141181.1389072,20.599980354309082,0.11034310999183038,1739141181.1389086,20.599980354309082,0.7766568978351229,1739141181.1389105,20.599980354309082,0.0959110523644616,1739141181.1389117,20.599980354309082,1.8324025465057427,1739141181.1389134,20.599980354309082,0.0,1739141181.138915,20.599980354309082,-0.3607874201392687,1739141181.1389163,20.599980354309082,0.011681744061430518,1739141181.1389182,20.599980354309082,2.1931899666450114 +1739141181.158864,20.619980335235596,42.4161120764978,1739141181.1588683,20.619980335235596,0.20322717712698957,1739141181.1588733,20.619980335235596,41.920753240922934,1739141181.1588767,20.619980335235596,50.25289113288976,1739141181.1588783,20.619980335235596,1.0714884822017219,1739141181.1588802,20.619980335235596,0.11034310999183038,1739141181.1588826,20.619980335235596,0.7766568978351229,1739141181.158884,20.619980335235596,0.0959110523644616,1739141181.1588855,20.619980335235596,1.8324025465057427,1739141181.1588874,20.619980335235596,0.0,1739141181.158889,20.619980335235596,-0.3607874201392687,1739141181.1588907,20.619980335235596,0.011681744061430518,1739141181.158892,20.619980335235596,2.1931899666450114 +1739141181.1792872,20.63998031616211,42.65527772468831,1739141181.1792934,20.63998031616211,0.20617052100205147,1739141181.1792982,20.63998031616211,41.92577571953493,1739141181.1793022,20.63998031616211,50.158444386989,1739141181.1793046,20.63998031616211,1.002225548310343,1739141181.1793072,20.63998031616211,0.10570045792943307,1739141181.1793094,20.63998031616211,0.6967947274536024,1739141181.179311,20.63998031616211,0.09396661358558822,1739141181.1793127,20.63998031616211,1.8918834001306948,1739141181.1793146,20.63998031616211,0.0,1739141181.1793168,20.63998031616211,-0.16950186646538473,1739141181.1793182,20.63998031616211,0.01322023481888578,1739141181.1793199,20.63998031616211,2.152473670991043 +1739141181.1986086,20.659980297088623,42.65527772468831,1739141181.198611,20.659980297088623,0.20617052100205147,1739141181.1986136,20.659980297088623,41.92577571953493,1739141181.1986165,20.659980297088623,50.158444386989,1739141181.198618,20.659980297088623,1.002225548310343,1739141181.1986194,20.659980297088623,0.10570045792943307,1739141181.1986206,20.659980297088623,0.6967947274536024,1739141181.198622,20.659980297088623,0.09396661358558822,1739141181.198623,20.659980297088623,1.8918834001306948,1739141181.1986248,20.659980297088623,0.0,1739141181.198626,20.659980297088623,-0.26059027086034803,1739141181.198627,20.659980297088623,0.01322023481888578,1739141181.1986284,20.659980297088623,2.152473670991043 +1739141181.2186198,20.679980278015137,42.65527772468831,1739141181.2186227,20.679980278015137,0.20617052100205147,1739141181.2186255,20.679980278015137,41.92577571953493,1739141181.2186284,20.679980278015137,50.158444386989,1739141181.2186296,20.679980278015137,1.002225548310343,1739141181.2186313,20.679980278015137,0.10570045792943307,1739141181.2186327,20.679980278015137,0.6967947274536024,1739141181.218634,20.679980278015137,0.09396661358558822,1739141181.2186353,20.679980278015137,1.8918834001306948,1739141181.2186368,20.679980278015137,0.0,1739141181.2186384,20.679980278015137,-0.26059027086034803,1739141181.2186396,20.679980278015137,0.01322023481888578,1739141181.2186408,20.679980278015137,2.152473670991043 +1739141181.2398689,20.69998025894165,42.65527772468831,1739141181.239872,20.69998025894165,0.20617052100205147,1739141181.2398748,20.69998025894165,41.92577571953493,1739141181.2398777,20.69998025894165,50.158444386989,1739141181.239879,20.69998025894165,1.002225548310343,1739141181.2398808,20.69998025894165,0.10570045792943307,1739141181.239882,20.69998025894165,0.6967947274536024,1739141181.2398832,20.69998025894165,0.09396661358558822,1739141181.2398846,20.69998025894165,1.8918834001306948,1739141181.239886,20.69998025894165,0.0,1739141181.2398875,20.69998025894165,-0.26059027086034803,1739141181.2398887,20.69998025894165,0.01322023481888578,1739141181.2398899,20.69998025894165,2.152473670991043 +1739141181.262909,20.719980239868164,42.65527772468831,1739141181.2629185,20.719980239868164,0.20617052100205147,1739141181.262929,20.719980239868164,41.92577571953493,1739141181.2629395,20.719980239868164,50.158444386989,1739141181.262944,20.719980239868164,1.002225548310343,1739141181.2629502,20.719980239868164,0.10570045792943307,1739141181.262955,20.719980239868164,0.6967947274536024,1739141181.2629597,20.719980239868164,0.09396661358558822,1739141181.262964,20.719980239868164,1.8918834001306948,1739141181.2629702,20.719980239868164,0.0,1739141181.2629752,20.719980239868164,-0.26059027086034803,1739141181.2629795,20.719980239868164,0.01322023481888578,1739141181.2629843,20.719980239868164,2.152473670991043 +1739141181.2849941,20.739980220794678,42.65527772468831,1739141181.2850027,20.739980220794678,0.20617052100205147,1739141181.2850137,20.739980220794678,41.92577571953493,1739141181.2850232,20.739980220794678,50.158444386989,1739141181.285028,20.739980220794678,1.002225548310343,1739141181.285034,20.739980220794678,0.10570045792943307,1739141181.2850387,20.739980220794678,0.6967947274536024,1739141181.2850432,20.739980220794678,0.09396661358558822,1739141181.2850475,20.739980220794678,1.8918834001306948,1739141181.2850535,20.739980220794678,0.0,1739141181.2850583,20.739980220794678,-0.26059027086034803,1739141181.2850626,20.739980220794678,0.01322023481888578,1739141181.2850676,20.739980220794678,2.152473670991043 +1739141181.3042312,20.75998020172119,42.890433701618065,1739141181.3042405,20.75998020172119,0.2095172478194467,1739141181.3042507,20.75998020172119,41.93071399505046,1739141181.3042603,20.75998020172119,50.07630857364792,1739141181.304265,20.75998020172119,0.9445662200213572,1739141181.3042707,20.75998020172119,0.10193626450580083,1739141181.3042755,20.75998020172119,0.62349882717455,1739141181.3042803,20.75998020172119,0.0917448192304632,1739141181.3042846,20.75998020172119,1.9481714233293703,1739141181.3042908,20.75998020172119,0.0,1739141181.3042958,20.75998020172119,-0.08612560478765452,1739141181.3043,20.75998020172119,0.01551184595821379,1739141181.3043046,20.75998020172119,2.1173754820339106 +1739141181.3252316,20.779980182647705,42.890433701618065,1739141181.3252409,20.779980182647705,0.2095172478194467,1739141181.325251,20.779980182647705,41.93071399505046,1739141181.325261,20.779980182647705,50.07630857364792,1739141181.3252656,20.779980182647705,0.9445662200213572,1739141181.3252716,20.779980182647705,0.10193626450580083,1739141181.3252766,20.779980182647705,0.62349882717455,1739141181.3252811,20.779980182647705,0.0917448192304632,1739141181.3252857,20.779980182647705,1.9481714233293703,1739141181.3252912,20.779980182647705,0.0,1739141181.3252964,20.779980182647705,-0.16920405870454025,1739141181.3253007,20.779980182647705,0.01551184595821379,1739141181.3253055,20.779980182647705,2.1173754820339106 +1739141181.3422875,20.79998016357422,42.890433701618065,1739141181.3422961,20.79998016357422,0.2095172478194467,1739141181.3423066,20.79998016357422,41.93071399505046,1739141181.3423164,20.79998016357422,50.07630857364792,1739141181.3423214,20.79998016357422,0.9445662200213572,1739141181.3423274,20.79998016357422,0.10193626450580083,1739141181.342332,20.79998016357422,0.62349882717455,1739141181.3423364,20.79998016357422,0.0917448192304632,1739141181.342341,20.79998016357422,1.9481714233293703,1739141181.342347,20.79998016357422,0.0,1739141181.342352,20.79998016357422,-0.16920405870454025,1739141181.3423562,20.79998016357422,0.01551184595821379,1739141181.3423607,20.79998016357422,2.1173754820339106 +1739141181.3816266,20.82998013496399,42.890433701618065,1739141181.3816338,20.82998013496399,0.2095172478194467,1739141181.381643,20.82998013496399,41.93071399505046,1739141181.3816535,20.82998013496399,50.07630857364792,1739141181.3816595,20.82998013496399,0.9445662200213572,1739141181.381667,20.82998013496399,0.10193626450580083,1739141181.3816736,20.82998013496399,0.62349882717455,1739141181.38168,20.82998013496399,0.0917448192304632,1739141181.3816864,20.82998013496399,1.9481714233293703,1739141181.3816934,20.82998013496399,0.0,1739141181.3817003,20.82998013496399,-0.16920405870454025,1739141181.3817067,20.82998013496399,0.01551184595821379,1739141181.3817134,20.82998013496399,2.1173754820339106 +1739141181.3999274,20.849980115890503,42.890433701618065,1739141181.3999326,20.849980115890503,0.2095172478194467,1739141181.3999388,20.849980115890503,41.93071399505046,1739141181.399946,20.849980115890503,50.07630857364792,1739141181.39995,20.849980115890503,0.9445662200213572,1739141181.3999553,20.849980115890503,0.10193626450580083,1739141181.3999598,20.849980115890503,0.62349882717455,1739141181.399964,20.849980115890503,0.0917448192304632,1739141181.3999689,20.849980115890503,1.9481714233293703,1739141181.3999734,20.849980115890503,0.0,1739141181.3999784,20.849980115890503,-0.16920405870454025,1739141181.3999832,20.849980115890503,0.01551184595821379,1739141181.3999875,20.849980115890503,2.1173754820339106 +1739141181.419348,20.869980096817017,43.12234499356667,1739141181.4193532,20.869980096817017,0.2133641795293757,1739141181.4193597,20.869980096817017,42.406153062095896,1739141181.4193668,20.869980096817017,50.41062592494407,1739141181.419371,20.869980096817017,1.1975121204087837,1739141181.4193761,20.869980096817017,0.13421972253214615,1739141181.4193807,20.869980096817017,0.8536865504583134,1739141181.4193852,20.869980096817017,0.12115068743423907,1739141181.4193897,20.869980096817017,1.776803763431182,1739141181.4193945,20.869980096817017,0.0,1739141181.4193993,20.869980096817017,-0.4607053645903497,1739141181.4194038,20.869980096817017,0.01787952929319682,1739141181.4194083,20.869980096817017,2.0986989130198554 +1739141181.439288,20.88998007774353,43.12234499356667,1739141181.4392927,20.88998007774353,0.2133641795293757,1739141181.4392986,20.88998007774353,42.406153062095896,1739141181.4393058,20.88998007774353,50.41062592494407,1739141181.4393098,20.88998007774353,1.1975121204087837,1739141181.4393148,20.88998007774353,0.13421972253214615,1739141181.4393196,20.88998007774353,0.8536865504583134,1739141181.4393241,20.88998007774353,0.12115068743423907,1739141181.4393284,20.88998007774353,1.776803763431182,1739141181.4393334,20.88998007774353,0.0,1739141181.439338,20.88998007774353,-0.3218951495886735,1739141181.4393425,20.88998007774353,0.01787952929319682,1739141181.439347,20.88998007774353,2.0986989130198554 +1739141181.4590726,20.909980058670044,43.12234499356667,1739141181.4590764,20.909980058670044,0.2133641795293757,1739141181.4590807,20.909980058670044,42.406153062095896,1739141181.4590847,20.909980058670044,50.41062592494407,1739141181.459087,20.909980058670044,1.1975121204087837,1739141181.4590895,20.909980058670044,0.13421972253214615,1739141181.4590914,20.909980058670044,0.8536865504583134,1739141181.4590933,20.909980058670044,0.12115068743423907,1739141181.459095,20.909980058670044,1.776803763431182,1739141181.4590974,20.909980058670044,0.0,1739141181.4590993,20.909980058670044,-0.3218951495886735,1739141181.4591014,20.909980058670044,0.01787952929319682,1739141181.4591033,20.909980058670044,2.0986989130198554 +1739141181.4779239,20.929980039596558,43.12234499356667,1739141181.4779277,20.929980039596558,0.2133641795293757,1739141181.4779317,20.929980039596558,42.406153062095896,1739141181.477936,20.929980039596558,50.41062592494407,1739141181.4779382,20.929980039596558,1.1975121204087837,1739141181.477941,20.929980039596558,0.13421972253214615,1739141181.477943,20.929980039596558,0.8536865504583134,1739141181.4779449,20.929980039596558,0.12115068743423907,1739141181.4779465,20.929980039596558,1.776803763431182,1739141181.4779491,20.929980039596558,0.0,1739141181.4779513,20.929980039596558,-0.3218951495886735,1739141181.477953,20.929980039596558,0.01787952929319682,1739141181.4779549,20.929980039596558,2.0986989130198554 +1739141181.4976468,20.94998002052307,43.12234499356667,1739141181.497651,20.94998002052307,0.2133641795293757,1739141181.4976559,20.94998002052307,42.406153062095896,1739141181.49766,20.94998002052307,50.41062592494407,1739141181.497662,20.94998002052307,1.1975121204087837,1739141181.4976645,20.94998002052307,0.13421972253214615,1739141181.4976666,20.94998002052307,0.8536865504583134,1739141181.4976683,20.94998002052307,0.12115068743423907,1739141181.4976704,20.94998002052307,1.776803763431182,1739141181.497673,20.94998002052307,0.0,1739141181.497675,20.94998002052307,-0.3218951495886735,1739141181.4976768,20.94998002052307,0.01787952929319682,1739141181.4976785,20.94998002052307,2.0986989130198554 +1739141181.5203652,20.969980001449585,43.35123768463149,1739141181.520369,20.969980001449585,0.2177219047674468,1739141181.5203738,20.969980001449585,42.94362286091515,1739141181.5203779,20.969980001449585,50.71945013805257,1739141181.52038,20.969980001449585,1.4842450579865596,1739141181.5203824,20.969980001449585,0.17022664177850108,1739141181.5203846,20.969980001449585,1.1145124083774718,1739141181.5203862,20.969980001449585,0.15300274515871334,1739141181.5203884,20.969980001449585,1.6007716088404065,1739141181.5203907,20.969980001449585,0.0,1739141181.5203927,20.969980001449585,-0.5842065504812646,1739141181.5203946,20.969980001449585,0.020595614877894117,1739141181.5203962,20.969980001449585,2.0600679060223084 +1739141181.53749,20.9899799823761,43.35123768463149,1739141181.537493,20.9899799823761,0.2177219047674468,1739141181.5374966,20.9899799823761,42.94362286091515,1739141181.5375001,20.9899799823761,50.71945013805257,1739141181.537502,20.9899799823761,1.4842450579865596,1739141181.5375042,20.9899799823761,0.17022664177850108,1739141181.537506,20.9899799823761,1.1145124083774718,1739141181.5375075,20.9899799823761,0.15300274515871334,1739141181.5375092,20.9899799823761,1.6007716088404065,1739141181.537511,20.9899799823761,0.0,1739141181.5375133,20.9899799823761,-0.4592962971819019,1739141181.537515,20.9899799823761,0.020595614877894117,1739141181.5375166,20.9899799823761,2.0600679060223084 +1739141181.5590403,21.009979963302612,43.35123768463149,1739141181.5590458,21.009979963302612,0.2177219047674468,1739141181.5590522,21.009979963302612,42.94362286091515,1739141181.5590618,21.009979963302612,50.71945013805257,1739141181.5590672,21.009979963302612,1.4842450579865596,1739141181.5590737,21.009979963302612,0.17022664177850108,1739141181.5590794,21.009979963302612,1.1145124083774718,1739141181.5590818,21.009979963302612,0.15300274515871334,1739141181.5590842,21.009979963302612,1.6007716088404065,1739141181.559087,21.009979963302612,0.0,1739141181.55909,21.009979963302612,-0.4592962971819019,1739141181.5590928,21.009979963302612,0.020595614877894117,1739141181.5590951,21.009979963302612,2.0600679060223084 +1739141181.5792317,21.029979944229126,43.35123768463149,1739141181.5792382,21.029979944229126,0.2177219047674468,1739141181.579245,21.029979944229126,42.94362286091515,1739141181.5792513,21.029979944229126,50.71945013805257,1739141181.5792546,21.029979944229126,1.4842450579865596,1739141181.579258,21.029979944229126,0.17022664177850108,1739141181.5792615,21.029979944229126,1.1145124083774718,1739141181.579265,21.029979944229126,0.15300274515871334,1739141181.579268,21.029979944229126,1.6007716088404065,1739141181.579272,21.029979944229126,0.0,1739141181.5792758,21.029979944229126,-0.4592962971819019,1739141181.5792792,21.029979944229126,0.020595614877894117,1739141181.5792832,21.029979944229126,2.0600679060223084 +1739141181.5974016,21.04997992515564,43.35123768463149,1739141181.5974054,21.04997992515564,0.2177219047674468,1739141181.597409,21.04997992515564,42.94362286091515,1739141181.597412,21.04997992515564,50.71945013805257,1739141181.5974135,21.04997992515564,1.4842450579865596,1739141181.5974157,21.04997992515564,0.17022664177850108,1739141181.5974174,21.04997992515564,1.1145124083774718,1739141181.5974188,21.04997992515564,0.15300274515871334,1739141181.5974202,21.04997992515564,1.6007716088404065,1739141181.5974221,21.04997992515564,0.0,1739141181.5974236,21.04997992515564,-0.4592962971819019,1739141181.5974252,21.04997992515564,0.020595614877894117,1739141181.5974267,21.04997992515564,2.0600679060223084 +1739141181.6180973,21.069979906082153,43.35123768463149,1739141181.6181002,21.069979906082153,0.2177219047674468,1739141181.6181037,21.069979906082153,42.94362286091515,1739141181.618107,21.069979906082153,50.71945013805257,1739141181.6181087,21.069979906082153,1.4842450579865596,1739141181.6181102,21.069979906082153,0.17022664177850108,1739141181.6181118,21.069979906082153,1.1145124083774718,1739141181.6181133,21.069979906082153,0.15300274515871334,1739141181.6181147,21.069979906082153,1.6007716088404065,1739141181.6181164,21.069979906082153,0.0,1739141181.6181178,21.069979906082153,-0.4592962971819019,1739141181.6181195,21.069979906082153,0.020595614877894117,1739141181.6181207,21.069979906082153,2.0600679060223084 +1739141181.6397848,21.089979887008667,43.575272095727684,1739141181.6397903,21.089979887008667,0.22268951852969288,1739141181.639796,21.089979887008667,42.94810354913707,1739141181.6398013,21.089979887008667,50.61486725573399,1739141181.6398048,21.089979887008667,1.381343963064782,1739141181.6398087,21.089979887008667,0.16312849310790825,1739141181.639813,21.089979887008667,0.9876245914023163,1739141181.6398163,21.089979887008667,0.1488991880264539,1739141181.6398199,21.089979887008667,1.6841161654728412,1739141181.639824,21.089979887008667,0.0,1739141181.6398275,21.089979887008667,-0.20395739244530994,1739141181.6398315,21.089979887008667,0.024249396721983903,1739141181.6398351,21.089979887008667,2.0096635732941484 +1739141181.6599147,21.10997986793518,43.575272095727684,1739141181.6599205,21.10997986793518,0.22268951852969288,1739141181.6599257,21.10997986793518,42.94810354913707,1739141181.6599314,21.10997986793518,50.61486725573399,1739141181.6599345,21.10997986793518,1.381343963064782,1739141181.6599386,21.10997986793518,0.16312849310790825,1739141181.6599424,21.10997986793518,0.9876245914023163,1739141181.6599457,21.10997986793518,0.1488991880264539,1739141181.6599493,21.10997986793518,1.6841161654728412,1739141181.659953,21.10997986793518,0.0,1739141181.6599565,21.10997986793518,-0.3255474078213072,1739141181.65996,21.10997986793518,0.024249396721983903,1739141181.6599638,21.10997986793518,2.0096635732941484 +1739141181.6786253,21.129979848861694,43.575272095727684,1739141181.6786296,21.129979848861694,0.22268951852969288,1739141181.6786346,21.129979848861694,42.94810354913707,1739141181.6786394,21.129979848861694,50.61486725573399,1739141181.6786408,21.129979848861694,1.381343963064782,1739141181.6786432,21.129979848861694,0.16312849310790825,1739141181.6786451,21.129979848861694,0.9876245914023163,1739141181.6786466,21.129979848861694,0.1488991880264539,1739141181.6786478,21.129979848861694,1.6841161654728412,1739141181.6786501,21.129979848861694,0.0,1739141181.6786518,21.129979848861694,-0.3255474078213072,1739141181.6786532,21.129979848861694,0.024249396721983903,1739141181.6786547,21.129979848861694,2.0096635732941484 +1739141181.6979144,21.149979829788208,43.575272095727684,1739141181.6979184,21.149979829788208,0.22268951852969288,1739141181.6979225,21.149979829788208,42.94810354913707,1739141181.6979253,21.149979829788208,50.61486725573399,1739141181.697927,21.149979829788208,1.381343963064782,1739141181.697929,21.149979829788208,0.16312849310790825,1739141181.6979308,21.149979829788208,0.9876245914023163,1739141181.6979325,21.149979829788208,0.1488991880264539,1739141181.6979344,21.149979829788208,1.6841161654728412,1739141181.6979363,21.149979829788208,0.0,1739141181.6979384,21.149979829788208,-0.3255474078213072,1739141181.6979399,21.149979829788208,0.024249396721983903,1739141181.6979418,21.149979829788208,2.0096635732941484 +1739141181.7178528,21.16997981071472,43.575272095727684,1739141181.717856,21.16997981071472,0.22268951852969288,1739141181.7178595,21.16997981071472,42.94810354913707,1739141181.7178628,21.16997981071472,50.61486725573399,1739141181.7178645,21.16997981071472,1.381343963064782,1739141181.717866,21.16997981071472,0.16312849310790825,1739141181.7178676,21.16997981071472,0.9876245914023163,1739141181.717869,21.16997981071472,0.1488991880264539,1739141181.7178702,21.16997981071472,1.6841161654728412,1739141181.717872,21.16997981071472,0.0,1739141181.7178736,21.16997981071472,-0.3255474078213072,1739141181.717875,21.16997981071472,0.024249396721983903,1739141181.7178767,21.16997981071472,2.0096635732941484 +1739141181.7392175,21.189979791641235,43.794378911368064,1739141181.7392247,21.189979791641235,0.22844310493112907,1739141181.7392313,21.189979791641235,42.952485685449886,1739141181.7392383,21.189979791641235,50.53715549739568,1739141181.7392418,21.189979791641235,1.3089451851282075,1739141181.7392468,21.189979791641235,0.15889498292737433,1739141181.739251,21.189979791641235,0.8859999142518714,1739141181.739255,21.189979791641235,0.14580213371478018,1739141181.7392592,21.189979791641235,1.7539857439378053,1739141181.7392642,21.189979791641235,0.0,1739141181.7392678,21.189979791641235,-0.12178050063064516,1739141181.739272,21.189979791641235,0.0287836022497194,1739141181.739276,21.189979791641235,1.9727981536071102 +1739141181.7590451,21.20997977256775,43.794378911368064,1739141181.7590501,21.20997977256775,0.22844310493112907,1739141181.7590563,21.20997977256775,42.952485685449886,1739141181.7590625,21.20997977256775,50.53715549739568,1739141181.7590656,21.20997977256775,1.3089451851282075,1739141181.7590702,21.20997977256775,0.15889498292737433,1739141181.7590735,21.20997977256775,0.8859999142518714,1739141181.7590775,21.20997977256775,0.14580213371478018,1739141181.759081,21.20997977256775,1.7539857439378053,1739141181.7590847,21.20997977256775,0.0,1739141181.759089,21.20997977256775,-0.21881240966930493,1739141181.759093,21.20997977256775,0.0287836022497194,1739141181.7590969,21.20997977256775,1.9727981536071102 +1739141181.7791665,21.229979753494263,43.794378911368064,1739141181.7791712,21.229979753494263,0.22844310493112907,1739141181.779177,21.229979753494263,42.952485685449886,1739141181.7791831,21.229979753494263,50.53715549739568,1739141181.7791867,21.229979753494263,1.3089451851282075,1739141181.7791908,21.229979753494263,0.15889498292737433,1739141181.7791948,21.229979753494263,0.8859999142518714,1739141181.7791986,21.229979753494263,0.14580213371478018,1739141181.7792022,21.229979753494263,1.7539857439378053,1739141181.779206,21.229979753494263,0.0,1739141181.77921,21.229979753494263,-0.21881240966930493,1739141181.779214,21.229979753494263,0.0287836022497194,1739141181.7792194,21.229979753494263,1.9727981536071102 +1739141181.7993042,21.249979734420776,43.794378911368064,1739141181.7993095,21.249979734420776,0.22844310493112907,1739141181.799317,21.249979734420776,42.952485685449886,1739141181.7993238,21.249979734420776,50.53715549739568,1739141181.7993279,21.249979734420776,1.3089451851282075,1739141181.799332,21.249979734420776,0.15889498292737433,1739141181.799336,21.249979734420776,0.8859999142518714,1739141181.7993395,21.249979734420776,0.14580213371478018,1739141181.7993433,21.249979734420776,1.7539857439378053,1739141181.799347,21.249979734420776,0.0,1739141181.7993507,21.249979734420776,-0.21881240966930493,1739141181.7993543,21.249979734420776,0.0287836022497194,1739141181.799359,21.249979734420776,1.9727981536071102 +1739141181.8202949,21.26997971534729,43.794378911368064,1739141181.8203,21.26997971534729,0.22844310493112907,1739141181.820305,21.26997971534729,42.952485685449886,1739141181.8203104,21.26997971534729,50.53715549739568,1739141181.8203137,21.26997971534729,1.3089451851282075,1739141181.8203175,21.26997971534729,0.15889498292737433,1739141181.8203208,21.26997971534729,0.8859999142518714,1739141181.8203242,21.26997971534729,0.14580213371478018,1739141181.8203278,21.26997971534729,1.7539857439378053,1739141181.8203313,21.26997971534729,0.0,1739141181.8203347,21.26997971534729,-0.21881240966930493,1739141181.8203382,21.26997971534729,0.0287836022497194,1739141181.8203416,21.26997971534729,1.9727981536071102 +1739141181.8396392,21.289979696273804,43.794378911368064,1739141181.8396437,21.289979696273804,0.22844310493112907,1739141181.839649,21.289979696273804,42.952485685449886,1739141181.8396544,21.289979696273804,50.53715549739568,1739141181.8396573,21.289979696273804,1.3089451851282075,1739141181.8396611,21.289979696273804,0.15889498292737433,1739141181.8396645,21.289979696273804,0.8859999142518714,1739141181.8396683,21.289979696273804,0.14580213371478018,1739141181.8396716,21.289979696273804,1.7539857439378053,1739141181.8396757,21.289979696273804,0.0,1739141181.8396792,21.289979696273804,-0.21881240966930493,1739141181.8396826,21.289979696273804,0.0287836022497194,1739141181.8396857,21.289979696273804,1.9727981536071102 +1739141181.8594189,21.309979677200317,44.010266710183274,1739141181.8594246,21.309979677200317,0.23511959369233804,1739141181.85943,21.309979677200317,43.22395451881835,1739141181.8594358,21.309979677200317,50.6860813527236,1739141181.859439,21.309979677200317,1.450317510992086,1739141181.8594427,21.309979677200317,0.18005844195021484,1739141181.8594475,21.309979677200317,0.9910224103372808,1739141181.8594522,21.309979677200317,0.16513540119222467,1739141181.8594556,21.309979677200317,1.6818287915231636,1739141181.8594599,21.309979677200317,0.0,1739141181.859464,21.309979677200317,-0.3144942274493826,1739141181.8594673,21.309979677200317,0.03348446688540545,1739141181.8594706,21.309979677200317,1.9507602258404748 +1739141181.8793705,21.32997965812683,44.010266710183274,1739141181.879376,21.32997965812683,0.23511959369233804,1739141181.8793805,21.32997965812683,43.22395451881835,1739141181.8793848,21.32997965812683,50.6860813527236,1739141181.8793871,21.32997965812683,1.450317510992086,1739141181.8793888,21.32997965812683,0.18005844195021484,1739141181.879391,21.32997965812683,0.9910224103372808,1739141181.8793933,21.32997965812683,0.16513540119222467,1739141181.8793948,21.32997965812683,1.6818287915231636,1739141181.8793967,21.32997965812683,0.0,1739141181.879398,21.32997965812683,-0.26893143431731126,1739141181.8794003,21.32997965812683,0.03348446688540545,1739141181.8794026,21.32997965812683,1.9507602258404748 +1739141181.898735,21.349979639053345,44.010266710183274,1739141181.8987393,21.349979639053345,0.23511959369233804,1739141181.8987427,21.349979639053345,43.22395451881835,1739141181.8987463,21.349979639053345,50.6860813527236,1739141181.898748,21.349979639053345,1.450317510992086,1739141181.8987496,21.349979639053345,0.18005844195021484,1739141181.8987515,21.349979639053345,0.9910224103372808,1739141181.8987527,21.349979639053345,0.16513540119222467,1739141181.8987541,21.349979639053345,1.6818287915231636,1739141181.8987556,21.349979639053345,0.0,1739141181.8987575,21.349979639053345,-0.26893143431731126,1739141181.8987586,21.349979639053345,0.03348446688540545,1739141181.8987598,21.349979639053345,1.9507602258404748 +1739141181.9170084,21.36997961997986,44.010266710183274,1739141181.917013,21.36997961997986,0.23511959369233804,1739141181.9170177,21.36997961997986,43.22395451881835,1739141181.9170206,21.36997961997986,50.6860813527236,1739141181.9170222,21.36997961997986,1.450317510992086,1739141181.917024,21.36997961997986,0.18005844195021484,1739141181.9170258,21.36997961997986,0.9910224103372808,1739141181.9170272,21.36997961997986,0.16513540119222467,1739141181.9170291,21.36997961997986,1.6818287915231636,1739141181.9170315,21.36997961997986,0.0,1739141181.9170332,21.36997961997986,-0.26893143431731126,1739141181.9170344,21.36997961997986,0.03348446688540545,1739141181.917036,21.36997961997986,1.9507602258404748 +1739141181.9374297,21.389979600906372,44.010266710183274,1739141181.937433,21.389979600906372,0.23511959369233804,1739141181.937436,21.389979600906372,43.22395451881835,1739141181.93744,21.389979600906372,50.6860813527236,1739141181.937442,21.389979600906372,1.450317510992086,1739141181.9374435,21.389979600906372,0.18005844195021484,1739141181.9374464,21.389979600906372,0.9910224103372808,1739141181.937448,21.389979600906372,0.16513540119222467,1739141181.9374495,21.389979600906372,1.6818287915231636,1739141181.9374516,21.389979600906372,0.0,1739141181.9374535,21.389979600906372,-0.26893143431731126,1739141181.9374552,21.389979600906372,0.03348446688540545,1739141181.9374566,21.389979600906372,1.9507602258404748 +1739141181.9590585,21.409979581832886,44.222991900472415,1739141181.9590628,21.409979581832886,0.24271733959151565,1739141181.9590678,21.409979581832886,43.33522343997637,1739141181.9590733,21.409979581832886,50.68933334097208,1739141181.9590764,21.409979581832886,1.4534920709489365,1739141181.9590802,21.409979581832886,0.18509930233911984,1739141181.9590838,21.409979581832886,0.9607323951813814,1739141181.9590871,21.409979581832886,0.17029978509480184,1739141181.9590905,21.409979581832886,1.7023297836387263,1739141181.9590943,21.409979581832886,0.0,1739141181.9590979,21.409979581832886,-0.16187764177638136,1739141181.9591022,21.409979581832886,0.03853879178857235,1739141181.959106,21.409979581832886,1.9151854473289187 +1739141181.979891,21.4299795627594,44.222991900472415,1739141181.9798956,21.4299795627594,0.24271733959151565,1739141181.9799008,21.4299795627594,43.33522343997637,1739141181.9799068,21.4299795627594,50.68933334097208,1739141181.9799097,21.4299795627594,1.4534920709489365,1739141181.979914,21.4299795627594,0.18509930233911984,1739141181.9799175,21.4299795627594,0.9607323951813814,1739141181.9799213,21.4299795627594,0.17029978509480184,1739141181.979925,21.4299795627594,1.7023297836387263,1739141181.9799287,21.4299795627594,0.0,1739141181.979933,21.4299795627594,-0.21285566369019238,1739141181.9799364,21.4299795627594,0.03853879178857235,1739141181.97994,21.4299795627594,1.9151854473289187 +1739141181.9992921,21.449979543685913,44.222991900472415,1739141181.9992962,21.449979543685913,0.24271733959151565,1739141181.9993014,21.449979543685913,43.33522343997637,1739141181.9993067,21.449979543685913,50.68933334097208,1739141181.9993098,21.449979543685913,1.4534920709489365,1739141181.9993138,21.449979543685913,0.18509930233911984,1739141181.9993172,21.449979543685913,0.9607323951813814,1739141181.9993207,21.449979543685913,0.17029978509480184,1739141181.999324,21.449979543685913,1.7023297836387263,1739141181.9993277,21.449979543685913,0.0,1739141181.9993312,21.449979543685913,-0.21285566369019238,1739141181.9993348,21.449979543685913,0.03853879178857235,1739141181.9993382,21.449979543685913,1.9151854473289187 +1739141182.0187645,21.469979524612427,44.222991900472415,1739141182.018768,21.469979524612427,0.24271733959151565,1739141182.018772,21.469979524612427,43.33522343997637,1739141182.0187747,21.469979524612427,50.68933334097208,1739141182.0187767,21.469979524612427,1.4534920709489365,1739141182.0187783,21.469979524612427,0.18509930233911984,1739141182.0187807,21.469979524612427,0.9607323951813814,1739141182.0187821,21.469979524612427,0.17029978509480184,1739141182.0187836,21.469979524612427,1.7023297836387263,1739141182.0187855,21.469979524612427,0.0,1739141182.0187874,21.469979524612427,-0.21285566369019238,1739141182.0187888,21.469979524612427,0.03853879178857235,1739141182.0187902,21.469979524612427,1.9151854473289187 +1739141182.0376756,21.48997950553894,44.222991900472415,1739141182.0376792,21.48997950553894,0.24271733959151565,1739141182.0376828,21.48997950553894,43.33522343997637,1739141182.0376866,21.48997950553894,50.68933334097208,1739141182.0377042,21.48997950553894,1.4534920709489365,1739141182.037706,21.48997950553894,0.18509930233911984,1739141182.0377078,21.48997950553894,0.9607323951813814,1739141182.0377092,21.48997950553894,0.17029978509480184,1739141182.0377107,21.48997950553894,1.7023297836387263,1739141182.0377126,21.48997950553894,0.0,1739141182.0377312,21.48997950553894,-0.21285566369019238,1739141182.0377328,21.48997950553894,0.03853879178857235,1739141182.0377338,21.48997950553894,1.9151854473289187 +1739141182.0578825,21.509979486465454,44.222991900472415,1739141182.0578868,21.509979486465454,0.24271733959151565,1739141182.0578897,21.509979486465454,43.33522343997637,1739141182.0578928,21.509979486465454,50.68933334097208,1739141182.0578945,21.509979486465454,1.4534920709489365,1739141182.0578961,21.509979486465454,0.18509930233911984,1739141182.0578976,21.509979486465454,0.9607323951813814,1739141182.057899,21.509979486465454,0.17029978509480184,1739141182.0579,21.509979486465454,1.7023297836387263,1739141182.0579019,21.509979486465454,0.0,1739141182.0579035,21.509979486465454,-0.21285566369019238,1739141182.057905,21.509979486465454,0.03853879178857235,1739141182.0579064,21.509979486465454,1.9151854473289187 +1739141182.0775385,21.529979467391968,44.43241414645743,1739141182.0775418,21.529979467391968,0.2513234861091149,1739141182.0775452,21.529979467391968,43.95027247275192,1739141182.077548,21.529979467391968,51.04434283031607,1739141182.0775495,21.529979467391968,1.870258609906207,1739141182.0775514,21.529979467391968,0.2401263875428355,1739141182.0775526,21.529979467391968,1.3254342930309764,1739141182.077554,21.529979467391968,0.21928178695152795,1739141182.0775554,21.529979467391968,1.471256819361681,1739141182.077557,21.529979467391968,0.0,1739141182.0775585,21.529979467391968,-0.6114221653359011,1739141182.0775597,21.529979467391968,0.04416519093785745,1739141182.0775611,21.529979467391968,1.8928853176751113 +1739141182.0985816,21.54997944831848,44.43241414645743,1739141182.098585,21.54997944831848,0.2513234861091149,1739141182.0985882,21.54997944831848,43.95027247275192,1739141182.0985916,21.54997944831848,51.04434283031607,1739141182.098593,21.54997944831848,1.870258609906207,1739141182.098595,21.54997944831848,0.2401263875428355,1739141182.0985966,21.54997944831848,1.3254342930309764,1739141182.0985985,21.54997944831848,0.21928178695152795,1739141182.0985997,21.54997944831848,1.471256819361681,1739141182.0986018,21.54997944831848,0.0,1739141182.0986032,21.54997944831848,-0.4216284983134302,1739141182.0986054,21.54997944831848,0.04416519093785745,1739141182.0986066,21.54997944831848,1.8928853176751113 +1739141182.1175268,21.569979429244995,44.43241414645743,1739141182.1175306,21.569979429244995,0.2513234861091149,1739141182.1175344,21.569979429244995,43.95027247275192,1739141182.1175375,21.569979429244995,51.04434283031607,1739141182.1175392,21.569979429244995,1.870258609906207,1739141182.117541,21.569979429244995,0.2401263875428355,1739141182.1175427,21.569979429244995,1.3254342930309764,1739141182.1175442,21.569979429244995,0.21928178695152795,1739141182.1175458,21.569979429244995,1.471256819361681,1739141182.1175475,21.569979429244995,0.0,1739141182.1175494,21.569979429244995,-0.4216284983134302,1739141182.1175508,21.569979429244995,0.04416519093785745,1739141182.1175528,21.569979429244995,1.8928853176751113 +1739141182.1372876,21.58997941017151,44.43241414645743,1739141182.1372914,21.58997941017151,0.2513234861091149,1739141182.137296,21.58997941017151,43.95027247275192,1739141182.1372993,21.58997941017151,51.04434283031607,1739141182.1373014,21.58997941017151,1.870258609906207,1739141182.1373034,21.58997941017151,0.2401263875428355,1739141182.1373048,21.58997941017151,1.3254342930309764,1739141182.1373065,21.58997941017151,0.21928178695152795,1739141182.1373076,21.58997941017151,1.471256819361681,1739141182.1373098,21.58997941017151,0.0,1739141182.1373115,21.58997941017151,-0.4216284983134302,1739141182.1373158,21.58997941017151,0.04416519093785745,1739141182.1373224,21.58997941017151,1.8928853176751113 +1739141182.1571665,21.609979391098022,44.43241414645743,1739141182.1571732,21.609979391098022,0.2513234861091149,1739141182.1571789,21.609979391098022,43.95027247275192,1739141182.1571856,21.609979391098022,51.04434283031607,1739141182.157189,21.609979391098022,1.870258609906207,1739141182.1571941,21.609979391098022,0.2401263875428355,1739141182.1571991,21.609979391098022,1.3254342930309764,1739141182.1572032,21.609979391098022,0.21928178695152795,1739141182.157205,21.609979391098022,1.471256819361681,1739141182.1572065,21.609979391098022,0.0,1739141182.1572082,21.609979391098022,-0.4216284983134302,1739141182.1572099,21.609979391098022,0.04416519093785745,1739141182.157212,21.609979391098022,1.8928853176751113 +1739141182.177596,21.629979372024536,44.638235614820324,1739141182.1775997,21.629979372024536,0.2609681158254338,1739141182.1776037,21.629979372024536,43.95438890211918,1739141182.177607,21.629979372024536,50.97430646654851,1739141182.1776087,21.629979372024536,1.7757419553980156,1739141182.1776114,21.629979372024536,0.23466684638799926,1739141182.177613,21.629979372024536,1.1948223370528885,1739141182.1776147,21.629979372024536,0.21584177096346763,1739141182.177616,21.629979372024536,1.550165651339959,1739141182.1776175,21.629979372024536,0.0,1739141182.1776197,21.629979372024536,-0.19350329712714065,1739141182.1776214,21.629979372024536,0.05021656377672019,1739141182.1776228,21.629979372024536,1.8523000509170289 +1739141182.1972108,21.64997935295105,44.638235614820324,1739141182.1972146,21.64997935295105,0.2609681158254338,1739141182.1972184,21.64997935295105,43.95438890211918,1739141182.1972213,21.64997935295105,50.97430646654851,1739141182.1972237,21.64997935295105,1.7757419553980156,1739141182.1972256,21.64997935295105,0.23466684638799926,1739141182.197227,21.64997935295105,1.1948223370528885,1739141182.197229,21.64997935295105,0.21584177096346763,1739141182.1972303,21.64997935295105,1.550165651339959,1739141182.1972325,21.64997935295105,0.0,1739141182.1972342,21.64997935295105,-0.3021343995770698,1739141182.1972363,21.64997935295105,0.05021656377672019,1739141182.1972377,21.64997935295105,1.8523000509170289 +1739141182.2172644,21.669979333877563,44.638235614820324,1739141182.2172682,21.669979333877563,0.2609681158254338,1739141182.217272,21.669979333877563,43.95438890211918,1739141182.2172754,21.669979333877563,50.97430646654851,1739141182.2172766,21.669979333877563,1.7757419553980156,1739141182.217279,21.669979333877563,0.23466684638799926,1739141182.2172806,21.669979333877563,1.1948223370528885,1739141182.2172823,21.669979333877563,0.21584177096346763,1739141182.2172837,21.669979333877563,1.550165651339959,1739141182.2172883,21.669979333877563,0.0,1739141182.2172952,21.669979333877563,-0.3021343995770698,1739141182.2172997,21.669979333877563,0.05021656377672019,1739141182.217304,21.669979333877563,1.8523000509170289 +1739141182.2371655,21.689979314804077,44.638235614820324,1739141182.2371733,21.689979314804077,0.2609681158254338,1739141182.23718,21.689979314804077,43.95438890211918,1739141182.2371874,21.689979314804077,50.97430646654851,1739141182.237193,21.689979314804077,1.7757419553980156,1739141182.2371988,21.689979314804077,0.23466684638799926,1739141182.2372026,21.689979314804077,1.1948223370528885,1739141182.2372053,21.689979314804077,0.21584177096346763,1739141182.2372077,21.689979314804077,1.550165651339959,1739141182.2372098,21.689979314804077,0.0,1739141182.237215,21.689979314804077,-0.3021343995770698,1739141182.237218,21.689979314804077,0.05021656377672019,1739141182.237221,21.689979314804077,1.8523000509170289 +1739141182.257289,21.70997929573059,44.638235614820324,1739141182.257293,21.70997929573059,0.2609681158254338,1739141182.257297,21.70997929573059,43.95438890211918,1739141182.2573001,21.70997929573059,50.97430646654851,1739141182.2573018,21.70997929573059,1.7757419553980156,1739141182.2573037,21.70997929573059,0.23466684638799926,1739141182.2573054,21.70997929573059,1.1948223370528885,1739141182.2573068,21.70997929573059,0.21584177096346763,1739141182.2573082,21.70997929573059,1.550165651339959,1739141182.25731,21.70997929573059,0.0,1739141182.2573118,21.70997929573059,-0.3021343995770698,1739141182.2573133,21.70997929573059,0.05021656377672019,1739141182.2573154,21.70997929573059,1.8523000509170289 +1739141182.2782645,21.729979276657104,44.638235614820324,1739141182.278268,21.729979276657104,0.2609681158254338,1739141182.2782717,21.729979276657104,43.95438890211918,1739141182.278275,21.729979276657104,50.97430646654851,1739141182.2782772,21.729979276657104,1.7757419553980156,1739141182.278279,21.729979276657104,0.23466684638799926,1739141182.278281,21.729979276657104,1.1948223370528885,1739141182.2782824,21.729979276657104,0.21584177096346763,1739141182.278284,21.729979276657104,1.550165651339959,1739141182.2782862,21.729979276657104,0.0,1739141182.2782884,21.729979276657104,-0.3021343995770698,1739141182.27829,21.729979276657104,0.05021656377672019,1739141182.2782915,21.729979276657104,1.8523000509170289 +1739141182.2982664,21.749979257583618,44.84015987893439,1739141182.2982702,21.749979257583618,0.27174696352888006,1739141182.2982743,21.749979257583618,43.95842738740146,1739141182.2982779,21.749979257583618,50.91486964928297,1739141182.29828,21.749979257583618,1.7010939221677708,1739141182.2982824,21.749979257583618,0.23109121051959786,1739141182.2982843,21.749979257583618,1.0792656190238292,1739141182.2982857,21.749979257583618,0.2124757470454946,1739141182.2982874,21.749979257583618,1.6235002787612405,1739141182.2982893,21.749979257583618,0.0,1739141182.2982912,21.749979257583618,-0.09882728525569302,1739141182.2982926,21.749979257583618,0.05727479497807723,1739141182.2982943,21.749979257583618,1.8191405239608447 +1739141182.3181427,21.769979238510132,44.84015987893439,1739141182.3181465,21.769979238510132,0.27174696352888006,1739141182.3181503,21.769979238510132,43.95842738740146,1739141182.318154,21.769979238510132,50.91486964928297,1739141182.318156,21.769979238510132,1.7010939221677708,1739141182.3181581,21.769979238510132,0.23109121051959786,1739141182.31816,21.769979238510132,1.0792656190238292,1739141182.318162,21.769979238510132,0.2124757470454946,1739141182.3181636,21.769979238510132,1.6235002787612405,1739141182.3181658,21.769979238510132,0.0,1739141182.3181674,21.769979238510132,-0.1956402451996042,1739141182.3181696,21.769979238510132,0.05727479497807723,1739141182.318171,21.769979238510132,1.8191405239608447 +1739141182.3380032,21.789979219436646,44.84015987893439,1739141182.3380075,21.789979219436646,0.27174696352888006,1739141182.3380115,21.789979219436646,43.95842738740146,1739141182.3380153,21.789979219436646,50.91486964928297,1739141182.3380167,21.789979219436646,1.7010939221677708,1739141182.3380194,21.789979219436646,0.23109121051959786,1739141182.3380208,21.789979219436646,1.0792656190238292,1739141182.338023,21.789979219436646,0.2124757470454946,1739141182.3380244,21.789979219436646,1.6235002787612405,1739141182.3380263,21.789979219436646,0.0,1739141182.3380284,21.789979219436646,-0.1956402451996042,1739141182.33803,21.789979219436646,0.05727479497807723,1739141182.3380315,21.789979219436646,1.8191405239608447 +1739141182.359018,21.80997920036316,44.84015987893439,1739141182.3590233,21.80997920036316,0.27174696352888006,1739141182.3590274,21.80997920036316,43.95842738740146,1739141182.359031,21.80997920036316,50.91486964928297,1739141182.3590326,21.80997920036316,1.7010939221677708,1739141182.3590345,21.80997920036316,0.23109121051959786,1739141182.3590367,21.80997920036316,1.0792656190238292,1739141182.359038,21.80997920036316,0.2124757470454946,1739141182.3590398,21.80997920036316,1.6235002787612405,1739141182.359042,21.80997920036316,0.0,1739141182.359044,21.80997920036316,-0.1956402451996042,1739141182.359046,21.80997920036316,0.05727479497807723,1739141182.3590474,21.80997920036316,1.8191405239608447 +1739141182.3780708,21.829979181289673,44.84015987893439,1739141182.3780742,21.829979181289673,0.27174696352888006,1739141182.378078,21.829979181289673,43.95842738740146,1739141182.378081,21.829979181289673,50.91486964928297,1739141182.3780828,21.829979181289673,1.7010939221677708,1739141182.3780847,21.829979181289673,0.23109121051959786,1739141182.378086,21.829979181289673,1.0792656190238292,1739141182.378088,21.829979181289673,0.2124757470454946,1739141182.3780894,21.829979181289673,1.6235002787612405,1739141182.3780913,21.829979181289673,0.0,1739141182.378093,21.829979181289673,-0.1956402451996042,1739141182.3780947,21.829979181289673,0.05727479497807723,1739141182.3780963,21.829979181289673,1.8191405239608447 +1739141182.397467,21.849979162216187,45.03886036058447,1739141182.3974707,21.849979162216187,0.28383553750750856,1739141182.397474,21.849979162216187,44.98774527576247,1739141182.3974774,21.849979162216187,51.42811831356931,1739141182.3974788,21.849979162216187,2.51788706589856,1739141182.397481,21.849979162216187,0.3363696037443609,1739141182.3974824,21.849979162216187,1.814497676933082,1739141182.397484,21.849979162216187,0.30313881837723444,1739141182.3974855,21.849979162216187,1.2098442848260198,1739141182.3974876,21.849979162216187,0.0,1739141182.3974893,21.849979162216187,-0.9456788472558526,1739141182.3974915,21.849979162216187,0.06497342248524306,1739141182.3974938,21.849979162216187,1.7983617145897361 +1739141182.4171846,21.8699791431427,45.03886036058447,1739141182.4171877,21.8699791431427,0.28383553750750856,1739141182.417191,21.8699791431427,44.98774527576247,1739141182.4171941,21.8699791431427,51.42811831356931,1739141182.4171958,21.8699791431427,2.51788706589856,1739141182.4171982,21.8699791431427,0.3363696037443609,1739141182.4171999,21.8699791431427,1.814497676933082,1739141182.4172015,21.8699791431427,0.30313881837723444,1739141182.4172032,21.8699791431427,1.2098442848260198,1739141182.417205,21.8699791431427,0.0,1739141182.4172068,21.8699791431427,-0.5885174297637163,1739141182.4172084,21.8699791431427,0.06497342248524306,1739141182.4172099,21.8699791431427,1.7983617145897361 +1739141182.4373128,21.889979124069214,45.03886036058447,1739141182.4373167,21.889979124069214,0.28383553750750856,1739141182.4373207,21.889979124069214,44.98774527576247,1739141182.4373243,21.889979124069214,51.42811831356931,1739141182.4373262,21.889979124069214,2.51788706589856,1739141182.437328,21.889979124069214,0.3363696037443609,1739141182.43733,21.889979124069214,1.814497676933082,1739141182.4373314,21.889979124069214,0.30313881837723444,1739141182.437333,21.889979124069214,1.2098442848260198,1739141182.437335,21.889979124069214,0.0,1739141182.4373372,21.889979124069214,-0.5885174297637163,1739141182.4373386,21.889979124069214,0.06497342248524306,1739141182.4373403,21.889979124069214,1.7983617145897361 +1739141182.457287,21.909979104995728,45.03886036058447,1739141182.4572906,21.909979104995728,0.28383553750750856,1739141182.4572947,21.909979104995728,44.98774527576247,1739141182.4572978,21.909979104995728,51.42811831356931,1739141182.4572997,21.909979104995728,2.51788706589856,1739141182.4573016,21.909979104995728,0.3363696037443609,1739141182.4573033,21.909979104995728,1.814497676933082,1739141182.4573047,21.909979104995728,0.30313881837723444,1739141182.4573064,21.909979104995728,1.2098442848260198,1739141182.4573085,21.909979104995728,0.0,1739141182.4573102,21.909979104995728,-0.5885174297637163,1739141182.4573116,21.909979104995728,0.06497342248524306,1739141182.4573133,21.909979104995728,1.7983617145897361 +1739141182.477406,21.92997908592224,45.03886036058447,1739141182.4774091,21.92997908592224,0.28383553750750856,1739141182.4774127,21.92997908592224,44.98774527576247,1739141182.4774156,21.92997908592224,51.42811831356931,1739141182.4774175,21.92997908592224,2.51788706589856,1739141182.4774196,21.92997908592224,0.3363696037443609,1739141182.477421,21.92997908592224,1.814497676933082,1739141182.4774225,21.92997908592224,0.30313881837723444,1739141182.4774241,21.92997908592224,1.2098442848260198,1739141182.4774258,21.92997908592224,0.0,1739141182.4774277,21.92997908592224,-0.5885174297637163,1739141182.4774294,21.92997908592224,0.06497342248524306,1739141182.4774308,21.92997908592224,1.7983617145897361 +1739141182.497994,21.949979066848755,45.03886036058447,1739141182.497998,21.949979066848755,0.28383553750750856,1739141182.4980032,21.949979066848755,44.98774527576247,1739141182.4980073,21.949979066848755,51.42811831356931,1739141182.4980094,21.949979066848755,2.51788706589856,1739141182.498012,21.949979066848755,0.3363696037443609,1739141182.4980142,21.949979066848755,1.814497676933082,1739141182.4980164,21.949979066848755,0.30313881837723444,1739141182.498018,21.949979066848755,1.2098442848260198,1739141182.4980206,21.949979066848755,0.0,1739141182.4980228,21.949979066848755,-0.5885174297637163,1739141182.4980247,21.949979066848755,0.06497342248524306,1739141182.4980268,21.949979066848755,1.7983617145897361 +1739141182.5189552,21.96997904777527,45.23231903860168,1739141182.5189595,21.96997904777527,0.29712471376856,1739141182.518964,21.96997904777527,45.022607705334345,1739141182.518968,21.96997904777527,51.347134070217564,1739141182.51897,21.96997904777527,2.3574347101433433,1739141182.5189724,21.96997904777527,0.3249907170861739,1739141182.5189748,21.96997904777527,1.607745079170259,1739141182.5189764,21.96997904777527,0.29559861961249967,1739141182.5189784,21.96997904777527,1.3141534580689864,1739141182.5189805,21.96997904777527,0.0,1739141182.5189826,21.96997904777527,-0.2527931951413934,1739141182.518985,21.96997904777527,0.07317483238326329,1739141182.518987,21.96997904777527,1.7268154162252987 +1739141182.5383513,21.989979028701782,45.23231903860168,1739141182.5383558,21.989979028701782,0.29712471376856,1739141182.53836,21.989979028701782,45.022607705334345,1739141182.5383642,21.989979028701782,51.347134070217564,1739141182.5383663,21.989979028701782,2.3574347101433433,1739141182.5383687,21.989979028701782,0.3249907170861739,1739141182.5383708,21.989979028701782,1.607745079170259,1739141182.5383725,21.989979028701782,0.29559861961249967,1739141182.5383747,21.989979028701782,1.3141534580689864,1739141182.538377,21.989979028701782,0.0,1739141182.5383794,21.989979028701782,-0.41266195815631224,1739141182.5383813,21.989979028701782,0.07317483238326329,1739141182.5383832,21.989979028701782,1.7268154162252987 +1739141182.5590065,22.009979009628296,45.23231903860168,1739141182.5590103,22.009979009628296,0.29712471376856,1739141182.5590146,22.009979009628296,45.022607705334345,1739141182.5590189,22.009979009628296,51.347134070217564,1739141182.5590205,22.009979009628296,2.3574347101433433,1739141182.5590231,22.009979009628296,0.3249907170861739,1739141182.559025,22.009979009628296,1.607745079170259,1739141182.559027,22.009979009628296,0.29559861961249967,1739141182.559029,22.009979009628296,1.3141534580689864,1739141182.5590315,22.009979009628296,0.0,1739141182.5590336,22.009979009628296,-0.41266195815631224,1739141182.5590353,22.009979009628296,0.07317483238326329,1739141182.5590374,22.009979009628296,1.7268154162252987 +1739141182.5797498,22.02997899055481,45.23231903860168,1739141182.5797544,22.02997899055481,0.29712471376856,1739141182.5797586,22.02997899055481,45.022607705334345,1739141182.579763,22.02997899055481,51.347134070217564,1739141182.579765,22.02997899055481,2.3574347101433433,1739141182.5797675,22.02997899055481,0.3249907170861739,1739141182.5797696,22.02997899055481,1.607745079170259,1739141182.5797718,22.02997899055481,0.29559861961249967,1739141182.5797737,22.02997899055481,1.3141534580689864,1739141182.579776,22.02997899055481,0.0,1739141182.579778,22.02997899055481,-0.41266195815631224,1739141182.57978,22.02997899055481,0.07317483238326329,1739141182.5797822,22.02997899055481,1.7268154162252987 +1739141182.5994413,22.049978971481323,45.23231903860168,1739141182.5994453,22.049978971481323,0.29712471376856,1739141182.5994499,22.049978971481323,45.022607705334345,1739141182.599454,22.049978971481323,51.347134070217564,1739141182.5994563,22.049978971481323,2.3574347101433433,1739141182.599459,22.049978971481323,0.3249907170861739,1739141182.5994608,22.049978971481323,1.607745079170259,1739141182.599463,22.049978971481323,0.29559861961249967,1739141182.5994647,22.049978971481323,1.3141534580689864,1739141182.5994673,22.049978971481323,0.0,1739141182.5994697,22.049978971481323,-0.41266195815631224,1739141182.5994716,22.049978971481323,0.07317483238326329,1739141182.5994737,22.049978971481323,1.7268154162252987 +1739141182.6190774,22.069978952407837,45.41946909593622,1739141182.6190822,22.069978952407837,0.3116187423939669,1739141182.6190872,22.069978952407837,45.271905199108744,1739141182.6190913,22.069978952407837,51.4063191985863,1739141182.6190932,22.069978952407837,2.472643619707424,1739141182.619096,22.069978952407837,0.3464068729693578,1739141182.6190982,22.069978952407837,1.660511500261199,1739141182.6191,22.069978952407837,0.31363808850072195,1739141182.619102,22.069978952407837,1.2867068588509496,1739141182.6191046,22.069978952407837,0.0,1739141182.6191065,22.069978952407837,-0.3888603885151596,1739141182.6191084,22.069978952407837,0.0824687967774469,1739141182.6191103,22.069978952407837,1.6869013338094818 +1739141182.6385622,22.08997893333435,45.41946909593622,1739141182.6385667,22.08997893333435,0.3116187423939669,1739141182.638571,22.08997893333435,45.271905199108744,1739141182.638575,22.08997893333435,51.4063191985863,1739141182.6385772,22.08997893333435,2.472643619707424,1739141182.63858,22.08997893333435,0.3464068729693578,1739141182.638582,22.08997893333435,1.660511500261199,1739141182.6385841,22.08997893333435,0.31363808850072195,1739141182.6385858,22.08997893333435,1.2867068588509496,1739141182.6385884,22.08997893333435,0.0,1739141182.6385908,22.08997893333435,-0.4001944749585322,1739141182.6385927,22.08997893333435,0.0824687967774469,1739141182.6385946,22.08997893333435,1.6869013338094818 +1739141182.658607,22.109978914260864,45.41946909593622,1739141182.6586118,22.109978914260864,0.3116187423939669,1739141182.6586168,22.109978914260864,45.271905199108744,1739141182.6586218,22.109978914260864,51.4063191985863,1739141182.658624,22.109978914260864,2.472643619707424,1739141182.6586268,22.109978914260864,0.3464068729693578,1739141182.6586292,22.109978914260864,1.660511500261199,1739141182.6586313,22.109978914260864,0.31363808850072195,1739141182.6586335,22.109978914260864,1.2867068588509496,1739141182.6586363,22.109978914260864,0.0,1739141182.6586392,22.109978914260864,-0.4001944749585322,1739141182.6586413,22.109978914260864,0.0824687967774469,1739141182.6586437,22.109978914260864,1.6869013338094818 +1739141182.6795511,22.129978895187378,45.41946909593622,1739141182.679557,22.129978895187378,0.3116187423939669,1739141182.679563,22.129978895187378,45.271905199108744,1739141182.6795685,22.129978895187378,51.4063191985863,1739141182.6795712,22.129978895187378,2.472643619707424,1739141182.6795743,22.129978895187378,0.3464068729693578,1739141182.6795774,22.129978895187378,1.660511500261199,1739141182.6795797,22.129978895187378,0.31363808850072195,1739141182.6795816,22.129978895187378,1.2867068588509496,1739141182.6795845,22.129978895187378,0.0,1739141182.6795874,22.129978895187378,-0.4001944749585322,1739141182.67959,22.129978895187378,0.0824687967774469,1739141182.6795921,22.129978895187378,1.6869013338094818 +1739141182.6983442,22.14997887611389,45.41946909593622,1739141182.698349,22.14997887611389,0.3116187423939669,1739141182.6983542,22.14997887611389,45.271905199108744,1739141182.698359,22.14997887611389,51.4063191985863,1739141182.6983616,22.14997887611389,2.472643619707424,1739141182.6983643,22.14997887611389,0.3464068729693578,1739141182.6983666,22.14997887611389,1.660511500261199,1739141182.6983688,22.14997887611389,0.31363808850072195,1739141182.6983712,22.14997887611389,1.2867068588509496,1739141182.6983738,22.14997887611389,0.0,1739141182.6983762,22.14997887611389,-0.4001944749585322,1739141182.6983786,22.14997887611389,0.0824687967774469,1739141182.6983805,22.14997887611389,1.6869013338094818 +1739141182.718821,22.169978857040405,45.41946909593622,1739141182.718825,22.169978857040405,0.3116187423939669,1739141182.71883,22.169978857040405,45.271905199108744,1739141182.7188349,22.169978857040405,51.4063191985863,1739141182.7188373,22.169978857040405,2.472643619707424,1739141182.7188401,22.169978857040405,0.3464068729693578,1739141182.7188423,22.169978857040405,1.660511500261199,1739141182.7188447,22.169978857040405,0.31363808850072195,1739141182.7188468,22.169978857040405,1.2867068588509496,1739141182.7188492,22.169978857040405,0.0,1739141182.7188516,22.169978857040405,-0.4001944749585322,1739141182.718854,22.169978857040405,0.0824687967774469,1739141182.7188559,22.169978857040405,1.6869013338094818 +1739141182.7394216,22.18997883796692,45.60261464575829,1739141182.7394261,22.18997883796692,0.32760854680277873,1739141182.7394314,22.18997883796692,45.454920833274805,1739141182.7394364,22.18997883796692,51.44114013816389,1739141182.7394388,22.18997883796692,2.5449134943024143,1739141182.739442,22.18997883796692,0.36294723156798275,1739141182.7394447,22.18997883796692,1.6663159732597999,1739141182.7394469,22.18997883796692,0.32679672917646907,1739141182.739449,22.18997883796692,1.2837228622092978,1739141182.7394516,22.18997883796692,0.0,1739141182.7394543,22.18997883796692,-0.34047649576704747,1739141182.7394571,22.18997883796692,0.0928681943059611,1739141182.739459,22.18997883796692,1.6526365051302687 +1739141182.7594087,22.209978818893433,45.60261464575829,1739141182.7594135,22.209978818893433,0.32760854680277873,1739141182.7594182,22.209978818893433,45.454920833274805,1739141182.7594233,22.209978818893433,51.44114013816389,1739141182.7594256,22.209978818893433,2.5449134943024143,1739141182.7594283,22.209978818893433,0.36294723156798275,1739141182.7594306,22.209978818893433,1.6663159732597999,1739141182.759433,22.209978818893433,0.32679672917646907,1739141182.7594352,22.209978818893433,1.2837228622092978,1739141182.7594378,22.209978818893433,0.0,1739141182.7594402,22.209978818893433,-0.36891364292097095,1739141182.7594423,22.209978818893433,0.0928681943059611,1739141182.759445,22.209978818893433,1.6526365051302687 +1739141182.7789586,22.229978799819946,45.60261464575829,1739141182.7789629,22.229978799819946,0.32760854680277873,1739141182.7789679,22.229978799819946,45.454920833274805,1739141182.7789726,22.229978799819946,51.44114013816389,1739141182.778975,22.229978799819946,2.5449134943024143,1739141182.7789779,22.229978799819946,0.36294723156798275,1739141182.7789805,22.229978799819946,1.6663159732597999,1739141182.7789826,22.229978799819946,0.32679672917646907,1739141182.778985,22.229978799819946,1.2837228622092978,1739141182.7789874,22.229978799819946,0.0,1739141182.77899,22.229978799819946,-0.36891364292097095,1739141182.7789924,22.229978799819946,0.0928681943059611,1739141182.7789943,22.229978799819946,1.6526365051302687 +1739141182.799208,22.24997878074646,45.60261464575829,1739141182.7992134,22.24997878074646,0.32760854680277873,1739141182.7992187,22.24997878074646,45.454920833274805,1739141182.7992241,22.24997878074646,51.44114013816389,1739141182.7992268,22.24997878074646,2.5449134943024143,1739141182.79923,22.24997878074646,0.36294723156798275,1739141182.7992332,22.24997878074646,1.6663159732597999,1739141182.7992358,22.24997878074646,0.32679672917646907,1739141182.799238,22.24997878074646,1.2837228622092978,1739141182.7992406,22.24997878074646,0.0,1739141182.799244,22.24997878074646,-0.36891364292097095,1739141182.7992465,22.24997878074646,0.0928681943059611,1739141182.799249,22.24997878074646,1.6526365051302687 +1739141182.818873,22.269978761672974,45.60261464575829,1739141182.8188772,22.269978761672974,0.32760854680277873,1739141182.818882,22.269978761672974,45.454920833274805,1739141182.818887,22.269978761672974,51.44114013816389,1739141182.8188891,22.269978761672974,2.5449134943024143,1739141182.818892,22.269978761672974,0.36294723156798275,1739141182.8188944,22.269978761672974,1.6663159732597999,1739141182.8188965,22.269978761672974,0.32679672917646907,1739141182.818899,22.269978761672974,1.2837228622092978,1739141182.8189018,22.269978761672974,0.0,1739141182.8189044,22.269978761672974,-0.36891364292097095,1739141182.8189065,22.269978761672974,0.0928681943059611,1739141182.8189092,22.269978761672974,1.6526365051302687 +1739141182.839161,22.289978742599487,45.781839220889076,1739141182.8391652,22.289978742599487,0.34522805240599297,1739141182.8391702,22.289978742599487,45.45834371970789,1739141182.839175,22.289978742599487,51.398412817535096,1739141182.8391771,22.289978742599487,2.456234149601147,1739141182.8391805,22.289978742599487,0.3595183056283961,1739141182.8391829,22.289978742599487,1.5142188816412445,1739141182.839185,22.289978742599487,0.3217735857500731,1739141182.8391871,22.289978742599487,1.3642477518999154,1739141182.8391898,22.289978742599487,0.0,1739141182.8391922,22.289978742599487,-0.15036490448302164,1739141182.8391943,22.289978742599487,0.10439787566598643,1739141182.8391964,22.289978742599487,1.6186835361984833 +1739141182.8588517,22.309978723526,45.781839220889076,1739141182.8588557,22.309978723526,0.34522805240599297,1739141182.8588605,22.309978723526,45.45834371970789,1739141182.8588653,22.309978723526,51.398412817535096,1739141182.8588674,22.309978723526,2.456234149601147,1739141182.8588703,22.309978723526,0.3595183056283961,1739141182.8588727,22.309978723526,1.5142188816412445,1739141182.8588746,22.309978723526,0.3217735857500731,1739141182.8588767,22.309978723526,1.3642477518999154,1739141182.8588796,22.309978723526,0.0,1739141182.8588817,22.309978723526,-0.25443578429856784,1739141182.8588839,22.309978723526,0.10439787566598643,1739141182.8588862,22.309978723526,1.6186835361984833 +1739141182.879211,22.329978704452515,45.781839220889076,1739141182.879215,22.329978704452515,0.34522805240599297,1739141182.8792202,22.329978704452515,45.45834371970789,1739141182.8792248,22.329978704452515,51.398412817535096,1739141182.8792272,22.329978704452515,2.456234149601147,1739141182.87923,22.329978704452515,0.3595183056283961,1739141182.8792322,22.329978704452515,1.5142188816412445,1739141182.8792346,22.329978704452515,0.3217735857500731,1739141182.8792367,22.329978704452515,1.3642477518999154,1739141182.879239,22.329978704452515,0.0,1739141182.8792417,22.329978704452515,-0.25443578429856784,1739141182.8792439,22.329978704452515,0.10439787566598643,1739141182.879246,22.329978704452515,1.6186835361984833 +1739141182.8974662,22.34997868537903,45.781839220889076,1739141182.8974693,22.34997868537903,0.34522805240599297,1739141182.8974729,22.34997868537903,45.45834371970789,1739141182.8974762,22.34997868537903,51.398412817535096,1739141182.8974774,22.34997868537903,2.456234149601147,1739141182.8974795,22.34997868537903,0.3595183056283961,1739141182.8974812,22.34997868537903,1.5142188816412445,1739141182.8974826,22.34997868537903,0.3217735857500731,1739141182.8974843,22.34997868537903,1.3642477518999154,1739141182.897486,22.34997868537903,0.0,1739141182.8974879,22.34997868537903,-0.25443578429856784,1739141182.8974893,22.34997868537903,0.10439787566598643,1739141182.897491,22.34997868537903,1.6186835361984833 +1739141182.9171188,22.369978666305542,45.781839220889076,1739141182.9171212,22.369978666305542,0.34522805240599297,1739141182.9171243,22.369978666305542,45.45834371970789,1739141182.917127,22.369978666305542,51.398412817535096,1739141182.917128,22.369978666305542,2.456234149601147,1739141182.9171298,22.369978666305542,0.3595183056283961,1739141182.9171312,22.369978666305542,1.5142188816412445,1739141182.9171326,22.369978666305542,0.3217735857500731,1739141182.9171338,22.369978666305542,1.3642477518999154,1739141182.917135,22.369978666305542,0.0,1739141182.9171367,22.369978666305542,-0.25443578429856784,1739141182.9171379,22.369978666305542,0.10439787566598643,1739141182.9171393,22.369978666305542,1.6186835361984833 +1739141182.93697,22.389978647232056,45.781839220889076,1739141182.9369724,22.389978647232056,0.34522805240599297,1739141182.9369748,22.389978647232056,45.45834371970789,1739141182.9369774,22.389978647232056,51.398412817535096,1739141182.9369786,22.389978647232056,2.456234149601147,1739141182.9369805,22.389978647232056,0.3595183056283961,1739141182.936982,22.389978647232056,1.5142188816412445,1739141182.9369833,22.389978647232056,0.3217735857500731,1739141182.9369843,22.389978647232056,1.3642477518999154,1739141182.936986,22.389978647232056,0.0,1739141182.9369872,22.389978647232056,-0.25443578429856784,1739141182.936988,22.389978647232056,0.10439787566598643,1739141182.9369895,22.389978647232056,1.6186835361984833 +1739141182.9571564,22.40997862815857,45.95743732169153,1739141182.9571593,22.40997862815857,0.3646216519095882,1739141182.9571624,22.40997862815857,45.46169947722264,1739141182.9571652,22.40997862815857,51.357949530915626,1739141182.957167,22.40997862815857,2.3778340774673885,1739141182.9571688,22.40997862815857,0.35682449168951585,1739141182.9571707,22.40997862815857,1.3700904877415798,1739141182.9571722,22.40997862815857,0.31559022834908346,1739141182.9571736,22.40997862815857,1.4452098512193956,1739141182.9571753,22.40997862815857,0.0,1739141182.9571767,22.40997862815857,-0.04157681305817619,1739141182.957178,22.40997862815857,0.11681046439197855,1739141182.9571793,22.40997862815857,1.5881481297884292 +1739141182.977391,22.429978609085083,45.95743732169153,1739141182.977394,22.429978609085083,0.3646216519095882,1739141182.9773974,22.429978609085083,45.46169947722264,1739141182.9774005,22.429978609085083,51.357949530915626,1739141182.9774022,22.429978609085083,2.3778340774673885,1739141182.977404,22.429978609085083,0.35682449168951585,1739141182.9774058,22.429978609085083,1.3700904877415798,1739141182.9774072,22.429978609085083,0.31559022834908346,1739141182.977409,22.429978609085083,1.4452098512193956,1739141182.9774108,22.429978609085083,0.0,1739141182.9774127,22.429978609085083,-0.14293827856903363,1739141182.9774141,22.429978609085083,0.11681046439197855,1739141182.9774156,22.429978609085083,1.5881481297884292 +1739141182.9975204,22.449978590011597,45.95743732169153,1739141182.9975238,22.449978590011597,0.3646216519095882,1739141182.9975276,22.449978590011597,45.46169947722264,1739141182.997531,22.449978590011597,51.357949530915626,1739141182.9975324,22.449978590011597,2.3778340774673885,1739141182.997535,22.449978590011597,0.35682449168951585,1739141182.9975364,22.449978590011597,1.3700904877415798,1739141182.997538,22.449978590011597,0.31559022834908346,1739141182.9975398,22.449978590011597,1.4452098512193956,1739141182.997542,22.449978590011597,0.0,1739141182.9975433,22.449978590011597,-0.14293827856903363,1739141182.997545,22.449978590011597,0.11681046439197855,1739141182.9975464,22.449978590011597,1.5881481297884292 +1739141183.0173287,22.46997857093811,45.95743732169153,1739141183.017332,22.46997857093811,0.3646216519095882,1739141183.017335,22.46997857093811,45.46169947722264,1739141183.0173383,22.46997857093811,51.357949530915626,1739141183.0173402,22.46997857093811,2.3778340774673885,1739141183.017342,22.46997857093811,0.35682449168951585,1739141183.017344,22.46997857093811,1.3700904877415798,1739141183.0173454,22.46997857093811,0.31559022834908346,1739141183.0173473,22.46997857093811,1.4452098512193956,1739141183.0173495,22.46997857093811,0.0,1739141183.0173512,22.46997857093811,-0.14293827856903363,1739141183.0173528,22.46997857093811,0.11681046439197855,1739141183.0173542,22.46997857093811,1.5881481297884292 +1739141183.0372088,22.489978551864624,45.95743732169153,1739141183.0372117,22.489978551864624,0.3646216519095882,1739141183.037215,22.489978551864624,45.46169947722264,1739141183.0372183,22.489978551864624,51.357949530915626,1739141183.03722,22.489978551864624,2.3778340774673885,1739141183.037222,22.489978551864624,0.35682449168951585,1739141183.0372236,22.489978551864624,1.3700904877415798,1739141183.0372252,22.489978551864624,0.31559022834908346,1739141183.0372264,22.489978551864624,1.4452098512193956,1739141183.0372283,22.489978551864624,0.0,1739141183.03723,22.489978551864624,-0.14293827856903363,1739141183.0372317,22.489978551864624,0.11681046439197855,1739141183.037233,22.489978551864624,1.5881481297884292 +1739141183.0592341,22.509978532791138,46.130056279509745,1739141183.0592391,22.509978532791138,0.3858684835230033,1739141183.0592449,22.509978532791138,45.4650004842528,1739141183.0592499,22.509978532791138,51.33799936647666,1739141183.0592525,22.509978532791138,2.340367237364278,1739141183.059256,22.509978532791138,0.35902654080909374,1739141183.0592585,22.509978532791138,1.2667784159909836,1739141183.0592608,22.509978532791138,0.313271267414017,1739141183.0592632,22.509978532791138,1.5061840988182216,1739141183.0592663,22.509978532791138,0.0,1739141183.059269,22.509978532791138,0.002580270594087261,1739141183.0592713,22.509978532791138,0.12928018643074976,1739141183.0592742,22.509978532791138,1.5728984100603391 +1739141183.0816264,22.52997851371765,46.130056279509745,1739141183.0816326,22.52997851371765,0.3858684835230033,1739141183.0816388,22.52997851371765,45.4650004842528,1739141183.0816453,22.52997851371765,51.33799936647666,1739141183.0816483,22.52997851371765,2.340367237364278,1739141183.081652,22.52997851371765,0.35902654080909374,1739141183.0816553,22.52997851371765,1.2667784159909836,1739141183.0816581,22.52997851371765,0.313271267414017,1739141183.081661,22.52997851371765,1.5061840988182216,1739141183.081665,22.52997851371765,0.0,1739141183.0816684,22.52997851371765,-0.06671431124211757,1739141183.0816715,22.52997851371765,0.12928018643074976,1739141183.0816746,22.52997851371765,1.5728984100603391 +1739141183.1012657,22.549978494644165,46.130056279509745,1739141183.1012719,22.549978494644165,0.3858684835230033,1739141183.1012783,22.549978494644165,45.4650004842528,1739141183.1012843,22.549978494644165,51.33799936647666,1739141183.1012871,22.549978494644165,2.340367237364278,1739141183.101291,22.549978494644165,0.35902654080909374,1739141183.101294,22.549978494644165,1.2667784159909836,1739141183.101297,22.549978494644165,0.313271267414017,1739141183.1012998,22.549978494644165,1.5061840988182216,1739141183.1013033,22.549978494644165,0.0,1739141183.101307,22.549978494644165,-0.06671431124211757,1739141183.10131,22.549978494644165,0.12928018643074976,1739141183.1013129,22.549978494644165,1.5728984100603391 +1739141183.1194909,22.56997847557068,46.130056279509745,1739141183.1194968,22.56997847557068,0.3858684835230033,1739141183.119503,22.56997847557068,45.4650004842528,1739141183.1195092,22.56997847557068,51.33799936647666,1739141183.1195126,22.56997847557068,2.340367237364278,1739141183.1195166,22.56997847557068,0.35902654080909374,1739141183.1195197,22.56997847557068,1.2667784159909836,1739141183.1195228,22.56997847557068,0.313271267414017,1739141183.1195257,22.56997847557068,1.5061840988182216,1739141183.1195295,22.56997847557068,0.0,1739141183.1195328,22.56997847557068,-0.06671431124211757,1739141183.119536,22.56997847557068,0.12928018643074976,1739141183.119539,22.56997847557068,1.5728984100603391 +1739141183.139057,22.589978456497192,46.130056279509745,1739141183.1390607,22.589978456497192,0.3858684835230033,1739141183.139065,22.589978456497192,45.4650004842528,1739141183.139069,22.589978456497192,51.33799936647666,1739141183.1390715,22.589978456497192,2.340367237364278,1739141183.1390738,22.589978456497192,0.35902654080909374,1739141183.1390758,22.589978456497192,1.2667784159909836,1739141183.139078,22.589978456497192,0.313271267414017,1739141183.1390796,22.589978456497192,1.5061840988182216,1739141183.139082,22.589978456497192,0.0,1739141183.1390843,22.589978456497192,-0.06671431124211757,1739141183.139086,22.589978456497192,0.12928018643074976,1739141183.1390882,22.589978456497192,1.5728984100603391 +1739141183.1571584,22.609978437423706,46.130056279509745,1739141183.1571615,22.609978437423706,0.3858684835230033,1739141183.1571646,22.609978437423706,45.4650004842528,1739141183.1571677,22.609978437423706,51.33799936647666,1739141183.1571689,22.609978437423706,2.340367237364278,1739141183.1571708,22.609978437423706,0.35902654080909374,1739141183.157172,22.609978437423706,1.2667784159909836,1739141183.1571732,22.609978437423706,0.313271267414017,1739141183.1571746,22.609978437423706,1.5061840988182216,1739141183.157176,22.609978437423706,0.0,1739141183.1571777,22.609978437423706,-0.06671431124211757,1739141183.1571789,22.609978437423706,0.12928018643074976,1739141183.15718,22.609978437423706,1.5728984100603391 +1739141183.1770184,22.62997841835022,46.30118070490294,1739141183.1770208,22.62997841835022,0.40910192135368373,1739141183.1770234,22.62997841835022,45.4682750817731,1739141183.177026,22.62997841835022,51.33009360575239,1739141183.1770272,22.62997841835022,2.325595947589987,1739141183.1770291,22.62997841835022,0.36410357577013636,1739141183.1770303,22.62997841835022,1.1868090245524128,1739141183.1770318,22.62997841835022,0.3135554328293335,1739141183.1770327,22.62997841835022,1.5551424078566998,1739141183.1770341,22.62997841835022,0.0,1739141183.1770358,22.62997841835022,0.039496986115158,1739141183.177037,22.62997841835022,0.14174990846952096,1739141183.1770382,22.62997841835022,1.5662222552722491 +1739141183.197147,22.649978399276733,46.30118070490294,1739141183.1971493,22.649978399276733,0.40910192135368373,1739141183.1971517,22.649978399276733,45.4682750817731,1739141183.1971543,22.649978399276733,51.33009360575239,1739141183.1971552,22.649978399276733,2.325595947589987,1739141183.197157,22.649978399276733,0.36410357577013636,1739141183.197158,22.649978399276733,1.1868090245524128,1739141183.197159,22.649978399276733,0.3135554328293335,1739141183.1971605,22.649978399276733,1.5551424078566998,1739141183.1971617,22.649978399276733,0.0,1739141183.1971633,22.649978399276733,-0.011079847415549349,1739141183.1971643,22.649978399276733,0.14174990846952096,1739141183.1971655,22.649978399276733,1.5662222552722491 +1739141183.21709,22.669978380203247,46.30118070490294,1739141183.2170923,22.669978380203247,0.40910192135368373,1739141183.2170951,22.669978380203247,45.4682750817731,1739141183.2170978,22.669978380203247,51.33009360575239,1739141183.217099,22.669978380203247,2.325595947589987,1739141183.2171004,22.669978380203247,0.36410357577013636,1739141183.2171018,22.669978380203247,1.1868090245524128,1739141183.217103,22.669978380203247,0.3135554328293335,1739141183.2171042,22.669978380203247,1.5551424078566998,1739141183.2171056,22.669978380203247,0.0,1739141183.2171073,22.669978380203247,-0.011079847415549349,1739141183.2171085,22.669978380203247,0.14174990846952096,1739141183.2171097,22.669978380203247,1.5662222552722491 +1739141183.2371857,22.68997836112976,46.30118070490294,1739141183.2371893,22.68997836112976,0.40910192135368373,1739141183.2371926,22.68997836112976,45.4682750817731,1739141183.237196,22.68997836112976,51.33009360575239,1739141183.2371976,22.68997836112976,2.325595947589987,1739141183.2371998,22.68997836112976,0.36410357577013636,1739141183.237202,22.68997836112976,1.1868090245524128,1739141183.2372034,22.68997836112976,0.3135554328293335,1739141183.237205,22.68997836112976,1.5551424078566998,1739141183.2372067,22.68997836112976,0.0,1739141183.2372084,22.68997836112976,-0.011079847415549349,1739141183.2372098,22.68997836112976,0.14174990846952096,1739141183.2372115,22.68997836112976,1.5662222552722491 +1739141183.2573555,22.709978342056274,46.30118070490294,1739141183.2573586,22.709978342056274,0.40910192135368373,1739141183.2573621,22.709978342056274,45.4682750817731,1739141183.2573657,22.709978342056274,51.33009360575239,1739141183.2573674,22.709978342056274,2.325595947589987,1739141183.2573693,22.709978342056274,0.36410357577013636,1739141183.2573712,22.709978342056274,1.1868090245524128,1739141183.2573729,22.709978342056274,0.3135554328293335,1739141183.2573743,22.709978342056274,1.5551424078566998,1739141183.2573762,22.709978342056274,0.0,1739141183.257378,22.709978342056274,-0.011079847415549349,1739141183.2573795,22.709978342056274,0.14174990846952096,1739141183.2573812,22.709978342056274,1.5662222552722491 +1739141183.2830946,22.729978322982788,46.471565767813445,1739141183.283104,22.729978322982788,0.43440324077297277,1739141183.2831151,22.729978322982788,45.73270553698416,1739141183.2831254,22.729978322982788,51.44812356270068,1739141183.2831302,22.729978322982788,2.559613256901487,1739141183.2831364,22.729978322982788,0.4036008068856131,1739141183.2831414,22.729978322982788,1.3355431364638761,1739141183.2831469,22.729978322982788,0.3486959416085714,1739141183.2831514,22.729978322982788,1.4653197488995784,1739141183.2831573,22.729978322982788,0.0,1739141183.2831624,22.729978322982788,-0.18111680651685336,1739141183.283167,22.729978322982788,0.15421963050829215,1739141183.2831717,22.729978322982788,1.5654665344439382 +1739141183.3031175,22.7499783039093,46.471565767813445,1739141183.3031318,22.7499783039093,0.43440324077297277,1739141183.3031435,22.7499783039093,45.73270553698416,1739141183.3031578,22.7499783039093,51.44812356270068,1739141183.3031843,22.7499783039093,2.559613256901487,1739141183.3031936,22.7499783039093,0.4036008068856131,1739141183.3032012,22.7499783039093,1.3355431364638761,1739141183.3032084,22.7499783039093,0.3486959416085714,1739141183.303226,22.7499783039093,1.4653197488995784,1739141183.3032322,22.7499783039093,0.0,1739141183.303238,22.7499783039093,-0.10014678554435985,1739141183.303245,22.7499783039093,0.15421963050829215,1739141183.30325,22.7499783039093,1.5654665344439382 +1739141183.3361907,22.779978275299072,46.471565767813445,1739141183.3362038,22.779978275299072,0.43440324077297277,1739141183.336223,22.779978275299072,45.73270553698416,1739141183.3362403,22.779978275299072,51.44812356270068,1739141183.3362486,22.779978275299072,2.559613256901487,1739141183.3362637,22.779978275299072,0.4036008068856131,1739141183.3362713,22.779978275299072,1.3355431364638761,1739141183.3362784,22.779978275299072,0.3486959416085714,1739141183.336286,22.779978275299072,1.4653197488995784,1739141183.3362944,22.779978275299072,0.0,1739141183.336302,22.779978275299072,-0.10014678554435985,1739141183.3363097,22.779978275299072,0.15421963050829215,1739141183.3363183,22.779978275299072,1.5654665344439382 +1739141183.3569002,22.809978246688843,46.471565767813445,1739141183.3569186,22.809978246688843,0.43440324077297277,1739141183.3569407,22.809978246688843,45.73270553698416,1739141183.3569686,22.809978246688843,51.44812356270068,1739141183.3569844,22.809978246688843,2.559613256901487,1739141183.357004,22.809978246688843,0.4036008068856131,1739141183.3570151,22.809978246688843,1.3355431364638761,1739141183.35703,22.809978246688843,0.3486959416085714,1739141183.357045,22.809978246688843,1.4653197488995784,1739141183.3570611,22.809978246688843,0.0,1739141183.3570757,22.809978246688843,-0.10014678554435985,1739141183.3570855,22.809978246688843,0.15421963050829215,1739141183.357094,22.809978246688843,1.5654665344439382 +1739141183.3848617,22.829978227615356,46.471565767813445,1739141183.384867,22.829978227615356,0.43440324077297277,1739141183.3848732,22.829978227615356,45.73270553698416,1739141183.38488,22.829978227615356,51.44812356270068,1739141183.3848846,22.829978227615356,2.559613256901487,1739141183.3848896,22.829978227615356,0.4036008068856131,1739141183.384894,22.829978227615356,1.3355431364638761,1739141183.3848987,22.829978227615356,0.3486959416085714,1739141183.3849032,22.829978227615356,1.4653197488995784,1739141183.384908,22.829978227615356,0.0,1739141183.3849127,22.829978227615356,-0.10014678554435985,1739141183.3849173,22.829978227615356,0.15421963050829215,1739141183.3849218,22.829978227615356,1.5654665344439382 +1739141183.404577,22.859978199005127,46.64097658631217,1739141183.4045815,22.859978199005127,0.46174018610448453,1739141183.4045863,22.859978199005127,45.92646969705017,1739141183.4045916,22.859978199005127,51.51229334015884,1739141183.4045944,22.859978199005127,2.704717053721606,1739141183.4045982,22.859978199005127,0.4315065416805514,1739141183.4046016,22.859978199005127,1.4013726083576168,1739141183.4046047,22.859978199005127,0.3722874720832009,1739141183.404608,22.859978199005127,1.4272388284853759,1739141183.4046116,22.859978199005127,0.0,1739141183.404615,22.859978199005127,-0.15051860253701504,1739141183.4046183,22.859978199005127,0.1671286307583094,1739141183.4046216,22.859978199005127,1.5537708395197285 +1739141183.4231346,22.87997817993164,46.64097658631217,1739141183.423138,22.87997817993164,0.46174018610448453,1739141183.423141,22.87997817993164,45.92646969705017,1739141183.4231439,22.87997817993164,51.51229334015884,1739141183.4231453,22.87997817993164,2.704717053721606,1739141183.423147,22.87997817993164,0.4315065416805514,1739141183.4231486,22.87997817993164,1.4013726083576168,1739141183.4231498,22.87997817993164,0.3722874720832009,1739141183.423151,22.87997817993164,1.4272388284853759,1739141183.423153,22.87997817993164,0.0,1739141183.4231544,22.87997817993164,-0.12653201103435263,1739141183.4231558,22.87997817993164,0.1671286307583094,1739141183.423157,22.87997817993164,1.5537708395197285 +1739141183.4427767,22.899978160858154,46.64097658631217,1739141183.4427824,22.899978160858154,0.46174018610448453,1739141183.4427874,22.899978160858154,45.92646969705017,1739141183.4427912,22.899978160858154,51.51229334015884,1739141183.4427931,22.899978160858154,2.704717053721606,1739141183.4427962,22.899978160858154,0.4315065416805514,1739141183.4427984,22.899978160858154,1.4013726083576168,1739141183.4428005,22.899978160858154,0.3722874720832009,1739141183.4428027,22.899978160858154,1.4272388284853759,1739141183.442805,22.899978160858154,0.0,1739141183.442808,22.899978160858154,-0.12653201103435263,1739141183.4428096,22.899978160858154,0.1671286307583094,1739141183.442812,22.899978160858154,1.5537708395197285 +1739141183.4649684,22.919978141784668,46.64097658631217,1739141183.4649727,22.919978141784668,0.46174018610448453,1739141183.4649777,22.919978141784668,45.92646969705017,1739141183.4649832,22.919978141784668,51.51229334015884,1739141183.4649863,22.919978141784668,2.704717053721606,1739141183.4649901,22.919978141784668,0.4315065416805514,1739141183.4649935,22.919978141784668,1.4013726083576168,1739141183.4649968,22.919978141784668,0.3722874720832009,1739141183.4650002,22.919978141784668,1.4272388284853759,1739141183.465004,22.919978141784668,0.0,1739141183.4650075,22.919978141784668,-0.12653201103435263,1739141183.465011,22.919978141784668,0.1671286307583094,1739141183.4650145,22.919978141784668,1.5537708395197285 +1739141183.4863894,22.93997812271118,46.64097658631217,1739141183.4863985,22.93997812271118,0.46174018610448453,1739141183.4864087,22.93997812271118,45.92646969705017,1739141183.4864185,22.93997812271118,51.51229334015884,1739141183.4864233,22.93997812271118,2.704717053721606,1739141183.4864297,22.93997812271118,0.4315065416805514,1739141183.4864345,22.93997812271118,1.4013726083576168,1739141183.4864392,22.93997812271118,0.3722874720832009,1739141183.4864435,22.93997812271118,1.4272388284853759,1739141183.4864497,22.93997812271118,0.0,1739141183.4864547,22.93997812271118,-0.12653201103435263,1739141183.4864595,22.93997812271118,0.1671286307583094,1739141183.486464,22.93997812271118,1.5537708395197285 +1739141183.506733,22.959978103637695,46.80865801877323,1739141183.506742,22.959978103637695,0.49111545026703407,1739141183.5067523,22.959978103637695,46.82983222363138,1739141183.5067618,22.959978103637695,51.74725125793766,1739141183.5067663,22.959978103637695,3.5320077763419406,1739141183.5067723,22.959978103637695,0.551913139332406,1739141183.5067768,22.959978103637695,2.1009830590640406,1739141183.506781,22.959978103637695,0.47567358448437025,1739141183.5067856,22.959978103637695,1.078851995060117,1739141183.506791,22.959978103637695,0.0,1739141183.5067964,22.959978103637695,-0.7652954401663232,1739141183.506801,22.959978103637695,0.18122590999735436,1739141183.5068054,22.959978103637695,1.5399742217872163 +1739141183.5261729,22.97997808456421,46.80865801877323,1739141183.5261776,22.97997808456421,0.49111545026703407,1739141183.526183,22.97997808456421,46.82983222363138,1739141183.5261881,22.97997808456421,51.74725125793766,1739141183.5261908,22.97997808456421,3.5320077763419406,1739141183.526194,22.97997808456421,0.551913139332406,1739141183.526197,22.97997808456421,2.1009830590640406,1739141183.5261993,22.97997808456421,0.47567358448437025,1739141183.5262015,22.97997808456421,1.078851995060117,1739141183.5262046,22.97997808456421,0.0,1739141183.5262074,22.97997808456421,-0.46112222672709935,1739141183.52621,22.97997808456421,0.18122590999735436,1739141183.5262127,22.97997808456421,1.5399742217872163 +1739141183.5457594,22.999978065490723,46.80865801877323,1739141183.5457628,22.999978065490723,0.49111545026703407,1739141183.5457666,22.999978065490723,46.82983222363138,1739141183.5457704,22.999978065490723,51.74725125793766,1739141183.5457726,22.999978065490723,3.5320077763419406,1739141183.5457747,22.999978065490723,0.551913139332406,1739141183.5457764,22.999978065490723,2.1009830590640406,1739141183.5457783,22.999978065490723,0.47567358448437025,1739141183.5457797,22.999978065490723,1.078851995060117,1739141183.545782,22.999978065490723,0.0,1739141183.5457838,22.999978065490723,-0.46112222672709935,1739141183.5457857,22.999978065490723,0.18122590999735436,1739141183.545787,22.999978065490723,1.5399742217872163 +1739141183.567819,23.019978046417236,46.80865801877323,1739141183.5678227,23.019978046417236,0.49111545026703407,1739141183.567827,23.019978046417236,46.82983222363138,1739141183.5678313,23.019978046417236,51.74725125793766,1739141183.5678334,23.019978046417236,3.5320077763419406,1739141183.5678358,23.019978046417236,0.551913139332406,1739141183.567838,23.019978046417236,2.1009830590640406,1739141183.56784,23.019978046417236,0.47567358448437025,1739141183.567842,23.019978046417236,1.078851995060117,1739141183.5678444,23.019978046417236,0.0,1739141183.5678463,23.019978046417236,-0.46112222672709935,1739141183.5678484,23.019978046417236,0.18122590999735436,1739141183.5678506,23.019978046417236,1.5399742217872163 +1739141183.5857475,23.03997802734375,46.80865801877323,1739141183.5857506,23.03997802734375,0.49111545026703407,1739141183.5857537,23.03997802734375,46.82983222363138,1739141183.585757,23.03997802734375,51.74725125793766,1739141183.5857582,23.03997802734375,3.5320077763419406,1739141183.5857604,23.03997802734375,0.551913139332406,1739141183.5857618,23.03997802734375,2.1009830590640406,1739141183.585763,23.03997802734375,0.47567358448437025,1739141183.5857644,23.03997802734375,1.078851995060117,1739141183.585766,23.03997802734375,0.0,1739141183.5857677,23.03997802734375,-0.46112222672709935,1739141183.585769,23.03997802734375,0.18122590999735436,1739141183.5857701,23.03997802734375,1.5399742217872163 +1739141183.6054978,23.059978008270264,46.972403810017134,1739141183.6055002,23.059978008270264,0.5222767230301582,1739141183.6055026,23.059978008270264,46.92479211269373,1739141183.6055055,23.059978008270264,51.7364378479839,1739141183.605507,23.059978008270264,3.4681892399195138,1739141183.6055086,23.059978008270264,0.5538139379049584,1739141183.60551,23.059978008270264,1.9586124255760526,1739141183.605511,23.059978008270264,0.47541947176704247,1739141183.605512,23.059978008270264,1.1420738331547695,1739141183.6055136,23.059978008270264,0.0,1739141183.6055148,23.059978008270264,-0.2388016712729801,1739141183.605516,23.059978008270264,0.19659313978977616,1739141183.6055171,23.059978008270264,1.4867424884815617 +1739141183.625078,23.079977989196777,46.972403810017134,1739141183.6250813,23.079977989196777,0.5222767230301582,1739141183.6250842,23.079977989196777,46.92479211269373,1739141183.625087,23.079977989196777,51.7364378479839,1739141183.6250882,23.079977989196777,3.4681892399195138,1739141183.6250901,23.079977989196777,0.5538139379049584,1739141183.6250916,23.079977989196777,1.9586124255760526,1739141183.6250932,23.079977989196777,0.47541947176704247,1739141183.6250942,23.079977989196777,1.1420738331547695,1739141183.6250958,23.079977989196777,0.0,1739141183.6250975,23.079977989196777,-0.34466865532679214,1739141183.6250985,23.079977989196777,0.19659313978977616,1739141183.6251001,23.079977989196777,1.4867424884815617 +1739141183.646307,23.09997797012329,46.972403810017134,1739141183.6463113,23.09997797012329,0.5222767230301582,1739141183.646316,23.09997797012329,46.92479211269373,1739141183.6463206,23.09997797012329,51.7364378479839,1739141183.646323,23.09997797012329,3.4681892399195138,1739141183.6463258,23.09997797012329,0.5538139379049584,1739141183.6463277,23.09997797012329,1.9586124255760526,1739141183.6463299,23.09997797012329,0.47541947176704247,1739141183.6463318,23.09997797012329,1.1420738331547695,1739141183.6463344,23.09997797012329,0.0,1739141183.6463368,23.09997797012329,-0.34466865532679214,1739141183.6463387,23.09997797012329,0.19659313978977616,1739141183.6463408,23.09997797012329,1.4867424884815617 +1739141183.6649597,23.119977951049805,46.972403810017134,1739141183.664962,23.119977951049805,0.5222767230301582,1739141183.6649647,23.119977951049805,46.92479211269373,1739141183.664967,23.119977951049805,51.7364378479839,1739141183.6649685,23.119977951049805,3.4681892399195138,1739141183.66497,23.119977951049805,0.5538139379049584,1739141183.6649714,23.119977951049805,1.9586124255760526,1739141183.6649725,23.119977951049805,0.47541947176704247,1739141183.6649735,23.119977951049805,1.1420738331547695,1739141183.6649752,23.119977951049805,0.0,1739141183.6649764,23.119977951049805,-0.34466865532679214,1739141183.6649776,23.119977951049805,0.19659313978977616,1739141183.6649787,23.119977951049805,1.4867424884815617 +1739141183.6853302,23.13997793197632,46.972403810017134,1739141183.6853328,23.13997793197632,0.5222767230301582,1739141183.6853354,23.13997793197632,46.92479211269373,1739141183.685338,23.13997793197632,51.7364378479839,1739141183.6853395,23.13997793197632,3.4681892399195138,1739141183.6853588,23.13997793197632,0.5538139379049584,1739141183.6853604,23.13997793197632,1.9586124255760526,1739141183.6853614,23.13997793197632,0.47541947176704247,1739141183.6853626,23.13997793197632,1.1420738331547695,1739141183.6853642,23.13997793197632,0.0,1739141183.6853654,23.13997793197632,-0.34466865532679214,1739141183.6853666,23.13997793197632,0.19659313978977616,1739141183.6853678,23.13997793197632,1.4867424884815617 +1739141183.705468,23.159977912902832,46.972403810017134,1739141183.7054703,23.159977912902832,0.5222767230301582,1739141183.7054727,23.159977912902832,46.92479211269373,1739141183.7054753,23.159977912902832,51.7364378479839,1739141183.7054765,23.159977912902832,3.4681892399195138,1739141183.7054782,23.159977912902832,0.5538139379049584,1739141183.7054794,23.159977912902832,1.9586124255760526,1739141183.7054808,23.159977912902832,0.47541947176704247,1739141183.705482,23.159977912902832,1.1420738331547695,1739141183.7054834,23.159977912902832,0.0,1739141183.7054849,23.159977912902832,-0.34466865532679214,1739141183.7054858,23.159977912902832,0.19659313978977616,1739141183.705487,23.159977912902832,1.4867424884815617 +1739141183.725598,23.179977893829346,47.130957964595666,1739141183.7256007,23.179977893829346,0.5550866172302884,1739141183.725604,23.179977893829346,46.92787026141912,1739141183.7256072,23.179977893829346,51.718464518488446,1739141183.7256086,23.179977893829346,3.375558291209676,1739141183.7256105,23.179977893829346,0.5512423291604559,1739141183.725612,23.179977893829346,1.7853462099876243,1739141183.7256136,23.179977893829346,0.46894719587468836,1739141183.7256148,23.179977893829346,1.2240343505597016,1739141183.7256167,23.179977893829346,0.0,1739141183.7256184,23.179977893829346,-0.1261927857664919,1739141183.7256198,23.179977893829346,0.2133186794276024,1739141183.7256212,23.179977893829346,1.4542633166588586 +1739141183.7449868,23.19997787475586,47.130957964595666,1739141183.7449894,23.19997787475586,0.5550866172302884,1739141183.7449925,23.19997787475586,46.92787026141912,1739141183.7449956,23.19997787475586,51.718464518488446,1739141183.744997,23.19997787475586,3.375558291209676,1739141183.744999,23.19997787475586,0.5512423291604559,1739141183.745001,23.19997787475586,1.7853462099876243,1739141183.7450023,23.19997787475586,0.46894719587468836,1739141183.7450035,23.19997787475586,1.2240343505597016,1739141183.7450054,23.19997787475586,0.0,1739141183.7450068,23.19997787475586,-0.230228966099157,1739141183.7450082,23.19997787475586,0.2133186794276024,1739141183.7450097,23.19997787475586,1.4542633166588586 +1739141183.7657213,23.219977855682373,47.130957964595666,1739141183.7657242,23.219977855682373,0.5550866172302884,1739141183.7657273,23.219977855682373,46.92787026141912,1739141183.7657306,23.219977855682373,51.718464518488446,1739141183.765732,23.219977855682373,3.375558291209676,1739141183.765734,23.219977855682373,0.5512423291604559,1739141183.7657354,23.219977855682373,1.7853462099876243,1739141183.7657368,23.219977855682373,0.46894719587468836,1739141183.7657382,23.219977855682373,1.2240343505597016,1739141183.76574,23.219977855682373,0.0,1739141183.7657416,23.219977855682373,-0.230228966099157,1739141183.7657428,23.219977855682373,0.2133186794276024,1739141183.7657444,23.219977855682373,1.4542633166588586 +1739141183.787471,23.239977836608887,47.130957964595666,1739141183.7874749,23.239977836608887,0.5550866172302884,1739141183.7874794,23.239977836608887,46.92787026141912,1739141183.7874835,23.239977836608887,51.718464518488446,1739141183.7874854,23.239977836608887,3.375558291209676,1739141183.7874882,23.239977836608887,0.5512423291604559,1739141183.7874904,23.239977836608887,1.7853462099876243,1739141183.7874923,23.239977836608887,0.46894719587468836,1739141183.7874944,23.239977836608887,1.2240343505597016,1739141183.787497,23.239977836608887,0.0,1739141183.7874992,23.239977836608887,-0.230228966099157,1739141183.787501,23.239977836608887,0.2133186794276024,1739141183.787503,23.239977836608887,1.4542633166588586 +1739141183.8076913,23.2599778175354,47.130957964595666,1739141183.8076952,23.2599778175354,0.5550866172302884,1739141183.8076994,23.2599778175354,46.92787026141912,1739141183.8077035,23.2599778175354,51.718464518488446,1739141183.8077056,23.2599778175354,3.375558291209676,1739141183.8077083,23.2599778175354,0.5512423291604559,1739141183.8077102,23.2599778175354,1.7853462099876243,1739141183.8077123,23.2599778175354,0.46894719587468836,1739141183.807714,23.2599778175354,1.2240343505597016,1739141183.8077166,23.2599778175354,0.0,1739141183.807719,23.2599778175354,-0.230228966099157,1739141183.807721,23.2599778175354,0.2133186794276024,1739141183.8077228,23.2599778175354,1.4542633166588586 +1739141183.8267019,23.279977798461914,47.28572414625838,1739141183.8267057,23.279977798461914,0.5899238927140189,1739141183.8267102,23.279977798461914,47.31272841781301,1739141183.8267143,23.279977798461914,51.769384006741696,1739141183.8267167,23.279977798461914,3.669400042135566,1739141183.8267195,23.279977798461914,0.6018267952050955,1739141183.8267214,23.279977798461914,1.9689587385411322,1739141183.8267236,23.279977798461914,0.5062396657178101,1739141183.8267257,23.279977798461914,1.1373570987261759,1739141183.826728,23.279977798461914,0.0,1739141183.8267303,23.279977798461914,-0.3405947541661129,1739141183.8267324,23.279977798461914,0.23143025388230684,1739141183.8267345,23.279977798461914,1.4253966894639476 +1739141183.8548388,23.299977779388428,47.28572414625838,1739141183.8548474,23.299977779388428,0.5899238927140189,1739141183.8548577,23.299977779388428,47.31272841781301,1739141183.8548682,23.299977779388428,51.769384006741696,1739141183.8548732,23.299977779388428,3.669400042135566,1739141183.8548794,23.299977779388428,0.6018267952050955,1739141183.8548844,23.299977779388428,1.9689587385411322,1739141183.8548887,23.299977779388428,0.5062396657178101,1739141183.854893,23.299977779388428,1.1373570987261759,1739141183.854899,23.299977779388428,0.0,1739141183.8549042,23.299977779388428,-0.28803959073777174,1739141183.8549085,23.299977779388428,0.23143025388230684,1739141183.854913,23.299977779388428,1.4253966894639476 +1739141183.8760366,23.31997776031494,47.28572414625838,1739141183.876043,23.31997776031494,0.5899238927140189,1739141183.8760507,23.31997776031494,47.31272841781301,1739141183.876059,23.31997776031494,51.769384006741696,1739141183.8760638,23.31997776031494,3.669400042135566,1739141183.8760695,23.31997776031494,0.6018267952050955,1739141183.8760753,23.31997776031494,1.9689587385411322,1739141183.8760808,23.31997776031494,0.5062396657178101,1739141183.876086,23.31997776031494,1.1373570987261759,1739141183.8760922,23.31997776031494,0.0,1739141183.8760977,23.31997776031494,-0.28803959073777174,1739141183.8761032,23.31997776031494,0.23143025388230684,1739141183.8761086,23.31997776031494,1.4253966894639476 +1739141183.8945937,23.349977731704712,47.28572414625838,1739141183.894599,23.349977731704712,0.5899238927140189,1739141183.8946035,23.349977731704712,47.31272841781301,1739141183.8946087,23.349977731704712,51.769384006741696,1739141183.8946116,23.349977731704712,3.669400042135566,1739141183.8946157,23.349977731704712,0.6018267952050955,1739141183.894619,23.349977731704712,1.9689587385411322,1739141183.8946218,23.349977731704712,0.5062396657178101,1739141183.894625,23.349977731704712,1.1373570987261759,1739141183.8946285,23.349977731704712,0.0,1739141183.8946323,23.349977731704712,-0.28803959073777174,1739141183.8946357,23.349977731704712,0.23143025388230684,1739141183.894639,23.349977731704712,1.4253966894639476 +1739141183.9115865,23.369977712631226,47.28572414625838,1739141183.9115894,23.369977712631226,0.5899238927140189,1739141183.9115922,23.369977712631226,47.31272841781301,1739141183.911595,23.369977712631226,51.769384006741696,1739141183.9115963,23.369977712631226,3.669400042135566,1739141183.9115977,23.369977712631226,0.6018267952050955,1739141183.9115994,23.369977712631226,1.9689587385411322,1739141183.9116006,23.369977712631226,0.5062396657178101,1739141183.911602,23.369977712631226,1.1373570987261759,1739141183.9116035,23.369977712631226,0.0,1739141183.911605,23.369977712631226,-0.28803959073777174,1739141183.9116063,23.369977712631226,0.23143025388230684,1739141183.9116075,23.369977712631226,1.4253966894639476 +1739141183.951829,23.409977674484253,47.436461524016835,1739141183.9518313,23.409977674484253,0.6268368019365633,1739141183.9518335,23.409977674484253,47.32161575161903,1739141183.951836,23.409977674484253,51.75558748590007,1739141183.9518375,23.409977674484253,3.5835408219277283,1739141183.9518387,23.409977674484253,0.6002887092083692,1739141183.95184,23.409977674484253,1.7914204892168006,1739141183.9518414,23.409977674484253,0.4975636726326149,1739141183.9518423,23.409977674484253,1.2210639101054235,1739141183.9518437,23.409977674484253,0.0,1739141183.9518452,23.409977674484253,-0.06724140501848705,1739141183.9518461,23.409977674484253,0.2509757320666865,1739141183.9518473,23.409977674484253,1.3934473608466154 +1739141183.9715044,23.429977655410767,47.436461524016835,1739141183.9715075,23.429977655410767,0.6268368019365633,1739141183.9715104,23.429977655410767,47.32161575161903,1739141183.971513,23.429977655410767,51.75558748590007,1739141183.9715145,23.429977655410767,3.5835408219277283,1739141183.971516,23.429977655410767,0.6002887092083692,1739141183.9715173,23.429977655410767,1.7914204892168006,1739141183.9715185,23.429977655410767,0.4975636726326149,1739141183.9715197,23.429977655410767,1.2210639101054235,1739141183.9715214,23.429977655410767,0.0,1739141183.971523,23.429977655410767,-0.17238345074119188,1739141183.9715242,23.429977655410767,0.2509757320666865,1739141183.9715257,23.429977655410767,1.3934473608466154 +1739141183.9914799,23.44997763633728,47.436461524016835,1739141183.9914823,23.44997763633728,0.6268368019365633,1739141183.9914849,23.44997763633728,47.32161575161903,1739141183.9914873,23.44997763633728,51.75558748590007,1739141183.9914885,23.44997763633728,3.5835408219277283,1739141183.99149,23.44997763633728,0.6002887092083692,1739141183.991491,23.44997763633728,1.7914204892168006,1739141183.9914923,23.44997763633728,0.4975636726326149,1739141183.9914935,23.44997763633728,1.2210639101054235,1739141183.991495,23.44997763633728,0.0,1739141183.991496,23.44997763633728,-0.17238345074119188,1739141183.9914975,23.44997763633728,0.2509757320666865,1739141183.9914985,23.44997763633728,1.3934473608466154 +1739141184.011132,23.469977617263794,47.436461524016835,1739141184.0111346,23.469977617263794,0.6268368019365633,1739141184.0111382,23.469977617263794,47.32161575161903,1739141184.0111408,23.469977617263794,51.75558748590007,1739141184.0111425,23.469977617263794,3.5835408219277283,1739141184.011144,23.469977617263794,0.6002887092083692,1739141184.0111454,23.469977617263794,1.7914204892168006,1739141184.0111468,23.469977617263794,0.4975636726326149,1739141184.0111482,23.469977617263794,1.2210639101054235,1739141184.01115,23.469977617263794,0.0,1739141184.0111513,23.469977617263794,-0.17238345074119188,1739141184.011153,23.469977617263794,0.2509757320666865,1739141184.0111542,23.469977617263794,1.3934473608466154 +1739141184.0309224,23.489977598190308,47.436461524016835,1739141184.030925,23.489977598190308,0.6268368019365633,1739141184.0309277,23.489977598190308,47.32161575161903,1739141184.0309303,23.489977598190308,51.75558748590007,1739141184.0309317,23.489977598190308,3.5835408219277283,1739141184.0309331,23.489977598190308,0.6002887092083692,1739141184.0309348,23.489977598190308,1.7914204892168006,1739141184.030936,23.489977598190308,0.4975636726326149,1739141184.0309374,23.489977598190308,1.2210639101054235,1739141184.0309386,23.489977598190308,0.0,1739141184.03094,23.489977598190308,-0.17238345074119188,1739141184.0309412,23.489977598190308,0.2509757320666865,1739141184.0309424,23.489977598190308,1.3934473608466154 +1739141184.0510693,23.50997757911682,47.583595807536405,1739141184.0510714,23.50997757911682,0.6660375717195857,1739141184.0510743,23.50997757911682,47.69098133817127,1739141184.0510771,23.50997757911682,51.796282382215786,1739141184.0510783,23.50997757911682,3.892812046806671,1739141184.05108,23.50997757911682,0.6536412560990189,1739141184.0510812,23.50997757911682,1.9769227409398373,1739141184.0510828,23.50997757911682,0.5334880873077736,1739141184.051084,23.50997757911682,1.1337396977183918,1739141184.0510852,23.50997757911682,0.0,1739141184.0510867,23.50997757911682,-0.30260116989479574,1739141184.0510879,23.50997757911682,0.27188774419346373,1739141184.0510895,23.50997757911682,1.374332398945056 +1739141184.0714078,23.529977560043335,47.583595807536405,1739141184.071411,23.529977560043335,0.6660375717195857,1739141184.0714145,23.529977560043335,47.69098133817127,1739141184.071418,23.529977560043335,51.796282382215786,1739141184.07142,23.529977560043335,3.892812046806671,1739141184.071422,23.529977560043335,0.6536412560990189,1739141184.071424,23.529977560043335,1.9769227409398373,1739141184.0714257,23.529977560043335,0.5334880873077736,1739141184.0714273,23.529977560043335,1.1337396977183918,1739141184.0714295,23.529977560043335,0.0,1739141184.0714312,23.529977560043335,-0.2405927012266642,1739141184.0714326,23.529977560043335,0.27188774419346373,1739141184.0714345,23.529977560043335,1.374332398945056 +1739141184.0920358,23.54997754096985,47.583595807536405,1739141184.0920405,23.54997754096985,0.6660375717195857,1739141184.0920453,23.54997754096985,47.69098133817127,1739141184.0920496,23.54997754096985,51.796282382215786,1739141184.0920517,23.54997754096985,3.892812046806671,1739141184.0920546,23.54997754096985,0.6536412560990189,1739141184.092057,23.54997754096985,1.9769227409398373,1739141184.0920591,23.54997754096985,0.5334880873077736,1739141184.0920613,23.54997754096985,1.1337396977183918,1739141184.0920637,23.54997754096985,0.0,1739141184.092066,23.54997754096985,-0.2405927012266642,1739141184.0920684,23.54997754096985,0.27188774419346373,1739141184.0920703,23.54997754096985,1.374332398945056 +1739141184.1121008,23.569977521896362,47.583595807536405,1739141184.1121047,23.569977521896362,0.6660375717195857,1739141184.1121094,23.569977521896362,47.69098133817127,1739141184.1121137,23.569977521896362,51.796282382215786,1739141184.1121159,23.569977521896362,3.892812046806671,1739141184.1121187,23.569977521896362,0.6536412560990189,1739141184.112121,23.569977521896362,1.9769227409398373,1739141184.1121233,23.569977521896362,0.5334880873077736,1739141184.1121252,23.569977521896362,1.1337396977183918,1739141184.1121278,23.569977521896362,0.0,1739141184.1121297,23.569977521896362,-0.2405927012266642,1739141184.112132,23.569977521896362,0.27188774419346373,1739141184.1121342,23.569977521896362,1.374332398945056 +1739141184.132114,23.589977502822876,47.583595807536405,1739141184.132119,23.589977502822876,0.6660375717195857,1739141184.132124,23.589977502822876,47.69098133817127,1739141184.1321282,23.589977502822876,51.796282382215786,1739141184.1321306,23.589977502822876,3.892812046806671,1739141184.132133,23.589977502822876,0.6536412560990189,1739141184.1321354,23.589977502822876,1.9769227409398373,1739141184.1321375,23.589977502822876,0.5334880873077736,1739141184.1321397,23.589977502822876,1.1337396977183918,1739141184.1321423,23.589977502822876,0.0,1739141184.1321447,23.589977502822876,-0.2405927012266642,1739141184.1321466,23.589977502822876,0.27188774419346373,1739141184.132149,23.589977502822876,1.374332398945056 +1739141184.1520889,23.60997748374939,47.72741027453565,1739141184.152094,23.60997748374939,0.7076431192128956,1739141184.1520987,23.60997748374939,47.7051655868291,1739141184.1521032,23.60997748374939,51.788346358152936,1739141184.1521056,23.60997748374939,3.8163376331101344,1739141184.152109,23.60997748374939,0.6533549744741065,1739141184.152111,23.60997748374939,1.8002284072661348,1739141184.1521134,23.60997748374939,0.5232339175945067,1739141184.1521158,23.60997748374939,1.216769467226467,1739141184.1521182,23.60997748374939,0.0,1739141184.1521204,23.60997748374939,-0.02412801189472781,1739141184.1521223,23.60997748374939,0.2936427258086655,1739141184.1521244,23.60997748374939,1.3439759541047949 +1739141184.1723287,23.629977464675903,47.72741027453565,1739141184.1723325,23.629977464675903,0.7076431192128956,1739141184.172337,23.629977464675903,47.7051655868291,1739141184.1723418,23.629977464675903,51.788346358152936,1739141184.1723437,23.629977464675903,3.8163376331101344,1739141184.1723466,23.629977464675903,0.6533549744741065,1739141184.172349,23.629977464675903,1.8002284072661348,1739141184.172351,23.629977464675903,0.5232339175945067,1739141184.172353,23.629977464675903,1.216769467226467,1739141184.172356,23.629977464675903,0.0,1739141184.172358,23.629977464675903,-0.1272064868783278,1739141184.1723602,23.629977464675903,0.2936427258086655,1739141184.1723623,23.629977464675903,1.3439759541047949 +1739141184.1913693,23.649977445602417,47.72741027453565,1739141184.191373,23.649977445602417,0.7076431192128956,1739141184.1913767,23.649977445602417,47.7051655868291,1739141184.19138,23.649977445602417,51.788346358152936,1739141184.1913815,23.649977445602417,3.8163376331101344,1739141184.1913836,23.649977445602417,0.6533549744741065,1739141184.191385,23.649977445602417,1.8002284072661348,1739141184.191387,23.649977445602417,0.5232339175945067,1739141184.1913884,23.649977445602417,1.216769467226467,1739141184.1913903,23.649977445602417,0.0,1739141184.191392,23.649977445602417,-0.1272064868783278,1739141184.1913936,23.649977445602417,0.2936427258086655,1739141184.191395,23.649977445602417,1.3439759541047949 +1739141184.2113223,23.66997742652893,47.72741027453565,1739141184.211326,23.66997742652893,0.7076431192128956,1739141184.2113292,23.66997742652893,47.7051655868291,1739141184.2113326,23.66997742652893,51.788346358152936,1739141184.2113345,23.66997742652893,3.8163376331101344,1739141184.2113361,23.66997742652893,0.6533549744741065,1739141184.211338,23.66997742652893,1.8002284072661348,1739141184.2113395,23.66997742652893,0.5232339175945067,1739141184.211341,23.66997742652893,1.216769467226467,1739141184.2113428,23.66997742652893,0.0,1739141184.2113447,23.66997742652893,-0.1272064868783278,1739141184.2113464,23.66997742652893,0.2936427258086655,1739141184.211348,23.66997742652893,1.3439759541047949 +1739141184.231169,23.689977407455444,47.72741027453565,1739141184.2311718,23.689977407455444,0.7076431192128956,1739141184.2311754,23.689977407455444,47.7051655868291,1739141184.2311785,23.689977407455444,51.788346358152936,1739141184.23118,23.689977407455444,3.8163376331101344,1739141184.231182,23.689977407455444,0.6533549744741065,1739141184.2311838,23.689977407455444,1.8002284072661348,1739141184.2311854,23.689977407455444,0.5232339175945067,1739141184.2311866,23.689977407455444,1.216769467226467,1739141184.2311888,23.689977407455444,0.0,1739141184.2311902,23.689977407455444,-0.1272064868783278,1739141184.2311916,23.689977407455444,0.2936427258086655,1739141184.231193,23.689977407455444,1.3439759541047949 +1739141184.251253,23.709977388381958,47.72741027453565,1739141184.2512558,23.709977388381958,0.7076431192128956,1739141184.2512593,23.709977388381958,47.7051655868291,1739141184.2512624,23.709977388381958,51.788346358152936,1739141184.2512643,23.709977388381958,3.8163376331101344,1739141184.251266,23.709977388381958,0.6533549744741065,1739141184.251268,23.709977388381958,1.8002284072661348,1739141184.2512693,23.709977388381958,0.5232339175945067,1739141184.251271,23.709977388381958,1.216769467226467,1739141184.2512727,23.709977388381958,0.0,1739141184.2512746,23.709977388381958,-0.1272064868783278,1739141184.251276,23.709977388381958,0.2936427258086655,1739141184.2512777,23.709977388381958,1.3439759541047949 +1739141184.2715771,23.72997736930847,47.86799051415942,1739141184.271581,23.72997736930847,0.7517310547790164,1739141184.2715845,23.72997736930847,47.88292743416044,1739141184.2715878,23.72997736930847,51.80158563396478,1739141184.2715893,23.72997736930847,3.9577845094716904,1739141184.2715914,23.72997736930847,0.6838470880697006,1739141184.2715929,23.72997736930847,1.8237125087259987,1739141184.2715948,23.72997736930847,0.538041532506154,1739141184.2715962,23.72997736930847,1.205393088638264,1739141184.2715983,23.72997736930847,0.0,1739141184.2716002,23.72997736930847,-0.1262211155726053,1739141184.271602,23.72997736930847,0.3162459560267897,1739141184.271603,23.72997736930847,1.332083428876564 +1739141184.2911744,23.749977350234985,47.86799051415942,1739141184.2911773,23.749977350234985,0.7517310547790164,1739141184.2911808,23.749977350234985,47.88292743416044,1739141184.2911842,23.749977350234985,51.80158563396478,1739141184.2911859,23.749977350234985,3.9577845094716904,1739141184.291188,23.749977350234985,0.6838470880697006,1739141184.2911897,23.749977350234985,1.8237125087259987,1739141184.2911913,23.749977350234985,0.538041532506154,1739141184.291193,23.749977350234985,1.205393088638264,1739141184.291195,23.749977350234985,0.0,1739141184.2911966,23.749977350234985,-0.12669034023829995,1739141184.2911983,23.749977350234985,0.3162459560267897,1739141184.2911997,23.749977350234985,1.332083428876564 +1739141184.311384,23.7699773311615,47.86799051415942,1739141184.3113875,23.7699773311615,0.7517310547790164,1739141184.3113909,23.7699773311615,47.88292743416044,1739141184.3113945,23.7699773311615,51.80158563396478,1739141184.3113964,23.7699773311615,3.9577845094716904,1739141184.3113985,23.7699773311615,0.6838470880697006,1739141184.3114,23.7699773311615,1.8237125087259987,1739141184.3114014,23.7699773311615,0.538041532506154,1739141184.3114035,23.7699773311615,1.205393088638264,1739141184.3114057,23.7699773311615,0.0,1739141184.311407,23.7699773311615,-0.12669034023829995,1739141184.3114088,23.7699773311615,0.3162459560267897,1739141184.3114104,23.7699773311615,1.332083428876564 +1739141184.3311725,23.789977312088013,47.86799051415942,1739141184.3311753,23.789977312088013,0.7517310547790164,1739141184.3311787,23.789977312088013,47.88292743416044,1739141184.3311818,23.789977312088013,51.80158563396478,1739141184.3311837,23.789977312088013,3.9577845094716904,1739141184.3311856,23.789977312088013,0.6838470880697006,1739141184.3311872,23.789977312088013,1.8237125087259987,1739141184.3311887,23.789977312088013,0.538041532506154,1739141184.33119,23.789977312088013,1.205393088638264,1739141184.331192,23.789977312088013,0.0,1739141184.3311937,23.789977312088013,-0.12669034023829995,1739141184.331195,23.789977312088013,0.3162459560267897,1739141184.3311968,23.789977312088013,1.332083428876564 +1739141184.3511684,23.809977293014526,47.86799051415942,1739141184.3511713,23.809977293014526,0.7517310547790164,1739141184.3511744,23.809977293014526,47.88292743416044,1739141184.3511777,23.809977293014526,51.80158563396478,1739141184.3511794,23.809977293014526,3.9577845094716904,1739141184.351181,23.809977293014526,0.6838470880697006,1739141184.3511827,23.809977293014526,1.8237125087259987,1739141184.3511841,23.809977293014526,0.538041532506154,1739141184.3511856,23.809977293014526,1.205393088638264,1739141184.3511875,23.809977293014526,0.0,1739141184.3511891,23.809977293014526,-0.12669034023829995,1739141184.3511908,23.809977293014526,0.3162459560267897,1739141184.3511922,23.809977293014526,1.332083428876564 +1739141184.3713183,23.82997727394104,48.00611169306352,1739141184.3713217,23.82997727394104,0.7985231361103509,1739141184.371325,23.82997727394104,47.885738904884946,1739141184.3713286,23.82997727394104,51.79900490254647,1739141184.37133,23.82997727394104,3.9190735381971256,1739141184.3713324,23.82997727394104,0.6884515254619069,1739141184.3713338,23.82997727394104,1.6799451283255171,1739141184.3713355,23.82997727394104,0.5292618197668629,1739141184.371337,23.82997727394104,1.2767434809290135,1739141184.3713393,23.82997727394104,0.0,1739141184.3713408,23.82997727394104,0.036002173206091725,1739141184.3713424,23.82997727394104,0.33936900627488115,1739141184.3713439,23.82997727394104,1.3182139718736126 +1739141184.3912518,23.849977254867554,48.00611169306352,1739141184.3912544,23.849977254867554,0.7985231361103509,1739141184.3912578,23.849977254867554,47.885738904884946,1739141184.391261,23.849977254867554,51.79900490254647,1739141184.3912628,23.849977254867554,3.9190735381971256,1739141184.3912644,23.849977254867554,0.6884515254619069,1739141184.391266,23.849977254867554,1.6799451283255171,1739141184.3912678,23.849977254867554,0.5292618197668629,1739141184.3912692,23.849977254867554,1.2767434809290135,1739141184.391271,23.849977254867554,0.0,1739141184.3912728,23.849977254867554,-0.04147049094459909,1739141184.3912742,23.849977254867554,0.33936900627488115,1739141184.391276,23.849977254867554,1.3182139718736126 +1739141184.411679,23.869977235794067,48.00611169306352,1739141184.4116821,23.869977235794067,0.7985231361103509,1739141184.4116855,23.869977235794067,47.885738904884946,1739141184.4116888,23.869977235794067,51.79900490254647,1739141184.4116902,23.869977235794067,3.9190735381971256,1739141184.4116924,23.869977235794067,0.6884515254619069,1739141184.4116938,23.869977235794067,1.6799451283255171,1739141184.4116952,23.869977235794067,0.5292618197668629,1739141184.411697,23.869977235794067,1.2767434809290135,1739141184.4116986,23.869977235794067,0.0,1739141184.4117005,23.869977235794067,-0.04147049094459909,1739141184.411702,23.869977235794067,0.33936900627488115,1739141184.4117036,23.869977235794067,1.3182139718736126 +1739141184.4338932,23.88997721672058,48.00611169306352,1739141184.4338987,23.88997721672058,0.7985231361103509,1739141184.433905,23.88997721672058,47.885738904884946,1739141184.4339113,23.88997721672058,51.79900490254647,1739141184.4339147,23.88997721672058,3.9190735381971256,1739141184.4339194,23.88997721672058,0.6884515254619069,1739141184.4339235,23.88997721672058,1.6799451283255171,1739141184.4339278,23.88997721672058,0.5292618197668629,1739141184.4339318,23.88997721672058,1.2767434809290135,1739141184.4339364,23.88997721672058,0.0,1739141184.4339404,23.88997721672058,-0.04147049094459909,1739141184.433945,23.88997721672058,0.33936900627488115,1739141184.433949,23.88997721672058,1.3182139718736126 +1739141184.4512012,23.909977197647095,48.00611169306352,1739141184.451204,23.909977197647095,0.7985231361103509,1739141184.4512076,23.909977197647095,47.885738904884946,1739141184.451211,23.909977197647095,51.79900490254647,1739141184.4512126,23.909977197647095,3.9190735381971256,1739141184.4512146,23.909977197647095,0.6884515254619069,1739141184.4512162,23.909977197647095,1.6799451283255171,1739141184.4512177,23.909977197647095,0.5292618197668629,1739141184.451219,23.909977197647095,1.2767434809290135,1739141184.4512212,23.909977197647095,0.0,1739141184.451223,23.909977197647095,-0.04147049094459909,1739141184.4512243,23.909977197647095,0.33936900627488115,1739141184.4512258,23.909977197647095,1.3182139718736126 +1739141184.471833,23.92997717857361,48.00611169306352,1739141184.4718375,23.92997717857361,0.7985231361103509,1739141184.4718423,23.92997717857361,47.885738904884946,1739141184.4718459,23.92997717857361,51.79900490254647,1739141184.4718478,23.92997717857361,3.9190735381971256,1739141184.47185,23.92997717857361,0.6884515254619069,1739141184.4718516,23.92997717857361,1.6799451283255171,1739141184.4718533,23.92997717857361,0.5292618197668629,1739141184.471855,23.92997717857361,1.2767434809290135,1739141184.4718568,23.92997717857361,0.0,1739141184.471859,23.92997717857361,-0.04147049094459909,1739141184.4718606,23.92997717857361,0.33936900627488115,1739141184.4718626,23.92997717857361,1.3182139718736126 +1739141184.4959083,23.949977159500122,48.14224310116517,1739141184.495918,23.949977159500122,0.848220912100853,1739141184.4959288,23.949977159500122,47.888524192742835,1739141184.4959388,23.949977159500122,51.79836423139903,1739141184.4959438,23.949977159500122,3.9128735025724475,1739141184.4959497,23.949977159500122,0.6976182983258542,1739141184.4959548,23.949977159500122,1.567392335438302,1739141184.4959593,23.949977159500122,0.5235275291479067,1739141184.4959638,23.949977159500122,1.3355374534620637,1739141184.4959698,23.949977159500122,0.0,1739141184.4959753,23.949977159500122,0.07651157425556351,1739141184.4959798,23.949977159500122,0.36285305670631973,1739141184.495984,23.949977159500122,1.315207843081447 +1739141184.5156422,23.969977140426636,48.14224310116517,1739141184.5156484,23.969977140426636,0.848220912100853,1739141184.5156553,23.969977140426636,47.888524192742835,1739141184.5156617,23.969977140426636,51.79836423139903,1739141184.515665,23.969977140426636,3.9128735025724475,1739141184.5156696,23.969977140426636,0.6976182983258542,1739141184.515673,23.969977140426636,1.567392335438302,1739141184.5156763,23.969977140426636,0.5235275291479067,1739141184.5156796,23.969977140426636,1.3355374534620637,1739141184.5156837,23.969977140426636,0.0,1739141184.5156872,23.969977140426636,0.02032961038061676,1739141184.5156906,23.969977140426636,0.36285305670631973,1739141184.515694,23.969977140426636,1.315207843081447 +1739141184.5338092,23.98997712135315,48.14224310116517,1739141184.5338137,23.98997712135315,0.848220912100853,1739141184.5338197,23.98997712135315,47.888524192742835,1739141184.533825,23.98997712135315,51.79836423139903,1739141184.5338278,23.98997712135315,3.9128735025724475,1739141184.5338311,23.98997712135315,0.6976182983258542,1739141184.533834,23.98997712135315,1.567392335438302,1739141184.5338366,23.98997712135315,0.5235275291479067,1739141184.5338387,23.98997712135315,1.3355374534620637,1739141184.5338418,23.98997712135315,0.0,1739141184.5338447,23.98997712135315,0.02032961038061676,1739141184.5338473,23.98997712135315,0.36285305670631973,1739141184.53385,23.98997712135315,1.315207843081447 +1739141184.5569925,24.009977102279663,48.14224310116517,1739141184.5570138,24.009977102279663,0.848220912100853,1739141184.5570312,24.009977102279663,47.888524192742835,1739141184.557042,24.009977102279663,51.79836423139903,1739141184.557047,24.009977102279663,3.9128735025724475,1739141184.557053,24.009977102279663,0.6976182983258542,1739141184.5570586,24.009977102279663,1.567392335438302,1739141184.557063,24.009977102279663,0.5235275291479067,1739141184.5570693,24.009977102279663,1.3355374534620637,1739141184.5570765,24.009977102279663,0.0,1739141184.5570836,24.009977102279663,0.02032961038061676,1739141184.5570886,24.009977102279663,0.36285305670631973,1739141184.5570934,24.009977102279663,1.315207843081447 +1739141184.57434,24.01997709274292,48.14224310116517,1739141184.574346,24.01997709274292,0.848220912100853,1739141184.5743535,24.01997709274292,47.888524192742835,1739141184.574362,24.01997709274292,51.79836423139903,1739141184.574367,24.01997709274292,3.9128735025724475,1739141184.574373,24.01997709274292,0.6976182983258542,1739141184.5743785,24.01997709274292,1.567392335438302,1739141184.574384,24.01997709274292,0.5235275291479067,1739141184.574389,24.01997709274292,1.3355374534620637,1739141184.574395,24.01997709274292,0.0,1739141184.5744002,24.01997709274292,0.02032961038061676,1739141184.5744057,24.01997709274292,0.36285305670631973,1739141184.5744112,24.01997709274292,1.315207843081447 +1739141184.5920362,24.04997706413269,48.277072268442254,1739141184.5920396,24.04997706413269,0.9010648205054448,1739141184.5920432,24.04997706413269,48.46528281914972,1739141184.5920465,24.04997706413269,51.808222694163724,1739141184.5920484,24.04997706413269,4.497375910497682,1739141184.5920508,24.04997706413269,0.7945401066891421,1739141184.5920525,24.04997706413269,2.0007160468609895,1739141184.5920544,24.04997706413269,0.596879372726044,1739141184.5920556,24.04997706413269,1.1230007157706159,1739141184.5920577,24.04997706413269,0.0,1739141184.5920594,24.04997706413269,-0.39064024749458004,1739141184.5920606,24.04997706413269,0.3863371071377583,1739141184.5920622,24.04997706413269,1.3179409331829586 +1739141184.6115332,24.069977045059204,48.277072268442254,1739141184.6115353,24.069977045059204,0.9010648205054448,1739141184.6115382,24.069977045059204,48.46528281914972,1739141184.6115408,24.069977045059204,51.808222694163724,1739141184.611542,24.069977045059204,4.497375910497682,1739141184.6115437,24.069977045059204,0.7945401066891421,1739141184.6115448,24.069977045059204,2.0007160468609895,1739141184.6115458,24.069977045059204,0.596879372726044,1739141184.6115472,24.069977045059204,1.1230007157706159,1739141184.6115487,24.069977045059204,0.0,1739141184.6115499,24.069977045059204,-0.1949402174123427,1739141184.6115513,24.069977045059204,0.3863371071377583,1739141184.6115522,24.069977045059204,1.3179409331829586 +1739141184.6314547,24.089977025985718,48.277072268442254,1739141184.6314576,24.089977025985718,0.9010648205054448,1739141184.631461,24.089977025985718,48.46528281914972,1739141184.6314638,24.089977025985718,51.808222694163724,1739141184.631465,24.089977025985718,4.497375910497682,1739141184.6314669,24.089977025985718,0.7945401066891421,1739141184.631468,24.089977025985718,2.0007160468609895,1739141184.6314692,24.089977025985718,0.596879372726044,1739141184.6314707,24.089977025985718,1.1230007157706159,1739141184.6314723,24.089977025985718,0.0,1739141184.6314738,24.089977025985718,-0.1949402174123427,1739141184.631475,24.089977025985718,0.3863371071377583,1739141184.6314762,24.089977025985718,1.3179409331829586 +1739141184.6532304,24.10997700691223,48.277072268442254,1739141184.653233,24.10997700691223,0.9010648205054448,1739141184.653236,24.10997700691223,48.46528281914972,1739141184.6532383,24.10997700691223,51.808222694163724,1739141184.6532395,24.10997700691223,4.497375910497682,1739141184.6532414,24.10997700691223,0.7945401066891421,1739141184.6532426,24.10997700691223,2.0007160468609895,1739141184.6532435,24.10997700691223,0.596879372726044,1739141184.653245,24.10997700691223,1.1230007157706159,1739141184.6532464,24.10997700691223,0.0,1739141184.653248,24.10997700691223,-0.1949402174123427,1739141184.653249,24.10997700691223,0.3863371071377583,1739141184.6532502,24.10997700691223,1.3179409331829586 +1739141184.6713827,24.129976987838745,48.277072268442254,1739141184.671385,24.129976987838745,0.9010648205054448,1739141184.671388,24.129976987838745,48.46528281914972,1739141184.6713905,24.129976987838745,51.808222694163724,1739141184.6713917,24.129976987838745,4.497375910497682,1739141184.6713936,24.129976987838745,0.7945401066891421,1739141184.6713948,24.129976987838745,2.0007160468609895,1739141184.671396,24.129976987838745,0.596879372726044,1739141184.6713974,24.129976987838745,1.1230007157706159,1739141184.6713989,24.129976987838745,0.0,1739141184.6714003,24.129976987838745,-0.1949402174123427,1739141184.6714015,24.129976987838745,0.3863371071377583,1739141184.6714027,24.129976987838745,1.3179409331829586 +1739141184.6915953,24.14997696876526,48.277072268442254,1739141184.691598,24.14997696876526,0.9010648205054448,1739141184.6916008,24.14997696876526,48.46528281914972,1739141184.6916037,24.14997696876526,51.808222694163724,1739141184.691605,24.14997696876526,4.497375910497682,1739141184.6916063,24.14997696876526,0.7945401066891421,1739141184.6916075,24.14997696876526,2.0007160468609895,1739141184.691609,24.14997696876526,0.596879372726044,1739141184.6916099,24.14997696876526,1.1230007157706159,1739141184.6916113,24.14997696876526,0.0,1739141184.6916127,24.14997696876526,-0.1949402174123427,1739141184.6916142,24.14997696876526,0.3863371071377583,1739141184.6916156,24.14997696876526,1.3179409331829586 +1739141184.712046,24.169976949691772,48.409136502916624,1739141184.7120483,24.169976949691772,0.9564615267001306,1739141184.7120512,24.169976949691772,48.65432745152568,1739141184.7120543,24.169976949691772,51.80351433776799,1739141184.7120554,24.169976949691772,4.586770595712071,1739141184.7120574,24.169976949691772,0.8189715575766607,1739141184.7120585,24.169976949691772,1.9736294395248573,1739141184.7120597,24.169976949691772,0.6052899915065293,1739141184.712061,24.169976949691772,1.135234180478997,1739141184.7120621,24.169976949691772,0.0,1739141184.7120638,24.169976949691772,-0.10825517083243165,1739141184.712065,24.169976949691772,0.4106077828026813,1739141184.7120664,24.169976949691772,1.2847679655413813 +1739141184.731438,24.189976930618286,48.409136502916624,1739141184.73144,24.189976930618286,0.9564615267001306,1739141184.731443,24.189976930618286,48.65432745152568,1739141184.7314456,24.189976930618286,51.80351433776799,1739141184.7314467,24.189976930618286,4.586770595712071,1739141184.7314484,24.189976930618286,0.8189715575766607,1739141184.7314498,24.189976930618286,1.9736294395248573,1739141184.731451,24.189976930618286,0.6052899915065293,1739141184.7314522,24.189976930618286,1.135234180478997,1739141184.7314537,24.189976930618286,0.0,1739141184.7314553,24.189976930618286,-0.14953378506238435,1739141184.7314563,24.189976930618286,0.4106077828026813,1739141184.7314577,24.189976930618286,1.2847679655413813 +1739141184.7513554,24.2099769115448,48.409136502916624,1739141184.7513585,24.2099769115448,0.9564615267001306,1739141184.7513616,24.2099769115448,48.65432745152568,1739141184.751364,24.2099769115448,51.80351433776799,1739141184.7513654,24.2099769115448,4.586770595712071,1739141184.7513669,24.2099769115448,0.8189715575766607,1739141184.7513685,24.2099769115448,1.9736294395248573,1739141184.7513697,24.2099769115448,0.6052899915065293,1739141184.751371,24.2099769115448,1.135234180478997,1739141184.7513728,24.2099769115448,0.0,1739141184.751374,24.2099769115448,-0.14953378506238435,1739141184.7513754,24.2099769115448,0.4106077828026813,1739141184.7513766,24.2099769115448,1.2847679655413813 +1739141184.7715635,24.229976892471313,48.409136502916624,1739141184.7715673,24.229976892471313,0.9564615267001306,1739141184.7715707,24.229976892471313,48.65432745152568,1739141184.7715743,24.229976892471313,51.80351433776799,1739141184.7715757,24.229976892471313,4.586770595712071,1739141184.7715778,24.229976892471313,0.8189715575766607,1739141184.7715795,24.229976892471313,1.9736294395248573,1739141184.7715812,24.229976892471313,0.6052899915065293,1739141184.7715826,24.229976892471313,1.135234180478997,1739141184.771585,24.229976892471313,0.0,1739141184.7715867,24.229976892471313,-0.14953378506238435,1739141184.771588,24.229976892471313,0.4106077828026813,1739141184.77159,24.229976892471313,1.2847679655413813 +1739141184.791423,24.249976873397827,48.409136502916624,1739141184.7914264,24.249976873397827,0.9564615267001306,1739141184.791429,24.249976873397827,48.65432745152568,1739141184.7914321,24.249976873397827,51.80351433776799,1739141184.7914336,24.249976873397827,4.586770595712071,1739141184.791435,24.249976873397827,0.8189715575766607,1739141184.7914362,24.249976873397827,1.9736294395248573,1739141184.7914376,24.249976873397827,0.6052899915065293,1739141184.7914388,24.249976873397827,1.135234180478997,1739141184.7914407,24.249976873397827,0.0,1739141184.791442,24.249976873397827,-0.14953378506238435,1739141184.791443,24.249976873397827,0.4106077828026813,1739141184.7914448,24.249976873397827,1.2847679655413813 +1739141184.8115685,24.26997685432434,48.537239686862506,1739141184.8115714,24.26997685432434,1.0140179623567347,1739141184.811575,24.26997685432434,48.75482725361292,1739141184.8115776,24.26997685432434,51.79976702474383,1739141184.8115792,24.26997685432434,4.636519717213404,1739141184.8115807,24.26997685432434,0.8376342458930119,1739141184.8115823,24.26997685432434,1.9028564402191417,1739141184.8115835,24.26997685432434,0.6064938836443842,1739141184.8115847,24.26997685432434,1.1678309692044728,1739141184.8115869,24.26997685432434,0.0,1739141184.8115883,24.26997685432434,-0.05509975635091146,1739141184.8115897,24.26997685432434,0.43665349076458304,1739141184.811591,24.26997685432434,1.2678993331198698 +1739141184.8356473,24.289976835250854,48.537239686862506,1739141184.835656,24.289976835250854,1.0140179623567347,1739141184.835666,24.289976835250854,48.75482725361292,1739141184.8356757,24.289976835250854,51.79976702474383,1739141184.8356802,24.289976835250854,4.636519717213404,1739141184.8356862,24.289976835250854,0.8376342458930119,1739141184.835691,24.289976835250854,1.9028564402191417,1739141184.8356955,24.289976835250854,0.6064938836443842,1739141184.8357,24.289976835250854,1.1678309692044728,1739141184.8357055,24.289976835250854,0.0,1739141184.8357108,24.289976835250854,-0.10006836391539697,1739141184.8357153,24.289976835250854,0.43665349076458304,1739141184.8357198,24.289976835250854,1.2678993331198698 +1739141184.8633046,24.309976816177368,48.537239686862506,1739141184.8633146,24.309976816177368,1.0140179623567347,1739141184.8633254,24.309976816177368,48.75482725361292,1739141184.8633366,24.309976816177368,51.79976702474383,1739141184.8633473,24.309976816177368,4.636519717213404,1739141184.863364,24.309976816177368,0.8376342458930119,1739141184.8633769,24.309976816177368,1.9028564402191417,1739141184.8633904,24.309976816177368,0.6064938836443842,1739141184.863402,24.309976816177368,1.1678309692044728,1739141184.8634121,24.309976816177368,0.0,1739141184.8634257,24.309976816177368,-0.10006836391539697,1739141184.8634396,24.309976816177368,0.43665349076458304,1739141184.8634508,24.309976816177368,1.2678993331198698 +1739141184.8842602,24.319976806640625,48.537239686862506,1739141184.8842654,24.319976806640625,1.0140179623567347,1739141184.884271,24.319976806640625,48.75482725361292,1739141184.8842762,24.319976806640625,51.79976702474383,1739141184.8842788,24.319976806640625,4.636519717213404,1739141184.884282,24.319976806640625,0.8376342458930119,1739141184.8842847,24.319976806640625,1.9028564402191417,1739141184.884287,24.319976806640625,0.6064938836443842,1739141184.8842897,24.319976806640625,1.1678309692044728,1739141184.884293,24.319976806640625,0.0,1739141184.884296,24.319976806640625,-0.10006836391539697,1739141184.8842986,24.319976806640625,0.43665349076458304,1739141184.8843014,24.319976806640625,1.2678993331198698 +1739141184.9016628,24.349976778030396,48.537239686862506,1739141184.9016678,24.349976778030396,1.0140179623567347,1739141184.901673,24.349976778030396,48.75482725361292,1739141184.9016774,24.349976778030396,51.79976702474383,1739141184.9016795,24.349976778030396,4.636519717213404,1739141184.9016821,24.349976778030396,0.8376342458930119,1739141184.9016845,24.349976778030396,1.9028564402191417,1739141184.9016867,24.349976778030396,0.6064938836443842,1739141184.9016888,24.349976778030396,1.1678309692044728,1739141184.9016914,24.349976778030396,0.0,1739141184.9016933,24.349976778030396,-0.10006836391539697,1739141184.9016955,24.349976778030396,0.43665349076458304,1739141184.9016979,24.349976778030396,1.2678993331198698 +1739141184.9212759,24.36997675895691,48.537239686862506,1739141184.921282,24.36997675895691,1.0140179623567347,1739141184.9212885,24.36997675895691,48.75482725361292,1739141184.9212937,24.36997675895691,51.79976702474383,1739141184.9212966,24.36997675895691,4.636519717213404,1739141184.9213002,24.36997675895691,0.8376342458930119,1739141184.921303,24.36997675895691,1.9028564402191417,1739141184.9213057,24.36997675895691,0.6064938836443842,1739141184.9213085,24.36997675895691,1.1678309692044728,1739141184.9213119,24.36997675895691,0.0,1739141184.9213147,24.36997675895691,-0.10006836391539697,1739141184.9213178,24.36997675895691,0.43665349076458304,1739141184.9213212,24.36997675895691,1.2678993331198698 +1739141184.9412692,24.389976739883423,48.66246036935824,1739141184.9412742,24.389976739883423,1.0743583690850924,1739141184.9412796,24.389976739883423,48.87847653172057,1739141184.9412851,24.389976739883423,51.790668936895926,1739141184.9412878,24.389976739883423,4.729498338702861,1739141184.9412916,24.389976739883423,0.8629226116428952,1739141184.941295,24.389976739883423,1.8687644878414467,1739141184.9412978,24.389976739883423,0.6108,1739141184.9413004,24.389976739883423,1.1838655055659126,1739141184.941304,24.389976739883423,0.0,1739141184.9413073,24.389976739883423,-0.05022627326564093,1739141184.94131,24.389976739883423,0.4639893009107135,1739141184.9413128,24.389976739883423,1.25782611956873 +1739141184.96083,24.409976720809937,48.66246036935824,1739141184.9608347,24.409976720809937,1.0743583690850924,1739141184.9608395,24.409976720809937,48.87847653172057,1739141184.9608443,24.409976720809937,51.790668936895926,1739141184.9608471,24.409976720809937,4.729498338702861,1739141184.96085,24.409976720809937,0.8629226116428952,1739141184.9608521,24.409976720809937,1.8687644878414467,1739141184.9608548,24.409976720809937,0.6108,1739141184.960857,24.409976720809937,1.1838655055659126,1739141184.9608593,24.409976720809937,0.0,1739141184.9608617,24.409976720809937,-0.07396061400281728,1739141184.9608638,24.409976720809937,0.4639893009107135,1739141184.9608662,24.409976720809937,1.25782611956873 +1739141184.9810684,24.42997670173645,48.66246036935824,1739141184.9810736,24.42997670173645,1.0743583690850924,1739141184.981078,24.42997670173645,48.87847653172057,1739141184.9810824,24.42997670173645,51.790668936895926,1739141184.9810848,24.42997670173645,4.729498338702861,1739141184.981088,24.42997670173645,0.8629226116428952,1739141184.98109,24.42997670173645,1.8687644878414467,1739141184.9810922,24.42997670173645,0.6108,1739141184.981094,24.42997670173645,1.1838655055659126,1739141184.981097,24.42997670173645,0.0,1739141184.981099,24.42997670173645,-0.07396061400281728,1739141184.9811008,24.42997670173645,0.4639893009107135,1739141184.9811032,24.42997670173645,1.25782611956873 +1739141185.000434,24.449976682662964,48.66246036935824,1739141185.0004396,24.449976682662964,1.0743583690850924,1739141185.000445,24.449976682662964,48.87847653172057,1739141185.0004504,24.449976682662964,51.790668936895926,1739141185.0004525,24.449976682662964,4.729498338702861,1739141185.0004554,24.449976682662964,0.8629226116428952,1739141185.0004578,24.449976682662964,1.8687644878414467,1739141185.0004601,24.449976682662964,0.6108,1739141185.0004618,24.449976682662964,1.1838655055659126,1739141185.000465,24.449976682662964,0.0,1739141185.0004678,24.449976682662964,-0.07396061400281728,1739141185.000471,24.449976682662964,0.4639893009107135,1739141185.0004737,24.449976682662964,1.25782611956873 +1739141185.020746,24.469976663589478,48.66246036935824,1739141185.0207505,24.469976663589478,1.0743583690850924,1739141185.0207553,24.469976663589478,48.87847653172057,1739141185.02076,24.469976663589478,51.790668936895926,1739141185.0207622,24.469976663589478,4.729498338702861,1739141185.0207655,24.469976663589478,0.8629226116428952,1739141185.020768,24.469976663589478,1.8687644878414467,1739141185.0207708,24.469976663589478,0.6108,1739141185.0207734,24.469976663589478,1.1838655055659126,1739141185.0207763,24.469976663589478,0.0,1739141185.0207784,24.469976663589478,-0.07396061400281728,1739141185.0207813,24.469976663589478,0.4639893009107135,1739141185.0207841,24.469976663589478,1.25782611956873 +1739141185.0416205,24.48997664451599,48.785056637175146,1739141185.0416257,24.48997664451599,1.1376407958308787,1739141185.0416305,24.48997664451599,49.12003909504482,1739141185.041634,24.48997664451599,51.760650167554694,1739141185.0416355,24.48997664451599,4.9452797510137625,1739141185.0416377,24.48997664451599,0.9074505502097887,1739141185.0416396,24.48997664451599,1.951984895565977,1739141185.0416417,24.48997664451599,0.6108,1739141185.0416436,24.48997664451599,1.1451055013147813,1739141185.0416458,24.48997664451599,0.0,1739141185.0416486,24.48997664451599,-0.13290360498161363,1739141185.0416512,24.48997664451599,0.49163581313802623,1739141185.0416534,24.48997664451599,1.2499410013328662 +1739141185.0611193,24.509976625442505,48.785056637175146,1739141185.0611238,24.509976625442505,1.1376407958308787,1739141185.0611281,24.509976625442505,49.12003909504482,1739141185.061133,24.509976625442505,51.760650167554694,1739141185.061135,24.509976625442505,4.9452797510137625,1739141185.061138,24.509976625442505,0.9074505502097887,1739141185.0611403,24.509976625442505,1.951984895565977,1739141185.0611436,24.509976625442505,0.6108,1739141185.0611455,24.509976625442505,1.1451055013147813,1739141185.0611486,24.509976625442505,0.0,1739141185.061151,24.509976625442505,-0.10483550001808495,1739141185.0611532,24.509976625442505,0.49163581313802623,1739141185.0611558,24.509976625442505,1.2499410013328662 +1739141185.0814123,24.52997660636902,48.785056637175146,1739141185.0814195,24.52997660636902,1.1376407958308787,1739141185.0814264,24.52997660636902,49.12003909504482,1739141185.0814319,24.52997660636902,51.760650167554694,1739141185.0814333,24.52997660636902,4.9452797510137625,1739141185.0814354,24.52997660636902,0.9074505502097887,1739141185.0814369,24.52997660636902,1.951984895565977,1739141185.0814388,24.52997660636902,0.6108,1739141185.0814402,24.52997660636902,1.1451055013147813,1739141185.081442,24.52997660636902,0.0,1739141185.0814433,24.52997660636902,-0.10483550001808495,1739141185.0814445,24.52997660636902,0.49163581313802623,1739141185.081446,24.52997660636902,1.2499410013328662 +1739141185.1000488,24.549976587295532,48.785056637175146,1739141185.1000533,24.549976587295532,1.1376407958308787,1739141185.1000576,24.549976587295532,49.12003909504482,1739141185.100062,24.549976587295532,51.760650167554694,1739141185.1000645,24.549976587295532,4.9452797510137625,1739141185.100069,24.549976587295532,0.9074505502097887,1739141185.1000738,24.549976587295532,1.951984895565977,1739141185.1000779,24.549976587295532,0.6108,1739141185.1000824,24.549976587295532,1.1451055013147813,1739141185.1000857,24.549976587295532,0.0,1739141185.1000903,24.549976587295532,-0.10483550001808495,1739141185.100095,24.549976587295532,0.49163581313802623,1739141185.1000984,24.549976587295532,1.2499410013328662 +1739141185.1201384,24.569976568222046,48.785056637175146,1739141185.120142,24.569976568222046,1.1376407958308787,1739141185.1201456,24.569976568222046,49.12003909504482,1739141185.1201484,24.569976568222046,51.760650167554694,1739141185.1201499,24.569976568222046,4.9452797510137625,1739141185.1201515,24.569976568222046,0.9074505502097887,1739141185.1201532,24.569976568222046,1.951984895565977,1739141185.1201544,24.569976568222046,0.6108,1739141185.120156,24.569976568222046,1.1451055013147813,1739141185.1201577,24.569976568222046,0.0,1739141185.1201591,24.569976568222046,-0.10483550001808495,1739141185.1201608,24.569976568222046,0.49163581313802623,1739141185.120162,24.569976568222046,1.2499410013328662 +1739141185.1403217,24.58997654914856,48.785056637175146,1739141185.140327,24.58997654914856,1.1376407958308787,1739141185.140331,24.58997654914856,49.12003909504482,1739141185.140335,24.58997654914856,51.760650167554694,1739141185.1403368,24.58997654914856,4.9452797510137625,1739141185.1403394,24.58997654914856,0.9074505502097887,1739141185.1403415,24.58997654914856,1.951984895565977,1739141185.1403432,24.58997654914856,0.6108,1739141185.1403449,24.58997654914856,1.1451055013147813,1739141185.1403468,24.58997654914856,0.0,1739141185.1403491,24.58997654914856,-0.10483550001808495,1739141185.140351,24.58997654914856,0.49163581313802623,1739141185.1403525,24.58997654914856,1.2499410013328662 +1739141185.1604176,24.609976530075073,48.9048855119647,1739141185.1604214,24.609976530075073,1.203761085325608,1739141185.160425,24.609976530075073,49.29896624554111,1739141185.1604292,24.609976530075073,51.73562066456898,1739141185.1604314,24.609976530075073,5.085846875229825,1739141185.1604338,24.609976530075073,0.9407544125135346,1739141185.1604354,24.609976530075073,1.9652180635375935,1739141185.1604373,24.609976530075073,0.6108,1739141185.1604385,24.609976530075073,1.1390601658402744,1739141185.160441,24.609976530075073,0.0,1739141185.1604424,24.609976530075073,-0.09337933309780008,1739141185.1604443,24.609976530075073,0.5193601563846635,1739141185.1604457,24.609976530075073,1.2378948192443333 +1739141185.181391,24.629976511001587,48.9048855119647,1739141185.181395,24.629976511001587,1.203761085325608,1739141185.181399,24.629976511001587,49.29896624554111,1739141185.1814024,24.629976511001587,51.73562066456898,1739141185.181404,24.629976511001587,5.085846875229825,1739141185.1814065,24.629976511001587,0.9407544125135346,1739141185.181408,24.629976511001587,1.9652180635375935,1739141185.1814096,24.629976511001587,0.6108,1739141185.181411,24.629976511001587,1.1390601658402744,1739141185.1814132,24.629976511001587,0.0,1739141185.1814146,24.629976511001587,-0.09883465340405895,1739141185.1814165,24.629976511001587,0.5193601563846635,1739141185.181418,24.629976511001587,1.2378948192443333 +1739141185.2075782,24.6499764919281,48.9048855119647,1739141185.2075849,24.6499764919281,1.203761085325608,1739141185.2075925,24.6499764919281,49.29896624554111,1739141185.2075994,24.6499764919281,51.73562066456898,1739141185.2076027,24.6499764919281,5.085846875229825,1739141185.2076073,24.6499764919281,0.9407544125135346,1739141185.2076108,24.6499764919281,1.9652180635375935,1739141185.207614,24.6499764919281,0.6108,1739141185.2076173,24.6499764919281,1.1390601658402744,1739141185.2076213,24.6499764919281,0.0,1739141185.2076247,24.6499764919281,-0.09883465340405895,1739141185.207628,24.6499764919281,0.5193601563846635,1739141185.2076313,24.6499764919281,1.2378948192443333 +1739141185.222868,24.669976472854614,48.9048855119647,1739141185.222875,24.669976472854614,1.203761085325608,1739141185.222882,24.669976472854614,49.29896624554111,1739141185.2228894,24.669976472854614,51.73562066456898,1739141185.2228932,24.669976472854614,5.085846875229825,1739141185.2228982,24.669976472854614,0.9407544125135346,1739141185.2229023,24.669976472854614,1.9652180635375935,1739141185.222906,24.669976472854614,0.6108,1739141185.2229097,24.669976472854614,1.1390601658402744,1739141185.222914,24.669976472854614,0.0,1739141185.2229178,24.669976472854614,-0.09883465340405895,1739141185.2229214,24.669976472854614,0.5193601563846635,1739141185.222925,24.669976472854614,1.2378948192443333 +1739141185.2429569,24.689976453781128,48.9048855119647,1739141185.2429636,24.689976453781128,1.203761085325608,1739141185.2429707,24.689976453781128,49.29896624554111,1739141185.2429779,24.689976453781128,51.73562066456898,1739141185.2429817,24.689976453781128,5.085846875229825,1739141185.2429862,24.689976453781128,0.9407544125135346,1739141185.2429903,24.689976453781128,1.9652180635375935,1739141185.242994,24.689976453781128,0.6108,1739141185.2429976,24.689976453781128,1.1390601658402744,1739141185.2430022,24.689976453781128,0.0,1739141185.2430062,24.689976453781128,-0.09883465340405895,1739141185.24301,24.689976453781128,0.5193601563846635,1739141185.2430139,24.689976453781128,1.2378948192443333 +1739141185.2675169,24.70997643470764,49.02177112820831,1739141185.2675269,24.70997643470764,1.272551647226214,1739141185.2675374,24.70997643470764,49.476851920427954,1739141185.2675478,24.70997643470764,51.70623970821695,1739141185.2675533,24.70997643470764,5.228392391714483,1739141185.2675595,24.70997643470764,0.9745715556844267,1739141185.2675645,24.70997643470764,1.9820060363768792,1739141185.267569,24.70997643470764,0.6108,1739141185.2675738,24.70997643470764,1.131436786254803,1739141185.2675798,24.70997643470764,0.0,1739141185.2675848,24.70997643470764,-0.09282079301776376,1739141185.2675896,24.70997643470764,0.5470844996313009,1739141185.2675943,24.70997643470764,1.2271213237442251 +1739141185.2890334,24.7199764251709,49.02177112820831,1739141185.2890387,24.7199764251709,1.272551647226214,1739141185.289044,24.7199764251709,49.476851920427954,1739141185.2890491,24.7199764251709,51.70623970821695,1739141185.289052,24.7199764251709,5.228392391714483,1739141185.2890553,24.7199764251709,0.9745715556844267,1739141185.2890577,24.7199764251709,1.9820060363768792,1739141185.28906,24.7199764251709,0.6108,1739141185.2890625,24.7199764251709,1.131436786254803,1739141185.2890654,24.7199764251709,0.0,1739141185.2890682,24.7199764251709,-0.09568453748942218,1739141185.2890706,24.7199764251709,0.5470844996313009,1739141185.2890732,24.7199764251709,1.2271213237442251 +1739141185.3050725,24.74997639656067,49.02177112820831,1739141185.3050802,24.74997639656067,1.272551647226214,1739141185.3050914,24.74997639656067,49.476851920427954,1739141185.3051045,24.74997639656067,51.70623970821695,1739141185.3051074,24.74997639656067,5.228392391714483,1739141185.3051107,24.74997639656067,0.9745715556844267,1739141185.3051133,24.74997639656067,1.9820060363768792,1739141185.305116,24.74997639656067,0.6108,1739141185.3051186,24.74997639656067,1.131436786254803,1739141185.3051214,24.74997639656067,0.0,1739141185.305124,24.74997639656067,-0.09568453748942218,1739141185.3051264,24.74997639656067,0.5470844996313009,1739141185.305129,24.74997639656067,1.2271213237442251 +1739141185.325999,24.769976377487183,49.02177112820831,1739141185.3260043,24.769976377487183,1.272551647226214,1739141185.3260098,24.769976377487183,49.476851920427954,1739141185.3260152,24.769976377487183,51.70623970821695,1739141185.326018,24.769976377487183,5.228392391714483,1739141185.3260212,24.769976377487183,0.9745715556844267,1739141185.3260238,24.769976377487183,1.9820060363768792,1739141185.3260264,24.769976377487183,0.6108,1739141185.3260288,24.769976377487183,1.131436786254803,1739141185.3260322,24.769976377487183,0.0,1739141185.3260348,24.769976377487183,-0.09568453748942218,1739141185.3260372,24.769976377487183,0.5470844996313009,1739141185.3260398,24.769976377487183,1.2271213237442251 +1739141185.3439875,24.789976358413696,49.02177112820831,1739141185.3439908,24.789976358413696,1.272551647226214,1739141185.3439944,24.789976358413696,49.476851920427954,1739141185.343998,24.789976358413696,51.70623970821695,1739141185.3439999,24.789976358413696,5.228392391714483,1739141185.344002,24.789976358413696,0.9745715556844267,1739141185.344004,24.789976358413696,1.9820060363768792,1739141185.3440058,24.789976358413696,0.6108,1739141185.3440075,24.789976358413696,1.131436786254803,1739141185.3440096,24.789976358413696,0.0,1739141185.3440115,24.789976358413696,-0.09568453748942218,1739141185.3440132,24.789976358413696,0.5470844996313009,1739141185.3440151,24.789976358413696,1.2271213237442251 +1739141185.3638494,24.80997633934021,49.02177112820831,1739141185.3638523,24.80997633934021,1.272551647226214,1739141185.3638554,24.80997633934021,49.476851920427954,1739141185.3638587,24.80997633934021,51.70623970821695,1739141185.3638601,24.80997633934021,5.228392391714483,1739141185.363862,24.80997633934021,0.9745715556844267,1739141185.3638637,24.80997633934021,1.9820060363768792,1739141185.3638651,24.80997633934021,0.6108,1739141185.3638663,24.80997633934021,1.131436786254803,1739141185.3638682,24.80997633934021,0.0,1739141185.36387,24.80997633934021,-0.09568453748942218,1739141185.3638713,24.80997633934021,0.5470844996313009,1739141185.3638728,24.80997633934021,1.2271213237442251 +1739141185.3835163,24.829976320266724,49.135718266487345,1739141185.38352,24.829976320266724,1.343937896597713,1739141185.3835237,24.829976320266724,49.57160205481613,1739141185.3835266,24.829976320266724,51.69154445051463,1739141185.3835285,24.829976320266724,5.290216271206214,1739141185.3835304,24.829976320266724,0.9960715106867277,1739141185.3835323,24.829976320266724,1.922559448502077,1739141185.3835337,24.829976320266724,0.6108,1739141185.3835354,24.829976320266724,1.1586632297631942,1739141185.383537,24.829976320266724,0.0,1739141185.3835387,24.829976320266724,-0.02385057306496438,1739141185.3835404,24.829976320266724,0.5748088428779383,1739141185.3835418,24.829976320266724,1.2167204696418155 +1739141185.403275,24.849976301193237,49.135718266487345,1739141185.4032776,24.849976301193237,1.343937896597713,1739141185.403281,24.849976301193237,49.57160205481613,1739141185.4032836,24.849976301193237,51.69154445051463,1739141185.403285,24.849976301193237,5.290216271206214,1739141185.4032865,24.849976301193237,0.9960715106867277,1739141185.4032881,24.849976301193237,1.922559448502077,1739141185.403289,24.849976301193237,0.6108,1739141185.4032903,24.849976301193237,1.1586632297631942,1739141185.403292,24.849976301193237,0.0,1739141185.4032931,24.849976301193237,-0.058057239878621214,1739141185.4032946,24.849976301193237,0.5748088428779383,1739141185.4032958,24.849976301193237,1.2167204696418155 +1739141185.424445,24.86997628211975,49.135718266487345,1739141185.4244473,24.86997628211975,1.343937896597713,1739141185.4244502,24.86997628211975,49.57160205481613,1739141185.4244523,24.86997628211975,51.69154445051463,1739141185.4244537,24.86997628211975,5.290216271206214,1739141185.4244552,24.86997628211975,0.9960715106867277,1739141185.4244564,24.86997628211975,1.922559448502077,1739141185.4244576,24.86997628211975,0.6108,1739141185.4244587,24.86997628211975,1.1586632297631942,1739141185.4244606,24.86997628211975,0.0,1739141185.4244618,24.86997628211975,-0.058057239878621214,1739141185.424463,24.86997628211975,0.5748088428779383,1739141185.4244645,24.86997628211975,1.2167204696418155 +1739141185.4436183,24.889976263046265,49.135718266487345,1739141185.443621,24.889976263046265,1.343937896597713,1739141185.4436235,24.889976263046265,49.57160205481613,1739141185.443626,24.889976263046265,51.69154445051463,1739141185.4436274,24.889976263046265,5.290216271206214,1739141185.443629,24.889976263046265,0.9960715106867277,1739141185.4436302,24.889976263046265,1.922559448502077,1739141185.4436314,24.889976263046265,0.6108,1739141185.4436326,24.889976263046265,1.1586632297631942,1739141185.4436345,24.889976263046265,0.0,1739141185.4436357,24.889976263046265,-0.058057239878621214,1739141185.443637,24.889976263046265,0.5748088428779383,1739141185.4436383,24.889976263046265,1.2167204696418155 +1739141185.4633818,24.90997624397278,49.135718266487345,1739141185.4633844,24.90997624397278,1.343937896597713,1739141185.4633873,24.90997624397278,49.57160205481613,1739141185.4633899,24.90997624397278,51.69154445051463,1739141185.4633915,24.90997624397278,5.290216271206214,1739141185.463393,24.90997624397278,0.9960715106867277,1739141185.4633946,24.90997624397278,1.922559448502077,1739141185.4633958,24.90997624397278,0.6108,1739141185.463397,24.90997624397278,1.1586632297631942,1739141185.4633987,24.90997624397278,0.0,1739141185.4634001,24.90997624397278,-0.058057239878621214,1739141185.4634018,24.90997624397278,0.5748088428779383,1739141185.463403,24.90997624397278,1.2167204696418155 +1739141185.484008,24.929976224899292,49.24687295098099,1739141185.484012,24.929976224899292,1.4179442756856284,1739141185.484016,24.929976224899292,49.76177370918807,1739141185.4840202,24.929976224899292,51.648093519790095,1739141185.4840224,24.929976224899292,5.4566570941029875,1739141185.4840248,24.929976224899292,1.0343931097922194,1739141185.484027,24.929976224899292,1.9666590217169657,1739141185.4840288,24.929976224899292,0.6108,1739141185.4840307,24.929976224899292,1.1384038197867823,1739141185.4840333,24.929976224899292,0.0,1739141185.4840353,24.929976224899292,-0.08518697657316379,1739141185.4840374,24.929976224899292,0.6025331861245757,1739141185.4840393,24.929976224899292,1.2106718676708803 +1739141185.5045264,24.949976205825806,49.24687295098099,1739141185.5045307,24.949976205825806,1.4179442756856284,1739141185.504536,24.949976205825806,49.76177370918807,1739141185.5045407,24.949976205825806,51.648093519790095,1739141185.504543,24.949976205825806,5.4566570941029875,1739141185.5045457,24.949976205825806,1.0343931097922194,1739141185.5045483,24.949976205825806,1.9666590217169657,1739141185.5045505,24.949976205825806,0.6108,1739141185.5045526,24.949976205825806,1.1384038197867823,1739141185.5045552,24.949976205825806,0.0,1739141185.504558,24.949976205825806,-0.07226804788409802,1739141185.5045607,24.949976205825806,0.6025331861245757,1739141185.5045626,24.949976205825806,1.2106718676708803 +1739141185.5259843,24.96997618675232,49.24687295098099,1739141185.5259883,24.96997618675232,1.4179442756856284,1739141185.5259936,24.96997618675232,49.76177370918807,1739141185.5259979,24.96997618675232,51.648093519790095,1739141185.5259998,24.96997618675232,5.4566570941029875,1739141185.526003,24.96997618675232,1.0343931097922194,1739141185.5260053,24.96997618675232,1.9666590217169657,1739141185.5260077,24.96997618675232,0.6108,1739141185.5260096,24.96997618675232,1.1384038197867823,1739141185.5260122,24.96997618675232,0.0,1739141185.5260148,24.96997618675232,-0.07226804788409802,1739141185.526017,24.96997618675232,0.6025331861245757,1739141185.5260193,24.96997618675232,1.2106718676708803 +1739141185.5446317,24.989976167678833,49.24687295098099,1739141185.5446362,24.989976167678833,1.4179442756856284,1739141185.544641,24.989976167678833,49.76177370918807,1739141185.5446458,24.989976167678833,51.648093519790095,1739141185.5446482,24.989976167678833,5.4566570941029875,1739141185.544651,24.989976167678833,1.0343931097922194,1739141185.5446534,24.989976167678833,1.9666590217169657,1739141185.5446556,24.989976167678833,0.6108,1739141185.5446577,24.989976167678833,1.1384038197867823,1739141185.5446606,24.989976167678833,0.0,1739141185.544663,24.989976167678833,-0.07226804788409802,1739141185.5446653,24.989976167678833,0.6025331861245757,1739141185.5446677,24.989976167678833,1.2106718676708803 +1739141185.5654502,25.009976148605347,49.24687295098099,1739141185.565455,25.009976148605347,1.4179442756856284,1739141185.5654597,25.009976148605347,49.76177370918807,1739141185.5654643,25.009976148605347,51.648093519790095,1739141185.5654666,25.009976148605347,5.4566570941029875,1739141185.5654697,25.009976148605347,1.0343931097922194,1739141185.565472,25.009976148605347,1.9666590217169657,1739141185.5654743,25.009976148605347,0.6108,1739141185.5654764,25.009976148605347,1.1384038197867823,1739141185.5654793,25.009976148605347,0.0,1739141185.5654814,25.009976148605347,-0.07226804788409802,1739141185.5654838,25.009976148605347,0.6025331861245757,1739141185.5654862,25.009976148605347,1.2106718676708803 +1739141185.5850422,25.02997612953186,49.24687295098099,1739141185.5850465,25.02997612953186,1.4179442756856284,1739141185.5850515,25.02997612953186,49.76177370918807,1739141185.5850563,25.02997612953186,51.648093519790095,1739141185.5850585,25.02997612953186,5.4566570941029875,1739141185.5850613,25.02997612953186,1.0343931097922194,1739141185.585064,25.02997612953186,1.9666590217169657,1739141185.585066,25.02997612953186,0.6108,1739141185.585068,25.02997612953186,1.1384038197867823,1739141185.5850708,25.02997612953186,0.0,1739141185.5850732,25.02997612953186,-0.07226804788409802,1739141185.5850754,25.02997612953186,0.6025331861245757,1739141185.5850778,25.02997612953186,1.2106718676708803 +1739141185.6052644,25.049976110458374,49.355289331850365,1739141185.6052673,25.049976110458374,1.4945477151246331,1739141185.6052704,25.049976110458374,49.9152904953983,1739141185.605273,25.049976110458374,51.610400071157066,1739141185.6052747,25.049976110458374,5.579999775293469,1739141185.6052763,25.049976110458374,1.0664299350587927,1739141185.605278,25.049976110458374,1.9714817913506204,1739141185.6052792,25.049976110458374,0.6108,1739141185.6052804,25.049976110458374,1.1362098329366543,1739141185.605282,25.049976110458374,0.0,1739141185.6052835,25.049976110458374,-0.06084661844023812,1739141185.605285,25.049976110458374,0.6302575293712132,1739141185.6052864,25.049976110458374,1.2024952300194476 +1739141185.6233249,25.069976091384888,49.355289331850365,1739141185.6233275,25.069976091384888,1.4945477151246331,1739141185.62333,25.069976091384888,49.9152904953983,1739141185.623333,25.069976091384888,51.610400071157066,1739141185.6233342,25.069976091384888,5.579999775293469,1739141185.6233356,25.069976091384888,1.0664299350587927,1739141185.6233373,25.069976091384888,1.9714817913506204,1739141185.6233382,25.069976091384888,0.6108,1739141185.6233394,25.069976091384888,1.1362098329366543,1739141185.623341,25.069976091384888,0.0,1739141185.6233425,25.069976091384888,-0.06628539708279324,1739141185.623344,25.069976091384888,0.6302575293712132,1739141185.6233451,25.069976091384888,1.2024952300194476 +1739141185.6436214,25.0899760723114,49.355289331850365,1739141185.6436236,25.0899760723114,1.4945477151246331,1739141185.6436265,25.0899760723114,49.9152904953983,1739141185.6436293,25.0899760723114,51.610400071157066,1739141185.6436305,25.0899760723114,5.579999775293469,1739141185.6436322,25.0899760723114,1.0664299350587927,1739141185.6436334,25.0899760723114,1.9714817913506204,1739141185.6436348,25.0899760723114,0.6108,1739141185.643636,25.0899760723114,1.1362098329366543,1739141185.6436372,25.0899760723114,0.0,1739141185.6436388,25.0899760723114,-0.06628539708279324,1739141185.64364,25.0899760723114,0.6302575293712132,1739141185.6436412,25.0899760723114,1.2024952300194476 +1739141185.663512,25.109976053237915,49.355289331850365,1739141185.6635146,25.109976053237915,1.4945477151246331,1739141185.6635175,25.109976053237915,49.9152904953983,1739141185.6635203,25.109976053237915,51.610400071157066,1739141185.6635215,25.109976053237915,5.579999775293469,1739141185.663523,25.109976053237915,1.0664299350587927,1739141185.6635244,25.109976053237915,1.9714817913506204,1739141185.6635258,25.109976053237915,0.6108,1739141185.663527,25.109976053237915,1.1362098329366543,1739141185.6635284,25.109976053237915,0.0,1739141185.6635299,25.109976053237915,-0.06628539708279324,1739141185.663531,25.109976053237915,0.6302575293712132,1739141185.6635323,25.109976053237915,1.2024952300194476 +1739141185.6833453,25.12997603416443,49.355289331850365,1739141185.6833477,25.12997603416443,1.4945477151246331,1739141185.6833506,25.12997603416443,49.9152904953983,1739141185.6833532,25.12997603416443,51.610400071157066,1739141185.6833544,25.12997603416443,5.579999775293469,1739141185.683356,25.12997603416443,1.0664299350587927,1739141185.6833577,25.12997603416443,1.9714817913506204,1739141185.6833587,25.12997603416443,0.6108,1739141185.68336,25.12997603416443,1.1362098329366543,1739141185.6833615,25.12997603416443,0.0,1739141185.6833627,25.12997603416443,-0.06628539708279324,1739141185.6833642,25.12997603416443,0.6302575293712132,1739141185.6833656,25.12997603416443,1.2024952300194476 +1739141185.7037947,25.149976015090942,49.46086948420948,1739141185.703797,25.149976015090942,1.5736247743600176,1739141185.7037997,25.149976015090942,50.03970278011035,1739141185.7038023,25.149976015090942,51.57782483934115,1739141185.7038035,25.149976015090942,5.677476272880534,1739141185.7038052,25.149976015090942,1.09455243338843,1739141185.7038064,25.149976015090942,1.9525187997403217,1739141185.7038076,25.149976015090942,0.6108,1739141185.7038088,25.149976015090942,1.1448609767833575,1739141185.7038102,25.149976015090942,0.0,1739141185.7038121,25.149976015090942,-0.036005496883609704,1739141185.703813,25.149976015090942,0.6579818726178506,1739141185.7038145,25.149976015090942,1.1952854809647406 +1739141185.7232904,25.169975996017456,49.46086948420948,1739141185.7232928,25.169975996017456,1.5736247743600176,1739141185.7232957,25.169975996017456,50.03970278011035,1739141185.7232983,25.169975996017456,51.57782483934115,1739141185.7232995,25.169975996017456,5.677476272880534,1739141185.7233012,25.169975996017456,1.09455243338843,1739141185.7233024,25.169975996017456,1.9525187997403217,1739141185.7233038,25.169975996017456,0.6108,1739141185.723305,25.169975996017456,1.1448609767833575,1739141185.7233064,25.169975996017456,0.0,1739141185.723308,25.169975996017456,-0.05042450418138311,1739141185.7233093,25.169975996017456,0.6579818726178506,1739141185.7233107,25.169975996017456,1.1952854809647406 +1739141185.7435176,25.18997597694397,49.46086948420948,1739141185.74352,25.18997597694397,1.5736247743600176,1739141185.7435226,25.18997597694397,50.03970278011035,1739141185.7435253,25.18997597694397,51.57782483934115,1739141185.7435267,25.18997597694397,5.677476272880534,1739141185.7435281,25.18997597694397,1.09455243338843,1739141185.7435296,25.18997597694397,1.9525187997403217,1739141185.7435308,25.18997597694397,0.6108,1739141185.7435317,25.18997597694397,1.1448609767833575,1739141185.7435336,25.18997597694397,0.0,1739141185.7435348,25.18997597694397,-0.05042450418138311,1739141185.7435362,25.18997597694397,0.6579818726178506,1739141185.7435374,25.18997597694397,1.1952854809647406 +1739141185.7636628,25.209975957870483,49.46086948420948,1739141185.7636654,25.209975957870483,1.5736247743600176,1739141185.7636685,25.209975957870483,50.03970278011035,1739141185.763671,25.209975957870483,51.57782483934115,1739141185.7636724,25.209975957870483,5.677476272880534,1739141185.7636738,25.209975957870483,1.09455243338843,1739141185.7636752,25.209975957870483,1.9525187997403217,1739141185.7636764,25.209975957870483,0.6108,1739141185.7636776,25.209975957870483,1.1448609767833575,1739141185.763679,25.209975957870483,0.0,1739141185.7636805,25.209975957870483,-0.05042450418138311,1739141185.7636817,25.209975957870483,0.6579818726178506,1739141185.7636828,25.209975957870483,1.1952854809647406 +1739141185.7832675,25.229975938796997,49.46086948420948,1739141185.78327,25.229975938796997,1.5736247743600176,1739141185.783273,25.229975938796997,50.03970278011035,1739141185.7832754,25.229975938796997,51.57782483934115,1739141185.7832766,25.229975938796997,5.677476272880534,1739141185.783278,25.229975938796997,1.09455243338843,1739141185.7832797,25.229975938796997,1.9525187997403217,1739141185.7832808,25.229975938796997,0.6108,1739141185.7832818,25.229975938796997,1.1448609767833575,1739141185.7832835,25.229975938796997,0.0,1739141185.783285,25.229975938796997,-0.05042450418138311,1739141185.7832863,25.229975938796997,0.6579818726178506,1739141185.7832875,25.229975938796997,1.1952854809647406 +1739141185.8034365,25.24997591972351,49.46086948420948,1739141185.8034391,25.24997591972351,1.5736247743600176,1739141185.803442,25.24997591972351,50.03970278011035,1739141185.8034444,25.24997591972351,51.57782483934115,1739141185.8034458,25.24997591972351,5.677476272880534,1739141185.8034472,25.24997591972351,1.09455243338843,1739141185.8034487,25.24997591972351,1.9525187997403217,1739141185.8034499,25.24997591972351,0.6108,1739141185.803451,25.24997591972351,1.1448609767833575,1739141185.8034527,25.24997591972351,0.0,1739141185.8034542,25.24997591972351,-0.05042450418138311,1739141185.8034558,25.24997591972351,0.6579818726178506,1739141185.803457,25.24997591972351,1.1952854809647406 +1739141185.8235066,25.269975900650024,49.563681934780504,1739141185.8235087,25.269975900650024,1.655174402090081,1739141185.8235116,25.269975900650024,50.24981262364905,1739141185.8235142,25.269975900650024,51.50905702891937,1739141185.8235154,25.269975900650024,5.859276117784699,1739141185.8235168,25.269975900650024,1.1374045279321527,1739141185.8235183,25.269975900650024,2.022007272924161,1739141185.8235195,25.269975900650024,0.6108,1739141185.8235211,25.269975900650024,1.1134773015218353,1739141185.8235228,25.269975900650024,0.0,1739141185.823524,25.269975900650024,-0.10033538836165004,1739141185.8235254,25.269975900650024,0.685706215864488,1739141185.8235266,25.269975900650024,1.1900455903058917 +1739141185.8433414,25.289975881576538,49.563681934780504,1739141185.8433437,25.289975881576538,1.655174402090081,1739141185.843346,25.289975881576538,50.24981262364905,1739141185.843349,25.289975881576538,51.50905702891937,1739141185.8433502,25.289975881576538,5.859276117784699,1739141185.8433518,25.289975881576538,1.1374045279321527,1739141185.843353,25.289975881576538,2.022007272924161,1739141185.8433545,25.289975881576538,0.6108,1739141185.8433554,25.289975881576538,1.1134773015218353,1739141185.8433568,25.289975881576538,0.0,1739141185.8433583,25.289975881576538,-0.07656828878405642,1739141185.8433595,25.289975881576538,0.685706215864488,1739141185.8433607,25.289975881576538,1.1900455903058917 +1739141185.8633602,25.30997586250305,49.563681934780504,1739141185.8633626,25.30997586250305,1.655174402090081,1739141185.8633657,25.30997586250305,50.24981262364905,1739141185.8633685,25.30997586250305,51.50905702891937,1739141185.86337,25.30997586250305,5.859276117784699,1739141185.8633718,25.30997586250305,1.1374045279321527,1739141185.863373,25.30997586250305,2.022007272924161,1739141185.8633747,25.30997586250305,0.6108,1739141185.8633757,25.30997586250305,1.1134773015218353,1739141185.863377,25.30997586250305,0.0,1739141185.8633788,25.30997586250305,-0.07656828878405642,1739141185.86338,25.30997586250305,0.685706215864488,1739141185.863381,25.30997586250305,1.1900455903058917 +1739141185.8907084,25.329975843429565,49.563681934780504,1739141185.8907173,25.329975843429565,1.655174402090081,1739141185.8907275,25.329975843429565,50.24981262364905,1739141185.8907368,25.329975843429565,51.50905702891937,1739141185.8907418,25.329975843429565,5.859276117784699,1739141185.8907473,25.329975843429565,1.1374045279321527,1739141185.8907523,25.329975843429565,2.022007272924161,1739141185.8907568,25.329975843429565,0.6108,1739141185.8907611,25.329975843429565,1.1134773015218353,1739141185.890767,25.329975843429565,0.0,1739141185.8907723,25.329975843429565,-0.07656828878405642,1739141185.8907766,25.329975843429565,0.685706215864488,1739141185.8907812,25.329975843429565,1.1900455903058917 +1739141185.9162006,25.34997582435608,49.563681934780504,1739141185.9162097,25.34997582435608,1.655174402090081,1739141185.9162195,25.34997582435608,50.24981262364905,1739141185.9162288,25.34997582435608,51.50905702891937,1739141185.9162338,25.34997582435608,5.859276117784699,1739141185.9162395,25.34997582435608,1.1374045279321527,1739141185.9162445,25.34997582435608,2.022007272924161,1739141185.916249,25.34997582435608,0.6108,1739141185.9162533,25.34997582435608,1.1134773015218353,1739141185.9162593,25.34997582435608,0.0,1739141185.9162643,25.34997582435608,-0.07656828878405642,1739141185.9162688,25.34997582435608,0.685706215864488,1739141185.9162734,25.34997582435608,1.1900455903058917 +1739141185.9369566,25.37997579574585,49.66361193930969,1739141185.936968,25.37997579574585,1.7390528082378767,1739141185.9369798,25.37997579574585,50.41298201586383,1739141185.9369934,25.37997579574585,51.45809587168628,1739141185.9370005,25.37997579574585,5.9868325685009225,1739141185.9370103,25.37997579574585,1.171085661067066,1739141185.9370184,25.37997579574585,2.0374697245439677,1739141185.937026,25.37997579574585,0.6108,1739141185.9370341,25.37997579574585,1.1066117195920169,1739141185.9370432,25.37997579574585,0.0,1739141185.9370506,25.37997579574585,-0.07325609969297286,1739141185.9370582,25.37997579574585,0.7134305591111254,1739141185.9370663,25.37997579574585,1.1814450529734029 +1739141185.9543,25.399975776672363,49.66361193930969,1739141185.9543061,25.399975776672363,1.7390528082378767,1739141185.954313,25.399975776672363,50.41298201586383,1739141185.9543204,25.399975776672363,51.45809587168628,1739141185.9543247,25.399975776672363,5.9868325685009225,1739141185.9543304,25.399975776672363,1.171085661067066,1739141185.9543352,25.399975776672363,2.0374697245439677,1739141185.9543395,25.399975776672363,0.6108,1739141185.9543438,25.399975776672363,1.1066117195920169,1739141185.954348,25.399975776672363,0.0,1739141185.9543526,25.399975776672363,-0.07483333338138598,1739141185.9543574,25.399975776672363,0.7134305591111254,1739141185.954362,25.399975776672363,1.1814450529734029 +1739141185.9830456,25.419975757598877,49.66361193930969,1739141185.9830503,25.419975757598877,1.7390528082378767,1739141185.9830549,25.419975757598877,50.41298201586383,1739141185.9830596,25.419975757598877,51.45809587168628,1739141185.9830618,25.419975757598877,5.9868325685009225,1739141185.9830644,25.419975757598877,1.171085661067066,1739141185.9830666,25.419975757598877,2.0374697245439677,1739141185.9830685,25.419975757598877,0.6108,1739141185.9830704,25.419975757598877,1.1066117195920169,1739141185.9830725,25.419975757598877,0.0,1739141185.9830751,25.419975757598877,-0.07483333338138598,1739141185.9830768,25.419975757598877,0.7134305591111254,1739141185.983079,25.419975757598877,1.1814450529734029 +1739141185.9940937,25.43997573852539,49.66361193930969,1739141185.9940982,25.43997573852539,1.7390528082378767,1739141185.994103,25.43997573852539,50.41298201586383,1739141185.994109,25.43997573852539,51.45809587168628,1739141185.994112,25.43997573852539,5.9868325685009225,1739141185.9941156,25.43997573852539,1.171085661067066,1739141185.994119,25.43997573852539,2.0374697245439677,1739141185.9941223,25.43997573852539,0.6108,1739141185.9941251,25.43997573852539,1.1066117195920169,1739141185.9941285,25.43997573852539,0.0,1739141185.994132,25.43997573852539,-0.07483333338138598,1739141185.9941354,25.43997573852539,0.7134305591111254,1739141185.9941387,25.43997573852539,1.1814450529734029 +1739141186.0137901,25.459975719451904,49.66361193930969,1739141186.0137935,25.459975719451904,1.7390528082378767,1739141186.0137966,25.459975719451904,50.41298201586383,1739141186.0137992,25.459975719451904,51.45809587168628,1739141186.0138009,25.459975719451904,5.9868325685009225,1739141186.0138025,25.459975719451904,1.171085661067066,1739141186.013804,25.459975719451904,2.0374697245439677,1739141186.0138054,25.459975719451904,0.6108,1739141186.0138066,25.459975719451904,1.1066117195920169,1739141186.013808,25.459975719451904,0.0,1739141186.01381,25.459975719451904,-0.07483333338138598,1739141186.013811,25.459975719451904,0.7134305591111254,1739141186.0138125,25.459975719451904,1.1814450529734029 +1739141186.0318632,25.479975700378418,49.76048946744016,1739141186.031866,25.479975700378418,1.825057713524724,1739141186.0318687,25.479975700378418,50.572625656144545,1739141186.0318713,25.479975700378418,51.40487815254734,1739141186.0318725,25.479975700378418,6.110996110582168,1739141186.0318744,25.479975700378418,1.2044457612419597,1739141186.0318756,25.479975700378418,2.0514979189016174,1739141186.0318768,25.479975700378418,0.6108,1739141186.031878,25.479975700378418,1.1004196029700517,1739141186.0318794,25.479975700378418,0.0,1739141186.0318813,25.479975700378418,-0.07103631248775577,1739141186.0318825,25.479975700378418,0.7411549023577628,1739141186.0318835,25.479975700378418,1.1732640215484784 +1739141186.0516405,25.49997568130493,49.76048946744016,1739141186.0516434,25.49997568130493,1.825057713524724,1739141186.0516467,25.49997568130493,50.572625656144545,1739141186.0516498,25.49997568130493,51.40487815254734,1739141186.051651,25.49997568130493,6.110996110582168,1739141186.0516527,25.49997568130493,1.2044457612419597,1739141186.0516543,25.49997568130493,2.0514979189016174,1739141186.051656,25.49997568130493,0.6108,1739141186.0516572,25.49997568130493,1.1004196029700517,1739141186.051659,25.49997568130493,0.0,1739141186.0516603,25.49997568130493,-0.07284441857842672,1739141186.051662,25.49997568130493,0.7411549023577628,1739141186.0516634,25.49997568130493,1.1732640215484784 +1739141186.0711102,25.519975662231445,49.76048946744016,1739141186.0711124,25.519975662231445,1.825057713524724,1739141186.0711153,25.519975662231445,50.572625656144545,1739141186.071118,25.519975662231445,51.40487815254734,1739141186.0711193,25.519975662231445,6.110996110582168,1739141186.0711212,25.519975662231445,1.2044457612419597,1739141186.0711224,25.519975662231445,2.0514979189016174,1739141186.0711236,25.519975662231445,0.6108,1739141186.071125,25.519975662231445,1.1004196029700517,1739141186.0711267,25.519975662231445,0.0,1739141186.0711281,25.519975662231445,-0.07284441857842672,1739141186.0711296,25.519975662231445,0.7411549023577628,1739141186.071131,25.519975662231445,1.1732640215484784 +1739141186.0909204,25.53997564315796,49.76048946744016,1739141186.0909228,25.53997564315796,1.825057713524724,1739141186.0909252,25.53997564315796,50.572625656144545,1739141186.0909283,25.53997564315796,51.40487815254734,1739141186.0909297,25.53997564315796,6.110996110582168,1739141186.0909312,25.53997564315796,1.2044457612419597,1739141186.0909324,25.53997564315796,2.0514979189016174,1739141186.0909338,25.53997564315796,0.6108,1739141186.0909348,25.53997564315796,1.1004196029700517,1739141186.0909364,25.53997564315796,0.0,1739141186.0909379,25.53997564315796,-0.07284441857842672,1739141186.0909388,25.53997564315796,0.7411549023577628,1739141186.0909402,25.53997564315796,1.1732640215484784 +1739141186.1109593,25.559975624084473,49.76048946744016,1739141186.1109622,25.559975624084473,1.825057713524724,1739141186.1109648,25.559975624084473,50.572625656144545,1739141186.1109676,25.559975624084473,51.40487815254734,1739141186.1109686,25.559975624084473,6.110996110582168,1739141186.1109703,25.559975624084473,1.2044457612419597,1739141186.1109717,25.559975624084473,2.0514979189016174,1739141186.110973,25.559975624084473,0.6108,1739141186.1109743,25.559975624084473,1.1004196029700517,1739141186.1109757,25.559975624084473,0.0,1739141186.110977,25.559975624084473,-0.07284441857842672,1739141186.1109784,25.559975624084473,0.7411549023577628,1739141186.1109793,25.559975624084473,1.1732640215484784 +1739141186.1313562,25.579975605010986,49.76048946744016,1739141186.1313584,25.579975605010986,1.825057713524724,1739141186.131361,25.579975605010986,50.572625656144545,1739141186.1313636,25.579975605010986,51.40487815254734,1739141186.1313648,25.579975605010986,6.110996110582168,1739141186.1313665,25.579975605010986,1.2044457612419597,1739141186.1313677,25.579975605010986,2.0514979189016174,1739141186.1313689,25.579975605010986,0.6108,1739141186.13137,25.579975605010986,1.1004196029700517,1739141186.1313715,25.579975605010986,0.0,1739141186.1313727,25.579975605010986,-0.07284441857842672,1739141186.1313741,25.579975605010986,0.7411549023577628,1739141186.1313753,25.579975605010986,1.1732640215484784 +1739141186.1514091,25.5999755859375,49.85429878223266,1739141186.1514118,25.5999755859375,1.9131079964031592,1739141186.151414,25.5999755859375,50.574631870750835,1739141186.1514165,25.5999755859375,51.41382984265868,1739141186.151418,25.5999755859375,6.091078600084438,1739141186.1514194,25.5999755859375,1.2135390348721178,1739141186.1514206,25.5999755859375,1.9182783836014452,1739141186.151422,25.5999755859375,0.6108,1739141186.151423,25.5999755859375,1.160649054560729,1739141186.1514244,25.5999755859375,0.0,1739141186.1514258,25.5999755859375,0.05731188119981301,1739141186.151427,25.5999755859375,0.7688792456044002,1739141186.151428,25.5999755859375,1.1653163946928353 +1739141186.1709545,25.619975566864014,49.85429878223266,1739141186.170957,25.619975566864014,1.9131079964031592,1739141186.1709597,25.619975566864014,50.574631870750835,1739141186.1709623,25.619975566864014,51.41382984265868,1739141186.1709635,25.619975566864014,6.091078600084438,1739141186.170965,25.619975566864014,1.2135390348721178,1739141186.1709666,25.619975566864014,1.9182783836014452,1739141186.1709678,25.619975566864014,0.6108,1739141186.1709688,25.619975566864014,1.160649054560729,1739141186.1709704,25.619975566864014,0.0,1739141186.1709719,25.619975566864014,-0.004667340132106235,1739141186.1709728,25.619975566864014,0.7688792456044002,1739141186.1709743,25.619975566864014,1.1653163946928353 +1739141186.1909556,25.639975547790527,49.85429878223266,1739141186.190958,25.639975547790527,1.9131079964031592,1739141186.190961,25.639975547790527,50.574631870750835,1739141186.1909637,25.639975547790527,51.41382984265868,1739141186.190965,25.639975547790527,6.091078600084438,1739141186.1909668,25.639975547790527,1.2135390348721178,1739141186.190968,25.639975547790527,1.9182783836014452,1739141186.1909692,25.639975547790527,0.6108,1739141186.1909707,25.639975547790527,1.160649054560729,1739141186.1909723,25.639975547790527,0.0,1739141186.190974,25.639975547790527,-0.004667340132106235,1739141186.1909752,25.639975547790527,0.7688792456044002,1739141186.1909769,25.639975547790527,1.1653163946928353 +1739141186.211801,25.65997552871704,49.85429878223266,1739141186.211805,25.65997552871704,1.9131079964031592,1739141186.2118094,25.65997552871704,50.574631870750835,1739141186.2118132,25.65997552871704,51.41382984265868,1739141186.211815,25.65997552871704,6.091078600084438,1739141186.2118177,25.65997552871704,1.2135390348721178,1739141186.21182,25.65997552871704,1.9182783836014452,1739141186.2118216,25.65997552871704,0.6108,1739141186.2118235,25.65997552871704,1.160649054560729,1739141186.2118256,25.65997552871704,0.0,1739141186.2118278,25.65997552871704,-0.004667340132106235,1739141186.2118294,25.65997552871704,0.7688792456044002,1739141186.2118313,25.65997552871704,1.1653163946928353 +1739141186.232695,25.679975509643555,49.85429878223266,1739141186.2326992,25.679975509643555,1.9131079964031592,1739141186.2327037,25.679975509643555,50.574631870750835,1739141186.232708,25.679975509643555,51.41382984265868,1739141186.2327104,25.679975509643555,6.091078600084438,1739141186.2327132,25.679975509643555,1.2135390348721178,1739141186.2327156,25.679975509643555,1.9182783836014452,1739141186.2327175,25.679975509643555,0.6108,1739141186.2327197,25.679975509643555,1.160649054560729,1739141186.2327223,25.679975509643555,0.0,1739141186.2327244,25.679975509643555,-0.004667340132106235,1739141186.2327266,25.679975509643555,0.7688792456044002,1739141186.2327285,25.679975509643555,1.1653163946928353 +1739141186.252412,25.69997549057007,49.94529907477361,1739141186.2524173,25.69997549057007,2.003398340121839,1739141186.2524223,25.69997549057007,50.8848105721787,1739141186.252427,25.69997549057007,51.27568156974936,1739141186.252429,25.69997549057007,6.368852446366588,1739141186.2524319,25.69997549057007,1.2749852806267525,1739141186.2524343,25.69997549057007,2.100855352653662,1739141186.2524364,25.69997549057007,0.6108,1739141186.2524385,25.69997549057007,1.078907106993982,1739141186.2524414,25.69997549057007,0.0,1739141186.2524436,25.69997549057007,-0.16081443812886992,1739141186.252446,25.69997549057007,0.7966035888510377,1739141186.2524483,25.69997549057007,1.1653657470280423 +1739141186.2722206,25.719975471496582,49.94529907477361,1739141186.2722244,25.719975471496582,2.003398340121839,1739141186.2722292,25.719975471496582,50.8848105721787,1739141186.2722335,25.719975471496582,51.27568156974936,1739141186.2722359,25.719975471496582,6.368852446366588,1739141186.2722383,25.719975471496582,1.2749852806267525,1739141186.2722406,25.719975471496582,2.100855352653662,1739141186.2722428,25.719975471496582,0.6108,1739141186.2722447,25.719975471496582,1.078907106993982,1739141186.2722473,25.719975471496582,0.0,1739141186.2722497,25.719975471496582,-0.08645864003406034,1739141186.2722516,25.719975471496582,0.7966035888510377,1739141186.272254,25.719975471496582,1.1653657470280423 +1739141186.2914584,25.739975452423096,49.94529907477361,1739141186.2914622,25.739975452423096,2.003398340121839,1739141186.2914655,25.739975452423096,50.8848105721787,1739141186.2914689,25.739975452423096,51.27568156974936,1739141186.2914703,25.739975452423096,6.368852446366588,1739141186.2914724,25.739975452423096,1.2749852806267525,1739141186.2914739,25.739975452423096,2.100855352653662,1739141186.2914755,25.739975452423096,0.6108,1739141186.291477,25.739975452423096,1.078907106993982,1739141186.291479,25.739975452423096,0.0,1739141186.2914808,25.739975452423096,-0.08645864003406034,1739141186.2914824,25.739975452423096,0.7966035888510377,1739141186.2914839,25.739975452423096,1.1653657470280423 +1739141186.3114948,25.75997543334961,49.94529907477361,1739141186.3115003,25.75997543334961,2.003398340121839,1739141186.311505,25.75997543334961,50.8848105721787,1739141186.311517,25.75997543334961,51.27568156974936,1739141186.31152,25.75997543334961,6.368852446366588,1739141186.3115222,25.75997543334961,1.2749852806267525,1739141186.311525,25.75997543334961,2.100855352653662,1739141186.3115327,25.75997543334961,0.6108,1739141186.3115351,25.75997543334961,1.078907106993982,1739141186.3115385,25.75997543334961,0.0,1739141186.3115418,25.75997543334961,-0.08645864003406034,1739141186.3115435,25.75997543334961,0.7966035888510377,1739141186.3115454,25.75997543334961,1.1653657470280423 +1739141186.3319316,25.779975414276123,49.94529907477361,1739141186.331935,25.779975414276123,2.003398340121839,1739141186.3319385,25.779975414276123,50.8848105721787,1739141186.3319416,25.779975414276123,51.27568156974936,1739141186.3319433,25.779975414276123,6.368852446366588,1739141186.3319452,25.779975414276123,1.2749852806267525,1739141186.3319468,25.779975414276123,2.100855352653662,1739141186.3319483,25.779975414276123,0.6108,1739141186.3319495,25.779975414276123,1.078907106993982,1739141186.3319516,25.779975414276123,0.0,1739141186.3319535,25.779975414276123,-0.08645864003406034,1739141186.331955,25.779975414276123,0.7966035888510377,1739141186.3319564,25.779975414276123,1.1653657470280423 +1739141186.3511198,25.799975395202637,49.94529907477361,1739141186.3511226,25.799975395202637,2.003398340121839,1739141186.3511262,25.799975395202637,50.8848105721787,1739141186.3511295,25.799975395202637,51.27568156974936,1739141186.3511314,25.799975395202637,6.368852446366588,1739141186.3511333,25.799975395202637,1.2749852806267525,1739141186.351135,25.799975395202637,2.100855352653662,1739141186.3511367,25.799975395202637,0.6108,1739141186.3511384,25.799975395202637,1.078907106993982,1739141186.35114,25.799975395202637,0.0,1739141186.351142,25.799975395202637,-0.08645864003406034,1739141186.3511434,25.799975395202637,0.7966035888510377,1739141186.351145,25.799975395202637,1.1653657470280423 +1739141186.371546,25.81997537612915,50.03333427955685,1739141186.3715494,25.81997537612915,2.095724545652309,1739141186.371553,25.81997537612915,51.033079922397214,1739141186.3715563,25.81997537612915,51.21854387173137,1739141186.371558,25.81997537612915,6.4691261277049925,1739141186.3715599,25.81997537612915,1.3061488899775486,1739141186.3715615,25.81997537612915,2.0997080540296498,1739141186.371563,25.81997537612915,0.6108,1739141186.3715646,25.81997537612915,1.0794023520798077,1739141186.3715665,25.81997537612915,0.0,1739141186.3715687,25.81997537612915,-0.06460383660645236,1739141186.37157,25.81997537612915,0.8243279320976751,1739141186.3715718,25.81997537612915,1.1544132431362804 +1739141186.394429,25.839975357055664,50.03333427955685,1739141186.3944335,25.839975357055664,2.095724545652309,1739141186.3944397,25.839975357055664,51.033079922397214,1739141186.3944461,25.839975357055664,51.21854387173137,1739141186.39445,25.839975357055664,6.4691261277049925,1739141186.3944545,25.839975357055664,1.3061488899775486,1739141186.3944585,25.839975357055664,2.0997080540296498,1739141186.3944628,25.839975357055664,0.6108,1739141186.3944669,25.839975357055664,1.0794023520798077,1739141186.3944812,25.839975357055664,0.0,1739141186.394486,25.839975357055664,-0.07501089105647263,1739141186.39449,25.839975357055664,0.8243279320976751,1739141186.3944943,25.839975357055664,1.1544132431362804 +1739141186.4117765,25.859975337982178,50.03333427955685,1739141186.41178,25.859975337982178,2.095724545652309,1739141186.4117837,25.859975337982178,51.033079922397214,1739141186.411787,25.859975337982178,51.21854387173137,1739141186.4117885,25.859975337982178,6.4691261277049925,1739141186.4117901,25.859975337982178,1.3061488899775486,1739141186.4117916,25.859975337982178,2.0997080540296498,1739141186.4117932,25.859975337982178,0.6108,1739141186.4117944,25.859975337982178,1.0794023520798077,1739141186.4117963,25.859975337982178,0.0,1739141186.4117978,25.859975337982178,-0.07501089105647263,1739141186.4117992,25.859975337982178,0.8243279320976751,1739141186.4118009,25.859975337982178,1.1544132431362804 +1739141186.431805,25.87997531890869,50.03333427955685,1739141186.4318085,25.87997531890869,2.095724545652309,1739141186.4318135,25.87997531890869,51.033079922397214,1739141186.4318187,25.87997531890869,51.21854387173137,1739141186.4318218,25.87997531890869,6.4691261277049925,1739141186.4318256,25.87997531890869,1.3061488899775486,1739141186.431829,25.87997531890869,2.0997080540296498,1739141186.4318323,25.87997531890869,0.6108,1739141186.4318357,25.87997531890869,1.0794023520798077,1739141186.4318392,25.87997531890869,0.0,1739141186.4318428,25.87997531890869,-0.07501089105647263,1739141186.4318461,25.87997531890869,0.8243279320976751,1739141186.4318495,25.87997531890869,1.1544132431362804 +1739141186.4512532,25.899975299835205,50.03333427955685,1739141186.4512563,25.899975299835205,2.095724545652309,1739141186.4512594,25.899975299835205,51.033079922397214,1739141186.4512622,25.899975299835205,51.21854387173137,1739141186.4512632,25.899975299835205,6.4691261277049925,1739141186.451265,25.899975299835205,1.3061488899775486,1739141186.4512663,25.899975299835205,2.0997080540296498,1739141186.4512675,25.899975299835205,0.6108,1739141186.4512691,25.899975299835205,1.0794023520798077,1739141186.4512708,25.899975299835205,0.0,1739141186.4512725,25.899975299835205,-0.07501089105647263,1739141186.451274,25.899975299835205,0.8243279320976751,1739141186.451275,25.899975299835205,1.1544132431362804 +1739141186.4732182,25.91997528076172,50.11811007600361,1739141186.4732225,25.91997528076172,2.189717915538396,1739141186.473227,25.91997528076172,51.178494794025134,1739141186.4732327,25.91997528076172,51.15681098886726,1739141186.4732356,25.91997528076172,6.573247005729866,1739141186.4732392,25.91997528076172,1.3381321054419635,1739141186.473243,25.91997528076172,2.104529671401279,1739141186.473246,25.91997528076172,0.6108,1739141186.4732494,25.91997528076172,1.0773225722522866,1739141186.473253,25.91997528076172,0.0,1739141186.4732563,25.91997528076172,-0.06347962342011913,1739141186.4732597,25.91997528076172,0.8520522753443125,1739141186.473263,25.91997528076172,1.1462932782422763 +1739141186.4930472,25.939975261688232,50.11811007600361,1739141186.4930522,25.939975261688232,2.189717915538396,1739141186.493057,25.939975261688232,51.178494794025134,1739141186.4930625,25.939975261688232,51.15681098886726,1739141186.4930658,25.939975261688232,6.573247005729866,1739141186.4930694,25.939975261688232,1.3381321054419635,1739141186.4930723,25.939975261688232,2.104529671401279,1739141186.4930756,25.939975261688232,0.6108,1739141186.4930792,25.939975261688232,1.0773225722522866,1739141186.4930825,25.939975261688232,0.0,1739141186.493086,25.939975261688232,-0.06897070598998978,1739141186.4930892,25.939975261688232,0.8520522753443125,1739141186.4930925,25.939975261688232,1.1462932782422763 +1739141186.5140448,25.959975242614746,50.11811007600361,1739141186.5140502,25.959975242614746,2.189717915538396,1739141186.5140567,25.959975242614746,51.178494794025134,1739141186.5140638,25.959975242614746,51.15681098886726,1739141186.514068,25.959975242614746,6.573247005729866,1739141186.5140727,25.959975242614746,1.3381321054419635,1739141186.514077,25.959975242614746,2.104529671401279,1739141186.5140815,25.959975242614746,0.6108,1739141186.5140858,25.959975242614746,1.0773225722522866,1739141186.5140903,25.959975242614746,0.0,1739141186.514095,25.959975242614746,-0.06897070598998978,1739141186.5140994,25.959975242614746,0.8520522753443125,1739141186.5141037,25.959975242614746,1.1462932782422763 +1739141186.5330632,25.97997522354126,50.11811007600361,1739141186.533068,25.97997522354126,2.189717915538396,1739141186.5330725,25.97997522354126,51.178494794025134,1739141186.533077,25.97997522354126,51.15681098886726,1739141186.5330796,25.97997522354126,6.573247005729866,1739141186.533083,25.97997522354126,1.3381321054419635,1739141186.5330856,25.97997522354126,2.104529671401279,1739141186.5330884,25.97997522354126,0.6108,1739141186.5330908,25.97997522354126,1.0773225722522866,1739141186.5330944,25.97997522354126,0.0,1739141186.5330977,25.97997522354126,-0.06897070598998978,1739141186.5331008,25.97997522354126,0.8520522753443125,1739141186.533103,25.97997522354126,1.1462932782422763 +1739141186.55179,25.999975204467773,50.11811007600361,1739141186.5517955,25.999975204467773,2.189717915538396,1739141186.5518034,25.999975204467773,51.178494794025134,1739141186.5518088,25.999975204467773,51.15681098886726,1739141186.5518122,25.999975204467773,6.573247005729866,1739141186.551816,25.999975204467773,1.3381321054419635,1739141186.5518193,25.999975204467773,2.104529671401279,1739141186.5518224,25.999975204467773,0.6108,1739141186.551827,25.999975204467773,1.0773225722522866,1739141186.5518312,25.999975204467773,0.0,1739141186.5518377,25.999975204467773,-0.06897070598998978,1739141186.5518417,25.999975204467773,0.8520522753443125,1739141186.5518448,25.999975204467773,1.1462932782422763 +1739141186.571314,26.019975185394287,50.11811007600361,1739141186.5713167,26.019975185394287,2.189717915538396,1739141186.5713193,26.019975185394287,51.178494794025134,1739141186.5713222,26.019975185394287,51.15681098886726,1739141186.5713234,26.019975185394287,6.573247005729866,1739141186.5713248,26.019975185394287,1.3381321054419635,1739141186.5713263,26.019975185394287,2.104529671401279,1739141186.5713277,26.019975185394287,0.6108,1739141186.5713289,26.019975185394287,1.0773225722522866,1739141186.5713303,26.019975185394287,0.0,1739141186.5713317,26.019975185394287,-0.06897070598998978,1739141186.571333,26.019975185394287,0.8520522753443125,1739141186.5713341,26.019975185394287,1.1462932782422763 +1739141186.5910974,26.0399751663208,50.19969172736096,1739141186.591101,26.0399751663208,2.2853735070573222,1739141186.5911052,26.0399751663208,51.336465205667565,1739141186.5911086,26.0399751663208,51.08518966054928,1739141186.5911105,26.0399751663208,6.688394342574485,1739141186.5911121,26.0399751663208,1.3723322875664168,1739141186.5911138,26.0399751663208,2.1237861194515384,1739141186.5911152,26.0399751663208,0.6108,1739141186.591117,26.0399751663208,1.0690562865239126,1739141186.5911188,26.0399751663208,0.0,1739141186.5911207,26.0399751663208,-0.07052882467945643,1739141186.5911222,26.0399751663208,0.8797766185909499,1739141186.5911238,26.0399751663208,1.1388431495520284 +1739141186.611213,26.059975147247314,50.19969172736096,1739141186.6112165,26.059975147247314,2.2853735070573222,1739141186.6112206,26.059975147247314,51.336465205667565,1739141186.6112235,26.059975147247314,51.08518966054928,1739141186.6112251,26.059975147247314,6.688394342574485,1739141186.6112268,26.059975147247314,1.3723322875664168,1739141186.6112285,26.059975147247314,2.1237861194515384,1739141186.6112297,26.059975147247314,0.6108,1739141186.611231,26.059975147247314,1.0690562865239126,1739141186.6112328,26.059975147247314,0.0,1739141186.6112351,26.059975147247314,-0.06978686302811576,1739141186.6112363,26.059975147247314,0.8797766185909499,1739141186.6112382,26.059975147247314,1.1388431495520284 +1739141186.6313372,26.079975128173828,50.19969172736096,1739141186.6313403,26.079975128173828,2.2853735070573222,1739141186.6313434,26.079975128173828,51.336465205667565,1739141186.631346,26.079975128173828,51.08518966054928,1739141186.6313474,26.079975128173828,6.688394342574485,1739141186.631349,26.079975128173828,1.3723322875664168,1739141186.6313505,26.079975128173828,2.1237861194515384,1739141186.6313515,26.079975128173828,0.6108,1739141186.6313531,26.079975128173828,1.0690562865239126,1739141186.6313543,26.079975128173828,0.0,1739141186.631356,26.079975128173828,-0.06978686302811576,1739141186.6313572,26.079975128173828,0.8797766185909499,1739141186.6313586,26.079975128173828,1.1388431495520284 +1739141186.6511695,26.099975109100342,50.19969172736096,1739141186.6511729,26.099975109100342,2.2853735070573222,1739141186.6511767,26.099975109100342,51.336465205667565,1739141186.6511796,26.099975109100342,51.08518966054928,1739141186.651181,26.099975109100342,6.688394342574485,1739141186.6511827,26.099975109100342,1.3723322875664168,1739141186.6511838,26.099975109100342,2.1237861194515384,1739141186.6511855,26.099975109100342,0.6108,1739141186.6511867,26.099975109100342,1.0690562865239126,1739141186.6511889,26.099975109100342,0.0,1739141186.6511903,26.099975109100342,-0.06978686302811576,1739141186.6511915,26.099975109100342,0.8797766185909499,1739141186.651193,26.099975109100342,1.1388431495520284 +1739141186.6709008,26.119975090026855,50.19969172736096,1739141186.6709032,26.119975090026855,2.2853735070573222,1739141186.6709063,26.119975090026855,51.336465205667565,1739141186.670909,26.119975090026855,51.08518966054928,1739141186.6709101,26.119975090026855,6.688394342574485,1739141186.670912,26.119975090026855,1.3723322875664168,1739141186.6709135,26.119975090026855,2.1237861194515384,1739141186.670915,26.119975090026855,0.6108,1739141186.6709163,26.119975090026855,1.0690562865239126,1739141186.670918,26.119975090026855,0.0,1739141186.6709194,26.119975090026855,-0.06978686302811576,1739141186.6709206,26.119975090026855,0.8797766185909499,1739141186.670922,26.119975090026855,1.1388431495520284 +1739141186.6909955,26.13997507095337,50.278066855071074,1739141186.690998,26.13997507095337,2.382604282141002,1739141186.691001,26.13997507095337,51.57516557378678,1739141186.6910033,26.13997507095337,50.962462899896416,1739141186.6910048,26.13997507095337,6.865806587898848,1739141186.6910064,26.13997507095337,1.419308029541917,1739141186.6910079,26.13997507095337,2.2211012743478924,1739141186.691009,26.13997507095337,0.6108,1739141186.6910102,26.13997507095337,1.0282416650460697,1739141186.691012,26.13997507095337,0.0,1739141186.6910133,26.13997507095337,-0.13310124960121533,1739141186.6910148,26.13997507095337,0.9075009618375873,1739141186.691016,26.13997507095337,1.131193191694229 +1739141186.7109249,26.159975051879883,50.278066855071074,1739141186.710927,26.159975051879883,2.382604282141002,1739141186.7109299,26.159975051879883,51.57516557378678,1739141186.7109325,26.159975051879883,50.962462899896416,1739141186.710934,26.159975051879883,6.865806587898848,1739141186.7109356,26.159975051879883,1.419308029541917,1739141186.7109368,26.159975051879883,2.2211012743478924,1739141186.7109385,26.159975051879883,0.6108,1739141186.7109396,26.159975051879883,1.0282416650460697,1739141186.7109408,26.159975051879883,0.0,1739141186.7109425,26.159975051879883,-0.10295152664815932,1739141186.7109437,26.159975051879883,0.9075009618375873,1739141186.7109451,26.159975051879883,1.131193191694229 +1739141186.730871,26.179975032806396,50.278066855071074,1739141186.7308738,26.179975032806396,2.382604282141002,1739141186.7308772,26.179975032806396,51.57516557378678,1739141186.7308803,26.179975032806396,50.962462899896416,1739141186.7308817,26.179975032806396,6.865806587898848,1739141186.7308836,26.179975032806396,1.419308029541917,1739141186.730885,26.179975032806396,2.2211012743478924,1739141186.7308865,26.179975032806396,0.6108,1739141186.7308877,26.179975032806396,1.0282416650460697,1739141186.7308896,26.179975032806396,0.0,1739141186.7308908,26.179975032806396,-0.10295152664815932,1739141186.730893,26.179975032806396,0.9075009618375873,1739141186.730894,26.179975032806396,1.131193191694229 +1739141186.7509017,26.19997501373291,50.278066855071074,1739141186.7509046,26.19997501373291,2.382604282141002,1739141186.7509077,26.19997501373291,51.57516557378678,1739141186.7509105,26.19997501373291,50.962462899896416,1739141186.750912,26.19997501373291,6.865806587898848,1739141186.7509139,26.19997501373291,1.419308029541917,1739141186.750915,26.19997501373291,2.2211012743478924,1739141186.7509167,26.19997501373291,0.6108,1739141186.750918,26.19997501373291,1.0282416650460697,1739141186.7509196,26.19997501373291,0.0,1739141186.7509212,26.19997501373291,-0.10295152664815932,1739141186.7509227,26.19997501373291,0.9075009618375873,1739141186.7509243,26.19997501373291,1.131193191694229 +1739141186.7708993,26.219974994659424,50.278066855071074,1739141186.7709022,26.219974994659424,2.382604282141002,1739141186.7709055,26.219974994659424,51.57516557378678,1739141186.7709086,26.219974994659424,50.962462899896416,1739141186.77091,26.219974994659424,6.865806587898848,1739141186.770912,26.219974994659424,1.419308029541917,1739141186.7709134,26.219974994659424,2.2211012743478924,1739141186.7709148,26.219974994659424,0.6108,1739141186.770916,26.219974994659424,1.0282416650460697,1739141186.7709177,26.219974994659424,0.0,1739141186.770919,26.219974994659424,-0.10295152664815932,1739141186.7709208,26.219974994659424,0.9075009618375873,1739141186.770922,26.219974994659424,1.131193191694229 +1739141186.790807,26.239974975585938,50.278066855071074,1739141186.7908094,26.239974975585938,2.382604282141002,1739141186.7908125,26.239974975585938,51.57516557378678,1739141186.790815,26.239974975585938,50.962462899896416,1739141186.7908165,26.239974975585938,6.865806587898848,1739141186.7908182,26.239974975585938,1.419308029541917,1739141186.79082,26.239974975585938,2.2211012743478924,1739141186.7908213,26.239974975585938,0.6108,1739141186.7908225,26.239974975585938,1.0282416650460697,1739141186.790824,26.239974975585938,0.0,1739141186.7908258,26.239974975585938,-0.10295152664815932,1739141186.790827,26.239974975585938,0.9075009618375873,1739141186.7908282,26.239974975585938,1.131193191694229 +1739141186.8118455,26.25997495651245,50.35306275355269,1739141186.8118486,26.25997495651245,2.481109839455847,1739141186.811852,26.25997495651245,51.70512371953666,1739141186.8118548,26.25997495651245,50.906610238755576,1739141186.8118563,26.25997495651245,6.941798514551613,1739141186.811858,26.25997495651245,1.4473328782123167,1739141186.8118594,26.25997495651245,2.2025725832792697,1739141186.8118608,26.25997495651245,0.6108,1739141186.811862,26.25997495651245,1.0358907644545488,1739141186.8118637,26.25997495651245,0.0,1739141186.8118649,26.25997495651245,-0.06566385353778403,1739141186.811866,26.25997495651245,0.9352253050842247,1739141186.8118677,26.25997495651245,1.1193106616767168 +1739141186.8308947,26.279974937438965,50.35306275355269,1739141186.830897,26.279974937438965,2.481109839455847,1739141186.8309,26.279974937438965,51.70512371953666,1739141186.8309028,26.279974937438965,50.906610238755576,1739141186.830904,26.279974937438965,6.941798514551613,1739141186.830906,26.279974937438965,1.4473328782123167,1739141186.830907,26.279974937438965,2.2025725832792697,1739141186.8309083,26.279974937438965,0.6108,1739141186.8309097,26.279974937438965,1.0358907644545488,1739141186.8309112,26.279974937438965,0.0,1739141186.8309128,26.279974937438965,-0.08341989722216803,1739141186.830914,26.279974937438965,0.9352253050842247,1739141186.8309152,26.279974937438965,1.1193106616767168 +1739141186.8508146,26.29997491836548,50.35306275355269,1739141186.8508172,26.29997491836548,2.481109839455847,1739141186.8508198,26.29997491836548,51.70512371953666,1739141186.850823,26.29997491836548,50.906610238755576,1739141186.850824,26.29997491836548,6.941798514551613,1739141186.8508258,26.29997491836548,1.4473328782123167,1739141186.8508272,26.29997491836548,2.2025725832792697,1739141186.8508286,26.29997491836548,0.6108,1739141186.8508298,26.29997491836548,1.0358907644545488,1739141186.8508313,26.29997491836548,0.0,1739141186.850833,26.29997491836548,-0.08341989722216803,1739141186.8508341,26.29997491836548,0.9352253050842247,1739141186.8508356,26.29997491836548,1.1193106616767168 +1739141186.8708098,26.319974899291992,50.35306275355269,1739141186.8708127,26.319974899291992,2.481109839455847,1739141186.8708155,26.319974899291992,51.70512371953666,1739141186.8708181,26.319974899291992,50.906610238755576,1739141186.8708193,26.319974899291992,6.941798514551613,1739141186.8708208,26.319974899291992,1.4473328782123167,1739141186.8708224,26.319974899291992,2.2025725832792697,1739141186.8708236,26.319974899291992,0.6108,1739141186.870825,26.319974899291992,1.0358907644545488,1739141186.8708265,26.319974899291992,0.0,1739141186.8708277,26.319974899291992,-0.08341989722216803,1739141186.870829,26.319974899291992,0.9352253050842247,1739141186.8708303,26.319974899291992,1.1193106616767168 +1739141186.8908038,26.339974880218506,50.35306275355269,1739141186.8908064,26.339974880218506,2.481109839455847,1739141186.8908093,26.339974880218506,51.70512371953666,1739141186.8908122,26.339974880218506,50.906610238755576,1739141186.8908134,26.339974880218506,6.941798514551613,1739141186.8908153,26.339974880218506,1.4473328782123167,1739141186.8908165,26.339974880218506,2.2025725832792697,1739141186.8908186,26.339974880218506,0.6108,1739141186.89082,26.339974880218506,1.0358907644545488,1739141186.8908217,26.339974880218506,0.0,1739141186.8908231,26.339974880218506,-0.08341989722216803,1739141186.8908246,26.339974880218506,0.9352253050842247,1739141186.8908257,26.339974880218506,1.1193106616767168 +1739141186.910993,26.35997486114502,50.42463857003546,1739141186.9109957,26.35997486114502,2.5807381575881294,1739141186.9109988,26.35997486114502,51.895155721337446,1739141186.9110017,26.35997486114502,50.80579386347559,1739141186.9110029,26.35997486114502,7.070007670655507,1739141186.9110043,26.35997486114502,1.4860958282914134,1739141186.9110057,26.35997486114502,2.25094442358299,1739141186.9110072,26.35997486114502,0.6108,1739141186.9110084,26.35997486114502,1.016040247894394,1739141186.9110098,26.35997486114502,0.0,1739141186.9110112,26.35997486114502,-0.10418132779392981,1739141186.9110126,26.35997486114502,0.9629496483308622,1739141186.9110138,26.35997486114502,1.110335175239272 +1739141186.9308803,26.379974842071533,50.42463857003546,1739141186.930883,26.379974842071533,2.5807381575881294,1739141186.9308858,26.379974842071533,51.895155721337446,1739141186.9308884,26.379974842071533,50.80579386347559,1739141186.93089,26.379974842071533,7.070007670655507,1739141186.9308915,26.379974842071533,1.4860958282914134,1739141186.930893,26.379974842071533,2.25094442358299,1739141186.9308944,26.379974842071533,0.6108,1739141186.9308956,26.379974842071533,1.016040247894394,1739141186.9308972,26.379974842071533,0.0,1739141186.930899,26.379974842071533,-0.0942949273448781,1739141186.9308999,26.379974842071533,0.9629496483308622,1739141186.9309015,26.379974842071533,1.110335175239272 +1739141186.950853,26.399974822998047,50.42463857003546,1739141186.9508557,26.399974822998047,2.5807381575881294,1739141186.9508586,26.399974822998047,51.895155721337446,1739141186.9508612,26.399974822998047,50.80579386347559,1739141186.9508626,26.399974822998047,7.070007670655507,1739141186.950864,26.399974822998047,1.4860958282914134,1739141186.9508655,26.399974822998047,2.25094442358299,1739141186.9508672,26.399974822998047,0.6108,1739141186.9508688,26.399974822998047,1.016040247894394,1739141186.9508703,26.399974822998047,0.0,1739141186.9508717,26.399974822998047,-0.0942949273448781,1739141186.9508731,26.399974822998047,0.9629496483308622,1739141186.9508743,26.399974822998047,1.110335175239272 +1739141186.971013,26.41997480392456,50.42463857003546,1739141186.9710157,26.41997480392456,2.5807381575881294,1739141186.9710186,26.41997480392456,51.895155721337446,1739141186.971021,26.41997480392456,50.80579386347559,1739141186.9710224,26.41997480392456,7.070007670655507,1739141186.971024,26.41997480392456,1.4860958282914134,1739141186.9710255,26.41997480392456,2.25094442358299,1739141186.971027,26.41997480392456,0.6108,1739141186.9710283,26.41997480392456,1.016040247894394,1739141186.9710298,26.41997480392456,0.0,1739141186.9710312,26.41997480392456,-0.0942949273448781,1739141186.971033,26.41997480392456,0.9629496483308622,1739141186.9710343,26.41997480392456,1.110335175239272 +1739141186.9908512,26.439974784851074,50.42463857003546,1739141186.9908538,26.439974784851074,2.5807381575881294,1739141186.9908566,26.439974784851074,51.895155721337446,1739141186.9908593,26.439974784851074,50.80579386347559,1739141186.9908607,26.439974784851074,7.070007670655507,1739141186.9908624,26.439974784851074,1.4860958282914134,1739141186.9908636,26.439974784851074,2.25094442358299,1739141186.9908652,26.439974784851074,0.6108,1739141186.9908662,26.439974784851074,1.016040247894394,1739141186.9908676,26.439974784851074,0.0,1739141186.9908693,26.439974784851074,-0.0942949273448781,1739141186.9908702,26.439974784851074,0.9629496483308622,1739141186.9908717,26.439974784851074,1.110335175239272 +1739141187.0112617,26.459974765777588,50.42463857003546,1739141187.0112646,26.459974765777588,2.5807381575881294,1739141187.0112674,26.459974765777588,51.895155721337446,1739141187.0112698,26.459974765777588,50.80579386347559,1739141187.0112715,26.459974765777588,7.070007670655507,1739141187.011273,26.459974765777588,1.4860958282914134,1739141187.0112743,26.459974765777588,2.25094442358299,1739141187.0112755,26.459974765777588,0.6108,1739141187.0112767,26.459974765777588,1.016040247894394,1739141187.0112782,26.459974765777588,0.0,1739141187.01128,26.459974765777588,-0.0942949273448781,1739141187.0112813,26.459974765777588,0.9629496483308622,1739141187.0112824,26.459974765777588,1.110335175239272 +1739141187.0308838,26.4799747467041,50.492821455303684,1739141187.0308862,26.4799747467041,2.681420186392918,1739141187.030889,26.4799747467041,51.98132637342922,1739141187.0308914,26.4799747467041,50.77062490325879,1739141187.0308928,26.4799747467041,7.111740855396981,1739141187.0308943,26.4799747467041,1.5081732742638505,1739141187.030896,26.4799747467041,2.196021523864029,1739141187.0308971,26.4799747467041,0.6108,1739141187.030898,26.4799747467041,1.0386087968758742,1739141187.0309,26.4799747467041,0.0,1739141187.0309012,26.4799747467041,-0.031103921027557768,1739141187.0309026,26.4799747467041,0.9906739915774996,1739141187.0309038,26.4799747467041,1.0998036883243865 +1739141187.0509167,26.499974727630615,50.492821455303684,1739141187.0509188,26.499974727630615,2.681420186392918,1739141187.050922,26.499974727630615,51.98132637342922,1739141187.0509245,26.499974727630615,50.77062490325879,1739141187.0509257,26.499974727630615,7.111740855396981,1739141187.0509276,26.499974727630615,1.5081732742638505,1739141187.0509288,26.499974727630615,2.196021523864029,1739141187.0509303,26.499974727630615,0.6108,1739141187.050932,26.499974727630615,1.0386087968758742,1739141187.0509336,26.499974727630615,0.0,1739141187.050935,26.499974727630615,-0.06119489144851231,1739141187.0509362,26.499974727630615,0.9906739915774996,1739141187.0509377,26.499974727630615,1.0998036883243865 +1739141187.0709496,26.51997470855713,50.492821455303684,1739141187.0709522,26.51997470855713,2.681420186392918,1739141187.0709553,26.51997470855713,51.98132637342922,1739141187.0709581,26.51997470855713,50.77062490325879,1739141187.0709593,26.51997470855713,7.111740855396981,1739141187.070961,26.51997470855713,1.5081732742638505,1739141187.0709624,26.51997470855713,2.196021523864029,1739141187.0709636,26.51997470855713,0.6108,1739141187.0709653,26.51997470855713,1.0386087968758742,1739141187.0709667,26.51997470855713,0.0,1739141187.0709682,26.51997470855713,-0.06119489144851231,1739141187.0709696,26.51997470855713,0.9906739915774996,1739141187.0709708,26.51997470855713,1.0998036883243865 +1739141187.090898,26.539974689483643,50.492821455303684,1739141187.0909004,26.539974689483643,2.681420186392918,1739141187.0909033,26.539974689483643,51.98132637342922,1739141187.0909061,26.539974689483643,50.77062490325879,1739141187.0909073,26.539974689483643,7.111740855396981,1739141187.0909095,26.539974689483643,1.5081732742638505,1739141187.0909107,26.539974689483643,2.196021523864029,1739141187.0909123,26.539974689483643,0.6108,1739141187.0909135,26.539974689483643,1.0386087968758742,1739141187.0909147,26.539974689483643,0.0,1739141187.0909166,26.539974689483643,-0.06119489144851231,1739141187.090918,26.539974689483643,0.9906739915774996,1739141187.0909195,26.539974689483643,1.0998036883243865 +1739141187.1107736,26.559974670410156,50.492821455303684,1739141187.1107764,26.559974670410156,2.681420186392918,1739141187.1107788,26.559974670410156,51.98132637342922,1739141187.1107814,26.559974670410156,50.77062490325879,1739141187.1107826,26.559974670410156,7.111740855396981,1739141187.1107845,26.559974670410156,1.5081732742638505,1739141187.1107857,26.559974670410156,2.196021523864029,1739141187.1107872,26.559974670410156,0.6108,1739141187.1107883,26.559974670410156,1.0386087968758742,1739141187.1107895,26.559974670410156,0.0,1739141187.1107914,26.559974670410156,-0.06119489144851231,1739141187.1107926,26.559974670410156,0.9906739915774996,1739141187.110794,26.559974670410156,1.0998036883243865 +1739141187.1309392,26.57997465133667,50.55768135376727,1739141187.1309416,26.57997465133667,2.7831621524648087,1739141187.1309445,26.57997465133667,52.14651251510443,1739141187.1309474,26.57997465133667,50.67397734508629,1739141187.130949,26.57997465133667,7.221014693855946,1739141187.1309507,26.57997465133667,1.5445968575647717,1739141187.130952,26.57997465133667,2.229675545491647,1739141187.1309536,26.57997465133667,0.6108,1739141187.1309547,26.57997465133667,1.0247211365552436,1739141187.1309562,26.57997465133667,0.0,1739141187.130958,26.57997465133667,-0.07543184691797007,1739141187.1309593,26.57997465133667,1.018398334824137,1739141187.1309607,26.57997465133667,1.0933734774820505 +1739141187.150835,26.599974632263184,50.55768135376727,1739141187.1508372,26.599974632263184,2.7831621524648087,1739141187.1508405,26.599974632263184,52.14651251510443,1739141187.1508431,26.599974632263184,50.67397734508629,1739141187.1508443,26.599974632263184,7.221014693855946,1739141187.1508462,26.599974632263184,1.5445968575647717,1739141187.150848,26.599974632263184,2.229675545491647,1739141187.1508496,26.599974632263184,0.6108,1739141187.1508508,26.599974632263184,1.0247211365552436,1739141187.1508524,26.599974632263184,0.0,1739141187.150854,26.599974632263184,-0.06865234092680694,1739141187.1508563,26.599974632263184,1.018398334824137,1739141187.1508577,26.599974632263184,1.0933734774820505 +1739141187.1708927,26.619974613189697,50.55768135376727,1739141187.1708953,26.619974613189697,2.7831621524648087,1739141187.1708984,26.619974613189697,52.14651251510443,1739141187.170901,26.619974613189697,50.67397734508629,1739141187.1709023,26.619974613189697,7.221014693855946,1739141187.170904,26.619974613189697,1.5445968575647717,1739141187.1709054,26.619974613189697,2.229675545491647,1739141187.1709065,26.619974613189697,0.6108,1739141187.1709077,26.619974613189697,1.0247211365552436,1739141187.1709094,26.619974613189697,0.0,1739141187.170911,26.619974613189697,-0.06865234092680694,1739141187.1709123,26.619974613189697,1.018398334824137,1739141187.1709135,26.619974613189697,1.0933734774820505 +1739141187.1908982,26.63997459411621,50.55768135376727,1739141187.1909008,26.63997459411621,2.7831621524648087,1739141187.190904,26.63997459411621,52.14651251510443,1739141187.1909063,26.63997459411621,50.67397734508629,1739141187.1909077,26.63997459411621,7.221014693855946,1739141187.1909096,26.63997459411621,1.5445968575647717,1739141187.1909113,26.63997459411621,2.229675545491647,1739141187.1909125,26.63997459411621,0.6108,1739141187.1909137,26.63997459411621,1.0247211365552436,1739141187.1909153,26.63997459411621,0.0,1739141187.190917,26.63997459411621,-0.06865234092680694,1739141187.1909184,26.63997459411621,1.018398334824137,1739141187.1909196,26.63997459411621,1.0933734774820505 +1739141187.211072,26.659974575042725,50.55768135376727,1739141187.2110746,26.659974575042725,2.7831621524648087,1739141187.2110777,26.659974575042725,52.14651251510443,1739141187.21108,26.659974575042725,50.67397734508629,1739141187.2110817,26.659974575042725,7.221014693855946,1739141187.2110832,26.659974575042725,1.5445968575647717,1739141187.2110846,26.659974575042725,2.229675545491647,1739141187.2110858,26.659974575042725,0.6108,1739141187.211087,26.659974575042725,1.0247211365552436,1739141187.2110887,26.659974575042725,0.0,1739141187.21109,26.659974575042725,-0.06865234092680694,1739141187.2110915,26.659974575042725,1.018398334824137,1739141187.2110927,26.659974575042725,1.0933734774820505 +1739141187.230871,26.67997455596924,50.55768135376727,1739141187.230873,26.67997455596924,2.7831621524648087,1739141187.2308762,26.67997455596924,52.14651251510443,1739141187.2308788,26.67997455596924,50.67397734508629,1739141187.23088,26.67997455596924,7.221014693855946,1739141187.2308817,26.67997455596924,1.5445968575647717,1739141187.2308831,26.67997455596924,2.229675545491647,1739141187.2308846,26.67997455596924,0.6108,1739141187.230886,26.67997455596924,1.0247211365552436,1739141187.2308874,26.67997455596924,0.0,1739141187.2308888,26.67997455596924,-0.06865234092680694,1739141187.2308905,26.67997455596924,1.018398334824137,1739141187.2308915,26.67997455596924,1.0933734774820505 +1739141187.2508767,26.699974536895752,50.61929544518396,1739141187.2508793,26.699974536895752,2.8859938429780794,1739141187.2508821,26.699974536895752,52.309427156822714,1739141187.2508845,26.699974536895752,50.57924388068952,1739141187.250886,26.699974536895752,7.324006385367459,1739141187.2508876,26.699974536895752,1.5798207441073957,1739141187.250889,26.699974536895752,2.2578003169798873,1739141187.2508905,26.699974536895752,0.6108,1739141187.250892,26.699974536895752,1.013257719531191,1739141187.2508936,26.699974536895752,0.0,1739141187.250895,26.699974536895752,-0.07591462361910178,1739141187.2508965,26.699974536895752,1.0461226780707744,1739141187.2508976,26.699974536895752,1.0857141115692812 +1739141187.2708633,26.719974517822266,50.61929544518396,1739141187.2708662,26.719974517822266,2.8859938429780794,1739141187.270869,26.719974517822266,52.309427156822714,1739141187.2708719,26.719974517822266,50.57924388068952,1739141187.2708733,26.719974517822266,7.324006385367459,1739141187.270875,26.719974517822266,1.5798207441073957,1739141187.2708764,26.719974517822266,2.2578003169798873,1739141187.2708776,26.719974517822266,0.6108,1739141187.270879,26.719974517822266,1.013257719531191,1739141187.2708805,26.719974517822266,0.0,1739141187.2708821,26.719974517822266,-0.07245639203809029,1739141187.2708838,26.719974517822266,1.0461226780707744,1739141187.2708852,26.719974517822266,1.0857141115692812 +1739141187.3052242,26.73997449874878,50.61929544518396,1739141187.3052392,26.73997449874878,2.8859938429780794,1739141187.3052561,26.73997449874878,52.309427156822714,1739141187.3052726,26.73997449874878,50.57924388068952,1739141187.3052812,26.73997449874878,7.324006385367459,1739141187.305292,26.73997449874878,1.5798207441073957,1739141187.3053007,26.73997449874878,2.2578003169798873,1739141187.3053083,26.73997449874878,0.6108,1739141187.3053164,26.73997449874878,1.013257719531191,1739141187.305327,26.73997449874878,0.0,1739141187.3053362,26.73997449874878,-0.07245639203809029,1739141187.305345,26.73997449874878,1.0461226780707744,1739141187.3053539,26.73997449874878,1.0857141115692812 +1739141187.318524,26.759974479675293,50.61929544518396,1739141187.3185377,26.759974479675293,2.8859938429780794,1739141187.3185508,26.759974479675293,52.309427156822714,1739141187.3185701,26.759974479675293,50.57924388068952,1739141187.318575,26.759974479675293,7.324006385367459,1739141187.318581,26.759974479675293,1.5798207441073957,1739141187.318586,26.759974479675293,2.2578003169798873,1739141187.3185909,26.759974479675293,0.6108,1739141187.318596,26.759974479675293,1.013257719531191,1739141187.3186018,26.759974479675293,0.0,1739141187.318607,26.759974479675293,-0.07245639203809029,1739141187.3186114,26.759974479675293,1.0461226780707744,1739141187.3186162,26.759974479675293,1.0857141115692812 +1739141187.3579426,26.789974451065063,50.61929544518396,1739141187.3579478,26.789974451065063,2.8859938429780794,1739141187.3579538,26.789974451065063,52.309427156822714,1739141187.3579597,26.789974451065063,50.57924388068952,1739141187.3579621,26.789974451065063,7.324006385367459,1739141187.3579655,26.789974451065063,1.5798207441073957,1739141187.3579683,26.789974451065063,2.2578003169798873,1739141187.357971,26.789974451065063,0.6108,1739141187.3579733,26.789974451065063,1.013257719531191,1739141187.3579767,26.789974451065063,0.0,1739141187.3579793,26.789974451065063,-0.07245639203809029,1739141187.357982,26.789974451065063,1.0461226780707744,1739141187.3579845,26.789974451065063,1.0857141115692812 +1739141187.3788471,26.809974431991577,50.67761786706798,1739141187.3788505,26.809974431991577,2.989751190331485,1739141187.3788545,26.809974431991577,52.4948461315256,1739141187.378858,26.809974431991577,50.46581542654382,1739141187.3788598,26.809974431991577,7.438975748967252,1739141187.378862,26.809974431991577,1.6183647651134803,1739141187.3788638,26.809974431991577,2.3073333884950147,1739141187.3788655,26.809974431991577,0.6108,1739141187.3788671,26.809974431991577,0.9933793899304564,1739141187.3788693,26.809974431991577,0.0,1739141187.378871,26.809974431991577,-0.09519578946146183,1739141187.3788729,26.809974431991577,1.0738470213174118,1739141187.3788745,26.809974431991577,1.0777468894953945 +1739141187.3957071,26.82997441291809,50.67761786706798,1739141187.3957095,26.82997441291809,2.989751190331485,1739141187.3957121,26.82997441291809,52.4948461315256,1739141187.395715,26.82997441291809,50.46581542654382,1739141187.3957167,26.82997441291809,7.438975748967252,1739141187.395718,26.82997441291809,1.6183647651134803,1739141187.3957198,26.82997441291809,2.3073333884950147,1739141187.395721,26.82997441291809,0.6108,1739141187.3957222,26.82997441291809,0.9933793899304564,1739141187.3957238,26.82997441291809,0.0,1739141187.3957253,26.82997441291809,-0.08436749956493816,1739141187.3957267,26.82997441291809,1.0738470213174118,1739141187.3957279,26.82997441291809,1.0777468894953945 +1739141187.4157317,26.849974393844604,50.67761786706798,1739141187.4157355,26.849974393844604,2.989751190331485,1739141187.4157386,26.849974393844604,52.4948461315256,1739141187.4157414,26.849974393844604,50.46581542654382,1739141187.4157429,26.849974393844604,7.438975748967252,1739141187.4157445,26.849974393844604,1.6183647651134803,1739141187.415746,26.849974393844604,2.3073333884950147,1739141187.4157474,26.849974393844604,0.6108,1739141187.4157486,26.849974393844604,0.9933793899304564,1739141187.4157505,26.849974393844604,0.0,1739141187.415752,26.849974393844604,-0.08436749956493816,1739141187.4157531,26.849974393844604,1.0738470213174118,1739141187.4157546,26.849974393844604,1.0777468894953945 +1739141187.435792,26.869974374771118,50.67761786706798,1739141187.4357944,26.869974374771118,2.989751190331485,1739141187.4357975,26.869974374771118,52.4948461315256,1739141187.4358,26.869974374771118,50.46581542654382,1739141187.4358013,26.869974374771118,7.438975748967252,1739141187.435803,26.869974374771118,1.6183647651134803,1739141187.4358044,26.869974374771118,2.3073333884950147,1739141187.4358058,26.869974374771118,0.6108,1739141187.4358068,26.869974374771118,0.9933793899304564,1739141187.4358084,26.869974374771118,0.0,1739141187.4358099,26.869974374771118,-0.08436749956493816,1739141187.435811,26.869974374771118,1.0738470213174118,1739141187.4358127,26.869974374771118,1.0777468894953945 +1739141187.4556139,26.889974355697632,50.67761786706798,1739141187.4556165,26.889974355697632,2.989751190331485,1739141187.4556196,26.889974355697632,52.4948461315256,1739141187.4556222,26.889974355697632,50.46581542654382,1739141187.4556236,26.889974355697632,7.438975748967252,1739141187.4556253,26.889974355697632,1.6183647651134803,1739141187.4556267,26.889974355697632,2.3073333884950147,1739141187.455628,26.889974355697632,0.6108,1739141187.4556293,26.889974355697632,0.9933793899304564,1739141187.4556308,26.889974355697632,0.0,1739141187.4556322,26.889974355697632,-0.08436749956493816,1739141187.4556334,26.889974355697632,1.0738470213174118,1739141187.4556346,26.889974355697632,1.0777468894953945 +1739141187.4759362,26.909974336624146,50.732601409128335,1739141187.4759388,26.909974336624146,3.0942479354271786,1739141187.475942,26.909974336624146,52.63540741593843,1739141187.4759445,26.909974336624146,50.38340714993746,1739141187.475946,26.909974336624146,7.515625422057532,1739141187.4759479,26.909974336624146,1.6496113382490751,1739141187.475949,26.909974336624146,2.3107784602045904,1739141187.4759505,26.909974336624146,0.6108,1739141187.475952,26.909974336624146,0.9920114273994852,1739141187.4759536,26.909974336624146,0.0,1739141187.475955,26.909974336624146,-0.06915073487488171,1739141187.4759564,26.909974336624146,1.1015713645640492,1739141187.4759579,26.909974336624146,1.068408244317938 +1739141187.495312,26.92997431755066,50.732601409128335,1739141187.4953146,26.92997431755066,3.0942479354271786,1739141187.4953177,26.92997431755066,52.63540741593843,1739141187.4953206,26.92997431755066,50.38340714993746,1739141187.4953222,26.92997431755066,7.515625422057532,1739141187.495324,26.92997431755066,1.6496113382490751,1739141187.495325,26.92997431755066,2.3107784602045904,1739141187.4953265,26.92997431755066,0.6108,1739141187.495328,26.92997431755066,0.9920114273994852,1739141187.4953296,26.92997431755066,0.0,1739141187.495331,26.92997431755066,-0.07639681691845268,1739141187.4953322,26.92997431755066,1.1015713645640492,1739141187.4953337,26.92997431755066,1.068408244317938 +1739141187.5150375,26.949974298477173,50.732601409128335,1739141187.5150397,26.949974298477173,3.0942479354271786,1739141187.5150428,26.949974298477173,52.63540741593843,1739141187.5150454,26.949974298477173,50.38340714993746,1739141187.5150466,26.949974298477173,7.515625422057532,1739141187.5150487,26.949974298477173,1.6496113382490751,1739141187.5150502,26.949974298477173,2.3107784602045904,1739141187.5150516,26.949974298477173,0.6108,1739141187.5150528,26.949974298477173,0.9920114273994852,1739141187.5150542,26.949974298477173,0.0,1739141187.5150564,26.949974298477173,-0.07639681691845268,1739141187.5150576,26.949974298477173,1.1015713645640492,1739141187.515059,26.949974298477173,1.068408244317938 +1739141187.5352404,26.969974279403687,50.732601409128335,1739141187.5352433,26.969974279403687,3.0942479354271786,1739141187.5352464,26.969974279403687,52.63540741593843,1739141187.5352492,26.969974279403687,50.38340714993746,1739141187.5352507,26.969974279403687,7.515625422057532,1739141187.5352523,26.969974279403687,1.6496113382490751,1739141187.5352538,26.969974279403687,2.3107784602045904,1739141187.535255,26.969974279403687,0.6108,1739141187.5352561,26.969974279403687,0.9920114273994852,1739141187.5352578,26.969974279403687,0.0,1739141187.5352592,26.969974279403687,-0.07639681691845268,1739141187.5352604,26.969974279403687,1.1015713645640492,1739141187.5352616,26.969974279403687,1.068408244317938 +1739141187.5549917,26.9899742603302,50.732601409128335,1739141187.554994,26.9899742603302,3.0942479354271786,1739141187.5549974,26.9899742603302,52.63540741593843,1739141187.5550003,26.9899742603302,50.38340714993746,1739141187.5550015,26.9899742603302,7.515625422057532,1739141187.5550034,26.9899742603302,1.6496113382490751,1739141187.5550046,26.9899742603302,2.3107784602045904,1739141187.5550063,26.9899742603302,0.6108,1739141187.5550075,26.9899742603302,0.9920114273994852,1739141187.5550091,26.9899742603302,0.0,1739141187.5550106,26.9899742603302,-0.07639681691845268,1739141187.5550117,26.9899742603302,1.1015713645640492,1739141187.5550134,26.9899742603302,1.068408244317938 +1739141187.575306,27.009974241256714,50.732601409128335,1739141187.5753088,27.009974241256714,3.0942479354271786,1739141187.5753121,27.009974241256714,52.63540741593843,1739141187.5753148,27.009974241256714,50.38340714993746,1739141187.5753162,27.009974241256714,7.515625422057532,1739141187.5753179,27.009974241256714,1.6496113382490751,1739141187.5753193,27.009974241256714,2.3107784602045904,1739141187.5753205,27.009974241256714,0.6108,1739141187.5753222,27.009974241256714,0.9920114273994852,1739141187.5753238,27.009974241256714,0.0,1739141187.5753255,27.009974241256714,-0.07639681691845268,1739141187.5753267,27.009974241256714,1.1015713645640492,1739141187.5753284,27.009974241256714,1.068408244317938 +1739141187.595756,27.029974222183228,50.78423800918613,1739141187.5957594,27.029974222183228,3.199355924920626,1739141187.5957632,27.029974222183228,52.63713711079163,1739141187.5957665,27.029974222183228,50.400463790647706,1739141187.595768,27.029974222183228,7.499933312604113,1739141187.5957701,27.029974222183228,1.6597984093551261,1739141187.5957718,27.029974222183228,2.1845970812001267,1739141187.5957737,27.029974222183228,0.6108,1739141187.595775,27.029974222183228,1.0433658686362053,1739141187.5957773,27.029974222183228,0.0,1739141187.5957792,27.029974222183228,0.03749321864289611,1739141187.5957806,27.029974222183228,1.1292957078106867,1739141187.595782,27.029974222183228,1.0601060273525595 +1739141187.6153316,27.04997420310974,50.78423800918613,1739141187.615335,27.04997420310974,3.199355924920626,1739141187.6153386,27.04997420310974,52.63713711079163,1739141187.615342,27.04997420310974,50.400463790647706,1739141187.6153433,27.04997420310974,7.499933312604113,1739141187.6153455,27.04997420310974,1.6597984093551261,1739141187.6153471,27.04997420310974,2.1845970812001267,1739141187.615349,27.04997420310974,0.6108,1739141187.6153505,27.04997420310974,1.0433658686362053,1739141187.6153524,27.04997420310974,0.0,1739141187.615354,27.04997420310974,-0.01674015871635426,1739141187.6153557,27.04997420310974,1.1292957078106867,1739141187.6153574,27.04997420310974,1.0601060273525595 +1739141187.6353471,27.069974184036255,50.78423800918613,1739141187.6353502,27.069974184036255,3.199355924920626,1739141187.6353536,27.069974184036255,52.63713711079163,1739141187.635357,27.069974184036255,50.400463790647706,1739141187.6353588,27.069974184036255,7.499933312604113,1739141187.6353605,27.069974184036255,1.6597984093551261,1739141187.6353624,27.069974184036255,2.1845970812001267,1739141187.635364,27.069974184036255,0.6108,1739141187.6353657,27.069974184036255,1.0433658686362053,1739141187.6353674,27.069974184036255,0.0,1739141187.6353693,27.069974184036255,-0.01674015871635426,1739141187.635371,27.069974184036255,1.1292957078106867,1739141187.6353726,27.069974184036255,1.0601060273525595 +1739141187.6555114,27.08997416496277,50.78423800918613,1739141187.6555145,27.08997416496277,3.199355924920626,1739141187.6555176,27.08997416496277,52.63713711079163,1739141187.655521,27.08997416496277,50.400463790647706,1739141187.6555228,27.08997416496277,7.499933312604113,1739141187.655525,27.08997416496277,1.6597984093551261,1739141187.6555264,27.08997416496277,2.1845970812001267,1739141187.6555283,27.08997416496277,0.6108,1739141187.6555295,27.08997416496277,1.0433658686362053,1739141187.6555314,27.08997416496277,0.0,1739141187.6555333,27.08997416496277,-0.01674015871635426,1739141187.6555347,27.08997416496277,1.1292957078106867,1739141187.6555364,27.08997416496277,1.0601060273525595 +1739141187.6754858,27.109974145889282,50.78423800918613,1739141187.6754887,27.109974145889282,3.199355924920626,1739141187.6754923,27.109974145889282,52.63713711079163,1739141187.6754954,27.109974145889282,50.400463790647706,1739141187.6754973,27.109974145889282,7.499933312604113,1739141187.6754992,27.109974145889282,1.6597984093551261,1739141187.6755009,27.109974145889282,2.1845970812001267,1739141187.6755023,27.109974145889282,0.6108,1739141187.675504,27.109974145889282,1.0433658686362053,1739141187.6755056,27.109974145889282,0.0,1739141187.6755075,27.109974145889282,-0.01674015871635426,1739141187.6755095,27.109974145889282,1.1292957078106867,1739141187.6755111,27.109974145889282,1.0601060273525595 +1739141187.6956265,27.129974126815796,50.83270747329708,1739141187.6956296,27.129974126815796,3.305348462371377,1739141187.6956332,27.129974126815796,52.934864829854156,1739141187.6956365,27.129974126815796,50.17793274302701,1739141187.6956382,27.129974126815796,7.691487042933454,1739141187.6956406,27.129974126815796,1.71898471165003,1739141187.695642,27.129974126815796,2.3630514232296176,1739141187.695644,27.129974126815796,0.6108,1739141187.695645,27.129974126815796,0.9714846239453429,1739141187.6956472,27.129974126815796,0.0,1739141187.695649,27.129974126815796,-0.15140373682703595,1739141187.6956506,27.129974126815796,1.157020051057324,1739141187.695652,27.129974126815796,1.0587628153528283 +1739141187.7212179,27.14997410774231,50.83270747329708,1739141187.7212267,27.14997410774231,3.305348462371377,1739141187.7212377,27.14997410774231,52.934864829854156,1739141187.721248,27.14997410774231,50.17793274302701,1739141187.721253,27.14997410774231,7.691487042933454,1739141187.7212586,27.14997410774231,1.71898471165003,1739141187.7212636,27.14997410774231,2.3630514232296176,1739141187.7212684,27.14997410774231,0.6108,1739141187.7212732,27.14997410774231,0.9714846239453429,1739141187.7212787,27.14997410774231,0.0,1739141187.7212842,27.14997410774231,-0.0872781914074855,1739141187.7212887,27.14997410774231,1.157020051057324,1739141187.7212932,27.14997410774231,1.0587628153528283 +1739141187.7487743,27.169974088668823,50.83270747329708,1739141187.748782,27.169974088668823,3.305348462371377,1739141187.748791,27.169974088668823,52.934864829854156,1739141187.7488015,27.169974088668823,50.17793274302701,1739141187.7488072,27.169974088668823,7.691487042933454,1739141187.7488146,27.169974088668823,1.71898471165003,1739141187.7488213,27.169974088668823,2.3630514232296176,1739141187.748828,27.169974088668823,0.6108,1739141187.7488344,27.169974088668823,0.9714846239453429,1739141187.7488415,27.169974088668823,0.0,1739141187.7488487,27.169974088668823,-0.0872781914074855,1739141187.748855,27.169974088668823,1.157020051057324,1739141187.7488618,27.169974088668823,1.0587628153528283 +1739141187.762732,27.199974060058594,50.83270747329708,1739141187.7627375,27.199974060058594,3.305348462371377,1739141187.7627432,27.199974060058594,52.934864829854156,1739141187.762749,27.199974060058594,50.17793274302701,1739141187.762752,27.199974060058594,7.691487042933454,1739141187.7627554,27.199974060058594,1.71898471165003,1739141187.7627583,27.199974060058594,2.3630514232296176,1739141187.7627604,27.199974060058594,0.6108,1739141187.762763,27.199974060058594,0.9714846239453429,1739141187.7627661,27.199974060058594,0.0,1739141187.7627687,27.199974060058594,-0.0872781914074855,1739141187.7627714,27.199974060058594,1.157020051057324,1739141187.762774,27.199974060058594,1.0587628153528283 +1739141187.7794363,27.219974040985107,50.83270747329708,1739141187.7794406,27.219974040985107,3.305348462371377,1739141187.7794452,27.219974040985107,52.934864829854156,1739141187.7794495,27.219974040985107,50.17793274302701,1739141187.7794516,27.219974040985107,7.691487042933454,1739141187.7794542,27.219974040985107,1.71898471165003,1739141187.7794561,27.219974040985107,2.3630514232296176,1739141187.7794585,27.219974040985107,0.6108,1739141187.7794607,27.219974040985107,0.9714846239453429,1739141187.779463,27.219974040985107,0.0,1739141187.7794654,27.219974040985107,-0.0872781914074855,1739141187.7794676,27.219974040985107,1.157020051057324,1739141187.7794695,27.219974040985107,1.0587628153528283 +1739141187.7990553,27.23997402191162,50.87798559064078,1739141187.7990596,27.23997402191162,3.412084816951632,1739141187.7990642,27.23997402191162,53.07023143751727,1739141187.7990687,27.23997402191162,50.09513301956834,1739141187.799071,27.23997402191162,7.755957102683036,1739141187.7990737,27.23997402191162,1.7491023319773187,1739141187.7990758,27.23997402191162,2.360851849644652,1739141187.799078,27.23997402191162,0.6108,1739141187.79908,27.23997402191162,0.9723397408354977,1739141187.7990825,27.23997402191162,0.0,1739141187.799085,27.23997402191162,-0.06628752419731414,1739141187.7990868,27.23997402191162,1.1847443943039615,1739141187.799089,27.23997402191162,1.0486228258403985 +1739141187.8189912,27.259974002838135,50.87798559064078,1739141187.818995,27.259974002838135,3.412084816951632,1739141187.8189993,27.259974002838135,53.07023143751727,1739141187.8190036,27.259974002838135,50.09513301956834,1739141187.8190057,27.259974002838135,7.755957102683036,1739141187.8190088,27.259974002838135,1.7491023319773187,1739141187.8190107,27.259974002838135,2.360851849644652,1739141187.8190129,27.259974002838135,0.6108,1739141187.8190145,27.259974002838135,0.9723397408354977,1739141187.8190172,27.259974002838135,0.0,1739141187.8190196,27.259974002838135,-0.07628308500490077,1739141187.8190212,27.259974002838135,1.1847443943039615,1739141187.8190234,27.259974002838135,1.0486228258403985 +1739141187.8395364,27.27997398376465,50.87798559064078,1739141187.8395412,27.27997398376465,3.412084816951632,1739141187.839546,27.27997398376465,53.07023143751727,1739141187.8395503,27.27997398376465,50.09513301956834,1739141187.8395524,27.27997398376465,7.755957102683036,1739141187.839555,27.27997398376465,1.7491023319773187,1739141187.8395574,27.27997398376465,2.360851849644652,1739141187.8395593,27.27997398376465,0.6108,1739141187.8395612,27.27997398376465,0.9723397408354977,1739141187.8395638,27.27997398376465,0.0,1739141187.8395662,27.27997398376465,-0.07628308500490077,1739141187.8395684,27.27997398376465,1.1847443943039615,1739141187.8395705,27.27997398376465,1.0486228258403985 +1739141187.8589323,27.299973964691162,50.87798559064078,1739141187.858936,27.299973964691162,3.412084816951632,1739141187.8589404,27.299973964691162,53.07023143751727,1739141187.8589447,27.299973964691162,50.09513301956834,1739141187.8589468,27.299973964691162,7.755957102683036,1739141187.8589497,27.299973964691162,1.7491023319773187,1739141187.8589516,27.299973964691162,2.360851849644652,1739141187.8589537,27.299973964691162,0.6108,1739141187.8589556,27.299973964691162,0.9723397408354977,1739141187.858958,27.299973964691162,0.0,1739141187.8589604,27.299973964691162,-0.07628308500490077,1739141187.8589625,27.299973964691162,1.1847443943039615,1739141187.8589642,27.299973964691162,1.0486228258403985 +1739141187.8791456,27.319973945617676,50.87798559064078,1739141187.8791502,27.319973945617676,3.412084816951632,1739141187.879155,27.319973945617676,53.07023143751727,1739141187.8791592,27.319973945617676,50.09513301956834,1739141187.8791614,27.319973945617676,7.755957102683036,1739141187.879164,27.319973945617676,1.7491023319773187,1739141187.8791661,27.319973945617676,2.360851849644652,1739141187.8791683,27.319973945617676,0.6108,1739141187.8791704,27.319973945617676,0.9723397408354977,1739141187.8791728,27.319973945617676,0.0,1739141187.8791752,27.319973945617676,-0.07628308500490077,1739141187.8791773,27.319973945617676,1.1847443943039615,1739141187.8791795,27.319973945617676,1.0486228258403985 +1739141187.898896,27.33997392654419,50.87798559064078,1739141187.8988998,27.33997392654419,3.412084816951632,1739141187.8989043,27.33997392654419,53.07023143751727,1739141187.8989084,27.33997392654419,50.09513301956834,1739141187.898911,27.33997392654419,7.755957102683036,1739141187.8989139,27.33997392654419,1.7491023319773187,1739141187.8989158,27.33997392654419,2.360851849644652,1739141187.898918,27.33997392654419,0.6108,1739141187.8989203,27.33997392654419,0.9723397408354977,1739141187.8989224,27.33997392654419,0.0,1739141187.8989248,27.33997392654419,-0.07628308500490077,1739141187.8989267,27.33997392654419,1.1847443943039615,1739141187.8989289,27.33997392654419,1.0486228258403985 +1739141187.9188282,27.359973907470703,50.91992292518208,1739141187.9188323,27.359973907470703,3.51910650923519,1739141187.918837,27.359973907470703,53.23595339782499,1739141187.9188416,27.359973907470703,49.98103489932628,1739141187.918844,27.359973907470703,7.839185580958247,1739141187.9188464,27.359973907470703,1.784799630206909,1739141187.9188488,27.359973907470703,2.3943428482311786,1739141187.918851,27.359973907470703,0.6108,1739141187.9188528,27.359973907470703,0.959400750726819,1739141187.9188554,27.359973907470703,0.0,1739141187.9188578,27.359973907470703,-0.08540111961154417,1739141187.9188597,27.359973907470703,1.212468737550599,1739141187.9188616,27.359973907470703,1.040459946928124 +1739141187.9392447,27.379973888397217,50.91992292518208,1739141187.9392495,27.379973888397217,3.51910650923519,1739141187.9392545,27.379973888397217,53.23595339782499,1739141187.9392588,27.379973888397217,49.98103489932628,1739141187.939261,27.379973888397217,7.839185580958247,1739141187.9392636,27.379973888397217,1.784799630206909,1739141187.9392657,27.379973888397217,2.3943428482311786,1739141187.9392679,27.379973888397217,0.6108,1739141187.9392698,27.379973888397217,0.959400750726819,1739141187.9392724,27.379973888397217,0.0,1739141187.9392748,27.379973888397217,-0.08105919620130497,1739141187.9392767,27.379973888397217,1.212468737550599,1739141187.9392788,27.379973888397217,1.040459946928124 +1739141187.9588373,27.39997386932373,50.91992292518208,1739141187.9588413,27.39997386932373,3.51910650923519,1739141187.9588459,27.39997386932373,53.23595339782499,1739141187.9588504,27.39997386932373,49.98103489932628,1739141187.9588523,27.39997386932373,7.839185580958247,1739141187.9588552,27.39997386932373,1.784799630206909,1739141187.9588575,27.39997386932373,2.3943428482311786,1739141187.9588594,27.39997386932373,0.6108,1739141187.9588616,27.39997386932373,0.959400750726819,1739141187.9588642,27.39997386932373,0.0,1739141187.9588664,27.39997386932373,-0.08105919620130497,1739141187.9588685,27.39997386932373,1.212468737550599,1739141187.9588704,27.39997386932373,1.040459946928124 +1739141187.979695,27.419973850250244,50.91992292518208,1739141187.9797006,27.419973850250244,3.51910650923519,1739141187.979709,27.419973850250244,53.23595339782499,1739141187.9797196,27.419973850250244,49.98103489932628,1739141187.9797256,27.419973850250244,7.839185580958247,1739141187.979733,27.419973850250244,1.784799630206909,1739141187.97974,27.419973850250244,2.3943428482311786,1739141187.9797466,27.419973850250244,0.6108,1739141187.979753,27.419973850250244,0.959400750726819,1739141187.97976,27.419973850250244,0.0,1739141187.9797664,27.419973850250244,-0.08105919620130497,1739141187.9797692,27.419973850250244,1.212468737550599,1739141187.9797714,27.419973850250244,1.040459946928124 +1739141187.9985807,27.439973831176758,50.91992292518208,1739141187.9985843,27.439973831176758,3.51910650923519,1739141187.9985878,27.439973831176758,53.23595339782499,1739141187.9985917,27.439973831176758,49.98103489932628,1739141187.9985936,27.439973831176758,7.839185580958247,1739141187.998596,27.439973831176758,1.784799630206909,1739141187.9985976,27.439973831176758,2.3943428482311786,1739141187.9985995,27.439973831176758,0.6108,1739141187.998601,27.439973831176758,0.959400750726819,1739141187.998603,27.439973831176758,0.0,1739141187.998605,27.439973831176758,-0.08105919620130497,1739141187.9986067,27.439973831176758,1.212468737550599,1739141187.9986084,27.439973831176758,1.040459946928124 +1739141188.0181386,27.45997381210327,50.958557328263254,1739141188.0181422,27.45997381210327,3.626360407126036,1739141188.018146,27.45997381210327,53.40068331785621,1739141188.01815,27.45997381210327,49.86750019850175,1739141188.0181518,27.45997381210327,7.917538705828958,1739141188.018154,27.45997381210327,1.8197764551657492,1739141188.0181558,27.45997381210327,2.424947896401963,1739141188.0181575,27.45997381210327,0.6108,1739141188.0181592,27.45997381210327,0.9477273470545643,1739141188.018161,27.45997381210327,0.0,1739141188.0181632,27.45997381210327,-0.08631916587171073,1739141188.0181653,27.45997381210327,1.2401930807972363,1739141188.0181668,27.45997381210327,1.0315417642129456 +1739141188.0392733,27.479973793029785,50.958557328263254,1739141188.039277,27.479973793029785,3.626360407126036,1739141188.0392807,27.479973793029785,53.40068331785621,1739141188.0392845,27.479973793029785,49.86750019850175,1739141188.039286,27.479973793029785,7.917538705828958,1739141188.039288,27.479973793029785,1.8197764551657492,1739141188.03929,27.479973793029785,2.424947896401963,1739141188.0392916,27.479973793029785,0.6108,1739141188.0392933,27.479973793029785,0.9477273470545643,1739141188.0392954,27.479973793029785,0.0,1739141188.0392976,27.479973793029785,-0.08381441715838134,1739141188.039299,27.479973793029785,1.2401930807972363,1739141188.039301,27.479973793029785,1.0315417642129456 +1739141188.060665,27.4999737739563,50.958557328263254,1739141188.0606682,27.4999737739563,3.626360407126036,1739141188.0606723,27.4999737739563,53.40068331785621,1739141188.060676,27.4999737739563,49.86750019850175,1739141188.060678,27.4999737739563,7.917538705828958,1739141188.0606802,27.4999737739563,1.8197764551657492,1739141188.060682,27.4999737739563,2.424947896401963,1739141188.0606837,27.4999737739563,0.6108,1739141188.0606856,27.4999737739563,0.9477273470545643,1739141188.0606875,27.4999737739563,0.0,1739141188.0606894,27.4999737739563,-0.08381441715838134,1739141188.060691,27.4999737739563,1.2401930807972363,1739141188.0606928,27.4999737739563,1.0315417642129456 +1739141188.0788536,27.519973754882812,50.958557328263254,1739141188.0788567,27.519973754882812,3.626360407126036,1739141188.0788605,27.519973754882812,53.40068331785621,1739141188.0788639,27.519973754882812,49.86750019850175,1739141188.0788658,27.519973754882812,7.917538705828958,1739141188.0788677,27.519973754882812,1.8197764551657492,1739141188.0788696,27.519973754882812,2.424947896401963,1739141188.078871,27.519973754882812,0.6108,1739141188.0788727,27.519973754882812,0.9477273470545643,1739141188.0788746,27.519973754882812,0.0,1739141188.0788765,27.519973754882812,-0.08381441715838134,1739141188.0788782,27.519973754882812,1.2401930807972363,1739141188.07888,27.519973754882812,1.0315417642129456 +1739141188.0988545,27.539973735809326,50.958557328263254,1739141188.0988579,27.539973735809326,3.626360407126036,1739141188.0988615,27.539973735809326,53.40068331785621,1739141188.0988655,27.539973735809326,49.86750019850175,1739141188.0988672,27.539973735809326,7.917538705828958,1739141188.0988693,27.539973735809326,1.8197764551657492,1739141188.0988712,27.539973735809326,2.424947896401963,1739141188.0988731,27.539973735809326,0.6108,1739141188.0988746,27.539973735809326,0.9477273470545643,1739141188.0988767,27.539973735809326,0.0,1739141188.0988784,27.539973735809326,-0.08381441715838134,1739141188.0988805,27.539973735809326,1.2401930807972363,1739141188.0988822,27.539973735809326,1.0315417642129456 +1739141188.119489,27.55997371673584,50.958557328263254,1739141188.1194923,27.55997371673584,3.626360407126036,1739141188.119496,27.55997371673584,53.40068331785621,1739141188.1194997,27.55997371673584,49.86750019850175,1739141188.1195016,27.55997371673584,7.917538705828958,1739141188.1195035,27.55997371673584,1.8197764551657492,1739141188.1195056,27.55997371673584,2.424947896401963,1739141188.1195073,27.55997371673584,0.6108,1739141188.119509,27.55997371673584,0.9477273470545643,1739141188.1195111,27.55997371673584,0.0,1739141188.1195128,27.55997371673584,-0.08381441715838134,1739141188.1195147,27.55997371673584,1.2401930807972363,1739141188.1195161,27.55997371673584,1.0315417642129456 +1739141188.139601,27.579973697662354,50.99389148901977,1739141188.1396043,27.579973697662354,3.733695307589265,1739141188.139608,27.579973697662354,53.41605821585585,1739141188.1396117,27.579973697662354,49.877840734895166,1739141188.1396132,27.579973697662354,7.9108123374953765,1739141188.1396155,27.579973697662354,1.831879837860128,1739141188.1396172,27.579973697662354,2.311155853770752,1739141188.139619,27.579973697662354,0.6108,1739141188.1396208,27.579973697662354,0.9918616872098627,1739141188.139623,27.579973697662354,0.0,1739141188.1396246,27.579973697662354,0.018076145301184288,1739141188.1396265,27.579973697662354,1.2679174240438738,1739141188.1396286,27.579973697662354,1.0223048816031444 +1739141188.1579843,27.599973678588867,50.99389148901977,1739141188.1579878,27.599973678588867,3.733695307589265,1739141188.1579914,27.599973678588867,53.41605821585585,1739141188.1579947,27.599973678588867,49.877840734895166,1739141188.1579962,27.599973678588867,7.9108123374953765,1739141188.1579986,27.599973678588867,1.831879837860128,1739141188.1580005,27.599973678588867,2.311155853770752,1739141188.158002,27.599973678588867,0.6108,1739141188.1580036,27.599973678588867,0.9918616872098627,1739141188.1580052,27.599973678588867,0.0,1739141188.1580071,27.599973678588867,-0.030443194393281692,1739141188.1580088,27.599973678588867,1.2679174240438738,1739141188.1580105,27.599973678588867,1.0223048816031444 +1739141188.1840284,27.61997365951538,50.99389148901977,1739141188.1840384,27.61997365951538,3.733695307589265,1739141188.1840487,27.61997365951538,53.41605821585585,1739141188.1840594,27.61997365951538,49.877840734895166,1739141188.1840637,27.61997365951538,7.9108123374953765,1739141188.1840696,27.61997365951538,1.831879837860128,1739141188.1840746,27.61997365951538,2.311155853770752,1739141188.18408,27.61997365951538,0.6108,1739141188.1840844,27.61997365951538,0.9918616872098627,1739141188.1840901,27.61997365951538,0.0,1739141188.1840951,27.61997365951538,-0.030443194393281692,1739141188.1840997,27.61997365951538,1.2679174240438738,1739141188.1841044,27.61997365951538,1.0223048816031444 +1739141188.204297,27.639973640441895,50.99389148901977,1739141188.204306,27.639973640441895,3.733695307589265,1739141188.2043161,27.639973640441895,53.41605821585585,1739141188.2043257,27.639973640441895,49.877840734895166,1739141188.204331,27.639973640441895,7.9108123374953765,1739141188.2043366,27.639973640441895,1.831879837860128,1739141188.2043414,27.639973640441895,2.311155853770752,1739141188.2043462,27.639973640441895,0.6108,1739141188.2043507,27.639973640441895,0.9918616872098627,1739141188.2043567,27.639973640441895,0.0,1739141188.2043614,27.639973640441895,-0.030443194393281692,1739141188.2043657,27.639973640441895,1.2679174240438738,1739141188.2043703,27.639973640441895,1.0223048816031444 +1739141188.2240486,27.659973621368408,50.99389148901977,1739141188.2240582,27.659973621368408,3.733695307589265,1739141188.2240689,27.659973621368408,53.41605821585585,1739141188.2240794,27.659973621368408,49.877840734895166,1739141188.2240841,27.659973621368408,7.9108123374953765,1739141188.2240903,27.659973621368408,1.831879837860128,1739141188.224096,27.659973621368408,2.311155853770752,1739141188.2241006,27.659973621368408,0.6108,1739141188.2241051,27.659973621368408,0.9918616872098627,1739141188.2241113,27.659973621368408,0.0,1739141188.2241166,27.659973621368408,-0.030443194393281692,1739141188.224121,27.659973621368408,1.2679174240438738,1739141188.2241259,27.659973621368408,1.0223048816031444 +1739141188.24154,27.679973602294922,51.02603795302883,1739141188.2415462,27.679973602294922,3.841309081695311,1739141188.2415533,27.679973602294922,53.615683765205816,1739141188.24156,27.679973602294922,49.71649564787089,1739141188.2415633,27.679973602294922,8.012882553249078,1739141188.2415671,27.679973602294922,1.8749747650600062,1739141188.2415707,27.679973602294922,2.393680049782188,1739141188.2415736,27.679973602294922,0.6108,1739141188.2415767,27.679973602294922,0.9596551401789327,1739141188.2415807,27.679973602294922,0.0,1739141188.2415845,27.679973602294922,-0.08639993580277294,1739141188.2415876,27.679973602294922,1.2956417672905112,1739141188.2415907,27.679973602294922,1.0194089953329712 +1739141188.2599964,27.699973583221436,51.02603795302883,1739141188.260001,27.699973583221436,3.841309081695311,1739141188.2600062,27.699973583221436,53.615683765205816,1739141188.2600114,27.699973583221436,49.71649564787089,1739141188.260014,27.699973583221436,8.012882553249078,1739141188.2600172,27.699973583221436,1.8749747650600062,1739141188.2600198,27.699973583221436,2.393680049782188,1739141188.2600222,27.699973583221436,0.6108,1739141188.2600245,27.699973583221436,0.9596551401789327,1739141188.2600276,27.699973583221436,0.0,1739141188.2600303,27.699973583221436,-0.05975385515403853,1739141188.2600327,27.699973583221436,1.2956417672905112,1739141188.260035,27.699973583221436,1.0194089953329712 +1739141188.2809458,27.71997356414795,51.02603795302883,1739141188.2809508,27.71997356414795,3.841309081695311,1739141188.2809565,27.71997356414795,53.615683765205816,1739141188.2809618,27.71997356414795,49.71649564787089,1739141188.2809644,27.71997356414795,8.012882553249078,1739141188.2809677,27.71997356414795,1.8749747650600062,1739141188.2809703,27.71997356414795,2.393680049782188,1739141188.2809727,27.71997356414795,0.6108,1739141188.280975,27.71997356414795,0.9596551401789327,1739141188.280978,27.71997356414795,0.0,1739141188.280981,27.71997356414795,-0.05975385515403853,1739141188.2809834,27.71997356414795,1.2956417672905112,1739141188.280986,27.71997356414795,1.0194089953329712 +1739141188.2990277,27.739973545074463,51.02603795302883,1739141188.2990305,27.739973545074463,3.841309081695311,1739141188.2990339,27.739973545074463,53.615683765205816,1739141188.2990372,27.739973545074463,49.71649564787089,1739141188.2990386,27.739973545074463,8.012882553249078,1739141188.2990408,27.739973545074463,1.8749747650600062,1739141188.2990422,27.739973545074463,2.393680049782188,1739141188.299044,27.739973545074463,0.6108,1739141188.2990453,27.739973545074463,0.9596551401789327,1739141188.2990472,27.739973545074463,0.0,1739141188.2990487,27.739973545074463,-0.05975385515403853,1739141188.2990503,27.739973545074463,1.2956417672905112,1739141188.2990518,27.739973545074463,1.0194089953329712 +1739141188.318011,27.759973526000977,51.02603795302883,1739141188.318014,27.759973526000977,3.841309081695311,1739141188.318017,27.759973526000977,53.615683765205816,1739141188.31802,27.759973526000977,49.71649564787089,1739141188.3180215,27.759973526000977,8.012882553249078,1739141188.3180237,27.759973526000977,1.8749747650600062,1739141188.3180249,27.759973526000977,2.393680049782188,1739141188.3180268,27.759973526000977,0.6108,1739141188.3180282,27.759973526000977,0.9596551401789327,1739141188.3180304,27.759973526000977,0.0,1739141188.3180318,27.759973526000977,-0.05975385515403853,1739141188.3180335,27.759973526000977,1.2956417672905112,1739141188.3180354,27.759973526000977,1.0194089953329712 +1739141188.3405175,27.77997350692749,51.02603795302883,1739141188.3405223,27.77997350692749,3.841309081695311,1739141188.3405275,27.77997350692749,53.615683765205816,1739141188.3405337,27.77997350692749,49.71649564787089,1739141188.3405373,27.77997350692749,8.012882553249078,1739141188.3405416,27.77997350692749,1.8749747650600062,1739141188.3405457,27.77997350692749,2.393680049782188,1739141188.3405497,27.77997350692749,0.6108,1739141188.3405535,27.77997350692749,0.9596551401789327,1739141188.3405576,27.77997350692749,0.0,1739141188.3405616,27.77997350692749,-0.05975385515403853,1739141188.3405654,27.77997350692749,1.2956417672905112,1739141188.3405695,27.77997350692749,1.0194089953329712 +1739141188.3643637,27.799973487854004,51.055044740833466,1739141188.3643782,27.799973487854004,3.9492319315972324,1739141188.364398,27.799973487854004,53.74011596964279,1739141188.3644123,27.799973487854004,49.62734707701087,1739141188.3644204,27.799973487854004,8.064856259059638,1739141188.364433,27.799973487854004,1.9047040959404578,1739141188.3644414,27.799973487854004,2.3921880549889463,1739141188.3644488,27.799973487854004,0.6108,1739141188.3644557,27.799973487854004,0.960228031301025,1739141188.3644643,27.799973487854004,0.0,1739141188.364476,27.799973487854004,-0.045145261081240395,1739141188.364486,27.799973487854004,1.3233661105371486,1739141188.3645017,27.799973487854004,1.0123297692253286 +1739141188.3831577,27.819973468780518,51.055044740833466,1739141188.3831635,27.819973468780518,3.9492319315972324,1739141188.3831692,27.819973468780518,53.74011596964279,1739141188.3831747,27.819973468780518,49.62734707701087,1739141188.3831775,27.819973468780518,8.064856259059638,1739141188.3831809,27.819973468780518,1.9047040959404578,1739141188.3831837,27.819973468780518,2.3921880549889463,1739141188.383186,27.819973468780518,0.6108,1739141188.3831887,27.819973468780518,0.960228031301025,1739141188.3831918,27.819973468780518,0.0,1739141188.3831944,27.819973468780518,-0.052101737924303615,1739141188.3831968,27.819973468780518,1.3233661105371486,1739141188.3831995,27.819973468780518,1.0123297692253286 +1739141188.4015882,27.83997344970703,51.055044740833466,1739141188.401592,27.83997344970703,3.9492319315972324,1739141188.4015968,27.83997344970703,53.74011596964279,1739141188.4016008,27.83997344970703,49.62734707701087,1739141188.401603,27.83997344970703,8.064856259059638,1739141188.4016058,27.83997344970703,1.9047040959404578,1739141188.401608,27.83997344970703,2.3921880549889463,1739141188.4016101,27.83997344970703,0.6108,1739141188.401612,27.83997344970703,0.960228031301025,1739141188.4016147,27.83997344970703,0.0,1739141188.4016168,27.83997344970703,-0.052101737924303615,1739141188.4016192,27.83997344970703,1.3233661105371486,1739141188.401621,27.83997344970703,1.0123297692253286 +1739141188.4209492,27.859973430633545,51.055044740833466,1739141188.420953,27.859973430633545,3.9492319315972324,1739141188.4209578,27.859973430633545,53.74011596964279,1739141188.4209623,27.859973430633545,49.62734707701087,1739141188.420964,27.859973430633545,8.064856259059638,1739141188.4209669,27.859973430633545,1.9047040959404578,1739141188.420969,27.859973430633545,2.3921880549889463,1739141188.420971,27.859973430633545,0.6108,1739141188.4209728,27.859973430633545,0.960228031301025,1739141188.4209754,27.859973430633545,0.0,1739141188.4209774,27.859973430633545,-0.052101737924303615,1739141188.4209795,27.859973430633545,1.3233661105371486,1739141188.4209812,27.859973430633545,1.0123297692253286 +1739141188.4479947,27.87997341156006,51.055044740833466,1739141188.4480038,27.87997341156006,3.9492319315972324,1739141188.4480155,27.87997341156006,53.74011596964279,1739141188.4480252,27.87997341156006,49.62734707701087,1739141188.44803,27.87997341156006,8.064856259059638,1739141188.4480367,27.87997341156006,1.9047040959404578,1739141188.4480417,27.87997341156006,2.3921880549889463,1739141188.4480467,27.87997341156006,0.6108,1739141188.4480512,27.87997341156006,0.960228031301025,1739141188.4480572,27.87997341156006,0.0,1739141188.448062,27.87997341156006,-0.052101737924303615,1739141188.4480665,27.87997341156006,1.3233661105371486,1739141188.4480712,27.87997341156006,1.0123297692253286 +1739141188.4644904,27.899973392486572,51.080889769565474,1739141188.4644992,27.899973392486572,4.05725462446423,1739141188.4645092,27.899973392486572,53.91738851150103,1739141188.4645193,27.899973392486572,49.48706067800973,1739141188.4645243,27.899973392486572,8.142488264298871,1739141188.4645305,27.899973392486572,1.9427773196215874,1739141188.4645352,27.899973392486572,2.445862323783136,1739141188.46454,27.899973392486572,0.6108,1739141188.4645445,27.899973392486572,0.9398319487379686,1739141188.4645505,27.899973392486572,0.0,1739141188.4645553,27.899973392486572,-0.08026509423512893,1739141188.46456,27.899973392486572,1.351090453783786,1739141188.4645648,27.899973392486572,1.0066859142208788 +1739141188.4904664,27.90997338294983,51.080889769565474,1739141188.490509,27.90997338294983,4.05725462446423,1739141188.4905326,27.90997338294983,53.91738851150103,1739141188.490548,27.90997338294983,49.48706067800973,1739141188.4905531,27.90997338294983,8.142488264298871,1739141188.4905593,27.90997338294983,1.9427773196215874,1739141188.490564,27.90997338294983,2.445862323783136,1739141188.4905686,27.90997338294983,0.6108,1739141188.4905734,27.90997338294983,0.9398319487379686,1739141188.4905791,27.90997338294983,0.0,1739141188.4905841,27.90997338294983,-0.06685396548291023,1739141188.490589,27.90997338294983,1.351090453783786,1739141188.4905934,27.90997338294983,1.0066859142208788 +1739141188.512966,27.9399733543396,51.080889769565474,1739141188.5129757,27.9399733543396,4.05725462446423,1739141188.5129864,27.9399733543396,53.91738851150103,1739141188.5129967,27.9399733543396,49.48706067800973,1739141188.5130012,27.9399733543396,8.142488264298871,1739141188.5130076,27.9399733543396,1.9427773196215874,1739141188.5130126,27.9399733543396,2.445862323783136,1739141188.5130174,27.9399733543396,0.6108,1739141188.5130227,27.9399733543396,0.9398319487379686,1739141188.5130284,27.9399733543396,0.0,1739141188.5130336,27.9399733543396,-0.06685396548291023,1739141188.5130386,27.9399733543396,1.351090453783786,1739141188.5130432,27.9399733543396,1.0066859142208788 +1739141188.5289297,27.959973335266113,51.080889769565474,1739141188.5289345,27.959973335266113,4.05725462446423,1739141188.5289397,27.959973335266113,53.91738851150103,1739141188.5289454,27.959973335266113,49.48706067800973,1739141188.528948,27.959973335266113,8.142488264298871,1739141188.528951,27.959973335266113,1.9427773196215874,1739141188.5289536,27.959973335266113,2.445862323783136,1739141188.5289562,27.959973335266113,0.6108,1739141188.5289586,27.959973335266113,0.9398319487379686,1739141188.5289614,27.959973335266113,0.0,1739141188.5289643,27.959973335266113,-0.06685396548291023,1739141188.528967,27.959973335266113,1.351090453783786,1739141188.5289695,27.959973335266113,1.0066859142208788 +1739141188.5462503,27.979973316192627,51.080889769565474,1739141188.5462544,27.979973316192627,4.05725462446423,1739141188.5462587,27.979973316192627,53.91738851150103,1739141188.5462623,27.979973316192627,49.48706067800973,1739141188.5462644,27.979973316192627,8.142488264298871,1739141188.5462666,27.979973316192627,1.9427773196215874,1739141188.546269,27.979973316192627,2.445862323783136,1739141188.5462706,27.979973316192627,0.6108,1739141188.5462725,27.979973316192627,0.9398319487379686,1739141188.5462751,27.979973316192627,0.0,1739141188.5462773,27.979973316192627,-0.06685396548291023,1739141188.5462792,27.979973316192627,1.351090453783786,1739141188.5462809,27.979973316192627,1.0066859142208788 +1739141188.5651588,27.99997329711914,51.080889769565474,1739141188.5651612,27.99997329711914,4.05725462446423,1739141188.565164,27.99997329711914,53.91738851150103,1739141188.565167,27.99997329711914,49.48706067800973,1739141188.5651681,27.99997329711914,8.142488264298871,1739141188.5651698,27.99997329711914,1.9427773196215874,1739141188.5651712,27.99997329711914,2.445862323783136,1739141188.5651727,27.99997329711914,0.6108,1739141188.565174,27.99997329711914,0.9398319487379686,1739141188.5651755,27.99997329711914,0.0,1739141188.5651772,27.99997329711914,-0.06685396548291023,1739141188.5651786,27.99997329711914,1.351090453783786,1739141188.5651798,27.99997329711914,1.0066859142208788 +1739141188.5853624,28.019973278045654,51.10358282379753,1739141188.5853648,28.019973278045654,4.165247737066029,1739141188.5853674,28.019973278045654,53.99660912007658,1739141188.5853703,28.019973278045654,49.43635365376865,1739141188.5853717,28.019973278045654,8.168162706952584,1739141188.5853734,28.019973278045654,1.9654486376813147,1739141188.585375,28.019973278045654,2.400372728925703,1739141188.5853763,28.019973278045654,0.6108,1739141188.5853775,28.019973278045654,0.9570895103220233,1739141188.5853791,28.019973278045654,0.0,1739141188.5853803,28.019973278045654,-0.01966321025621351,1739141188.585382,28.019973278045654,1.3788147970304234,1739141188.5853832,28.019973278045654,0.9992245200070713 +1739141188.6051192,28.039973258972168,51.10358282379753,1739141188.6051219,28.039973258972168,4.165247737066029,1739141188.6051247,28.039973258972168,53.99660912007658,1739141188.6051273,28.039973258972168,49.43635365376865,1739141188.6051288,28.039973258972168,8.168162706952584,1739141188.6051302,28.039973258972168,1.9654486376813147,1739141188.6051319,28.039973258972168,2.400372728925703,1739141188.605133,28.039973258972168,0.6108,1739141188.605134,28.039973258972168,0.9570895103220233,1739141188.605136,28.039973258972168,0.0,1739141188.605137,28.039973258972168,-0.04213500968504802,1739141188.6051385,28.039973258972168,1.3788147970304234,1739141188.6051397,28.039973258972168,0.9992245200070713 +1739141188.6251214,28.05997323989868,51.10358282379753,1739141188.6251235,28.05997323989868,4.165247737066029,1739141188.6251266,28.05997323989868,53.99660912007658,1739141188.6251295,28.05997323989868,49.43635365376865,1739141188.6251307,28.05997323989868,8.168162706952584,1739141188.6251326,28.05997323989868,1.9654486376813147,1739141188.625134,28.05997323989868,2.400372728925703,1739141188.6251354,28.05997323989868,0.6108,1739141188.6251364,28.05997323989868,0.9570895103220233,1739141188.6251383,28.05997323989868,0.0,1739141188.6251397,28.05997323989868,-0.04213500968504802,1739141188.625141,28.05997323989868,1.3788147970304234,1739141188.6251423,28.05997323989868,0.9992245200070713 +1739141188.6453354,28.079973220825195,51.10358282379753,1739141188.6453388,28.079973220825195,4.165247737066029,1739141188.6453428,28.079973220825195,53.99660912007658,1739141188.6453457,28.079973220825195,49.43635365376865,1739141188.6453474,28.079973220825195,8.168162706952584,1739141188.645349,28.079973220825195,1.9654486376813147,1739141188.6453512,28.079973220825195,2.400372728925703,1739141188.6453526,28.079973220825195,0.6108,1739141188.6453538,28.079973220825195,0.9570895103220233,1739141188.6453557,28.079973220825195,0.0,1739141188.6453574,28.079973220825195,-0.04213500968504802,1739141188.6453586,28.079973220825195,1.3788147970304234,1739141188.6453602,28.079973220825195,0.9992245200070713 +1739141188.665463,28.09997320175171,51.10358282379753,1739141188.6654663,28.09997320175171,4.165247737066029,1739141188.6654696,28.09997320175171,53.99660912007658,1739141188.6654727,28.09997320175171,49.43635365376865,1739141188.6654744,28.09997320175171,8.168162706952584,1739141188.665476,28.09997320175171,1.9654486376813147,1739141188.6654775,28.09997320175171,2.400372728925703,1739141188.665479,28.09997320175171,0.6108,1739141188.6654801,28.09997320175171,0.9570895103220233,1739141188.665482,28.09997320175171,0.0,1739141188.6654835,28.09997320175171,-0.04213500968504802,1739141188.665485,28.09997320175171,1.3788147970304234,1739141188.665486,28.09997320175171,0.9992245200070713 +1739141188.6860862,28.119973182678223,51.1231553785236,1739141188.6860888,28.119973182678223,4.273181397675755,1739141188.6860917,28.119973182678223,54.16434761449176,1739141188.6860945,28.119973182678223,49.29687301432677,1739141188.6860962,28.119973182678223,8.234560329252357,1739141188.6860976,28.119973182678223,2.0027781542575456,1739141188.6860993,28.119973182678223,2.449463715078183,1739141188.6861005,28.119973182678223,0.6108,1739141188.6861017,28.119973182678223,0.9384790424013555,1739141188.6861033,28.119973182678223,0.0,1739141188.6861045,28.119973182678223,-0.06924084954111734,1739141188.686106,28.119973182678223,1.4065391402770608,1739141188.6861072,28.119973182678223,0.9948123427059836 +1739141188.7074068,28.139973163604736,51.1231553785236,1739141188.7074094,28.139973163604736,4.273181397675755,1739141188.707412,28.139973163604736,54.16434761449176,1739141188.7074149,28.139973163604736,49.29687301432677,1739141188.707416,28.139973163604736,8.234560329252357,1739141188.707418,28.139973163604736,2.0027781542575456,1739141188.7074192,28.139973163604736,2.449463715078183,1739141188.7074203,28.139973163604736,0.6108,1739141188.7074218,28.139973163604736,0.9384790424013555,1739141188.7074232,28.139973163604736,0.0,1739141188.7074249,28.139973163604736,-0.05633330030462813,1739141188.7074258,28.139973163604736,1.4065391402770608,1739141188.707427,28.139973163604736,0.9948123427059836 +1739141188.7254796,28.15997314453125,51.1231553785236,1739141188.7254822,28.15997314453125,4.273181397675755,1739141188.7254848,28.15997314453125,54.16434761449176,1739141188.7254877,28.15997314453125,49.29687301432677,1739141188.725489,28.15997314453125,8.234560329252357,1739141188.7254903,28.15997314453125,2.0027781542575456,1739141188.7254918,28.15997314453125,2.449463715078183,1739141188.725493,28.15997314453125,0.6108,1739141188.7254944,28.15997314453125,0.9384790424013555,1739141188.7254958,28.15997314453125,0.0,1739141188.7254972,28.15997314453125,-0.05633330030462813,1739141188.7254987,28.15997314453125,1.4065391402770608,1739141188.7254999,28.15997314453125,0.9948123427059836 +1739141188.7470126,28.179973125457764,51.1231553785236,1739141188.7470167,28.179973125457764,4.273181397675755,1739141188.7470212,28.179973125457764,54.16434761449176,1739141188.7470257,28.179973125457764,49.29687301432677,1739141188.7470279,28.179973125457764,8.234560329252357,1739141188.7470305,28.179973125457764,2.0027781542575456,1739141188.7470329,28.179973125457764,2.449463715078183,1739141188.747035,28.179973125457764,0.6108,1739141188.7470374,28.179973125457764,0.9384790424013555,1739141188.7470403,28.179973125457764,0.0,1739141188.7470427,28.179973125457764,-0.05633330030462813,1739141188.7470448,28.179973125457764,1.4065391402770608,1739141188.7470472,28.179973125457764,0.9948123427059836 +1739141188.765049,28.199973106384277,51.1231553785236,1739141188.7650511,28.199973106384277,4.273181397675755,1739141188.765054,28.199973106384277,54.16434761449176,1739141188.7650566,28.199973106384277,49.29687301432677,1739141188.7650578,28.199973106384277,8.234560329252357,1739141188.7650592,28.199973106384277,2.0027781542575456,1739141188.7650607,28.199973106384277,2.449463715078183,1739141188.7650619,28.199973106384277,0.6108,1739141188.7650628,28.199973106384277,0.9384790424013555,1739141188.7650645,28.199973106384277,0.0,1739141188.7650657,28.199973106384277,-0.05633330030462813,1739141188.765067,28.199973106384277,1.4065391402770608,1739141188.7650685,28.199973106384277,0.9948123427059836 +1739141188.7859192,28.21997308731079,51.1231553785236,1739141188.7859216,28.21997308731079,4.273181397675755,1739141188.7859242,28.21997308731079,54.16434761449176,1739141188.7859263,28.21997308731079,49.29687301432677,1739141188.7859278,28.21997308731079,8.234560329252357,1739141188.785929,28.21997308731079,2.0027781542575456,1739141188.7859302,28.21997308731079,2.449463715078183,1739141188.7859313,28.21997308731079,0.6108,1739141188.7859323,28.21997308731079,0.9384790424013555,1739141188.785934,28.21997308731079,0.0,1739141188.7859354,28.21997308731079,-0.05633330030462813,1739141188.7859364,28.21997308731079,1.4065391402770608,1739141188.7859375,28.21997308731079,0.9948123427059836 +1739141188.8057284,28.239973068237305,51.13963802597892,1739141188.8057308,28.239973068237305,4.381021291700321,1739141188.8057334,28.239973068237305,54.29761770152411,1739141188.8057358,28.239973068237305,49.192841177506324,1739141188.8057373,28.239973068237305,8.281120032444722,1739141188.8057387,28.239973068237305,2.0337765461765853,1739141188.80574,28.239973068237305,2.4595184165833204,1739141188.8057413,28.239973068237305,0.6108,1739141188.8057423,28.239973068237305,0.9347121717748286,1739141188.805744,28.239973068237305,0.0,1739141188.8057451,28.239973068237305,-0.05124626319034274,1739141188.8057463,28.239973068237305,1.4342634835236983,1739141188.8057475,28.239973068237305,0.988380834801116 +1739141188.8258188,28.25997304916382,51.13963802597892,1739141188.8258214,28.25997304916382,4.381021291700321,1739141188.8258243,28.25997304916382,54.29761770152411,1739141188.8258266,28.25997304916382,49.192841177506324,1739141188.8258278,28.25997304916382,8.281120032444722,1739141188.8258293,28.25997304916382,2.0337765461765853,1739141188.8258307,28.25997304916382,2.4595184165833204,1739141188.825832,28.25997304916382,0.6108,1739141188.8258336,28.25997304916382,0.9347121717748286,1739141188.825835,28.25997304916382,0.0,1739141188.8258362,28.25997304916382,-0.05366866302628748,1739141188.8258376,28.25997304916382,1.4342634835236983,1739141188.8258388,28.25997304916382,0.988380834801116 +1739141188.8457274,28.279973030090332,51.13963802597892,1739141188.84573,28.279973030090332,4.381021291700321,1739141188.8457332,28.279973030090332,54.29761770152411,1739141188.8457358,28.279973030090332,49.192841177506324,1739141188.845737,28.279973030090332,8.281120032444722,1739141188.8457384,28.279973030090332,2.0337765461765853,1739141188.8457398,28.279973030090332,2.4595184165833204,1739141188.845741,28.279973030090332,0.6108,1739141188.845742,28.279973030090332,0.9347121717748286,1739141188.8457437,28.279973030090332,0.0,1739141188.845745,28.279973030090332,-0.05366866302628748,1739141188.8457463,28.279973030090332,1.4342634835236983,1739141188.8457475,28.279973030090332,0.988380834801116 +1739141188.8657079,28.299973011016846,51.13963802597892,1739141188.8657103,28.299973011016846,4.381021291700321,1739141188.865713,28.299973011016846,54.29761770152411,1739141188.865716,28.299973011016846,49.192841177506324,1739141188.8657172,28.299973011016846,8.281120032444722,1739141188.8657188,28.299973011016846,2.0337765461765853,1739141188.86572,28.299973011016846,2.4595184165833204,1739141188.8657212,28.299973011016846,0.6108,1739141188.8657224,28.299973011016846,0.9347121717748286,1739141188.8657238,28.299973011016846,0.0,1739141188.8657255,28.299973011016846,-0.05366866302628748,1739141188.8657265,28.299973011016846,1.4342634835236983,1739141188.8657277,28.299973011016846,0.988380834801116 +1739141188.885939,28.31997299194336,51.13963802597892,1739141188.8859413,28.31997299194336,4.381021291700321,1739141188.885944,28.31997299194336,54.29761770152411,1739141188.8859465,28.31997299194336,49.192841177506324,1739141188.885948,28.31997299194336,8.281120032444722,1739141188.8859494,28.31997299194336,2.0337765461765853,1739141188.8859508,28.31997299194336,2.4595184165833204,1739141188.885952,28.31997299194336,0.6108,1739141188.885953,28.31997299194336,0.9347121717748286,1739141188.8859546,28.31997299194336,0.0,1739141188.8859558,28.31997299194336,-0.05366866302628748,1739141188.885957,28.31997299194336,1.4342634835236983,1739141188.8859584,28.31997299194336,0.988380834801116 +1739141188.905484,28.339972972869873,51.153042419245864,1739141188.9054863,28.339972972869873,4.488615312240713,1739141188.9054892,28.339972972869873,54.35274874308268,1739141188.9054918,28.339972972869873,49.158372777056485,1739141188.9054928,28.339972972869873,8.2960337294642,1739141188.9054942,28.339972972869873,2.0533730180588856,1739141188.905496,28.339972972869873,2.396336059581632,1739141188.905497,28.339972972869873,0.6108,1739141188.905498,28.339972972869873,0.9586361401870104,1739141188.9054997,28.339972972869873,0.0,1739141188.905501,28.339972972869873,0.003185657472306192,1739141188.9055023,28.339972972869873,1.4619878267703357,1739141188.9055033,28.339972972869873,0.9825239821908113 +1739141188.9253232,28.359972953796387,51.153042419245864,1739141188.9253259,28.359972953796387,4.488615312240713,1739141188.9253285,28.359972953796387,54.35274874308268,1739141188.9253314,28.359972953796387,49.158372777056485,1739141188.9253328,28.359972953796387,8.2960337294642,1739141188.9253342,28.359972953796387,2.0533730180588856,1739141188.9253356,28.359972953796387,2.396336059581632,1739141188.925337,28.359972953796387,0.6108,1739141188.925338,28.359972953796387,0.9586361401870104,1739141188.9253397,28.359972953796387,0.0,1739141188.9253411,28.359972953796387,-0.023887842003800897,1739141188.9253426,28.359972953796387,1.4619878267703357,1739141188.9253438,28.359972953796387,0.9825239821908113 +1739141188.9453115,28.3799729347229,51.153042419245864,1739141188.9453135,28.3799729347229,4.488615312240713,1739141188.9453163,28.3799729347229,54.35274874308268,1739141188.945319,28.3799729347229,49.158372777056485,1739141188.9453201,28.3799729347229,8.2960337294642,1739141188.9453218,28.3799729347229,2.0533730180588856,1739141188.945323,28.3799729347229,2.396336059581632,1739141188.9453242,28.3799729347229,0.6108,1739141188.9453254,28.3799729347229,0.9586361401870104,1739141188.945327,28.3799729347229,0.0,1739141188.9453285,28.3799729347229,-0.023887842003800897,1739141188.94533,28.3799729347229,1.4619878267703357,1739141188.9453309,28.3799729347229,0.9825239821908113 +1739141188.9658644,28.399972915649414,51.153042419245864,1739141188.965867,28.399972915649414,4.488615312240713,1739141188.9658701,28.399972915649414,54.35274874308268,1739141188.965873,28.399972915649414,49.158372777056485,1739141188.9658742,28.399972915649414,8.2960337294642,1739141188.9658759,28.399972915649414,2.0533730180588856,1739141188.9658773,28.399972915649414,2.396336059581632,1739141188.965879,28.399972915649414,0.6108,1739141188.9658804,28.399972915649414,0.9586361401870104,1739141188.9658818,28.399972915649414,0.0,1739141188.9658835,28.399972915649414,-0.023887842003800897,1739141188.965885,28.399972915649414,1.4619878267703357,1739141188.965886,28.399972915649414,0.9825239821908113 +1739141188.9960852,28.40997290611267,51.153042419245864,1739141188.996094,28.40997290611267,4.488615312240713,1739141188.996104,28.40997290611267,54.35274874308268,1739141188.996113,28.40997290611267,49.158372777056485,1739141188.9961183,28.40997290611267,8.2960337294642,1739141188.9961243,28.40997290611267,2.0533730180588856,1739141188.996129,28.40997290611267,2.396336059581632,1739141188.9961338,28.40997290611267,0.6108,1739141188.9961386,28.40997290611267,0.9586361401870104,1739141188.996144,28.40997290611267,0.0,1739141188.9961493,28.40997290611267,-0.023887842003800897,1739141188.9961538,28.40997290611267,1.4619878267703357,1739141188.9961584,28.40997290611267,0.9825239821908113 +1739141189.0115023,28.429972887039185,51.153042419245864,1739141189.0115113,28.429972887039185,4.488615312240713,1739141189.011521,28.429972887039185,54.35274874308268,1739141189.0115304,28.429972887039185,49.158372777056485,1739141189.0115354,28.429972887039185,8.2960337294642,1739141189.0115416,28.429972887039185,2.0533730180588856,1739141189.0115464,28.429972887039185,2.396336059581632,1739141189.011551,28.429972887039185,0.6108,1739141189.0115554,28.429972887039185,0.9586361401870104,1739141189.0115612,28.429972887039185,0.0,1739141189.0115662,28.429972887039185,-0.023887842003800897,1739141189.0115707,28.429972887039185,1.4619878267703357,1739141189.0115752,28.429972887039185,0.9825239821908113 +1739141189.0323212,28.459972858428955,51.16341672696181,1739141189.0323298,28.459972858428955,4.59611024802469,1739141189.0323403,28.459972858428955,54.53618693212236,1739141189.0323503,28.459972858428955,48.993976170744936,1739141189.0323548,28.459972858428955,8.362133935970649,1739141189.0323608,28.459972858428955,2.093423859403514,1739141189.0323656,28.459972858428955,2.4673431712774403,1739141189.0323699,28.459972858428955,0.6108,1739141189.0323744,28.459972858428955,0.9317911879742368,1739141189.03238,28.459972858428955,0.0,1739141189.0323856,28.459972858428955,-0.0711651981350328,1739141189.0323899,28.459972858428955,1.489712170016973,1739141189.0323944,28.459972858428955,0.9804433481338655 +1739141189.0719566,28.489972829818726,51.16341672696181,1739141189.0719726,28.489972829818726,4.59611024802469,1739141189.07199,28.489972829818726,54.53618693212236,1739141189.072011,28.489972829818726,48.993976170744936,1739141189.0720222,28.489972829818726,8.362133935970649,1739141189.0720365,28.489972829818726,2.093423859403514,1739141189.072049,28.489972829818726,2.4673431712774403,1739141189.0720606,28.489972829818726,0.6108,1739141189.0720725,28.489972829818726,0.9317911879742368,1739141189.072085,28.489972829818726,0.0,1739141189.072097,28.489972829818726,-0.0486521601596287,1739141189.072109,28.489972829818726,1.489712170016973,1739141189.0721211,28.489972829818726,0.9804433481338655 +1739141189.098443,28.529972791671753,51.16341672696181,1739141189.0984468,28.529972791671753,4.59611024802469,1739141189.0984502,28.529972791671753,54.53618693212236,1739141189.0984535,28.529972791671753,48.993976170744936,1739141189.0984557,28.529972791671753,8.362133935970649,1739141189.0984576,28.529972791671753,2.093423859403514,1739141189.0984595,28.529972791671753,2.4673431712774403,1739141189.098461,28.529972791671753,0.6108,1739141189.098462,28.529972791671753,0.9317911879742368,1739141189.0984643,28.529972791671753,0.0,1739141189.0984657,28.529972791671753,-0.0486521601596287,1739141189.0984805,28.529972791671753,1.489712170016973,1739141189.098485,28.529972791671753,0.9804433481338655 +1739141189.1179156,28.549972772598267,51.16341672696181,1739141189.11792,28.549972772598267,4.59611024802469,1739141189.1179247,28.549972772598267,54.53618693212236,1739141189.117931,28.549972772598267,48.993976170744936,1739141189.117933,28.549972772598267,8.362133935970649,1739141189.1179368,28.549972772598267,2.093423859403514,1739141189.1179402,28.549972772598267,2.4673431712774403,1739141189.1179442,28.549972772598267,0.6108,1739141189.1179478,28.549972772598267,0.9317911879742368,1739141189.117952,28.549972772598267,0.0,1739141189.1179547,28.549972772598267,-0.0486521601596287,1739141189.1179569,28.549972772598267,1.489712170016973,1739141189.1179585,28.549972772598267,0.9804433481338655 +1739141189.1378381,28.56997275352478,51.170776848931,1739141189.137842,28.56997275352478,4.703393848113036,1739141189.1378467,28.56997275352478,54.69446209303083,1739141189.1378531,28.56997275352478,48.86174129267033,1739141189.137857,28.56997275352478,8.409049813723765,1739141189.137862,28.56997275352478,2.1280362159420485,1739141189.1378665,28.56997275352478,2.503388404110582,1739141189.1378708,28.56997275352478,0.6108,1739141189.1378746,28.56997275352478,0.9184529230819778,1739141189.1378775,28.56997275352478,0.0,1739141189.1378813,28.56997275352478,-0.06269665122018693,1739141189.1378844,28.56997275352478,1.5174365132636105,1739141189.1378865,28.56997275352478,0.9744617180753082 +1739141189.1573625,28.589972734451294,51.170776848931,1739141189.1573648,28.589972734451294,4.703393848113036,1739141189.1573675,28.589972734451294,54.69446209303083,1739141189.15737,28.589972734451294,48.86174129267033,1739141189.1573718,28.589972734451294,8.409049813723765,1739141189.1573734,28.589972734451294,2.1280362159420485,1739141189.1573746,28.589972734451294,2.503388404110582,1739141189.1573758,28.589972734451294,0.6108,1739141189.157377,28.589972734451294,0.9184529230819778,1739141189.1573787,28.589972734451294,0.0,1739141189.1573799,28.589972734451294,-0.056008794993330446,1739141189.1573808,28.589972734451294,1.5174365132636105,1739141189.1573822,28.589972734451294,0.9744617180753082 +1739141189.1775427,28.609972715377808,51.170776848931,1739141189.1775455,28.609972715377808,4.703393848113036,1739141189.1775482,28.609972715377808,54.69446209303083,1739141189.177551,28.609972715377808,48.86174129267033,1739141189.1775525,28.609972715377808,8.409049813723765,1739141189.177554,28.609972715377808,2.1280362159420485,1739141189.177555,28.609972715377808,2.503388404110582,1739141189.1775565,28.609972715377808,0.6108,1739141189.1775575,28.609972715377808,0.9184529230819778,1739141189.1775591,28.609972715377808,0.0,1739141189.1775606,28.609972715377808,-0.056008794993330446,1739141189.1775618,28.609972715377808,1.5174365132636105,1739141189.177563,28.609972715377808,0.9744617180753082 +1739141189.198763,28.62997269630432,51.170776848931,1739141189.1987708,28.62997269630432,4.703393848113036,1739141189.1987786,28.62997269630432,54.69446209303083,1739141189.1987848,28.62997269630432,48.86174129267033,1739141189.1987877,28.62997269630432,8.409049813723765,1739141189.1987913,28.62997269630432,2.1280362159420485,1739141189.198794,28.62997269630432,2.503388404110582,1739141189.198797,28.62997269630432,0.6108,1739141189.1987998,28.62997269630432,0.9184529230819778,1739141189.1988027,28.62997269630432,0.0,1739141189.1988058,28.62997269630432,-0.056008794993330446,1739141189.1988084,28.62997269630432,1.5174365132636105,1739141189.198811,28.62997269630432,0.9744617180753082 +1739141189.2179427,28.649972677230835,51.170776848931,1739141189.2179458,28.649972677230835,4.703393848113036,1739141189.2179487,28.649972677230835,54.69446209303083,1739141189.2179515,28.649972677230835,48.86174129267033,1739141189.2179527,28.649972677230835,8.409049813723765,1739141189.2179544,28.649972677230835,2.1280362159420485,1739141189.2179558,28.649972677230835,2.503388404110582,1739141189.2179568,28.649972677230835,0.6108,1739141189.2179582,28.649972677230835,0.9184529230819778,1739141189.2179596,28.649972677230835,0.0,1739141189.217961,28.649972677230835,-0.056008794993330446,1739141189.2179623,28.649972677230835,1.5174365132636105,1739141189.2179635,28.649972677230835,0.9744617180753082 +1739141189.2380905,28.66997265815735,51.17513326610645,1739141189.2380934,28.66997265815735,4.810181420314786,1739141189.2380967,28.66997265815735,54.77888671231988,1739141189.2380996,28.66997265815735,48.79915938655077,1739141189.2381008,28.66997265815735,8.429498199371,1739141189.2381024,28.66997265815735,2.1517066314395183,1739141189.2381039,28.66997265815735,2.4679659298230994,1739141189.238105,28.66997265815735,0.6108,1739141189.2381063,28.66997265815735,0.9315591045117966,1739141189.2381082,28.66997265815735,0.0,1739141189.2381096,28.66997265815735,-0.01916030588057083,1739141189.238111,28.66997265815735,1.545160856510248,1739141189.238112,28.66997265815735,0.9682663187353193 +1739141189.2575185,28.689972639083862,51.17513326610645,1739141189.257521,28.689972639083862,4.810181420314786,1739141189.2575235,28.689972639083862,54.77888671231988,1739141189.257526,28.689972639083862,48.79915938655077,1739141189.2575274,28.689972639083862,8.429498199371,1739141189.2575288,28.689972639083862,2.1517066314395183,1739141189.2575302,28.689972639083862,2.4679659298230994,1739141189.2575314,28.689972639083862,0.6108,1739141189.2575324,28.689972639083862,0.9315591045117966,1739141189.257534,28.689972639083862,0.0,1739141189.2575355,28.689972639083862,-0.036707214223522744,1739141189.2575364,28.689972639083862,1.545160856510248,1739141189.2575378,28.689972639083862,0.9682663187353193 +1739141189.2774355,28.709972620010376,51.17513326610645,1739141189.277438,28.709972620010376,4.810181420314786,1739141189.2774403,28.709972620010376,54.77888671231988,1739141189.277443,28.709972620010376,48.79915938655077,1739141189.2774441,28.709972620010376,8.429498199371,1739141189.2774456,28.709972620010376,2.1517066314395183,1739141189.2774475,28.709972620010376,2.4679659298230994,1739141189.2774487,28.709972620010376,0.6108,1739141189.2774498,28.709972620010376,0.9315591045117966,1739141189.2774513,28.709972620010376,0.0,1739141189.2774525,28.709972620010376,-0.036707214223522744,1739141189.277454,28.709972620010376,1.545160856510248,1739141189.277455,28.709972620010376,0.9682663187353193 +1739141189.2978737,28.72997260093689,51.17513326610645,1739141189.2978761,28.72997260093689,4.810181420314786,1739141189.297879,28.72997260093689,54.77888671231988,1739141189.2978818,28.72997260093689,48.79915938655077,1739141189.297883,28.72997260093689,8.429498199371,1739141189.297885,28.72997260093689,2.1517066314395183,1739141189.2978861,28.72997260093689,2.4679659298230994,1739141189.2978876,28.72997260093689,0.6108,1739141189.2978888,28.72997260093689,0.9315591045117966,1739141189.2978902,28.72997260093689,0.0,1739141189.2978916,28.72997260093689,-0.036707214223522744,1739141189.2978928,28.72997260093689,1.545160856510248,1739141189.2978942,28.72997260093689,0.9682663187353193 +1739141189.3183758,28.749972581863403,51.17513326610645,1739141189.318381,28.749972581863403,4.810181420314786,1739141189.3183844,28.749972581863403,54.77888671231988,1739141189.318387,28.749972581863403,48.79915938655077,1739141189.3183882,28.749972581863403,8.429498199371,1739141189.3183901,28.749972581863403,2.1517066314395183,1739141189.3183913,28.749972581863403,2.4679659298230994,1739141189.3183925,28.749972581863403,0.6108,1739141189.3183942,28.749972581863403,0.9315591045117966,1739141189.3183959,28.749972581863403,0.0,1739141189.3183975,28.749972581863403,-0.036707214223522744,1739141189.3183985,28.749972581863403,1.545160856510248,1739141189.3184001,28.749972581863403,0.9682663187353193 +1739141189.3374922,28.769972562789917,51.17513326610645,1739141189.3374946,28.769972562789917,4.810181420314786,1739141189.337497,28.769972562789917,54.77888671231988,1739141189.3374999,28.769972562789917,48.79915938655077,1739141189.3375013,28.769972562789917,8.429498199371,1739141189.3375027,28.769972562789917,2.1517066314395183,1739141189.337504,28.769972562789917,2.4679659298230994,1739141189.3375053,28.769972562789917,0.6108,1739141189.3375065,28.769972562789917,0.9315591045117966,1739141189.3375082,28.769972562789917,0.0,1739141189.3375096,28.769972562789917,-0.036707214223522744,1739141189.3375108,28.769972562789917,1.545160856510248,1739141189.3375123,28.769972562789917,0.9682663187353193 +1739141189.3573663,28.78997254371643,51.17652013182413,1739141189.357369,28.78997254371643,4.916510064309527,1739141189.3573716,28.78997254371643,54.93567737506436,1739141189.3573744,28.78997254371643,48.659615926905985,1739141189.3573759,28.78997254371643,8.471597921014528,1739141189.3573773,28.78997254371643,2.1868529022337895,1739141189.3573785,28.78997254371643,2.5094725923016505,1739141189.35738,28.78997254371643,0.6108,1739141189.357381,28.78997254371643,0.9162204246005722,1739141189.3573828,28.78997254371643,0.0,1739141189.357384,28.78997254371643,-0.058973886924125495,1739141189.3573852,28.78997254371643,1.5728851997568853,1739141189.3573866,28.78997254371643,0.9645911287514671 +1739141189.3773723,28.809972524642944,51.17652013182413,1739141189.3773744,28.809972524642944,4.916510064309527,1739141189.3773773,28.809972524642944,54.93567737506436,1739141189.3773801,28.809972524642944,48.659615926905985,1739141189.3773813,28.809972524642944,8.471597921014528,1739141189.377383,28.809972524642944,2.1868529022337895,1739141189.3773842,28.809972524642944,2.5094725923016505,1739141189.3773854,28.809972524642944,0.6108,1739141189.3773868,28.809972524642944,0.9162204246005722,1739141189.3773882,28.809972524642944,0.0,1739141189.3773897,28.809972524642944,-0.04837070415089495,1739141189.3773909,28.809972524642944,1.5728851997568853,1739141189.3773918,28.809972524642944,0.9645911287514671 +1739141189.3975363,28.829972505569458,51.17652013182413,1739141189.397539,28.829972505569458,4.916510064309527,1739141189.397542,28.829972505569458,54.93567737506436,1739141189.3975444,28.829972505569458,48.659615926905985,1739141189.3975458,28.829972505569458,8.471597921014528,1739141189.3975475,28.829972505569458,2.1868529022337895,1739141189.3975492,28.829972505569458,2.5094725923016505,1739141189.3975503,28.829972505569458,0.6108,1739141189.3975515,28.829972505569458,0.9162204246005722,1739141189.3975532,28.829972505569458,0.0,1739141189.3975546,28.829972505569458,-0.04837070415089495,1739141189.397556,28.829972505569458,1.5728851997568853,1739141189.3975573,28.829972505569458,0.9645911287514671 +1739141189.4174545,28.84997248649597,51.17652013182413,1739141189.417457,28.84997248649597,4.916510064309527,1739141189.41746,28.84997248649597,54.93567737506436,1739141189.4174628,28.84997248649597,48.659615926905985,1739141189.417464,28.84997248649597,8.471597921014528,1739141189.4174657,28.84997248649597,2.1868529022337895,1739141189.4174669,28.84997248649597,2.5094725923016505,1739141189.417468,28.84997248649597,0.6108,1739141189.4174695,28.84997248649597,0.9162204246005722,1739141189.417471,28.84997248649597,0.0,1739141189.4174724,28.84997248649597,-0.04837070415089495,1739141189.4174736,28.84997248649597,1.5728851997568853,1739141189.4174747,28.84997248649597,0.9645911287514671 +1739141189.437515,28.869972467422485,51.17652013182413,1739141189.4375174,28.869972467422485,4.916510064309527,1739141189.43752,28.869972467422485,54.93567737506436,1739141189.4375226,28.869972467422485,48.659615926905985,1739141189.437524,28.869972467422485,8.471597921014528,1739141189.4375255,28.869972467422485,2.1868529022337895,1739141189.4375272,28.869972467422485,2.5094725923016505,1739141189.4375284,28.869972467422485,0.6108,1739141189.4375296,28.869972467422485,0.9162204246005722,1739141189.4375312,28.869972467422485,0.0,1739141189.4375327,28.869972467422485,-0.04837070415089495,1739141189.437534,28.869972467422485,1.5728851997568853,1739141189.4375355,28.869972467422485,0.9645911287514671 +1739141189.457521,28.889972448349,51.174966831923435,1739141189.457523,28.889972448349,5.022328743129757,1739141189.4575257,28.889972448349,54.96665517208947,1739141189.4575286,28.889972448349,48.64539858876131,1739141189.4575298,28.889972448349,8.475685405731122,1739141189.4575317,28.889972448349,2.203000115523633,1739141189.457533,28.889972448349,2.4255037332002085,1739141189.4575346,28.889972448349,0.6108,1739141189.4575355,28.889972448349,0.9475166577835236,1739141189.4575372,28.889972448349,0.0,1739141189.4575386,28.889972448349,0.02167593933787714,1739141189.4575398,28.889972448349,1.6006095430035228,1739141189.4575408,28.889972448349,0.9591962796266694 +1739141189.477373,28.909972429275513,51.174966831923435,1739141189.4773753,28.909972429275513,5.022328743129757,1739141189.4773781,28.909972429275513,54.96665517208947,1739141189.4773808,28.909972429275513,48.64539858876131,1739141189.4773822,28.909972429275513,8.475685405731122,1739141189.4773836,28.909972429275513,2.203000115523633,1739141189.4773853,28.909972429275513,2.4255037332002085,1739141189.4773865,28.909972429275513,0.6108,1739141189.4773877,28.909972429275513,0.9475166577835236,1739141189.4773893,28.909972429275513,0.0,1739141189.4773905,28.909972429275513,-0.01167962184314586,1739141189.477392,28.909972429275513,1.6006095430035228,1739141189.4773932,28.909972429275513,0.9591962796266694 +1739141189.4978168,28.929972410202026,51.174966831923435,1739141189.4978197,28.929972410202026,5.022328743129757,1739141189.4978228,28.929972410202026,54.96665517208947,1739141189.497826,28.929972410202026,48.64539858876131,1739141189.4978273,28.929972410202026,8.475685405731122,1739141189.4978292,28.929972410202026,2.203000115523633,1739141189.4978306,28.929972410202026,2.4255037332002085,1739141189.4978323,28.929972410202026,0.6108,1739141189.4978335,28.929972410202026,0.9475166577835236,1739141189.4978352,28.929972410202026,0.0,1739141189.4978368,28.929972410202026,-0.01167962184314586,1739141189.497838,28.929972410202026,1.6006095430035228,1739141189.4978397,28.929972410202026,0.9591962796266694 +1739141189.5175214,28.94997239112854,51.174966831923435,1739141189.5175242,28.94997239112854,5.022328743129757,1739141189.5175273,28.94997239112854,54.96665517208947,1739141189.5175304,28.94997239112854,48.64539858876131,1739141189.517532,28.94997239112854,8.475685405731122,1739141189.517534,28.94997239112854,2.203000115523633,1739141189.5175354,28.94997239112854,2.4255037332002085,1739141189.5175369,28.94997239112854,0.6108,1739141189.517538,28.94997239112854,0.9475166577835236,1739141189.5175397,28.94997239112854,0.0,1739141189.5175414,28.94997239112854,-0.01167962184314586,1739141189.5175428,28.94997239112854,1.6006095430035228,1739141189.5175443,28.94997239112854,0.9591962796266694 +1739141189.537584,28.969972372055054,51.174966831923435,1739141189.5375867,28.969972372055054,5.022328743129757,1739141189.5375898,28.969972372055054,54.96665517208947,1739141189.537593,28.969972372055054,48.64539858876131,1739141189.537594,28.969972372055054,8.475685405731122,1739141189.537596,28.969972372055054,2.203000115523633,1739141189.5375974,28.969972372055054,2.4255037332002085,1739141189.537599,28.969972372055054,0.6108,1739141189.5376003,28.969972372055054,0.9475166577835236,1739141189.537602,28.969972372055054,0.0,1739141189.5376036,28.969972372055054,-0.01167962184314586,1739141189.5376048,28.969972372055054,1.6006095430035228,1739141189.5376062,28.969972372055054,0.9591962796266694 +1739141189.5577185,28.989972352981567,51.174966831923435,1739141189.5577233,28.989972352981567,5.022328743129757,1739141189.5577297,28.989972352981567,54.96665517208947,1739141189.557737,28.989972352981567,48.64539858876131,1739141189.5577393,28.989972352981567,8.475685405731122,1739141189.5577414,28.989972352981567,2.203000115523633,1739141189.5577426,28.989972352981567,2.4255037332002085,1739141189.557744,28.989972352981567,0.6108,1739141189.5577455,28.989972352981567,0.9475166577835236,1739141189.5577471,28.989972352981567,0.0,1739141189.5577488,28.989972352981567,-0.01167962184314586,1739141189.5577502,28.989972352981567,1.6006095430035228,1739141189.5577517,28.989972352981567,0.9591962796266694 +1739141189.5777977,29.00997233390808,51.17049326646794,1739141189.5778005,29.00997233390808,5.127741183849482,1739141189.5778039,29.00997233390808,55.17787894793873,1739141189.577807,29.00997233390808,48.442957927627894,1739141189.5778084,29.00997233390808,8.528996337034886,1739141189.5778103,29.00997233390808,2.246707049023576,1739141189.5778117,29.00997233390808,2.527429776177257,1739141189.577813,29.00997233390808,0.6108,1739141189.5778146,29.00997233390808,0.9096629082457454,1739141189.577816,29.00997233390808,0.0,1739141189.5778177,29.00997233390808,-0.08276687942042679,1739141189.5778189,29.00997233390808,1.6283338862501602,1739141189.5778203,29.00997233390808,0.9585786957192723 +1739141189.5991032,29.029972314834595,51.17049326646794,1739141189.599107,29.029972314834595,5.127741183849482,1739141189.599111,29.029972314834595,55.17787894793873,1739141189.599115,29.029972314834595,48.442957927627894,1739141189.5991192,29.029972314834595,8.528996337034886,1739141189.5991254,29.029972314834595,2.246707049023576,1739141189.5991302,29.029972314834595,2.527429776177257,1739141189.5991342,29.029972314834595,0.6108,1739141189.5991383,29.029972314834595,0.9096629082457454,1739141189.599143,29.029972314834595,0.0,1739141189.5991473,29.029972314834595,-0.048915787473526984,1739141189.5991511,29.029972314834595,1.6283338862501602,1739141189.599156,29.029972314834595,0.9585786957192723 +1739141189.6182704,29.04997229576111,51.17049326646794,1739141189.618274,29.04997229576111,5.127741183849482,1739141189.618278,29.04997229576111,55.17787894793873,1739141189.618282,29.04997229576111,48.442957927627894,1739141189.6182837,29.04997229576111,8.528996337034886,1739141189.6182861,29.04997229576111,2.246707049023576,1739141189.6182878,29.04997229576111,2.527429776177257,1739141189.61829,29.04997229576111,0.6108,1739141189.6182923,29.04997229576111,0.9096629082457454,1739141189.6182942,29.04997229576111,0.0,1739141189.6182964,29.04997229576111,-0.048915787473526984,1739141189.618298,29.04997229576111,1.6283338862501602,1739141189.6182997,29.04997229576111,0.9585786957192723 +1739141189.6390636,29.069972276687622,51.17049326646794,1739141189.6390698,29.069972276687622,5.127741183849482,1739141189.6390767,29.069972276687622,55.17787894793873,1739141189.6390843,29.069972276687622,48.442957927627894,1739141189.6390889,29.069972276687622,8.528996337034886,1739141189.6390946,29.069972276687622,2.246707049023576,1739141189.6390991,29.069972276687622,2.527429776177257,1739141189.639104,29.069972276687622,0.6108,1739141189.6391087,29.069972276687622,0.9096629082457454,1739141189.6391134,29.069972276687622,0.0,1739141189.6391182,29.069972276687622,-0.048915787473526984,1739141189.639123,29.069972276687622,1.6283338862501602,1739141189.6391275,29.069972276687622,0.9585786957192723 +1739141189.6583016,29.089972257614136,51.17049326646794,1739141189.658305,29.089972257614136,5.127741183849482,1739141189.658309,29.089972257614136,55.17787894793873,1739141189.6583126,29.089972257614136,48.442957927627894,1739141189.658314,29.089972257614136,8.528996337034886,1739141189.6583164,29.089972257614136,2.246707049023576,1739141189.6583178,29.089972257614136,2.527429776177257,1739141189.6583197,29.089972257614136,0.6108,1739141189.6583211,29.089972257614136,0.9096629082457454,1739141189.6583233,29.089972257614136,0.0,1739141189.658325,29.089972257614136,-0.048915787473526984,1739141189.6583269,29.089972257614136,1.6283338862501602,1739141189.6583283,29.089972257614136,0.9585786957192723 +1739141189.677407,29.10997223854065,51.16312550787167,1739141189.6774151,29.10997223854065,5.232634347003501,1739141189.6774192,29.10997223854065,55.24656008935475,1739141189.677424,29.10997223854065,48.39273404227614,1739141189.67744,29.10997223854065,8.541203531391215,1739141189.677442,29.10997223854065,2.267893498212781,1739141189.6774452,29.10997223854065,2.478574514229794,1739141189.677448,29.10997223854065,0.6108,1739141189.6774507,29.10997223854065,0.9276144704715766,1739141189.6774743,29.10997223854065,0.0,1739141189.6774762,29.10997223854065,-0.0038295845236234957,1739141189.6774793,29.10997223854065,1.6560582294967976,1739141189.6774821,29.10997223854065,0.9529136861725539 +1739141189.6974769,29.129972219467163,51.16312550787167,1739141189.6974792,29.129972219467163,5.232634347003501,1739141189.6974819,29.129972219467163,55.24656008935475,1739141189.6974845,29.129972219467163,48.39273404227614,1739141189.697486,29.129972219467163,8.541203531391215,1739141189.6974874,29.129972219467163,2.267893498212781,1739141189.6974885,29.129972219467163,2.478574514229794,1739141189.6974897,29.129972219467163,0.6108,1739141189.6974907,29.129972219467163,0.9276144704715766,1739141189.6974921,29.129972219467163,0.0,1739141189.6974938,29.129972219467163,-0.025299215700977262,1739141189.697495,29.129972219467163,1.6560582294967976,1739141189.6974962,29.129972219467163,0.9529136861725539 +1739141189.7174156,29.149972200393677,51.16312550787167,1739141189.7174177,29.149972200393677,5.232634347003501,1739141189.7174206,29.149972200393677,55.24656008935475,1739141189.7174234,29.149972200393677,48.39273404227614,1739141189.7174246,29.149972200393677,8.541203531391215,1739141189.7174265,29.149972200393677,2.267893498212781,1739141189.7174277,29.149972200393677,2.478574514229794,1739141189.717429,29.149972200393677,0.6108,1739141189.71743,29.149972200393677,0.9276144704715766,1739141189.7174318,29.149972200393677,0.0,1739141189.717433,29.149972200393677,-0.025299215700977262,1739141189.7174344,29.149972200393677,1.6560582294967976,1739141189.7174354,29.149972200393677,0.9529136861725539 +1739141189.7377267,29.16997218132019,51.16312550787167,1739141189.7377353,29.16997218132019,5.232634347003501,1739141189.7377386,29.16997218132019,55.24656008935475,1739141189.7377412,29.16997218132019,48.39273404227614,1739141189.7377427,29.16997218132019,8.541203531391215,1739141189.737744,29.16997218132019,2.267893498212781,1739141189.7377458,29.16997218132019,2.478574514229794,1739141189.737747,29.16997218132019,0.6108,1739141189.7377496,29.16997218132019,0.9276144704715766,1739141189.7377539,29.16997218132019,0.0,1739141189.7377582,29.16997218132019,-0.025299215700977262,1739141189.7377622,29.16997218132019,1.6560582294967976,1739141189.7377665,29.16997218132019,0.9529136861725539 +1739141189.7573411,29.189972162246704,51.16312550787167,1739141189.7573438,29.189972162246704,5.232634347003501,1739141189.7573464,29.189972162246704,55.24656008935475,1739141189.757349,29.189972162246704,48.39273404227614,1739141189.7573504,29.189972162246704,8.541203531391215,1739141189.7573519,29.189972162246704,2.267893498212781,1739141189.7573533,29.189972162246704,2.478574514229794,1739141189.7573545,29.189972162246704,0.6108,1739141189.7573557,29.189972162246704,0.9276144704715766,1739141189.7573574,29.189972162246704,0.0,1739141189.7573588,29.189972162246704,-0.025299215700977262,1739141189.75736,29.189972162246704,1.6560582294967976,1739141189.7573612,29.189972162246704,0.9529136861725539 +1739141189.777341,29.209972143173218,51.16312550787167,1739141189.7773433,29.209972143173218,5.232634347003501,1739141189.777346,29.209972143173218,55.24656008935475,1739141189.7773485,29.209972143173218,48.39273404227614,1739141189.77735,29.209972143173218,8.541203531391215,1739141189.7773514,29.209972143173218,2.267893498212781,1739141189.7773528,29.209972143173218,2.478574514229794,1739141189.777354,29.209972143173218,0.6108,1739141189.7773552,29.209972143173218,0.9276144704715766,1739141189.7773566,29.209972143173218,0.0,1739141189.7773578,29.209972143173218,-0.025299215700977262,1739141189.777359,29.209972143173218,1.6560582294967976,1739141189.7773602,29.209972143173218,0.9529136861725539 +1739141189.7975323,29.22997212409973,51.15289427293393,1739141189.797535,29.22997212409973,5.336852337615548,1739141189.7975383,29.22997212409973,55.41774141803676,1739141189.7975411,29.22997212409973,48.23181796810474,1739141189.7975426,29.22997212409973,8.573471630980361,1739141189.7975445,29.22997212409973,2.304995592566411,1739141189.7975457,29.22997212409973,2.5375351666759713,1739141189.797547,29.22997212409973,0.6108,1739141189.7975483,29.22997212409973,0.9059933301820404,1739141189.79755,29.22997212409973,0.0,1739141189.7975516,29.22997212409973,-0.062095810901519985,1739141189.7975528,29.22997212409973,1.683782572743435,1739141189.7975543,29.22997212409973,0.9505669441397229 +1739141189.817473,29.249972105026245,51.15289427293393,1739141189.8174756,29.249972105026245,5.336852337615548,1739141189.8174787,29.249972105026245,55.41774141803676,1739141189.8174815,29.249972105026245,48.23181796810474,1739141189.817483,29.249972105026245,8.573471630980361,1739141189.8174849,29.249972105026245,2.304995592566411,1739141189.8174863,29.249972105026245,2.5375351666759713,1739141189.8174877,29.249972105026245,0.6108,1739141189.8174891,29.249972105026245,0.9059933301820404,1739141189.8174906,29.249972105026245,0.0,1739141189.8174922,29.249972105026245,-0.044573613957682445,1739141189.8174934,29.249972105026245,1.683782572743435,1739141189.8174949,29.249972105026245,0.9505669441397229 +1739141189.8380373,29.26997208595276,51.15289427293393,1739141189.8380404,29.26997208595276,5.336852337615548,1739141189.8380435,29.26997208595276,55.41774141803676,1739141189.8380466,29.26997208595276,48.23181796810474,1739141189.8380482,29.26997208595276,8.573471630980361,1739141189.8380501,29.26997208595276,2.304995592566411,1739141189.8380516,29.26997208595276,2.5375351666759713,1739141189.8380532,29.26997208595276,0.6108,1739141189.8380544,29.26997208595276,0.9059933301820404,1739141189.838056,29.26997208595276,0.0,1739141189.838058,29.26997208595276,-0.044573613957682445,1739141189.8380594,29.26997208595276,1.683782572743435,1739141189.8380609,29.26997208595276,0.9505669441397229 +1739141189.857489,29.289972066879272,51.15289427293393,1739141189.8574917,29.289972066879272,5.336852337615548,1739141189.8574948,29.289972066879272,55.41774141803676,1739141189.8574977,29.289972066879272,48.23181796810474,1739141189.857499,29.289972066879272,8.573471630980361,1739141189.8575006,29.289972066879272,2.304995592566411,1739141189.8575022,29.289972066879272,2.5375351666759713,1739141189.8575034,29.289972066879272,0.6108,1739141189.8575048,29.289972066879272,0.9059933301820404,1739141189.8575063,29.289972066879272,0.0,1739141189.857508,29.289972066879272,-0.044573613957682445,1739141189.8575091,29.289972066879272,1.683782572743435,1739141189.8575103,29.289972066879272,0.9505669441397229 +1739141189.8774664,29.309972047805786,51.15289427293393,1739141189.8774686,29.309972047805786,5.336852337615548,1739141189.8774717,29.309972047805786,55.41774141803676,1739141189.8774745,29.309972047805786,48.23181796810474,1739141189.8774757,29.309972047805786,8.573471630980361,1739141189.8774776,29.309972047805786,2.304995592566411,1739141189.8774793,29.309972047805786,2.5375351666759713,1739141189.8774807,29.309972047805786,0.6108,1739141189.8774817,29.309972047805786,0.9059933301820404,1739141189.8774836,29.309972047805786,0.0,1739141189.877485,29.309972047805786,-0.044573613957682445,1739141189.8774862,29.309972047805786,1.683782572743435,1739141189.8774877,29.309972047805786,0.9505669441397229 +1739141189.8975823,29.3299720287323,51.139830607973366,1739141189.897585,29.3299720287323,5.440335086463552,1739141189.897588,29.3299720287323,55.499747154432825,1739141189.8975909,29.3299720287323,48.1659144132997,1739141189.8975923,29.3299720287323,8.584847597783384,1739141189.897594,29.3299720287323,2.3283193384602554,1739141189.8975954,29.3299720287323,2.5035162032554585,1739141189.8975966,29.3299720287323,0.6108,1739141189.897598,29.3299720287323,0.9184059732827452,1739141189.8975995,29.3299720287323,0.0,1739141189.8976011,29.3299720287323,-0.011251882854132839,1739141189.8976023,29.3299720287323,1.7115069159900724,1739141189.8976038,29.3299720287323,0.9455253550650773 +1739141189.9176633,29.349972009658813,51.139830607973366,1739141189.9176662,29.349972009658813,5.440335086463552,1739141189.9176695,29.349972009658813,55.499747154432825,1739141189.9176726,29.349972009658813,48.1659144132997,1739141189.9176743,29.349972009658813,8.584847597783384,1739141189.9176762,29.349972009658813,2.3283193384602554,1739141189.9176779,29.349972009658813,2.5035162032554585,1739141189.917679,29.349972009658813,0.6108,1739141189.9176807,29.349972009658813,0.9184059732827452,1739141189.9176824,29.349972009658813,0.0,1739141189.917684,29.349972009658813,-0.027119381782332086,1739141189.9176857,29.349972009658813,1.7115069159900724,1739141189.917687,29.349972009658813,0.9455253550650773 +1739141189.9381125,29.369971990585327,51.139830607973366,1739141189.9381173,29.369971990585327,5.440335086463552,1739141189.938122,29.369971990585327,55.499747154432825,1739141189.938126,29.369971990585327,48.1659144132997,1739141189.9381292,29.369971990585327,8.584847597783384,1739141189.9381318,29.369971990585327,2.3283193384602554,1739141189.938134,29.369971990585327,2.5035162032554585,1739141189.9381359,29.369971990585327,0.6108,1739141189.9381375,29.369971990585327,0.9184059732827452,1739141189.9381404,29.369971990585327,0.0,1739141189.9381433,29.369971990585327,-0.027119381782332086,1739141189.9381447,29.369971990585327,1.7115069159900724,1739141189.9381468,29.369971990585327,0.9455253550650773 +1739141189.9579139,29.38997197151184,51.139830607973366,1739141189.9579172,29.38997197151184,5.440335086463552,1739141189.9579208,29.38997197151184,55.499747154432825,1739141189.9579244,29.38997197151184,48.1659144132997,1739141189.957926,29.38997197151184,8.584847597783384,1739141189.9579284,29.38997197151184,2.3283193384602554,1739141189.95793,29.38997197151184,2.5035162032554585,1739141189.9579318,29.38997197151184,0.6108,1739141189.9579334,29.38997197151184,0.9184059732827452,1739141189.9579353,29.38997197151184,0.0,1739141189.9579372,29.38997197151184,-0.027119381782332086,1739141189.9579387,29.38997197151184,1.7115069159900724,1739141189.9579403,29.38997197151184,0.9455253550650773 +1739141189.977772,29.409971952438354,51.139830607973366,1739141189.977775,29.409971952438354,5.440335086463552,1739141189.9777787,29.409971952438354,55.499747154432825,1739141189.9777827,29.409971952438354,48.1659144132997,1739141189.9777856,29.409971952438354,8.584847597783384,1739141189.977788,29.409971952438354,2.3283193384602554,1739141189.9777913,29.409971952438354,2.5035162032554585,1739141189.977793,29.409971952438354,0.6108,1739141189.9777951,29.409971952438354,0.9184059732827452,1739141189.977797,29.409971952438354,0.0,1739141189.9777994,29.409971952438354,-0.027119381782332086,1739141189.9778008,29.409971952438354,1.7115069159900724,1739141189.9778025,29.409971952438354,0.9455253550650773 +1739141189.9984179,29.429971933364868,51.139830607973366,1739141189.998422,29.429971933364868,5.440335086463552,1739141189.9984264,29.429971933364868,55.499747154432825,1739141189.99843,29.429971933364868,48.1659144132997,1739141189.9984317,29.429971933364868,8.584847597783384,1739141189.998434,29.429971933364868,2.3283193384602554,1739141189.9984357,29.429971933364868,2.5035162032554585,1739141189.9984374,29.429971933364868,0.6108,1739141189.998439,29.429971933364868,0.9184059732827452,1739141189.9984412,29.429971933364868,0.0,1739141189.9984431,29.429971933364868,-0.027119381782332086,1739141189.9984448,29.429971933364868,1.7115069159900724,1739141189.9984467,29.429971933364868,0.9455253550650773 +1739141190.0179646,29.449971914291382,51.12396663083707,1739141190.0179675,29.449971914291382,5.543002379379919,1739141190.0179713,29.449971914291382,55.56869455529499,1739141190.0179746,29.449971914291382,48.10563240806925,1739141190.0179763,29.449971914291382,8.594011152346633,1739141190.0179784,29.449971914291382,2.3508110022985247,1739141190.0179799,29.449971914291382,2.4641497883664227,1739141190.0179818,29.449971914291382,0.6108,1739141190.0179832,29.449971914291382,0.9329821748902777,1739141190.0179853,29.449971914291382,0.0,1739141190.0179873,29.449971914291382,0.0057815236894621785,1739141190.0179892,29.449971914291382,1.7392312592367098,1739141190.0179906,29.449971914291382,0.9428677568709308 +1739141190.0383456,29.469971895217896,51.12396663083707,1739141190.0383499,29.469971895217896,5.543002379379919,1739141190.0383542,29.469971895217896,55.56869455529499,1739141190.038358,29.469971895217896,48.10563240806925,1739141190.0383615,29.469971895217896,8.594011152346633,1739141190.0383701,29.469971895217896,2.3508110022985247,1739141190.0383763,29.469971895217896,2.4641497883664227,1739141190.0383801,29.469971895217896,0.6108,1739141190.0383825,29.469971895217896,0.9329821748902777,1739141190.0383863,29.469971895217896,0.0,1739141190.0383897,29.469971895217896,-0.009885581980653146,1739141190.0383925,29.469971895217896,1.7392312592367098,1739141190.0383954,29.469971895217896,0.9428677568709308 +1739141190.0580056,29.48997187614441,51.12396663083707,1739141190.0580087,29.48997187614441,5.543002379379919,1739141190.0580122,29.48997187614441,55.56869455529499,1739141190.0580158,29.48997187614441,48.10563240806925,1739141190.0580175,29.48997187614441,8.594011152346633,1739141190.0580196,29.48997187614441,2.3508110022985247,1739141190.0580213,29.48997187614441,2.4641497883664227,1739141190.0580232,29.48997187614441,0.6108,1739141190.058025,29.48997187614441,0.9329821748902777,1739141190.058027,29.48997187614441,0.0,1739141190.0580292,29.48997187614441,-0.009885581980653146,1739141190.0580306,29.48997187614441,1.7392312592367098,1739141190.0580323,29.48997187614441,0.9428677568709308 +1739141190.078058,29.509971857070923,51.12396663083707,1739141190.078061,29.509971857070923,5.543002379379919,1739141190.078065,29.509971857070923,55.56869455529499,1739141190.0780683,29.509971857070923,48.10563240806925,1739141190.0780702,29.509971857070923,8.594011152346633,1739141190.0780723,29.509971857070923,2.3508110022985247,1739141190.0780742,29.509971857070923,2.4641497883664227,1739141190.078076,29.509971857070923,0.6108,1739141190.0780776,29.509971857070923,0.9329821748902777,1739141190.0780797,29.509971857070923,0.0,1739141190.0780816,29.509971857070923,-0.009885581980653146,1739141190.078083,29.509971857070923,1.7392312592367098,1739141190.0780847,29.509971857070923,0.9428677568709308 +1739141190.098292,29.529971837997437,51.12396663083707,1739141190.0982964,29.529971837997437,5.543002379379919,1739141190.0983002,29.529971837997437,55.56869455529499,1739141190.0983043,29.529971837997437,48.10563240806925,1739141190.0983064,29.529971837997437,8.594011152346633,1739141190.0983086,29.529971837997437,2.3508110022985247,1739141190.0983105,29.529971837997437,2.4641497883664227,1739141190.0983124,29.529971837997437,0.6108,1739141190.098314,29.529971837997437,0.9329821748902777,1739141190.098316,29.529971837997437,0.0,1739141190.0983183,29.529971837997437,-0.009885581980653146,1739141190.0983202,29.529971837997437,1.7392312592367098,1739141190.098322,29.529971837997437,0.9428677568709308 +1739141190.11808,29.54997181892395,51.10530154974893,1739141190.118083,29.54997181892395,5.644975703943379,1739141190.1180868,29.54997181892395,55.735430579858104,1739141190.1180904,29.54997181892395,47.943120859842416,1739141190.1180923,29.54997181892395,8.615248903267728,1739141190.1180944,29.54997181892395,2.387478032783703,1739141190.118096,29.54997181892395,2.522620331204207,1739141190.1180978,29.54997181892395,0.6108,1739141190.1180995,29.54997181892395,0.9114145821018085,1739141190.1181016,29.54997181892395,0.0,1739141190.1181035,29.54997181892395,-0.049262681964439795,1739141190.1181054,29.54997181892395,1.7669556024833473,1739141190.1181068,29.54997181892395,0.9419262547070205 +1739141190.1384354,29.569971799850464,51.10530154974893,1739141190.13844,29.569971799850464,5.644975703943379,1739141190.1384442,29.569971799850464,55.735430579858104,1739141190.1384485,29.569971799850464,47.943120859842416,1739141190.1384504,29.569971799850464,8.615248903267728,1739141190.1384525,29.569971799850464,2.387478032783703,1739141190.1384542,29.569971799850464,2.522620331204207,1739141190.1384563,29.569971799850464,0.6108,1739141190.1384578,29.569971799850464,0.9114145821018085,1739141190.1384604,29.569971799850464,0.0,1739141190.1384625,29.569971799850464,-0.030511672605212037,1739141190.1384642,29.569971799850464,1.7669556024833473,1739141190.1384664,29.569971799850464,0.9419262547070205 +1739141190.157903,29.589971780776978,51.10530154974893,1739141190.1579082,29.589971780776978,5.644975703943379,1739141190.1579173,29.589971780776978,55.735430579858104,1739141190.1579247,29.589971780776978,47.943120859842416,1739141190.1579287,29.589971780776978,8.615248903267728,1739141190.1579356,29.589971780776978,2.387478032783703,1739141190.1579442,29.589971780776978,2.522620331204207,1739141190.1579492,29.589971780776978,0.6108,1739141190.1579554,29.589971780776978,0.9114145821018085,1739141190.157961,29.589971780776978,0.0,1739141190.1579633,29.589971780776978,-0.030511672605212037,1739141190.157965,29.589971780776978,1.7669556024833473,1739141190.1579666,29.589971780776978,0.9419262547070205 +1739141190.17794,29.60997176170349,51.10530154974893,1739141190.1779435,29.60997176170349,5.644975703943379,1739141190.177947,29.60997176170349,55.735430579858104,1739141190.1779506,29.60997176170349,47.943120859842416,1739141190.1779525,29.60997176170349,8.615248903267728,1739141190.1779547,29.60997176170349,2.387478032783703,1739141190.177956,29.60997176170349,2.522620331204207,1739141190.1779575,29.60997176170349,0.6108,1739141190.1779594,29.60997176170349,0.9114145821018085,1739141190.177961,29.60997176170349,0.0,1739141190.177963,29.60997176170349,-0.030511672605212037,1739141190.1779647,29.60997176170349,1.7669556024833473,1739141190.1779664,29.60997176170349,0.9419262547070205 +1739141190.1983888,29.629971742630005,51.10530154974893,1739141190.1983929,29.629971742630005,5.644975703943379,1739141190.1983967,29.629971742630005,55.735430579858104,1739141190.1984003,29.629971742630005,47.943120859842416,1739141190.1984022,29.629971742630005,8.615248903267728,1739141190.1984043,29.629971742630005,2.387478032783703,1739141190.1984062,29.629971742630005,2.522620331204207,1739141190.198408,29.629971742630005,0.6108,1739141190.1984098,29.629971742630005,0.9114145821018085,1739141190.198412,29.629971742630005,0.0,1739141190.1984138,29.629971742630005,-0.030511672605212037,1739141190.1984155,29.629971742630005,1.7669556024833473,1739141190.1984172,29.629971742630005,0.9419262547070205 +1739141190.2178302,29.64997172355652,51.10530154974893,1739141190.2178333,29.64997172355652,5.644975703943379,1739141190.217837,29.64997172355652,55.735430579858104,1739141190.2178404,29.64997172355652,47.943120859842416,1739141190.217842,29.64997172355652,8.615248903267728,1739141190.2178452,29.64997172355652,2.387478032783703,1739141190.2178476,29.64997172355652,2.522620331204207,1739141190.217849,29.64997172355652,0.6108,1739141190.217851,29.64997172355652,0.9114145821018085,1739141190.2178526,29.64997172355652,0.0,1739141190.2178547,29.64997172355652,-0.030511672605212037,1739141190.2178574,29.64997172355652,1.7669556024833473,1739141190.2178607,29.64997172355652,0.9419262547070205 +1739141190.238446,29.669971704483032,51.08387181128817,1739141190.2384515,29.669971704483032,5.746136402955832,1739141190.238458,29.669971704483032,55.73707656877405,1739141190.2384653,29.669971704483032,47.95256728728105,1739141190.2384858,29.669971704483032,8.614186180180882,1739141190.2384887,29.669971704483032,2.4000468721131782,1739141190.2384903,29.669971704483032,2.4163965917805057,1739141190.2384923,29.669971704483032,0.6108,1739141190.238494,29.669971704483032,0.950974619669045,1739141190.238496,29.669971704483032,0.0,1739141190.238498,29.669971704483032,0.05210880445429861,1739141190.2384999,29.669971704483032,1.7946799457299847,1739141190.2385013,29.669971704483032,0.9382089191823983 +1739141190.2579005,29.689971685409546,51.08387181128817,1739141190.2579038,29.689971685409546,5.746136402955832,1739141190.2579072,29.689971685409546,55.73707656877405,1739141190.2579107,29.689971685409546,47.95256728728105,1739141190.2579126,29.689971685409546,8.614186180180882,1739141190.2579145,29.689971685409546,2.4000468721131782,1739141190.2579167,29.689971685409546,2.4163965917805057,1739141190.2579188,29.689971685409546,0.6108,1739141190.2579203,29.689971685409546,0.950974619669045,1739141190.2579224,29.689971685409546,0.0,1739141190.257924,29.689971685409546,0.012765700486646603,1739141190.2579257,29.689971685409546,1.7946799457299847,1739141190.2579274,29.689971685409546,0.9382089191823983 +1739141190.2779372,29.70997166633606,51.08387181128817,1739141190.2779403,29.70997166633606,5.746136402955832,1739141190.2779438,29.70997166633606,55.73707656877405,1739141190.2779474,29.70997166633606,47.95256728728105,1739141190.277949,29.70997166633606,8.614186180180882,1739141190.2779515,29.70997166633606,2.4000468721131782,1739141190.2779534,29.70997166633606,2.4163965917805057,1739141190.2779548,29.70997166633606,0.6108,1739141190.2779562,29.70997166633606,0.950974619669045,1739141190.2779584,29.70997166633606,0.0,1739141190.2779603,29.70997166633606,0.012765700486646603,1739141190.2779617,29.70997166633606,1.7946799457299847,1739141190.2779632,29.70997166633606,0.9382089191823983 +1739141190.2986205,29.729971647262573,51.08387181128817,1739141190.2986236,29.729971647262573,5.746136402955832,1739141190.2986343,29.729971647262573,55.73707656877405,1739141190.2986379,29.729971647262573,47.95256728728105,1739141190.2986393,29.729971647262573,8.614186180180882,1739141190.2986414,29.729971647262573,2.4000468721131782,1739141190.2986426,29.729971647262573,2.4163965917805057,1739141190.2986443,29.729971647262573,0.6108,1739141190.2986455,29.729971647262573,0.950974619669045,1739141190.2986474,29.729971647262573,0.0,1739141190.2986488,29.729971647262573,0.012765700486646603,1739141190.2986503,29.729971647262573,1.7946799457299847,1739141190.298652,29.729971647262573,0.9382089191823983 +1739141190.3176997,29.749971628189087,51.08387181128817,1739141190.3177028,29.749971628189087,5.746136402955832,1739141190.3177056,29.749971628189087,55.73707656877405,1739141190.317709,29.749971628189087,47.95256728728105,1739141190.3177109,29.749971628189087,8.614186180180882,1739141190.3177123,29.749971628189087,2.4000468721131782,1739141190.317714,29.749971628189087,2.4163965917805057,1739141190.3177152,29.749971628189087,0.6108,1739141190.3177161,29.749971628189087,0.950974619669045,1739141190.317718,29.749971628189087,0.0,1739141190.3177195,29.749971628189087,0.012765700486646603,1739141190.317721,29.749971628189087,1.7946799457299847,1739141190.317722,29.749971628189087,0.9382089191823983 +1739141190.3377154,29.7699716091156,51.05967092345398,1739141190.337718,29.7699716091156,5.846554939749364,1739141190.3377209,29.7699716091156,55.73872805215296,1739141190.3377235,29.7699716091156,47.94569590329572,1739141190.337725,29.7699716091156,8.614959210879231,1739141190.3377264,29.7699716091156,2.414873812037481,1739141190.337728,29.7699716091156,2.326699994666288,1739141190.3377292,29.7699716091156,0.6108,1739141190.3377304,29.7699716091156,0.985713764724738,1739141190.3377318,29.7699716091156,0.0,1739141190.3377333,29.7699716091156,0.07573657618552185,1739141190.3377347,29.7699716091156,1.822404288976622,1739141190.3377357,29.7699716091156,0.939963334803785 +1739141190.3644106,29.789971590042114,51.05967092345398,1739141190.3644247,29.789971590042114,5.846554939749364,1739141190.36444,29.789971590042114,55.73872805215296,1739141190.3644545,29.789971590042114,47.94569590329572,1739141190.3644614,29.789971590042114,8.614959210879231,1739141190.3644755,29.789971590042114,2.414873812037481,1739141190.3644865,29.789971590042114,2.326699994666288,1739141190.3644936,29.789971590042114,0.6108,1739141190.3645008,29.789971590042114,0.985713764724738,1739141190.3645105,29.789971590042114,0.0,1739141190.3645198,29.789971590042114,0.04575042992095302,1739141190.364529,29.789971590042114,1.822404288976622,1739141190.3645372,29.789971590042114,0.939963334803785 +1739141190.3881657,29.79997158050537,51.05967092345398,1739141190.3881762,29.79997158050537,5.846554939749364,1739141190.3881874,29.79997158050537,55.73872805215296,1739141190.388198,29.79997158050537,47.94569590329572,1739141190.3882027,29.79997158050537,8.614959210879231,1739141190.3882089,29.79997158050537,2.414873812037481,1739141190.3882139,29.79997158050537,2.326699994666288,1739141190.3882182,29.79997158050537,0.6108,1739141190.388223,29.79997158050537,0.985713764724738,1739141190.3882294,29.79997158050537,0.0,1739141190.3882349,29.79997158050537,0.04575042992095302,1739141190.3882399,29.79997158050537,1.822404288976622,1739141190.3882444,29.79997158050537,0.939963334803785 +1739141190.4042876,29.819971561431885,51.05967092345398,1739141190.4042943,29.819971561431885,5.846554939749364,1739141190.4043007,29.819971561431885,55.73872805215296,1739141190.4043062,29.819971561431885,47.94569590329572,1739141190.404309,29.819971561431885,8.614959210879231,1739141190.4043126,29.819971561431885,2.414873812037481,1739141190.4043155,29.819971561431885,2.326699994666288,1739141190.4043179,29.819971561431885,0.6108,1739141190.4043205,29.819971561431885,0.985713764724738,1739141190.4043236,29.819971561431885,0.0,1739141190.4043267,29.819971561431885,0.04575042992095302,1739141190.4043293,29.819971561431885,1.822404288976622,1739141190.4043317,29.819971561431885,0.939963334803785 +1739141190.422612,29.849971532821655,51.05967092345398,1739141190.4226148,29.849971532821655,5.846554939749364,1739141190.422618,29.849971532821655,55.73872805215296,1739141190.4226213,29.849971532821655,47.94569590329572,1739141190.4226227,29.849971532821655,8.614959210879231,1739141190.4226248,29.849971532821655,2.414873812037481,1739141190.4226263,29.849971532821655,2.326699994666288,1739141190.422628,29.849971532821655,0.6108,1739141190.4226294,29.849971532821655,0.985713764724738,1739141190.4226313,29.849971532821655,0.0,1739141190.4226327,29.849971532821655,0.04575042992095302,1739141190.4226346,29.849971532821655,1.822404288976622,1739141190.422636,29.849971532821655,0.939963334803785 +1739141190.4435031,29.86997151374817,51.05967092345398,1739141190.4435067,29.86997151374817,5.846554939749364,1739141190.44351,29.86997151374817,55.73872805215296,1739141190.443513,29.86997151374817,47.94569590329572,1739141190.443514,29.86997151374817,8.614959210879231,1739141190.4435163,29.86997151374817,2.414873812037481,1739141190.4435177,29.86997151374817,2.326699994666288,1739141190.4435189,29.86997151374817,0.6108,1739141190.4435203,29.86997151374817,0.985713764724738,1739141190.443522,29.86997151374817,0.0,1739141190.4435236,29.86997151374817,0.04575042992095302,1739141190.443525,29.86997151374817,1.822404288976622,1739141190.443526,29.86997151374817,0.939963334803785 +1739141190.4643655,29.889971494674683,51.03258853501855,1739141190.4643688,29.889971494674683,5.946656669663424,1739141190.4643734,29.889971494674683,56.04618619334989,1739141190.464378,29.889971494674683,47.62231983689352,1739141190.464381,29.889971494674683,8.637958316750979,1739141190.4643846,29.889971494674683,2.4734867487125283,1739141190.464388,29.889971494674683,2.536056553460803,1739141190.464391,29.889971494674683,0.6108,1739141190.464394,29.889971494674683,0.9065293341592731,1739141190.4643977,29.889971494674683,0.0,1739141190.464401,29.889971494674683,-0.11613197153204104,1739141190.4644039,29.889971494674683,1.8501286322232595,1739141190.4644072,29.889971494674683,0.9455744093482824 +1739141190.484605,29.909971475601196,51.03258853501855,1739141190.4846087,29.909971475601196,5.946656669663424,1739141190.4846137,29.909971475601196,56.04618619334989,1739141190.4846194,29.909971475601196,47.62231983689352,1739141190.4846222,29.909971475601196,8.637958316750979,1739141190.4846265,29.909971475601196,2.4734867487125283,1739141190.48463,29.909971475601196,2.536056553460803,1739141190.4846337,29.909971475601196,0.6108,1739141190.4846582,29.909971475601196,0.9065293341592731,1739141190.484662,29.909971475601196,0.0,1739141190.4846659,29.909971475601196,-0.03904507518900935,1739141190.4846694,29.909971475601196,1.8501286322232595,1739141190.484673,29.909971475601196,0.9455744093482824 +1739141190.5083256,29.92997145652771,51.03258853501855,1739141190.5083447,29.92997145652771,5.946656669663424,1739141190.5083673,29.92997145652771,56.04618619334989,1739141190.508391,29.92997145652771,47.62231983689352,1739141190.5084043,29.92997145652771,8.637958316750979,1739141190.5084176,29.92997145652771,2.4734867487125283,1739141190.5084321,29.92997145652771,2.536056553460803,1739141190.508447,29.92997145652771,0.6108,1739141190.5084636,29.92997145652771,0.9065293341592731,1739141190.5084798,29.92997145652771,0.0,1739141190.508497,29.92997145652771,-0.03904507518900935,1739141190.5085108,29.92997145652771,1.8501286322232595,1739141190.5085273,29.92997145652771,0.9455744093482824 +1739141190.5307317,29.949971437454224,51.03258853501855,1739141190.5307364,29.949971437454224,5.946656669663424,1739141190.5307415,29.949971437454224,56.04618619334989,1739141190.530747,29.949971437454224,47.62231983689352,1739141190.5307493,29.949971437454224,8.637958316750979,1739141190.5307524,29.949971437454224,2.4734867487125283,1739141190.5307553,29.949971437454224,2.536056553460803,1739141190.5307577,29.949971437454224,0.6108,1739141190.5307603,29.949971437454224,0.9065293341592731,1739141190.5307631,29.949971437454224,0.0,1739141190.5307658,29.949971437454224,-0.03904507518900935,1739141190.5307684,29.949971437454224,1.8501286322232595,1739141190.5307708,29.949971437454224,0.9455744093482824 +1739141190.5467262,29.969971418380737,51.03258853501855,1739141190.5467312,29.969971418380737,5.946656669663424,1739141190.546737,29.969971418380737,56.04618619334989,1739141190.5467422,29.969971418380737,47.62231983689352,1739141190.5467453,29.969971418380737,8.637958316750979,1739141190.5467484,29.969971418380737,2.4734867487125283,1739141190.546751,29.969971418380737,2.536056553460803,1739141190.546754,29.969971418380737,0.6108,1739141190.5467563,29.969971418380737,0.9065293341592731,1739141190.5467596,29.969971418380737,0.0,1739141190.5467622,29.969971418380737,-0.03904507518900935,1739141190.546765,29.969971418380737,1.8501286322232595,1739141190.5467675,29.969971418380737,0.9455744093482824 +1739141190.5702221,29.98997139930725,51.002730347880444,1739141190.5702279,29.98997139930725,6.046016362831844,1739141190.5702355,29.98997139930725,56.144349821183475,1739141190.570244,29.98997139930725,47.53913440660372,1739141190.5702486,29.98997139930725,8.64088267325054,1739141190.5702548,29.98997139930725,2.4986147940305847,1739141190.5702603,29.98997139930725,2.5172849254130476,1739141190.5702658,29.98997139930725,0.6108,1739141190.5702713,29.98997139930725,0.9133617658216036,1739141190.570277,29.98997139930725,0.0,1739141190.5702825,29.98997139930725,-0.016504297292109577,1739141190.570288,29.98997139930725,1.877852975469897,1739141190.5702932,29.98997139930725,0.9405997722360983 +1739141190.588239,30.009971380233765,51.002730347880444,1739141190.588243,30.009971380233765,6.046016362831844,1739141190.5882475,30.009971380233765,56.144349821183475,1739141190.5882516,30.009971380233765,47.53913440660372,1739141190.5882537,30.009971380233765,8.64088267325054,1739141190.5882566,30.009971380233765,2.4986147940305847,1739141190.5882585,30.009971380233765,2.5172849254130476,1739141190.5882607,30.009971380233765,0.6108,1739141190.5882626,30.009971380233765,0.9133617658216036,1739141190.588265,30.009971380233765,0.0,1739141190.5882673,30.009971380233765,-0.027238006414494698,1739141190.5882692,30.009971380233765,1.877852975469897,1739141190.5882714,30.009971380233765,0.9405997722360983 +1739141190.607061,30.02997136116028,51.002730347880444,1739141190.6070647,30.02997136116028,6.046016362831844,1739141190.6070697,30.02997136116028,56.144349821183475,1739141190.607074,30.02997136116028,47.53913440660372,1739141190.6070764,30.02997136116028,8.64088267325054,1739141190.607079,30.02997136116028,2.4986147940305847,1739141190.607081,30.02997136116028,2.5172849254130476,1739141190.607083,30.02997136116028,0.6108,1739141190.607085,30.02997136116028,0.9133617658216036,1739141190.6070876,30.02997136116028,0.0,1739141190.6070898,30.02997136116028,-0.027238006414494698,1739141190.6070917,30.02997136116028,1.877852975469897,1739141190.6070938,30.02997136116028,0.9405997722360983 +1739141190.6259098,30.049971342086792,51.002730347880444,1739141190.6259127,30.049971342086792,6.046016362831844,1739141190.6259158,30.049971342086792,56.144349821183475,1739141190.6259186,30.049971342086792,47.53913440660372,1739141190.6259203,30.049971342086792,8.64088267325054,1739141190.625922,30.049971342086792,2.4986147940305847,1739141190.6259239,30.049971342086792,2.5172849254130476,1739141190.625925,30.049971342086792,0.6108,1739141190.6259267,30.049971342086792,0.9133617658216036,1739141190.6259284,30.049971342086792,0.0,1739141190.6259303,30.049971342086792,-0.027238006414494698,1739141190.6259315,30.049971342086792,1.877852975469897,1739141190.6259332,30.049971342086792,0.9405997722360983 +1739141190.645453,30.069971323013306,51.002730347880444,1739141190.6454563,30.069971323013306,6.046016362831844,1739141190.6454594,30.069971323013306,56.144349821183475,1739141190.6454623,30.069971323013306,47.53913440660372,1739141190.6454635,30.069971323013306,8.64088267325054,1739141190.6454654,30.069971323013306,2.4986147940305847,1739141190.6454666,30.069971323013306,2.5172849254130476,1739141190.645468,30.069971323013306,0.6108,1739141190.6454692,30.069971323013306,0.9133617658216036,1739141190.6454704,30.069971323013306,0.0,1739141190.645472,30.069971323013306,-0.027238006414494698,1739141190.6454732,30.069971323013306,1.877852975469897,1739141190.6454747,30.069971323013306,0.9405997722360983 +1739141190.6659658,30.08997130393982,51.002730347880444,1739141190.6659684,30.08997130393982,6.046016362831844,1739141190.6659708,30.08997130393982,56.144349821183475,1739141190.665973,30.08997130393982,47.53913440660372,1739141190.6659746,30.08997130393982,8.64088267325054,1739141190.6659758,30.08997130393982,2.4986147940305847,1739141190.665977,30.08997130393982,2.5172849254130476,1739141190.6659782,30.08997130393982,0.6108,1739141190.6659794,30.08997130393982,0.9133617658216036,1739141190.6659806,30.08997130393982,0.0,1739141190.665982,30.08997130393982,-0.027238006414494698,1739141190.6659834,30.08997130393982,1.877852975469897,1739141190.6659846,30.08997130393982,0.9405997722360983 +1739141190.685335,30.109971284866333,50.97026622166127,1739141190.6853375,30.109971284866333,6.144094522787874,1739141190.6853402,30.109971284866333,56.30377018504346,1739141190.6853428,30.109971284866333,47.388709750541835,1739141190.685344,30.109971284866333,8.641637304494125,1739141190.6853456,30.109971284866333,2.5326578769816517,1739141190.6853468,30.109971284866333,2.562118186023766,1739141190.685348,30.109971284866333,0.6108,1739141190.6853492,30.109971284866333,0.8971281674817339,1739141190.685351,30.109971284866333,0.0,1739141190.685352,30.109971284866333,-0.052515369935356666,1739141190.6853533,30.109971284866333,1.9055773187165344,1739141190.6853545,30.109971284866333,0.9376066916323211 +1739141190.7057173,30.129971265792847,50.97026622166127,1739141190.7057195,30.129971265792847,6.144094522787874,1739141190.705722,30.129971265792847,56.30377018504346,1739141190.7057247,30.129971265792847,47.388709750541835,1739141190.705726,30.129971265792847,8.641637304494125,1739141190.7057276,30.129971265792847,2.5326578769816517,1739141190.7057288,30.129971265792847,2.562118186023766,1739141190.70573,30.129971265792847,0.6108,1739141190.7057312,30.129971265792847,0.8971281674817339,1739141190.7057326,30.129971265792847,0.0,1739141190.7057338,30.129971265792847,-0.04047852415058728,1739141190.7057352,30.129971265792847,1.9055773187165344,1739141190.7057362,30.129971265792847,0.9376066916323211 +1739141190.7256804,30.14997124671936,50.97026622166127,1739141190.7256827,30.14997124671936,6.144094522787874,1739141190.7256854,30.14997124671936,56.30377018504346,1739141190.7256877,30.14997124671936,47.388709750541835,1739141190.7256892,30.14997124671936,8.641637304494125,1739141190.7256906,30.14997124671936,2.5326578769816517,1739141190.7256916,30.14997124671936,2.562118186023766,1739141190.725693,30.14997124671936,0.6108,1739141190.725694,30.14997124671936,0.8971281674817339,1739141190.7256954,30.14997124671936,0.0,1739141190.7256968,30.14997124671936,-0.04047852415058728,1739141190.7256978,30.14997124671936,1.9055773187165344,1739141190.7256987,30.14997124671936,0.9376066916323211 +1739141190.7456236,30.169971227645874,50.97026622166127,1739141190.745626,30.169971227645874,6.144094522787874,1739141190.7456286,30.169971227645874,56.30377018504346,1739141190.7456312,30.169971227645874,47.388709750541835,1739141190.7456324,30.169971227645874,8.641637304494125,1739141190.745634,30.169971227645874,2.5326578769816517,1739141190.7456353,30.169971227645874,2.562118186023766,1739141190.7456367,30.169971227645874,0.6108,1739141190.745638,30.169971227645874,0.8971281674817339,1739141190.745639,30.169971227645874,0.0,1739141190.7456408,30.169971227645874,-0.04047852415058728,1739141190.7456422,30.169971227645874,1.9055773187165344,1739141190.7456434,30.169971227645874,0.9376066916323211 +1739141190.7657754,30.189971208572388,50.97026622166127,1739141190.7657778,30.189971208572388,6.144094522787874,1739141190.7657804,30.189971208572388,56.30377018504346,1739141190.765783,30.189971208572388,47.388709750541835,1739141190.7657845,30.189971208572388,8.641637304494125,1739141190.7657862,30.189971208572388,2.5326578769816517,1739141190.7657874,30.189971208572388,2.562118186023766,1739141190.7657883,30.189971208572388,0.6108,1739141190.7657897,30.189971208572388,0.8971281674817339,1739141190.7657914,30.189971208572388,0.0,1739141190.7657928,30.189971208572388,-0.04047852415058728,1739141190.765794,30.189971208572388,1.9055773187165344,1739141190.765795,30.189971208572388,0.9376066916323211 +1739141190.785647,30.2099711894989,50.9352347597052,1739141190.785649,30.2099711894989,6.240852413381328,1739141190.7856517,30.2099711894989,56.388923142926515,1739141190.7856543,30.2099711894989,47.31719752648849,1739141190.7856555,30.2099711894989,8.640440962217653,1739141190.7856574,30.2099711894989,2.5559734948096096,1739141190.7856586,30.2099711894989,2.5319688206938884,1739141190.7856596,30.2099711894989,0.6108,1739141190.785661,30.2099711894989,0.9080128065018298,1739141190.7856624,30.2099711894989,0.0,1739141190.7856638,30.2099711894989,-0.01102543817552014,1739141190.785665,30.2099711894989,1.9333016619631718,1739141190.785666,30.2099711894989,0.9330635307193393 +1739141190.805513,30.229971170425415,50.9352347597052,1739141190.8055153,30.229971170425415,6.240852413381328,1739141190.8055184,30.229971170425415,56.388923142926515,1739141190.8055205,30.229971170425415,47.31719752648849,1739141190.8055222,30.229971170425415,8.640440962217653,1739141190.8055236,30.229971170425415,2.5559734948096096,1739141190.805525,30.229971170425415,2.5319688206938884,1739141190.8055263,30.229971170425415,0.6108,1739141190.8055272,30.229971170425415,0.9080128065018298,1739141190.8055289,30.229971170425415,0.0,1739141190.8055303,30.229971170425415,-0.025050724217509535,1739141190.8055317,30.229971170425415,1.9333016619631718,1739141190.8055327,30.229971170425415,0.9330635307193393 +1739141190.825307,30.24997115135193,50.9352347597052,1739141190.8253093,30.24997115135193,6.240852413381328,1739141190.8253117,30.24997115135193,56.388923142926515,1739141190.8253145,30.24997115135193,47.31719752648849,1739141190.825316,30.24997115135193,8.640440962217653,1739141190.8253174,30.24997115135193,2.5559734948096096,1739141190.8253186,30.24997115135193,2.5319688206938884,1739141190.8253198,30.24997115135193,0.6108,1739141190.8253212,30.24997115135193,0.9080128065018298,1739141190.8253229,30.24997115135193,0.0,1739141190.825324,30.24997115135193,-0.025050724217509535,1739141190.8253253,30.24997115135193,1.9333016619631718,1739141190.8253267,30.24997115135193,0.9330635307193393 +1739141190.8459988,30.269971132278442,50.9352347597052,1739141190.8460011,30.269971132278442,6.240852413381328,1739141190.846004,30.269971132278442,56.388923142926515,1739141190.8460066,30.269971132278442,47.31719752648849,1739141190.8460083,30.269971132278442,8.640440962217653,1739141190.84601,30.269971132278442,2.5559734948096096,1739141190.8460112,30.269971132278442,2.5319688206938884,1739141190.8460124,30.269971132278442,0.6108,1739141190.8460135,30.269971132278442,0.9080128065018298,1739141190.846015,30.269971132278442,0.0,1739141190.8460162,30.269971132278442,-0.025050724217509535,1739141190.8460178,30.269971132278442,1.9333016619631718,1739141190.8460188,30.269971132278442,0.9330635307193393 +1739141190.8657608,30.289971113204956,50.9352347597052,1739141190.8657634,30.289971113204956,6.240852413381328,1739141190.865766,30.289971113204956,56.388923142926515,1739141190.865769,30.289971113204956,47.31719752648849,1739141190.8657706,30.289971113204956,8.640440962217653,1739141190.865772,30.289971113204956,2.5559734948096096,1739141190.8657732,30.289971113204956,2.5319688206938884,1739141190.8657746,30.289971113204956,0.6108,1739141190.8657756,30.289971113204956,0.9080128065018298,1739141190.8657773,30.289971113204956,0.0,1739141190.8657787,30.289971113204956,-0.025050724217509535,1739141190.8657799,30.289971113204956,1.9333016619631718,1739141190.865781,30.289971113204956,0.9330635307193393 +1739141190.8852973,30.30997109413147,50.9352347597052,1739141190.8853,30.30997109413147,6.240852413381328,1739141190.8853025,30.30997109413147,56.388923142926515,1739141190.8853052,30.30997109413147,47.31719752648849,1739141190.8853064,30.30997109413147,8.640440962217653,1739141190.8853078,30.30997109413147,2.5559734948096096,1739141190.8853092,30.30997109413147,2.5319688206938884,1739141190.8853104,30.30997109413147,0.6108,1739141190.8853118,30.30997109413147,0.9080128065018298,1739141190.8853133,30.30997109413147,0.0,1739141190.8853145,30.30997109413147,-0.025050724217509535,1739141190.885316,30.30997109413147,1.9333016619631718,1739141190.885317,30.30997109413147,0.9330635307193393 +1739141190.9054384,30.329971075057983,50.89767383371573,1739141190.905441,30.329971075057983,6.336246872002782,1739141190.905444,30.329971075057983,56.47354941049702,1739141190.9054468,30.329971075057983,47.240019677315075,1739141190.9054482,30.329971075057983,8.637924086016158,1739141190.9054496,30.329971075057983,2.5799237354605564,1739141190.905451,30.329971075057983,2.5071180494517464,1739141190.9054523,30.329971075057983,0.6108,1739141190.9054537,30.329971075057983,0.917083743180747,1739141190.905455,30.329971075057983,0.0,1739141190.9054563,30.329971075057983,-0.0030228671963116634,1739141190.9054575,30.329971075057983,1.9610260052098092,1739141190.9054587,30.329971075057983,0.9305960713413827 +1739141190.9258301,30.349971055984497,50.89767383371573,1739141190.9258327,30.349971055984497,6.336246872002782,1739141190.9258354,30.349971055984497,56.47354941049702,1739141190.9258378,30.349971055984497,47.240019677315075,1739141190.9258394,30.349971055984497,8.637924086016158,1739141190.9258409,30.349971055984497,2.5799237354605564,1739141190.9258423,30.349971055984497,2.5071180494517464,1739141190.9258435,30.349971055984497,0.6108,1739141190.9258444,30.349971055984497,0.917083743180747,1739141190.925846,30.349971055984497,0.0,1739141190.9258473,30.349971055984497,-0.013512328160635634,1739141190.9258482,30.349971055984497,1.9610260052098092,1739141190.92585,30.349971055984497,0.9305960713413827 +1739141190.945673,30.36997103691101,50.89767383371573,1739141190.9456754,30.36997103691101,6.336246872002782,1739141190.945678,30.36997103691101,56.47354941049702,1739141190.9456806,30.36997103691101,47.240019677315075,1739141190.9456823,30.36997103691101,8.637924086016158,1739141190.9456837,30.36997103691101,2.5799237354605564,1739141190.945685,30.36997103691101,2.5071180494517464,1739141190.9456863,30.36997103691101,0.6108,1739141190.9456873,30.36997103691101,0.917083743180747,1739141190.9456894,30.36997103691101,0.0,1739141190.9456906,30.36997103691101,-0.013512328160635634,1739141190.9456916,30.36997103691101,1.9610260052098092,1739141190.945693,30.36997103691101,0.9305960713413827 +1739141190.9654498,30.389971017837524,50.89767383371573,1739141190.965452,30.389971017837524,6.336246872002782,1739141190.9654546,30.389971017837524,56.47354941049702,1739141190.965457,30.389971017837524,47.240019677315075,1739141190.9654603,30.389971017837524,8.637924086016158,1739141190.9654646,30.389971017837524,2.5799237354605564,1739141190.9654667,30.389971017837524,2.5071180494517464,1739141190.9654684,30.389971017837524,0.6108,1739141190.9654717,30.389971017837524,0.917083743180747,1739141190.9654748,30.389971017837524,0.0,1739141190.9654777,30.389971017837524,-0.013512328160635634,1739141190.96548,30.389971017837524,1.9610260052098092,1739141190.9654841,30.389971017837524,0.9305960713413827 +1739141190.9858341,30.409970998764038,50.89767383371573,1739141190.9858365,30.409970998764038,6.336246872002782,1739141190.9858394,30.409970998764038,56.47354941049702,1739141190.985842,30.409970998764038,47.240019677315075,1739141190.9858434,30.409970998764038,8.637924086016158,1739141190.985845,30.409970998764038,2.5799237354605564,1739141190.9858463,30.409970998764038,2.5071180494517464,1739141190.9858475,30.409970998764038,0.6108,1739141190.9858487,30.409970998764038,0.917083743180747,1739141190.98585,30.409970998764038,0.0,1739141190.9858518,30.409970998764038,-0.013512328160635634,1739141190.985853,30.409970998764038,1.9610260052098092,1739141190.9858541,30.409970998764038,0.9305960713413827 +1739141191.0134642,30.42997097969055,50.85757210663852,1739141191.0134735,30.42997097969055,6.430353396032649,1739141191.0134835,30.42997097969055,56.58168302202121,1739141191.0134933,30.42997097969055,47.13617935407062,1739141191.0134978,30.42997097969055,8.632598941234392,1739141191.0135038,30.42997097969055,2.6072392464831777,1739141191.0135086,30.42997097969055,2.5071874764288977,1739141191.0135133,30.42997097969055,0.6108,1739141191.0135176,30.42997097969055,0.9170582753935455,1739141191.0135233,30.42997097969055,0.0,1739141191.0135283,30.42997097969055,-0.010915688182879602,1739141191.013533,30.42997097969055,1.9887503484564466,1739141191.013538,30.42997097969055,0.9292104594216116 +1739141191.034369,30.459970951080322,50.85757210663852,1739141191.0343845,30.459970951080322,6.430353396032649,1739141191.034403,30.459970951080322,56.58168302202121,1739141191.0344248,30.459970951080322,47.13617935407062,1739141191.034437,30.459970951080322,8.632598941234392,1739141191.034453,30.459970951080322,2.6072392464831777,1739141191.034488,30.459970951080322,2.5071874764288977,1739141191.0345032,30.459970951080322,0.6108,1739141191.0345078,30.459970951080322,0.9170582753935455,1739141191.0345137,30.459970951080322,0.0,1739141191.0345187,30.459970951080322,-0.01215218402806617,1739141191.0345235,30.459970951080322,1.9887503484564466,1739141191.034528,30.459970951080322,0.9292104594216116 +1739141191.0666654,30.489970922470093,50.85757210663852,1739141191.066668,30.489970922470093,6.430353396032649,1739141191.066671,30.489970922470093,56.58168302202121,1739141191.0666735,30.489970922470093,47.13617935407062,1739141191.0666747,30.489970922470093,8.632598941234392,1739141191.0666761,30.489970922470093,2.6072392464831777,1739141191.0666776,30.489970922470093,2.5071874764288977,1739141191.0666788,30.489970922470093,0.6108,1739141191.06668,30.489970922470093,0.9170582753935455,1739141191.0666816,30.489970922470093,0.0,1739141191.066683,30.489970922470093,-0.01215218402806617,1739141191.0666845,30.489970922470093,1.9887503484564466,1739141191.0666857,30.489970922470093,0.9292104594216116 +1739141191.0879636,30.509970903396606,50.85757210663852,1739141191.0879664,30.509970903396606,6.430353396032649,1739141191.0879695,30.509970903396606,56.58168302202121,1739141191.0879722,30.509970903396606,47.13617935407062,1739141191.0879736,30.509970903396606,8.632598941234392,1739141191.0879755,30.509970903396606,2.6072392464831777,1739141191.087977,30.509970903396606,2.5071874764288977,1739141191.0879781,30.509970903396606,0.6108,1739141191.0879796,30.509970903396606,0.9170582753935455,1739141191.0879807,30.509970903396606,0.0,1739141191.0879827,30.509970903396606,-0.01215218402806617,1739141191.0879836,30.509970903396606,1.9887503484564466,1739141191.0879848,30.509970903396606,0.9292104594216116 +1739141191.1080554,30.52997088432312,50.85757210663852,1739141191.1080592,30.52997088432312,6.430353396032649,1739141191.1080618,30.52997088432312,56.58168302202121,1739141191.1080644,30.52997088432312,47.13617935407062,1739141191.108066,30.52997088432312,8.632598941234392,1739141191.108068,30.52997088432312,2.6072392464831777,1739141191.1080697,30.52997088432312,2.5071874764288977,1739141191.1080709,30.52997088432312,0.6108,1739141191.108073,30.52997088432312,0.9170582753935455,1739141191.1080756,30.52997088432312,0.0,1739141191.108077,30.52997088432312,-0.01215218402806617,1739141191.1080782,30.52997088432312,1.9887503484564466,1739141191.1080797,30.52997088432312,0.9292104594216116 +1739141191.1280031,30.549970865249634,50.81493992355842,1739141191.1280057,30.549970865249634,6.523175280651261,1739141191.1280084,30.549970865249634,56.72610469247577,1739141191.128011,30.549970865249634,46.99623395828656,1739141191.1280127,30.549970865249634,8.620844508542211,1739141191.128014,30.549970865249634,2.6392761581522004,1739141191.1280153,30.549970865249634,2.5414464052552725,1739141191.1280167,30.549970865249634,0.6108,1739141191.1280177,30.549970865249634,0.9045770159532582,1739141191.1280196,30.549970865249634,0.0,1739141191.128021,30.549970865249634,-0.03345977664430585,1739141191.128022,30.549970865249634,2.016474691703084,1739141191.1280234,30.549970865249634,0.9278903148545553 +1739141191.1493282,30.569970846176147,50.81493992355842,1739141191.1493316,30.569970846176147,6.523175280651261,1739141191.1493351,30.569970846176147,56.72610469247577,1739141191.149338,30.569970846176147,46.99623395828656,1739141191.14934,30.569970846176147,8.620844508542211,1739141191.1493416,30.569970846176147,2.6392761581522004,1739141191.1493435,30.569970846176147,2.5414464052552725,1739141191.1493447,30.569970846176147,0.6108,1739141191.149346,30.569970846176147,0.9045770159532582,1739141191.1493483,30.569970846176147,0.0,1739141191.14935,30.569970846176147,-0.023313298901297075,1739141191.1493514,30.569970846176147,2.016474691703084,1739141191.1493528,30.569970846176147,0.9278903148545553 +1739141191.1695418,30.58997082710266,50.81493992355842,1739141191.1695457,30.58997082710266,6.523175280651261,1739141191.1695502,30.58997082710266,56.72610469247577,1739141191.1695552,30.58997082710266,46.99623395828656,1739141191.169558,30.58997082710266,8.620844508542211,1739141191.1695616,30.58997082710266,2.6392761581522004,1739141191.1695652,30.58997082710266,2.5414464052552725,1739141191.1695685,30.58997082710266,0.6108,1739141191.1695716,30.58997082710266,0.9045770159532582,1739141191.1695752,30.58997082710266,0.0,1739141191.1695786,30.58997082710266,-0.023313298901297075,1739141191.1695817,30.58997082710266,2.016474691703084,1739141191.169585,30.58997082710266,0.9278903148545553 +1739141191.1879754,30.609970808029175,50.81493992355842,1739141191.1879797,30.609970808029175,6.523175280651261,1739141191.1879847,30.609970808029175,56.72610469247577,1739141191.18799,30.609970808029175,46.99623395828656,1739141191.1879928,30.609970808029175,8.620844508542211,1739141191.1879964,30.609970808029175,2.6392761581522004,1739141191.1879997,30.609970808029175,2.5414464052552725,1739141191.1880035,30.609970808029175,0.6108,1739141191.1880069,30.609970808029175,0.9045770159532582,1739141191.1880102,30.609970808029175,0.0,1739141191.1880138,30.609970808029175,-0.023313298901297075,1739141191.188017,30.609970808029175,2.016474691703084,1739141191.1880202,30.609970808029175,0.9278903148545553 +1739141191.2075963,30.62997078895569,50.81493992355842,1739141191.2075994,30.62997078895569,6.523175280651261,1739141191.2076027,30.62997078895569,56.72610469247577,1739141191.2076058,30.62997078895569,46.99623395828656,1739141191.207607,30.62997078895569,8.620844508542211,1739141191.2076085,30.62997078895569,2.6392761581522004,1739141191.2076101,30.62997078895569,2.5414464052552725,1739141191.2076113,30.62997078895569,0.6108,1739141191.2076128,30.62997078895569,0.9045770159532582,1739141191.2076142,30.62997078895569,0.0,1739141191.2076154,30.62997078895569,-0.023313298901297075,1739141191.207617,30.62997078895569,2.016474691703084,1739141191.2076182,30.62997078895569,0.9278903148545553 +1739141191.2270787,30.649970769882202,50.76984033402232,1739141191.2270813,30.649970769882202,6.614599430297716,1739141191.2270844,30.649970769882202,56.81301697987417,1739141191.2270868,30.649970769882202,46.91738411712936,1739141191.2270882,30.649970769882202,8.612338735864826,1739141191.2270896,30.649970769882202,2.6632055650507747,1739141191.2270908,30.649970769882202,2.5179670144001083,1739141191.227092,30.649970769882202,0.6108,1739141191.2270932,30.649970769882202,0.9131126022128322,1739141191.227095,30.649970769882202,0.0,1739141191.227096,30.649970769882202,-0.002180425091541288,1739141191.2270973,30.649970769882202,2.044199034949721,1739141191.2270987,30.649970769882202,0.9253563055741615 +1739141191.2465985,30.669970750808716,50.76984033402232,1739141191.2466009,30.669970750808716,6.614599430297716,1739141191.2466037,30.669970750808716,56.81301697987417,1739141191.2466068,30.669970750808716,46.91738411712936,1739141191.246608,30.669970750808716,8.612338735864826,1739141191.2466097,30.669970750808716,2.6632055650507747,1739141191.2466109,30.669970750808716,2.5179670144001083,1739141191.2466123,30.669970750808716,0.6108,1739141191.2466135,30.669970750808716,0.9131126022128322,1739141191.2466147,30.669970750808716,0.0,1739141191.2466164,30.669970750808716,-0.012243703361329294,1739141191.2466176,30.669970750808716,2.044199034949721,1739141191.2466185,30.669970750808716,0.9253563055741615 +1739141191.2665515,30.68997073173523,50.76984033402232,1739141191.2665539,30.68997073173523,6.614599430297716,1739141191.2665567,30.68997073173523,56.81301697987417,1739141191.2665596,30.68997073173523,46.91738411712936,1739141191.2665608,30.68997073173523,8.612338735864826,1739141191.2665625,30.68997073173523,2.6632055650507747,1739141191.266564,30.68997073173523,2.5179670144001083,1739141191.2665648,30.68997073173523,0.6108,1739141191.266566,30.68997073173523,0.9131126022128322,1739141191.2665677,30.68997073173523,0.0,1739141191.266569,30.68997073173523,-0.012243703361329294,1739141191.26657,30.68997073173523,2.044199034949721,1739141191.2665713,30.68997073173523,0.9253563055741615 +1739141191.2868311,30.709970712661743,50.76984033402232,1739141191.2868338,30.709970712661743,6.614599430297716,1739141191.2868361,30.709970712661743,56.81301697987417,1739141191.286839,30.709970712661743,46.91738411712936,1739141191.2868404,30.709970712661743,8.612338735864826,1739141191.2868419,30.709970712661743,2.6632055650507747,1739141191.286843,30.709970712661743,2.5179670144001083,1739141191.2868445,30.709970712661743,0.6108,1739141191.2868454,30.709970712661743,0.9131126022128322,1739141191.2868469,30.709970712661743,0.0,1739141191.2868483,30.709970712661743,-0.012243703361329294,1739141191.2868495,30.709970712661743,2.044199034949721,1739141191.286851,30.709970712661743,0.9253563055741615 +1739141191.306601,30.729970693588257,50.76984033402232,1739141191.3066037,30.729970693588257,6.614599430297716,1739141191.3066065,30.729970693588257,56.81301697987417,1739141191.3066092,30.729970693588257,46.91738411712936,1739141191.3066106,30.729970693588257,8.612338735864826,1739141191.3066123,30.729970693588257,2.6632055650507747,1739141191.3066134,30.729970693588257,2.5179670144001083,1739141191.3066149,30.729970693588257,0.6108,1739141191.3066158,30.729970693588257,0.9131126022128322,1739141191.3066173,30.729970693588257,0.0,1739141191.3066187,30.729970693588257,-0.012243703361329294,1739141191.30662,30.729970693588257,2.044199034949721,1739141191.3066208,30.729970693588257,0.9253563055741615 +1739141191.3266635,30.74997067451477,50.76984033402232,1739141191.3266659,30.74997067451477,6.614599430297716,1739141191.3266687,30.74997067451477,56.81301697987417,1739141191.3266714,30.74997067451477,46.91738411712936,1739141191.3266726,30.74997067451477,8.612338735864826,1739141191.3266742,30.74997067451477,2.6632055650507747,1739141191.3266754,30.74997067451477,2.5179670144001083,1739141191.3266768,30.74997067451477,0.6108,1739141191.3266778,30.74997067451477,0.9131126022128322,1739141191.3266792,30.74997067451477,0.0,1739141191.326681,30.74997067451477,-0.012243703361329294,1739141191.3266823,30.74997067451477,2.044199034949721,1739141191.3266838,30.74997067451477,0.9253563055741615 +1739141191.3527577,30.769970655441284,50.72231917546873,1739141191.3527677,30.769970655441284,6.7045567781929005,1739141191.3527782,30.769970655441284,56.97677691169698,1739141191.3527899,30.769970655441284,46.75802950383211,1739141191.3527956,30.769970655441284,8.594699937193939,1739141191.352803,30.769970655441284,2.696682901587716,1739141191.352809,30.769970655441284,2.5687953935511487,1739141191.3528147,30.769970655441284,0.6108,1739141191.3528202,30.769970655441284,0.894735240137573,1739141191.3528266,30.769970655441284,0.0,1739141191.352833,30.769970655441284,-0.045147124822923504,1739141191.3528388,30.769970655441284,2.0719233781963586,1739141191.3528445,30.769970655441284,0.9242140611994017 +1739141191.3726885,30.789970636367798,50.72231917546873,1739141191.3726978,30.789970636367798,6.7045567781929005,1739141191.372708,30.789970636367798,56.97677691169698,1739141191.3727183,30.789970636367798,46.75802950383211,1739141191.372723,30.789970636367798,8.594699937193939,1739141191.3727293,30.789970636367798,2.696682901587716,1739141191.3727343,30.789970636367798,2.5687953935511487,1739141191.372739,30.789970636367798,0.6108,1739141191.3727436,30.789970636367798,0.894735240137573,1739141191.3727493,30.789970636367798,0.0,1739141191.3727543,30.789970636367798,-0.029478821061828753,1739141191.372759,30.789970636367798,2.0719233781963586,1739141191.3727636,30.789970636367798,0.9242140611994017 +1739141191.3920066,30.80997061729431,50.72231917546873,1739141191.3920155,30.80997061729431,6.7045567781929005,1739141191.392025,30.80997061729431,56.97677691169698,1739141191.3920348,30.80997061729431,46.75802950383211,1739141191.3920398,30.80997061729431,8.594699937193939,1739141191.3920455,30.80997061729431,2.696682901587716,1739141191.3920503,30.80997061729431,2.5687953935511487,1739141191.3920548,30.80997061729431,0.6108,1739141191.392059,30.80997061729431,0.894735240137573,1739141191.3920648,30.80997061729431,0.0,1739141191.3920698,30.80997061729431,-0.029478821061828753,1739141191.3920746,30.80997061729431,2.0719233781963586,1739141191.392079,30.80997061729431,0.9242140611994017 +1739141191.421716,30.829970598220825,50.72231917546873,1739141191.421723,30.829970598220825,6.7045567781929005,1739141191.4217322,30.829970598220825,56.97677691169698,1739141191.4217424,30.829970598220825,46.75802950383211,1739141191.4217482,30.829970598220825,8.594699937193939,1739141191.4217558,30.829970598220825,2.696682901587716,1739141191.4217625,30.829970598220825,2.5687953935511487,1739141191.4217691,30.829970598220825,0.6108,1739141191.4217756,30.829970598220825,0.894735240137573,1739141191.4217825,30.829970598220825,0.0,1739141191.4217894,30.829970598220825,-0.029478821061828753,1739141191.421796,30.829970598220825,2.0719233781963586,1739141191.4218025,30.829970598220825,0.9242140611994017 +1739141191.4384227,30.84997057914734,50.72231917546873,1739141191.4384272,30.84997057914734,6.7045567781929005,1739141191.4384327,30.84997057914734,56.97677691169698,1739141191.4384391,30.84997057914734,46.75802950383211,1739141191.4384425,30.84997057914734,8.594699937193939,1739141191.4384468,30.84997057914734,2.696682901587716,1739141191.4384506,30.84997057914734,2.5687953935511487,1739141191.4384549,30.84997057914734,0.6108,1739141191.4384587,30.84997057914734,0.894735240137573,1739141191.4384627,30.84997057914734,0.0,1739141191.4384668,30.84997057914734,-0.029478821061828753,1739141191.4384782,30.84997057914734,2.0719233781963586,1739141191.4384825,30.84997057914734,0.9242140611994017 +1739141191.4563966,30.869970560073853,50.67244526267776,1739141191.4564,30.869970560073853,6.792945994238593,1739141191.4564042,30.869970560073853,57.06309052816051,1739141191.456409,30.869970560073853,46.682434224881966,1739141191.4564118,30.869970560073853,8.585118631731042,1739141191.4564154,30.869970560073853,2.7194334708766346,1739141191.4564185,30.869970560073853,2.540697959824266,1739141191.4564216,30.869970560073853,0.6108,1739141191.456425,30.869970560073853,0.9048478671085305,1739141191.456428,30.869970560073853,0.0,1739141191.4564314,30.869970560073853,-0.00373698011104992,1739141191.4564345,30.869970560073853,2.099647721442996,1739141191.4564378,30.869970560073853,0.9208428728433706 +1739141191.4769938,30.889970541000366,50.67244526267776,1739141191.4769974,30.889970541000366,6.792945994238593,1739141191.477002,30.889970541000366,57.06309052816051,1739141191.4770067,30.889970541000366,46.682434224881966,1739141191.4770093,30.889970541000366,8.585118631731042,1739141191.4770126,30.889970541000366,2.7194334708766346,1739141191.4770157,30.889970541000366,2.540697959824266,1739141191.4770188,30.889970541000366,0.6108,1739141191.477022,30.889970541000366,0.9048478671085305,1739141191.477025,30.889970541000366,0.0,1739141191.4770281,30.889970541000366,-0.01599500573484014,1739141191.4770315,30.889970541000366,2.099647721442996,1739141191.4770346,30.889970541000366,0.9208428728433706 +1739141191.4967213,30.90997052192688,50.67244526267776,1739141191.4967253,30.90997052192688,6.792945994238593,1739141191.4967299,30.90997052192688,57.06309052816051,1739141191.4967346,30.90997052192688,46.682434224881966,1739141191.4967375,30.90997052192688,8.585118631731042,1739141191.496741,30.90997052192688,2.7194334708766346,1739141191.4967444,30.90997052192688,2.540697959824266,1739141191.4967475,30.90997052192688,0.6108,1739141191.4967506,30.90997052192688,0.9048478671085305,1739141191.4967542,30.90997052192688,0.0,1739141191.4967573,30.90997052192688,-0.01599500573484014,1739141191.4967606,30.90997052192688,2.099647721442996,1739141191.496764,30.90997052192688,0.9208428728433706 +1739141191.5165362,30.929970502853394,50.67244526267776,1739141191.5165398,30.929970502853394,6.792945994238593,1739141191.5165446,30.929970502853394,57.06309052816051,1739141191.5165496,30.929970502853394,46.682434224881966,1739141191.5165524,30.929970502853394,8.585118631731042,1739141191.516556,30.929970502853394,2.7194334708766346,1739141191.5165594,30.929970502853394,2.540697959824266,1739141191.5165625,30.929970502853394,0.6108,1739141191.5165656,30.929970502853394,0.9048478671085305,1739141191.516569,30.929970502853394,0.0,1739141191.5165722,30.929970502853394,-0.01599500573484014,1739141191.5165756,30.929970502853394,2.099647721442996,1739141191.5165787,30.929970502853394,0.9208428728433706 +1739141191.5363483,30.949970483779907,50.67244526267776,1739141191.536352,30.949970483779907,6.792945994238593,1739141191.5363562,30.949970483779907,57.06309052816051,1739141191.5363612,30.949970483779907,46.682434224881966,1739141191.5363638,30.949970483779907,8.585118631731042,1739141191.5363674,30.949970483779907,2.7194334708766346,1739141191.5363708,30.949970483779907,2.540697959824266,1739141191.5363739,30.949970483779907,0.6108,1739141191.5363772,30.949970483779907,0.9048478671085305,1739141191.5363805,30.949970483779907,0.0,1739141191.5363834,30.949970483779907,-0.01599500573484014,1739141191.5363867,30.949970483779907,2.099647721442996,1739141191.5363898,30.949970483779907,0.9208428728433706 +1739141191.5558517,30.96997046470642,50.67244526267776,1739141191.5558548,30.96997046470642,6.792945994238593,1739141191.555858,30.96997046470642,57.06309052816051,1739141191.555861,30.96997046470642,46.682434224881966,1739141191.5558624,30.96997046470642,8.585118631731042,1739141191.5558643,30.96997046470642,2.7194334708766346,1739141191.5558655,30.96997046470642,2.540697959824266,1739141191.555867,30.96997046470642,0.6108,1739141191.5558681,30.96997046470642,0.9048478671085305,1739141191.5558696,30.96997046470642,0.0,1739141191.5558712,30.96997046470642,-0.01599500573484014,1739141191.5558724,30.96997046470642,2.099647721442996,1739141191.5558739,30.96997046470642,0.9208428728433706 +1739141191.5768175,30.989970445632935,50.62027102231954,1739141191.576822,30.989970445632935,6.879700336766403,1739141191.5768268,30.989970445632935,57.148291862313286,1739141191.5768323,30.989970445632935,46.602342675271885,1739141191.5768352,30.989970445632935,8.572888114939895,1739141191.576839,30.989970445632935,2.7427682591708415,1739141191.5768423,30.989970445632935,2.517018250029346,1739141191.576846,30.989970445632935,0.6108,1739141191.5768495,30.989970445632935,0.9134591994578851,1739141191.576853,30.989970445632935,0.0,1739141191.5768566,30.989970445632935,0.003094564850877673,1739141191.57686,30.989970445632935,2.1273720646896335,1739141191.5768635,30.989970445632935,0.9194549108554823 +1739141191.597163,31.00997042655945,50.62027102231954,1739141191.5971668,31.00997042655945,6.879700336766403,1739141191.5971713,31.00997042655945,57.148291862313286,1739141191.5971763,31.00997042655945,46.602342675271885,1739141191.5971792,31.00997042655945,8.572888114939895,1739141191.5971828,31.00997042655945,2.7427682591708415,1739141191.597186,31.00997042655945,2.517018250029346,1739141191.5971892,31.00997042655945,0.6108,1739141191.5971925,31.00997042655945,0.9134591994578851,1739141191.5971959,31.00997042655945,0.0,1739141191.5971994,31.00997042655945,-0.0059957113975971366,1739141191.5972025,31.00997042655945,2.1273720646896335,1739141191.5972059,31.00997042655945,0.9194549108554823 +1739141191.617288,31.029970407485962,50.62027102231954,1739141191.617292,31.029970407485962,6.879700336766403,1739141191.6172962,31.029970407485962,57.148291862313286,1739141191.6173007,31.029970407485962,46.602342675271885,1739141191.6173036,31.029970407485962,8.572888114939895,1739141191.617307,31.029970407485962,2.7427682591708415,1739141191.61731,31.029970407485962,2.517018250029346,1739141191.6173134,31.029970407485962,0.6108,1739141191.6173162,31.029970407485962,0.9134591994578851,1739141191.6173196,31.029970407485962,0.0,1739141191.6173227,31.029970407485962,-0.0059957113975971366,1739141191.6173255,31.029970407485962,2.1273720646896335,1739141191.617329,31.029970407485962,0.9194549108554823 +1739141191.6366014,31.049970388412476,50.62027102231954,1739141191.636605,31.049970388412476,6.879700336766403,1739141191.6366093,31.049970388412476,57.148291862313286,1739141191.6366143,31.049970388412476,46.602342675271885,1739141191.6366172,31.049970388412476,8.572888114939895,1739141191.6366208,31.049970388412476,2.7427682591708415,1739141191.636624,31.049970388412476,2.517018250029346,1739141191.6366277,31.049970388412476,0.6108,1739141191.636631,31.049970388412476,0.9134591994578851,1739141191.6366346,31.049970388412476,0.0,1739141191.636638,31.049970388412476,-0.0059957113975971366,1739141191.6366413,31.049970388412476,2.1273720646896335,1739141191.6366446,31.049970388412476,0.9194549108554823 +1739141191.6558862,31.06997036933899,50.62027102231954,1739141191.6558883,31.06997036933899,6.879700336766403,1739141191.6558912,31.06997036933899,57.148291862313286,1739141191.6558938,31.06997036933899,46.602342675271885,1739141191.655895,31.06997036933899,8.572888114939895,1739141191.655897,31.06997036933899,2.7427682591708415,1739141191.655898,31.06997036933899,2.517018250029346,1739141191.655899,31.06997036933899,0.6108,1739141191.6559005,31.06997036933899,0.9134591994578851,1739141191.655902,31.06997036933899,0.0,1739141191.6559033,31.06997036933899,-0.0059957113975971366,1739141191.6559043,31.06997036933899,2.1273720646896335,1739141191.6559055,31.06997036933899,0.9194549108554823 +1739141191.674302,31.089970350265503,50.565779242082826,1739141191.6743045,31.089970350265503,6.964869396477374,1739141191.674307,31.089970350265503,57.23355761097279,1739141191.6743097,31.089970350265503,46.52010938059227,1739141191.6743112,31.089970350265503,8.558185325428912,1739141191.6743126,31.089970350265503,2.7664144420958854,1739141191.6743143,31.089970350265503,2.495588555484237,1739141191.6743155,31.089970350265503,0.6108,1739141191.6743166,31.089970350265503,0.9213229153631866,1739141191.6743183,31.089970350265503,0.0,1739141191.6743195,31.089970350265503,0.010114370548643569,1739141191.674321,31.089970350265503,2.155096407936271,1739141191.6743221,31.089970350265503,0.9188800162402261 +1739141191.6945434,31.109970331192017,50.565779242082826,1739141191.694546,31.109970331192017,6.964869396477374,1739141191.6945484,31.109970331192017,57.23355761097279,1739141191.6945512,31.109970331192017,46.52010938059227,1739141191.6945527,31.109970331192017,8.558185325428912,1739141191.6945543,31.109970331192017,2.7664144420958854,1739141191.6945558,31.109970331192017,2.495588555484237,1739141191.694557,31.109970331192017,0.6108,1739141191.6945581,31.109970331192017,0.9213229153631866,1739141191.6945598,31.109970331192017,0.0,1739141191.694561,31.109970331192017,0.0024428991229604735,1739141191.6945622,31.109970331192017,2.155096407936271,1739141191.6945636,31.109970331192017,0.9188800162402261 +1739141191.7151275,31.12997031211853,50.565779242082826,1739141191.71513,31.12997031211853,6.964869396477374,1739141191.7151332,31.12997031211853,57.23355761097279,1739141191.7151358,31.12997031211853,46.52010938059227,1739141191.715137,31.12997031211853,8.558185325428912,1739141191.7151387,31.12997031211853,2.7664144420958854,1739141191.71514,31.12997031211853,2.495588555484237,1739141191.715141,31.12997031211853,0.6108,1739141191.7151425,31.12997031211853,0.9213229153631866,1739141191.7151442,31.12997031211853,0.0,1739141191.7151458,31.12997031211853,0.0024428991229604735,1739141191.715147,31.12997031211853,2.155096407936271,1739141191.7151482,31.12997031211853,0.9188800162402261 +1739141191.7345505,31.149970293045044,50.565779242082826,1739141191.734553,31.149970293045044,6.964869396477374,1739141191.734556,31.149970293045044,57.23355761097279,1739141191.7345588,31.149970293045044,46.52010938059227,1739141191.73456,31.149970293045044,8.558185325428912,1739141191.7345614,31.149970293045044,2.7664144420958854,1739141191.734563,31.149970293045044,2.495588555484237,1739141191.7345643,31.149970293045044,0.6108,1739141191.7345657,31.149970293045044,0.9213229153631866,1739141191.7345672,31.149970293045044,0.0,1739141191.7345684,31.149970293045044,0.0024428991229604735,1739141191.7345698,31.149970293045044,2.155096407936271,1739141191.734571,31.149970293045044,0.9188800162402261 +1739141191.75479,31.169970273971558,50.565779242082826,1739141191.7547927,31.169970273971558,6.964869396477374,1739141191.7547956,31.169970273971558,57.23355761097279,1739141191.7547984,31.169970273971558,46.52010938059227,1739141191.7547998,31.169970273971558,8.558185325428912,1739141191.7548018,31.169970273971558,2.7664144420958854,1739141191.754803,31.169970273971558,2.495588555484237,1739141191.7548041,31.169970273971558,0.6108,1739141191.7548056,31.169970273971558,0.9213229153631866,1739141191.754807,31.169970273971558,0.0,1739141191.754809,31.169970273971558,0.0024428991229604735,1739141191.75481,31.169970273971558,2.155096407936271,1739141191.7548113,31.169970273971558,0.9188800162402261 +1739141191.7759683,31.18997025489807,50.565779242082826,1739141191.7759707,31.18997025489807,6.964869396477374,1739141191.7759733,31.18997025489807,57.23355761097279,1739141191.7759762,31.18997025489807,46.52010938059227,1739141191.7759774,31.18997025489807,8.558185325428912,1739141191.775979,31.18997025489807,2.7664144420958854,1739141191.7759805,31.18997025489807,2.495588555484237,1739141191.775982,31.18997025489807,0.6108,1739141191.7759829,31.18997025489807,0.9213229153631866,1739141191.7759845,31.18997025489807,0.0,1739141191.775986,31.18997025489807,0.0024428991229604735,1739141191.7759871,31.18997025489807,2.155096407936271,1739141191.7759886,31.18997025489807,0.9188800162402261 +1739141191.7962313,31.209970235824585,50.508951719116105,1739141191.7962334,31.209970235824585,7.048488488143066,1739141191.7962363,31.209970235824585,57.4104370587246,1739141191.796239,31.209970235824585,46.34577386573472,1739141191.7962403,31.209970235824585,8.521617380993463,1739141191.796242,31.209970235824585,2.801494590177452,1739141191.7962432,31.209970235824585,2.5611550754062082,1739141191.7962444,31.209970235824585,0.6108,1739141191.7962458,31.209970235824585,0.8974738475284478,1739141191.7962472,31.209970235824585,0.0,1739141191.796249,31.209970235824585,-0.043889432396073166,1739141191.79625,31.209970235824585,2.1828207511829083,1739141191.7962513,31.209970235824585,0.9193002538940119 +1739141191.815355,31.2299702167511,50.508951719116105,1739141191.815358,31.2299702167511,7.048488488143066,1739141191.8153605,31.2299702167511,57.4104370587246,1739141191.8153632,31.2299702167511,46.34577386573472,1739141191.8153646,31.2299702167511,8.521617380993463,1739141191.8153658,31.2299702167511,2.801494590177452,1739141191.8153675,31.2299702167511,2.5611550754062082,1739141191.8153684,31.2299702167511,0.6108,1739141191.8153698,31.2299702167511,0.8974738475284478,1739141191.8153713,31.2299702167511,0.0,1739141191.8153727,31.2299702167511,-0.0218264063655641,1739141191.815374,31.2299702167511,2.1828207511829083,1739141191.815375,31.2299702167511,0.9193002538940119 +1739141191.8353326,31.249970197677612,50.508951719116105,1739141191.835337,31.249970197677612,7.048488488143066,1739141191.8353415,31.249970197677612,57.4104370587246,1739141191.8353455,31.249970197677612,46.34577386573472,1739141191.8353474,31.249970197677612,8.521617380993463,1739141191.8353498,31.249970197677612,2.801494590177452,1739141191.8353517,31.249970197677612,2.5611550754062082,1739141191.8353536,31.249970197677612,0.6108,1739141191.8353558,31.249970197677612,0.8974738475284478,1739141191.835358,31.249970197677612,0.0,1739141191.8353603,31.249970197677612,-0.0218264063655641,1739141191.8353622,31.249970197677612,2.1828207511829083,1739141191.8353646,31.249970197677612,0.9193002538940119 +1739141191.8549435,31.269970178604126,50.508951719116105,1739141191.8549464,31.269970178604126,7.048488488143066,1739141191.8549492,31.269970178604126,57.4104370587246,1739141191.8549519,31.269970178604126,46.34577386573472,1739141191.8549533,31.269970178604126,8.521617380993463,1739141191.854955,31.269970178604126,2.801494590177452,1739141191.8549564,31.269970178604126,2.5611550754062082,1739141191.8549576,31.269970178604126,0.6108,1739141191.8549588,31.269970178604126,0.8974738475284478,1739141191.8549604,31.269970178604126,0.0,1739141191.8549619,31.269970178604126,-0.0218264063655641,1739141191.8549633,31.269970178604126,2.1828207511829083,1739141191.8549645,31.269970178604126,0.9193002538940119 +1739141191.8759344,31.28997015953064,50.508951719116105,1739141191.8759367,31.28997015953064,7.048488488143066,1739141191.8759396,31.28997015953064,57.4104370587246,1739141191.8759422,31.28997015953064,46.34577386573472,1739141191.8759437,31.28997015953064,8.521617380993463,1739141191.8759453,31.28997015953064,2.801494590177452,1739141191.8759465,31.28997015953064,2.5611550754062082,1739141191.8759477,31.28997015953064,0.6108,1739141191.8759491,31.28997015953064,0.8974738475284478,1739141191.8759503,31.28997015953064,0.0,1739141191.8759518,31.28997015953064,-0.0218264063655641,1739141191.875953,31.28997015953064,2.1828207511829083,1739141191.8759542,31.28997015953064,0.9193002538940119 +1739141191.8952696,31.309970140457153,50.44989579164944,1739141191.8952723,31.309970140457153,7.13040751155124,1739141191.895275,31.309970140457153,57.425271825022755,1739141191.8952775,31.309970140457153,46.33887308758038,1739141191.8952792,31.309970140457153,8.520113365241878,1739141191.8952806,31.309970140457153,2.8156086613992897,1739141191.895282,31.309970140457153,2.468404632507018,1739141191.8952832,31.309970140457153,0.6108,1739141191.8952842,31.309970140457153,0.9313956478622388,1739141191.8952858,31.309970140457153,0.0,1739141191.8952873,31.309970140457153,0.04787923803913276,1739141191.8952885,31.309970140457153,2.2105450944295457,1739141191.89529,31.309970140457153,0.9167095904067866 +1739141191.9151478,31.329970121383667,50.44989579164944,1739141191.9151504,31.329970121383667,7.13040751155124,1739141191.9151535,31.329970121383667,57.425271825022755,1739141191.9151561,31.329970121383667,46.33887308758038,1739141191.9151576,31.329970121383667,8.520113365241878,1739141191.915159,31.329970121383667,2.8156086613992897,1739141191.9151607,31.329970121383667,2.468404632507018,1739141191.9151618,31.329970121383667,0.6108,1739141191.9151628,31.329970121383667,0.9313956478622388,1739141191.9151647,31.329970121383667,0.0,1739141191.915166,31.329970121383667,0.014686057455452262,1739141191.9151673,31.329970121383667,2.2105450944295457,1739141191.9151685,31.329970121383667,0.9167095904067866 +1739141191.934244,31.34997010231018,50.44989579164944,1739141191.934247,31.34997010231018,7.13040751155124,1739141191.9342494,31.34997010231018,57.425271825022755,1739141191.9342523,31.34997010231018,46.33887308758038,1739141191.9342535,31.34997010231018,8.520113365241878,1739141191.9342551,31.34997010231018,2.8156086613992897,1739141191.9342566,31.34997010231018,2.468404632507018,1739141191.934258,31.34997010231018,0.6108,1739141191.934259,31.34997010231018,0.9313956478622388,1739141191.9342608,31.34997010231018,0.0,1739141191.934262,31.34997010231018,0.014686057455452262,1739141191.9342632,31.34997010231018,2.2105450944295457,1739141191.9342647,31.34997010231018,0.9167095904067866 +1739141191.9546068,31.369970083236694,50.44989579164944,1739141191.9546096,31.369970083236694,7.13040751155124,1739141191.9546127,31.369970083236694,57.425271825022755,1739141191.9546154,31.369970083236694,46.33887308758038,1739141191.954617,31.369970083236694,8.520113365241878,1739141191.9546187,31.369970083236694,2.8156086613992897,1739141191.95462,31.369970083236694,2.468404632507018,1739141191.954621,31.369970083236694,0.6108,1739141191.9546225,31.369970083236694,0.9313956478622388,1739141191.9546242,31.369970083236694,0.0,1739141191.9546256,31.369970083236694,0.014686057455452262,1739141191.9546268,31.369970083236694,2.2105450944295457,1739141191.954628,31.369970083236694,0.9167095904067866 +1739141191.9749115,31.389970064163208,50.44989579164944,1739141191.9749148,31.389970064163208,7.13040751155124,1739141191.974918,31.389970064163208,57.425271825022755,1739141191.9749212,31.389970064163208,46.33887308758038,1739141191.9749227,31.389970064163208,8.520113365241878,1739141191.9749246,31.389970064163208,2.8156086613992897,1739141191.9749258,31.389970064163208,2.468404632507018,1739141191.9749272,31.389970064163208,0.6108,1739141191.9749284,31.389970064163208,0.9313956478622388,1739141191.9749303,31.389970064163208,0.0,1739141191.9749317,31.389970064163208,0.014686057455452262,1739141191.974933,31.389970064163208,2.2105450944295457,1739141191.9749343,31.389970064163208,0.9167095904067866 +1739141191.9946225,31.40997004508972,50.44989579164944,1739141191.9946253,31.40997004508972,7.13040751155124,1739141191.9946282,31.40997004508972,57.425271825022755,1739141191.9946308,31.40997004508972,46.33887308758038,1739141191.9946322,31.40997004508972,8.520113365241878,1739141191.9946337,31.40997004508972,2.8156086613992897,1739141191.994635,31.40997004508972,2.468404632507018,1739141191.9946363,31.40997004508972,0.6108,1739141191.9946375,31.40997004508972,0.9313956478622388,1739141191.9946392,31.40997004508972,0.0,1739141191.9946404,31.40997004508972,0.014686057455452262,1739141191.9946418,31.40997004508972,2.2105450944295457,1739141191.994643,31.40997004508972,0.9167095904067866 +1739141192.0143929,31.429970026016235,50.38862184305216,1739141192.014396,31.429970026016235,7.210616499631104,1739141192.0143986,31.429970026016235,57.56212924951942,1739141192.0144012,31.429970026016235,46.2006258648164,1739141192.0144026,31.429970026016235,8.485267634951196,1739141192.0144043,31.429970026016235,2.846142274418153,1739141192.0144057,31.429970026016235,2.500189788295818,1739141192.014407,31.429970026016235,0.6108,1739141192.014408,31.429970026016235,0.919628786366506,1739141192.0144098,31.429970026016235,0.0,1739141192.0144112,31.429970026016235,-0.011422600304486254,1739141192.0144124,31.429970026016235,2.238269437676183,1739141192.0144136,31.429970026016235,0.918618686288916 +1739141192.0343444,31.44997000694275,50.38862184305216,1739141192.0343473,31.44997000694275,7.210616499631104,1739141192.0343502,31.44997000694275,57.56212924951942,1739141192.0343533,31.44997000694275,46.2006258648164,1739141192.0343547,31.44997000694275,8.485267634951196,1739141192.034356,31.44997000694275,2.846142274418153,1739141192.0343575,31.44997000694275,2.500189788295818,1739141192.0343587,31.44997000694275,0.6108,1739141192.0343602,31.44997000694275,0.919628786366506,1739141192.0343616,31.44997000694275,0.0,1739141192.034363,31.44997000694275,0.0010101000775900593,1739141192.0343645,31.44997000694275,2.238269437676183,1739141192.0343654,31.44997000694275,0.918618686288916 +1739141192.0547438,31.469969987869263,50.38862184305216,1739141192.0547464,31.469969987869263,7.210616499631104,1739141192.0547493,31.469969987869263,57.56212924951942,1739141192.0547516,31.469969987869263,46.2006258648164,1739141192.054753,31.469969987869263,8.485267634951196,1739141192.0547545,31.469969987869263,2.846142274418153,1739141192.054756,31.469969987869263,2.500189788295818,1739141192.054757,31.469969987869263,0.6108,1739141192.0547583,31.469969987869263,0.919628786366506,1739141192.05476,31.469969987869263,0.0,1739141192.0547612,31.469969987869263,0.0010101000775900593,1739141192.0547626,31.469969987869263,2.238269437676183,1739141192.0547638,31.469969987869263,0.918618686288916 +1739141192.0743756,31.489969968795776,50.38862184305216,1739141192.0743783,31.489969968795776,7.210616499631104,1739141192.074381,31.489969968795776,57.56212924951942,1739141192.074384,31.489969968795776,46.2006258648164,1739141192.0743854,31.489969968795776,8.485267634951196,1739141192.0743868,31.489969968795776,2.846142274418153,1739141192.0743885,31.489969968795776,2.500189788295818,1739141192.0743897,31.489969968795776,0.6108,1739141192.074391,31.489969968795776,0.919628786366506,1739141192.0743928,31.489969968795776,0.0,1739141192.0743945,31.489969968795776,0.0010101000775900593,1739141192.0743957,31.489969968795776,2.238269437676183,1739141192.0743968,31.489969968795776,0.918618686288916 +1739141192.0946004,31.50996994972229,50.38862184305216,1739141192.0946033,31.50996994972229,7.210616499631104,1739141192.0946062,31.50996994972229,57.56212924951942,1739141192.0946088,31.50996994972229,46.2006258648164,1739141192.0946105,31.50996994972229,8.485267634951196,1739141192.094612,31.50996994972229,2.846142274418153,1739141192.0946133,31.50996994972229,2.500189788295818,1739141192.0946145,31.50996994972229,0.6108,1739141192.0946157,31.50996994972229,0.919628786366506,1739141192.0946176,31.50996994972229,0.0,1739141192.094619,31.50996994972229,0.0010101000775900593,1739141192.0946205,31.50996994972229,2.238269437676183,1739141192.0946217,31.50996994972229,0.918618686288916 +1739141192.1144578,31.529969930648804,50.325080944213575,1739141192.1144607,31.529969930648804,7.289179876516309,1739141192.1144636,31.529969930648804,57.72413860760243,1739141192.1144662,31.529969930648804,46.04666136052908,1739141192.1144753,31.529969930648804,8.435130543729963,1739141192.1144776,31.529969930648804,2.87989105391581,1739141192.114479,31.529969930648804,2.551491045793748,1739141192.1144805,31.529969930648804,0.6108,1739141192.1144817,31.529969930648804,0.9009498471682333,1739141192.114483,31.529969930648804,0.0,1739141192.1144848,31.529969930648804,-0.03464598765787178,1739141192.114486,31.529969930648804,2.2659937809228206,1739141192.1144874,31.529969930648804,0.918616736946465 +1739141192.1347773,31.549969911575317,50.325080944213575,1739141192.13478,31.549969911575317,7.289179876516309,1739141192.1347828,31.549969911575317,57.72413860760243,1739141192.1347857,31.549969911575317,46.04666136052908,1739141192.1347868,31.549969911575317,8.435130543729963,1739141192.1347883,31.549969911575317,2.87989105391581,1739141192.1347897,31.549969911575317,2.551491045793748,1739141192.134791,31.549969911575317,0.6108,1739141192.134792,31.549969911575317,0.9009498471682333,1739141192.1347938,31.549969911575317,0.0,1739141192.1347952,31.549969911575317,-0.01766688977823161,1739141192.1347966,31.549969911575317,2.2659937809228206,1739141192.1347978,31.549969911575317,0.918616736946465 +1739141192.1543834,31.56996989250183,50.325080944213575,1739141192.1543865,31.56996989250183,7.289179876516309,1739141192.1543891,31.56996989250183,57.72413860760243,1739141192.1543918,31.56996989250183,46.04666136052908,1739141192.1543934,31.56996989250183,8.435130543729963,1739141192.154395,31.56996989250183,2.87989105391581,1739141192.1543965,31.56996989250183,2.551491045793748,1739141192.1543977,31.56996989250183,0.6108,1739141192.154399,31.56996989250183,0.9009498471682333,1739141192.1544006,31.56996989250183,0.0,1739141192.154402,31.56996989250183,-0.01766688977823161,1739141192.154403,31.56996989250183,2.2659937809228206,1739141192.1544046,31.56996989250183,0.918616736946465 +1739141192.1743908,31.589969873428345,50.325080944213575,1739141192.1743937,31.589969873428345,7.289179876516309,1739141192.1743965,31.589969873428345,57.72413860760243,1739141192.1743991,31.589969873428345,46.04666136052908,1739141192.1744008,31.589969873428345,8.435130543729963,1739141192.1744022,31.589969873428345,2.87989105391581,1739141192.1744037,31.589969873428345,2.551491045793748,1739141192.1744049,31.589969873428345,0.6108,1739141192.174406,31.589969873428345,0.9009498471682333,1739141192.174408,31.589969873428345,0.0,1739141192.1744094,31.589969873428345,-0.01766688977823161,1739141192.1744108,31.589969873428345,2.2659937809228206,1739141192.174412,31.589969873428345,0.918616736946465 +1739141192.194347,31.60996985435486,50.325080944213575,1739141192.19435,31.60996985435486,7.289179876516309,1739141192.194353,31.60996985435486,57.72413860760243,1739141192.194356,31.60996985435486,46.04666136052908,1739141192.1943572,31.60996985435486,8.435130543729963,1739141192.1943588,31.60996985435486,2.87989105391581,1739141192.1943603,31.60996985435486,2.551491045793748,1739141192.1943617,31.60996985435486,0.6108,1739141192.1943629,31.60996985435486,0.9009498471682333,1739141192.1943643,31.60996985435486,0.0,1739141192.1943657,31.60996985435486,-0.01766688977823161,1739141192.194367,31.60996985435486,2.2659937809228206,1739141192.1943686,31.60996985435486,0.918616736946465 +1739141192.2144158,31.629969835281372,50.325080944213575,1739141192.2144184,31.629969835281372,7.289179876516309,1739141192.2144215,31.629969835281372,57.72413860760243,1739141192.2144244,31.629969835281372,46.04666136052908,1739141192.2144258,31.629969835281372,8.435130543729963,1739141192.2144275,31.629969835281372,2.87989105391581,1739141192.214429,31.629969835281372,2.551491045793748,1739141192.21443,31.629969835281372,0.6108,1739141192.2144315,31.629969835281372,0.9009498471682333,1739141192.2144332,31.629969835281372,0.0,1739141192.2144346,31.629969835281372,-0.01766688977823161,1739141192.214436,31.629969835281372,2.2659937809228206,1739141192.2144375,31.629969835281372,0.918616736946465 +1739141192.2346652,31.649969816207886,50.25947864802481,1739141192.2346685,31.649969816207886,7.3658450067067065,1739141192.2346716,31.649969816207886,57.80879175600426,1739141192.2346745,31.649969816207886,45.97404463017536,1739141192.2346756,31.649969816207886,8.40859936104128,1739141192.2346776,31.649969816207886,2.902905895706591,1739141192.2346787,31.649969816207886,2.5236799996132966,1739141192.2346802,31.649969816207886,0.6108,1739141192.2346814,31.649969816207886,0.9110283450681331,1739141192.234683,31.649969816207886,0.0,1739141192.2346845,31.649969816207886,0.006237755748446552,1739141192.2346857,31.649969816207886,2.293718124169458,1739141192.234687,31.649969816207886,0.9161737595425908 +1739141192.2545857,31.6699697971344,50.25947864802481,1739141192.2545888,31.6699697971344,7.3658450067067065,1739141192.2545917,31.6699697971344,57.80879175600426,1739141192.2545946,31.6699697971344,45.97404463017536,1739141192.254596,31.6699697971344,8.40859936104128,1739141192.2545977,31.6699697971344,2.902905895706591,1739141192.2545989,31.6699697971344,2.5236799996132966,1739141192.2546003,31.6699697971344,0.6108,1739141192.2546015,31.6699697971344,0.9110283450681331,1739141192.2546031,31.6699697971344,0.0,1739141192.2546048,31.6699697971344,-0.00514541447445771,1739141192.254606,31.6699697971344,2.293718124169458,1739141192.2546074,31.6699697971344,0.9161737595425908 +1739141192.2806396,31.689969778060913,50.25947864802481,1739141192.280656,31.689969778060913,7.3658450067067065,1739141192.2806742,31.689969778060913,57.80879175600426,1739141192.2806966,31.689969778060913,45.97404463017536,1739141192.2807093,31.689969778060913,8.40859936104128,1739141192.2807243,31.689969778060913,2.902905895706591,1739141192.280736,31.689969778060913,2.5236799996132966,1739141192.280748,31.689969778060913,0.6108,1739141192.2807596,31.689969778060913,0.9110283450681331,1739141192.2807734,31.689969778060913,0.0,1739141192.2807872,31.689969778060913,-0.00514541447445771,1739141192.2807994,31.689969778060913,2.293718124169458,1739141192.2808104,31.689969778060913,0.9161737595425908 +1739141192.313913,31.719969749450684,50.25947864802481,1739141192.3139226,31.719969749450684,7.3658450067067065,1739141192.3139334,31.719969749450684,57.80879175600426,1739141192.3139434,31.719969749450684,45.97404463017536,1739141192.3139482,31.719969749450684,8.40859936104128,1739141192.313954,31.719969749450684,2.902905895706591,1739141192.313959,31.719969749450684,2.5236799996132966,1739141192.3139632,31.719969749450684,0.6108,1739141192.3139677,31.719969749450684,0.9110283450681331,1739141192.3139732,31.719969749450684,0.0,1739141192.3139784,31.719969749450684,-0.00514541447445771,1739141192.313983,31.719969749450684,2.293718124169458,1739141192.3139875,31.719969749450684,0.9161737595425908 +1739141192.344534,31.749969720840454,50.19187480288094,1739141192.344542,31.749969720840454,7.440552576326111,1739141192.344551,31.749969720840454,57.88118550669774,1739141192.3445597,31.749969720840454,45.90855732388315,1739141192.344564,31.749969720840454,8.381136942273582,1739141192.3445692,31.749969720840454,2.925431075496099,1739141192.3445745,31.749969720840454,2.4905852356058276,1739141192.3445785,31.749969720840454,0.6108,1739141192.3445826,31.749969720840454,0.9231686309910172,1739141192.3445868,31.749969720840454,0.0,1739141192.344591,31.749969720840454,0.01891049900514606,1739141192.3445947,31.749969720840454,2.3214424674160954,1739141192.3445985,31.749969720840454,0.9157133346032947 +1739141192.3616116,31.779969692230225,50.19187480288094,1739141192.3616157,31.779969692230225,7.440552576326111,1739141192.3616202,31.779969692230225,57.88118550669774,1739141192.3616245,31.779969692230225,45.90855732388315,1739141192.3616266,31.779969692230225,8.381136942273582,1739141192.3616292,31.779969692230225,2.925431075496099,1739141192.3616314,31.779969692230225,2.4905852356058276,1739141192.3616333,31.779969692230225,0.6108,1739141192.3616347,31.779969692230225,0.9231686309910172,1739141192.3616374,31.779969692230225,0.0,1739141192.3616397,31.779969692230225,0.007455296387722465,1739141192.3616416,31.779969692230225,2.3214424674160954,1739141192.3616438,31.779969692230225,0.9157133346032947 +1739141192.379836,31.79996967315674,50.19187480288094,1739141192.3798392,31.79996967315674,7.440552576326111,1739141192.379842,31.79996967315674,57.88118550669774,1739141192.3798447,31.79996967315674,45.90855732388315,1739141192.3798459,31.79996967315674,8.381136942273582,1739141192.3798475,31.79996967315674,2.925431075496099,1739141192.3798487,31.79996967315674,2.4905852356058276,1739141192.37985,31.79996967315674,0.6108,1739141192.3798513,31.79996967315674,0.9231686309910172,1739141192.3798528,31.79996967315674,0.0,1739141192.3798544,31.79996967315674,0.007455296387722465,1739141192.3798556,31.79996967315674,2.3214424674160954,1739141192.3798568,31.79996967315674,0.9157133346032947 +1739141192.4006844,31.819969654083252,50.19187480288094,1739141192.400705,31.819969654083252,7.440552576326111,1739141192.4007108,31.819969654083252,57.88118550669774,1739141192.4007156,31.819969654083252,45.90855732388315,1739141192.4007185,31.819969654083252,8.381136942273582,1739141192.4007215,31.819969654083252,2.925431075496099,1739141192.4007244,31.819969654083252,2.4905852356058276,1739141192.4007275,31.819969654083252,0.6108,1739141192.4007304,31.819969654083252,0.9231686309910172,1739141192.4007335,31.819969654083252,0.0,1739141192.4007366,31.819969654083252,0.007455296387722465,1739141192.4007552,31.819969654083252,2.3214424674160954,1739141192.400758,31.819969654083252,0.9157133346032947 +1739141192.4196978,31.839969635009766,50.19187480288094,1739141192.4197044,31.839969635009766,7.440552576326111,1739141192.4197102,31.839969635009766,57.88118550669774,1739141192.4197173,31.839969635009766,45.90855732388315,1739141192.4197211,31.839969635009766,8.381136942273582,1739141192.419725,31.839969635009766,2.925431075496099,1739141192.419728,31.839969635009766,2.4905852356058276,1739141192.4197311,31.839969635009766,0.6108,1739141192.4197338,31.839969635009766,0.9231686309910172,1739141192.4197369,31.839969635009766,0.0,1739141192.4197402,31.839969635009766,0.007455296387722465,1739141192.4197435,31.839969635009766,2.3214424674160954,1739141192.4197462,31.839969635009766,0.9157133346032947 +1739141192.439613,31.85996961593628,50.12221299768802,1739141192.4396203,31.85996961593628,7.513370475463544,1739141192.4396265,31.85996961593628,57.98185646622196,1739141192.439635,31.85996961593628,45.81339877997471,1739141192.4396396,31.85996961593628,8.340609724604361,1739141192.4396439,31.85996961593628,2.9519129826972232,1739141192.4396474,31.85996961593628,2.4873069589501418,1739141192.4396513,31.85996961593628,0.6108,1739141192.439655,31.85996961593628,0.9243799859176478,1739141192.4396594,31.85996961593628,0.0,1739141192.4396632,31.85996961593628,0.0080110854236256,1739141192.4396672,31.85996961593628,2.349166810662733,1739141192.4396706,31.85996961593628,0.9166335620719004 +1739141192.4614687,31.879969596862793,50.12221299768802,1739141192.4614727,31.879969596862793,7.513370475463544,1739141192.4614775,31.879969596862793,57.98185646622196,1739141192.461483,31.879969596862793,45.81339877997471,1739141192.4614859,31.879969596862793,8.340609724604361,1739141192.4614897,31.879969596862793,2.9519129826972232,1739141192.461493,31.879969596862793,2.4873069589501418,1739141192.4614966,31.879969596862793,0.6108,1739141192.4615,31.879969596862793,0.9243799859176478,1739141192.4615035,31.879969596862793,0.0,1739141192.4615073,31.879969596862793,0.007746423845747419,1739141192.4615107,31.879969596862793,2.349166810662733,1739141192.461514,31.879969596862793,0.9166335620719004 +1739141192.4796953,31.899969577789307,50.12221299768802,1739141192.4796991,31.899969577789307,7.513370475463544,1739141192.4797025,31.899969577789307,57.98185646622196,1739141192.479705,31.899969577789307,45.81339877997471,1739141192.4797065,31.899969577789307,8.340609724604361,1739141192.4797082,31.899969577789307,2.9519129826972232,1739141192.4797096,31.899969577789307,2.4873069589501418,1739141192.479711,31.899969577789307,0.6108,1739141192.4797122,31.899969577789307,0.9243799859176478,1739141192.4797146,31.899969577789307,0.0,1739141192.479719,31.899969577789307,0.007746423845747419,1739141192.4797256,31.899969577789307,2.349166810662733,1739141192.4797292,31.899969577789307,0.9166335620719004 +1739141192.5002513,31.91996955871582,50.12221299768802,1739141192.5002542,31.91996955871582,7.513370475463544,1739141192.5002573,31.91996955871582,57.98185646622196,1739141192.50026,31.91996955871582,45.81339877997471,1739141192.5002615,31.91996955871582,8.340609724604361,1739141192.5002632,31.91996955871582,2.9519129826972232,1739141192.5002646,31.91996955871582,2.4873069589501418,1739141192.500266,31.91996955871582,0.6108,1739141192.5002673,31.91996955871582,0.9243799859176478,1739141192.5002687,31.91996955871582,0.0,1739141192.5002704,31.91996955871582,0.007746423845747419,1739141192.5002716,31.91996955871582,2.349166810662733,1739141192.500273,31.91996955871582,0.9166335620719004 +1739141192.5189435,31.939969539642334,50.12221299768802,1739141192.5189471,31.939969539642334,7.513370475463544,1739141192.518952,31.939969539642334,57.98185646622196,1739141192.5189602,31.939969539642334,45.81339877997471,1739141192.5189643,31.939969539642334,8.340609724604361,1739141192.518969,31.939969539642334,2.9519129826972232,1739141192.518972,31.939969539642334,2.4873069589501418,1739141192.5189745,31.939969539642334,0.6108,1739141192.5189767,31.939969539642334,0.9243799859176478,1739141192.5189795,31.939969539642334,0.0,1739141192.5189831,31.939969539642334,0.007746423845747419,1739141192.5189855,31.939969539642334,2.349166810662733,1739141192.5189884,31.939969539642334,0.9166335620719004 +1739141192.538995,31.959969520568848,50.12221299768802,1739141192.5389981,31.959969520568848,7.513370475463544,1739141192.539001,31.959969520568848,57.98185646622196,1739141192.5390038,31.959969520568848,45.81339877997471,1739141192.5390055,31.959969520568848,8.340609724604361,1739141192.539007,31.959969520568848,2.9519129826972232,1739141192.5390081,31.959969520568848,2.4873069589501418,1739141192.5390096,31.959969520568848,0.6108,1739141192.5390108,31.959969520568848,0.9243799859176478,1739141192.5390124,31.959969520568848,0.0,1739141192.539014,31.959969520568848,0.007746423845747419,1739141192.5390155,31.959969520568848,2.349166810662733,1739141192.5390167,31.959969520568848,0.9166335620719004 +1739141192.5590389,31.97996950149536,50.0504908545313,1739141192.5590415,31.97996950149536,7.584297139799208,1739141192.5590444,31.97996950149536,58.0680449014455,1739141192.5590472,31.97996950149536,45.73261934188679,1739141192.5590484,31.97996950149536,8.303872319841108,1739141192.5590503,31.97996950149536,2.9764597659931646,1739141192.5590518,31.97996950149536,2.4701182957074894,1739141192.559053,31.97996950149536,0.6108,1739141192.5590544,31.97996950149536,0.9307574272475365,1739141192.5590558,31.97996950149536,0.0,1739141192.559058,31.97996950149536,0.01829030211479554,1739141192.5590594,31.97996950149536,2.3768911539093702,1739141192.559061,31.97996950149536,0.9174880220547308 +1739141192.5792737,31.999969482421875,50.0504908545313,1739141192.5792773,31.999969482421875,7.584297139799208,1739141192.5792818,31.999969482421875,58.0680449014455,1739141192.5792873,31.999969482421875,45.73261934188679,1739141192.5792904,31.999969482421875,8.303872319841108,1739141192.5792942,31.999969482421875,2.9764597659931646,1739141192.5792978,31.999969482421875,2.4701182957074894,1739141192.579301,31.999969482421875,0.6108,1739141192.5793045,31.999969482421875,0.9307574272475365,1739141192.579308,31.999969482421875,0.0,1739141192.5793116,31.999969482421875,0.013269405192805728,1739141192.5793154,31.999969482421875,2.3768911539093702,1739141192.5793188,31.999969482421875,0.9174880220547308 +1739141192.5991805,32.01996946334839,50.0504908545313,1739141192.599183,32.01996946334839,7.584297139799208,1739141192.5991857,32.01996946334839,58.0680449014455,1739141192.5991888,32.01996946334839,45.73261934188679,1739141192.59919,32.01996946334839,8.303872319841108,1739141192.5991921,32.01996946334839,2.9764597659931646,1739141192.5991936,32.01996946334839,2.4701182957074894,1739141192.5991948,32.01996946334839,0.6108,1739141192.599196,32.01996946334839,0.9307574272475365,1739141192.5991979,32.01996946334839,0.0,1739141192.5991993,32.01996946334839,0.013269405192805728,1739141192.5992005,32.01996946334839,2.3768911539093702,1739141192.5992017,32.01996946334839,0.9174880220547308 +1739141192.6191351,32.0399694442749,50.0504908545313,1739141192.619138,32.0399694442749,7.584297139799208,1739141192.6191409,32.0399694442749,58.0680449014455,1739141192.6191437,32.0399694442749,45.73261934188679,1739141192.6191454,32.0399694442749,8.303872319841108,1739141192.619147,32.0399694442749,2.9764597659931646,1739141192.6191485,32.0399694442749,2.4701182957074894,1739141192.61915,32.0399694442749,0.6108,1739141192.619151,32.0399694442749,0.9307574272475365,1739141192.6191525,32.0399694442749,0.0,1739141192.6191545,32.0399694442749,0.013269405192805728,1739141192.6191556,32.0399694442749,2.3768911539093702,1739141192.6191573,32.0399694442749,0.9174880220547308 +1739141192.6390896,32.059969425201416,50.0504908545313,1739141192.6390927,32.059969425201416,7.584297139799208,1739141192.6390958,32.059969425201416,58.0680449014455,1739141192.639099,32.059969425201416,45.73261934188679,1739141192.6391003,32.059969425201416,8.303872319841108,1739141192.6391022,32.059969425201416,2.9764597659931646,1739141192.6391037,32.059969425201416,2.4701182957074894,1739141192.639105,32.059969425201416,0.6108,1739141192.6391063,32.059969425201416,0.9307574272475365,1739141192.6391082,32.059969425201416,0.0,1739141192.6391096,32.059969425201416,0.013269405192805728,1739141192.6391115,32.059969425201416,2.3768911539093702,1739141192.6391127,32.059969425201416,0.9174880220547308 +1739141192.6592302,32.07996940612793,49.97673745454146,1739141192.659233,32.07996940612793,7.653294819123518,1739141192.6592364,32.07996940612793,58.23297941488639,1739141192.6592388,32.07996940612793,45.58071263988134,1739141192.6592405,32.07996940612793,8.228852635836585,1739141192.659242,32.07996940612793,3.0114062809849464,1739141192.6592436,32.07996940612793,2.5281571798137383,1739141192.6592448,32.07996940612793,0.6108,1739141192.659246,32.07996940612793,0.9093982699044184,1739141192.6592476,32.07996940612793,0.0,1739141192.659249,32.07996940612793,-0.030369026413924017,1739141192.659251,32.07996940612793,2.4046154971560076,1739141192.6592522,32.07996940612793,0.9189870804107025 +1739141192.6790414,32.09996938705444,49.97673745454146,1739141192.6790435,32.09996938705444,7.653294819123518,1739141192.6790469,32.09996938705444,58.23297941488639,1739141192.6790497,32.09996938705444,45.58071263988134,1739141192.6790512,32.09996938705444,8.228852635836585,1739141192.679053,32.09996938705444,3.0114062809849464,1739141192.6790547,32.09996938705444,2.5281571798137383,1739141192.6790564,32.09996938705444,0.6108,1739141192.6790574,32.09996938705444,0.9093982699044184,1739141192.679059,32.09996938705444,0.0,1739141192.6790607,32.09996938705444,-0.009588810506284129,1739141192.6790626,32.09996938705444,2.4046154971560076,1739141192.679064,32.09996938705444,0.9189870804107025 +1739141192.6991522,32.11996936798096,49.97673745454146,1739141192.6991549,32.11996936798096,7.653294819123518,1739141192.699158,32.11996936798096,58.23297941488639,1739141192.6991608,32.11996936798096,45.58071263988134,1739141192.699162,32.11996936798096,8.228852635836585,1739141192.699164,32.11996936798096,3.0114062809849464,1739141192.6991653,32.11996936798096,2.5281571798137383,1739141192.699167,32.11996936798096,0.6108,1739141192.6991682,32.11996936798096,0.9093982699044184,1739141192.6991699,32.11996936798096,0.0,1739141192.6991713,32.11996936798096,-0.009588810506284129,1739141192.699173,32.11996936798096,2.4046154971560076,1739141192.6991742,32.11996936798096,0.9189870804107025 +1739141192.7191563,32.13996934890747,49.97673745454146,1739141192.7191591,32.13996934890747,7.653294819123518,1739141192.7191617,32.13996934890747,58.23297941488639,1739141192.7191646,32.13996934890747,45.58071263988134,1739141192.719166,32.13996934890747,8.228852635836585,1739141192.7191677,32.13996934890747,3.0114062809849464,1739141192.7191691,32.13996934890747,2.5281571798137383,1739141192.7191703,32.13996934890747,0.6108,1739141192.7191718,32.13996934890747,0.9093982699044184,1739141192.7191734,32.13996934890747,0.0,1739141192.719175,32.13996934890747,-0.009588810506284129,1739141192.7191763,32.13996934890747,2.4046154971560076,1739141192.7191777,32.13996934890747,0.9189870804107025 +1739141192.7393205,32.159969329833984,49.97673745454146,1739141192.7393243,32.159969329833984,7.653294819123518,1739141192.7393296,32.159969329833984,58.23297941488639,1739141192.739335,32.159969329833984,45.58071263988134,1739141192.7393386,32.159969329833984,8.228852635836585,1739141192.739343,32.159969329833984,3.0114062809849464,1739141192.7393467,32.159969329833984,2.5281571798137383,1739141192.7393503,32.159969329833984,0.6108,1739141192.739354,32.159969329833984,0.9093982699044184,1739141192.7393577,32.159969329833984,0.0,1739141192.7393615,32.159969329833984,-0.009588810506284129,1739141192.7393653,32.159969329833984,2.4046154971560076,1739141192.739369,32.159969329833984,0.9189870804107025 +1739141192.759347,32.1799693107605,49.97673745454146,1739141192.7593498,32.1799693107605,7.653294819123518,1739141192.7593534,32.1799693107605,58.23297941488639,1739141192.7593567,32.1799693107605,45.58071263988134,1739141192.7593582,32.1799693107605,8.228852635836585,1739141192.7593603,32.1799693107605,3.0114062809849464,1739141192.759362,32.1799693107605,2.5281571798137383,1739141192.7593637,32.1799693107605,0.6108,1739141192.7593648,32.1799693107605,0.9093982699044184,1739141192.759367,32.1799693107605,0.0,1739141192.7593687,32.1799693107605,-0.009588810506284129,1739141192.7593703,32.1799693107605,2.4046154971560076,1739141192.759372,32.1799693107605,0.9189870804107025 +1739141192.779479,32.19996929168701,49.9011023663734,1739141192.7794821,32.19996929168701,7.720220111754914,1739141192.7794855,32.19996929168701,58.23470755904706,1739141192.7794888,32.19996929168701,45.58308320854606,1739141192.7794905,32.19996929168701,8.230068312074902,1739141192.7794926,32.19996929168701,3.0240622676796614,1739141192.779494,32.19996929168701,2.4252855248270633,1739141192.7794957,32.19996929168701,0.6108,1739141192.7794971,32.19996929168701,0.9475993638202701,1739141192.779499,32.19996929168701,0.0,1739141192.7795007,32.19996929168701,0.06613565372432018,1739141192.7795024,32.19996929168701,2.432339840402645,1739141192.7795038,32.19996929168701,0.9175229967903792 +1739141192.7993429,32.219969272613525,49.9011023663734,1739141192.7993457,32.219969272613525,7.720220111754914,1739141192.7993493,32.219969272613525,58.23470755904706,1739141192.7993526,32.219969272613525,45.58308320854606,1739141192.7993543,32.219969272613525,8.230068312074902,1739141192.7993565,32.219969272613525,3.0240622676796614,1739141192.799358,32.219969272613525,2.4252855248270633,1739141192.7993598,32.219969272613525,0.6108,1739141192.7993615,32.219969272613525,0.9475993638202701,1739141192.7993634,32.219969272613525,0.0,1739141192.7993648,32.219969272613525,0.030076367029890916,1739141192.7993665,32.219969272613525,2.432339840402645,1739141192.799368,32.219969272613525,0.9175229967903792 +1739141192.819268,32.23996925354004,49.9011023663734,1739141192.8192708,32.23996925354004,7.720220111754914,1739141192.8192742,32.23996925354004,58.23470755904706,1739141192.8192778,32.23996925354004,45.58308320854606,1739141192.8192794,32.23996925354004,8.230068312074902,1739141192.8192816,32.23996925354004,3.0240622676796614,1739141192.8192832,32.23996925354004,2.4252855248270633,1739141192.8192847,32.23996925354004,0.6108,1739141192.8192863,32.23996925354004,0.9475993638202701,1739141192.8192883,32.23996925354004,0.0,1739141192.8192902,32.23996925354004,0.030076367029890916,1739141192.8192916,32.23996925354004,2.432339840402645,1739141192.8192933,32.23996925354004,0.9175229967903792 +1739141192.839531,32.25996923446655,49.9011023663734,1739141192.8395338,32.25996923446655,7.720220111754914,1739141192.8395371,32.25996923446655,58.23470755904706,1739141192.8395402,32.25996923446655,45.58308320854606,1739141192.839542,32.25996923446655,8.230068312074902,1739141192.8395438,32.25996923446655,3.0240622676796614,1739141192.8395455,32.25996923446655,2.4252855248270633,1739141192.839547,32.25996923446655,0.6108,1739141192.8395486,32.25996923446655,0.9475993638202701,1739141192.8395505,32.25996923446655,0.0,1739141192.8395522,32.25996923446655,0.030076367029890916,1739141192.8395536,32.25996923446655,2.432339840402645,1739141192.839555,32.25996923446655,0.9175229967903792 +1739141192.8595014,32.279969215393066,49.9011023663734,1739141192.859505,32.279969215393066,7.720220111754914,1739141192.8595088,32.279969215393066,58.23470755904706,1739141192.859512,32.279969215393066,45.58308320854606,1739141192.8595135,32.279969215393066,8.230068312074902,1739141192.8595157,32.279969215393066,3.0240622676796614,1739141192.859517,32.279969215393066,2.4252855248270633,1739141192.8595188,32.279969215393066,0.6108,1739141192.8595202,32.279969215393066,0.9475993638202701,1739141192.8595223,32.279969215393066,0.0,1739141192.859524,32.279969215393066,0.030076367029890916,1739141192.859526,32.279969215393066,2.432339840402645,1739141192.8595273,32.279969215393066,0.9175229967903792 +1739141192.8796296,32.29996919631958,49.82354998644381,1739141192.8796332,32.29996919631958,7.7850975558710385,1739141192.8796372,32.29996919631958,58.23644206680723,1739141192.8796427,32.29996919631958,45.57187328797809,1739141192.8796444,32.29996919631958,8.22431963486056,1739141192.879647,32.29996919631958,3.038652196793843,1739141192.8796484,32.29996919631958,2.337370051718745,1739141192.8796504,32.29996919631958,0.6108,1739141192.8796523,32.29996919631958,0.9815156810131743,1739141192.8796544,32.29996919631958,0.0,1739141192.8796568,32.29996919631958,0.08791259456996209,1739141192.8796585,32.29996919631958,2.4600641836492825,1739141192.8796604,32.29996919631958,0.9211441609345494 +1739141192.9001667,32.319969177246094,49.82354998644381,1739141192.9001706,32.319969177246094,7.7850975558710385,1739141192.9001744,32.319969177246094,58.23644206680723,1739141192.9001782,32.319969177246094,45.57187328797809,1739141192.9001799,32.319969177246094,8.22431963486056,1739141192.9001825,32.319969177246094,3.038652196793843,1739141192.9001846,32.319969177246094,2.337370051718745,1739141192.9001865,32.319969177246094,0.6108,1739141192.9001884,32.319969177246094,0.9815156810131743,1739141192.9001908,32.319969177246094,0.0,1739141192.9001927,32.319969177246094,0.060371520078624896,1739141192.9001946,32.319969177246094,2.4600641836492825,1739141192.9001963,32.319969177246094,0.9211441609345494 +1739141192.919583,32.33996915817261,49.82354998644381,1739141192.9195864,32.33996915817261,7.7850975558710385,1739141192.9195905,32.33996915817261,58.23644206680723,1739141192.9195943,32.33996915817261,45.57187328797809,1739141192.9195962,32.33996915817261,8.22431963486056,1739141192.9195988,32.33996915817261,3.038652196793843,1739141192.9196007,32.33996915817261,2.337370051718745,1739141192.9196022,32.33996915817261,0.6108,1739141192.919604,32.33996915817261,0.9815156810131743,1739141192.9196062,32.33996915817261,0.0,1739141192.9196084,32.33996915817261,0.060371520078624896,1739141192.91961,32.33996915817261,2.4600641836492825,1739141192.919612,32.33996915817261,0.9211441609345494 +1739141192.939863,32.35996913909912,49.82354998644381,1739141192.9398677,32.35996913909912,7.7850975558710385,1739141192.9398723,32.35996913909912,58.23644206680723,1739141192.9398763,32.35996913909912,45.57187328797809,1739141192.9398785,32.35996913909912,8.22431963486056,1739141192.9398808,32.35996913909912,3.038652196793843,1739141192.9398828,32.35996913909912,2.337370051718745,1739141192.9398847,32.35996913909912,0.6108,1739141192.939886,32.35996913909912,0.9815156810131743,1739141192.9398885,32.35996913909912,0.0,1739141192.9398904,32.35996913909912,0.060371520078624896,1739141192.9398923,32.35996913909912,2.4600641836492825,1739141192.939894,32.35996913909912,0.9211441609345494 +1739141192.96019,32.379969120025635,49.82354998644381,1739141192.9601939,32.379969120025635,7.7850975558710385,1739141192.960198,32.379969120025635,58.23644206680723,1739141192.9602017,32.379969120025635,45.57187328797809,1739141192.9602034,32.379969120025635,8.22431963486056,1739141192.960206,32.379969120025635,3.038652196793843,1739141192.9602082,32.379969120025635,2.337370051718745,1739141192.96021,32.379969120025635,0.6108,1739141192.960212,32.379969120025635,0.9815156810131743,1739141192.960214,32.379969120025635,0.0,1739141192.960216,32.379969120025635,0.060371520078624896,1739141192.960218,32.379969120025635,2.4600641836492825,1739141192.9602196,32.379969120025635,0.9211441609345494 +1739141192.9797463,32.39996910095215,49.82354998644381,1739141192.9797502,32.39996910095215,7.7850975558710385,1739141192.979754,32.39996910095215,58.23644206680723,1739141192.9797573,32.39996910095215,45.57187328797809,1739141192.9797587,32.39996910095215,8.22431963486056,1739141192.979761,32.39996910095215,3.038652196793843,1739141192.9797623,32.39996910095215,2.337370051718745,1739141192.979764,32.39996910095215,0.6108,1739141192.9797652,32.39996910095215,0.9815156810131743,1739141192.9797673,32.39996910095215,0.0,1739141192.9797688,32.39996910095215,0.060371520078624896,1739141192.9797704,32.39996910095215,2.4600641836492825,1739141192.9797719,32.39996910095215,0.9211441609345494 +1739141192.9993818,32.41996908187866,49.7437616413725,1739141192.999385,32.41996908187866,7.848168659393352,1739141192.9993887,32.41996908187866,58.473584604290295,1739141192.9993918,32.41996908187866,45.34620701282137,1739141192.9993935,32.41996908187866,8.098079406208344,1739141192.9993954,32.41996908187866,3.0848242330423923,1739141192.9993968,32.41996908187866,2.4762654488330886,1739141192.9993985,32.41996908187866,0.6108,1739141192.9994,32.41996908187866,0.9284716352506461,1739141192.9994018,32.41996908187866,0.0,1739141192.9994035,32.41996908187866,-0.054573891269075185,1739141192.9994051,32.41996908187866,2.48778852689592,1739141192.999407,32.41996908187866,0.9283095890111577 +1739141193.0192175,32.439969062805176,49.7437616413725,1739141193.0192218,32.439969062805176,7.848168659393352,1739141193.0192251,32.439969062805176,58.473584604290295,1739141193.0192285,32.439969062805176,45.34620701282137,1739141193.0192301,32.439969062805176,8.098079406208344,1739141193.019232,32.439969062805176,3.0848242330423923,1739141193.0192337,32.439969062805176,2.4762654488330886,1739141193.0192354,32.439969062805176,0.6108,1739141193.0192368,32.439969062805176,0.9284716352506461,1739141193.019239,32.439969062805176,0.0,1739141193.0192406,32.439969062805176,0.00016204623948845587,1739141193.0192423,32.439969062805176,2.48778852689592,1739141193.0192437,32.439969062805176,0.9283095890111577 +1739141193.0393894,32.45996904373169,49.7437616413725,1739141193.0393927,32.45996904373169,7.848168659393352,1739141193.039396,32.45996904373169,58.473584604290295,1739141193.0393991,32.45996904373169,45.34620701282137,1739141193.039401,32.45996904373169,8.098079406208344,1739141193.039403,32.45996904373169,3.0848242330423923,1739141193.0394046,32.45996904373169,2.4762654488330886,1739141193.0394063,32.45996904373169,0.6108,1739141193.0394077,32.45996904373169,0.9284716352506461,1739141193.0394094,32.45996904373169,0.0,1739141193.0394113,32.45996904373169,0.00016204623948845587,1739141193.0394127,32.45996904373169,2.48778852689592,1739141193.0394142,32.45996904373169,0.9283095890111577 +1739141193.0603373,32.4799690246582,49.7437616413725,1739141193.060342,32.4799690246582,7.848168659393352,1739141193.0603454,32.4799690246582,58.473584604290295,1739141193.0603492,32.4799690246582,45.34620701282137,1739141193.0603507,32.4799690246582,8.098079406208344,1739141193.0603528,32.4799690246582,3.0848242330423923,1739141193.0603545,32.4799690246582,2.4762654488330886,1739141193.0603566,32.4799690246582,0.6108,1739141193.0603578,32.4799690246582,0.9284716352506461,1739141193.06036,32.4799690246582,0.0,1739141193.0603616,32.4799690246582,0.00016204623948845587,1739141193.0603633,32.4799690246582,2.48778852689592,1739141193.0603647,32.4799690246582,0.9283095890111577 +1739141193.0790393,32.49996900558472,49.7437616413725,1739141193.0790422,32.49996900558472,7.848168659393352,1739141193.0790453,32.49996900558472,58.473584604290295,1739141193.0790486,32.49996900558472,45.34620701282137,1739141193.0790503,32.49996900558472,8.098079406208344,1739141193.079052,32.49996900558472,3.0848242330423923,1739141193.0790539,32.49996900558472,2.4762654488330886,1739141193.079055,32.49996900558472,0.6108,1739141193.0790572,32.49996900558472,0.9284716352506461,1739141193.0790591,32.49996900558472,0.0,1739141193.0790608,32.49996900558472,0.00016204623948845587,1739141193.0790622,32.49996900558472,2.48778852689592,1739141193.0790641,32.49996900558472,0.9283095890111577 +1739141193.099218,32.51996898651123,49.66195843822704,1739141193.0992208,32.51996898651123,7.909227981399017,1739141193.0992236,32.51996898651123,58.59140027657001,1739141193.0992265,32.51996898651123,45.24647545614025,1739141193.099228,32.51996898651123,8.038090499933984,1739141193.0992298,32.51996898651123,3.112416694171976,1739141193.099231,32.51996898651123,2.482930750064745,1739141193.0992327,32.51996898651123,0.6108,1739141193.099234,32.51996898651123,0.9259995149467098,1739141193.0992358,32.51996898651123,0.0,1739141193.0992374,32.51996898651123,-0.0036458929079879973,1739141193.0992389,32.51996898651123,2.5155128701425573,1739141193.0992408,32.51996898651123,0.9278321025929315 +1739141193.1189322,32.539968967437744,49.66195843822704,1739141193.118935,32.539968967437744,7.909227981399017,1739141193.118938,32.539968967437744,58.59140027657001,1739141193.1189408,32.539968967437744,45.24647545614025,1739141193.1189425,32.539968967437744,8.038090499933984,1739141193.1189442,32.539968967437744,3.112416694171976,1739141193.1189458,32.539968967437744,2.482930750064745,1739141193.118947,32.539968967437744,0.6108,1739141193.1189485,32.539968967437744,0.9259995149467098,1739141193.11895,32.539968967437744,0.0,1739141193.1189537,32.539968967437744,-0.0018325876462216284,1739141193.1189582,32.539968967437744,2.5155128701425573,1739141193.1189609,32.539968967437744,0.9278321025929315 +1739141193.1392057,32.55996894836426,49.66195843822704,1739141193.139209,32.55996894836426,7.909227981399017,1739141193.1392126,32.55996894836426,58.59140027657001,1739141193.1392164,32.55996894836426,45.24647545614025,1739141193.139218,32.55996894836426,8.038090499933984,1739141193.1392202,32.55996894836426,3.112416694171976,1739141193.1392224,32.55996894836426,2.482930750064745,1739141193.139224,32.55996894836426,0.6108,1739141193.1392255,32.55996894836426,0.9259995149467098,1739141193.1392279,32.55996894836426,0.0,1739141193.1392298,32.55996894836426,-0.0018325876462216284,1739141193.1392317,32.55996894836426,2.5155128701425573,1739141193.1392334,32.55996894836426,0.9278321025929315 +1739141193.1604319,32.57996892929077,49.66195843822704,1739141193.1604362,32.57996892929077,7.909227981399017,1739141193.1604412,32.57996892929077,58.59140027657001,1739141193.1604455,32.57996892929077,45.24647545614025,1739141193.1604476,32.57996892929077,8.038090499933984,1739141193.16045,32.57996892929077,3.112416694171976,1739141193.1604521,32.57996892929077,2.482930750064745,1739141193.1604538,32.57996892929077,0.6108,1739141193.1604557,32.57996892929077,0.9259995149467098,1739141193.160458,32.57996892929077,0.0,1739141193.1604605,32.57996892929077,-0.0018325876462216284,1739141193.1604626,32.57996892929077,2.5155128701425573,1739141193.1604645,32.57996892929077,0.9278321025929315 +1739141193.1796646,32.599968910217285,49.66195843822704,1739141193.1796682,32.599968910217285,7.909227981399017,1739141193.1796718,32.599968910217285,58.59140027657001,1739141193.1796756,32.599968910217285,45.24647545614025,1739141193.1796775,32.599968910217285,8.038090499933984,1739141193.17968,32.599968910217285,3.112416694171976,1739141193.179682,32.599968910217285,2.482930750064745,1739141193.179684,32.599968910217285,0.6108,1739141193.1796858,32.599968910217285,0.9259995149467098,1739141193.179688,32.599968910217285,0.0,1739141193.1796906,32.599968910217285,-0.0018325876462216284,1739141193.1796923,32.599968910217285,2.5155128701425573,1739141193.1796942,32.599968910217285,0.9278321025929315 +1739141193.2000048,32.6199688911438,49.66195843822704,1739141193.2000089,32.6199688911438,7.909227981399017,1739141193.2000139,32.6199688911438,58.59140027657001,1739141193.200018,32.6199688911438,45.24647545614025,1739141193.20002,32.6199688911438,8.038090499933984,1739141193.2000225,32.6199688911438,3.112416694171976,1739141193.2000246,32.6199688911438,2.482930750064745,1739141193.2000263,32.6199688911438,0.6108,1739141193.2000282,32.6199688911438,0.9259995149467098,1739141193.2000306,32.6199688911438,0.0,1739141193.2000325,32.6199688911438,-0.0018325876462216284,1739141193.2000346,32.6199688911438,2.5155128701425573,1739141193.2000365,32.6199688911438,0.9278321025929315 +1739141193.220537,32.63996887207031,49.578521467707894,1739141193.220548,32.63996887207031,7.9679767039441955,1739141193.220557,32.63996887207031,58.76023600274409,1739141193.2205648,32.63996887207031,45.106468534401465,1739141193.2205706,32.63996887207031,7.9450322197724255,1739141193.2205775,32.63996887207031,-3.1364620607298312,1739141193.2205846,32.63996887207031,2.5379958187475418,1739141193.2205884,32.63996887207031,0.6108,1739141193.2205908,32.63996887207031,0.9058264064795116,1739141193.2205932,32.63996887207031,0.0,1739141193.2205954,32.63996887207031,-0.0398925902499365,1739141193.2205973,32.63996887207031,2.5432372133891947,1739141193.220599,32.63996887207031,0.9275951769121346 +1739141193.2398174,32.659968852996826,49.578521467707894,1739141193.2398257,32.659968852996826,7.9679767039441955,1739141193.2398345,32.659968852996826,58.76023600274409,1739141193.239844,32.659968852996826,45.106468534401465,1739141193.239848,32.659968852996826,7.9450322197724255,1739141193.239853,32.659968852996826,-3.1364620607298312,1739141193.2398567,32.659968852996826,2.5379958187475418,1739141193.2398615,32.659968852996826,0.6108,1739141193.2398667,32.659968852996826,0.9058264064795116,1739141193.2398715,32.659968852996826,0.0,1739141193.239878,32.659968852996826,-0.02176877043262293,1739141193.2398841,32.659968852996826,2.5432372133891947,1739141193.239887,32.659968852996826,0.9275951769121346 +1739141193.260491,32.67996883392334,49.578521467707894,1739141193.2604957,32.67996883392334,7.9679767039441955,1739141193.2605002,32.67996883392334,58.76023600274409,1739141193.2605042,32.67996883392334,45.106468534401465,1739141193.2605066,32.67996883392334,7.9450322197724255,1739141193.2605093,32.67996883392334,-3.1364620607298312,1739141193.2605112,32.67996883392334,2.5379958187475418,1739141193.260513,32.67996883392334,0.6108,1739141193.2605147,32.67996883392334,0.9058264064795116,1739141193.2605171,32.67996883392334,0.0,1739141193.2605193,32.67996883392334,-0.02176877043262293,1739141193.260521,32.67996883392334,2.5432372133891947,1739141193.2605233,32.67996883392334,0.9275951769121346 +1739141193.279849,32.69996881484985,49.578521467707894,1739141193.2798529,32.69996881484985,7.9679767039441955,1739141193.2798572,32.69996881484985,58.76023600274409,1739141193.279861,32.69996881484985,45.106468534401465,1739141193.279863,32.69996881484985,7.9450322197724255,1739141193.2798667,32.69996881484985,-3.1364620607298312,1739141193.2798688,32.69996881484985,2.5379958187475418,1739141193.2798707,32.69996881484985,0.6108,1739141193.2798727,32.69996881484985,0.9058264064795116,1739141193.279875,32.69996881484985,0.0,1739141193.279877,32.69996881484985,-0.02176877043262293,1739141193.2798789,32.69996881484985,2.5432372133891947,1739141193.2798808,32.69996881484985,0.9275951769121346 +1739141193.3005943,32.71996879577637,49.578521467707894,1739141193.3005986,32.71996879577637,7.9679767039441955,1739141193.3006027,32.71996879577637,58.76023600274409,1739141193.3006067,32.71996879577637,45.106468534401465,1739141193.3006089,32.71996879577637,7.9450322197724255,1739141193.300611,32.71996879577637,-3.1364620607298312,1739141193.300613,32.71996879577637,2.5379958187475418,1739141193.3006146,32.71996879577637,0.6108,1739141193.3006182,32.71996879577637,0.9058264064795116,1739141193.3006206,32.71996879577637,0.0,1739141193.3006227,32.71996879577637,-0.02176877043262293,1739141193.3006246,32.71996879577637,2.5432372133891947,1739141193.3006265,32.71996879577637,0.9275951769121346 +1739141193.3199046,32.73996877670288,49.493607407055514,1739141193.3199117,32.73996877670288,8.02431143207167,1739141193.3199182,32.73996877670288,58.84895619180689,1739141193.319925,32.73996877670288,45.04030073873502,1739141193.3199294,32.73996877670288,7.898184582579939,1739141193.3199356,32.73996877670288,-3.1132781557728806,1739141193.3199399,32.73996877670288,2.5116560009828737,1739141193.3199456,32.73996877670288,0.6108,1739141193.3199515,32.73996877670288,0.9154205804771391,1739141193.3199546,32.73996877670288,0.0,1739141193.319957,32.73996877670288,0.0014128713585307984,1739141193.3199587,32.73996877670288,2.570961556635832,1739141193.3199606,32.73996877670288,0.925046591676419 +1739141193.3399146,32.759968757629395,49.493607407055514,1739141193.3399184,32.759968757629395,8.02431143207167,1739141193.3399224,32.759968757629395,58.84895619180689,1739141193.3399265,32.759968757629395,45.04030073873502,1739141193.3399284,32.759968757629395,7.898184582579939,1739141193.3399308,32.759968757629395,-3.1132781557728806,1739141193.3399332,32.759968757629395,2.5116560009828737,1739141193.339935,32.759968757629395,0.6108,1739141193.3399367,32.759968757629395,0.9154205804771391,1739141193.3399394,32.759968757629395,0.0,1739141193.339942,32.759968757629395,-0.00962601119927986,1739141193.3399441,32.759968757629395,2.570961556635832,1739141193.3399467,32.759968757629395,0.925046591676419 +1739141193.360369,32.77996873855591,49.493607407055514,1739141193.3603735,32.77996873855591,8.02431143207167,1739141193.360378,32.77996873855591,58.84895619180689,1739141193.3603826,32.77996873855591,45.04030073873502,1739141193.3603845,32.77996873855591,7.898184582579939,1739141193.360387,32.77996873855591,-3.1132781557728806,1739141193.3603895,32.77996873855591,2.5116560009828737,1739141193.3603914,32.77996873855591,0.6108,1739141193.3603935,32.77996873855591,0.9154205804771391,1739141193.3603957,32.77996873855591,0.0,1739141193.360398,32.77996873855591,-0.00962601119927986,1739141193.3604,32.77996873855591,2.570961556635832,1739141193.3604019,32.77996873855591,0.925046591676419 +1739141193.3798528,32.79996871948242,49.493607407055514,1739141193.3798566,32.79996871948242,8.02431143207167,1739141193.3798614,32.79996871948242,58.84895619180689,1739141193.3798654,32.79996871948242,45.04030073873502,1739141193.3798673,32.79996871948242,7.898184582579939,1739141193.37987,32.79996871948242,-3.1132781557728806,1739141193.3798718,32.79996871948242,2.5116560009828737,1739141193.3798738,32.79996871948242,0.6108,1739141193.379876,32.79996871948242,0.9154205804771391,1739141193.3798778,32.79996871948242,0.0,1739141193.37988,32.79996871948242,-0.00962601119927986,1739141193.379882,32.79996871948242,2.570961556635832,1739141193.3798838,32.79996871948242,0.925046591676419 +1739141193.4001124,32.819968700408936,49.493607407055514,1739141193.400117,32.819968700408936,8.02431143207167,1739141193.400122,32.819968700408936,58.84895619180689,1739141193.400126,32.819968700408936,45.04030073873502,1739141193.4001284,32.819968700408936,7.898184582579939,1739141193.4001307,32.819968700408936,-3.1132781557728806,1739141193.4001327,32.819968700408936,2.5116560009828737,1739141193.4001343,32.819968700408936,0.6108,1739141193.4001365,32.819968700408936,0.9154205804771391,1739141193.4001389,32.819968700408936,0.0,1739141193.400141,32.819968700408936,-0.00962601119927986,1739141193.4001431,32.819968700408936,2.570961556635832,1739141193.4001448,32.819968700408936,0.925046591676419 +1739141193.4203773,32.83996868133545,49.493607407055514,1739141193.4203875,32.83996868133545,8.02431143207167,1739141193.420397,32.83996868133545,58.84895619180689,1739141193.4204047,32.83996868133545,45.04030073873502,1739141193.4204087,32.83996868133545,7.898184582579939,1739141193.4204133,32.83996868133545,-3.1132781557728806,1739141193.4204164,32.83996868133545,2.5116560009828737,1739141193.4204192,32.83996868133545,0.6108,1739141193.420423,32.83996868133545,0.9154205804771391,1739141193.4204283,32.83996868133545,0.0,1739141193.4204345,32.83996868133545,-0.00962601119927986,1739141193.4204404,32.83996868133545,2.570961556635832,1739141193.420443,32.83996868133545,0.925046591676419 +1739141193.439627,32.85996866226196,49.40731843733344,1739141193.4396305,32.85996866226196,8.078173910073689,1739141193.4396348,32.85996866226196,58.93817043045975,1739141193.4396384,32.85996866226196,44.97068682774282,1739141193.43964,32.85996866226196,7.84649763264389,1739141193.4396424,32.85996866226196,-3.0894210824841335,1739141193.4396443,32.85996866226196,2.490447201841703,1739141193.4396462,32.85996866226196,0.6108,1739141193.439648,32.85996866226196,0.9232196037746203,1739141193.4396503,32.85996866226196,0.0,1739141193.4396524,32.85996866226196,0.006858844290765245,1739141193.439654,32.85996866226196,2.5986858998824696,1739141193.439656,32.85996866226196,0.9242106945909764 +1739141193.4601645,32.87996864318848,49.40731843733344,1739141193.4601777,32.87996864318848,8.078173910073689,1739141193.4601834,32.87996864318848,58.93817043045975,1739141193.46019,32.87996864318848,44.97068682774282,1739141193.460212,32.87996864318848,7.84649763264389,1739141193.4602172,32.87996864318848,-3.0894210824841335,1739141193.4602222,32.87996864318848,2.490447201841703,1739141193.460226,32.87996864318848,0.6108,1739141193.4602304,32.87996864318848,0.9232196037746203,1739141193.4602358,32.87996864318848,0.0,1739141193.4602401,32.87996864318848,-0.000991090816356066,1739141193.460251,32.87996864318848,2.5986858998824696,1739141193.4602535,32.87996864318848,0.9242106945909764 +1739141193.4792194,32.89996862411499,49.40731843733344,1739141193.4792225,32.89996862411499,8.078173910073689,1739141193.4792259,32.89996862411499,58.93817043045975,1739141193.4792287,32.89996862411499,44.97068682774282,1739141193.4792304,32.89996862411499,7.84649763264389,1739141193.4792323,32.89996862411499,-3.0894210824841335,1739141193.4792342,32.89996862411499,2.490447201841703,1739141193.479236,32.89996862411499,0.6108,1739141193.479237,32.89996862411499,0.9232196037746203,1739141193.4792387,32.89996862411499,0.0,1739141193.4792404,32.89996862411499,-0.000991090816356066,1739141193.4792426,32.89996862411499,2.5986858998824696,1739141193.479244,32.89996862411499,0.9242106945909764 +1739141193.4989743,32.919968605041504,49.40731843733344,1739141193.4989774,32.919968605041504,8.078173910073689,1739141193.4989824,32.919968605041504,58.93817043045975,1739141193.4989862,32.919968605041504,44.97068682774282,1739141193.4989886,32.919968605041504,7.84649763264389,1739141193.4989917,32.919968605041504,-3.0894210824841335,1739141193.4989939,32.919968605041504,2.490447201841703,1739141193.4989963,32.919968605041504,0.6108,1739141193.4989982,32.919968605041504,0.9232196037746203,1739141193.4990005,32.919968605041504,0.0,1739141193.499003,32.919968605041504,-0.000991090816356066,1739141193.499005,32.919968605041504,2.5986858998824696,1739141193.4990075,32.919968605041504,0.9242106945909764 +1739141193.5189795,32.93996858596802,49.40731843733344,1739141193.5189834,32.93996858596802,8.078173910073689,1739141193.5189874,32.93996858596802,58.93817043045975,1739141193.5189917,32.93996858596802,44.97068682774282,1739141193.5189939,32.93996858596802,7.84649763264389,1739141193.5189965,32.93996858596802,-3.0894210824841335,1739141193.518999,32.93996858596802,2.490447201841703,1739141193.5190012,32.93996858596802,0.6108,1739141193.5190034,32.93996858596802,0.9232196037746203,1739141193.519006,32.93996858596802,0.0,1739141193.5190082,32.93996858596802,-0.000991090816356066,1739141193.519011,32.93996858596802,2.5986858998824696,1739141193.5190136,32.93996858596802,0.9242106945909764 +1739141193.5388954,32.95996856689453,49.31962176873757,1739141193.538898,32.95996856689453,8.129592786676351,1739141193.538901,32.95996856689453,59.02796645799863,1739141193.5389037,32.95996856689453,44.899667285619145,1739141193.5389054,32.95996856689453,7.791733828495318,1739141193.538907,32.95996856689453,-3.0653015467230063,1739141193.5389087,32.95996856689453,2.4716890809778755,1739141193.5389102,32.95996856689453,0.6108,1739141193.5389118,32.95996856689453,0.9301728029078207,1739141193.5389163,32.95996856689453,0.0,1739141193.5389202,32.95996856689453,0.012355275272820796,1739141193.5389228,32.95996856689453,2.626410243129107,1739141193.5389247,32.95996856689453,0.9241729432332252 +1739141193.5594149,32.979968547821045,49.31962176873757,1739141193.559419,32.979968547821045,8.129592786676351,1739141193.5594223,32.979968547821045,59.02796645799863,1739141193.559425,32.979968547821045,44.899667285619145,1739141193.5594265,32.979968547821045,7.791733828495318,1739141193.5594282,32.979968547821045,-3.0653015467230063,1739141193.5594296,32.979968547821045,2.4716890809778755,1739141193.5594308,32.979968547821045,0.6108,1739141193.5594323,32.979968547821045,0.9301728029078207,1739141193.559434,32.979968547821045,0.0,1739141193.5594356,32.979968547821045,0.005999859674595487,1739141193.5594368,32.979968547821045,2.626410243129107,1739141193.559438,32.979968547821045,0.9241729432332252 +1739141193.5789492,32.99996852874756,49.31962176873757,1739141193.5789518,32.99996852874756,8.129592786676351,1739141193.578955,32.99996852874756,59.02796645799863,1739141193.5789578,32.99996852874756,44.899667285619145,1739141193.5789595,32.99996852874756,7.791733828495318,1739141193.578961,32.99996852874756,-3.0653015467230063,1739141193.5789623,32.99996852874756,2.4716890809778755,1739141193.5789638,32.99996852874756,0.6108,1739141193.578965,32.99996852874756,0.9301728029078207,1739141193.5789669,32.99996852874756,0.0,1739141193.5789683,32.99996852874756,0.005999859674595487,1739141193.57897,32.99996852874756,2.626410243129107,1739141193.5789711,32.99996852874756,0.9241729432332252 +1739141193.5994947,33.01996850967407,49.31962176873757,1739141193.599498,33.01996850967407,8.129592786676351,1739141193.5995016,33.01996850967407,59.02796645799863,1739141193.5995045,33.01996850967407,44.899667285619145,1739141193.599506,33.01996850967407,7.791733828495318,1739141193.599508,33.01996850967407,-3.0653015467230063,1739141193.5995095,33.01996850967407,2.4716890809778755,1739141193.5995111,33.01996850967407,0.6108,1739141193.5995126,33.01996850967407,0.9301728029078207,1739141193.5995145,33.01996850967407,0.0,1739141193.599516,33.01996850967407,0.005999859674595487,1739141193.5995173,33.01996850967407,2.626410243129107,1739141193.5995188,33.01996850967407,0.9241729432332252 +1739141193.6189582,33.039968490600586,49.31962176873757,1739141193.618961,33.039968490600586,8.129592786676351,1739141193.6189642,33.039968490600586,59.02796645799863,1739141193.618967,33.039968490600586,44.899667285619145,1739141193.6189685,33.039968490600586,7.791733828495318,1739141193.6189704,33.039968490600586,-3.0653015467230063,1739141193.6189718,33.039968490600586,2.4716890809778755,1739141193.6189733,33.039968490600586,0.6108,1739141193.6189744,33.039968490600586,0.9301728029078207,1739141193.6189764,33.039968490600586,0.0,1739141193.6189778,33.039968490600586,0.005999859674595487,1739141193.6189792,33.039968490600586,2.626410243129107,1739141193.618981,33.039968490600586,0.9241729432332252 +1739141193.639012,33.0599684715271,49.31962176873757,1739141193.639017,33.0599684715271,8.129592786676351,1739141193.639022,33.0599684715271,59.02796645799863,1739141193.639029,33.0599684715271,44.899667285619145,1739141193.6390326,33.0599684715271,7.791733828495318,1739141193.6390374,33.0599684715271,-3.0653015467230063,1739141193.6390412,33.0599684715271,2.4716890809778755,1739141193.6390438,33.0599684715271,0.6108,1739141193.6390457,33.0599684715271,0.9301728029078207,1739141193.6390479,33.0599684715271,0.0,1739141193.63905,33.0599684715271,0.005999859674595487,1739141193.6390517,33.0599684715271,2.626410243129107,1739141193.6390538,33.0599684715271,0.9241729432332252 +1739141193.6592135,33.07996845245361,49.230496973905026,1739141193.6592185,33.07996845245361,8.17858070946744,1739141193.6592243,33.07996845245361,59.11170629699477,1739141193.659228,33.07996845245361,44.83247582039183,1739141193.6592298,33.07996845245361,7.737909663761984,1739141193.6592314,33.07996845245361,-3.041728388068775,1739141193.659233,33.07996845245361,2.449296379031684,1739141193.6592343,33.07996845245361,0.6108,1739141193.6592355,33.07996845245361,0.9385418610527679,1739141193.6592374,33.07996845245361,0.0,1739141193.659239,33.07996845245361,0.02048040730824931,1739141193.6592405,33.07996845245361,2.6541345863757444,1739141193.659242,33.07996845245361,0.9249569560622918 +1739141193.6792784,33.09996843338013,49.230496973905026,1739141193.6792812,33.09996843338013,8.17858070946744,1739141193.6792848,33.09996843338013,59.11170629699477,1739141193.679288,33.09996843338013,44.83247582039183,1739141193.6792893,33.09996843338013,7.737909663761984,1739141193.6792915,33.09996843338013,-3.041728388068775,1739141193.679293,33.09996843338013,2.449296379031684,1739141193.6792943,33.09996843338013,0.6108,1739141193.679296,33.09996843338013,0.9385418610527679,1739141193.6792974,33.09996843338013,0.0,1739141193.6792994,33.09996843338013,0.013584904990476154,1739141193.6793005,33.09996843338013,2.6541345863757444,1739141193.6793025,33.09996843338013,0.9249569560622918 +1739141193.6989717,33.11996841430664,49.230496973905026,1739141193.6989753,33.11996841430664,8.17858070946744,1739141193.6989794,33.11996841430664,59.11170629699477,1739141193.6989827,33.11996841430664,44.83247582039183,1739141193.6989846,33.11996841430664,7.737909663761984,1739141193.6989872,33.11996841430664,-3.041728388068775,1739141193.6989899,33.11996841430664,2.449296379031684,1739141193.6989918,33.11996841430664,0.6108,1739141193.6989937,33.11996841430664,0.9385418610527679,1739141193.6989963,33.11996841430664,0.0,1739141193.6989982,33.11996841430664,0.013584904990476154,1739141193.6990004,33.11996841430664,2.6541345863757444,1739141193.6990027,33.11996841430664,0.9249569560622918 +1739141193.7189887,33.139968395233154,49.230496973905026,1739141193.7189918,33.139968395233154,8.17858070946744,1739141193.718996,33.139968395233154,59.11170629699477,1739141193.7189999,33.139968395233154,44.83247582039183,1739141193.7190015,33.139968395233154,7.737909663761984,1739141193.7190042,33.139968395233154,-3.041728388068775,1739141193.7190063,33.139968395233154,2.449296379031684,1739141193.7190082,33.139968395233154,0.6108,1739141193.7190106,33.139968395233154,0.9385418610527679,1739141193.7190132,33.139968395233154,0.0,1739141193.7190156,33.139968395233154,0.013584904990476154,1739141193.7190175,33.139968395233154,2.6541345863757444,1739141193.7190194,33.139968395233154,0.9249569560622918 +1739141193.7389047,33.15996837615967,49.230496973905026,1739141193.7389076,33.15996837615967,8.17858070946744,1739141193.7389107,33.15996837615967,59.11170629699477,1739141193.7389135,33.15996837615967,44.83247582039183,1739141193.7389154,33.15996837615967,7.737909663761984,1739141193.738917,33.15996837615967,-3.041728388068775,1739141193.7389183,33.15996837615967,2.449296379031684,1739141193.7389197,33.15996837615967,0.6108,1739141193.7389214,33.15996837615967,0.9385418610527679,1739141193.738923,33.15996837615967,0.0,1739141193.7389245,33.15996837615967,0.013584904990476154,1739141193.738926,33.15996837615967,2.6541345863757444,1739141193.7389274,33.15996837615967,0.9249569560622918 +1739141193.7591066,33.17996835708618,49.13994170743928,1739141193.7591088,33.17996835708618,8.225133828565383,1739141193.759112,33.17996835708618,59.1134810530919,1739141193.7591147,33.17996835708618,44.82752643806928,1739141193.759116,33.17996835708618,7.73381095652612,1739141193.7591178,33.17996835708618,-3.0281496367318472,1739141193.759119,33.17996835708618,2.3537687483667975,1739141193.7591207,33.17996835708618,0.6108,1739141193.759122,33.17996835708618,0.9750985194760781,1739141193.7591236,33.17996835708618,0.0,1739141193.759125,33.17996835708618,0.08041492272278294,1739141193.7591262,33.17996835708618,2.681858929622382,1739141193.7591279,33.17996835708618,0.9265074306184556 +1739141193.7789505,33.199968338012695,49.13994170743928,1739141193.778955,33.199968338012695,8.225133828565383,1739141193.7789621,33.199968338012695,59.1134810530919,1739141193.7789676,33.199968338012695,44.82752643806928,1739141193.7789698,33.199968338012695,7.73381095652612,1739141193.7789745,33.199968338012695,-3.0281496367318472,1739141193.7789783,33.199968338012695,2.3537687483667975,1739141193.7789824,33.199968338012695,0.6108,1739141193.778987,33.199968338012695,0.9750985194760781,1739141193.7789896,33.199968338012695,0.0,1739141193.778992,33.199968338012695,0.04859108885762242,1739141193.778997,33.199968338012695,2.681858929622382,1739141193.7790008,33.199968338012695,0.9265074306184556 +1739141193.7992249,33.21996831893921,49.13994170743928,1739141193.7992291,33.21996831893921,8.225133828565383,1739141193.7992358,33.21996831893921,59.1134810530919,1739141193.79924,33.21996831893921,44.82752643806928,1739141193.7992418,33.21996831893921,7.73381095652612,1739141193.7992437,33.21996831893921,-3.0281496367318472,1739141193.7992454,33.21996831893921,2.3537687483667975,1739141193.799247,33.21996831893921,0.6108,1739141193.7992487,33.21996831893921,0.9750985194760781,1739141193.7992504,33.21996831893921,0.0,1739141193.799252,33.21996831893921,0.04859108885762242,1739141193.7992535,33.21996831893921,2.681858929622382,1739141193.799255,33.21996831893921,0.9265074306184556 +1739141193.8193088,33.23996829986572,49.13994170743928,1739141193.8193128,33.23996829986572,8.225133828565383,1739141193.8193161,33.23996829986572,59.1134810530919,1739141193.8193192,33.23996829986572,44.82752643806928,1739141193.8193212,33.23996829986572,7.73381095652612,1739141193.8193228,33.23996829986572,-3.0281496367318472,1739141193.8193247,33.23996829986572,2.3537687483667975,1739141193.8193266,33.23996829986572,0.6108,1739141193.8193283,33.23996829986572,0.9750985194760781,1739141193.8193297,33.23996829986572,0.0,1739141193.8193314,33.23996829986572,0.04859108885762242,1739141193.8193328,33.23996829986572,2.681858929622382,1739141193.8193345,33.23996829986572,0.9265074306184556 +1739141193.8392997,33.259968280792236,49.13994170743928,1739141193.8393023,33.259968280792236,8.225133828565383,1739141193.8393059,33.259968280792236,59.1134810530919,1739141193.839309,33.259968280792236,44.82752643806928,1739141193.8393106,33.259968280792236,7.73381095652612,1739141193.8393126,33.259968280792236,-3.0281496367318472,1739141193.8393145,33.259968280792236,2.3537687483667975,1739141193.839316,33.259968280792236,0.6108,1739141193.8393173,33.259968280792236,0.9750985194760781,1739141193.839319,33.259968280792236,0.0,1739141193.839321,33.259968280792236,0.04859108885762242,1739141193.8393223,33.259968280792236,2.681858929622382,1739141193.839324,33.259968280792236,0.9265074306184556 +1739141193.8592832,33.27996826171875,49.13994170743928,1739141193.859286,33.27996826171875,8.225133828565383,1739141193.8592896,33.27996826171875,59.1134810530919,1739141193.8592927,33.27996826171875,44.82752643806928,1739141193.8592944,33.27996826171875,7.73381095652612,1739141193.8592963,33.27996826171875,-3.0281496367318472,1739141193.8592978,33.27996826171875,2.3537687483667975,1739141193.8592994,33.27996826171875,0.6108,1739141193.8593009,33.27996826171875,0.9750985194760781,1739141193.8593023,33.27996826171875,0.0,1739141193.8593047,33.27996826171875,0.04859108885762242,1739141193.8593066,33.27996826171875,2.681858929622382,1739141193.859308,33.27996826171875,0.9265074306184556 +1739141193.8793387,33.299968242645264,49.04775258780785,1739141193.8793418,33.299968242645264,8.269338965269586,1739141193.8793454,33.299968242645264,59.372939520923104,1739141193.8793488,33.299968242645264,44.61996536741691,1739141193.8793504,33.299968242645264,7.550052560134662,1739141193.8793528,33.299968242645264,-2.9805511417352575,1739141193.8793547,33.299968242645264,2.507101523445342,1739141193.8793566,33.299968242645264,0.6108,1739141193.8793585,33.299968242645264,0.9170898054935093,1739141193.8793602,33.299968242645264,0.0,1739141193.879362,33.299968242645264,-0.07352929091435442,1739141193.8793638,33.299968242645264,2.7095832728690192,1739141193.8793654,33.299968242645264,0.9324665055619245 +1739141193.8990905,33.31996822357178,49.04775258780785,1739141193.8990934,33.31996822357178,8.269338965269586,1739141193.8990967,33.31996822357178,59.372939520923104,1739141193.8990998,33.31996822357178,44.61996536741691,1739141193.8991015,33.31996822357178,7.550052560134662,1739141193.8991034,33.31996822357178,-2.9805511417352575,1739141193.899105,33.31996822357178,2.507101523445342,1739141193.8991065,33.31996822357178,0.6108,1739141193.8991082,33.31996822357178,0.9170898054935093,1739141193.8991098,33.31996822357178,0.0,1739141193.8991115,33.31996822357178,-0.015376700068415183,1739141193.899113,33.31996822357178,2.7095832728690192,1739141193.8991146,33.31996822357178,0.9324665055619245 +1739141193.919141,33.33996820449829,49.04775258780785,1739141193.919144,33.33996820449829,8.269338965269586,1739141193.9191473,33.33996820449829,59.372939520923104,1739141193.9191504,33.33996820449829,44.61996536741691,1739141193.919152,33.33996820449829,7.550052560134662,1739141193.919154,33.33996820449829,-2.9805511417352575,1739141193.9191554,33.33996820449829,2.507101523445342,1739141193.919157,33.33996820449829,0.6108,1739141193.9191585,33.33996820449829,0.9170898054935093,1739141193.9191604,33.33996820449829,0.0,1739141193.9191618,33.33996820449829,-0.015376700068415183,1739141193.9191635,33.33996820449829,2.7095832728690192,1739141193.919165,33.33996820449829,0.9324665055619245 +1739141193.9392252,33.359968185424805,49.04775258780785,1739141193.939228,33.359968185424805,8.269338965269586,1739141193.9392314,33.359968185424805,59.372939520923104,1739141193.9392374,33.359968185424805,44.61996536741691,1739141193.9392412,33.359968185424805,7.550052560134662,1739141193.9392455,33.359968185424805,-2.9805511417352575,1739141193.93925,33.359968185424805,2.507101523445342,1739141193.939253,33.359968185424805,0.6108,1739141193.9392552,33.359968185424805,0.9170898054935093,1739141193.9392586,33.359968185424805,0.0,1739141193.939262,33.359968185424805,-0.015376700068415183,1739141193.939266,33.359968185424805,2.7095832728690192,1739141193.939269,33.359968185424805,0.9324665055619245 +1739141193.9592426,33.37996816635132,49.04775258780785,1739141193.9592478,33.37996816635132,8.269338965269586,1739141193.9592543,33.37996816635132,59.372939520923104,1739141193.959259,33.37996816635132,44.61996536741691,1739141193.959263,33.37996816635132,7.550052560134662,1739141193.959266,33.37996816635132,-2.9805511417352575,1739141193.9592702,33.37996816635132,2.507101523445342,1739141193.9592738,33.37996816635132,0.6108,1739141193.9592776,33.37996816635132,0.9170898054935093,1739141193.9592822,33.37996816635132,0.0,1739141193.959284,33.37996816635132,-0.015376700068415183,1739141193.9592855,33.37996816635132,2.7095832728690192,1739141193.959287,33.37996816635132,0.9324665055619245 +1739141193.9866054,33.39996814727783,48.954183593485766,1739141193.986614,33.39996814727783,8.31105853451733,1739141193.9866242,33.39996814727783,59.46058658652993,1739141193.9866343,33.39996814727783,44.5604594362418,1739141193.9866393,33.39996814727783,7.495077198849649,1739141193.9866455,33.39996814727783,-2.9579694491041133,1739141193.9866502,33.39996814727783,2.478522161985622,1739141193.9866548,33.39996814727783,0.6108,1739141193.9866593,33.39996814727783,0.9276338957546695,1739141193.9866652,33.39996814727783,0.0,1739141193.9866705,33.39996814727783,0.008973340468144114,1739141193.986675,33.39996814727783,2.7373076161156566,1739141193.9866793,33.39996814727783,0.9302558184772275 +1739141194.0044415,33.419968128204346,48.954183593485766,1739141194.0044508,33.419968128204346,8.31105853451733,1739141194.0044613,33.419968128204346,59.46058658652993,1739141194.0044713,33.419968128204346,44.5604594362418,1739141194.004476,33.419968128204346,7.495077198849649,1739141194.004482,33.419968128204346,-2.9579694491041133,1739141194.0044866,33.419968128204346,2.478522161985622,1739141194.0044916,33.419968128204346,0.6108,1739141194.004496,33.419968128204346,0.9276338957546695,1739141194.0045018,33.419968128204346,0.0,1739141194.0045068,33.419968128204346,-0.002621922722558012,1739141194.0045116,33.419968128204346,2.7373076161156566,1739141194.0045161,33.419968128204346,0.9302558184772275 +1739141194.0333488,33.43996810913086,48.954183593485766,1739141194.0333586,33.43996810913086,8.31105853451733,1739141194.0333707,33.43996810913086,59.46058658652993,1739141194.033384,33.43996810913086,44.5604594362418,1739141194.033392,33.43996810913086,7.495077198849649,1739141194.0334015,33.43996810913086,-2.9579694491041133,1739141194.0334103,33.43996810913086,2.478522161985622,1739141194.0334187,33.43996810913086,0.6108,1739141194.0334275,33.43996810913086,0.9276338957546695,1739141194.0334363,33.43996810913086,0.0,1739141194.0334454,33.43996810913086,-0.002621922722558012,1739141194.033454,33.43996810913086,2.7373076161156566,1739141194.0334625,33.43996810913086,0.9302558184772275 +1739141194.0402246,33.45996809005737,48.954183593485766,1739141194.0402281,33.45996809005737,8.31105853451733,1739141194.0402324,33.45996809005737,59.46058658652993,1739141194.0402367,33.45996809005737,44.5604594362418,1739141194.0402389,33.45996809005737,7.495077198849649,1739141194.0402415,33.45996809005737,-2.9579694491041133,1739141194.0402434,33.45996809005737,2.478522161985622,1739141194.0402455,33.45996809005737,0.6108,1739141194.0402472,33.45996809005737,0.9276338957546695,1739141194.0402498,33.45996809005737,0.0,1739141194.0402522,33.45996809005737,-0.002621922722558012,1739141194.040254,33.45996809005737,2.7373076161156566,1739141194.0402563,33.45996809005737,0.9302558184772275 +1739141194.060369,33.47996807098389,48.954183593485766,1739141194.060373,33.47996807098389,8.31105853451733,1739141194.0603778,33.47996807098389,59.46058658652993,1739141194.0603824,33.47996807098389,44.5604594362418,1739141194.0603848,33.47996807098389,7.495077198849649,1739141194.0603874,33.47996807098389,-2.9579694491041133,1739141194.0603893,33.47996807098389,2.478522161985622,1739141194.0603917,33.47996807098389,0.6108,1739141194.0603938,33.47996807098389,0.9276338957546695,1739141194.0603962,33.47996807098389,0.0,1739141194.0603986,33.47996807098389,-0.002621922722558012,1739141194.0604007,33.47996807098389,2.7373076161156566,1739141194.0604026,33.47996807098389,0.9302558184772275 +1739141194.080601,33.4999680519104,48.954183593485766,1739141194.080605,33.4999680519104,8.31105853451733,1739141194.0806093,33.4999680519104,59.46058658652993,1739141194.0806136,33.4999680519104,44.5604594362418,1739141194.080616,33.4999680519104,7.495077198849649,1739141194.0806184,33.4999680519104,-2.9579694491041133,1739141194.0806205,33.4999680519104,2.478522161985622,1739141194.0806227,33.4999680519104,0.6108,1739141194.0806243,33.4999680519104,0.9276338957546695,1739141194.080627,33.4999680519104,0.0,1739141194.0806293,33.4999680519104,-0.002621922722558012,1739141194.0806313,33.4999680519104,2.7373076161156566,1739141194.0806334,33.4999680519104,0.9302558184772275 +1739141194.1015947,33.519968032836914,48.859623303503554,1739141194.1015983,33.519968032836914,8.35011424463165,1739141194.1016028,33.519968032836914,59.54756777575121,1739141194.101607,33.519968032836914,44.499398389088306,1739141194.1016092,33.519968032836914,7.4343983890883045,1739141194.101612,33.519968032836914,-2.9345853856444113,1739141194.101614,33.519968032836914,2.454916829265326,1739141194.1016161,33.519968032836914,0.6108,1739141194.1016185,33.519968032836914,0.9364342199899373,1739141194.101621,33.519968032836914,0.0,1739141194.101623,33.519968032836914,0.014746380475284905,1739141194.1016252,33.519968032836914,2.765031959362294,1739141194.101627,33.519968032836914,0.9299584642165921 +1739141194.1202166,33.53996801376343,48.859623303503554,1739141194.1202204,33.53996801376343,8.35011424463165,1739141194.1202247,33.53996801376343,59.54756777575121,1739141194.1202295,33.53996801376343,44.499398389088306,1739141194.1202314,33.53996801376343,7.4343983890883045,1739141194.1202343,33.53996801376343,-2.9345853856444113,1739141194.1202364,33.53996801376343,2.454916829265326,1739141194.120238,33.53996801376343,0.6108,1739141194.12024,33.53996801376343,0.9364342199899373,1739141194.1202424,33.53996801376343,0.0,1739141194.1202447,33.53996801376343,0.006475755773345138,1739141194.120247,33.53996801376343,2.765031959362294,1739141194.1202486,33.53996801376343,0.9299584642165921 +1739141194.1430385,33.55996799468994,48.859623303503554,1739141194.1430447,33.55996799468994,8.35011424463165,1739141194.143052,33.55996799468994,59.54756777575121,1739141194.1430604,33.55996799468994,44.499398389088306,1739141194.1430655,33.55996799468994,7.4343983890883045,1739141194.1430714,33.55996799468994,-2.9345853856444113,1739141194.143077,33.55996799468994,2.454916829265326,1739141194.1430821,33.55996799468994,0.6108,1739141194.1430874,33.55996799468994,0.9364342199899373,1739141194.143093,33.55996799468994,0.0,1739141194.1430986,33.55996799468994,0.006475755773345138,1739141194.143104,33.55996799468994,2.765031959362294,1739141194.1431093,33.55996799468994,0.9299584642165921 +1739141194.1615682,33.579967975616455,48.859623303503554,1739141194.161573,33.579967975616455,8.35011424463165,1739141194.1615782,33.579967975616455,59.54756777575121,1739141194.1615846,33.579967975616455,44.499398389088306,1739141194.1615882,33.579967975616455,7.4343983890883045,1739141194.1615925,33.579967975616455,-2.9345853856444113,1739141194.1615963,33.579967975616455,2.454916829265326,1739141194.1616004,33.579967975616455,0.6108,1739141194.1616044,33.579967975616455,0.9364342199899373,1739141194.1616085,33.579967975616455,0.0,1739141194.1616125,33.579967975616455,0.006475755773345138,1739141194.1616163,33.579967975616455,2.765031959362294,1739141194.1616201,33.579967975616455,0.9299584642165921 +1739141194.1808617,33.59996795654297,48.859623303503554,1739141194.1808653,33.59996795654297,8.35011424463165,1739141194.1808698,33.59996795654297,59.54756777575121,1739141194.180875,33.59996795654297,44.499398389088306,1739141194.180878,33.59996795654297,7.4343983890883045,1739141194.1808815,33.59996795654297,-2.9345853856444113,1739141194.1808848,33.59996795654297,2.454916829265326,1739141194.1808882,33.59996795654297,0.6108,1739141194.180904,33.59996795654297,0.9364342199899373,1739141194.1809075,33.59996795654297,0.0,1739141194.1809108,33.59996795654297,0.006475755773345138,1739141194.180914,33.59996795654297,2.765031959362294,1739141194.1809173,33.59996795654297,0.9299584642165921 +1739141194.2018123,33.61996793746948,48.76399383928208,1739141194.201816,33.61996793746948,8.38654207465485,1739141194.2018204,33.61996793746948,59.633531547936144,1739141194.2018251,33.61996793746948,44.43807335619647,1739141194.2018278,33.61996793746948,7.370855209318493,1739141194.201831,33.61996793746948,-2.9109788369040865,1739141194.2018344,33.61996793746948,2.433132133379962,1739141194.2018375,33.61996793746948,0.6108,1739141194.2018406,33.61996793746948,0.9446298498715738,1739141194.2018437,33.61996793746948,0.0,1739141194.2018468,33.61996793746948,0.020624868737789258,1739141194.20185,33.61996793746948,2.7927563026089315,1739141194.201853,33.61996793746948,0.9307426573397597 +1739141194.2194164,33.639967918395996,48.76399383928208,1739141194.2194197,33.639967918395996,8.38654207465485,1739141194.2194238,33.639967918395996,59.633531547936144,1739141194.2194283,33.639967918395996,44.43807335619647,1739141194.219431,33.639967918395996,7.370855209318493,1739141194.2194343,33.639967918395996,-2.9109788369040865,1739141194.2194374,33.639967918395996,2.433132133379962,1739141194.2194407,33.639967918395996,0.6108,1739141194.2194438,33.639967918395996,0.9446298498715738,1739141194.219447,33.639967918395996,0.0,1739141194.2194498,33.639967918395996,0.013887192531814141,1739141194.219453,33.639967918395996,2.7927563026089315,1739141194.2194562,33.639967918395996,0.9307426573397597 +1739141194.2407584,33.65996789932251,48.76399383928208,1739141194.240762,33.65996789932251,8.38654207465485,1739141194.2407665,33.65996789932251,59.633531547936144,1739141194.2407715,33.65996789932251,44.43807335619647,1739141194.2407744,33.65996789932251,7.370855209318493,1739141194.240778,33.65996789932251,-2.9109788369040865,1739141194.2407813,33.65996789932251,2.433132133379962,1739141194.2407846,33.65996789932251,0.6108,1739141194.240788,33.65996789932251,0.9446298498715738,1739141194.2407913,33.65996789932251,0.0,1739141194.2407947,33.65996789932251,0.013887192531814141,1739141194.240798,33.65996789932251,2.7927563026089315,1739141194.2408013,33.65996789932251,0.9307426573397597 +1739141194.2616594,33.67996788024902,48.76399383928208,1739141194.261663,33.67996788024902,8.38654207465485,1739141194.261667,33.67996788024902,59.633531547936144,1739141194.2616718,33.67996788024902,44.43807335619647,1739141194.2616746,33.67996788024902,7.370855209318493,1739141194.261678,33.67996788024902,-2.9109788369040865,1739141194.261681,33.67996788024902,2.433132133379962,1739141194.2616842,33.67996788024902,0.6108,1739141194.261687,33.67996788024902,0.9446298498715738,1739141194.2616904,33.67996788024902,0.0,1739141194.2616935,33.67996788024902,0.013887192531814141,1739141194.2616966,33.67996788024902,2.7927563026089315,1739141194.2616994,33.67996788024902,0.9307426573397597 +1739141194.2870862,33.69996786117554,48.76399383928208,1739141194.2870944,33.69996786117554,8.38654207465485,1739141194.287104,33.69996786117554,59.633531547936144,1739141194.2871153,33.69996786117554,44.43807335619647,1739141194.2871213,33.69996786117554,7.370855209318493,1739141194.2871294,33.69996786117554,-2.9109788369040865,1739141194.2871366,33.69996786117554,2.433132133379962,1739141194.2871435,33.69996786117554,0.6108,1739141194.2871504,33.69996786117554,0.9446298498715738,1739141194.2871578,33.69996786117554,0.0,1739141194.287165,33.69996786117554,0.013887192531814141,1739141194.287172,33.69996786117554,2.7927563026089315,1739141194.287179,33.69996786117554,0.9307426573397597 +1739141194.2999609,33.71996784210205,48.76399383928208,1739141194.2999642,33.71996784210205,8.38654207465485,1739141194.299968,33.71996784210205,59.633531547936144,1739141194.2999716,33.71996784210205,44.43807335619647,1739141194.2999735,33.71996784210205,7.370855209318493,1739141194.2999756,33.71996784210205,-2.9109788369040865,1739141194.2999778,33.71996784210205,2.433132133379962,1739141194.2999794,33.71996784210205,0.6108,1739141194.299981,33.71996784210205,0.9446298498715738,1739141194.2999833,33.71996784210205,0.0,1739141194.2999854,33.71996784210205,0.013887192531814141,1739141194.2999868,33.71996784210205,2.7927563026089315,1739141194.2999887,33.71996784210205,0.9307426573397597 +1739141194.3199675,33.739967823028564,48.66726407035984,1739141194.3199713,33.739967823028564,8.420349246731858,1739141194.3199754,33.739967823028564,59.795815283634276,1739141194.319979,33.739967823028564,44.32507797758902,1739141194.319981,33.739967823028564,7.247557739658318,1739141194.319983,33.739967823028564,-2.8777946899533813,1739141194.3199854,33.739967823028564,2.4833334301008696,1739141194.319987,33.739967823028564,0.6108,1739141194.3199887,33.739967823028564,0.9258503743509683,1739141194.319991,33.739967823028564,0.0,1739141194.319993,33.739967823028564,-0.025126459959833175,1739141194.319995,33.739967823028564,2.820480645855569,1739141194.3199964,33.739967823028564,0.932398895272382 +1739141194.343707,33.75996780395508,48.66726407035984,1739141194.343716,33.75996780395508,8.420349246731858,1739141194.3437264,33.75996780395508,59.795815283634276,1739141194.3437362,33.75996780395508,44.32507797758902,1739141194.3437414,33.75996780395508,7.247557739658318,1739141194.3437476,33.75996780395508,-2.8777946899533813,1739141194.3437521,33.75996780395508,2.4833334301008696,1739141194.3437564,33.75996780395508,0.6108,1739141194.343761,33.75996780395508,0.9258503743509683,1739141194.3437665,33.75996780395508,0.0,1739141194.3437717,33.75996780395508,-0.00654852092141367,1739141194.3437762,33.75996780395508,2.820480645855569,1739141194.3437805,33.75996780395508,0.932398895272382 +1739141194.3628137,33.77996778488159,48.66726407035984,1739141194.3628201,33.77996778488159,8.420349246731858,1739141194.3628278,33.77996778488159,59.795815283634276,1739141194.3628345,33.77996778488159,44.32507797758902,1739141194.3628378,33.77996778488159,7.247557739658318,1739141194.3628418,33.77996778488159,-2.8777946899533813,1739141194.3628452,33.77996778488159,2.4833334301008696,1739141194.3628483,33.77996778488159,0.6108,1739141194.3628516,33.77996778488159,0.9258503743509683,1739141194.3628554,33.77996778488159,0.0,1739141194.362859,33.77996778488159,-0.00654852092141367,1739141194.3628623,33.77996778488159,2.820480645855569,1739141194.3628657,33.77996778488159,0.932398895272382 +1739141194.381731,33.799967765808105,48.66726407035984,1739141194.381737,33.799967765808105,8.420349246731858,1739141194.3817425,33.799967765808105,59.795815283634276,1739141194.3817477,33.799967765808105,44.32507797758902,1739141194.3817506,33.799967765808105,7.247557739658318,1739141194.3817544,33.799967765808105,-2.8777946899533813,1739141194.3817573,33.799967765808105,2.4833334301008696,1739141194.3817596,33.799967765808105,0.6108,1739141194.381762,33.799967765808105,0.9258503743509683,1739141194.3817651,33.799967765808105,0.0,1739141194.3817682,33.799967765808105,-0.00654852092141367,1739141194.3817708,33.799967765808105,2.820480645855569,1739141194.3817732,33.799967765808105,0.932398895272382 +1739141194.4012642,33.81996774673462,48.66726407035984,1739141194.4012687,33.81996774673462,8.420349246731858,1739141194.4012742,33.81996774673462,59.795815283634276,1739141194.4012794,33.81996774673462,44.32507797758902,1739141194.401282,33.81996774673462,7.247557739658318,1739141194.4012854,33.81996774673462,-2.8777946899533813,1739141194.4012878,33.81996774673462,2.4833334301008696,1739141194.4012902,33.81996774673462,0.6108,1739141194.4012926,33.81996774673462,0.9258503743509683,1739141194.4012957,33.81996774673462,0.0,1739141194.4012983,33.81996774673462,-0.00654852092141367,1739141194.4013007,33.81996774673462,2.820480645855569,1739141194.4013033,33.81996774673462,0.932398895272382 +1739141194.4223068,33.83996772766113,48.56959067237764,1739141194.4223118,33.83996772766113,8.451476602223257,1739141194.4223168,33.83996772766113,59.880690223133556,1739141194.422322,33.83996772766113,44.27188576245214,1739141194.4223247,33.83996772766113,7.1848671114239195,1739141194.4223275,33.83996772766113,-2.8549890697404146,1739141194.4223301,33.83996772766113,2.4553692981712003,1739141194.4223328,33.83996772766113,0.6108,1739141194.422335,33.83996772766113,0.9362647523793878,1739141194.4223382,33.83996772766113,0.0,1739141194.422341,33.83996772766113,0.01502386270442687,1739141194.4223435,33.83996772766113,2.8482049891022063,1739141194.4223459,33.83996772766113,0.9315134584379104 +1739141194.439491,33.85996770858765,48.56959067237764,1739141194.4394944,33.85996770858765,8.451476602223257,1739141194.4394977,33.85996770858765,59.880690223133556,1739141194.4395006,33.85996770858765,44.27188576245214,1739141194.439502,33.85996770858765,7.1848671114239195,1739141194.4395037,33.85996770858765,-2.8549890697404146,1739141194.439505,33.85996770858765,2.4553692981712003,1739141194.4395065,33.85996770858765,0.6108,1739141194.4395077,33.85996770858765,0.9362647523793878,1739141194.4395094,33.85996770858765,0.0,1739141194.4395108,33.85996770858765,0.00475129394147733,1739141194.4395123,33.85996770858765,2.8482049891022063,1739141194.4395137,33.85996770858765,0.9315134584379104 +1739141194.459498,33.87996768951416,48.56959067237764,1739141194.4595008,33.87996768951416,8.451476602223257,1739141194.4595037,33.87996768951416,59.880690223133556,1739141194.4595063,33.87996768951416,44.27188576245214,1739141194.4595075,33.87996768951416,7.1848671114239195,1739141194.4595091,33.87996768951416,-2.8549890697404146,1739141194.4595106,33.87996768951416,2.4553692981712003,1739141194.4595118,33.87996768951416,0.6108,1739141194.459513,33.87996768951416,0.9362647523793878,1739141194.4595141,33.87996768951416,0.0,1739141194.4595156,33.87996768951416,0.00475129394147733,1739141194.459517,33.87996768951416,2.8482049891022063,1739141194.4595184,33.87996768951416,0.9315134584379104 +1739141194.479612,33.899967670440674,48.56959067237764,1739141194.479615,33.899967670440674,8.451476602223257,1739141194.4796178,33.899967670440674,59.880690223133556,1739141194.4796207,33.899967670440674,44.27188576245214,1739141194.4796221,33.899967670440674,7.1848671114239195,1739141194.4796238,33.899967670440674,-2.8549890697404146,1739141194.479625,33.899967670440674,2.4553692981712003,1739141194.4796262,33.899967670440674,0.6108,1739141194.4796274,33.899967670440674,0.9362647523793878,1739141194.4796288,33.899967670440674,0.0,1739141194.4796302,33.899967670440674,0.00475129394147733,1739141194.4796317,33.899967670440674,2.8482049891022063,1739141194.4796326,33.899967670440674,0.9315134584379104 +1739141194.4988403,33.91996765136719,48.56959067237764,1739141194.4988427,33.91996765136719,8.451476602223257,1739141194.498845,33.91996765136719,59.880690223133556,1739141194.4988477,33.91996765136719,44.27188576245214,1739141194.498849,33.91996765136719,7.1848671114239195,1739141194.4988506,33.91996765136719,-2.8549890697404146,1739141194.4988518,33.91996765136719,2.4553692981712003,1739141194.4988532,33.91996765136719,0.6108,1739141194.4988542,33.91996765136719,0.9362647523793878,1739141194.4988556,33.91996765136719,0.0,1739141194.498857,33.91996765136719,0.00475129394147733,1739141194.4988582,33.91996765136719,2.8482049891022063,1739141194.4988594,33.91996765136719,0.9315134584379104 +1739141194.5188286,33.9399676322937,48.56959067237764,1739141194.5188308,33.9399676322937,8.451476602223257,1739141194.5188339,33.9399676322937,59.880690223133556,1739141194.5188365,33.9399676322937,44.27188576245214,1739141194.518838,33.9399676322937,7.1848671114239195,1739141194.5188398,33.9399676322937,-2.8549890697404146,1739141194.518841,33.9399676322937,2.4553692981712003,1739141194.5188427,33.9399676322937,0.6108,1739141194.5188437,33.9399676322937,0.9362647523793878,1739141194.5188456,33.9399676322937,0.0,1739141194.5188468,33.9399676322937,0.00475129394147733,1739141194.518848,33.9399676322937,2.8482049891022063,1739141194.5188494,33.9399676322937,0.9315134584379104 +1739141194.5441868,33.959967613220215,48.47109630919893,1739141194.5441964,33.959967613220215,8.479882712268063,1739141194.5442073,33.959967613220215,59.982938314632825,1739141194.5442173,33.959967613220215,44.20451629047949,1739141194.5442219,33.959967613220215,7.105096272985458,1739141194.544228,33.959967613220215,-2.8298753040878766,1739141194.5442328,33.959967613220215,2.4467448745153932,1739141194.5442376,33.959967613220215,0.6108,1739141194.5442421,33.959967613220215,0.9395002275437471,1739141194.5442476,33.959967613220215,0.0,1739141194.5442529,33.959967613220215,0.009544082319424172,1739141194.5442576,33.959967613220215,2.8759293323488437,1739141194.544262,33.959967613220215,0.9322384265443968 +1739141194.5637212,33.97996759414673,48.47109630919893,1739141194.5637312,33.97996759414673,8.479882712268063,1739141194.5637422,33.97996759414673,59.982938314632825,1739141194.5637517,33.97996759414673,44.20451629047949,1739141194.5637565,33.97996759414673,7.105096272985458,1739141194.5637624,33.97996759414673,-2.8298753040878766,1739141194.5637672,33.97996759414673,2.4467448745153932,1739141194.563772,33.97996759414673,0.6108,1739141194.5637765,33.97996759414673,0.9395002275437471,1739141194.5637822,33.97996759414673,0.0,1739141194.563787,33.97996759414673,0.007261800999350254,1739141194.5637915,33.97996759414673,2.8759293323488437,1739141194.5637963,33.97996759414673,0.9322384265443968 +1739141194.5844018,33.99996757507324,48.47109630919893,1739141194.5844111,33.99996757507324,8.479882712268063,1739141194.5844212,33.99996757507324,59.982938314632825,1739141194.5844312,33.99996757507324,44.20451629047949,1739141194.584436,33.99996757507324,7.105096272985458,1739141194.584442,33.99996757507324,-2.8298753040878766,1739141194.5844467,33.99996757507324,2.4467448745153932,1739141194.5844517,33.99996757507324,0.6108,1739141194.5844562,33.99996757507324,0.9395002275437471,1739141194.584462,33.99996757507324,0.0,1739141194.584467,33.99996757507324,0.007261800999350254,1739141194.5844715,33.99996757507324,2.8759293323488437,1739141194.5844762,33.99996757507324,0.9322384265443968 +1739141194.6106327,34.019967555999756,48.47109630919893,1739141194.6106393,34.019967555999756,8.479882712268063,1739141194.6106465,34.019967555999756,59.982938314632825,1739141194.6106539,34.019967555999756,44.20451629047949,1739141194.6106572,34.019967555999756,7.105096272985458,1739141194.6106613,34.019967555999756,-2.8298753040878766,1739141194.6106646,34.019967555999756,2.4467448745153932,1739141194.610668,34.019967555999756,0.6108,1739141194.610671,34.019967555999756,0.9395002275437471,1739141194.6106749,34.019967555999756,0.0,1739141194.6106784,34.019967555999756,0.007261800999350254,1739141194.6106818,34.019967555999756,2.8759293323488437,1739141194.6106849,34.019967555999756,0.9322384265443968 +1739141194.6289687,34.03996753692627,48.47109630919893,1739141194.6289747,34.03996753692627,8.479882712268063,1739141194.6289818,34.03996753692627,59.982938314632825,1739141194.628989,34.03996753692627,44.20451629047949,1739141194.6289923,34.03996753692627,7.105096272985458,1739141194.6289966,34.03996753692627,-2.8298753040878766,1739141194.629,34.03996753692627,2.4467448745153932,1739141194.6290033,34.03996753692627,0.6108,1739141194.6290064,34.03996753692627,0.9395002275437471,1739141194.6290102,34.03996753692627,0.0,1739141194.6290138,34.03996753692627,0.007261800999350254,1739141194.629017,34.03996753692627,2.8759293323488437,1739141194.6290202,34.03996753692627,0.9322384265443968 +1739141194.6487572,34.05996751785278,48.371779367268154,1739141194.6487625,34.05996751785278,8.505566396097427,1739141194.6487675,34.05996751785278,59.99813888320488,1739141194.6487722,34.05996751785278,44.193432622261525,1739141194.6487749,34.05996751785278,7.091362162367546,1739141194.6487782,34.05996751785278,-2.8152350036878957,1739141194.6487808,34.05996751785278,2.3591972466855036,1739141194.6487834,34.05996751785278,0.6108,1739141194.6487856,34.05996751785278,0.9729834883262932,1739141194.6487887,34.05996751785278,0.0,1739141194.6487916,34.05996751785278,0.06962657244841121,1739141194.6487942,34.05996751785278,2.903653675595481,1739141194.6487966,34.05996751785278,0.9330544409269318 +1739141194.6679204,34.0799674987793,48.371779367268154,1739141194.6679254,34.0799674987793,8.505566396097427,1739141194.667931,34.0799674987793,59.99813888320488,1739141194.6679368,34.0799674987793,44.193432622261525,1739141194.6679397,34.0799674987793,7.091362162367546,1739141194.6679428,34.0799674987793,-2.8152350036878957,1739141194.6679454,34.0799674987793,2.3591972466855036,1739141194.667948,34.0799674987793,0.6108,1739141194.6679506,34.0799674987793,0.9729834883262932,1739141194.6679537,34.0799674987793,0.0,1739141194.667956,34.0799674987793,0.03992904739936143,1739141194.6679585,34.0799674987793,2.903653675595481,1739141194.6679611,34.0799674987793,0.9330544409269318 +1739141194.688374,34.10996747016907,48.371779367268154,1739141194.6883771,34.10996747016907,8.505566396097427,1739141194.6883805,34.10996747016907,59.99813888320488,1739141194.6883843,34.10996747016907,44.193432622261525,1739141194.688386,34.10996747016907,7.091362162367546,1739141194.688388,34.10996747016907,-2.8152350036878957,1739141194.6883898,34.10996747016907,2.3591972466855036,1739141194.6883917,34.10996747016907,0.6108,1739141194.688393,34.10996747016907,0.9729834883262932,1739141194.6883953,34.10996747016907,0.0,1739141194.6883972,34.10996747016907,0.03992904739936143,1739141194.6883986,34.10996747016907,2.903653675595481,1739141194.6884003,34.10996747016907,0.9330544409269318 +1739141194.7070754,34.119967460632324,48.371779367268154,1739141194.7070785,34.119967460632324,8.505566396097427,1739141194.7070813,34.119967460632324,59.99813888320488,1739141194.7070837,34.119967460632324,44.193432622261525,1739141194.7070851,34.119967460632324,7.091362162367546,1739141194.7070866,34.119967460632324,-2.8152350036878957,1739141194.7070878,34.119967460632324,2.3591972466855036,1739141194.7070892,34.119967460632324,0.6108,1739141194.7070901,34.119967460632324,0.9729834883262932,1739141194.7070918,34.119967460632324,0.0,1739141194.7070932,34.119967460632324,0.03992904739936143,1739141194.7070944,34.119967460632324,2.903653675595481,1739141194.7070959,34.119967460632324,0.9330544409269318 +1739141194.726589,34.13996744155884,48.371779367268154,1739141194.7265916,34.13996744155884,8.505566396097427,1739141194.726594,34.13996744155884,59.99813888320488,1739141194.7265966,34.13996744155884,44.193432622261525,1739141194.7265983,34.13996744155884,7.091362162367546,1739141194.7265997,34.13996744155884,-2.8152350036878957,1739141194.7266006,34.13996744155884,2.3591972466855036,1739141194.726602,34.13996744155884,0.6108,1739141194.7266033,34.13996744155884,0.9729834883262932,1739141194.7266045,34.13996744155884,0.0,1739141194.726606,34.13996744155884,0.03992904739936143,1739141194.726607,34.13996744155884,2.903653675595481,1739141194.7266083,34.13996744155884,0.9330544409269318 +1739141194.7467427,34.15996742248535,48.371779367268154,1739141194.7467453,34.15996742248535,8.505566396097427,1739141194.746748,34.15996742248535,59.99813888320488,1739141194.7467508,34.15996742248535,44.193432622261525,1739141194.7467523,34.15996742248535,7.091362162367546,1739141194.746754,34.15996742248535,-2.8152350036878957,1739141194.7467556,34.15996742248535,2.3591972466855036,1739141194.746757,34.15996742248535,0.6108,1739141194.7467582,34.15996742248535,0.9729834883262932,1739141194.7467597,34.15996742248535,0.0,1739141194.7467613,34.15996742248535,0.03992904739936143,1739141194.7467628,34.15996742248535,2.903653675595481,1739141194.746764,34.15996742248535,0.9330544409269318 +1739141194.7668424,34.179967403411865,48.27153326439415,1739141194.766845,34.179967403411865,8.528544656667783,1739141194.7668474,34.179967403411865,60.20840955159643,1739141194.76685,34.179967403411865,44.05957045577662,1739141194.7668517,34.179967403411865,6.912658497400493,1739141194.766853,34.179967403411865,-2.775266977717373,1739141194.7668548,34.179967403411865,2.459223780657679,1739141194.766856,34.179967403411865,0.6108,1739141194.766857,34.179967403411865,0.9348223381808729,1739141194.7668586,34.179967403411865,0.0,1739141194.7668598,34.179967403411865,-0.04122347364983749,1739141194.766861,34.179967403411865,2.9313780188421186,1739141194.7668622,34.179967403411865,0.9374017348838299 +1739141194.7872524,34.19996738433838,48.27153326439415,1739141194.7872553,34.19996738433838,8.528544656667783,1739141194.7872586,34.19996738433838,60.20840955159643,1739141194.7872615,34.19996738433838,44.05957045577662,1739141194.7872627,34.19996738433838,6.912658497400493,1739141194.7872646,34.19996738433838,-2.775266977717373,1739141194.787266,34.19996738433838,2.459223780657679,1739141194.7872674,34.19996738433838,0.6108,1739141194.7872686,34.19996738433838,0.9348223381808729,1739141194.7872703,34.19996738433838,0.0,1739141194.787272,34.19996738433838,-0.0025793967029570375,1739141194.7872732,34.19996738433838,2.9313780188421186,1739141194.7872746,34.19996738433838,0.9374017348838299 +1739141194.8066695,34.21996736526489,48.27153326439415,1739141194.8066723,34.21996736526489,8.528544656667783,1739141194.8066752,34.21996736526489,60.20840955159643,1739141194.8066783,34.21996736526489,44.05957045577662,1739141194.8066797,34.21996736526489,6.912658497400493,1739141194.8066816,34.21996736526489,-2.775266977717373,1739141194.806683,34.21996736526489,2.459223780657679,1739141194.806685,34.21996736526489,0.6108,1739141194.8066862,34.21996736526489,0.9348223381808729,1739141194.8066878,34.21996736526489,0.0,1739141194.8066895,34.21996736526489,-0.0025793967029570375,1739141194.8066912,34.21996736526489,2.9313780188421186,1739141194.8066926,34.21996736526489,0.9374017348838299 +1739141194.827317,34.239967346191406,48.27153326439415,1739141194.8273194,34.239967346191406,8.528544656667783,1739141194.8273225,34.239967346191406,60.20840955159643,1739141194.827325,34.239967346191406,44.05957045577662,1739141194.8273265,34.239967346191406,6.912658497400493,1739141194.827328,34.239967346191406,-2.775266977717373,1739141194.8273294,34.239967346191406,2.459223780657679,1739141194.8273306,34.239967346191406,0.6108,1739141194.8273315,34.239967346191406,0.9348223381808729,1739141194.8273332,34.239967346191406,0.0,1739141194.8273346,34.239967346191406,-0.0025793967029570375,1739141194.8273358,34.239967346191406,2.9313780188421186,1739141194.8273373,34.239967346191406,0.9374017348838299 +1739141194.8470635,34.25996732711792,48.27153326439415,1739141194.8470662,34.25996732711792,8.528544656667783,1739141194.8470714,34.25996732711792,60.20840955159643,1739141194.8470776,34.25996732711792,44.05957045577662,1739141194.8470805,34.25996732711792,6.912658497400493,1739141194.847083,34.25996732711792,-2.775266977717373,1739141194.8470848,34.25996732711792,2.459223780657679,1739141194.8470867,34.25996732711792,0.6108,1739141194.8470883,34.25996732711792,0.9348223381808729,1739141194.8470902,34.25996732711792,0.0,1739141194.8470922,34.25996732711792,-0.0025793967029570375,1739141194.847094,34.25996732711792,2.9313780188421186,1739141194.847097,34.25996732711792,0.9374017348838299 +1739141194.8675296,34.279967308044434,48.17049249537037,1739141194.8675337,34.279967308044434,8.548775990114223,1739141194.8675377,34.279967308044434,60.29040271402158,1739141194.8675418,34.279967308044434,44.01378858667748,1739141194.8675437,34.279967308044434,6.848345871761213,1739141194.8675466,34.279967308044434,-2.7532821093131337,1739141194.8675487,34.279967308044434,2.426548921162352,1739141194.8675506,34.279967308044434,0.6108,1739141194.8675528,34.279967308044434,0.9471206073768573,1739141194.8675551,34.279967308044434,0.0,1739141194.867557,34.279967308044434,0.022839753857076504,1739141194.8675592,34.279967308044434,2.959102362088756,1739141194.8675616,34.279967308044434,0.936385216975979 +1739141194.8875031,34.29996728897095,48.17049249537037,1739141194.887507,34.29996728897095,8.548775990114223,1739141194.887511,34.29996728897095,60.29040271402158,1739141194.887515,34.29996728897095,44.01378858667748,1739141194.8875172,34.29996728897095,6.848345871761213,1739141194.8875198,34.29996728897095,-2.7532821093131337,1739141194.8875217,34.29996728897095,2.426548921162352,1739141194.8875237,34.29996728897095,0.6108,1739141194.8875253,34.29996728897095,0.9471206073768573,1739141194.887528,34.29996728897095,0.0,1739141194.88753,34.29996728897095,0.010735390400878342,1739141194.8875318,34.29996728897095,2.959102362088756,1739141194.887534,34.29996728897095,0.936385216975979 +1739141194.9075456,34.31996726989746,48.17049249537037,1739141194.9075491,34.31996726989746,8.548775990114223,1739141194.9075532,34.31996726989746,60.29040271402158,1739141194.907557,34.31996726989746,44.01378858667748,1739141194.9075592,34.31996726989746,6.848345871761213,1739141194.9075618,34.31996726989746,-2.7532821093131337,1739141194.9075637,34.31996726989746,2.426548921162352,1739141194.9075656,34.31996726989746,0.6108,1739141194.9075673,34.31996726989746,0.9471206073768573,1739141194.90757,34.31996726989746,0.0,1739141194.907572,34.31996726989746,0.010735390400878342,1739141194.907574,34.31996726989746,2.959102362088756,1739141194.9075758,34.31996726989746,0.936385216975979 +1739141194.9282498,34.339967250823975,48.17049249537037,1739141194.9282532,34.339967250823975,8.548775990114223,1739141194.9282575,34.339967250823975,60.29040271402158,1739141194.9282615,34.339967250823975,44.01378858667748,1739141194.9282634,34.339967250823975,6.848345871761213,1739141194.928266,34.339967250823975,-2.7532821093131337,1739141194.9282677,34.339967250823975,2.426548921162352,1739141194.9282699,34.339967250823975,0.6108,1739141194.9282715,34.339967250823975,0.9471206073768573,1739141194.928274,34.339967250823975,0.0,1739141194.9282763,34.339967250823975,0.010735390400878342,1739141194.9282782,34.339967250823975,2.959102362088756,1739141194.9282804,34.339967250823975,0.936385216975979 +1739141194.9480314,34.35996723175049,48.17049249537037,1739141194.9480352,34.35996723175049,8.548775990114223,1739141194.9480395,34.35996723175049,60.29040271402158,1739141194.9480436,34.35996723175049,44.01378858667748,1739141194.9480455,34.35996723175049,6.848345871761213,1739141194.948048,34.35996723175049,-2.7532821093131337,1739141194.9480503,34.35996723175049,2.426548921162352,1739141194.948052,34.35996723175049,0.6108,1739141194.9480538,34.35996723175049,0.9471206073768573,1739141194.9480565,34.35996723175049,0.0,1739141194.9480586,34.35996723175049,0.010735390400878342,1739141194.9480608,34.35996723175049,2.959102362088756,1739141194.9480624,34.35996723175049,0.936385216975979 +1739141194.9673698,34.379967212677,48.17049249537037,1739141194.9673736,34.379967212677,8.548775990114223,1739141194.967378,34.379967212677,60.29040271402158,1739141194.967382,34.379967212677,44.01378858667748,1739141194.967384,34.379967212677,6.848345871761213,1739141194.9673867,34.379967212677,-2.7532821093131337,1739141194.9673886,34.379967212677,2.426548921162352,1739141194.9673908,34.379967212677,0.6108,1739141194.9673927,34.379967212677,0.9471206073768573,1739141194.967395,34.379967212677,0.0,1739141194.9673972,34.379967212677,0.010735390400878342,1739141194.9673991,34.379967212677,2.959102362088756,1739141194.967401,34.379967212677,0.936385216975979 +1739141194.9886389,34.399967193603516,48.06889547302094,1739141194.988643,34.399967193603516,8.566203787418134,1739141194.988647,34.399967193603516,60.347694417528594,1739141194.988651,34.399967193603516,43.979419444870395,1739141194.988653,34.399967193603516,6.797301211470598,1739141194.9886556,34.399967193603516,-2.733344565606271,1739141194.9886575,34.399967193603516,2.378148033357607,1739141194.9886594,34.399967193603516,0.6108,1739141194.9886613,34.399967193603516,0.9656358512015508,1739141194.9886634,34.399967193603516,0.0,1739141194.9886656,34.399967193603516,0.04337683164794712,1739141194.9886675,34.399967193603516,2.9868267053353934,1739141194.9886694,34.399967193603516,0.9378025707692718 +1739141195.007573,34.41996717453003,48.06889547302094,1739141195.007577,34.41996717453003,8.566203787418134,1739141195.0075817,34.41996717453003,60.347694417528594,1739141195.007586,34.41996717453003,43.979419444870395,1739141195.0075884,34.41996717453003,6.797301211470598,1739141195.007591,34.41996717453003,-2.733344565606271,1739141195.007593,34.41996717453003,2.378148033357607,1739141195.007595,34.41996717453003,0.6108,1739141195.0075967,34.41996717453003,0.9656358512015508,1739141195.0075994,34.41996717453003,0.0,1739141195.0076015,34.41996717453003,0.02783328043227906,1739141195.0076034,34.41996717453003,2.9868267053353934,1739141195.0076056,34.41996717453003,0.9378025707692718 +1739141195.0280561,34.4499671459198,48.06889547302094,1739141195.02806,34.4499671459198,8.566203787418134,1739141195.0280643,34.4499671459198,60.347694417528594,1739141195.028068,34.4499671459198,43.979419444870395,1739141195.0280702,34.4499671459198,6.797301211470598,1739141195.0280724,34.4499671459198,-2.733344565606271,1739141195.0280745,34.4499671459198,2.378148033357607,1739141195.0280762,34.4499671459198,0.6108,1739141195.028078,34.4499671459198,0.9656358512015508,1739141195.0280805,34.4499671459198,0.0,1739141195.0280824,34.4499671459198,0.02783328043227906,1739141195.0280845,34.4499671459198,2.9868267053353934,1739141195.0280862,34.4499671459198,0.9378025707692718 +1739141195.0475328,34.45996713638306,48.06889547302094,1739141195.0475366,34.45996713638306,8.566203787418134,1739141195.047541,34.45996713638306,60.347694417528594,1739141195.0475452,34.45996713638306,43.979419444870395,1739141195.047547,34.45996713638306,6.797301211470598,1739141195.0475497,34.45996713638306,-2.733344565606271,1739141195.047552,34.45996713638306,2.378148033357607,1739141195.047554,34.45996713638306,0.6108,1739141195.047556,34.45996713638306,0.9656358512015508,1739141195.047558,34.45996713638306,0.0,1739141195.0475605,34.45996713638306,0.02783328043227906,1739141195.0475621,34.45996713638306,2.9868267053353934,1739141195.047564,34.45996713638306,0.9378025707692718 +1739141195.0681205,34.47996711730957,48.06889547302094,1739141195.068124,34.47996711730957,8.566203787418134,1739141195.0681283,34.47996711730957,60.347694417528594,1739141195.0681324,34.47996711730957,43.979419444870395,1739141195.0681343,34.47996711730957,6.797301211470598,1739141195.0681367,34.47996711730957,-2.733344565606271,1739141195.0681386,34.47996711730957,2.378148033357607,1739141195.0681403,34.47996711730957,0.6108,1739141195.0681422,34.47996711730957,0.9656358512015508,1739141195.0681443,34.47996711730957,0.0,1739141195.0681465,34.47996711730957,0.02783328043227906,1739141195.0681484,34.47996711730957,2.9868267053353934,1739141195.0681503,34.47996711730957,0.9378025707692718 +1739141195.0872924,34.499967098236084,47.9666497620206,1739141195.0872958,34.499967098236084,8.580837403285276,1739141195.0873,34.499967098236084,60.53229558328521,1739141195.0873039,34.499967098236084,43.87722359439943,1739141195.087306,34.499967098236084,6.633383304684744,1739141195.0873084,34.499967098236084,-2.6971518552631317,1739141195.0873103,34.499967098236084,2.449890588923699,1739141195.0873122,34.499967098236084,0.6108,1739141195.0873141,34.499967098236084,0.9383188112183385,1739141195.0873165,34.499967098236084,0.0,1739141195.0873184,34.499967098236084,-0.029785229673986547,1739141195.0873208,34.499967098236084,3.014551048582031,1739141195.0873227,34.499967098236084,0.9406666414212569 +1739141195.1074703,34.5199670791626,47.9666497620206,1739141195.1074739,34.5199670791626,8.580837403285276,1739141195.1074784,34.5199670791626,60.53229558328521,1739141195.1074824,34.5199670791626,43.87722359439943,1739141195.1074846,34.5199670791626,6.633383304684744,1739141195.1074874,34.5199670791626,-2.6971518552631317,1739141195.1074896,34.5199670791626,2.449890588923699,1739141195.1074915,34.5199670791626,0.6108,1739141195.1074934,34.5199670791626,0.9383188112183385,1739141195.107496,34.5199670791626,0.0,1739141195.107498,34.5199670791626,-0.0023478302029183995,1739141195.1075,34.5199670791626,3.014551048582031,1739141195.107502,34.5199670791626,0.9406666414212569 +1739141195.128696,34.53996706008911,47.9666497620206,1739141195.1286995,34.53996706008911,8.580837403285276,1739141195.1287038,34.53996706008911,60.53229558328521,1739141195.1287081,34.53996706008911,43.87722359439943,1739141195.12871,34.53996706008911,6.633383304684744,1739141195.1287127,34.53996706008911,-2.6971518552631317,1739141195.1287148,34.53996706008911,2.449890588923699,1739141195.1287167,34.53996706008911,0.6108,1739141195.1287184,34.53996706008911,0.9383188112183385,1739141195.128721,34.53996706008911,0.0,1739141195.128723,34.53996706008911,-0.0023478302029183995,1739141195.1287248,34.53996706008911,3.014551048582031,1739141195.1287267,34.53996706008911,0.9406666414212569 +1739141195.147979,34.56996703147888,47.9666497620206,1739141195.1479826,34.56996703147888,8.580837403285276,1739141195.147987,34.56996703147888,60.53229558328521,1739141195.147991,34.56996703147888,43.87722359439943,1739141195.147993,34.56996703147888,6.633383304684744,1739141195.1479957,34.56996703147888,-2.6971518552631317,1739141195.1479974,34.56996703147888,2.449890588923699,1739141195.1479995,34.56996703147888,0.6108,1739141195.1480012,34.56996703147888,0.9383188112183385,1739141195.1480036,34.56996703147888,0.0,1739141195.148006,34.56996703147888,-0.0023478302029183995,1739141195.1480079,34.56996703147888,3.014551048582031,1739141195.1480098,34.56996703147888,0.9406666414212569 +1739141195.1706083,34.57996702194214,47.9666497620206,1739141195.1706123,34.57996702194214,8.580837403285276,1739141195.1706166,34.57996702194214,60.53229558328521,1739141195.1706204,34.57996702194214,43.87722359439943,1739141195.1706228,34.57996702194214,6.633383304684744,1739141195.170625,34.57996702194214,-2.6971518552631317,1739141195.170627,34.57996702194214,2.449890588923699,1739141195.1706288,34.57996702194214,0.6108,1739141195.170631,34.57996702194214,0.9383188112183385,1739141195.1706333,34.57996702194214,0.0,1739141195.1706355,34.57996702194214,-0.0023478302029183995,1739141195.1706374,34.57996702194214,3.014551048582031,1739141195.1706393,34.57996702194214,0.9406666414212569 +1739141195.190534,34.60996699333191,47.86392098005588,1739141195.1905372,34.60996699333191,8.592645400861702,1739141195.1905408,34.60996699333191,60.614700525269164,1739141195.1905441,34.60996699333191,43.83708845636056,1739141195.1905463,34.60996699333191,6.5641829095668545,1739141195.1905482,34.60996699333191,-2.674960320440387,1739141195.19055,34.60996699333191,2.41774323571077,1739141195.1905515,34.60996699333191,0.6108,1739141195.1905532,34.60996699333191,0.9504625079280958,1739141195.190555,34.60996699333191,0.0,1739141195.190557,34.60996699333191,0.022367735634030578,1739141195.1905584,34.60996699333191,3.0422753918286682,1739141195.1905603,34.60996699333191,0.9398640952385701 +1739141195.20699,34.619966983795166,47.86392098005588,1739141195.2069929,34.619966983795166,8.592645400861702,1739141195.2069964,34.619966983795166,60.614700525269164,1739141195.207,34.619966983795166,43.83708845636056,1739141195.207002,34.619966983795166,6.5641829095668545,1739141195.207004,34.619966983795166,-2.674960320440387,1739141195.2070062,34.619966983795166,2.41774323571077,1739141195.2070076,34.619966983795166,0.6108,1739141195.2070093,34.619966983795166,0.9504625079280958,1739141195.207011,34.619966983795166,0.0,1739141195.207013,34.619966983795166,0.010598412689525771,1739141195.2070148,34.619966983795166,3.0422753918286682,1739141195.2070167,34.619966983795166,0.9398640952385701 +1739141195.2273633,34.63996696472168,47.86392098005588,1739141195.2273662,34.63996696472168,8.592645400861702,1739141195.2273693,34.63996696472168,60.614700525269164,1739141195.2273722,34.63996696472168,43.83708845636056,1739141195.2273738,34.63996696472168,6.5641829095668545,1739141195.2273755,34.63996696472168,-2.674960320440387,1739141195.2273772,34.63996696472168,2.41774323571077,1739141195.2273786,34.63996696472168,0.6108,1739141195.22738,34.63996696472168,0.9504625079280958,1739141195.2273815,34.63996696472168,0.0,1739141195.2273834,34.63996696472168,0.010598412689525771,1739141195.2273848,34.63996696472168,3.0422753918286682,1739141195.2273865,34.63996696472168,0.9398640952385701 +1739141195.2472131,34.65996694564819,47.86392098005588,1739141195.247216,34.65996694564819,8.592645400861702,1739141195.2472188,34.65996694564819,60.614700525269164,1739141195.247222,34.65996694564819,43.83708845636056,1739141195.2472236,34.65996694564819,6.5641829095668545,1739141195.2472253,34.65996694564819,-2.674960320440387,1739141195.2472267,34.65996694564819,2.41774323571077,1739141195.2472281,34.65996694564819,0.6108,1739141195.2472293,34.65996694564819,0.9504625079280958,1739141195.2472312,34.65996694564819,0.0,1739141195.2472327,34.65996694564819,0.010598412689525771,1739141195.2472343,34.65996694564819,3.0422753918286682,1739141195.2472358,34.65996694564819,0.9398640952385701 +1739141195.2668633,34.67996692657471,47.86392098005588,1739141195.266866,34.67996692657471,8.592645400861702,1739141195.2668693,34.67996692657471,60.614700525269164,1739141195.2668724,34.67996692657471,43.83708845636056,1739141195.2668738,34.67996692657471,6.5641829095668545,1739141195.2668757,34.67996692657471,-2.674960320440387,1739141195.2668772,34.67996692657471,2.41774323571077,1739141195.2668786,34.67996692657471,0.6108,1739141195.26688,34.67996692657471,0.9504625079280958,1739141195.2668817,34.67996692657471,0.0,1739141195.2668834,34.67996692657471,0.010598412689525771,1739141195.2668846,34.67996692657471,3.0422753918286682,1739141195.2668862,34.67996692657471,0.9398640952385701 +1739141195.286814,34.69996690750122,47.86392098005588,1739141195.2868168,34.69996690750122,8.592645400861702,1739141195.2868202,34.69996690750122,60.614700525269164,1739141195.2868233,34.69996690750122,43.83708845636056,1739141195.2868247,34.69996690750122,6.5641829095668545,1739141195.2868266,34.69996690750122,-2.674960320440387,1739141195.286828,34.69996690750122,2.41774323571077,1739141195.2868292,34.69996690750122,0.6108,1739141195.286831,34.69996690750122,0.9504625079280958,1739141195.2868326,34.69996690750122,0.0,1739141195.2868342,34.69996690750122,0.010598412689525771,1739141195.2868357,34.69996690750122,3.0422753918286682,1739141195.286837,34.69996690750122,0.9398640952385701 +1739141195.3070717,34.719966888427734,47.76085799559004,1739141195.3070743,34.719966888427734,8.601604697137187,1739141195.3070776,34.719966888427734,60.69691773575775,1739141195.3070807,34.719966888427734,43.79509253210261,1739141195.3070822,34.719966888427734,6.48907733109565,1739141195.307084,34.719966888427734,-2.6521355873767276,1739141195.3070855,34.719966888427734,2.390793994386697,1739141195.3070872,34.719966888427734,0.6108,1739141195.3070884,34.719966888427734,0.9607636270447766,1739141195.3070905,34.719966888427734,0.0,1739141195.307092,34.719966888427734,0.02782302195860089,1739141195.3070936,34.719966888427734,3.0699997350753057,1739141195.307095,34.719966888427734,0.9411428040735682 +1739141195.3267775,34.73996686935425,47.76085799559004,1739141195.32678,34.73996686935425,8.601604697137187,1739141195.3267832,34.73996686935425,60.69691773575775,1739141195.3267863,34.73996686935425,43.79509253210261,1739141195.326788,34.73996686935425,6.48907733109565,1739141195.3267896,34.73996686935425,-2.6521355873767276,1739141195.3267913,34.73996686935425,2.390793994386697,1739141195.3267925,34.73996686935425,0.6108,1739141195.3267937,34.73996686935425,0.9607636270447766,1739141195.3267956,34.73996686935425,0.0,1739141195.326797,34.73996686935425,0.019620822971208374,1739141195.3267984,34.73996686935425,3.0699997350753057,1739141195.3267999,34.73996686935425,0.9411428040735682 +1739141195.3473282,34.75996685028076,47.76085799559004,1739141195.347331,34.75996685028076,8.601604697137187,1739141195.3473341,34.75996685028076,60.69691773575775,1739141195.347337,34.75996685028076,43.79509253210261,1739141195.3473384,34.75996685028076,6.48907733109565,1739141195.3473403,34.75996685028076,-2.6521355873767276,1739141195.3473415,34.75996685028076,2.390793994386697,1739141195.3473432,34.75996685028076,0.6108,1739141195.3473444,34.75996685028076,0.9607636270447766,1739141195.347346,34.75996685028076,0.0,1739141195.3473477,34.75996685028076,0.019620822971208374,1739141195.3473492,34.75996685028076,3.0699997350753057,1739141195.3473506,34.75996685028076,0.9411428040735682 +1739141195.3669093,34.779966831207275,47.76085799559004,1739141195.366912,34.779966831207275,8.601604697137187,1739141195.366915,34.779966831207275,60.69691773575775,1739141195.366918,34.779966831207275,43.79509253210261,1739141195.3669198,34.779966831207275,6.48907733109565,1739141195.3669214,34.779966831207275,-2.6521355873767276,1739141195.366923,34.779966831207275,2.390793994386697,1739141195.3669245,34.779966831207275,0.6108,1739141195.3669257,34.779966831207275,0.9607636270447766,1739141195.3669276,34.779966831207275,0.0,1739141195.366929,34.779966831207275,0.019620822971208374,1739141195.3669307,34.779966831207275,3.0699997350753057,1739141195.3669322,34.779966831207275,0.9411428040735682 +1739141195.387107,34.79996681213379,47.76085799559004,1739141195.3871093,34.79996681213379,8.601604697137187,1739141195.3871126,34.79996681213379,60.69691773575775,1739141195.3871155,34.79996681213379,43.79509253210261,1739141195.3871171,34.79996681213379,6.48907733109565,1739141195.3871188,34.79996681213379,-2.6521355873767276,1739141195.3871205,34.79996681213379,2.390793994386697,1739141195.3871217,34.79996681213379,0.6108,1739141195.387123,34.79996681213379,0.9607636270447766,1739141195.387125,34.79996681213379,0.0,1739141195.3871264,34.79996681213379,0.019620822971208374,1739141195.387128,34.79996681213379,3.0699997350753057,1739141195.3871293,34.79996681213379,0.9411428040735682 +1739141195.406905,34.8199667930603,47.76085799559004,1739141195.4069078,34.8199667930603,8.601604697137187,1739141195.406911,34.8199667930603,60.69691773575775,1739141195.406914,34.8199667930603,43.79509253210261,1739141195.406916,34.8199667930603,6.48907733109565,1739141195.4069176,34.8199667930603,-2.6521355873767276,1739141195.4069192,34.8199667930603,2.390793994386697,1739141195.4069207,34.8199667930603,0.6108,1739141195.406922,34.8199667930603,0.9607636270447766,1739141195.4069238,34.8199667930603,0.0,1739141195.4069252,34.8199667930603,0.019620822971208374,1739141195.4069266,34.8199667930603,3.0699997350753057,1739141195.406928,34.8199667930603,0.9411428040735682 +1739141195.4363072,34.839966773986816,47.657392602519,1739141195.4363172,34.839966773986816,8.60771473625961,1739141195.4363286,34.839966773986816,60.7973102080304,1739141195.4363396,34.839966773986816,43.744786927117694,1739141195.4363453,34.839966773986816,6.3942802595359245,1739141195.436352,34.839966773986816,-2.6267614361624854,1739141195.436358,34.839966773986816,2.3828903837439026,1739141195.4363627,34.839966773986816,0.6108,1739141195.4363673,34.839966773986816,0.9638058340460354,1739141195.436373,34.839966773986816,0.0,1739141195.4363792,34.839966773986816,0.021011320312133434,1739141195.4363847,34.839966773986816,3.097724078321943,1739141195.4363906,34.839966773986816,0.9434566556555875 +1739141195.4518142,34.85996675491333,47.657392602519,1739141195.4518235,34.85996675491333,8.60771473625961,1739141195.4518335,34.85996675491333,60.7973102080304,1739141195.4518433,34.85996675491333,43.744786927117694,1739141195.451848,34.85996675491333,6.3942802595359245,1739141195.4518535,34.85996675491333,-2.6267614361624854,1739141195.4518585,34.85996675491333,2.3828903837439026,1739141195.4518633,34.85996675491333,0.6108,1739141195.4518676,34.85996675491333,0.9638058340460354,1739141195.451873,34.85996675491333,0.0,1739141195.4518778,34.85996675491333,0.02034917839044792,1739141195.4518828,34.85996675491333,3.097724078321943,1739141195.4518871,34.85996675491333,0.9434566556555875 +1739141195.4767554,34.879966735839844,47.657392602519,1739141195.4767609,34.879966735839844,8.60771473625961,1739141195.4767668,34.879966735839844,60.7973102080304,1739141195.4767718,34.879966735839844,43.744786927117694,1739141195.4767745,34.879966735839844,6.3942802595359245,1739141195.4767778,34.879966735839844,-2.6267614361624854,1739141195.4767807,34.879966735839844,2.3828903837439026,1739141195.476783,34.879966735839844,0.6108,1739141195.476786,34.879966735839844,0.9638058340460354,1739141195.476789,34.879966735839844,0.0,1739141195.4767919,34.879966735839844,0.02034917839044792,1739141195.4767945,34.879966735839844,3.097724078321943,1739141195.4767969,34.879966735839844,0.9434566556555875 +1739141195.4953737,34.909966707229614,47.657392602519,1739141195.495377,34.909966707229614,8.60771473625961,1739141195.4953806,34.909966707229614,60.7973102080304,1739141195.4953842,34.909966707229614,43.744786927117694,1739141195.4953864,34.909966707229614,6.3942802595359245,1739141195.4953885,34.909966707229614,-2.6267614361624854,1739141195.4953904,34.909966707229614,2.3828903837439026,1739141195.495392,34.909966707229614,0.6108,1739141195.4953935,34.909966707229614,0.9638058340460354,1739141195.495396,34.909966707229614,0.0,1739141195.4953976,34.909966707229614,0.02034917839044792,1739141195.4953995,34.909966707229614,3.097724078321943,1739141195.4954011,34.909966707229614,0.9434566556555875 +1739141195.5146406,34.92996668815613,47.657392602519,1739141195.5146434,34.92996668815613,8.60771473625961,1739141195.5146475,34.92996668815613,60.7973102080304,1739141195.5146503,34.92996668815613,43.744786927117694,1739141195.5146523,34.92996668815613,6.3942802595359245,1739141195.5146542,34.92996668815613,-2.6267614361624854,1739141195.5146556,34.92996668815613,2.3828903837439026,1739141195.514657,34.92996668815613,0.6108,1739141195.514658,34.92996668815613,0.9638058340460354,1739141195.51466,34.92996668815613,0.0,1739141195.514662,34.92996668815613,0.02034917839044792,1739141195.5146644,34.92996668815613,3.097724078321943,1739141195.5146658,34.92996668815613,0.9434566556555875 +1739141195.5366051,34.94996666908264,47.55355589230437,1739141195.5366092,34.94996666908264,8.610961854056125,1739141195.5366142,34.94996666908264,60.93282938142214,1739141195.5366194,34.94996666908264,43.681169946991936,1739141195.5366225,34.94996666908264,6.26713774734044,1739141195.5366263,34.94996666908264,-2.5973099836441884,1739141195.53663,34.94996666908264,2.4060326521393116,1739141195.5366333,34.94996666908264,0.6108,1739141195.5366366,34.94996666908264,0.9549251400256376,1739141195.5366404,34.94996666908264,0.0,1739141195.5366437,34.94996666908264,-0.0008424235123232517,1739141195.5366473,34.94996666908264,3.1254484215685805,1739141195.5366507,34.94996666908264,0.9456763194956239 +1739141195.556518,34.969966650009155,47.55355589230437,1739141195.556522,34.969966650009155,8.610961854056125,1739141195.5565267,34.969966650009155,60.93282938142214,1739141195.556532,34.969966650009155,43.681169946991936,1739141195.556535,34.969966650009155,6.26713774734044,1739141195.5565388,34.969966650009155,-2.5973099836441884,1739141195.5565424,34.969966650009155,2.4060326521393116,1739141195.556546,34.969966650009155,0.6108,1739141195.5565493,34.969966650009155,0.9549251400256376,1739141195.5565531,34.969966650009155,0.0,1739141195.5565567,34.969966650009155,0.009248820530013635,1739141195.55656,34.969966650009155,3.1254484215685805,1739141195.5565636,34.969966650009155,0.9456763194956239 +1739141195.57644,34.98996663093567,47.55355589230437,1739141195.5764434,34.98996663093567,8.610961854056125,1739141195.5764477,34.98996663093567,60.93282938142214,1739141195.5764525,34.98996663093567,43.681169946991936,1739141195.5764554,34.98996663093567,6.26713774734044,1739141195.576459,34.98996663093567,-2.5973099836441884,1739141195.576462,34.98996663093567,2.4060326521393116,1739141195.5764654,34.98996663093567,0.6108,1739141195.5764685,34.98996663093567,0.9549251400256376,1739141195.5764718,34.98996663093567,0.0,1739141195.5764751,34.98996663093567,0.009248820530013635,1739141195.5764782,34.98996663093567,3.1254484215685805,1739141195.5764816,34.98996663093567,0.9456763194956239 +1739141195.5955524,35.00996661186218,47.55355589230437,1739141195.595555,35.00996661186218,8.610961854056125,1739141195.5955577,35.00996661186218,60.93282938142214,1739141195.59556,35.00996661186218,43.681169946991936,1739141195.5955615,35.00996661186218,6.26713774734044,1739141195.595563,35.00996661186218,-2.5973099836441884,1739141195.5955644,35.00996661186218,2.4060326521393116,1739141195.5955656,35.00996661186218,0.6108,1739141195.5955665,35.00996661186218,0.9549251400256376,1739141195.5955682,35.00996661186218,0.0,1739141195.5955694,35.00996661186218,0.009248820530013635,1739141195.5955703,35.00996661186218,3.1254484215685805,1739141195.5955718,35.00996661186218,0.9456763194956239 +1739141195.6146169,35.029966592788696,47.55355589230437,1739141195.6146212,35.029966592788696,8.610961854056125,1739141195.6146255,35.029966592788696,60.93282938142214,1739141195.6146293,35.029966592788696,43.681169946991936,1739141195.6146317,35.029966592788696,6.26713774734044,1739141195.6146367,35.029966592788696,-2.5973099836441884,1739141195.614641,35.029966592788696,2.4060326521393116,1739141195.6146443,35.029966592788696,0.6108,1739141195.6146474,35.029966592788696,0.9549251400256376,1739141195.614651,35.029966592788696,0.0,1739141195.6146545,35.029966592788696,0.009248820530013635,1739141195.6146576,35.029966592788696,3.1254484215685805,1739141195.614661,35.029966592788696,0.9456763194956239 +1739141195.6363258,35.04996657371521,47.44949088839364,1739141195.6363297,35.04996657371521,8.61133026455034,1739141195.6363344,35.04996657371521,61.013847396311895,1739141195.6363394,35.04996657371521,43.645132036312496,1739141195.6363423,35.04996657371521,6.1915009655486015,1739141195.636346,35.04996657371521,-2.5750741923140086,1739141195.6363492,35.04996657371521,2.3756131384636396,1739141195.6363528,35.04996657371521,0.6108,1739141195.636356,35.04996657371521,0.9666154619151179,1739141195.6363595,35.04996657371521,0.0,1739141195.6363628,35.04996657371521,0.02980663394373709,1739141195.6363661,35.04996657371521,3.153172764815218,1739141195.6363695,35.04996657371521,0.9465982678205497 +1739141195.656428,35.069966554641724,47.44949088839364,1739141195.6564317,35.069966554641724,8.61133026455034,1739141195.656436,35.069966554641724,61.013847396311895,1739141195.656441,35.069966554641724,43.645132036312496,1739141195.6564438,35.069966554641724,6.1915009655486015,1739141195.6564476,35.069966554641724,-2.5750741923140086,1739141195.6564512,35.069966554641724,2.3756131384636396,1739141195.6564546,35.069966554641724,0.6108,1739141195.6564577,35.069966554641724,0.9666154619151179,1739141195.656461,35.069966554641724,0.0,1739141195.6564646,35.069966554641724,0.020017194094568258,1739141195.6564677,35.069966554641724,3.153172764815218,1739141195.656471,35.069966554641724,0.9465982678205497 +1739141195.6763752,35.08996653556824,47.44949088839364,1739141195.6763787,35.08996653556824,8.61133026455034,1739141195.676383,35.08996653556824,61.013847396311895,1739141195.676388,35.08996653556824,43.645132036312496,1739141195.676391,35.08996653556824,6.1915009655486015,1739141195.6763947,35.08996653556824,-2.5750741923140086,1739141195.6763978,35.08996653556824,2.3756131384636396,1739141195.6764011,35.08996653556824,0.6108,1739141195.6764045,35.08996653556824,0.9666154619151179,1739141195.6764078,35.08996653556824,0.0,1739141195.6764112,35.08996653556824,0.020017194094568258,1739141195.6764145,35.08996653556824,3.153172764815218,1739141195.6764178,35.08996653556824,0.9465982678205497 +1739141195.6964474,35.10996651649475,47.44949088839364,1739141195.6964507,35.10996651649475,8.61133026455034,1739141195.6964555,35.10996651649475,61.013847396311895,1739141195.6964602,35.10996651649475,43.645132036312496,1739141195.6964633,35.10996651649475,6.1915009655486015,1739141195.696467,35.10996651649475,-2.5750741923140086,1739141195.6964703,35.10996651649475,2.3756131384636396,1739141195.6964736,35.10996651649475,0.6108,1739141195.696477,35.10996651649475,0.9666154619151179,1739141195.6964805,35.10996651649475,0.0,1739141195.6964839,35.10996651649475,0.020017194094568258,1739141195.6964872,35.10996651649475,3.153172764815218,1739141195.6964905,35.10996651649475,0.9465982678205497 +1739141195.7146423,35.129966497421265,47.44949088839364,1739141195.7146447,35.129966497421265,8.61133026455034,1739141195.7146475,35.129966497421265,61.013847396311895,1739141195.7146504,35.129966497421265,43.645132036312496,1739141195.7146518,35.129966497421265,6.1915009655486015,1739141195.7146537,35.129966497421265,-2.5750741923140086,1739141195.714655,35.129966497421265,2.3756131384636396,1739141195.7146564,35.129966497421265,0.6108,1739141195.7146575,35.129966497421265,0.9666154619151179,1739141195.714659,35.129966497421265,0.0,1739141195.7146604,35.129966497421265,0.020017194094568258,1739141195.7146616,35.129966497421265,3.153172764815218,1739141195.714663,35.129966497421265,0.9465982678205497 +1739141195.7341397,35.14996647834778,47.44949088839364,1739141195.734142,35.14996647834778,8.61133026455034,1739141195.7341447,35.14996647834778,61.013847396311895,1739141195.734147,35.14996647834778,43.645132036312496,1739141195.7341485,35.14996647834778,6.1915009655486015,1739141195.7341502,35.14996647834778,-2.5750741923140086,1739141195.7341514,35.14996647834778,2.3756131384636396,1739141195.7341528,35.14996647834778,0.6108,1739141195.734154,35.14996647834778,0.9666154619151179,1739141195.7341554,35.14996647834778,0.0,1739141195.7341568,35.14996647834778,0.020017194094568258,1739141195.734158,35.14996647834778,3.153172764815218,1739141195.734159,35.14996647834778,0.9465982678205497 +1739141195.7542274,35.16996645927429,47.345270471862214,1739141195.7542298,35.16996645927429,8.60880891855126,1739141195.7542324,35.16996645927429,61.09392577988279,1739141195.754235,35.16996645927429,43.609741983658964,1739141195.7542367,35.16996645927429,6.1117622111900385,1739141195.7542381,35.16996645927429,-2.552350402275653,1739141195.7542396,35.16996645927429,2.348333077331379,1739141195.7542408,35.16996645927429,0.6108,1739141195.754242,35.16996645927429,0.977220951920449,1739141195.7542436,35.16996645927429,0.0,1739141195.7542448,35.16996645927429,0.03570355896493437,1739141195.7542462,35.16996645927429,3.1808971080618553,1739141195.7542472,35.16996645927429,0.948987094244274 +1739141195.774153,35.189966440200806,47.345270471862214,1739141195.774155,35.189966440200806,8.60880891855126,1739141195.7741575,35.189966440200806,61.09392577988279,1739141195.7741604,35.189966440200806,43.609741983658964,1739141195.7741618,35.189966440200806,6.1117622111900385,1739141195.7741635,35.189966440200806,-2.552350402275653,1739141195.7741644,35.189966440200806,2.348333077331379,1739141195.7741659,35.189966440200806,0.6108,1739141195.774167,35.189966440200806,0.977220951920449,1739141195.7741683,35.189966440200806,0.0,1739141195.77417,35.189966440200806,0.028233857676175034,1739141195.774171,35.189966440200806,3.1808971080618553,1739141195.774172,35.189966440200806,0.948987094244274 +1739141195.7941635,35.20996642112732,47.345270471862214,1739141195.794166,35.20996642112732,8.60880891855126,1739141195.7941685,35.20996642112732,61.09392577988279,1739141195.7941713,35.20996642112732,43.609741983658964,1739141195.7941728,35.20996642112732,6.1117622111900385,1739141195.7941744,35.20996642112732,-2.552350402275653,1739141195.7941756,35.20996642112732,2.348333077331379,1739141195.794177,35.20996642112732,0.6108,1739141195.7941782,35.20996642112732,0.977220951920449,1739141195.79418,35.20996642112732,0.0,1739141195.794181,35.20996642112732,0.028233857676175034,1739141195.7941825,35.20996642112732,3.1808971080618553,1739141195.794184,35.20996642112732,0.948987094244274 +1739141195.8143637,35.22996640205383,47.345270471862214,1739141195.8143666,35.22996640205383,8.60880891855126,1739141195.8143694,35.22996640205383,61.09392577988279,1739141195.8143723,35.22996640205383,43.609741983658964,1739141195.8143737,35.22996640205383,6.1117622111900385,1739141195.8143754,35.22996640205383,-2.552350402275653,1739141195.814377,35.22996640205383,2.348333077331379,1739141195.8143783,35.22996640205383,0.6108,1739141195.8143795,35.22996640205383,0.977220951920449,1739141195.8143811,35.22996640205383,0.0,1739141195.8143826,35.22996640205383,0.028233857676175034,1739141195.814384,35.22996640205383,3.1808971080618553,1739141195.8143852,35.22996640205383,0.948987094244274 +1739141195.8342657,35.24996638298035,47.345270471862214,1739141195.834268,35.24996638298035,8.60880891855126,1739141195.834271,35.24996638298035,61.09392577988279,1739141195.8342738,35.24996638298035,43.609741983658964,1739141195.8342752,35.24996638298035,6.1117622111900385,1739141195.8342772,35.24996638298035,-2.552350402275653,1739141195.8342786,35.24996638298035,2.348333077331379,1739141195.83428,35.24996638298035,0.6108,1739141195.8342812,35.24996638298035,0.977220951920449,1739141195.834283,35.24996638298035,0.0,1739141195.8342845,35.24996638298035,0.028233857676175034,1739141195.8342857,35.24996638298035,3.1808971080618553,1739141195.8342872,35.24996638298035,0.948987094244274 +1739141195.8545518,35.26996636390686,47.240866783011654,1739141195.854555,35.26996636390686,8.60338401340085,1739141195.8545578,35.26996636390686,61.246042587283625,1739141195.8545609,35.26996636390686,43.54867497797344,1739141195.854562,35.26996636390686,5.962151032368974,1739141195.854564,35.26996636390686,-2.520634569164979,1739141195.8545651,35.26996636390686,2.3880039561347903,1739141195.8545663,35.26996636390686,0.6108,1739141195.854568,35.26996636390686,0.9618364524864292,1739141195.8545694,35.26996636390686,0.0,1739141195.854571,35.26996636390686,-0.007169894053478419,1739141195.8545725,35.26996636390686,3.2086214513084927,1739141195.8545737,35.26996636390686,0.9521474087230586 +1739141195.874293,35.289966344833374,47.240866783011654,1739141195.8742955,35.289966344833374,8.60338401340085,1739141195.8742986,35.289966344833374,61.246042587283625,1739141195.8743014,35.289966344833374,43.54867497797344,1739141195.8743029,35.289966344833374,5.962151032368974,1739141195.8743048,35.289966344833374,-2.520634569164979,1739141195.8743067,35.289966344833374,2.3880039561347903,1739141195.8743079,35.289966344833374,0.6108,1739141195.8743093,35.289966344833374,0.9618364524864292,1739141195.874311,35.289966344833374,0.0,1739141195.8743122,35.289966344833374,0.009689043763370653,1739141195.8743138,35.289966344833374,3.2086214513084927,1739141195.874315,35.289966344833374,0.9521474087230586 +1739141195.894304,35.30996632575989,47.240866783011654,1739141195.8943067,35.30996632575989,8.60338401340085,1739141195.8943093,35.30996632575989,61.246042587283625,1739141195.8943124,35.30996632575989,43.54867497797344,1739141195.8943138,35.30996632575989,5.962151032368974,1739141195.8943155,35.30996632575989,-2.520634569164979,1739141195.8943172,35.30996632575989,2.3880039561347903,1739141195.8943183,35.30996632575989,0.6108,1739141195.8943195,35.30996632575989,0.9618364524864292,1739141195.8943214,35.30996632575989,0.0,1739141195.8943226,35.30996632575989,0.009689043763370653,1739141195.894324,35.30996632575989,3.2086214513084927,1739141195.8943253,35.30996632575989,0.9521474087230586 +1739141195.9143374,35.3299663066864,47.240866783011654,1739141195.9143398,35.3299663066864,8.60338401340085,1739141195.9143429,35.3299663066864,61.246042587283625,1739141195.9143457,35.3299663066864,43.54867497797344,1739141195.914347,35.3299663066864,5.962151032368974,1739141195.9143488,35.3299663066864,-2.520634569164979,1739141195.9143503,35.3299663066864,2.3880039561347903,1739141195.9143517,35.3299663066864,0.6108,1739141195.914353,35.3299663066864,0.9618364524864292,1739141195.9143548,35.3299663066864,0.0,1739141195.914356,35.3299663066864,0.009689043763370653,1739141195.9143572,35.3299663066864,3.2086214513084927,1739141195.9143586,35.3299663066864,0.9521474087230586 +1739141195.9342754,35.349966287612915,47.240866783011654,1739141195.9342782,35.349966287612915,8.60338401340085,1739141195.9342809,35.349966287612915,61.246042587283625,1739141195.934284,35.349966287612915,43.54867497797344,1739141195.9342856,35.349966287612915,5.962151032368974,1739141195.9342873,35.349966287612915,-2.520634569164979,1739141195.9342887,35.349966287612915,2.3880039561347903,1739141195.9342902,35.349966287612915,0.6108,1739141195.9342914,35.349966287612915,0.9618364524864292,1739141195.9342935,35.349966287612915,0.0,1739141195.934295,35.349966287612915,0.009689043763370653,1739141195.9342964,35.349966287612915,3.2086214513084927,1739141195.9342976,35.349966287612915,0.9521474087230586 +1739141195.9543622,35.36996626853943,47.240866783011654,1739141195.9543653,35.36996626853943,8.60338401340085,1739141195.9543684,35.36996626853943,61.246042587283625,1739141195.954371,35.36996626853943,43.54867497797344,1739141195.9543726,35.36996626853943,5.962151032368974,1739141195.954374,35.36996626853943,-2.520634569164979,1739141195.954376,35.36996626853943,2.3880039561347903,1739141195.9543772,35.36996626853943,0.6108,1739141195.9543786,35.36996626853943,0.9618364524864292,1739141195.9543803,35.36996626853943,0.0,1739141195.954382,35.36996626853943,0.009689043763370653,1739141195.9543831,35.36996626853943,3.2086214513084927,1739141195.9543843,35.36996626853943,0.9521474087230586 +1739141195.9742815,35.38996624946594,47.13644462111461,1739141195.974284,35.38996624946594,8.595050966035165,1739141195.9742868,35.38996624946594,61.32622334486013,1739141195.9742894,35.38996624946594,43.51960980970905,1739141195.9742908,35.38996624946594,5.885099743905957,1739141195.9742928,35.38996624946594,-2.4985650347977635,1739141195.974294,35.38996624946594,2.355601259621561,1739141195.9742956,35.38996624946594,0.6108,1739141195.9742968,35.38996624946594,0.9743840297655788,1739141195.9742987,35.38996624946594,0.0,1739141195.9743001,35.38996624946594,0.03225532549114858,1739141195.9743013,35.38996624946594,3.23634579455513,1739141195.9743028,35.38996624946594,0.9528745580842527 +1739141195.994327,35.409966230392456,47.13644462111461,1739141195.9943297,35.409966230392456,8.595050966035165,1739141195.9943328,35.409966230392456,61.32622334486013,1739141195.9943354,35.409966230392456,43.51960980970905,1739141195.994337,35.409966230392456,5.885099743905957,1739141195.9943385,35.409966230392456,-2.4985650347977635,1739141195.9943402,35.409966230392456,2.355601259621561,1739141195.9943414,35.409966230392456,0.6108,1739141195.9943426,35.409966230392456,0.9743840297655788,1739141195.9943442,35.409966230392456,0.0,1739141195.9943457,35.409966230392456,0.02150947168132611,1739141195.994347,35.409966230392456,3.23634579455513,1739141195.9943483,35.409966230392456,0.9528745580842527 +1739141196.0146952,35.42996621131897,47.13644462111461,1739141196.0146983,35.42996621131897,8.595050966035165,1739141196.0147018,35.42996621131897,61.32622334486013,1739141196.0147052,35.42996621131897,43.51960980970905,1739141196.014707,35.42996621131897,5.885099743905957,1739141196.0147092,35.42996621131897,-2.4985650347977635,1739141196.014711,35.42996621131897,2.355601259621561,1739141196.0147123,35.42996621131897,0.6108,1739141196.0147138,35.42996621131897,0.9743840297655788,1739141196.014716,35.42996621131897,0.0,1739141196.0147176,35.42996621131897,0.02150947168132611,1739141196.0147192,35.42996621131897,3.23634579455513,1739141196.0147204,35.42996621131897,0.9528745580842527 +1739141196.0354342,35.44996619224548,47.13644462111461,1739141196.035437,35.44996619224548,8.595050966035165,1739141196.0354404,35.44996619224548,61.32622334486013,1739141196.0354435,35.44996619224548,43.51960980970905,1739141196.035445,35.44996619224548,5.885099743905957,1739141196.0354471,35.44996619224548,-2.4985650347977635,1739141196.0354486,35.44996619224548,2.355601259621561,1739141196.0354502,35.44996619224548,0.6108,1739141196.0354517,35.44996619224548,0.9743840297655788,1739141196.0354538,35.44996619224548,0.0,1739141196.0354555,35.44996619224548,0.02150947168132611,1739141196.0354571,35.44996619224548,3.23634579455513,1739141196.0354586,35.44996619224548,0.9528745580842527 +1739141196.054519,35.469966173172,47.13644462111461,1739141196.0545218,35.469966173172,8.595050966035165,1739141196.0545254,35.469966173172,61.32622334486013,1739141196.0545285,35.469966173172,43.51960980970905,1739141196.0545301,35.469966173172,5.885099743905957,1739141196.054532,35.469966173172,-2.4985650347977635,1739141196.0545337,35.469966173172,2.355601259621561,1739141196.0545352,35.469966173172,0.6108,1739141196.0545368,35.469966173172,0.9743840297655788,1739141196.0545385,35.469966173172,0.0,1739141196.05454,35.469966173172,0.02150947168132611,1739141196.0545413,35.469966173172,3.23634579455513,1739141196.0545428,35.469966173172,0.9528745580842527 +1739141196.0745585,35.48996615409851,47.032111503935106,1739141196.0745614,35.48996615409851,8.58380640318773,1739141196.0745645,35.48996615409851,61.40655038380103,1739141196.0745678,35.48996615409851,43.4901689528235,1739141196.0745692,35.48996615409851,5.802501784310378,1739141196.0745714,35.48996615409851,-2.475911554795023,1739141196.0745728,35.48996615409851,2.327745425099649,1739141196.074574,35.48996615409851,0.6108,1739141196.0745757,35.48996615409851,0.9853016528303162,1739141196.0745773,35.48996615409851,0.0,1739141196.074579,35.48996615409851,0.03766796006539594,1739141196.0745804,35.48996615409851,3.2640701378017676,1739141196.074582,35.48996615409851,0.9553282148867988 +1739141196.0945532,35.509966135025024,47.032111503935106,1739141196.0945559,35.509966135025024,8.58380640318773,1739141196.094559,35.509966135025024,61.40655038380103,1739141196.094562,35.509966135025024,43.4901689528235,1739141196.0945635,35.509966135025024,5.802501784310378,1739141196.0945654,35.509966135025024,-2.475911554795023,1739141196.0945668,35.509966135025024,2.327745425099649,1739141196.0945685,35.509966135025024,0.6108,1739141196.09457,35.509966135025024,0.9853016528303162,1739141196.0945718,35.509966135025024,0.0,1739141196.0945733,35.509966135025024,0.029973437943517478,1739141196.0945747,35.509966135025024,3.2640701378017676,1739141196.0945761,35.509966135025024,0.9553282148867988 +1739141196.1148956,35.52996611595154,47.032111503935106,1739141196.1148992,35.52996611595154,8.58380640318773,1739141196.114903,35.52996611595154,61.40655038380103,1739141196.1149065,35.52996611595154,43.4901689528235,1739141196.1149085,35.52996611595154,5.802501784310378,1739141196.1149104,35.52996611595154,-2.475911554795023,1739141196.1149123,35.52996611595154,2.327745425099649,1739141196.1149137,35.52996611595154,0.6108,1739141196.1149156,35.52996611595154,0.9853016528303162,1739141196.1149175,35.52996611595154,0.0,1739141196.1149194,35.52996611595154,0.029973437943517478,1739141196.1149213,35.52996611595154,3.2640701378017676,1739141196.1149228,35.52996611595154,0.9553282148867988 +1739141196.1346004,35.54996609687805,47.032111503935106,1739141196.1346035,35.54996609687805,8.58380640318773,1739141196.134607,35.54996609687805,61.40655038380103,1739141196.134611,35.54996609687805,43.4901689528235,1739141196.1346128,35.54996609687805,5.802501784310378,1739141196.134615,35.54996609687805,-2.475911554795023,1739141196.1346166,35.54996609687805,2.327745425099649,1739141196.1346183,35.54996609687805,0.6108,1739141196.13462,35.54996609687805,0.9853016528303162,1739141196.134622,35.54996609687805,0.0,1739141196.134624,35.54996609687805,0.029973437943517478,1739141196.1346254,35.54996609687805,3.2640701378017676,1739141196.1346273,35.54996609687805,0.9553282148867988 +1739141196.1548414,35.569966077804565,47.032111503935106,1739141196.1548452,35.569966077804565,8.58380640318773,1739141196.1548493,35.569966077804565,61.40655038380103,1739141196.1548529,35.569966077804565,43.4901689528235,1739141196.154855,35.569966077804565,5.802501784310378,1739141196.1548572,35.569966077804565,-2.475911554795023,1739141196.154859,35.569966077804565,2.327745425099649,1739141196.1548605,35.569966077804565,0.6108,1739141196.1548629,35.569966077804565,0.9853016528303162,1739141196.1548653,35.569966077804565,0.0,1739141196.1548672,35.569966077804565,0.029973437943517478,1739141196.154869,35.569966077804565,3.2640701378017676,1739141196.154871,35.569966077804565,0.9553282148867988 +1739141196.1749315,35.58996605873108,47.032111503935106,1739141196.1749346,35.58996605873108,8.58380640318773,1739141196.1749384,35.58996605873108,61.40655038380103,1739141196.1749418,35.58996605873108,43.4901689528235,1739141196.1749434,35.58996605873108,5.802501784310378,1739141196.1749456,35.58996605873108,-2.475911554795023,1739141196.1749473,35.58996605873108,2.327745425099649,1739141196.1749492,35.58996605873108,0.6108,1739141196.1749506,35.58996605873108,0.9853016528303162,1739141196.1749525,35.58996605873108,0.0,1739141196.1749542,35.58996605873108,0.029973437943517478,1739141196.174956,35.58996605873108,3.2640701378017676,1739141196.1749575,35.58996605873108,0.9553282148867988 +1739141196.1948555,35.60996603965759,46.92780863840963,1739141196.1948583,35.60996603965759,8.56963004285187,1739141196.194862,35.60996603965759,61.55768918342524,1739141196.1948652,35.60996603965759,43.43869190635368,1739141196.1948671,35.60996603965759,5.6494963918917565,1739141196.1948693,35.60996603965759,-2.4447376656209356,1739141196.194871,35.60996603965759,2.3651521956843844,1739141196.1948726,35.60996603965759,0.6108,1739141196.194874,35.60996603965759,0.9706686195859698,1739141196.1948762,35.60996603965759,0.0,1739141196.194878,35.60996603965759,-0.004526946353950609,1739141196.1948798,35.60996603965759,3.291794481048405,1739141196.1948812,35.60996603965759,0.95876680330567 +1739141196.2149801,35.629966020584106,46.92780863840963,1739141196.2149837,35.629966020584106,8.56963004285187,1739141196.2149875,35.629966020584106,61.55768918342524,1739141196.2149909,35.629966020584106,43.43869190635368,1739141196.2149925,35.629966020584106,5.6494963918917565,1739141196.2149947,35.629966020584106,-2.4447376656209356,1739141196.2149966,35.629966020584106,2.3651521956843844,1739141196.2149985,35.629966020584106,0.6108,1739141196.2150002,35.629966020584106,0.9706686195859698,1739141196.215002,35.629966020584106,0.0,1739141196.215004,35.629966020584106,0.011901816280299848,1739141196.2150056,35.629966020584106,3.291794481048405,1739141196.2150075,35.629966020584106,0.95876680330567 +1739141196.234754,35.64996600151062,46.92780863840963,1739141196.2347572,35.64996600151062,8.56963004285187,1739141196.234761,35.64996600151062,61.55768918342524,1739141196.2347646,35.64996600151062,43.43869190635368,1739141196.2347665,35.64996600151062,5.6494963918917565,1739141196.2347689,35.64996600151062,-2.4447376656209356,1739141196.2347705,35.64996600151062,2.3651521956843844,1739141196.2347722,35.64996600151062,0.6108,1739141196.234774,35.64996600151062,0.9706686195859698,1739141196.234776,35.64996600151062,0.0,1739141196.234778,35.64996600151062,0.011901816280299848,1739141196.2347796,35.64996600151062,3.291794481048405,1739141196.2347813,35.64996600151062,0.95876680330567 +1739141196.2550008,35.669965982437134,46.92780863840963,1739141196.2550044,35.669965982437134,8.56963004285187,1739141196.2550082,35.669965982437134,61.55768918342524,1739141196.2550118,35.669965982437134,43.43869190635368,1739141196.2550137,35.669965982437134,5.6494963918917565,1739141196.2550156,35.669965982437134,-2.4447376656209356,1739141196.2550175,35.669965982437134,2.3651521956843844,1739141196.255019,35.669965982437134,0.6108,1739141196.2550209,35.669965982437134,0.9706686195859698,1739141196.2550228,35.669965982437134,0.0,1739141196.2550247,35.669965982437134,0.011901816280299848,1739141196.2550263,35.669965982437134,3.291794481048405,1739141196.255028,35.669965982437134,0.95876680330567 +1739141196.2749248,35.68996596336365,46.92780863840963,1739141196.2749279,35.68996596336365,8.56963004285187,1739141196.274932,35.68996596336365,61.55768918342524,1739141196.2749352,35.68996596336365,43.43869190635368,1739141196.2749372,35.68996596336365,5.6494963918917565,1739141196.274939,35.68996596336365,-2.4447376656209356,1739141196.274941,35.68996596336365,2.3651521956843844,1739141196.2749424,35.68996596336365,0.6108,1739141196.274944,35.68996596336365,0.9706686195859698,1739141196.2749457,35.68996596336365,0.0,1739141196.274948,35.68996596336365,0.011901816280299848,1739141196.2749493,35.68996596336365,3.291794481048405,1739141196.274951,35.68996596336365,0.95876680330567 +1739141196.2949123,35.70996594429016,46.823687710249786,1739141196.2949154,35.70996594429016,8.552527121663086,1739141196.2949193,35.70996594429016,61.55938932411818,1739141196.2949226,35.70996594429016,43.43721556162064,1739141196.2949243,35.70996594429016,5.644546294845674,1739141196.2949264,35.70996594429016,-2.4320665025961192,1739141196.294928,35.70996594429016,2.262704242492579,1739141196.29493,35.70996594429016,0.6108,1739141196.2949314,35.70996594429016,1.0112720914895816,1739141196.2949333,35.70996594429016,0.0,1739141196.2949352,35.70996594429016,0.08721230000176364,1739141196.2949371,35.70996594429016,3.3195188242950424,1739141196.2949386,35.70996594429016,0.9599219445079892 +1739141196.315086,35.729965925216675,46.823687710249786,1739141196.3150897,35.729965925216675,8.552527121663086,1739141196.3150935,35.729965925216675,61.55938932411818,1739141196.315097,35.729965925216675,43.43721556162064,1739141196.3150988,35.729965925216675,5.644546294845674,1739141196.315101,35.729965925216675,-2.4320665025961192,1739141196.3151028,35.729965925216675,2.262704242492579,1739141196.3151045,35.729965925216675,0.6108,1739141196.3151064,35.729965925216675,1.0112720914895816,1739141196.3151083,35.729965925216675,0.0,1739141196.3151102,35.729965925216675,0.05135014698159246,1739141196.3151116,35.729965925216675,3.3195188242950424,1739141196.3151133,35.729965925216675,0.9599219445079892 +1739141196.3349214,35.74996590614319,46.823687710249786,1739141196.3349247,35.74996590614319,8.552527121663086,1739141196.3349288,35.74996590614319,61.55938932411818,1739141196.3349328,35.74996590614319,43.43721556162064,1739141196.334935,35.74996590614319,5.644546294845674,1739141196.3349376,35.74996590614319,-2.4320665025961192,1739141196.3349397,35.74996590614319,2.262704242492579,1739141196.3349414,35.74996590614319,0.6108,1739141196.334943,35.74996590614319,1.0112720914895816,1739141196.334945,35.74996590614319,0.0,1739141196.3349473,35.74996590614319,0.05135014698159246,1739141196.3349495,35.74996590614319,3.3195188242950424,1739141196.3349514,35.74996590614319,0.9599219445079892 +1739141196.355262,35.7699658870697,46.823687710249786,1739141196.355266,35.7699658870697,8.552527121663086,1739141196.3552697,35.7699658870697,61.55938932411818,1739141196.355273,35.7699658870697,43.43721556162064,1739141196.3552747,35.7699658870697,5.644546294845674,1739141196.355277,35.7699658870697,-2.4320665025961192,1739141196.3552787,35.7699658870697,2.262704242492579,1739141196.3552806,35.7699658870697,0.6108,1739141196.355282,35.7699658870697,1.0112720914895816,1739141196.355284,35.7699658870697,0.0,1739141196.3552856,35.7699658870697,0.05135014698159246,1739141196.3552876,35.7699658870697,3.3195188242950424,1739141196.355289,35.7699658870697,0.9599219445079892 +1739141196.374951,35.789965867996216,46.823687710249786,1739141196.3749542,35.789965867996216,8.552527121663086,1739141196.374958,35.789965867996216,61.55938932411818,1739141196.3749616,35.789965867996216,43.43721556162064,1739141196.3749635,35.789965867996216,5.644546294845674,1739141196.374966,35.789965867996216,-2.4320665025961192,1739141196.3749678,35.789965867996216,2.262704242492579,1739141196.3749692,35.789965867996216,0.6108,1739141196.374971,35.789965867996216,1.0112720914895816,1739141196.3749728,35.789965867996216,0.0,1739141196.374975,35.789965867996216,0.05135014698159246,1739141196.3749769,35.789965867996216,3.3195188242950424,1739141196.3749783,35.789965867996216,0.9599219445079892 +1739141196.3949091,35.80996584892273,46.823687710249786,1739141196.3949127,35.80996584892273,8.552527121663086,1739141196.3949168,35.80996584892273,61.55938932411818,1739141196.3949206,35.80996584892273,43.43721556162064,1739141196.3949227,35.80996584892273,5.644546294845674,1739141196.3949256,35.80996584892273,-2.4320665025961192,1739141196.3949275,35.80996584892273,2.262704242492579,1739141196.3949296,35.80996584892273,0.6108,1739141196.3949313,35.80996584892273,1.0112720914895816,1739141196.3949332,35.80996584892273,0.0,1739141196.3949354,35.80996584892273,0.05135014698159246,1739141196.394937,35.80996584892273,3.3195188242950424,1739141196.3949392,35.80996584892273,0.9599219445079892 +1739141196.4151964,35.82996582984924,46.71966718938867,1739141196.4152,35.82996582984924,8.532463363362382,1739141196.4152038,35.82996582984924,61.56109377996855,1739141196.4152074,35.82996582984924,43.431291085051704,1739141196.4152093,35.82996582984924,5.624681873408659,1739141196.4152114,35.82996582984924,-2.4175417098497483,1739141196.415213,35.82996582984924,2.1750101623960587,1739141196.4152148,35.82996582984924,0.6108,1739141196.4152164,35.82996582984924,1.0473746155761778,1739141196.4152184,35.82996582984924,0.0,1739141196.4152203,35.82996582984924,0.10816659578194354,1739141196.4152222,35.82996582984924,3.34724316754168,1739141196.4152238,35.82996582984924,0.9662634851193123 +1739141196.4346843,35.84996581077576,46.71966718938867,1739141196.4346871,35.84996581077576,8.532463363362382,1739141196.4346907,35.84996581077576,61.56109377996855,1739141196.4346943,35.84996581077576,43.431291085051704,1739141196.4346962,35.84996581077576,5.624681873408659,1739141196.4346986,35.84996581077576,-2.4175417098497483,1739141196.4347003,35.84996581077576,2.1750101623960587,1739141196.4347022,35.84996581077576,0.6108,1739141196.4347036,35.84996581077576,1.0473746155761778,1739141196.4347057,35.84996581077576,0.0,1739141196.4347074,35.84996581077576,0.08111113045686558,1739141196.434709,35.84996581077576,3.34724316754168,1739141196.4347107,35.84996581077576,0.9662634851193123 +1739141196.4549923,35.86996579170227,46.71966718938867,1739141196.4549954,35.86996579170227,8.532463363362382,1739141196.455,35.86996579170227,61.56109377996855,1739141196.455003,35.86996579170227,43.431291085051704,1739141196.455005,35.86996579170227,5.624681873408659,1739141196.4550076,35.86996579170227,-2.4175417098497483,1739141196.4550095,35.86996579170227,2.1750101623960587,1739141196.4550111,35.86996579170227,0.6108,1739141196.4550128,35.86996579170227,1.0473746155761778,1739141196.455015,35.86996579170227,0.0,1739141196.4550169,35.86996579170227,0.08111113045686558,1739141196.4550188,35.86996579170227,3.34724316754168,1739141196.4550204,35.86996579170227,0.9662634851193123 +1739141196.4747083,35.889965772628784,46.71966718938867,1739141196.4747112,35.889965772628784,8.532463363362382,1739141196.4747152,35.889965772628784,61.56109377996855,1739141196.4747186,35.889965772628784,43.431291085051704,1739141196.47472,35.889965772628784,5.624681873408659,1739141196.4747224,35.889965772628784,-2.4175417098497483,1739141196.4747238,35.889965772628784,2.1750101623960587,1739141196.4747257,35.889965772628784,0.6108,1739141196.4747272,35.889965772628784,1.0473746155761778,1739141196.4747293,35.889965772628784,0.0,1739141196.474731,35.889965772628784,0.08111113045686558,1739141196.474733,35.889965772628784,3.34724316754168,1739141196.4747345,35.889965772628784,0.9662634851193123 +1739141196.4946442,35.9099657535553,46.71966718938867,1739141196.4946473,35.9099657535553,8.532463363362382,1739141196.4946506,35.9099657535553,61.56109377996855,1739141196.4946542,35.9099657535553,43.431291085051704,1739141196.4946563,35.9099657535553,5.624681873408659,1739141196.4946582,35.9099657535553,-2.4175417098497483,1739141196.4946601,35.9099657535553,2.1750101623960587,1739141196.4946616,35.9099657535553,0.6108,1739141196.4946632,35.9099657535553,1.0473746155761778,1739141196.4946651,35.9099657535553,0.0,1739141196.494667,35.9099657535553,0.08111113045686558,1739141196.4946687,35.9099657535553,3.34724316754168,1739141196.4946704,35.9099657535553,0.9662634851193123 +1739141196.5150661,35.92996573448181,46.61545346643915,1739141196.5150697,35.92996573448181,8.509347894335995,1739141196.515074,35.92996573448181,61.562807430473796,1739141196.5150776,35.92996573448181,43.42265051035851,1739141196.5150797,35.92996573448181,5.5968932828019335,1739141196.515082,35.92996573448181,-2.4020814238165813,1739141196.5150838,35.92996573448181,2.09512757054367,1739141196.5150855,35.92996573448181,0.6108,1739141196.5150871,35.92996573448181,1.0813818387866634,1739141196.5150895,35.92996573448181,0.0,1739141196.5150912,35.92996573448181,0.12860527610474967,1739141196.515093,35.92996573448181,3.3749675107883172,1739141196.5150945,35.92996573448181,0.975392833812055 +1739141196.5346797,35.949965715408325,46.61545346643915,1739141196.534683,35.949965715408325,8.509347894335995,1739141196.5346866,35.949965715408325,61.562807430473796,1739141196.53469,35.949965715408325,43.42265051035851,1739141196.5346916,35.949965715408325,5.5968932828019335,1739141196.534694,35.949965715408325,-2.4020814238165813,1739141196.5346956,35.949965715408325,2.09512757054367,1739141196.5346973,35.949965715408325,0.6108,1739141196.534699,35.949965715408325,1.0813818387866634,1739141196.534701,35.949965715408325,0.0,1739141196.5347028,35.949965715408325,0.10598900497460839,1739141196.5347044,35.949965715408325,3.3749675107883172,1739141196.534706,35.949965715408325,0.975392833812055 +1739141196.5557008,35.96996569633484,46.61545346643915,1739141196.5557075,35.96996569633484,8.509347894335995,1739141196.555716,35.96996569633484,61.562807430473796,1739141196.5557241,35.96996569633484,43.42265051035851,1739141196.5557284,35.96996569633484,5.5968932828019335,1739141196.555733,35.96996569633484,-2.4020814238165813,1739141196.5557365,35.96996569633484,2.09512757054367,1739141196.5557392,35.96996569633484,0.6108,1739141196.5557423,35.96996569633484,1.0813818387866634,1739141196.5557466,35.96996569633484,0.0,1739141196.5557516,35.96996569633484,0.10598900497460839,1739141196.5557566,35.96996569633484,3.3749675107883172,1739141196.5557604,35.96996569633484,0.975392833812055 +1739141196.5756447,35.98996567726135,46.61545346643915,1739141196.5756493,35.98996567726135,8.509347894335995,1739141196.575655,35.98996567726135,61.562807430473796,1739141196.5756605,35.98996567726135,43.42265051035851,1739141196.5756633,35.98996567726135,5.5968932828019335,1739141196.5756667,35.98996567726135,-2.4020814238165813,1739141196.5756695,35.98996567726135,2.09512757054367,1739141196.5756721,35.98996567726135,0.6108,1739141196.5756745,35.98996567726135,1.0813818387866634,1739141196.5756772,35.98996567726135,0.0,1739141196.57568,35.98996567726135,0.10598900497460839,1739141196.5756834,35.98996567726135,3.3749675107883172,1739141196.5756865,35.98996567726135,0.975392833812055 +1739141196.5950634,36.009965658187866,46.61545346643915,1739141196.5950668,36.009965658187866,8.509347894335995,1739141196.5950704,36.009965658187866,61.562807430473796,1739141196.595074,36.009965658187866,43.42265051035851,1739141196.5950758,36.009965658187866,5.5968932828019335,1739141196.595078,36.009965658187866,-2.4020814238165813,1739141196.5950794,36.009965658187866,2.09512757054367,1739141196.5950813,36.009965658187866,0.6108,1739141196.595083,36.009965658187866,1.0813818387866634,1739141196.5950851,36.009965658187866,0.0,1739141196.5950868,36.009965658187866,0.10598900497460839,1739141196.5950887,36.009965658187866,3.3749675107883172,1739141196.5950902,36.009965658187866,0.975392833812055 +1739141196.6149747,36.02996563911438,46.61545346643915,1739141196.6149783,36.02996563911438,8.509347894335995,1739141196.6149817,36.02996563911438,61.562807430473796,1739141196.614985,36.02996563911438,43.42265051035851,1739141196.614987,36.02996563911438,5.5968932828019335,1739141196.614989,36.02996563911438,-2.4020814238165813,1739141196.614991,36.02996563911438,2.09512757054367,1739141196.6149926,36.02996563911438,0.6108,1739141196.6149943,36.02996563911438,1.0813818387866634,1739141196.6149962,36.02996563911438,0.0,1739141196.614998,36.02996563911438,0.10598900497460839,1739141196.6149995,36.02996563911438,3.3749675107883172,1739141196.6150014,36.02996563911438,0.975392833812055 +1739141196.6347406,36.049965620040894,46.5107880762992,1739141196.6347437,36.049965620040894,8.483067414180889,1739141196.6347475,36.049965620040894,61.95846653653109,1739141196.634751,36.049965620040894,43.315599195135626,1739141196.634753,36.049965620040894,5.178673022580352,1739141196.6347551,36.049965620040894,-2.339394146049383,1739141196.6347568,36.049965620040894,2.3675833954582375,1739141196.6347587,36.049965620040894,0.6108,1739141196.6347606,36.049965620040894,0.9697251226948428,1739141196.6347628,36.049965620040894,0.0,1739141196.6347644,36.049965620040894,-0.13021217463279017,1739141196.6347663,36.049965620040894,3.4026918540349547,1739141196.6347678,36.049965620040894,0.9874604889465538 +1739141196.6548874,36.06996560096741,46.5107880762992,1739141196.6548915,36.06996560096741,8.483067414180889,1739141196.6548965,36.06996560096741,61.95846653653109,1739141196.6549,36.06996560096741,43.315599195135626,1739141196.654902,36.06996560096741,5.178673022580352,1739141196.6549041,36.06996560096741,-2.339394146049383,1739141196.654906,36.06996560096741,2.3675833954582375,1739141196.654908,36.06996560096741,0.6108,1739141196.6549094,36.06996560096741,0.9697251226948428,1739141196.6549118,36.06996560096741,0.0,1739141196.654914,36.06996560096741,-0.017735366251711016,1739141196.6549156,36.06996560096741,3.4026918540349547,1739141196.654917,36.06996560096741,0.9874604889465538 +1739141196.67467,36.08996558189392,46.5107880762992,1739141196.674673,36.08996558189392,8.483067414180889,1739141196.6746771,36.08996558189392,61.95846653653109,1739141196.6746805,36.08996558189392,43.315599195135626,1739141196.6746824,36.08996558189392,5.178673022580352,1739141196.6746848,36.08996558189392,-2.339394146049383,1739141196.6746867,36.08996558189392,2.3675833954582375,1739141196.6746883,36.08996558189392,0.6108,1739141196.6746898,36.08996558189392,0.9697251226948428,1739141196.674692,36.08996558189392,0.0,1739141196.6746936,36.08996558189392,-0.017735366251711016,1739141196.6746953,36.08996558189392,3.4026918540349547,1739141196.674697,36.08996558189392,0.9874604889465538 +1739141196.694674,36.109965562820435,46.5107880762992,1739141196.6946769,36.109965562820435,8.483067414180889,1739141196.6946807,36.109965562820435,61.95846653653109,1739141196.6946845,36.109965562820435,43.315599195135626,1739141196.6946862,36.109965562820435,5.178673022580352,1739141196.6946886,36.109965562820435,-2.339394146049383,1739141196.69469,36.109965562820435,2.3675833954582375,1739141196.694692,36.109965562820435,0.6108,1739141196.6946933,36.109965562820435,0.9697251226948428,1739141196.6946952,36.109965562820435,0.0,1739141196.694697,36.109965562820435,-0.017735366251711016,1739141196.6946988,36.109965562820435,3.4026918540349547,1739141196.6947002,36.109965562820435,0.9874604889465538 +1739141196.71495,36.12996554374695,46.5107880762992,1739141196.714955,36.12996554374695,8.483067414180889,1739141196.7149591,36.12996554374695,61.95846653653109,1739141196.714963,36.12996554374695,43.315599195135626,1739141196.7149646,36.12996554374695,5.178673022580352,1739141196.7149673,36.12996554374695,-2.339394146049383,1739141196.7149692,36.12996554374695,2.3675833954582375,1739141196.7149708,36.12996554374695,0.6108,1739141196.7149725,36.12996554374695,0.9697251226948428,1739141196.7149746,36.12996554374695,0.0,1739141196.7149768,36.12996554374695,-0.017735366251711016,1739141196.7149785,36.12996554374695,3.4026918540349547,1739141196.7149801,36.12996554374695,0.9874604889465538 +1739141196.7347918,36.14996552467346,46.40637305543765,1739141196.7347949,36.14996552467346,8.453754185351885,1739141196.7347984,36.14996552467346,62.11557974367156,1739141196.734802,36.14996552467346,43.28672182293417,1739141196.7348037,36.14996552467346,5.033283660804283,1739141196.7348058,36.14996552467346,-2.310230908576355,1739141196.7348075,36.14996552467346,2.39023963241956,1739141196.7348094,36.14996552467346,0.6108,1739141196.7348108,36.14996552467346,0.9609766949929537,1739141196.734813,36.14996552467346,0.0,1739141196.7348151,36.14996552467346,-0.028785925332553888,1739141196.7348168,36.14996552467346,3.430416197281592,1739141196.7348182,36.14996552467346,0.9845004467059444 +1739141196.7548754,36.169965505599976,46.40637305543765,1739141196.7548795,36.169965505599976,8.453754185351885,1739141196.754884,36.169965505599976,62.11557974367156,1739141196.7548876,36.169965505599976,43.28672182293417,1739141196.7548895,36.169965505599976,5.033283660804283,1739141196.754892,36.169965505599976,-2.310230908576355,1739141196.754894,36.169965505599976,2.39023963241956,1739141196.754896,36.169965505599976,0.6108,1739141196.7548974,36.169965505599976,0.9609766949929537,1739141196.7548997,36.169965505599976,0.0,1739141196.7549016,36.169965505599976,-0.023523751712990704,1739141196.754904,36.169965505599976,3.430416197281592,1739141196.754906,36.169965505599976,0.9845004467059444 +1739141196.7747154,36.18996548652649,46.40637305543765,1739141196.7747185,36.18996548652649,8.453754185351885,1739141196.774722,36.18996548652649,62.11557974367156,1739141196.7747257,36.18996548652649,43.28672182293417,1739141196.7747273,36.18996548652649,5.033283660804283,1739141196.7747297,36.18996548652649,-2.310230908576355,1739141196.7747316,36.18996548652649,2.39023963241956,1739141196.7747333,36.18996548652649,0.6108,1739141196.7747347,36.18996548652649,0.9609766949929537,1739141196.7747371,36.18996548652649,0.0,1739141196.774739,36.18996548652649,-0.023523751712990704,1739141196.7747405,36.18996548652649,3.430416197281592,1739141196.7747421,36.18996548652649,0.9845004467059444 +1739141196.7946877,36.209965467453,46.40637305543765,1739141196.794691,36.209965467453,8.453754185351885,1739141196.7946947,36.209965467453,62.11557974367156,1739141196.794698,36.209965467453,43.28672182293417,1739141196.7946997,36.209965467453,5.033283660804283,1739141196.7947023,36.209965467453,-2.310230908576355,1739141196.794704,36.209965467453,2.39023963241956,1739141196.7947056,36.209965467453,0.6108,1739141196.7947073,36.209965467453,0.9609766949929537,1739141196.7947092,36.209965467453,0.0,1739141196.7947109,36.209965467453,-0.023523751712990704,1739141196.7947125,36.209965467453,3.430416197281592,1739141196.7947142,36.209965467453,0.9845004467059444 +1739141196.8149898,36.22996544837952,46.40637305543765,1739141196.8149943,36.22996544837952,8.453754185351885,1739141196.8149984,36.22996544837952,62.11557974367156,1739141196.815002,36.22996544837952,43.28672182293417,1739141196.8150036,36.22996544837952,5.033283660804283,1739141196.8150058,36.22996544837952,-2.310230908576355,1739141196.8150077,36.22996544837952,2.39023963241956,1739141196.8150094,36.22996544837952,0.6108,1739141196.8150108,36.22996544837952,0.9609766949929537,1739141196.815013,36.22996544837952,0.0,1739141196.8150148,36.22996544837952,-0.023523751712990704,1739141196.815017,36.22996544837952,3.430416197281592,1739141196.8150187,36.22996544837952,0.9845004467059444 +1739141196.834705,36.24996542930603,46.40637305543765,1739141196.8347082,36.24996542930603,8.453754185351885,1739141196.8347118,36.24996542930603,62.11557974367156,1739141196.8347154,36.24996542930603,43.28672182293417,1739141196.8347178,36.24996542930603,5.033283660804283,1739141196.8347197,36.24996542930603,-2.310230908576355,1739141196.8347216,36.24996542930603,2.39023963241956,1739141196.8347232,36.24996542930603,0.6108,1739141196.834725,36.24996542930603,0.9609766949929537,1739141196.834727,36.24996542930603,0.0,1739141196.834729,36.24996542930603,-0.023523751712990704,1739141196.8347304,36.24996542930603,3.430416197281592,1739141196.834732,36.24996542930603,0.9845004467059444 +1739141196.8552446,36.269965410232544,46.303096460379976,1739141196.8552485,36.269965410232544,8.421646309355221,1739141196.8552525,36.269965410232544,62.19793918823462,1739141196.855256,36.269965410232544,43.272538308845704,1739141196.8552585,36.269965410232544,4.960339874063601,1739141196.8552604,36.269965410232544,-2.2899395942966874,1739141196.8552625,36.269965410232544,2.3459579211194486,1739141196.8552642,36.269965410232544,0.6108,1739141196.855266,36.269965410232544,0.9781498140548683,1739141196.8552682,36.269965410232544,0.0,1739141196.8552701,36.269965410232544,0.014383719068455349,1739141196.8552716,36.269965410232544,3.4581405405282295,1739141196.8552735,36.269965410232544,0.9818172805663622 +1739141196.8746612,36.28996539115906,46.303096460379976,1739141196.8746638,36.28996539115906,8.421646309355221,1739141196.8746674,36.28996539115906,62.19793918823462,1739141196.8746707,36.28996539115906,43.272538308845704,1739141196.8746727,36.28996539115906,4.960339874063601,1739141196.8746748,36.28996539115906,-2.2899395942966874,1739141196.8746765,36.28996539115906,2.3459579211194486,1739141196.8746781,36.28996539115906,0.6108,1739141196.8746796,36.28996539115906,0.9781498140548683,1739141196.874682,36.28996539115906,0.0,1739141196.8746839,36.28996539115906,-0.0036674665114938554,1739141196.8746855,36.28996539115906,3.4581405405282295,1739141196.874687,36.28996539115906,0.9818172805663622 +1739141196.8947093,36.30996537208557,46.303096460379976,1739141196.894712,36.30996537208557,8.421646309355221,1739141196.8947155,36.30996537208557,62.19793918823462,1739141196.894719,36.30996537208557,43.272538308845704,1739141196.8947208,36.30996537208557,4.960339874063601,1739141196.8947227,36.30996537208557,-2.2899395942966874,1739141196.8947246,36.30996537208557,2.3459579211194486,1739141196.8947265,36.30996537208557,0.6108,1739141196.894728,36.30996537208557,0.9781498140548683,1739141196.89473,36.30996537208557,0.0,1739141196.894732,36.30996537208557,-0.0036674665114938554,1739141196.894734,36.30996537208557,3.4581405405282295,1739141196.8947353,36.30996537208557,0.9818172805663622 +1739141196.915265,36.329965353012085,46.303096460379976,1739141196.9152687,36.329965353012085,8.421646309355221,1739141196.9152725,36.329965353012085,62.19793918823462,1739141196.915276,36.329965353012085,43.272538308845704,1739141196.9152777,36.329965353012085,4.960339874063601,1739141196.9152796,36.329965353012085,-2.2899395942966874,1739141196.9152813,36.329965353012085,2.3459579211194486,1739141196.915283,36.329965353012085,0.6108,1739141196.9152846,36.329965353012085,0.9781498140548683,1739141196.9152868,36.329965353012085,0.0,1739141196.9152887,36.329965353012085,-0.0036674665114938554,1739141196.9152904,36.329965353012085,3.4581405405282295,1739141196.9152923,36.329965353012085,0.9818172805663622 +1739141196.9346988,36.3499653339386,46.303096460379976,1739141196.9347017,36.3499653339386,8.421646309355221,1739141196.9347055,36.3499653339386,62.19793918823462,1739141196.9347088,36.3499653339386,43.272538308845704,1739141196.9347105,36.3499653339386,4.960339874063601,1739141196.934713,36.3499653339386,-2.2899395942966874,1739141196.9347146,36.3499653339386,2.3459579211194486,1739141196.9347162,36.3499653339386,0.6108,1739141196.9347177,36.3499653339386,0.9781498140548683,1739141196.9347198,36.3499653339386,0.0,1739141196.9347215,36.3499653339386,-0.0036674665114938554,1739141196.9347231,36.3499653339386,3.4581405405282295,1739141196.9347248,36.3499653339386,0.9818172805663622 +1739141196.9550679,36.36996531486511,46.20090614176631,1739141196.9550717,36.36996531486511,8.386740656869378,1739141196.9550755,36.36996531486511,62.28167092672547,1739141196.955079,36.36996531486511,43.25718335402827,1739141196.955081,36.36996531486511,4.878756521690683,1739141196.955083,36.36996531486511,-2.2689572333398518,1739141196.955085,36.36996531486511,2.3085994145607143,1739141196.955087,36.36996531486511,0.6108,1739141196.9550884,36.36996531486511,0.9928764596054723,1739141196.9550905,36.36996531486511,0.0,1739141196.9550922,36.36996531486511,0.02490228484063419,1739141196.9550939,36.36996531486511,3.485864883774867,1739141196.9550953,36.36996531486511,0.9815788250619687 +1739141196.9749427,36.389965295791626,46.20090614176631,1739141196.9749463,36.389965295791626,8.386740656869378,1739141196.97495,36.389965295791626,62.28167092672547,1739141196.9749534,36.389965295791626,43.25718335402827,1739141196.9749553,36.389965295791626,4.878756521690683,1739141196.9749572,36.389965295791626,-2.2689572333398518,1739141196.9749594,36.389965295791626,2.3085994145607143,1739141196.974961,36.389965295791626,0.6108,1739141196.9749627,36.389965295791626,0.9928764596054723,1739141196.9749646,36.389965295791626,0.0,1739141196.9749665,36.389965295791626,0.011297634543503632,1739141196.9749684,36.389965295791626,3.485864883774867,1739141196.9749699,36.389965295791626,0.9815788250619687 +1739141196.9946773,36.40996527671814,46.20090614176631,1739141196.9946804,36.40996527671814,8.386740656869378,1739141196.9946842,36.40996527671814,62.28167092672547,1739141196.9946878,36.40996527671814,43.25718335402827,1739141196.9946895,36.40996527671814,4.878756521690683,1739141196.9946918,36.40996527671814,-2.2689572333398518,1739141196.9946935,36.40996527671814,2.3085994145607143,1739141196.9946952,36.40996527671814,0.6108,1739141196.9946966,36.40996527671814,0.9928764596054723,1739141196.9946988,36.40996527671814,0.0,1739141196.9947004,36.40996527671814,0.011297634543503632,1739141196.9947023,36.40996527671814,3.485864883774867,1739141196.9947042,36.40996527671814,0.9815788250619687 +1739141197.015005,36.42996525764465,46.20090614176631,1739141197.0150087,36.42996525764465,8.386740656869378,1739141197.0150132,36.42996525764465,62.28167092672547,1739141197.0150168,36.42996525764465,43.25718335402827,1739141197.0150185,36.42996525764465,4.878756521690683,1739141197.0150208,36.42996525764465,-2.2689572333398518,1739141197.0150225,36.42996525764465,2.3085994145607143,1739141197.0150244,36.42996525764465,0.6108,1739141197.015026,36.42996525764465,0.9928764596054723,1739141197.0150282,36.42996525764465,0.0,1739141197.0150304,36.42996525764465,0.011297634543503632,1739141197.0150318,36.42996525764465,3.485864883774867,1739141197.015034,36.42996525764465,0.9815788250619687 +1739141197.0347495,36.44996523857117,46.20090614176631,1739141197.0347526,36.44996523857117,8.386740656869378,1739141197.0347564,36.44996523857117,62.28167092672547,1739141197.03476,36.44996523857117,43.25718335402827,1739141197.0347617,36.44996523857117,4.878756521690683,1739141197.0347638,36.44996523857117,-2.2689572333398518,1739141197.0347655,36.44996523857117,2.3085994145607143,1739141197.0347674,36.44996523857117,0.6108,1739141197.0347688,36.44996523857117,0.9928764596054723,1739141197.034771,36.44996523857117,0.0,1739141197.0347729,36.44996523857117,0.011297634543503632,1739141197.0347748,36.44996523857117,3.485864883774867,1739141197.0347762,36.44996523857117,0.9815788250619687 +1739141197.0549328,36.46996521949768,46.20090614176631,1739141197.054937,36.46996521949768,8.386740656869378,1739141197.0549412,36.46996521949768,62.28167092672547,1739141197.054945,36.46996521949768,43.25718335402827,1739141197.0549471,36.46996521949768,4.878756521690683,1739141197.0549493,36.46996521949768,-2.2689572333398518,1739141197.0549514,36.46996521949768,2.3085994145607143,1739141197.0549529,36.46996521949768,0.6108,1739141197.0549548,36.46996521949768,0.9928764596054723,1739141197.0549574,36.46996521949768,0.0,1739141197.054959,36.46996521949768,0.011297634543503632,1739141197.0549612,36.46996521949768,3.485864883774867,1739141197.0549629,36.46996521949768,0.9815788250619687 +1739141197.0747416,36.489965200424194,46.09965661889847,1739141197.0747445,36.489965200424194,8.348990565009663,1739141197.0747485,36.489965200424194,62.38636883434069,1739141197.0747519,36.489965200424194,43.23721180673451,1739141197.0747533,36.489965200424194,4.771375006063179,1739141197.0747554,36.489965200424194,-2.2455973219742313,1739141197.074757,36.489965200424194,2.2924886851340407,1739141197.074759,36.489965200424194,0.6108,1739141197.0747604,36.489965200424194,0.9992955060929822,1739141197.0747623,36.489965200424194,0.0,1739141197.0747643,36.489965200424194,0.020671899060553424,1739141197.074766,36.489965200424194,3.5135892270215043,1739141197.0747674,36.489965200424194,0.9830875447466701 +1739141197.0949688,36.50996518135071,46.09965661889847,1739141197.0949726,36.50996518135071,8.348990565009663,1739141197.0949764,36.50996518135071,62.38636883434069,1739141197.09498,36.50996518135071,43.23721180673451,1739141197.094982,36.50996518135071,4.771375006063179,1739141197.094984,36.50996518135071,-2.2455973219742313,1739141197.0949857,36.50996518135071,2.2924886851340407,1739141197.0949876,36.50996518135071,0.6108,1739141197.094989,36.50996518135071,0.9992955060929822,1739141197.0949912,36.50996518135071,0.0,1739141197.094993,36.50996518135071,0.016207961346312083,1739141197.0949948,36.50996518135071,3.5135892270215043,1739141197.0949962,36.50996518135071,0.9830875447466701 +1739141197.1150105,36.52996516227722,46.09965661889847,1739141197.1150146,36.52996516227722,8.348990565009663,1739141197.115019,36.52996516227722,62.38636883434069,1739141197.1150231,36.52996516227722,43.23721180673451,1739141197.1150248,36.52996516227722,4.771375006063179,1739141197.115027,36.52996516227722,-2.2455973219742313,1739141197.1150286,36.52996516227722,2.2924886851340407,1739141197.1150305,36.52996516227722,0.6108,1739141197.1150324,36.52996516227722,0.9992955060929822,1739141197.1150343,36.52996516227722,0.0,1739141197.1150365,36.52996516227722,0.016207961346312083,1739141197.115038,36.52996516227722,3.5135892270215043,1739141197.1150398,36.52996516227722,0.9830875447466701 +1739141197.1347246,36.549965143203735,46.09965661889847,1739141197.134728,36.549965143203735,8.348990565009663,1739141197.1347313,36.549965143203735,62.38636883434069,1739141197.1347346,36.549965143203735,43.23721180673451,1739141197.134737,36.549965143203735,4.771375006063179,1739141197.134739,36.549965143203735,-2.2455973219742313,1739141197.1347406,36.549965143203735,2.2924886851340407,1739141197.1347423,36.549965143203735,0.6108,1739141197.1347437,36.549965143203735,0.9992955060929822,1739141197.1347458,36.549965143203735,0.0,1739141197.1347477,36.549965143203735,0.016207961346312083,1739141197.1347492,36.549965143203735,3.5135892270215043,1739141197.134751,36.549965143203735,0.9830875447466701 +1739141197.1549087,36.56996512413025,46.09965661889847,1739141197.154913,36.56996512413025,8.348990565009663,1739141197.154917,36.56996512413025,62.38636883434069,1739141197.154921,36.56996512413025,43.23721180673451,1739141197.154923,36.56996512413025,4.771375006063179,1739141197.154925,36.56996512413025,-2.2455973219742313,1739141197.1549268,36.56996512413025,2.2924886851340407,1739141197.1549292,36.56996512413025,0.6108,1739141197.1549306,36.56996512413025,0.9992955060929822,1739141197.1549327,36.56996512413025,0.0,1739141197.1549346,36.56996512413025,0.016207961346312083,1739141197.1549366,36.56996512413025,3.5135892270215043,1739141197.1549382,36.56996512413025,0.9830875447466701 +1739141197.1750286,36.58996510505676,45.999335203599635,1739141197.175032,36.58996510505676,8.308384496068246,1739141197.1750357,36.58996510505676,62.55849150113239,1739141197.175039,36.58996510505676,43.20502091047587,1739141197.1750412,36.58996510505676,4.596754589407749,1739141197.1750433,36.58996510505676,-2.216121300670052,1739141197.175045,36.58996510505676,2.3316018672644456,1739141197.1750467,36.58996510505676,0.6108,1739141197.1750484,36.58996510505676,0.9837829209761781,1739141197.1750507,36.58996510505676,0.0,1739141197.1750526,36.58996510505676,-0.016873179160613483,1739141197.1750543,36.58996510505676,3.5413135702681418,1739141197.175056,36.58996510505676,0.984903168216597 +1739141197.1949606,36.609965085983276,45.999335203599635,1739141197.1949642,36.609965085983276,8.308384496068246,1739141197.1949677,36.609965085983276,62.55849150113239,1739141197.1949713,36.609965085983276,43.20502091047587,1739141197.194973,36.609965085983276,4.596754589407749,1739141197.194975,36.609965085983276,-2.216121300670052,1739141197.1949768,36.609965085983276,2.3316018672644456,1739141197.1949782,36.609965085983276,0.6108,1739141197.19498,36.609965085983276,0.9837829209761781,1739141197.1949818,36.609965085983276,0.0,1739141197.1949837,36.609965085983276,-0.0011202472404188146,1739141197.1949852,36.609965085983276,3.5413135702681418,1739141197.1949868,36.609965085983276,0.984903168216597 +1739141197.215117,36.62996506690979,45.999335203599635,1739141197.2151208,36.62996506690979,8.308384496068246,1739141197.2151256,36.62996506690979,62.55849150113239,1739141197.2151296,36.62996506690979,43.20502091047587,1739141197.2151318,36.62996506690979,4.596754589407749,1739141197.2151341,36.62996506690979,-2.216121300670052,1739141197.215136,36.62996506690979,2.3316018672644456,1739141197.2151375,36.62996506690979,0.6108,1739141197.2151392,36.62996506690979,0.9837829209761781,1739141197.215141,36.62996506690979,0.0,1739141197.2151432,36.62996506690979,-0.0011202472404188146,1739141197.2151449,36.62996506690979,3.5413135702681418,1739141197.2151473,36.62996506690979,0.984903168216597 +1739141197.2348497,36.649965047836304,45.999335203599635,1739141197.2348528,36.649965047836304,8.308384496068246,1739141197.2348561,36.649965047836304,62.55849150113239,1739141197.2348597,36.649965047836304,43.20502091047587,1739141197.2348616,36.649965047836304,4.596754589407749,1739141197.2348635,36.649965047836304,-2.216121300670052,1739141197.2348654,36.649965047836304,2.3316018672644456,1739141197.234867,36.649965047836304,0.6108,1739141197.2348688,36.649965047836304,0.9837829209761781,1739141197.2348707,36.649965047836304,0.0,1739141197.2348726,36.649965047836304,-0.0011202472404188146,1739141197.234874,36.649965047836304,3.5413135702681418,1739141197.2348757,36.649965047836304,0.984903168216597 +1739141197.255116,36.66996502876282,45.999335203599635,1739141197.2551193,36.66996502876282,8.308384496068246,1739141197.2551231,36.66996502876282,62.55849150113239,1739141197.2551267,36.66996502876282,43.20502091047587,1739141197.2551289,36.66996502876282,4.596754589407749,1739141197.2551312,36.66996502876282,-2.216121300670052,1739141197.255133,36.66996502876282,2.3316018672644456,1739141197.2551346,36.66996502876282,0.6108,1739141197.2551363,36.66996502876282,0.9837829209761781,1739141197.2551384,36.66996502876282,0.0,1739141197.25514,36.66996502876282,-0.0011202472404188146,1739141197.255142,36.66996502876282,3.5413135702681418,1739141197.2551436,36.66996502876282,0.984903168216597 +1739141197.2748923,36.68996500968933,45.999335203599635,1739141197.2748954,36.68996500968933,8.308384496068246,1739141197.274899,36.68996500968933,62.55849150113239,1739141197.2749023,36.68996500968933,43.20502091047587,1739141197.2749043,36.68996500968933,4.596754589407749,1739141197.2749064,36.68996500968933,-2.216121300670052,1739141197.274908,36.68996500968933,2.3316018672644456,1739141197.2749097,36.68996500968933,0.6108,1739141197.2749112,36.68996500968933,0.9837829209761781,1739141197.2749133,36.68996500968933,0.0,1739141197.274915,36.68996500968933,-0.0011202472404188146,1739141197.274917,36.68996500968933,3.5413135702681418,1739141197.2749183,36.68996500968933,0.984903168216597 +1739141197.2951906,36.709964990615845,45.900111604691666,1739141197.2951941,36.709964990615845,8.26498461486635,1739141197.2951982,36.709964990615845,62.573052021219475,1739141197.2952015,36.709964990615845,43.2026417340029,1739141197.2952032,36.709964990615845,4.583716702335886,1739141197.2952056,36.709964990615845,-2.203169398693396,1739141197.2952075,36.709964990615845,2.231827281781119,1739141197.295209,36.709964990615845,0.6108,1739141197.2952106,36.709964990615845,1.0238395441381,1739141197.2952125,36.709964990615845,0.0,1739141197.2952144,36.709964990615845,0.07618346188606645,1739141197.2952158,36.709964990615845,3.569037913514779,1739141197.2952178,36.709964990615845,0.9844673907011215 +1739141197.3151624,36.72996497154236,45.900111604691666,1739141197.3151665,36.72996497154236,8.26498461486635,1739141197.3151703,36.72996497154236,62.573052021219475,1739141197.315174,36.72996497154236,43.2026417340029,1739141197.315176,36.72996497154236,4.583716702335886,1739141197.315178,36.72996497154236,-2.203169398693396,1739141197.3151803,36.72996497154236,2.231827281781119,1739141197.3151817,36.72996497154236,0.6108,1739141197.3151834,36.72996497154236,1.0238395441381,1739141197.3151853,36.72996497154236,0.0,1739141197.3151872,36.72996497154236,0.03937215343697853,1739141197.3151886,36.72996497154236,3.569037913514779,1739141197.3151906,36.72996497154236,0.9844673907011215 +1739141197.3348126,36.74996495246887,45.900111604691666,1739141197.3348157,36.74996495246887,8.26498461486635,1739141197.3348193,36.74996495246887,62.573052021219475,1739141197.3348227,36.74996495246887,43.2026417340029,1739141197.3348248,36.74996495246887,4.583716702335886,1739141197.334827,36.74996495246887,-2.203169398693396,1739141197.3348289,36.74996495246887,2.231827281781119,1739141197.3348305,36.74996495246887,0.6108,1739141197.3348322,36.74996495246887,1.0238395441381,1739141197.3348343,36.74996495246887,0.0,1739141197.3348365,36.74996495246887,0.03937215343697853,1739141197.334838,36.74996495246887,3.569037913514779,1739141197.3348398,36.74996495246887,0.9844673907011215 +1739141197.3552911,36.769964933395386,45.900111604691666,1739141197.3552942,36.769964933395386,8.26498461486635,1739141197.355298,36.769964933395386,62.573052021219475,1739141197.3553016,36.769964933395386,43.2026417340029,1739141197.3553035,36.769964933395386,4.583716702335886,1739141197.3553057,36.769964933395386,-2.203169398693396,1739141197.3553076,36.769964933395386,2.231827281781119,1739141197.355309,36.769964933395386,0.6108,1739141197.355311,36.769964933395386,1.0238395441381,1739141197.3553128,36.769964933395386,0.0,1739141197.3553147,36.769964933395386,0.03937215343697853,1739141197.3553164,36.769964933395386,3.569037913514779,1739141197.355318,36.769964933395386,0.9844673907011215 +1739141197.3747888,36.7899649143219,45.900111604691666,1739141197.3747919,36.7899649143219,8.26498461486635,1739141197.3747954,36.7899649143219,62.573052021219475,1739141197.3747988,36.7899649143219,43.2026417340029,1739141197.3748004,36.7899649143219,4.583716702335886,1739141197.3748024,36.7899649143219,-2.203169398693396,1739141197.3748043,36.7899649143219,2.231827281781119,1739141197.374806,36.7899649143219,0.6108,1739141197.3748076,36.7899649143219,1.0238395441381,1739141197.3748095,36.7899649143219,0.0,1739141197.3748114,36.7899649143219,0.03937215343697853,1739141197.374813,36.7899649143219,3.569037913514779,1739141197.3748147,36.7899649143219,0.9844673907011215 +1739141197.3948627,36.80996489524841,45.80192510655846,1739141197.3948658,36.80996489524841,8.218753296502193,1739141197.3948693,36.80996489524841,62.77738171345827,1739141197.3948727,36.80996489524841,43.16310683201816,1739141197.3948743,36.80996489524841,4.36906086809532,1739141197.3948765,36.80996489524841,-2.1716985332406455,1739141197.3948781,36.80996489524841,2.2976785089885055,1739141197.3948798,36.80996489524841,0.6108,1739141197.3948815,36.80996489524841,0.9972231907654316,1739141197.3948834,36.80996489524841,0.0,1739141197.394885,36.80996489524841,-0.020310428331771498,1739141197.3948867,36.80996489524841,3.5967622567614166,1739141197.3948884,36.80996489524841,0.9891133278672879 +1739141197.415136,36.82996487617493,45.80192510655846,1739141197.41514,36.82996487617493,8.218753296502193,1739141197.4151444,36.82996487617493,62.77738171345827,1739141197.4151483,36.82996487617493,43.16310683201816,1739141197.4151504,36.82996487617493,4.36906086809532,1739141197.4151525,36.82996487617493,-2.1716985332406455,1739141197.4151545,36.82996487617493,2.2976785089885055,1739141197.4151561,36.82996487617493,0.6108,1739141197.4151578,36.82996487617493,0.9972231907654316,1739141197.4151602,36.82996487617493,0.0,1739141197.4151618,36.82996487617493,0.00810986289814375,1739141197.4151638,36.82996487617493,3.5967622567614166,1739141197.4151654,36.82996487617493,0.9891133278672879 +1739141197.4348457,36.84996485710144,45.80192510655846,1739141197.4348488,36.84996485710144,8.218753296502193,1739141197.4348528,36.84996485710144,62.77738171345827,1739141197.4348562,36.84996485710144,43.16310683201816,1739141197.4348583,36.84996485710144,4.36906086809532,1739141197.4348602,36.84996485710144,-2.1716985332406455,1739141197.434862,36.84996485710144,2.2976785089885055,1739141197.4348636,36.84996485710144,0.6108,1739141197.4348655,36.84996485710144,0.9972231907654316,1739141197.4348676,36.84996485710144,0.0,1739141197.4348698,36.84996485710144,0.00810986289814375,1739141197.4348712,36.84996485710144,3.5967622567614166,1739141197.434873,36.84996485710144,0.9891133278672879 +1739141197.4551787,36.869964838027954,45.80192510655846,1739141197.4551828,36.869964838027954,8.218753296502193,1739141197.4551868,36.869964838027954,62.77738171345827,1739141197.455191,36.869964838027954,43.16310683201816,1739141197.4551926,36.869964838027954,4.36906086809532,1739141197.455195,36.869964838027954,-2.1716985332406455,1739141197.4551966,36.869964838027954,2.2976785089885055,1739141197.4551985,36.869964838027954,0.6108,1739141197.4552,36.869964838027954,0.9972231907654316,1739141197.4552023,36.869964838027954,0.0,1739141197.4552042,36.869964838027954,0.00810986289814375,1739141197.455206,36.869964838027954,3.5967622567614166,1739141197.4552076,36.869964838027954,0.9891133278672879 +1739141197.4749644,36.88996481895447,45.80192510655846,1739141197.4749675,36.88996481895447,8.218753296502193,1739141197.474971,36.88996481895447,62.77738171345827,1739141197.4749746,36.88996481895447,43.16310683201816,1739141197.4749765,36.88996481895447,4.36906086809532,1739141197.474979,36.88996481895447,-2.1716985332406455,1739141197.4749804,36.88996481895447,2.2976785089885055,1739141197.4749823,36.88996481895447,0.6108,1739141197.4749837,36.88996481895447,0.9972231907654316,1739141197.4749858,36.88996481895447,0.0,1739141197.4749875,36.88996481895447,0.00810986289814375,1739141197.4749894,36.88996481895447,3.5967622567614166,1739141197.474991,36.88996481895447,0.9891133278672879 +1739141197.4949903,36.90996479988098,45.80192510655846,1739141197.4949934,36.90996479988098,8.218753296502193,1739141197.494997,36.90996479988098,62.77738171345827,1739141197.4950006,36.90996479988098,43.16310683201816,1739141197.495002,36.90996479988098,4.36906086809532,1739141197.4950044,36.90996479988098,-2.1716985332406455,1739141197.4950063,36.90996479988098,2.2976785089885055,1739141197.4950078,36.90996479988098,0.6108,1739141197.4950092,36.90996479988098,0.9972231907654316,1739141197.4950113,36.90996479988098,0.0,1739141197.4950132,36.90996479988098,0.00810986289814375,1739141197.4950147,36.90996479988098,3.5967622567614166,1739141197.4950163,36.90996479988098,0.9891133278672879 +1739141197.5151715,36.929964780807495,45.70482217929864,1739141197.5151753,36.929964780807495,8.169700094108142,1739141197.5151799,36.929964780807495,62.8637774130152,1739141197.5151837,36.929964780807495,43.146973991585114,1739141197.5151854,36.929964780807495,4.283194621787263,1739141197.5151875,36.929964780807495,-2.15286963352236,1739141197.5151892,36.929964780807495,2.254380553406306,1739141197.515191,36.929964780807495,0.6108,1739141197.5151927,36.929964780807495,1.0146447086858759,1739141197.515195,36.929964780807495,0.0,1739141197.515197,36.929964780807495,0.0407499639082223,1739141197.5151985,36.929964780807495,3.624486600008054,1739141197.5152001,36.929964780807495,0.9894376577849122 +1739141197.5347962,36.94996476173401,45.70482217929864,1739141197.5347993,36.94996476173401,8.169700094108142,1739141197.5348032,36.94996476173401,62.8637774130152,1739141197.5348065,36.94996476173401,43.146973991585114,1739141197.5348084,36.94996476173401,4.283194621787263,1739141197.5348103,36.94996476173401,-2.15286963352236,1739141197.534812,36.94996476173401,2.254380553406306,1739141197.5348136,36.94996476173401,0.6108,1739141197.5348153,36.94996476173401,1.0146447086858759,1739141197.5348172,36.94996476173401,0.0,1739141197.5348191,36.94996476173401,0.025207050900963646,1739141197.5348206,36.94996476173401,3.624486600008054,1739141197.5348225,36.94996476173401,0.9894376577849122 +1739141197.5551422,36.96996474266052,45.70482217929864,1739141197.555146,36.96996474266052,8.169700094108142,1739141197.5551498,36.96996474266052,62.8637774130152,1739141197.5551536,36.96996474266052,43.146973991585114,1739141197.5551558,36.96996474266052,4.283194621787263,1739141197.555158,36.96996474266052,-2.15286963352236,1739141197.5551598,36.96996474266052,2.254380553406306,1739141197.5551612,36.96996474266052,0.6108,1739141197.5551631,36.96996474266052,1.0146447086858759,1739141197.5551653,36.96996474266052,0.0,1739141197.555167,36.96996474266052,0.025207050900963646,1739141197.5551686,36.96996474266052,3.624486600008054,1739141197.5551703,36.96996474266052,0.9894376577849122 +1739141197.5749226,36.989964723587036,45.70482217929864,1739141197.574926,36.989964723587036,8.169700094108142,1739141197.5749297,36.989964723587036,62.8637774130152,1739141197.5749333,36.989964723587036,43.146973991585114,1739141197.574935,36.989964723587036,4.283194621787263,1739141197.574937,36.989964723587036,-2.15286963352236,1739141197.5749388,36.989964723587036,2.254380553406306,1739141197.5749407,36.989964723587036,0.6108,1739141197.574942,36.989964723587036,1.0146447086858759,1739141197.5749443,36.989964723587036,0.0,1739141197.5749462,36.989964723587036,0.025207050900963646,1739141197.5749478,36.989964723587036,3.624486600008054,1739141197.5749493,36.989964723587036,0.9894376577849122 +1739141197.5949402,37.00996470451355,45.70482217929864,1739141197.5949433,37.00996470451355,8.169700094108142,1739141197.5949469,37.00996470451355,62.8637774130152,1739141197.5949504,37.00996470451355,43.146973991585114,1739141197.594952,37.00996470451355,4.283194621787263,1739141197.5949543,37.00996470451355,-2.15286963352236,1739141197.594956,37.00996470451355,2.254380553406306,1739141197.5949578,37.00996470451355,0.6108,1739141197.5949593,37.00996470451355,1.0146447086858759,1739141197.5949614,37.00996470451355,0.0,1739141197.5949633,37.00996470451355,0.025207050900963646,1739141197.5949647,37.00996470451355,3.624486600008054,1739141197.5949664,37.00996470451355,0.9894376577849122 +1739141197.616373,37.02996468544006,45.60894719582471,1739141197.6163769,37.02996468544006,8.117881824957642,1739141197.6163807,37.02996468544006,62.95189534507151,1739141197.6163843,37.02996468544006,43.12841556534343,1739141197.616386,37.02996468544006,4.188166299551124,1739141197.616388,37.02996468544006,-2.133858972678272,1739141197.6163902,37.02996468544006,2.2161734728687232,1739141197.616392,37.02996468544006,0.6108,1739141197.6163938,37.02996468544006,1.0302704522004476,1739141197.6163957,37.02996468544006,0.0,1739141197.6163976,37.02996468544006,0.049497597815373065,1739141197.6163995,37.02996468544006,3.6522109432546914,1739141197.6164014,37.02996468544006,0.9923397872653625 +1739141197.6350605,37.04996466636658,45.60894719582471,1739141197.6350636,37.04996466636658,8.117881824957642,1739141197.6350675,37.04996466636658,62.95189534507151,1739141197.6350713,37.04996466636658,43.12841556534343,1739141197.635073,37.04996466636658,4.188166299551124,1739141197.635075,37.04996466636658,-2.133858972678272,1739141197.6350772,37.04996466636658,2.2161734728687232,1739141197.635079,37.04996466636658,0.6108,1739141197.6350803,37.04996466636658,1.0302704522004476,1739141197.6350825,37.04996466636658,0.0,1739141197.6350844,37.04996466636658,0.03793066493508501,1739141197.6350858,37.04996466636658,3.6522109432546914,1739141197.6350877,37.04996466636658,0.9923397872653625 +1739141197.6551502,37.06996464729309,45.60894719582471,1739141197.6551585,37.06996464729309,8.117881824957642,1739141197.655182,37.06996464729309,62.95189534507151,1739141197.6551888,37.06996464729309,43.12841556534343,1739141197.6552033,37.06996464729309,4.188166299551124,1739141197.655216,37.06996464729309,-2.133858972678272,1739141197.6552198,37.06996464729309,2.2161734728687232,1739141197.655224,37.06996464729309,0.6108,1739141197.6552274,37.06996464729309,1.0302704522004476,1739141197.6552315,37.06996464729309,0.0,1739141197.6552353,37.06996464729309,0.03793066493508501,1739141197.6552384,37.06996464729309,3.6522109432546914,1739141197.6552413,37.06996464729309,0.9923397872653625 +1739141197.6751409,37.089964628219604,45.60894719582471,1739141197.675144,37.089964628219604,8.117881824957642,1739141197.6751475,37.089964628219604,62.95189534507151,1739141197.675151,37.089964628219604,43.12841556534343,1739141197.6751528,37.089964628219604,4.188166299551124,1739141197.6751554,37.089964628219604,-2.133858972678272,1739141197.675157,37.089964628219604,2.2161734728687232,1739141197.6751587,37.089964628219604,0.6108,1739141197.6751604,37.089964628219604,1.0302704522004476,1739141197.6751623,37.089964628219604,0.0,1739141197.6751642,37.089964628219604,0.03793066493508501,1739141197.675166,37.089964628219604,3.6522109432546914,1739141197.6751676,37.089964628219604,0.9923397872653625 +1739141197.6949685,37.10996460914612,45.60894719582471,1739141197.6949718,37.10996460914612,8.117881824957642,1739141197.6949759,37.10996460914612,62.95189534507151,1739141197.6949794,37.10996460914612,43.12841556534343,1739141197.6949809,37.10996460914612,4.188166299551124,1739141197.6949832,37.10996460914612,-2.133858972678272,1739141197.694985,37.10996460914612,2.2161734728687232,1739141197.6949866,37.10996460914612,0.6108,1739141197.694988,37.10996460914612,1.0302704522004476,1739141197.6949902,37.10996460914612,0.0,1739141197.6949918,37.10996460914612,0.03793066493508501,1739141197.6949937,37.10996460914612,3.6522109432546914,1739141197.6949952,37.10996460914612,0.9923397872653625 +1739141197.7154212,37.12996459007263,45.60894719582471,1739141197.715425,37.12996459007263,8.117881824957642,1739141197.715429,37.12996459007263,62.95189534507151,1739141197.7154326,37.12996459007263,43.12841556534343,1739141197.7154348,37.12996459007263,4.188166299551124,1739141197.7154367,37.12996459007263,-2.133858972678272,1739141197.7154386,37.12996459007263,2.2161734728687232,1739141197.7154403,37.12996459007263,0.6108,1739141197.715442,37.12996459007263,1.0302704522004476,1739141197.7154438,37.12996459007263,0.0,1739141197.715446,37.12996459007263,0.03793066493508501,1739141197.715448,37.12996459007263,3.6522109432546914,1739141197.7154496,37.12996459007263,0.9923397872653625 +1739141197.735058,37.149964570999146,45.5141977255293,1739141197.7350612,37.149964570999146,8.063224743879735,1739141197.7350647,37.149964570999146,63.120691356844596,1739141197.735068,37.149964570999146,43.09245700846207,1739141197.73507,37.149964570999146,4.00979937282299,1739141197.735072,37.149964570999146,-2.109342668058816,1739141197.7350738,37.149964570999146,2.2384475663577312,1739141197.7350755,37.149964570999146,0.6108,1739141197.7350771,37.149964570999146,1.0211318871551478,1739141197.735079,37.149964570999146,0.0,1739141197.735081,37.149964570999146,0.0121079096307403,1739141197.7350829,37.149964570999146,3.679935286501329,1739141197.7350843,37.149964570999146,0.9967274212368143 +1739141197.7552383,37.16996455192566,45.5141977255293,1739141197.7552419,37.16996455192566,8.063224743879735,1739141197.7552464,37.16996455192566,63.120691356844596,1739141197.75525,37.16996455192566,43.09245700846207,1739141197.7552521,37.16996455192566,4.00979937282299,1739141197.7552545,37.16996455192566,-2.109342668058816,1739141197.7552564,37.16996455192566,2.2384475663577312,1739141197.7552583,37.16996455192566,0.6108,1739141197.75526,37.16996455192566,1.0211318871551478,1739141197.7552621,37.16996455192566,0.0,1739141197.7552643,37.16996455192566,0.02440446591833345,1739141197.7552662,37.16996455192566,3.679935286501329,1739141197.755268,37.16996455192566,0.9967274212368143 +1739141197.7750874,37.18996453285217,45.5141977255293,1739141197.7750905,37.18996453285217,8.063224743879735,1739141197.7750943,37.18996453285217,63.120691356844596,1739141197.775098,37.18996453285217,43.09245700846207,1739141197.7750998,37.18996453285217,4.00979937282299,1739141197.7751017,37.18996453285217,-2.109342668058816,1739141197.7751036,37.18996453285217,2.2384475663577312,1739141197.7751055,37.18996453285217,0.6108,1739141197.7751074,37.18996453285217,1.0211318871551478,1739141197.7751093,37.18996453285217,0.0,1739141197.7751112,37.18996453285217,0.02440446591833345,1739141197.7751126,37.18996453285217,3.679935286501329,1739141197.7751145,37.18996453285217,0.9967274212368143 +1739141197.795089,37.20996451377869,45.5141977255293,1739141197.7950919,37.20996451377869,8.063224743879735,1739141197.7950954,37.20996451377869,63.120691356844596,1739141197.795099,37.20996451377869,43.09245700846207,1739141197.7951007,37.20996451377869,4.00979937282299,1739141197.7951028,37.20996451377869,-2.109342668058816,1739141197.7951045,37.20996451377869,2.2384475663577312,1739141197.7951064,37.20996451377869,0.6108,1739141197.7951078,37.20996451377869,1.0211318871551478,1739141197.7951097,37.20996451377869,0.0,1739141197.7951114,37.20996451377869,0.02440446591833345,1739141197.7951133,37.20996451377869,3.679935286501329,1739141197.7951148,37.20996451377869,0.9967274212368143 +1739141197.815186,37.2299644947052,45.5141977255293,1739141197.8151894,37.2299644947052,8.063224743879735,1739141197.8151934,37.2299644947052,63.120691356844596,1739141197.815197,37.2299644947052,43.09245700846207,1739141197.8151991,37.2299644947052,4.00979937282299,1739141197.8152013,37.2299644947052,-2.109342668058816,1739141197.8152032,37.2299644947052,2.2384475663577312,1739141197.8152046,37.2299644947052,0.6108,1739141197.8152063,37.2299644947052,1.0211318871551478,1739141197.8152084,37.2299644947052,0.0,1739141197.8152103,37.2299644947052,0.02440446591833345,1739141197.815212,37.2299644947052,3.679935286501329,1739141197.8152137,37.2299644947052,0.9967274212368143 +1739141197.8351285,37.249964475631714,45.42067680837816,1739141197.8351321,37.249964475631714,8.005764229074456,1739141197.835136,37.249964475631714,63.22662285107661,1739141197.83514,37.249964475631714,43.06873361516679,1739141197.8351421,37.249964475631714,3.8986865160653905,1739141197.8351452,37.249964475631714,-2.0908673354882317,1739141197.8351476,37.249964475631714,2.2050564345548,1739141197.8351493,37.249964475631714,0.6108,1739141197.8351512,37.249964475631714,1.034862076122294,1739141197.8351529,37.249964475631714,0.0,1739141197.8351552,37.249964475631714,0.045725711068221694,1739141197.8351574,37.249964475631714,3.7076596297479663,1739141197.8351595,37.249964475631714,0.999289344006828 +1739141197.8554554,37.26996445655823,45.42067680837816,1739141197.8554592,37.26996445655823,8.005764229074456,1739141197.8554637,37.26996445655823,63.22662285107661,1739141197.8554673,37.26996445655823,43.06873361516679,1739141197.8554692,37.26996445655823,3.8986865160653905,1739141197.8554716,37.26996445655823,-2.0908673354882317,1739141197.8554738,37.26996445655823,2.2050564345548,1739141197.8554754,37.26996445655823,0.6108,1739141197.8554773,37.26996445655823,1.034862076122294,1739141197.8554795,37.26996445655823,0.0,1739141197.8554816,37.26996445655823,0.035572732115465966,1739141197.8554833,37.26996445655823,3.7076596297479663,1739141197.8554852,37.26996445655823,0.999289344006828 +1739141197.8748858,37.28996443748474,45.42067680837816,1739141197.8748894,37.28996443748474,8.005764229074456,1739141197.874893,37.28996443748474,63.22662285107661,1739141197.8748963,37.28996443748474,43.06873361516679,1739141197.8748982,37.28996443748474,3.8986865160653905,1739141197.8749003,37.28996443748474,-2.0908673354882317,1739141197.8749022,37.28996443748474,2.2050564345548,1739141197.874904,37.28996443748474,0.6108,1739141197.8749056,37.28996443748474,1.034862076122294,1739141197.8749077,37.28996443748474,0.0,1739141197.8749094,37.28996443748474,0.035572732115465966,1739141197.874911,37.28996443748474,3.7076596297479663,1739141197.8749127,37.28996443748474,0.999289344006828 +1739141197.8949442,37.309964418411255,45.42067680837816,1739141197.8949473,37.309964418411255,8.005764229074456,1739141197.8949506,37.309964418411255,63.22662285107661,1739141197.894954,37.309964418411255,43.06873361516679,1739141197.8949559,37.309964418411255,3.8986865160653905,1739141197.8949583,37.309964418411255,-2.0908673354882317,1739141197.8949602,37.309964418411255,2.2050564345548,1739141197.8949616,37.309964418411255,0.6108,1739141197.8949633,37.309964418411255,1.034862076122294,1739141197.8949652,37.309964418411255,0.0,1739141197.894967,37.309964418411255,0.035572732115465966,1739141197.8949685,37.309964418411255,3.7076596297479663,1739141197.8949704,37.309964418411255,0.999289344006828 +1739141197.915189,37.32996439933777,45.42067680837816,1739141197.9151926,37.32996439933777,8.005764229074456,1739141197.915197,37.32996439933777,63.22662285107661,1739141197.9152002,37.32996439933777,43.06873361516679,1739141197.9152021,37.32996439933777,3.8986865160653905,1739141197.9152045,37.32996439933777,-2.0908673354882317,1739141197.9152067,37.32996439933777,2.2050564345548,1739141197.9152083,37.32996439933777,0.6108,1739141197.9152102,37.32996439933777,1.034862076122294,1739141197.9152124,37.32996439933777,0.0,1739141197.9152143,37.32996439933777,0.035572732115465966,1739141197.915216,37.32996439933777,3.7076596297479663,1739141197.9152176,37.32996439933777,0.999289344006828 +1739141197.9350686,37.34996438026428,45.42067680837816,1739141197.935072,37.34996438026428,8.005764229074456,1739141197.9350758,37.34996438026428,63.22662285107661,1739141197.9350793,37.34996438026428,43.06873361516679,1739141197.9350812,37.34996438026428,3.8986865160653905,1739141197.9350832,37.34996438026428,-2.0908673354882317,1739141197.935085,37.34996438026428,2.2050564345548,1739141197.935087,37.34996438026428,0.6108,1739141197.9350884,37.34996438026428,1.034862076122294,1739141197.9350905,37.34996438026428,0.0,1739141197.9350922,37.34996438026428,0.035572732115465966,1739141197.9350936,37.34996438026428,3.7076596297479663,1739141197.9350955,37.34996438026428,0.999289344006828 +1739141197.9580226,37.369964361190796,45.32847513499999,1739141197.9580264,37.369964361190796,7.945530636553309,1739141197.9580312,37.369964361190796,63.2437043610376,1739141197.9580348,37.369964361190796,43.06264598566522,1739141197.9580367,37.369964361190796,3.869939376752434,1739141197.958039,37.369964361190796,-2.078196980855787,1739141197.9580412,37.369964361190796,2.110205306067635,1739141197.958043,37.369964361190796,0.6108,1739141197.9580448,37.369964361190796,1.0748795507059616,1739141197.9580464,37.369964361190796,0.0,1739141197.9580486,37.369964361190796,0.10414049362727491,1739141197.9580505,37.369964361190796,3.7353839729946037,1739141197.9580524,37.369964361190796,1.0033903883950765 +1739141197.9751282,37.38996434211731,45.32847513499999,1739141197.9751313,37.38996434211731,7.945530636553309,1739141197.9751353,37.38996434211731,63.2437043610376,1739141197.9751387,37.38996434211731,43.06264598566522,1739141197.9751403,37.38996434211731,3.869939376752434,1739141197.9751425,37.38996434211731,-2.078196980855787,1739141197.9751441,37.38996434211731,2.110205306067635,1739141197.9751458,37.38996434211731,0.6108,1739141197.9751472,37.38996434211731,1.0748795507059616,1739141197.9751494,37.38996434211731,0.0,1739141197.9751513,37.38996434211731,0.07148916231088509,1739141197.9751532,37.38996434211731,3.7353839729946037,1739141197.9751546,37.38996434211731,1.0033903883950765 +1739141197.9949577,37.40996432304382,45.32847513499999,1739141197.9949613,37.40996432304382,7.945530636553309,1739141197.9949648,37.40996432304382,63.2437043610376,1739141197.9949682,37.40996432304382,43.06264598566522,1739141197.9949698,37.40996432304382,3.869939376752434,1739141197.994972,37.40996432304382,-2.078196980855787,1739141197.9949737,37.40996432304382,2.110205306067635,1739141197.9949756,37.40996432304382,0.6108,1739141197.994977,37.40996432304382,1.0748795507059616,1739141197.994979,37.40996432304382,0.0,1739141197.9949808,37.40996432304382,0.07148916231088509,1739141197.9949827,37.40996432304382,3.7353839729946037,1739141197.9949841,37.40996432304382,1.0033903883950765 +1739141198.0152678,37.42996430397034,45.32847513499999,1739141198.0152714,37.42996430397034,7.945530636553309,1739141198.0152755,37.42996430397034,63.2437043610376,1739141198.015279,37.42996430397034,43.06264598566522,1739141198.0152812,37.42996430397034,3.869939376752434,1739141198.015283,37.42996430397034,-2.078196980855787,1739141198.0152853,37.42996430397034,2.110205306067635,1739141198.015287,37.42996430397034,0.6108,1739141198.0152886,37.42996430397034,1.0748795507059616,1739141198.0152907,37.42996430397034,0.0,1739141198.0152926,37.42996430397034,0.07148916231088509,1739141198.0152943,37.42996430397034,3.7353839729946037,1739141198.015296,37.42996430397034,1.0033903883950765 +1739141198.03518,37.44996428489685,45.32847513499999,1739141198.035184,37.44996428489685,7.945530636553309,1739141198.0351877,37.44996428489685,63.2437043610376,1739141198.0351913,37.44996428489685,43.06264598566522,1739141198.0351932,37.44996428489685,3.869939376752434,1739141198.035195,37.44996428489685,-2.078196980855787,1739141198.035197,37.44996428489685,2.110205306067635,1739141198.0351987,37.44996428489685,0.6108,1739141198.0352004,37.44996428489685,1.0748795507059616,1739141198.0352023,37.44996428489685,0.0,1739141198.0352044,37.44996428489685,0.07148916231088509,1739141198.0352058,37.44996428489685,3.7353839729946037,1739141198.0352075,37.44996428489685,1.0033903883950765 +1739141198.0552304,37.469964265823364,45.23744655596597,1739141198.055234,37.469964265823364,7.8823939505966845,1739141198.0552402,37.469964265823364,63.44923322136838,1739141198.055244,37.469964265823364,43.01318927198982,1739141198.0552456,37.469964265823364,3.6454177946203026,1739141198.0552478,37.469964265823364,-2.054214613060795,1739141198.0552497,37.469964265823364,2.149534379383247,1739141198.0552516,37.469964265823364,0.6108,1739141198.0552535,37.469964265823364,1.0581022571337908,1739141198.0552557,37.469964265823364,0.0,1739141198.0552573,37.469964265823364,0.0239466150429122,1739141198.0552592,37.469964265823364,3.763108316241241,1739141198.055261,37.469964265823364,1.0115163225587052 +1739141198.0750532,37.48996424674988,45.23744655596597,1739141198.0750568,37.48996424674988,7.8823939505966845,1739141198.075061,37.48996424674988,63.44923322136838,1739141198.075065,37.48996424674988,43.01318927198982,1739141198.0750668,37.48996424674988,3.6454177946203026,1739141198.0750692,37.48996424674988,-2.054214613060795,1739141198.0750713,37.48996424674988,2.149534379383247,1739141198.075073,37.48996424674988,0.6108,1739141198.075075,37.48996424674988,1.0581022571337908,1739141198.0750768,37.48996424674988,0.0,1739141198.0750787,37.48996424674988,0.04658593457508564,1739141198.0750806,37.48996424674988,3.763108316241241,1739141198.0750825,37.48996424674988,1.0115163225587052 +1739141198.0955973,37.50996422767639,45.23744655596597,1739141198.0956004,37.50996422767639,7.8823939505966845,1739141198.0956042,37.50996422767639,63.44923322136838,1739141198.0956078,37.50996422767639,43.01318927198982,1739141198.0956097,37.50996422767639,3.6454177946203026,1739141198.0956116,37.50996422767639,-2.054214613060795,1739141198.0956137,37.50996422767639,2.149534379383247,1739141198.0956151,37.50996422767639,0.6108,1739141198.0956168,37.50996422767639,1.0581022571337908,1739141198.0956187,37.50996422767639,0.0,1739141198.0956206,37.50996422767639,0.04658593457508564,1739141198.0956223,37.50996422767639,3.763108316241241,1739141198.0956242,37.50996422767639,1.0115163225587052 +1739141198.1150482,37.529964208602905,45.23744655596597,1739141198.1150515,37.529964208602905,7.8823939505966845,1739141198.115055,37.529964208602905,63.44923322136838,1739141198.1150584,37.529964208602905,43.01318927198982,1739141198.1150603,37.529964208602905,3.6454177946203026,1739141198.1150625,37.529964208602905,-2.054214613060795,1739141198.1150644,37.529964208602905,2.149534379383247,1739141198.1150658,37.529964208602905,0.6108,1739141198.1150677,37.529964208602905,1.0581022571337908,1739141198.1150696,37.529964208602905,0.0,1739141198.1150715,37.529964208602905,0.04658593457508564,1739141198.115073,37.529964208602905,3.763108316241241,1739141198.1150746,37.529964208602905,1.0115163225587052 +1739141198.1352777,37.54996418952942,45.23744655596597,1739141198.1352816,37.54996418952942,7.8823939505966845,1739141198.1352859,37.54996418952942,63.44923322136838,1739141198.1352897,37.54996418952942,43.01318927198982,1739141198.1352918,37.54996418952942,3.6454177946203026,1739141198.1352944,37.54996418952942,-2.054214613060795,1739141198.1352966,37.54996418952942,2.149534379383247,1739141198.1352983,37.54996418952942,0.6108,1739141198.1353002,37.54996418952942,1.0581022571337908,1739141198.1353023,37.54996418952942,0.0,1739141198.1353045,37.54996418952942,0.04658593457508564,1739141198.1353066,37.54996418952942,3.763108316241241,1739141198.1353085,37.54996418952942,1.0115163225587052 +1739141198.1551723,37.56996417045593,45.23744655596597,1739141198.1551762,37.56996417045593,7.8823939505966845,1739141198.1551797,37.56996417045593,63.44923322136838,1739141198.1551836,37.56996417045593,43.01318927198982,1739141198.1551855,37.56996417045593,3.6454177946203026,1739141198.1551876,37.56996417045593,-2.054214613060795,1739141198.15519,37.56996417045593,2.149534379383247,1739141198.155192,37.56996417045593,0.6108,1739141198.1551933,37.56996417045593,1.0581022571337908,1739141198.1551955,37.56996417045593,0.0,1739141198.1551976,37.56996417045593,0.04658593457508564,1739141198.1551993,37.56996417045593,3.763108316241241,1739141198.155201,37.56996417045593,1.0115163225587052 +1739141198.1752763,37.589964151382446,45.1476427464045,1739141198.1752796,37.589964151382446,7.816347104326422,1739141198.1752834,37.589964151382446,63.551429375533765,1739141198.1752875,37.589964151382446,42.98603057848263,1739141198.1752896,37.589964151382446,3.5324875161954785,1739141198.1752925,37.589964151382446,-2.0381128103811705,1739141198.1752944,37.589964151382446,2.1054104341169477,1739141198.1752965,37.589964151382446,0.6108,1739141198.1752985,37.589964151382446,1.0769430928807129,1739141198.1753006,37.589964151382446,0.0,1739141198.175303,37.589964151382446,0.0736647221359435,1739141198.175305,37.589964151382446,3.7908326594878785,1739141198.1753068,37.589964151382446,1.0161730379294847 +1739141198.1948936,37.60996413230896,45.1476427464045,1739141198.1948967,37.60996413230896,7.816347104326422,1739141198.1949003,37.60996413230896,63.551429375533765,1739141198.1949036,37.60996413230896,42.98603057848263,1739141198.1949053,37.60996413230896,3.5324875161954785,1739141198.1949074,37.60996413230896,-2.0381128103811705,1739141198.1949093,37.60996413230896,2.1054104341169477,1739141198.1949112,37.60996413230896,0.6108,1739141198.1949127,37.60996413230896,1.0769430928807129,1739141198.1949148,37.60996413230896,0.0,1739141198.1949167,37.60996413230896,0.060770054951228225,1739141198.1949182,37.60996413230896,3.7908326594878785,1739141198.1949198,37.60996413230896,1.0161730379294847 +1739141198.2146626,37.629964113235474,45.1476427464045,1739141198.2146654,37.629964113235474,7.816347104326422,1739141198.2146688,37.629964113235474,63.551429375533765,1739141198.2146716,37.629964113235474,42.98603057848263,1739141198.2146728,37.629964113235474,3.5324875161954785,1739141198.2146747,37.629964113235474,-2.0381128103811705,1739141198.2146761,37.629964113235474,2.1054104341169477,1739141198.2146776,37.629964113235474,0.6108,1739141198.2146788,37.629964113235474,1.0769430928807129,1739141198.2146807,37.629964113235474,0.0,1739141198.2146819,37.629964113235474,0.060770054951228225,1739141198.214683,37.629964113235474,3.7908326594878785,1739141198.2146845,37.629964113235474,1.0161730379294847 +1739141198.234359,37.64996409416199,45.1476427464045,1739141198.2343614,37.64996409416199,7.816347104326422,1739141198.2343643,37.64996409416199,63.551429375533765,1739141198.2343667,37.64996409416199,42.98603057848263,1739141198.2343686,37.64996409416199,3.5324875161954785,1739141198.2343702,37.64996409416199,-2.0381128103811705,1739141198.2343717,37.64996409416199,2.1054104341169477,1739141198.2343729,37.64996409416199,0.6108,1739141198.234374,37.64996409416199,1.0769430928807129,1739141198.2343757,37.64996409416199,0.0,1739141198.234377,37.64996409416199,0.060770054951228225,1739141198.234378,37.64996409416199,3.7908326594878785,1739141198.2343793,37.64996409416199,1.0161730379294847 +1739141198.254624,37.6699640750885,45.1476427464045,1739141198.2546268,37.6699640750885,7.816347104326422,1739141198.2546296,37.6699640750885,63.551429375533765,1739141198.2546322,37.6699640750885,42.98603057848263,1739141198.2546334,37.6699640750885,3.5324875161954785,1739141198.254635,37.6699640750885,-2.0381128103811705,1739141198.2546365,37.6699640750885,2.1054104341169477,1739141198.2546377,37.6699640750885,0.6108,1739141198.254639,37.6699640750885,1.0769430928807129,1739141198.2546403,37.6699640750885,0.0,1739141198.2546418,37.6699640750885,0.060770054951228225,1739141198.2546432,37.6699640750885,3.7908326594878785,1739141198.2546444,37.6699640750885,1.0161730379294847 +1739141198.2743645,37.689964056015015,45.05919949173834,1739141198.2743666,37.689964056015015,7.747442255592109,1739141198.2743697,37.689964056015015,63.638572854788144,1739141198.2743723,37.689964056015015,42.959193131620495,1739141198.2743735,37.689964056015015,3.428429569529085,1739141198.2743754,37.689964056015015,-2.023362287168385,1739141198.274377,37.689964056015015,2.0510687290279344,1739141198.2743814,37.689964056015015,0.6108,1739141198.2743857,37.689964056015015,1.1006085347672694,1739141198.2743883,37.689964056015015,0.0,1739141198.2743902,37.689964056015015,0.0930183309119143,1739141198.274392,37.689964056015015,3.818557002734516,1739141198.2743936,37.689964056015015,1.0229465334125536 +1739141198.2943933,37.70996403694153,45.05919949173834,1739141198.2943957,37.70996403694153,7.747442255592109,1739141198.2943985,37.70996403694153,63.638572854788144,1739141198.294401,37.70996403694153,42.959193131620495,1739141198.2944024,37.70996403694153,3.428429569529085,1739141198.2944038,37.70996403694153,-2.023362287168385,1739141198.2944052,37.70996403694153,2.0510687290279344,1739141198.2944064,37.70996403694153,0.6108,1739141198.2944076,37.70996403694153,1.1006085347672694,1739141198.294409,37.70996403694153,0.0,1739141198.2944105,37.70996403694153,0.07766200135471579,1739141198.2944114,37.70996403694153,3.818557002734516,1739141198.294413,37.70996403694153,1.0229465334125536 +1739141198.3146877,37.72996401786804,45.05919949173834,1739141198.3146906,37.72996401786804,7.747442255592109,1739141198.314694,37.72996401786804,63.638572854788144,1739141198.3146968,37.72996401786804,42.959193131620495,1739141198.314698,37.72996401786804,3.428429569529085,1739141198.3147001,37.72996401786804,-2.023362287168385,1739141198.3147013,37.72996401786804,2.0510687290279344,1739141198.3147027,37.72996401786804,0.6108,1739141198.3147042,37.72996401786804,1.1006085347672694,1739141198.3147058,37.72996401786804,0.0,1739141198.3147073,37.72996401786804,0.07766200135471579,1739141198.3147085,37.72996401786804,3.818557002734516,1739141198.31471,37.72996401786804,1.0229465334125536 +1739141198.3346236,37.749963998794556,45.05919949173834,1739141198.334626,37.749963998794556,7.747442255592109,1739141198.334629,37.749963998794556,63.638572854788144,1739141198.334632,37.749963998794556,42.959193131620495,1739141198.3346336,37.749963998794556,3.428429569529085,1739141198.3346353,37.749963998794556,-2.023362287168385,1739141198.3346364,37.749963998794556,2.0510687290279344,1739141198.334638,37.749963998794556,0.6108,1739141198.3346393,37.749963998794556,1.1006085347672694,1739141198.3346412,37.749963998794556,0.0,1739141198.3346424,37.749963998794556,0.07766200135471579,1739141198.3346436,37.749963998794556,3.818557002734516,1739141198.3346453,37.749963998794556,1.0229465334125536 +1739141198.3547513,37.76996397972107,45.05919949173834,1739141198.354754,37.76996397972107,7.747442255592109,1739141198.3547573,37.76996397972107,63.638572854788144,1739141198.3547602,37.76996397972107,42.959193131620495,1739141198.3547618,37.76996397972107,3.428429569529085,1739141198.3547635,37.76996397972107,-2.023362287168385,1739141198.3547654,37.76996397972107,2.0510687290279344,1739141198.3547666,37.76996397972107,0.6108,1739141198.3547678,37.76996397972107,1.1006085347672694,1739141198.3547695,37.76996397972107,0.0,1739141198.354771,37.76996397972107,0.07766200135471579,1739141198.3547723,37.76996397972107,3.818557002734516,1739141198.3547738,37.76996397972107,1.0229465334125536 +1739141198.374618,37.78996396064758,45.05919949173834,1739141198.3746219,37.78996396064758,7.747442255592109,1739141198.3746269,37.78996396064758,63.638572854788144,1739141198.3746324,37.78996396064758,42.959193131620495,1739141198.3746355,37.78996396064758,3.428429569529085,1739141198.3746395,37.78996396064758,-2.023362287168385,1739141198.374643,37.78996396064758,2.0510687290279344,1739141198.374647,37.78996396064758,0.6108,1739141198.37465,37.78996396064758,1.1006085347672694,1739141198.374654,37.78996396064758,0.0,1739141198.3746576,37.78996396064758,0.07766200135471579,1739141198.3746612,37.78996396064758,3.818557002734516,1739141198.374665,37.78996396064758,1.0229465334125536 +1739141198.3945088,37.8099639415741,44.97203753148475,1739141198.3945115,37.8099639415741,7.67556501744407,1739141198.394514,37.8099639415741,63.80143138494147,1739141198.394517,37.8099639415741,42.90856182807357,1739141198.3945186,37.8099639415741,3.2460167138179155,1739141198.3945208,37.8099639415741,-2.0067472074672428,1739141198.3945222,37.8099639415741,2.037775844543305,1739141198.3945234,37.8099639415741,0.6108,1739141198.3945246,37.8099639415741,1.1064762254961293,1739141198.3945265,37.8099639415741,0.0,1739141198.394528,37.8099639415741,0.07202989753197982,1739141198.3945293,37.8099639415741,3.8462813459811533,1739141198.3945305,37.8099639415741,1.0317643724230927 +1739141198.414819,37.82996392250061,44.97203753148475,1739141198.414822,37.82996392250061,7.67556501744407,1739141198.4148254,37.82996392250061,63.80143138494147,1739141198.414828,37.82996392250061,42.90856182807357,1739141198.4148295,37.82996392250061,3.2460167138179155,1739141198.4148314,37.82996392250061,-2.0067472074672428,1739141198.4148333,37.82996392250061,2.037775844543305,1739141198.414835,37.82996392250061,0.6108,1739141198.4148362,37.82996392250061,1.1064762254961293,1739141198.4148378,37.82996392250061,0.0,1739141198.4148393,37.82996392250061,0.07471185307303663,1739141198.4148412,37.82996392250061,3.8462813459811533,1739141198.4148424,37.82996392250061,1.0317643724230927 +1739141198.4344914,37.849963903427124,44.97203753148475,1739141198.434494,37.849963903427124,7.67556501744407,1739141198.4344969,37.849963903427124,63.80143138494147,1739141198.4344995,37.849963903427124,42.90856182807357,1739141198.4345012,37.849963903427124,3.2460167138179155,1739141198.4345028,37.849963903427124,-2.0067472074672428,1739141198.4345045,37.849963903427124,2.037775844543305,1739141198.4345057,37.849963903427124,0.6108,1739141198.434507,37.849963903427124,1.1064762254961293,1739141198.4345086,37.849963903427124,0.0,1739141198.43451,37.849963903427124,0.07471185307303663,1739141198.4345117,37.849963903427124,3.8462813459811533,1739141198.434513,37.849963903427124,1.0317643724230927 +1739141198.4548244,37.86996388435364,44.97203753148475,1739141198.4548275,37.86996388435364,7.67556501744407,1739141198.4548311,37.86996388435364,63.80143138494147,1739141198.454834,37.86996388435364,42.90856182807357,1739141198.4548352,37.86996388435364,3.2460167138179155,1739141198.454837,37.86996388435364,-2.0067472074672428,1739141198.4548385,37.86996388435364,2.037775844543305,1739141198.45484,37.86996388435364,0.6108,1739141198.4548414,37.86996388435364,1.1064762254961293,1739141198.454843,37.86996388435364,0.0,1739141198.4548447,37.86996388435364,0.07471185307303663,1739141198.454846,37.86996388435364,3.8462813459811533,1739141198.4548473,37.86996388435364,1.0317643724230927 +1739141198.4746087,37.88996386528015,44.97203753148475,1739141198.4746118,37.88996386528015,7.67556501744407,1739141198.4746146,37.88996386528015,63.80143138494147,1739141198.4746175,37.88996386528015,42.90856182807357,1739141198.474619,37.88996386528015,3.2460167138179155,1739141198.4746206,37.88996386528015,-2.0067472074672428,1739141198.474622,37.88996386528015,2.037775844543305,1739141198.4746234,37.88996386528015,0.6108,1739141198.4746249,37.88996386528015,1.1064762254961293,1739141198.4746265,37.88996386528015,0.0,1739141198.4746277,37.88996386528015,0.07471185307303663,1739141198.4746292,37.88996386528015,3.8462813459811533,1739141198.4746304,37.88996386528015,1.0317643724230927 +1739141198.494625,37.909963846206665,44.88620633651172,1739141198.4946275,37.909963846206665,7.60069296258602,1739141198.4946306,37.909963846206665,63.88740588792789,1739141198.494634,37.909963846206665,42.876837592899555,1739141198.4946358,37.909963846206665,3.1402221769235577,1739141198.494638,37.909963846206665,-1.9940523062182338,1739141198.4946396,37.909963846206665,1.973045073749574,1739141198.494641,37.909963846206665,0.6108,1739141198.4946427,37.909963846206665,1.1354995682953015,1739141198.4946442,37.909963846206665,0.0,1739141198.494646,37.909963846206665,0.11454357317585001,1739141198.4946475,37.909963846206665,3.8740056892277908,1739141198.4946494,37.909963846206665,1.0399234903577885 +1739141198.51475,37.92996382713318,44.88620633651172,1739141198.514753,37.92996382713318,7.60069296258602,1739141198.5147562,37.92996382713318,63.88740588792789,1739141198.5147588,37.92996382713318,42.876837592899555,1739141198.5147603,37.92996382713318,3.1402221769235577,1739141198.514762,37.92996382713318,-1.9940523062182338,1739141198.5147634,37.92996382713318,1.973045073749574,1739141198.5147648,37.92996382713318,0.6108,1739141198.514766,37.92996382713318,1.1354995682953015,1739141198.5147676,37.92996382713318,0.0,1739141198.514769,37.92996382713318,0.095576077937513,1739141198.5147705,37.92996382713318,3.8740056892277908,1739141198.514772,37.92996382713318,1.0399234903577885 +1739141198.5345004,37.94996380805969,44.88620633651172,1739141198.5345027,37.94996380805969,7.60069296258602,1739141198.5345058,37.94996380805969,63.88740588792789,1739141198.5345087,37.94996380805969,42.876837592899555,1739141198.5345104,37.94996380805969,3.1402221769235577,1739141198.534512,37.94996380805969,-1.9940523062182338,1739141198.5345137,37.94996380805969,1.973045073749574,1739141198.5345151,37.94996380805969,0.6108,1739141198.5345166,37.94996380805969,1.1354995682953015,1739141198.5345182,37.94996380805969,0.0,1739141198.5345194,37.94996380805969,0.095576077937513,1739141198.5345209,37.94996380805969,3.8740056892277908,1739141198.534522,37.94996380805969,1.0399234903577885 +1739141198.5544662,37.969963788986206,44.88620633651172,1739141198.5544803,37.969963788986206,7.60069296258602,1739141198.554484,37.969963788986206,63.88740588792789,1739141198.5544868,37.969963788986206,42.876837592899555,1739141198.5544884,37.969963788986206,3.1402221769235577,1739141198.5544899,37.969963788986206,-1.9940523062182338,1739141198.554491,37.969963788986206,1.973045073749574,1739141198.5544927,37.969963788986206,0.6108,1739141198.554494,37.969963788986206,1.1354995682953015,1739141198.5544956,37.969963788986206,0.0,1739141198.5544972,37.969963788986206,0.095576077937513,1739141198.5544987,37.969963788986206,3.8740056892277908,1739141198.5544999,37.969963788986206,1.0399234903577885 +1739141198.5746315,37.98996376991272,44.88620633651172,1739141198.5746343,37.98996376991272,7.60069296258602,1739141198.5746374,37.98996376991272,63.88740588792789,1739141198.57464,37.98996376991272,42.876837592899555,1739141198.5746417,37.98996376991272,3.1402221769235577,1739141198.5746434,37.98996376991272,-1.9940523062182338,1739141198.5746448,37.98996376991272,1.973045073749574,1739141198.574646,37.98996376991272,0.6108,1739141198.5746477,37.98996376991272,1.1354995682953015,1739141198.574649,37.98996376991272,0.0,1739141198.5746505,37.98996376991272,0.095576077937513,1739141198.574652,37.98996376991272,3.8740056892277908,1739141198.5746534,37.98996376991272,1.0399234903577885 +1739141198.5948982,38.00996375083923,44.88620633651172,1739141198.594901,38.00996375083923,7.60069296258602,1739141198.5949044,38.00996375083923,63.88740588792789,1739141198.5949078,38.00996375083923,42.876837592899555,1739141198.5949092,38.00996375083923,3.1402221769235577,1739141198.5949113,38.00996375083923,-1.9940523062182338,1739141198.5949128,38.00996375083923,1.973045073749574,1739141198.5949142,38.00996375083923,0.6108,1739141198.5949156,38.00996375083923,1.1354995682953015,1739141198.5949173,38.00996375083923,0.0,1739141198.594919,38.00996375083923,0.095576077937513,1739141198.5949204,38.00996375083923,3.8740056892277908,1739141198.594922,38.00996375083923,1.0399234903577885 +1739141198.6148837,38.02996373176575,44.801712152375586,1739141198.6148872,38.02996373176575,7.522757918749512,1739141198.6148906,38.02996373176575,63.973556023297725,1739141198.6148937,38.02996373176575,42.84011347448901,1739141198.614895,38.02996373176575,3.0273404234670234,1739141198.614897,38.02996373176575,-1.9822454604029138,1739141198.6148982,38.02996373176575,1.906432278608648,1739141198.6148996,38.02996373176575,0.6004722553506057,1739141198.6149013,38.02996373176575,1.1661617733191418,1739141198.614903,38.02996373176575,0.0,1739141198.6149049,38.02996373176575,0.13339367190973517,1739141198.614906,38.02996373176575,3.901730032474428,1739141198.6149077,38.02996373176575,1.0507764884873934 +1739141198.6347518,38.04996371269226,44.801712152375586,1739141198.634755,38.04996371269226,7.522757918749512,1739141198.6347582,38.04996371269226,63.973556023297725,1739141198.6347618,38.04996371269226,42.84011347448901,1739141198.6347637,38.04996371269226,3.0273404234670234,1739141198.634766,38.04996371269226,-1.9822454604029138,1739141198.6347678,38.04996371269226,1.906432278608648,1739141198.63477,38.04996371269226,0.6004722553506057,1739141198.6347713,38.04996371269226,1.1661617733191418,1739141198.6347735,38.04996371269226,0.0,1739141198.6347756,38.04996371269226,0.11538528483174848,1739141198.6347773,38.04996371269226,3.901730032474428,1739141198.634779,38.04996371269226,1.0507764884873934 +1739141198.654906,38.069963693618774,44.801712152375586,1739141198.6549096,38.069963693618774,7.522757918749512,1739141198.6549134,38.069963693618774,63.973556023297725,1739141198.6549168,38.069963693618774,42.84011347448901,1739141198.6549191,38.069963693618774,3.0273404234670234,1739141198.6549215,38.069963693618774,-1.9822454604029138,1739141198.6549232,38.069963693618774,1.906432278608648,1739141198.6549253,38.069963693618774,0.6004722553506057,1739141198.654927,38.069963693618774,1.1661617733191418,1739141198.6549292,38.069963693618774,0.0,1739141198.6549313,38.069963693618774,0.11538528483174848,1739141198.654933,38.069963693618774,3.901730032474428,1739141198.654935,38.069963693618774,1.0507764884873934 +1739141198.6748836,38.08996367454529,44.801712152375586,1739141198.6748867,38.08996367454529,7.522757918749512,1739141198.6748903,38.08996367454529,63.973556023297725,1739141198.6748939,38.08996367454529,42.84011347448901,1739141198.6748955,38.08996367454529,3.0273404234670234,1739141198.674898,38.08996367454529,-1.9822454604029138,1739141198.6749,38.08996367454529,1.906432278608648,1739141198.6749015,38.08996367454529,0.6004722553506057,1739141198.6749027,38.08996367454529,1.1661617733191418,1739141198.6749046,38.08996367454529,0.0,1739141198.6749067,38.08996367454529,0.11538528483174848,1739141198.6749084,38.08996367454529,3.901730032474428,1739141198.67491,38.08996367454529,1.0507764884873934 +1739141198.6947927,38.1099636554718,44.801712152375586,1739141198.6947956,38.1099636554718,7.522757918749512,1739141198.694799,38.1099636554718,63.973556023297725,1739141198.6948023,38.1099636554718,42.84011347448901,1739141198.6948042,38.1099636554718,3.0273404234670234,1739141198.6948066,38.1099636554718,-1.9822454604029138,1739141198.6948085,38.1099636554718,1.906432278608648,1739141198.6948104,38.1099636554718,0.6004722553506057,1739141198.6948116,38.1099636554718,1.1661617733191418,1739141198.6948135,38.1099636554718,0.0,1739141198.6948152,38.1099636554718,0.11538528483174848,1739141198.6948168,38.1099636554718,3.901730032474428,1739141198.694819,38.1099636554718,1.0507764884873934 +1739141198.7148821,38.129963636398315,44.71849720157497,1739141198.7148855,38.129963636398315,7.44161899587243,1739141198.7148888,38.129963636398315,64.08051042242592,1739141198.7148921,38.129963636398315,42.79436947163802,1739141198.7148938,38.129963636398315,2.889369299451988,1739141198.7148957,38.129963636398315,-1.970697073022112,1739141198.7148972,38.129963636398315,1.8470753928245383,1739141198.7148986,38.129963636398315,0.5736772440004384,1739141198.7149003,38.129963636398315,1.1941809760840725,1739141198.714902,38.129963636398315,0.0,1739141198.7149036,38.129963636398315,0.14443818233818495,1739141198.714905,38.129963636398315,3.9294543757210656,1739141198.7149067,38.129963636398315,1.0635775137552377 +1739141198.7347717,38.14996361732483,44.71849720157497,1739141198.7347746,38.14996361732483,7.44161899587243,1739141198.7347777,38.14996361732483,64.08051042242592,1739141198.7347808,38.14996361732483,42.79436947163802,1739141198.7347825,38.14996361732483,2.889369299451988,1739141198.7347846,38.14996361732483,-1.970697073022112,1739141198.734786,38.14996361732483,1.8470753928245383,1739141198.7347877,38.14996361732483,0.5736772440004384,1739141198.7347891,38.14996361732483,1.1941809760840725,1739141198.7347908,38.14996361732483,0.0,1739141198.7347925,38.14996361732483,0.1306034623288348,1739141198.7347941,38.14996361732483,3.9294543757210656,1739141198.7347958,38.14996361732483,1.0635775137552377 +1739141198.755064,38.16996359825134,44.71849720157497,1739141198.7550676,38.16996359825134,7.44161899587243,1739141198.7550712,38.16996359825134,64.08051042242592,1739141198.7550743,38.16996359825134,42.79436947163802,1739141198.755076,38.16996359825134,2.889369299451988,1739141198.7550778,38.16996359825134,-1.970697073022112,1739141198.7550795,38.16996359825134,1.8470753928245383,1739141198.755081,38.16996359825134,0.5736772440004384,1739141198.7550821,38.16996359825134,1.1941809760840725,1739141198.755084,38.16996359825134,0.0,1739141198.7550857,38.16996359825134,0.1306034623288348,1739141198.7550874,38.16996359825134,3.9294543757210656,1739141198.7550888,38.16996359825134,1.0635775137552377 +1739141198.7745779,38.189963579177856,44.71849720157497,1739141198.7745805,38.189963579177856,7.44161899587243,1739141198.7745838,38.189963579177856,64.08051042242592,1739141198.774587,38.189963579177856,42.79436947163802,1739141198.7745886,38.189963579177856,2.889369299451988,1739141198.7745905,38.189963579177856,-1.970697073022112,1739141198.774592,38.189963579177856,1.8470753928245383,1739141198.7745936,38.189963579177856,0.5736772440004384,1739141198.774595,38.189963579177856,1.1941809760840725,1739141198.774597,38.189963579177856,0.0,1739141198.7745984,38.189963579177856,0.1306034623288348,1739141198.7745998,38.189963579177856,3.9294543757210656,1739141198.7746015,38.189963579177856,1.0635775137552377 +1739141198.794787,38.20996356010437,44.71849720157497,1739141198.7947896,38.20996356010437,7.44161899587243,1739141198.7947927,38.20996356010437,64.08051042242592,1739141198.794796,38.20996356010437,42.79436947163802,1739141198.7947977,38.20996356010437,2.889369299451988,1739141198.7947996,38.20996356010437,-1.970697073022112,1739141198.7948012,38.20996356010437,1.8470753928245383,1739141198.794803,38.20996356010437,0.5736772440004384,1739141198.7948043,38.20996356010437,1.1941809760840725,1739141198.794806,38.20996356010437,0.0,1739141198.794808,38.20996356010437,0.1306034623288348,1739141198.7948093,38.20996356010437,3.9294543757210656,1739141198.7948108,38.20996356010437,1.0635775137552377 +1739141198.815072,38.229963541030884,44.71849720157497,1739141198.8150754,38.229963541030884,7.44161899587243,1739141198.8150787,38.229963541030884,64.08051042242592,1739141198.8150818,38.229963541030884,42.79436947163802,1739141198.8150833,38.229963541030884,2.889369299451988,1739141198.8150852,38.229963541030884,-1.970697073022112,1739141198.8150868,38.229963541030884,1.8470753928245383,1739141198.8150883,38.229963541030884,0.5736772440004384,1739141198.8150897,38.229963541030884,1.1941809760840725,1739141198.8150914,38.229963541030884,0.0,1739141198.8150933,38.229963541030884,0.1306034623288348,1739141198.8150947,38.229963541030884,3.9294543757210656,1739141198.8150964,38.229963541030884,1.0635775137552377 +1739141198.8349662,38.2499635219574,44.636513781590835,1739141198.8349705,38.2499635219574,7.357122098280648,1739141198.834974,38.2499635219574,64.26155880396753,1739141198.834977,38.2499635219574,42.71893845376536,1739141198.8349786,38.2499635219574,2.6776082636940277,1739141198.834981,38.2499635219574,-1.9597059623649091,1739141198.8349824,38.2499635219574,1.8112950872785778,1739141198.8349848,38.2499635219574,0.5380757683944914,1739141198.8349862,38.2499635219574,1.211395131875336,1739141198.8349884,38.2499635219574,0.0,1739141198.8349912,38.2499635219574,0.13561311755230074,1739141198.8349926,38.2499635219574,3.957178718967703,1739141198.8349943,38.2499635219574,1.0781675656211347 +1739141198.855043,38.26996350288391,44.636513781590835,1739141198.8550458,38.26996350288391,7.357122098280648,1739141198.8550494,38.26996350288391,64.26155880396753,1739141198.8550527,38.26996350288391,42.71893845376536,1739141198.8550544,38.26996350288391,2.6776082636940277,1739141198.8550563,38.26996350288391,-1.9597059623649091,1739141198.855058,38.26996350288391,1.8112950872785778,1739141198.8550594,38.26996350288391,0.5380757683944914,1739141198.855061,38.26996350288391,1.211395131875336,1739141198.8550627,38.26996350288391,0.0,1739141198.8550644,38.26996350288391,0.1332275662542013,1739141198.8550658,38.26996350288391,3.957178718967703,1739141198.8550675,38.26996350288391,1.0781675656211347 +1739141198.8749123,38.289963483810425,44.636513781590835,1739141198.874915,38.289963483810425,7.357122098280648,1739141198.8749182,38.289963483810425,64.26155880396753,1739141198.8749213,38.289963483810425,42.71893845376536,1739141198.8749228,38.289963483810425,2.6776082636940277,1739141198.8749247,38.289963483810425,-1.9597059623649091,1739141198.874926,38.289963483810425,1.8112950872785778,1739141198.8749275,38.289963483810425,0.5380757683944914,1739141198.8749292,38.289963483810425,1.211395131875336,1739141198.8749306,38.289963483810425,0.0,1739141198.8749325,38.289963483810425,0.1332275662542013,1739141198.874934,38.289963483810425,3.957178718967703,1739141198.8749354,38.289963483810425,1.0781675656211347 +1739141198.8947656,38.30996346473694,44.636513781590835,1739141198.8947685,38.30996346473694,7.357122098280648,1739141198.8947718,38.30996346473694,64.26155880396753,1739141198.8947747,38.30996346473694,42.71893845376536,1739141198.8947763,38.30996346473694,2.6776082636940277,1739141198.8947783,38.30996346473694,-1.9597059623649091,1739141198.89478,38.30996346473694,1.8112950872785778,1739141198.8947814,38.30996346473694,0.5380757683944914,1739141198.8947828,38.30996346473694,1.211395131875336,1739141198.8947845,38.30996346473694,0.0,1739141198.8947861,38.30996346473694,0.1332275662542013,1739141198.8947875,38.30996346473694,3.957178718967703,1739141198.8947892,38.30996346473694,1.0781675656211347 +1739141198.9150903,38.32996344566345,44.636513781590835,1739141198.9150937,38.32996344566345,7.357122098280648,1739141198.9150977,38.32996344566345,64.26155880396753,1739141198.9151008,38.32996344566345,42.71893845376536,1739141198.9151032,38.32996344566345,2.6776082636940277,1739141198.9151053,38.32996344566345,-1.9597059623649091,1739141198.9151073,38.32996344566345,1.8112950872785778,1739141198.9151092,38.32996344566345,0.5380757683944914,1739141198.9151108,38.32996344566345,1.211395131875336,1739141198.915113,38.32996344566345,0.0,1739141198.915115,38.32996344566345,0.1332275662542013,1739141198.9151168,38.32996344566345,3.957178718967703,1739141198.9151187,38.32996344566345,1.0781675656211347 +1739141198.9350877,38.349963426589966,44.55582671297258,1739141198.9350908,38.349963426589966,7.269211110637235,1739141198.9350946,38.349963426589966,64.37169838465577,1739141198.935098,38.349963426589966,42.662354789683356,1739141198.9350996,38.349963426589966,2.5344096788673363,1739141198.935102,38.349963426589966,-1.9512210152910066,1739141198.9351034,38.349963426589966,1.7344781421960924,1739141198.9351053,38.349963426589966,0.5073741158665015,1739141198.9351068,38.349963426589966,1.2491951638176708,1739141198.935109,38.349963426589966,0.0,1739141198.9351108,38.349963426589966,0.1774924768524609,1739141198.9351125,38.349963426589966,3.9849030622143404,1739141198.935114,38.349963426589966,1.0927812263511754 +1739141198.9553,38.36996340751648,44.55582671297258,1739141198.9553037,38.36996340751648,7.269211110637235,1739141198.9553077,38.36996340751648,64.37169838465577,1739141198.9553115,38.36996340751648,42.662354789683356,1739141198.9553134,38.36996340751648,2.5344096788673363,1739141198.9553154,38.36996340751648,-1.9512210152910066,1739141198.9553173,38.36996340751648,1.7344781421960924,1739141198.955319,38.36996340751648,0.5073741158665015,1739141198.9553206,38.36996340751648,1.2491951638176708,1739141198.9553227,38.36996340751648,0.0,1739141198.9553246,38.36996340751648,0.15641393746649546,1739141198.9553263,38.36996340751648,3.9849030622143404,1739141198.9553282,38.36996340751648,1.0927812263511754 +1739141198.9749525,38.38996338844299,44.55582671297258,1739141198.9749556,38.38996338844299,7.269211110637235,1739141198.9749591,38.38996338844299,64.37169838465577,1739141198.9749625,38.38996338844299,42.662354789683356,1739141198.9749644,38.38996338844299,2.5344096788673363,1739141198.9749665,38.38996338844299,-1.9512210152910066,1739141198.974968,38.38996338844299,1.7344781421960924,1739141198.9749699,38.38996338844299,0.5073741158665015,1739141198.9749713,38.38996338844299,1.2491951638176708,1739141198.9749734,38.38996338844299,0.0,1739141198.9749753,38.38996338844299,0.15641393746649546,1739141198.9749768,38.38996338844299,3.9849030622143404,1739141198.9749782,38.38996338844299,1.0927812263511754 +1739141198.9950087,38.40996336936951,44.55582671297258,1739141198.9950118,38.40996336936951,7.269211110637235,1739141198.9950154,38.40996336936951,64.37169838465577,1739141198.9950187,38.40996336936951,42.662354789683356,1739141198.9950206,38.40996336936951,2.5344096788673363,1739141198.995023,38.40996336936951,-1.9512210152910066,1739141198.995025,38.40996336936951,1.7344781421960924,1739141198.9950266,38.40996336936951,0.5073741158665015,1739141198.9950283,38.40996336936951,1.2491951638176708,1739141198.9950302,38.40996336936951,0.0,1739141198.9950323,38.40996336936951,0.15641393746649546,1739141198.9950337,38.40996336936951,3.9849030622143404,1739141198.9950356,38.40996336936951,1.0927812263511754 +1739141199.0151596,38.42996335029602,44.55582671297258,1739141199.0151637,38.42996335029602,7.269211110637235,1739141199.015168,38.42996335029602,64.37169838465577,1739141199.0151718,38.42996335029602,42.662354789683356,1739141199.015174,38.42996335029602,2.5344096788673363,1739141199.0151758,38.42996335029602,-1.9512210152910066,1739141199.015178,38.42996335029602,1.7344781421960924,1739141199.0151799,38.42996335029602,0.5073741158665015,1739141199.0151813,38.42996335029602,1.2491951638176708,1739141199.0151834,38.42996335029602,0.0,1739141199.015185,38.42996335029602,0.15641393746649546,1739141199.0151873,38.42996335029602,3.9849030622143404,1739141199.015189,38.42996335029602,1.0927812263511754 +1739141199.0349505,38.449963331222534,44.55582671297258,1739141199.0349534,38.449963331222534,7.269211110637235,1739141199.0349574,38.449963331222534,64.37169838465577,1739141199.0349607,38.449963331222534,42.662354789683356,1739141199.0349627,38.449963331222534,2.5344096788673363,1739141199.0349648,38.449963331222534,-1.9512210152910066,1739141199.0349662,38.449963331222534,1.7344781421960924,1739141199.0349681,38.449963331222534,0.5073741158665015,1739141199.0349696,38.449963331222534,1.2491951638176708,1739141199.0349717,38.449963331222534,0.0,1739141199.0349734,38.449963331222534,0.15641393746649546,1739141199.0349753,38.449963331222534,3.9849030622143404,1739141199.0349767,38.449963331222534,1.0927812263511754 +1739141199.0553901,38.46996331214905,44.476425401618144,1739141199.055394,38.46996331214905,7.177773730692568,1739141199.055398,38.46996331214905,64.52428366899859,1739141199.0554018,38.46996331214905,42.58035550620583,1739141199.0554035,38.46996331214905,2.3462532148939754,1739141199.0554059,38.46996331214905,-1.9447663662781953,1739141199.0554073,38.46996331214905,1.665011810744146,1739141199.0554092,38.46996331214905,0.47077867338682816,1739141199.0554106,38.46996331214905,1.2843927102071895,1739141199.0554128,38.46996331214905,0.0,1739141199.0554142,38.46996331214905,0.19008095224616586,1739141199.055416,38.46996331214905,4.011848932128006,1739141199.0554175,38.46996331214905,1.110343677769511 +1739141199.075036,38.48996329307556,44.476425401618144,1739141199.0750394,38.48996329307556,7.177773730692568,1739141199.0750434,38.48996329307556,64.52428366899859,1739141199.0750465,38.48996329307556,42.58035550620583,1739141199.0750484,38.48996329307556,2.3462532148939754,1739141199.0750508,38.48996329307556,-1.9447663662781953,1739141199.0750525,38.48996329307556,1.665011810744146,1739141199.0750542,38.48996329307556,0.47077867338682816,1739141199.0750558,38.48996329307556,1.2843927102071895,1739141199.075058,38.48996329307556,0.0,1739141199.0750597,38.48996329307556,0.17404903243767844,1739141199.0750616,38.48996329307556,4.011848932128006,1739141199.0750632,38.48996329307556,1.110343677769511 +1739141199.0980124,38.509963274002075,44.476425401618144,1739141199.0980175,38.509963274002075,7.177773730692568,1739141199.0980225,38.509963274002075,64.52428366899859,1739141199.0980277,38.509963274002075,42.58035550620583,1739141199.0980308,38.509963274002075,2.3462532148939754,1739141199.0980349,38.509963274002075,-1.9447663662781953,1739141199.0980382,38.509963274002075,1.665011810744146,1739141199.0980413,38.509963274002075,0.47077867338682816,1739141199.0980444,38.509963274002075,1.2843927102071895,1739141199.098048,38.509963274002075,0.0,1739141199.0980513,38.509963274002075,0.17404903243767844,1739141199.0980544,38.509963274002075,4.011848932128006,1739141199.0980575,38.509963274002075,1.110343677769511 +1739141199.1172113,38.52996325492859,44.476425401618144,1739141199.1172166,38.52996325492859,7.177773730692568,1739141199.1172214,38.52996325492859,64.52428366899859,1739141199.1172261,38.52996325492859,42.58035550620583,1739141199.117229,38.52996325492859,2.3462532148939754,1739141199.1172328,38.52996325492859,-1.9447663662781953,1739141199.117236,38.52996325492859,1.665011810744146,1739141199.1172392,38.52996325492859,0.47077867338682816,1739141199.1172423,38.52996325492859,1.2843927102071895,1739141199.117246,38.52996325492859,0.0,1739141199.1172493,38.52996325492859,0.17404903243767844,1739141199.1172526,38.52996325492859,4.011848932128006,1739141199.1172557,38.52996325492859,1.110343677769511 +1739141199.1370006,38.5499632358551,44.476425401618144,1739141199.1370032,38.5499632358551,7.177773730692568,1739141199.1370063,38.5499632358551,64.52428366899859,1739141199.1370091,38.5499632358551,42.58035550620583,1739141199.1370103,38.5499632358551,2.3462532148939754,1739141199.1370125,38.5499632358551,-1.9447663662781953,1739141199.1370137,38.5499632358551,1.665011810744146,1739141199.137015,38.5499632358551,0.47077867338682816,1739141199.1370163,38.5499632358551,1.2843927102071895,1739141199.137018,38.5499632358551,0.0,1739141199.1370192,38.5499632358551,0.17404903243767844,1739141199.1370203,38.5499632358551,4.011848932128006,1739141199.1370218,38.5499632358551,1.110343677769511 +1739141199.1552155,38.569963216781616,44.39818753194882,1739141199.155218,38.569963216781616,7.082737147637843,1739141199.1552205,38.569963216781616,64.604640816206,1739141199.1552231,38.569963216781616,42.51873453198872,1739141199.1552243,38.569963216781616,2.222808771591072,1739141199.1552258,38.569963216781616,-1.939806116804272,1739141199.1552272,38.569963216781616,1.5694814056773057,1739141199.1552281,38.569963216781616,0.4407447745369021,1739141199.1552293,38.569963216781616,1.3344219069991192,1739141199.1552308,38.569963216781616,0.0,1739141199.155232,38.569963216781616,0.23289078930615337,1739141199.155233,38.569963216781616,4.0374237531765775,1739141199.1552343,38.569963216781616,1.1295510159132125 +1739141199.1751757,38.58996319770813,44.39818753194882,1739141199.175178,38.58996319770813,7.082737147637843,1739141199.1751804,38.58996319770813,64.604640816206,1739141199.1751828,38.58996319770813,42.51873453198872,1739141199.175184,38.58996319770813,2.222808771591072,1739141199.1751854,38.58996319770813,-1.939806116804272,1739141199.1751866,38.58996319770813,1.5694814056773057,1739141199.175188,38.58996319770813,0.4407447745369021,1739141199.1751893,38.58996319770813,1.3344219069991192,1739141199.1751904,38.58996319770813,0.0,1739141199.175192,38.58996319770813,0.20487089108590673,1739141199.1751933,38.58996319770813,4.0374237531765775,1739141199.1751947,38.58996319770813,1.1295510159132125 +1739141199.1951752,38.609963178634644,44.39818753194882,1739141199.195178,38.609963178634644,7.082737147637843,1739141199.195181,38.609963178634644,64.604640816206,1739141199.1951833,38.609963178634644,42.51873453198872,1739141199.1951847,38.609963178634644,2.222808771591072,1739141199.1951861,38.609963178634644,-1.939806116804272,1739141199.1951876,38.609963178634644,1.5694814056773057,1739141199.1951888,38.609963178634644,0.4407447745369021,1739141199.1951897,38.609963178634644,1.3344219069991192,1739141199.1951914,38.609963178634644,0.0,1739141199.1951926,38.609963178634644,0.20487089108590673,1739141199.1951938,38.609963178634644,4.0374237531765775,1739141199.195195,38.609963178634644,1.1295510159132125 +1739141199.2176995,38.62996315956116,44.39818753194882,1739141199.2177033,38.62996315956116,7.082737147637843,1739141199.2177083,38.62996315956116,64.604640816206,1739141199.2177134,38.62996315956116,42.51873453198872,1739141199.2177165,38.62996315956116,2.222808771591072,1739141199.2177203,38.62996315956116,-1.939806116804272,1739141199.2177236,38.62996315956116,1.5694814056773057,1739141199.217727,38.62996315956116,0.4407447745369021,1739141199.2177303,38.62996315956116,1.3344219069991192,1739141199.2177339,38.62996315956116,0.0,1739141199.2177377,38.62996315956116,0.20487089108590673,1739141199.217741,38.62996315956116,4.0374237531765775,1739141199.2177444,38.62996315956116,1.1295510159132125 +1739141199.237141,38.64996314048767,44.39818753194882,1739141199.2371461,38.64996314048767,7.082737147637843,1739141199.2371504,38.64996314048767,64.604640816206,1739141199.2371554,38.64996314048767,42.51873453198872,1739141199.237158,38.64996314048767,2.222808771591072,1739141199.237161,38.64996314048767,-1.939806116804272,1739141199.2371638,38.64996314048767,1.5694814056773057,1739141199.2371664,38.64996314048767,0.4407447745369021,1739141199.2371686,38.64996314048767,1.3344219069991192,1739141199.237171,38.64996314048767,0.0,1739141199.2371738,38.64996314048767,0.20487089108590673,1739141199.2371764,38.64996314048767,4.0374237531765775,1739141199.2371788,38.64996314048767,1.1295510159132125 +1739141199.2579482,38.669963121414185,44.39818753194882,1739141199.257952,38.669963121414185,7.082737147637843,1739141199.2579572,38.669963121414185,64.604640816206,1739141199.2579622,38.669963121414185,42.51873453198872,1739141199.2579653,38.669963121414185,2.222808771591072,1739141199.2579691,38.669963121414185,-1.939806116804272,1739141199.2579725,38.669963121414185,1.5694814056773057,1739141199.2579758,38.669963121414185,0.4407447745369021,1739141199.2579794,38.669963121414185,1.3344219069991192,1739141199.2579827,38.669963121414185,0.0,1739141199.2579863,38.669963121414185,0.20487089108590673,1739141199.2579896,38.669963121414185,4.0374237531765775,1739141199.257993,38.669963121414185,1.1295510159132125 +1739141199.2780466,38.6899631023407,44.32090337309049,1739141199.278051,38.6899631023407,6.983951557256278,1739141199.2780554,38.6899631023407,64.75392904489149,1739141199.278061,38.6899631023407,42.413327724593856,1739141199.2780638,38.6899631023407,2.0316569788439316,1739141199.2780678,38.6899631023407,-1.9384708597882159,1739141199.278071,38.6899631023407,1.483286161325087,1739141199.2780743,38.6899631023407,0.40204976472111353,1739141199.2780776,38.6899631023407,1.3812325701993666,1739141199.2780814,38.6899631023407,0.0,1739141199.2780852,38.6899631023407,0.2503074854743432,1739141199.2780883,38.6899631023407,4.061444180070348,1739141199.2780917,38.6899631023407,1.1525615690516957 +1739141199.2980273,38.70996308326721,44.32090337309049,1739141199.298031,38.70996308326721,6.983951557256278,1739141199.2980359,38.70996308326721,64.75392904489149,1739141199.298041,38.70996308326721,42.413327724593856,1739141199.2980442,38.70996308326721,2.0316569788439316,1739141199.298048,38.70996308326721,-1.9384708597882159,1739141199.2980514,38.70996308326721,1.483286161325087,1739141199.2980547,38.70996308326721,0.40204976472111353,1739141199.298058,38.70996308326721,1.3812325701993666,1739141199.2980616,38.70996308326721,0.0,1739141199.2980652,38.70996308326721,0.22867100114767092,1739141199.2980685,38.70996308326721,4.061444180070348,1739141199.2980719,38.70996308326721,1.1525615690516957 +1739141199.3178468,38.729963064193726,44.32090337309049,1739141199.3178508,38.729963064193726,6.983951557256278,1739141199.3178551,38.729963064193726,64.75392904489149,1739141199.3178606,38.729963064193726,42.413327724593856,1739141199.3178635,38.729963064193726,2.0316569788439316,1739141199.3178673,38.729963064193726,-1.9384708597882159,1739141199.3178706,38.729963064193726,1.483286161325087,1739141199.3178744,38.729963064193726,0.40204976472111353,1739141199.3178778,38.729963064193726,1.3812325701993666,1739141199.3178813,38.729963064193726,0.0,1739141199.317885,38.729963064193726,0.22867100114767092,1739141199.3178883,38.729963064193726,4.061444180070348,1739141199.3178916,38.729963064193726,1.1525615690516957 +1739141199.3365095,38.74996304512024,44.32090337309049,1739141199.3365133,38.74996304512024,6.983951557256278,1739141199.3365173,38.74996304512024,64.75392904489149,1739141199.3365216,38.74996304512024,42.413327724593856,1739141199.3365238,38.74996304512024,2.0316569788439316,1739141199.3365269,38.74996304512024,-1.9384708597882159,1739141199.3365295,38.74996304512024,1.483286161325087,1739141199.3365319,38.74996304512024,0.40204976472111353,1739141199.3365345,38.74996304512024,1.3812325701993666,1739141199.3365374,38.74996304512024,0.0,1739141199.3365397,38.74996304512024,0.22867100114767092,1739141199.336542,38.74996304512024,4.061444180070348,1739141199.3365445,38.74996304512024,1.1525615690516957 +1739141199.3552048,38.76996302604675,44.32090337309049,1739141199.3552074,38.76996302604675,6.983951557256278,1739141199.35521,38.76996302604675,64.75392904489149,1739141199.3552125,38.76996302604675,42.413327724593856,1739141199.3552139,38.76996302604675,2.0316569788439316,1739141199.3552153,38.76996302604675,-1.9384708597882159,1739141199.355217,38.76996302604675,1.483286161325087,1739141199.355218,38.76996302604675,0.40204976472111353,1739141199.3552191,38.76996302604675,1.3812325701993666,1739141199.3552208,38.76996302604675,0.0,1739141199.355222,38.76996302604675,0.22867100114767092,1739141199.3552232,38.76996302604675,4.061444180070348,1739141199.3552246,38.76996302604675,1.1525615690516957 +1739141199.3750813,38.78996300697327,44.24437964500018,1739141199.3750834,38.78996300697327,6.881288437446575,1739141199.3750863,38.78996300697327,64.82513812107183,1739141199.375089,38.78996300697327,42.33647229388656,1739141199.3750901,38.78996300697327,1.906456461821731,1739141199.3750918,38.78996300697327,-1.937008537792861,1739141199.375093,38.78996300697327,1.3810753754077658,1739141199.3750942,38.78996300697327,0.37170394965236053,1739141199.3750954,38.78996300697327,1.4388735948787577,1739141199.3750968,38.78996300697327,0.0,1739141199.3750982,38.78996300697327,0.29052928987064114,1739141199.3750994,38.78996300697327,4.083978733952438,1739141199.3751006,38.78996300697327,1.1778006476861658 +1739141199.3948476,38.80996298789978,44.24437964500018,1739141199.3948498,38.80996298789978,6.881288437446575,1739141199.3948524,38.80996298789978,64.82513812107183,1739141199.394855,38.80996298789978,42.33647229388656,1739141199.3948565,38.80996298789978,1.906456461821731,1739141199.3948581,38.80996298789978,-1.937008537792861,1739141199.3948596,38.80996298789978,1.3810753754077658,1739141199.3948607,38.80996298789978,0.37170394965236053,1739141199.3948622,38.80996298789978,1.4388735948787577,1739141199.3948636,38.80996298789978,0.0,1739141199.3948648,38.80996298789978,0.2610729471925919,1739141199.394866,38.80996298789978,4.083978733952438,1739141199.3948672,38.80996298789978,1.1778006476861658 +1739141199.417829,38.829962968826294,44.24437964500018,1739141199.4178333,38.829962968826294,6.881288437446575,1739141199.4178379,38.829962968826294,64.82513812107183,1739141199.4178426,38.829962968826294,42.33647229388656,1739141199.4178455,38.829962968826294,1.906456461821731,1739141199.417849,38.829962968826294,-1.937008537792861,1739141199.4178526,38.829962968826294,1.3810753754077658,1739141199.4178557,38.829962968826294,0.37170394965236053,1739141199.417859,38.829962968826294,1.4388735948787577,1739141199.4178624,38.829962968826294,0.0,1739141199.4178658,38.829962968826294,0.2610729471925919,1739141199.4178689,38.829962968826294,4.083978733952438,1739141199.4178722,38.829962968826294,1.1778006476861658 +1739141199.434972,38.84996294975281,44.24437964500018,1739141199.4349744,38.84996294975281,6.881288437446575,1739141199.4349773,38.84996294975281,64.82513812107183,1739141199.43498,38.84996294975281,42.33647229388656,1739141199.434981,38.84996294975281,1.906456461821731,1739141199.434983,38.84996294975281,-1.937008537792861,1739141199.434984,38.84996294975281,1.3810753754077658,1739141199.4349852,38.84996294975281,0.37170394965236053,1739141199.4349866,38.84996294975281,1.4388735948787577,1739141199.434988,38.84996294975281,0.0,1739141199.4349892,38.84996294975281,0.2610729471925919,1739141199.4349906,38.84996294975281,4.083978733952438,1739141199.4349918,38.84996294975281,1.1778006476861658 +1739141199.4552188,38.86996293067932,44.24437964500018,1739141199.4552212,38.86996293067932,6.881288437446575,1739141199.455224,38.86996293067932,64.82513812107183,1739141199.4552267,38.86996293067932,42.33647229388656,1739141199.4552279,38.86996293067932,1.906456461821731,1739141199.4552295,38.86996293067932,-1.937008537792861,1739141199.4552307,38.86996293067932,1.3810753754077658,1739141199.455232,38.86996293067932,0.37170394965236053,1739141199.4552333,38.86996293067932,1.4388735948787577,1739141199.4552348,38.86996293067932,0.0,1739141199.4552364,38.86996293067932,0.2610729471925919,1739141199.4552376,38.86996293067932,4.083978733952438,1739141199.4552388,38.86996293067932,1.1778006476861658 +1739141199.4749558,38.889962911605835,44.24437964500018,1739141199.4749584,38.889962911605835,6.881288437446575,1739141199.474961,38.889962911605835,64.82513812107183,1739141199.4749637,38.889962911605835,42.33647229388656,1739141199.474965,38.889962911605835,1.906456461821731,1739141199.4749665,38.889962911605835,-1.937008537792861,1739141199.4749677,38.889962911605835,1.3810753754077658,1739141199.4749691,38.889962911605835,0.37170394965236053,1739141199.47497,38.889962911605835,1.4388735948787577,1739141199.4749715,38.889962911605835,0.0,1739141199.474973,38.889962911605835,0.2610729471925919,1739141199.4749742,38.889962911605835,4.083978733952438,1739141199.4749756,38.889962911605835,1.1778006476861658 +1739141199.4952865,38.90996289253235,44.16838242223861,1739141199.4952888,38.90996289253235,6.774531729058172,1739141199.4952915,38.90996289253235,65.04430008981865,1739141199.4952939,38.90996289253235,42.16477256869095,1739141199.4952955,38.90996289253235,1.6523228686654112,1739141199.495297,38.90996289253235,-1.9436599857020045,1739141199.4952984,38.90996289253235,1.2775497446569972,1739141199.4952993,38.90996289253235,0.3230791699975709,1739141199.4953008,38.90996289253235,1.499708617159773,1739141199.4953024,38.90996289253235,0.0,1739141199.4953036,38.90996289253235,0.32147210386291547,1739141199.4953048,38.90996289253235,4.105108182956409,1739141199.495306,38.90996289253235,1.2069980308408368 +1739141199.5152342,38.92996287345886,44.16838242223861,1739141199.515237,38.92996287345886,6.774531729058172,1739141199.5152404,38.92996287345886,65.04430008981865,1739141199.5152433,38.92996287345886,42.16477256869095,1739141199.5152445,38.92996287345886,1.6523228686654112,1739141199.5152462,38.92996287345886,-1.9436599857020045,1739141199.5152473,38.92996287345886,1.2775497446569972,1739141199.5152485,38.92996287345886,0.3230791699975709,1739141199.51525,38.92996287345886,1.499708617159773,1739141199.5152514,38.92996287345886,0.0,1739141199.5152528,38.92996287345886,0.2927105863189363,1739141199.515254,38.92996287345886,4.105108182956409,1739141199.5152552,38.92996287345886,1.2069980308408368 +1739141199.53504,38.949962854385376,44.16838242223861,1739141199.5350423,38.949962854385376,6.774531729058172,1739141199.5350451,38.949962854385376,65.04430008981865,1739141199.535048,38.949962854385376,42.16477256869095,1739141199.5350492,38.949962854385376,1.6523228686654112,1739141199.5350509,38.949962854385376,-1.9436599857020045,1739141199.535052,38.949962854385376,1.2775497446569972,1739141199.5350533,38.949962854385376,0.3230791699975709,1739141199.5350544,38.949962854385376,1.499708617159773,1739141199.5350559,38.949962854385376,0.0,1739141199.535057,38.949962854385376,0.2927105863189363,1739141199.5350585,38.949962854385376,4.105108182956409,1739141199.5350597,38.949962854385376,1.2069980308408368 +1739141199.5550146,38.96996283531189,44.16838242223861,1739141199.555017,38.96996283531189,6.774531729058172,1739141199.5550199,38.96996283531189,65.04430008981865,1739141199.5550225,38.96996283531189,42.16477256869095,1739141199.555024,38.96996283531189,1.6523228686654112,1739141199.5550256,38.96996283531189,-1.9436599857020045,1739141199.555027,38.96996283531189,1.2775497446569972,1739141199.5550282,38.96996283531189,0.3230791699975709,1739141199.5550294,38.96996283531189,1.499708617159773,1739141199.555031,38.96996283531189,0.0,1739141199.5550323,38.96996283531189,0.2927105863189363,1739141199.5550337,38.96996283531189,4.105108182956409,1739141199.5550349,38.96996283531189,1.2069980308408368 +1739141199.575094,38.9899628162384,44.16838242223861,1739141199.5750964,38.9899628162384,6.774531729058172,1739141199.5750992,38.9899628162384,65.04430008981865,1739141199.5751016,38.9899628162384,42.16477256869095,1739141199.575103,38.9899628162384,1.6523228686654112,1739141199.5751045,38.9899628162384,-1.9436599857020045,1739141199.575106,38.9899628162384,1.2775497446569972,1739141199.575107,38.9899628162384,0.3230791699975709,1739141199.5751083,38.9899628162384,1.499708617159773,1739141199.5751097,38.9899628162384,0.0,1739141199.5751112,38.9899628162384,0.2927105863189363,1739141199.575112,38.9899628162384,4.105108182956409,1739141199.5751135,38.9899628162384,1.2069980308408368 +1739141199.5951617,39.00996279716492,44.092707877535936,1739141199.595164,39.00996279716492,6.663474239280934,1739141199.5951672,39.00996279716492,65.20179927410605,1739141199.59517,39.00996279716492,42.00749225433034,1739141199.5951717,39.00996279716492,1.4524600551297877,1739141199.5951734,39.00996279716492,-1.9514366883710785,1739141199.595175,39.00996279716492,1.152715989304848,1739141199.5951765,39.00996279716492,0.280200580502034,1739141199.5951777,39.00996279716492,1.5764954851457378,1739141199.5951793,39.00996279716492,0.0,1739141199.5951807,39.00996279716492,0.3776116339216017,1739141199.5951822,39.00996279716492,4.124901657168187,1739141199.5951836,39.00996279716492,1.2393129417072166 +1739141199.6177022,39.02996277809143,44.092707877535936,1739141199.617706,39.02996277809143,6.663474239280934,1739141199.6177108,39.02996277809143,65.20179927410605,1739141199.6177166,39.02996277809143,42.00749225433034,1739141199.61772,39.02996277809143,1.4524600551297877,1739141199.617724,39.02996277809143,-1.9514366883710785,1739141199.6177275,39.02996277809143,1.152715989304848,1739141199.617731,39.02996277809143,0.280200580502034,1739141199.6177344,39.02996277809143,1.5764954851457378,1739141199.6177382,39.02996277809143,0.0,1739141199.6177418,39.02996277809143,0.33718254343852117,1739141199.6177454,39.02996277809143,4.124901657168187,1739141199.617749,39.02996277809143,1.2393129417072166 +1739141199.6349201,39.049962759017944,44.092707877535936,1739141199.6349223,39.049962759017944,6.663474239280934,1739141199.634925,39.049962759017944,65.20179927410605,1739141199.634927,39.049962759017944,42.00749225433034,1739141199.6349287,39.049962759017944,1.4524600551297877,1739141199.6349301,39.049962759017944,-1.9514366883710785,1739141199.6349316,39.049962759017944,1.152715989304848,1739141199.6349325,39.049962759017944,0.280200580502034,1739141199.634934,39.049962759017944,1.5764954851457378,1739141199.6349354,39.049962759017944,0.0,1739141199.6349368,39.049962759017944,0.33718254343852117,1739141199.6349378,39.049962759017944,4.124901657168187,1739141199.6349392,39.049962759017944,1.2393129417072166 +1739141199.655283,39.06996273994446,44.092707877535936,1739141199.6552856,39.06996273994446,6.663474239280934,1739141199.655301,39.06996273994446,65.20179927410605,1739141199.6553037,39.06996273994446,42.00749225433034,1739141199.655305,39.06996273994446,1.4524600551297877,1739141199.6553068,39.06996273994446,-1.9514366883710785,1739141199.655308,39.06996273994446,1.152715989304848,1739141199.6553092,39.06996273994446,0.280200580502034,1739141199.6553104,39.06996273994446,1.5764954851457378,1739141199.6553118,39.06996273994446,0.0,1739141199.6553133,39.06996273994446,0.33718254343852117,1739141199.6553142,39.06996273994446,4.124901657168187,1739141199.6553154,39.06996273994446,1.2393129417072166 +1739141199.674946,39.08996272087097,44.092707877535936,1739141199.674948,39.08996272087097,6.663474239280934,1739141199.674951,39.08996272087097,65.20179927410605,1739141199.6749537,39.08996272087097,42.00749225433034,1739141199.674955,39.08996272087097,1.4524600551297877,1739141199.6749566,39.08996272087097,-1.9514366883710785,1739141199.6749578,39.08996272087097,1.152715989304848,1739141199.6749592,39.08996272087097,0.280200580502034,1739141199.6749604,39.08996272087097,1.5764954851457378,1739141199.6749616,39.08996272087097,0.0,1739141199.674963,39.08996272087097,0.33718254343852117,1739141199.674964,39.08996272087097,4.124901657168187,1739141199.6749651,39.08996272087097,1.2393129417072166 +1739141199.694903,39.109962701797485,44.092707877535936,1739141199.694905,39.109962701797485,6.663474239280934,1739141199.694908,39.109962701797485,65.20179927410605,1739141199.6949103,39.109962701797485,42.00749225433034,1739141199.6949117,39.109962701797485,1.4524600551297877,1739141199.6949134,39.109962701797485,-1.9514366883710785,1739141199.6949146,39.109962701797485,1.152715989304848,1739141199.6949155,39.109962701797485,0.280200580502034,1739141199.694917,39.109962701797485,1.5764954851457378,1739141199.6949182,39.109962701797485,0.0,1739141199.6949193,39.109962701797485,0.33718254343852117,1739141199.6949208,39.109962701797485,4.124901657168187,1739141199.694922,39.109962701797485,1.2393129417072166 +1739141199.715237,39.129962682724,44.0170693039257,1739141199.7152393,39.129962682724,6.547751761805358,1739141199.7152417,39.129962682724,65.32909684146301,1739141199.7152443,39.129962682724,41.84459713073912,1739141199.7152457,39.129962682724,1.2755971307391132,1739141199.7152474,39.129962682724,-1.9616603915267288,1739141199.7152486,39.129962682724,1.010150995356254,1739141199.71525,39.129962682724,0.23809333945127545,1739141199.7152512,39.129962682724,1.6690094950547225,1739141199.7152526,39.129962682724,0.0,1739141199.715254,39.129962682724,0.4417242569690669,1739141199.7152553,39.129962682724,4.143434364088499,1739141199.7152567,39.129962682724,1.2770670313017152 +1739141199.7348368,39.14996266365051,44.0170693039257,1739141199.734839,39.14996266365051,6.547751761805358,1739141199.7348418,39.14996266365051,65.32909684146301,1739141199.7348444,39.14996266365051,41.84459713073912,1739141199.7348459,39.14996266365051,1.2755971307391132,1739141199.7348475,39.14996266365051,-1.9616603915267288,1739141199.734849,39.14996266365051,1.010150995356254,1739141199.7348504,39.14996266365051,0.23809333945127545,1739141199.7348514,39.14996266365051,1.6690094950547225,1739141199.7348528,39.14996266365051,0.0,1739141199.7348542,39.14996266365051,0.39194246375300734,1739141199.7348554,39.14996266365051,4.143434364088499,1739141199.7348566,39.14996266365051,1.2770670313017152 +1739141199.7550209,39.169962644577026,44.0170693039257,1739141199.755023,39.169962644577026,6.547751761805358,1739141199.755026,39.169962644577026,65.32909684146301,1739141199.7550287,39.169962644577026,41.84459713073912,1739141199.7550302,39.169962644577026,1.2755971307391132,1739141199.7550318,39.169962644577026,-1.9616603915267288,1739141199.755033,39.169962644577026,1.010150995356254,1739141199.7550344,39.169962644577026,0.23809333945127545,1739141199.7550356,39.169962644577026,1.6690094950547225,1739141199.755037,39.169962644577026,0.0,1739141199.7550387,39.169962644577026,0.39194246375300734,1739141199.7550397,39.169962644577026,4.143434364088499,1739141199.7550411,39.169962644577026,1.2770670313017152 +1739141199.7749128,39.18996262550354,44.0170693039257,1739141199.774915,39.18996262550354,6.547751761805358,1739141199.7749178,39.18996262550354,65.32909684146301,1739141199.7749207,39.18996262550354,41.84459713073912,1739141199.774922,39.18996262550354,1.2755971307391132,1739141199.7749236,39.18996262550354,-1.9616603915267288,1739141199.774925,39.18996262550354,1.010150995356254,1739141199.7749264,39.18996262550354,0.23809333945127545,1739141199.7749274,39.18996262550354,1.6690094950547225,1739141199.7749288,39.18996262550354,0.0,1739141199.7749305,39.18996262550354,0.39194246375300734,1739141199.7749317,39.18996262550354,4.143434364088499,1739141199.774933,39.18996262550354,1.2770670313017152 +1739141199.7949443,39.209962606430054,44.0170693039257,1739141199.7949467,39.209962606430054,6.547751761805358,1739141199.7949493,39.209962606430054,65.32909684146301,1739141199.7949522,39.209962606430054,41.84459713073912,1739141199.7949538,39.209962606430054,1.2755971307391132,1739141199.794955,39.209962606430054,-1.9616603915267288,1739141199.7949564,39.209962606430054,1.010150995356254,1739141199.7949579,39.209962606430054,0.23809333945127545,1739141199.7949588,39.209962606430054,1.6690094950547225,1739141199.7949605,39.209962606430054,0.0,1739141199.794962,39.209962606430054,0.39194246375300734,1739141199.794963,39.209962606430054,4.143434364088499,1739141199.7949643,39.209962606430054,1.2770670313017152 +1739141199.8150196,39.22996258735657,43.94118121402655,1739141199.8150218,39.22996258735657,6.426958623482234,1739141199.8150244,39.22996258735657,65.46724161642908,1739141199.815027,39.22996258735657,41.65008891706186,1739141199.8150284,39.22996258735657,1.0910017016008633,1739141199.81503,39.22996258735657,-1.9763613821633006,1739141199.8150315,39.22996258735657,0.8451543899549349,1739141199.8150327,39.22996258735657,0.19221841550109794,1739141199.8150342,39.22996258735657,1.7828781129572588,1739141199.8150358,39.22996258735657,0.0,1739141199.8150373,39.22996258735657,0.5265342071305408,1739141199.8150384,39.22996258735657,4.160765169583577,1739141199.8150396,39.22996258735657,1.3204352442133958 +1739141199.8352714,39.24996256828308,43.94118121402655,1739141199.8352747,39.24996256828308,6.426958623482234,1739141199.835278,39.24996256828308,65.46724161642908,1739141199.8352814,39.24996256828308,41.65008891706186,1739141199.8352833,39.24996256828308,1.0910017016008633,1739141199.835285,39.24996256828308,-1.9763613821633006,1739141199.8352866,39.24996256828308,0.8451543899549349,1739141199.8352885,39.24996256828308,0.19221841550109794,1739141199.83529,39.24996256828308,1.7828781129572588,1739141199.8352919,39.24996256828308,0.0,1739141199.8352938,39.24996256828308,0.4624428687438631,1739141199.835295,39.24996256828308,4.160765169583577,1739141199.8352966,39.24996256828308,1.3204352442133958 +1739141199.8557506,39.269962549209595,43.94118121402655,1739141199.855754,39.269962549209595,6.426958623482234,1739141199.8557575,39.269962549209595,65.46724161642908,1739141199.8557608,39.269962549209595,41.65008891706186,1739141199.8557627,39.269962549209595,1.0910017016008633,1739141199.8557646,39.269962549209595,-1.9763613821633006,1739141199.8557665,39.269962549209595,0.8451543899549349,1739141199.855768,39.269962549209595,0.19221841550109794,1739141199.8557696,39.269962549209595,1.7828781129572588,1739141199.855772,39.269962549209595,0.0,1739141199.8557734,39.269962549209595,0.4624428687438631,1739141199.8557749,39.269962549209595,4.160765169583577,1739141199.8557768,39.269962549209595,1.3204352442133958 +1739141199.8754196,39.28996253013611,43.94118121402655,1739141199.8754222,39.28996253013611,6.426958623482234,1739141199.8754258,39.28996253013611,65.46724161642908,1739141199.8754294,39.28996253013611,41.65008891706186,1739141199.8754308,39.28996253013611,1.0910017016008633,1739141199.875433,39.28996253013611,-1.9763613821633006,1739141199.8754346,39.28996253013611,0.8451543899549349,1739141199.8754363,39.28996253013611,0.19221841550109794,1739141199.8754377,39.28996253013611,1.7828781129572588,1739141199.8754396,39.28996253013611,0.0,1739141199.8754413,39.28996253013611,0.4624428687438631,1739141199.875443,39.28996253013611,4.160765169583577,1739141199.8754444,39.28996253013611,1.3204352442133958 +1739141199.8953743,39.30996251106262,43.94118121402655,1739141199.8953774,39.30996251106262,6.426958623482234,1739141199.8953807,39.30996251106262,65.46724161642908,1739141199.895384,39.30996251106262,41.65008891706186,1739141199.8953855,39.30996251106262,1.0910017016008633,1739141199.8953876,39.30996251106262,-1.9763613821633006,1739141199.895389,39.30996251106262,0.8451543899549349,1739141199.8953907,39.30996251106262,0.19221841550109794,1739141199.8953922,39.30996251106262,1.7828781129572588,1739141199.8953943,39.30996251106262,0.0,1739141199.895396,39.30996251106262,0.4624428687438631,1739141199.8953977,39.30996251106262,4.160765169583577,1739141199.895399,39.30996251106262,1.3204352442133958 +1739141199.9156606,39.329962491989136,43.94118121402655,1739141199.9156642,39.329962491989136,6.426958623482234,1739141199.9156675,39.329962491989136,65.46724161642908,1739141199.9156709,39.329962491989136,41.65008891706186,1739141199.9156723,39.329962491989136,1.0910017016008633,1739141199.9156744,39.329962491989136,-1.9763613821633006,1739141199.9156759,39.329962491989136,0.8451543899549349,1739141199.9156775,39.329962491989136,0.19221841550109794,1739141199.915679,39.329962491989136,1.7828781129572588,1739141199.915681,39.329962491989136,0.0,1739141199.9156826,39.329962491989136,0.4624428687438631,1739141199.9156845,39.329962491989136,4.160765169583577,1739141199.915686,39.329962491989136,1.3204352442133958 +1739141199.9354198,39.34996247291565,43.86461550613445,1739141199.9354227,39.34996247291565,6.300413564423421,1739141199.935426,39.34996247291565,65.55988914048714,1739141199.9354293,39.34996247291565,41.457636030860606,1739141199.935431,39.34996247291565,0.9339027788724614,1739141199.9354331,39.34996247291565,-1.9924175701795865,1739141199.9354348,39.34996247291565,0.6679680644385806,1739141199.9354362,39.34996247291565,0.14817518543927075,1739141199.935438,39.34996247291565,1.9138243278744023,1739141199.9354398,39.34996247291565,0.0,1739141199.9354415,39.34996247291565,0.6132605958819588,1739141199.935443,39.34996247291565,4.176952686027693,1739141199.9354448,39.34996247291565,1.3723817331725279 +1739141199.9563084,39.36996245384216,43.86461550613445,1739141199.9563112,39.36996245384216,6.300413564423421,1739141199.9563148,39.36996245384216,65.55988914048714,1739141199.9563181,39.36996245384216,41.457636030860606,1739141199.9563198,39.36996245384216,0.9339027788724614,1739141199.956322,39.36996245384216,-1.9924175701795865,1739141199.9563239,39.36996245384216,0.6679680644385806,1739141199.9563253,39.36996245384216,0.14817518543927075,1739141199.9563267,39.36996245384216,1.9138243278744023,1739141199.9563286,39.36996245384216,0.0,1739141199.9563303,39.36996245384216,0.5414425947018744,1739141199.9563317,39.36996245384216,4.176952686027693,1739141199.9563334,39.36996245384216,1.3723817331725279 +1739141199.9754982,39.38996243476868,43.86461550613445,1739141199.975501,39.38996243476868,6.300413564423421,1739141199.9755044,39.38996243476868,65.55988914048714,1739141199.9755075,39.38996243476868,41.457636030860606,1739141199.975509,39.38996243476868,0.9339027788724614,1739141199.975511,39.38996243476868,-1.9924175701795865,1739141199.9755125,39.38996243476868,0.6679680644385806,1739141199.9755142,39.38996243476868,0.14817518543927075,1739141199.9755156,39.38996243476868,1.9138243278744023,1739141199.975518,39.38996243476868,0.0,1739141199.9755194,39.38996243476868,0.5414425947018744,1739141199.975521,39.38996243476868,4.176952686027693,1739141199.9755225,39.38996243476868,1.3723817331725279 +1739141199.9956458,39.40996241569519,43.86461550613445,1739141199.9956486,39.40996241569519,6.300413564423421,1739141199.9956517,39.40996241569519,65.55988914048714,1739141199.995655,39.40996241569519,41.457636030860606,1739141199.995657,39.40996241569519,0.9339027788724614,1739141199.995659,39.40996241569519,-1.9924175701795865,1739141199.9956608,39.40996241569519,0.6679680644385806,1739141199.9956625,39.40996241569519,0.14817518543927075,1739141199.995664,39.40996241569519,1.9138243278744023,1739141199.9956656,39.40996241569519,0.0,1739141199.9956675,39.40996241569519,0.5414425947018744,1739141199.995669,39.40996241569519,4.176952686027693,1739141199.9956706,39.40996241569519,1.3723817331725279 +1739141200.0156646,39.429962396621704,43.86461550613445,1739141200.0156682,39.429962396621704,6.300413564423421,1739141200.015672,39.429962396621704,65.55988914048714,1739141200.0156755,39.429962396621704,41.457636030860606,1739141200.0156775,39.429962396621704,0.9339027788724614,1739141200.0156798,39.429962396621704,-1.9924175701795865,1739141200.0156817,39.429962396621704,0.6679680644385806,1739141200.015684,39.429962396621704,0.14817518543927075,1739141200.0156858,39.429962396621704,1.9138243278744023,1739141200.015688,39.429962396621704,0.0,1739141200.0156903,39.429962396621704,0.5414425947018744,1739141200.0156925,39.429962396621704,4.176952686027693,1739141200.0156949,39.429962396621704,1.3723817331725279 +1739141200.0356221,39.44996237754822,43.786986478032574,1739141200.0356252,39.44996237754822,6.167444892068881,1739141200.0356286,39.44996237754822,65.79675620640356,1739141200.0356317,39.44996237754822,41.11259556318811,1739141200.035633,39.44996237754822,0.7007573379128628,1739141200.0356352,39.44996237754822,-2.0257795618049,1739141200.0356371,39.44996237754822,0.3974820734160307,1739141200.0356388,39.44996237754822,0.0824011486205437,1739141200.0356402,39.44996237754822,2.1325061887885077,1739141200.0356421,39.44996237754822,0.0,1739141200.0356438,39.44996237754822,0.8445129181842539,1739141200.0356455,39.44996237754822,4.192046253744036,1739141200.035647,39.44996237754822,1.4323125443563123 +1739141200.0556178,39.46996235847473,43.786986478032574,1739141200.055621,39.46996235847473,6.167444892068881,1739141200.055624,39.46996235847473,65.79675620640356,1739141200.0556273,39.46996235847473,41.11259556318811,1739141200.0556288,39.46996235847473,0.7007573379128628,1739141200.055631,39.46996235847473,-2.0257795618049,1739141200.0556328,39.46996235847473,0.3974820734160307,1739141200.0556345,39.46996235847473,0.0824011486205437,1739141200.0556357,39.46996235847473,2.1325061887885077,1739141200.0556378,39.46996235847473,0.0,1739141200.0556393,39.46996235847473,0.7001936444321955,1739141200.055641,39.46996235847473,4.192046253744036,1739141200.0556424,39.46996235847473,1.4323125443563123 +1739141200.075462,39.489962339401245,43.786986478032574,1739141200.075465,39.489962339401245,6.167444892068881,1739141200.0754683,39.489962339401245,65.79675620640356,1739141200.0754714,39.489962339401245,41.11259556318811,1739141200.0754728,39.489962339401245,0.7007573379128628,1739141200.075475,39.489962339401245,-2.0257795618049,1739141200.0754764,39.489962339401245,0.3974820734160307,1739141200.075478,39.489962339401245,0.0824011486205437,1739141200.0754793,39.489962339401245,2.1325061887885077,1739141200.0754812,39.489962339401245,0.0,1739141200.075483,39.489962339401245,0.7001936444321955,1739141200.0754848,39.489962339401245,4.192046253744036,1739141200.0754862,39.489962339401245,1.4323125443563123 +1739141200.0955284,39.50996232032776,43.786986478032574,1739141200.0955312,39.50996232032776,6.167444892068881,1739141200.0955348,39.50996232032776,65.79675620640356,1739141200.0955384,39.50996232032776,41.11259556318811,1739141200.0955403,39.50996232032776,0.7007573379128628,1739141200.095542,39.50996232032776,-2.0257795618049,1739141200.0955436,39.50996232032776,0.3974820734160307,1739141200.095545,39.50996232032776,0.0824011486205437,1739141200.0955467,39.50996232032776,2.1325061887885077,1739141200.0955484,39.50996232032776,0.0,1739141200.09555,39.50996232032776,0.7001936444321955,1739141200.0955515,39.50996232032776,4.192046253744036,1739141200.095553,39.50996232032776,1.4323125443563123 +1739141200.1157115,39.52996230125427,43.786986478032574,1739141200.115715,39.52996230125427,6.167444892068881,1739141200.1157184,39.52996230125427,65.79675620640356,1739141200.1157217,39.52996230125427,41.11259556318811,1739141200.1157234,39.52996230125427,0.7007573379128628,1739141200.1157253,39.52996230125427,-2.0257795618049,1739141200.1157272,39.52996230125427,0.3974820734160307,1739141200.1157286,39.52996230125427,0.0824011486205437,1739141200.1157303,39.52996230125427,2.1325061887885077,1739141200.115732,39.52996230125427,0.0,1739141200.115734,39.52996230125427,0.7001936444321955,1739141200.1157355,39.52996230125427,4.192046253744036,1739141200.1157372,39.52996230125427,1.4323125443563123 +1739141200.1353786,39.549962282180786,43.786986478032574,1739141200.1353815,39.549962282180786,6.167444892068881,1739141200.135385,39.549962282180786,65.79675620640356,1739141200.1353881,39.549962282180786,41.11259556318811,1739141200.1353898,39.549962282180786,0.7007573379128628,1739141200.135392,39.549962282180786,-2.0257795618049,1739141200.1353936,39.549962282180786,0.3974820734160307,1739141200.135395,39.549962282180786,0.0824011486205437,1739141200.1353967,39.549962282180786,2.1325061887885077,1739141200.1353984,39.549962282180786,0.0,1739141200.1354003,39.549962282180786,0.7001936444321955,1739141200.1354017,39.549962282180786,4.192046253744036,1739141200.1354032,39.549962282180786,1.4323125443563123 +1739141200.1557074,39.5699622631073,43.707526881451564,1739141200.1557107,39.5699622631073,6.026651398397647,1739141200.1557143,39.5699622631073,65.92584480774802,1739141200.1557176,39.5699622631073,40.787229101024806,1739141200.1557193,39.5699622631073,0.5296616208448169,1739141200.1557212,39.5699622631073,-2.059133393609223,1739141200.1557229,39.5699622631073,0.11173522132675576,1739141200.1557243,39.5699622631073,0.022147635005677173,1739141200.1557257,39.5699622631073,2.390724942909924,1739141200.1557276,39.5699622631073,0.0,1739141200.1557293,39.5699622631073,1.0412277272208061,1739141200.155731,39.5699622631073,4.206100221623138,1739141200.1557324,39.5699622631073,1.5118944790939368 +1739141200.1754003,39.58996224403381,43.707526881451564,1739141200.175403,39.58996224403381,6.026651398397647,1739141200.175406,39.58996224403381,65.92584480774802,1739141200.1754093,39.58996224403381,40.787229101024806,1739141200.175411,39.58996224403381,0.5296616208448169,1739141200.175413,39.58996224403381,-2.059133393609223,1739141200.1754146,39.58996224403381,0.11173522132675576,1739141200.175416,39.58996224403381,0.022147635005677173,1739141200.1754177,39.58996224403381,2.390724942909924,1739141200.1754193,39.58996224403381,0.0,1739141200.1754212,39.58996224403381,0.8788304638159872,1739141200.175423,39.58996224403381,4.206100221623138,1739141200.1754246,39.58996224403381,1.5118944790939368 +1739141200.1954076,39.60996222496033,43.707526881451564,1739141200.1954107,39.60996222496033,6.026651398397647,1739141200.195414,39.60996222496033,65.92584480774802,1739141200.1954172,39.60996222496033,40.787229101024806,1739141200.1954186,39.60996222496033,0.5296616208448169,1739141200.1954207,39.60996222496033,-2.059133393609223,1739141200.1954222,39.60996222496033,0.11173522132675576,1739141200.1954238,39.60996222496033,0.022147635005677173,1739141200.1954253,39.60996222496033,2.390724942909924,1739141200.1954272,39.60996222496033,0.0,1739141200.1954288,39.60996222496033,0.8788304638159872,1739141200.1954305,39.60996222496033,4.206100221623138,1739141200.195432,39.60996222496033,1.5118944790939368 +1739141200.215728,39.62996220588684,43.707526881451564,1739141200.2157314,39.62996220588684,6.026651398397647,1739141200.215735,39.62996220588684,65.92584480774802,1739141200.215738,39.62996220588684,40.787229101024806,1739141200.21574,39.62996220588684,0.5296616208448169,1739141200.2157419,39.62996220588684,-2.059133393609223,1739141200.2157435,39.62996220588684,0.11173522132675576,1739141200.215745,39.62996220588684,0.022147635005677173,1739141200.2157466,39.62996220588684,2.390724942909924,1739141200.2157485,39.62996220588684,0.0,1739141200.2157505,39.62996220588684,0.8788304638159872,1739141200.215752,39.62996220588684,4.206100221623138,1739141200.2157538,39.62996220588684,1.5118944790939368 +1739141200.235405,39.649962186813354,43.707526881451564,1739141200.235408,39.649962186813354,6.026651398397647,1739141200.2354114,39.649962186813354,65.92584480774802,1739141200.2354145,39.649962186813354,40.787229101024806,1739141200.2354162,39.649962186813354,0.5296616208448169,1739141200.235418,39.649962186813354,-2.059133393609223,1739141200.23542,39.649962186813354,0.11173522132675576,1739141200.2354214,39.649962186813354,0.022147635005677173,1739141200.2354233,39.649962186813354,2.390724942909924,1739141200.235425,39.649962186813354,0.0,1739141200.235427,39.649962186813354,0.8788304638159872,1739141200.2354283,39.649962186813354,4.206100221623138,1739141200.23543,39.649962186813354,1.5118944790939368 +1739141200.2558057,39.66996216773987,43.62544270533802,1739141200.2558088,39.66996216773987,5.876469647373165,1739141200.2558122,39.66996216773987,66.10996097516846,1739141200.2558155,39.66996216773987,40.3464304233996,1739141200.255817,39.66996216773987,0.35413170724022974,1739141200.255819,39.66996216773987,-2.1066241835537447,1739141200.2558205,39.66996216773987,-0.2735374588549557,1739141200.2558222,39.66996216773987,-0.05092510858814811,1739141200.2558236,39.66996216773987,2.240895915840681,1739141200.2558255,39.66996216773987,0.0,1739141200.2558272,39.66996216773987,0.40789076853453576,1739141200.2558286,39.66996216773987,4.2191646964126175,1739141200.2558303,39.66996216773987,1.6087480375268493 +1739141200.2755177,39.68996214866638,43.62544270533802,1739141200.2755208,39.68996214866638,5.876469647373165,1739141200.2755244,39.68996214866638,66.10996097516846,1739141200.2755275,39.68996214866638,40.3464304233996,1739141200.275529,39.68996214866638,0.35413170724022974,1739141200.275531,39.68996214866638,-2.1066241835537447,1739141200.2755325,39.68996214866638,-0.2735374588549557,1739141200.2755342,39.68996214866638,-0.05092510858814811,1739141200.2755356,39.68996214866638,2.240895915840681,1739141200.2755377,39.68996214866638,0.0,1739141200.2755392,39.68996214866638,0.6321478783138319,1739141200.2755408,39.68996214866638,4.2191646964126175,1739141200.2755423,39.68996214866638,1.6087480375268493 +1739141200.2954786,39.709962129592896,43.62544270533802,1739141200.2954812,39.709962129592896,5.876469647373165,1739141200.2954853,39.709962129592896,66.10996097516846,1739141200.295488,39.709962129592896,40.3464304233996,1739141200.2954898,39.709962129592896,0.35413170724022974,1739141200.2954917,39.709962129592896,-2.1066241835537447,1739141200.2954934,39.709962129592896,-0.2735374588549557,1739141200.2954948,39.709962129592896,-0.05092510858814811,1739141200.2954962,39.709962129592896,2.240895915840681,1739141200.295498,39.709962129592896,0.0,1739141200.2954998,39.709962129592896,0.6321478783138319,1739141200.2955012,39.709962129592896,4.2191646964126175,1739141200.295503,39.709962129592896,1.6087480375268493 +1739141200.3156624,39.72996211051941,43.62544270533802,1739141200.315666,39.72996211051941,5.876469647373165,1739141200.3156698,39.72996211051941,66.10996097516846,1739141200.315673,39.72996211051941,40.3464304233996,1739141200.3156745,39.72996211051941,0.35413170724022974,1739141200.3156767,39.72996211051941,-2.1066241835537447,1739141200.3156781,39.72996211051941,-0.2735374588549557,1739141200.3156798,39.72996211051941,-0.05092510858814811,1739141200.3156812,39.72996211051941,2.240895915840681,1739141200.3156831,39.72996211051941,0.0,1739141200.3156846,39.72996211051941,0.6321478783138319,1739141200.3156865,39.72996211051941,4.2191646964126175,1739141200.315688,39.72996211051941,1.6087480375268493 +1739141200.3354814,39.74996209144592,43.62544270533802,1739141200.3354845,39.74996209144592,5.876469647373165,1739141200.3354878,39.74996209144592,66.10996097516846,1739141200.3354912,39.74996209144592,40.3464304233996,1739141200.3354928,39.74996209144592,0.35413170724022974,1739141200.335495,39.74996209144592,-2.1066241835537447,1739141200.3354964,39.74996209144592,-0.2735374588549557,1739141200.335498,39.74996209144592,-0.05092510858814811,1739141200.3354995,39.74996209144592,2.240895915840681,1739141200.3355012,39.74996209144592,0.0,1739141200.335503,39.74996209144592,0.6321478783138319,1739141200.3355045,39.74996209144592,4.2191646964126175,1739141200.335506,39.74996209144592,1.6087480375268493 +1739141200.355746,39.76996207237244,43.62544270533802,1739141200.3557496,39.76996207237244,5.876469647373165,1739141200.3557532,39.76996207237244,66.10996097516846,1739141200.3557563,39.76996207237244,40.3464304233996,1739141200.3557577,39.76996207237244,0.35413170724022974,1739141200.3557599,39.76996207237244,-2.1066241835537447,1739141200.3557618,39.76996207237244,-0.2735374588549557,1739141200.3557632,39.76996207237244,-0.05092510858814811,1739141200.3557646,39.76996207237244,2.240895915840681,1739141200.3557665,39.76996207237244,0.0,1739141200.3557682,39.76996207237244,0.6321478783138319,1739141200.3557699,39.76996207237244,4.2191646964126175,1739141200.3557713,39.76996207237244,1.6087480375268493 +1739141200.375427,39.78996205329895,43.54110870894473,1739141200.3754299,39.78996205329895,5.717442882123281,1739141200.3754334,39.78996205329895,66.32507162358121,1739141200.3754365,39.78996205329895,39.95536570528092,1739141200.3754385,39.78996205329895,0.23299921818693017,1739141200.3754404,39.78996205329895,-2.1498400184429625,1739141200.375442,39.78996205329895,-0.6406156446222973,1739141200.3754435,39.78996205329895,-0.11453000727720136,1739141200.375445,39.78996205329895,1.9348783843186173,1739141200.3754468,39.78996205329895,0.0,1739141200.3754482,39.78996205329895,-0.07577638736351838,1739141200.3754501,39.78996205329895,4.23126668615399,1739141200.3754513,39.78996205329895,1.6735478101027896 +1739141200.3953931,39.809962034225464,43.54110870894473,1739141200.3953958,39.809962034225464,5.717442882123281,1739141200.395399,39.809962034225464,66.32507162358121,1739141200.3954024,39.809962034225464,39.95536570528092,1739141200.395404,39.809962034225464,0.23299921818693017,1739141200.395406,39.809962034225464,-2.1498400184429625,1739141200.3954077,39.809962034225464,-0.6406156446222973,1739141200.395409,39.809962034225464,-0.11453000727720136,1739141200.3954108,39.809962034225464,1.9348783843186173,1739141200.3954124,39.809962034225464,0.0,1739141200.395414,39.809962034225464,0.2613305742158276,1739141200.3954155,39.809962034225464,4.23126668615399,1739141200.395417,39.809962034225464,1.6735478101027896 +1739141200.4155881,39.82996201515198,43.54110870894473,1739141200.4155917,39.82996201515198,5.717442882123281,1739141200.4155953,39.82996201515198,66.32507162358121,1739141200.4155986,39.82996201515198,39.95536570528092,1739141200.4156003,39.82996201515198,0.23299921818693017,1739141200.4156022,39.82996201515198,-2.1498400184429625,1739141200.4156039,39.82996201515198,-0.6406156446222973,1739141200.4156055,39.82996201515198,-0.11453000727720136,1739141200.415607,39.82996201515198,1.9348783843186173,1739141200.4156091,39.82996201515198,0.0,1739141200.4156106,39.82996201515198,0.2613305742158276,1739141200.4156122,39.82996201515198,4.23126668615399,1739141200.4156137,39.82996201515198,1.6735478101027896 +1739141200.4352832,39.84996199607849,43.54110870894473,1739141200.435286,39.84996199607849,5.717442882123281,1739141200.4352899,39.84996199607849,66.32507162358121,1739141200.435293,39.84996199607849,39.95536570528092,1739141200.4352946,39.84996199607849,0.23299921818693017,1739141200.4352968,39.84996199607849,-2.1498400184429625,1739141200.4352982,39.84996199607849,-0.6406156446222973,1739141200.4353,39.84996199607849,-0.11453000727720136,1739141200.4353013,39.84996199607849,1.9348783843186173,1739141200.4353034,39.84996199607849,0.0,1739141200.4353049,39.84996199607849,0.2613305742158276,1739141200.4353065,39.84996199607849,4.23126668615399,1739141200.435308,39.84996199607849,1.6735478101027896 +1739141200.4555876,39.869961977005005,43.54110870894473,1739141200.4555912,39.869961977005005,5.717442882123281,1739141200.4555948,39.869961977005005,66.32507162358121,1739141200.4555984,39.869961977005005,39.95536570528092,1739141200.4555998,39.869961977005005,0.23299921818693017,1739141200.4556017,39.869961977005005,-2.1498400184429625,1739141200.4556034,39.869961977005005,-0.6406156446222973,1739141200.455605,39.869961977005005,-0.11453000727720136,1739141200.4556065,39.869961977005005,1.9348783843186173,1739141200.4556084,39.869961977005005,0.0,1739141200.4556098,39.869961977005005,0.2613305742158276,1739141200.4556115,39.869961977005005,4.23126668615399,1739141200.455613,39.869961977005005,1.6735478101027896 +1739141200.4753013,39.88996195793152,43.4561969959988,1739141200.4753041,39.88996195793152,5.552725080569026,1739141200.4753075,39.88996195793152,66.41515871647941,1739141200.4753108,39.88996195793152,39.79365571776996,1739141200.4753125,39.88996195793152,0.19234495048337033,1739141200.4753144,39.88996195793152,-2.170199830550355,1739141200.4753163,39.88996195793152,-0.8378066968064508,1739141200.4753177,39.88996195793152,-0.15252984371728256,1739141200.4753194,39.88996195793152,1.788125837431592,1739141200.475321,39.88996195793152,0.0,1739141200.475323,39.88996195793152,-0.06762256144262427,1739141200.4753244,39.88996195793152,4.242395765913909,1739141200.4753256,39.88996195793152,1.699103970309932 +1739141200.4957073,39.90996193885803,43.4561969959988,1739141200.4957104,39.90996193885803,5.552725080569026,1739141200.4957137,39.90996193885803,66.41515871647941,1739141200.495717,39.90996193885803,39.79365571776996,1739141200.495719,39.90996193885803,0.19234495048337033,1739141200.4957206,39.90996193885803,-2.170199830550355,1739141200.4957225,39.90996193885803,-0.8378066968064508,1739141200.495724,39.90996193885803,-0.15252984371728256,1739141200.4957254,39.90996193885803,1.788125837431592,1739141200.4957273,39.90996193885803,0.0,1739141200.4957292,39.90996193885803,0.08902186712166005,1739141200.4957306,39.90996193885803,4.242395765913909,1739141200.4957323,39.90996193885803,1.699103970309932 +1739141200.5155928,39.929961919784546,43.4561969959988,1739141200.515596,39.929961919784546,5.552725080569026,1739141200.5155997,39.929961919784546,66.41515871647941,1739141200.5156033,39.929961919784546,39.79365571776996,1739141200.515605,39.929961919784546,0.19234495048337033,1739141200.515607,39.929961919784546,-2.170199830550355,1739141200.5156085,39.929961919784546,-0.8378066968064508,1739141200.5156102,39.929961919784546,-0.15252984371728256,1739141200.515612,39.929961919784546,1.788125837431592,1739141200.5156138,39.929961919784546,0.0,1739141200.5156155,39.929961919784546,0.08902186712166005,1739141200.5156171,39.929961919784546,4.242395765913909,1739141200.5156186,39.929961919784546,1.699103970309932 +1739141200.5353565,39.94996190071106,43.4561969959988,1739141200.5353591,39.94996190071106,5.552725080569026,1739141200.5353627,39.94996190071106,66.41515871647941,1739141200.535366,39.94996190071106,39.79365571776996,1739141200.5353677,39.94996190071106,0.19234495048337033,1739141200.5353696,39.94996190071106,-2.170199830550355,1739141200.5353715,39.94996190071106,-0.8378066968064508,1739141200.5353732,39.94996190071106,-0.15252984371728256,1739141200.5353749,39.94996190071106,1.788125837431592,1739141200.5353765,39.94996190071106,0.0,1739141200.5353782,39.94996190071106,0.08902186712166005,1739141200.5353796,39.94996190071106,4.242395765913909,1739141200.535381,39.94996190071106,1.699103970309932 +1739141200.555562,39.96996188163757,43.4561969959988,1739141200.5555654,39.96996188163757,5.552725080569026,1739141200.555569,39.96996188163757,66.41515871647941,1739141200.5555723,39.96996188163757,39.79365571776996,1739141200.5555737,39.96996188163757,0.19234495048337033,1739141200.5555756,39.96996188163757,-2.170199830550355,1739141200.5555773,39.96996188163757,-0.8378066968064508,1739141200.555579,39.96996188163757,-0.15252984371728256,1739141200.5555804,39.96996188163757,1.788125837431592,1739141200.5555823,39.96996188163757,0.0,1739141200.555584,39.96996188163757,0.08902186712166005,1739141200.5555856,39.96996188163757,4.242395765913909,1739141200.555587,39.96996188163757,1.699103970309932 +1739141200.5753806,39.98996186256409,43.4561969959988,1739141200.5753832,39.98996186256409,5.552725080569026,1739141200.5753865,39.98996186256409,66.41515871647941,1739141200.5753899,39.98996186256409,39.79365571776996,1739141200.5753918,39.98996186256409,0.19234495048337033,1739141200.5753937,39.98996186256409,-2.170199830550355,1739141200.5753953,39.98996186256409,-0.8378066968064508,1739141200.5753968,39.98996186256409,-0.15252984371728256,1739141200.5753984,39.98996186256409,1.788125837431592,1739141200.5754,39.98996186256409,0.0,1739141200.575402,39.98996186256409,0.08902186712166005,1739141200.5754032,39.98996186256409,4.242395765913909,1739141200.5754051,39.98996186256409,1.699103970309932 +1739141200.5955467,40.0099618434906,43.372250234104555,1739141200.5955493,40.0099618434906,5.385523014662864,1739141200.5955527,40.0099618434906,66.6524648922828,1739141200.5955558,40.0099618434906,39.54248245535014,1739141200.5955577,40.0099618434906,0.13700311618752767,1739141200.5955596,40.0099618434906,-2.2011687513769616,1739141200.5955613,40.0099618434906,-1.10250070100376,1739141200.5955627,40.0099618434906,-0.20027967106340408,1739141200.5955644,40.0099618434906,1.6084813154117472,1739141200.595566,40.0099618434906,0.0,1739141200.5955677,40.0099618434906,-0.2666188681471101,1739141200.5955691,40.0099618434906,4.252529255029305,1739141200.5955708,40.0099618434906,1.7057473678793602 +1739141200.6156826,40.029961824417114,43.372250234104555,1739141200.615686,40.029961824417114,5.385523014662864,1739141200.61569,40.029961824417114,66.6524648922828,1739141200.6156936,40.029961824417114,39.54248245535014,1739141200.615695,40.029961824417114,0.13700311618752767,1739141200.6156971,40.029961824417114,-2.2011687513769616,1739141200.615699,40.029961824417114,-1.10250070100376,1739141200.6157005,40.029961824417114,-0.20027967106340408,1739141200.615702,40.029961824417114,1.6084813154117472,1739141200.6157038,40.029961824417114,0.0,1739141200.6157055,40.029961824417114,-0.097266052467613,1739141200.6157074,40.029961824417114,4.252529255029305,1739141200.6157088,40.029961824417114,1.7057473678793602 +1739141200.635308,40.04996180534363,43.372250234104555,1739141200.635311,40.04996180534363,5.385523014662864,1739141200.6353142,40.04996180534363,66.6524648922828,1739141200.6353173,40.04996180534363,39.54248245535014,1739141200.635319,40.04996180534363,0.13700311618752767,1739141200.635321,40.04996180534363,-2.2011687513769616,1739141200.6353226,40.04996180534363,-1.10250070100376,1739141200.6353242,40.04996180534363,-0.20027967106340408,1739141200.6353257,40.04996180534363,1.6084813154117472,1739141200.6353276,40.04996180534363,0.0,1739141200.6353292,40.04996180534363,-0.097266052467613,1739141200.635331,40.04996180534363,4.252529255029305,1739141200.6353326,40.04996180534363,1.7057473678793602 +1739141200.6556492,40.06996178627014,43.372250234104555,1739141200.6556525,40.06996178627014,5.385523014662864,1739141200.655656,40.06996178627014,66.6524648922828,1739141200.6556597,40.06996178627014,39.54248245535014,1739141200.6556616,40.06996178627014,0.13700311618752767,1739141200.6556633,40.06996178627014,-2.2011687513769616,1739141200.655665,40.06996178627014,-1.10250070100376,1739141200.6556666,40.06996178627014,-0.20027967106340408,1739141200.6556683,40.06996178627014,1.6084813154117472,1739141200.6556702,40.06996178627014,0.0,1739141200.6556718,40.06996178627014,-0.097266052467613,1739141200.6556735,40.06996178627014,4.252529255029305,1739141200.6556752,40.06996178627014,1.7057473678793602 +1739141200.6752875,40.089961767196655,43.372250234104555,1739141200.6752903,40.089961767196655,5.385523014662864,1739141200.675294,40.089961767196655,66.6524648922828,1739141200.6752973,40.089961767196655,39.54248245535014,1739141200.675299,40.089961767196655,0.13700311618752767,1739141200.6753008,40.089961767196655,-2.2011687513769616,1739141200.6753027,40.089961767196655,-1.10250070100376,1739141200.675304,40.089961767196655,-0.20027967106340408,1739141200.6753054,40.089961767196655,1.6084813154117472,1739141200.6753073,40.089961767196655,0.0,1739141200.675309,40.089961767196655,-0.097266052467613,1739141200.6753106,40.089961767196655,4.252529255029305,1739141200.675312,40.089961767196655,1.7057473678793602 +1739141200.6953838,40.10996174812317,43.29000162341231,1739141200.6953864,40.10996174812317,5.21767666266868,1739141200.6953897,40.10996174812317,66.37183281244695,1739141200.695393,40.10996174812317,39.8546356737996,1739141200.6953945,40.10996174812317,0.20721458629845205,1739141200.6953967,40.10996174812317,-2.1718185652880564,1739141200.695398,40.10996174812317,-0.909567458359792,1739141200.6953998,40.10996174812317,-0.1890246221167401,1739141200.6954012,40.10996174812317,1.7375285822376707,1739141200.695403,40.10996174812317,0.0,1739141200.6954048,40.10996174812317,0.17415214898225728,1739141200.6954062,40.10996174812317,4.261653157245606,1739141200.6954076,40.10996174812317,1.6926232604150266 +1739141200.715511,40.12996172904968,43.29000162341231,1739141200.7155151,40.12996172904968,5.21767666266868,1739141200.7155187,40.12996172904968,66.37183281244695,1739141200.715522,40.12996172904968,39.8546356737996,1739141200.7155235,40.12996172904968,0.20721458629845205,1739141200.7155259,40.12996172904968,-2.1718185652880564,1739141200.7155278,40.12996172904968,-0.909567458359792,1739141200.7155292,40.12996172904968,-0.1890246221167401,1739141200.7155306,40.12996172904968,1.7375285822376707,1739141200.7155328,40.12996172904968,0.0,1739141200.7155347,40.12996172904968,0.04490532182264406,1739141200.715536,40.12996172904968,4.261653157245606,1739141200.7155375,40.12996172904968,1.6926232604150266 +1739141200.7353919,40.149961709976196,43.29000162341231,1739141200.7353945,40.149961709976196,5.21767666266868,1739141200.735398,40.149961709976196,66.37183281244695,1739141200.7354012,40.149961709976196,39.8546356737996,1739141200.735403,40.149961709976196,0.20721458629845205,1739141200.735405,40.149961709976196,-2.1718185652880564,1739141200.7354066,40.149961709976196,-0.909567458359792,1739141200.735408,40.149961709976196,-0.1890246221167401,1739141200.7354097,40.149961709976196,1.7375285822376707,1739141200.7354116,40.149961709976196,0.0,1739141200.7354136,40.149961709976196,0.04490532182264406,1739141200.735415,40.149961709976196,4.261653157245606,1739141200.735417,40.149961709976196,1.6926232604150266 +1739141200.7555637,40.16996169090271,43.29000162341231,1739141200.7555668,40.16996169090271,5.21767666266868,1739141200.755571,40.16996169090271,66.37183281244695,1739141200.7555742,40.16996169090271,39.8546356737996,1739141200.7555761,40.16996169090271,0.20721458629845205,1739141200.755578,40.16996169090271,-2.1718185652880564,1739141200.7555802,40.16996169090271,-0.909567458359792,1739141200.7555816,40.16996169090271,-0.1890246221167401,1739141200.7555833,40.16996169090271,1.7375285822376707,1739141200.7555852,40.16996169090271,0.0,1739141200.755587,40.16996169090271,0.04490532182264406,1739141200.7555883,40.16996169090271,4.261653157245606,1739141200.75559,40.16996169090271,1.6926232604150266 +1739141200.775283,40.189961671829224,43.29000162341231,1739141200.7752862,40.189961671829224,5.21767666266868,1739141200.7752895,40.189961671829224,66.37183281244695,1739141200.7752926,40.189961671829224,39.8546356737996,1739141200.7752943,40.189961671829224,0.20721458629845205,1739141200.7752962,40.189961671829224,-2.1718185652880564,1739141200.7752979,40.189961671829224,-0.909567458359792,1739141200.7752993,40.189961671829224,-0.1890246221167401,1739141200.775301,40.189961671829224,1.7375285822376707,1739141200.7753026,40.189961671829224,0.0,1739141200.7753046,40.189961671829224,0.04490532182264406,1739141200.775306,40.189961671829224,4.261653157245606,1739141200.775308,40.189961671829224,1.6926232604150266 +1739141200.795418,40.20996165275574,43.29000162341231,1739141200.7954211,40.20996165275574,5.21767666266868,1739141200.7954245,40.20996165275574,66.37183281244695,1739141200.7954276,40.20996165275574,39.8546356737996,1739141200.7954295,40.20996165275574,0.20721458629845205,1739141200.7954319,40.20996165275574,-2.1718185652880564,1739141200.7954335,40.20996165275574,-0.909567458359792,1739141200.795435,40.20996165275574,-0.1890246221167401,1739141200.7954366,40.20996165275574,1.7375285822376707,1739141200.7954383,40.20996165275574,0.0,1739141200.7954402,40.20996165275574,0.04490532182264406,1739141200.7954416,40.20996165275574,4.261653157245606,1739141200.7954433,40.20996165275574,1.6926232604150266 +1739141200.8157103,40.22996163368225,43.20931331412669,1739141200.8157136,40.22996163368225,5.04933628726646,1739141200.8157172,40.22996163368225,66.16584629390996,1739141200.8157206,40.22996163368225,40.03191984905173,1739141200.815722,40.22996163368225,0.25461450428683696,1739141200.8157241,40.22996163368225,-2.156037796393094,1739141200.8157258,40.22996163368225,-0.8175342496995792,1739141200.8157275,40.22996163368225,-0.18952011701289354,1739141200.815729,40.22996163368225,1.8026846608341192,1739141200.8157306,40.22996163368225,0.0,1739141200.8157325,40.22996163368225,0.15500791158472602,1739141200.815734,40.22996163368225,4.269761567236672,1739141200.8157356,40.22996163368225,1.7001065800889947 +1739141200.8355217,40.249961614608765,43.20931331412669,1739141200.835526,40.249961614608765,5.04933628726646,1739141200.8355298,40.249961614608765,66.16584629390996,1739141200.8355334,40.249961614608765,40.03191984905173,1739141200.8355353,40.249961614608765,0.25461450428683696,1739141200.8355374,40.249961614608765,-2.156037796393094,1739141200.835539,40.249961614608765,-0.8175342496995792,1739141200.8355408,40.249961614608765,-0.18952011701289354,1739141200.8355427,40.249961614608765,1.8026846608341192,1739141200.8355448,40.249961614608765,0.0,1739141200.8355467,40.249961614608765,0.10257808074512442,1739141200.8355482,40.249961614608765,4.269761567236672,1739141200.83555,40.249961614608765,1.7001065800889947 +1739141200.8558536,40.26996159553528,43.20931331412669,1739141200.8558571,40.26996159553528,5.04933628726646,1739141200.8558605,40.26996159553528,66.16584629390996,1739141200.8558638,40.26996159553528,40.03191984905173,1739141200.8558657,40.26996159553528,0.25461450428683696,1739141200.8558674,40.26996159553528,-2.156037796393094,1739141200.8558693,40.26996159553528,-0.8175342496995792,1739141200.8558707,40.26996159553528,-0.18952011701289354,1739141200.8558722,40.26996159553528,1.8026846608341192,1739141200.855874,40.26996159553528,0.0,1739141200.8558755,40.26996159553528,0.10257808074512442,1739141200.8558772,40.26996159553528,4.269761567236672,1739141200.8558786,40.26996159553528,1.7001065800889947 +1739141200.8753023,40.28996157646179,43.20931331412669,1739141200.8753052,40.28996157646179,5.04933628726646,1739141200.875309,40.28996157646179,66.16584629390996,1739141200.875312,40.28996157646179,40.03191984905173,1739141200.875314,40.28996157646179,0.25461450428683696,1739141200.8753157,40.28996157646179,-2.156037796393094,1739141200.8753173,40.28996157646179,-0.8175342496995792,1739141200.8753188,40.28996157646179,-0.18952011701289354,1739141200.8753204,40.28996157646179,1.8026846608341192,1739141200.8753223,40.28996157646179,0.0,1739141200.8753242,40.28996157646179,0.10257808074512442,1739141200.8753257,40.28996157646179,4.269761567236672,1739141200.8753273,40.28996157646179,1.7001065800889947 +1739141200.8952813,40.309961557388306,43.20931331412669,1739141200.8952844,40.309961557388306,5.04933628726646,1739141200.8952878,40.309961557388306,66.16584629390996,1739141200.8952913,40.309961557388306,40.03191984905173,1739141200.895293,40.309961557388306,0.25461450428683696,1739141200.895295,40.309961557388306,-2.156037796393094,1739141200.8952968,40.309961557388306,-0.8175342496995792,1739141200.8952982,40.309961557388306,-0.18952011701289354,1739141200.8953001,40.309961557388306,1.8026846608341192,1739141200.8953018,40.309961557388306,0.0,1739141200.8953037,40.309961557388306,0.10257808074512442,1739141200.8953052,40.309961557388306,4.269761567236672,1739141200.8953068,40.309961557388306,1.7001065800889947 +1739141200.9156945,40.32996153831482,43.12952196786303,1739141200.9156976,40.32996153831482,4.879545467038193,1739141200.9157014,40.32996153831482,66.32308366704429,1739141200.9157047,40.32996153831482,39.846092508517515,1739141200.9157064,40.32996153831482,0.20510974847533014,1739141200.915709,40.32996153831482,-2.1831463715213664,1739141200.9157104,40.32996153831482,-1.0048514107894875,1739141200.915712,40.32996153831482,-0.23601086569067345,1739141200.9157135,40.32996153831482,1.6725512705008279,1739141200.9157152,40.32996153831482,0.0,1739141200.9157171,40.32996153831482,-0.1681934932711365,1739141200.9157186,40.32996153831482,4.276866741595276,1739141200.9157205,40.32996153831482,1.7118058545916979 +1739141200.9354963,40.34996151924133,43.12952196786303,1739141200.9354992,40.34996151924133,4.879545467038193,1739141200.9355028,40.34996151924133,66.32308366704429,1739141200.9355059,40.34996151924133,39.846092508517515,1739141200.9355078,40.34996151924133,0.20510974847533014,1739141200.9355094,40.34996151924133,-2.1831463715213664,1739141200.935511,40.34996151924133,-1.0048514107894875,1739141200.9355128,40.34996151924133,-0.23601086569067345,1739141200.9355142,40.34996151924133,1.6725512705008279,1739141200.9355159,40.34996151924133,0.0,1739141200.9355178,40.34996151924133,-0.039254584090870015,1739141200.9355192,40.34996151924133,4.276866741595276,1739141200.9355211,40.34996151924133,1.7118058545916979 +1739141200.955601,40.36996150016785,43.12952196786303,1739141200.9556043,40.36996150016785,4.879545467038193,1739141200.9556081,40.36996150016785,66.32308366704429,1739141200.9556115,40.36996150016785,39.846092508517515,1739141200.955613,40.36996150016785,0.20510974847533014,1739141200.9556153,40.36996150016785,-2.1831463715213664,1739141200.9556167,40.36996150016785,-1.0048514107894875,1739141200.9556184,40.36996150016785,-0.23601086569067345,1739141200.95562,40.36996150016785,1.6725512705008279,1739141200.9556222,40.36996150016785,0.0,1739141200.9556239,40.36996150016785,-0.039254584090870015,1739141200.9556255,40.36996150016785,4.276866741595276,1739141200.955627,40.36996150016785,1.7118058545916979 +1739141200.9752753,40.38996148109436,43.12952196786303,1739141200.9752781,40.38996148109436,4.879545467038193,1739141200.9752817,40.38996148109436,66.32308366704429,1739141200.9752848,40.38996148109436,39.846092508517515,1739141200.9752862,40.38996148109436,0.20510974847533014,1739141200.9752884,40.38996148109436,-2.1831463715213664,1739141200.9752898,40.38996148109436,-1.0048514107894875,1739141200.9752915,40.38996148109436,-0.23601086569067345,1739141200.975293,40.38996148109436,1.6725512705008279,1739141200.9752948,40.38996148109436,0.0,1739141200.9752967,40.38996148109436,-0.039254584090870015,1739141200.9752984,40.38996148109436,4.276866741595276,1739141200.9752998,40.38996148109436,1.7118058545916979 +1739141200.9954278,40.409961462020874,43.12952196786303,1739141200.9954307,40.409961462020874,4.879545467038193,1739141200.9954343,40.409961462020874,66.32308366704429,1739141200.9954379,40.409961462020874,39.846092508517515,1739141200.9954393,40.409961462020874,0.20510974847533014,1739141200.9954414,40.409961462020874,-2.1831463715213664,1739141200.9954429,40.409961462020874,-1.0048514107894875,1739141200.9954448,40.409961462020874,-0.23601086569067345,1739141200.9954462,40.409961462020874,1.6725512705008279,1739141200.995448,40.409961462020874,0.0,1739141200.9954498,40.409961462020874,-0.039254584090870015,1739141200.9954515,40.409961462020874,4.276866741595276,1739141200.9954531,40.409961462020874,1.7118058545916979 +1739141201.0156488,40.42996144294739,43.12952196786303,1739141201.0156524,40.42996144294739,4.879545467038193,1739141201.0156562,40.42996144294739,66.32308366704429,1739141201.0156596,40.42996144294739,39.846092508517515,1739141201.015661,40.42996144294739,0.20510974847533014,1739141201.0156631,40.42996144294739,-2.1831463715213664,1739141201.0156648,40.42996144294739,-1.0048514107894875,1739141201.0156665,40.42996144294739,-0.23601086569067345,1739141201.015668,40.42996144294739,1.6725512705008279,1739141201.01567,40.42996144294739,0.0,1739141201.0156717,40.42996144294739,-0.039254584090870015,1739141201.0156734,40.42996144294739,4.276866741595276,1739141201.0156748,40.42996144294739,1.7118058545916979 +1739141201.0359275,40.4499614238739,43.05076201809416,1739141201.0359309,40.4499614238739,4.709015943398196,1739141201.0359342,40.4499614238739,66.5264638593363,1739141201.0359373,40.4499614238739,39.66810118620982,1739141201.035939,40.4499614238739,0.1635558977449983,1739141201.035941,40.4499614238739,-2.2105651030691766,1739141201.0359423,40.4499614238739,-1.183029619277808,1739141201.035944,40.4499614238739,-0.2821757559318291,1739141201.0359454,40.4499614238739,1.5574951912005695,1739141201.0359476,40.4499614238739,0.0,1739141201.0359492,40.4499614238739,-0.2458144525969243,1739141201.035951,40.4499614238739,4.282962178794693,1739141201.0359523,40.4499614238739,1.7049477525156915 +1739141201.0555987,40.469961404800415,43.05076201809416,1739141201.0556026,40.469961404800415,4.709015943398196,1739141201.0556061,40.469961404800415,66.5264638593363,1739141201.0556092,40.469961404800415,39.66810118620982,1739141201.055611,40.469961404800415,0.1635558977449983,1739141201.055613,40.469961404800415,-2.2105651030691766,1739141201.0556145,40.469961404800415,-1.183029619277808,1739141201.055616,40.469961404800415,-0.2821757559318291,1739141201.0556176,40.469961404800415,1.5574951912005695,1739141201.0556195,40.469961404800415,0.0,1739141201.0556211,40.469961404800415,-0.14745256131512208,1739141201.0556228,40.469961404800415,4.282962178794693,1739141201.0556247,40.469961404800415,1.7049477525156915 +1739141201.0752964,40.48996138572693,43.05076201809416,1739141201.0752993,40.48996138572693,4.709015943398196,1739141201.0753028,40.48996138572693,66.5264638593363,1739141201.0753062,40.48996138572693,39.66810118620982,1739141201.075308,40.48996138572693,0.1635558977449983,1739141201.07531,40.48996138572693,-2.2105651030691766,1739141201.0753117,40.48996138572693,-1.183029619277808,1739141201.075313,40.48996138572693,-0.2821757559318291,1739141201.0753148,40.48996138572693,1.5574951912005695,1739141201.0753164,40.48996138572693,0.0,1739141201.075318,40.48996138572693,-0.14745256131512208,1739141201.0753195,40.48996138572693,4.282962178794693,1739141201.0753212,40.48996138572693,1.7049477525156915 +1739141201.095403,40.50996136665344,43.05076201809416,1739141201.0954058,40.50996136665344,4.709015943398196,1739141201.0954094,40.50996136665344,66.5264638593363,1739141201.0954125,40.50996136665344,39.66810118620982,1739141201.0954142,40.50996136665344,0.1635558977449983,1739141201.095416,40.50996136665344,-2.2105651030691766,1739141201.0954182,40.50996136665344,-1.183029619277808,1739141201.0954194,40.50996136665344,-0.2821757559318291,1739141201.0954208,40.50996136665344,1.5574951912005695,1739141201.0954227,40.50996136665344,0.0,1739141201.0954242,40.50996136665344,-0.14745256131512208,1739141201.0954258,40.50996136665344,4.282962178794693,1739141201.0954273,40.50996136665344,1.7049477525156915 +1739141201.115557,40.529961347579956,43.05076201809416,1739141201.1155603,40.529961347579956,4.709015943398196,1739141201.1155639,40.529961347579956,66.5264638593363,1739141201.1155674,40.529961347579956,39.66810118620982,1739141201.1155689,40.529961347579956,0.1635558977449983,1739141201.1155708,40.529961347579956,-2.2105651030691766,1739141201.1155725,40.529961347579956,-1.183029619277808,1739141201.1155741,40.529961347579956,-0.2821757559318291,1739141201.1155753,40.529961347579956,1.5574951912005695,1739141201.115577,40.529961347579956,0.0,1739141201.1155787,40.529961347579956,-0.14745256131512208,1739141201.11558,40.529961347579956,4.282962178794693,1739141201.1155818,40.529961347579956,1.7049477525156915 +1739141201.1355336,40.54996132850647,42.97349204716573,1739141201.1355364,40.54996132850647,4.539209451833013,1739141201.1355398,40.54996132850647,66.76678498881574,1739141201.135543,40.54996132850647,39.486911625409796,1739141201.1355445,40.54996132850647,0.12546391541511615,1739141201.1355467,40.54996132850647,-2.2393710350107248,1739141201.1355484,40.54996132850647,-1.360008408542845,1739141201.13555,40.54996132850647,-0.32881989621669344,1739141201.1355512,40.54996132850647,1.4510499073575218,1739141201.1355534,40.54996132850647,0.0,1739141201.1355548,40.54996132850647,-0.31556444502917536,1739141201.1355565,40.54996132850647,4.288026109250623,1739141201.135558,40.54996132850647,1.6865610344374944 +1739141201.1552422,40.56996130943298,42.97349204716573,1739141201.1552448,40.56996130943298,4.539209451833013,1739141201.155248,40.56996130943298,66.76678498881574,1739141201.1552508,40.56996130943298,39.486911625409796,1739141201.1552522,40.56996130943298,0.12546391541511615,1739141201.1552536,40.56996130943298,-2.2393710350107248,1739141201.155255,40.56996130943298,-1.360008408542845,1739141201.1552563,40.56996130943298,-0.32881989621669344,1739141201.1552577,40.56996130943298,1.4510499073575218,1739141201.1552591,40.56996130943298,0.0,1739141201.1552606,40.56996130943298,-0.23551112707997257,1739141201.155262,40.56996130943298,4.288026109250623,1739141201.1552632,40.56996130943298,1.6865610344374944 +1739141201.1751406,40.5899612903595,42.97349204716573,1739141201.175143,40.5899612903595,4.539209451833013,1739141201.1751456,40.5899612903595,66.76678498881574,1739141201.1751482,40.5899612903595,39.486911625409796,1739141201.1751497,40.5899612903595,0.12546391541511615,1739141201.1751509,40.5899612903595,-2.2393710350107248,1739141201.175152,40.5899612903595,-1.360008408542845,1739141201.1751537,40.5899612903595,-0.32881989621669344,1739141201.175155,40.5899612903595,1.4510499073575218,1739141201.175156,40.5899612903595,0.0,1739141201.1751578,40.5899612903595,-0.23551112707997257,1739141201.1751587,40.5899612903595,4.288026109250623,1739141201.1751606,40.5899612903595,1.6865610344374944 +1739141201.1950302,40.60996127128601,42.97349204716573,1739141201.1950324,40.60996127128601,4.539209451833013,1739141201.1950352,40.60996127128601,66.76678498881574,1739141201.1950376,40.60996127128601,39.486911625409796,1739141201.195039,40.60996127128601,0.12546391541511615,1739141201.1950405,40.60996127128601,-2.2393710350107248,1739141201.195042,40.60996127128601,-1.360008408542845,1739141201.1950433,40.60996127128601,-0.32881989621669344,1739141201.1950443,40.60996127128601,1.4510499073575218,1739141201.195046,40.60996127128601,0.0,1739141201.1950471,40.60996127128601,-0.23551112707997257,1739141201.1950483,40.60996127128601,4.288026109250623,1739141201.1950498,40.60996127128601,1.6865610344374944 +1739141201.2153995,40.629961252212524,42.97349204716573,1739141201.2154021,40.629961252212524,4.539209451833013,1739141201.215405,40.629961252212524,66.76678498881574,1739141201.215408,40.629961252212524,39.486911625409796,1739141201.2154098,40.629961252212524,0.12546391541511615,1739141201.2154114,40.629961252212524,-2.2393710350107248,1739141201.215413,40.629961252212524,-1.360008408542845,1739141201.2154143,40.629961252212524,-0.32881989621669344,1739141201.2154155,40.629961252212524,1.4510499073575218,1739141201.2154171,40.629961252212524,0.0,1739141201.2154186,40.629961252212524,-0.23551112707997257,1739141201.21542,40.629961252212524,4.288026109250623,1739141201.2154214,40.629961252212524,1.6865610344374944 +1739141201.2354534,40.64996123313904,42.97349204716573,1739141201.2354562,40.64996123313904,4.539209451833013,1739141201.2354598,40.64996123313904,66.76678498881574,1739141201.2354631,40.64996123313904,39.486911625409796,1739141201.2354648,40.64996123313904,0.12546391541511615,1739141201.2354665,40.64996123313904,-2.2393710350107248,1739141201.2354684,40.64996123313904,-1.360008408542845,1739141201.2354696,40.64996123313904,-0.32881989621669344,1739141201.235471,40.64996123313904,1.4510499073575218,1739141201.235473,40.64996123313904,0.0,1739141201.2354746,40.64996123313904,-0.23551112707997257,1739141201.235476,40.64996123313904,4.288026109250623,1739141201.2354774,40.64996123313904,1.6865610344374944 +1739141201.2555664,40.66996121406555,42.898130540571586,1739141201.2555692,40.66996121406555,4.37156352144941,1739141201.2555728,40.66996121406555,66.95674750890913,1739141201.2555761,40.66996121406555,39.40137208086985,1739141201.2555776,40.66996121406555,0.1086714395270115,1739141201.2555795,40.66996121406555,-2.2577804440932137,1739141201.255581,40.66996121406555,-1.4526986424245467,1739141201.2555826,40.66996121406555,-0.36518821139443824,1739141201.2555838,40.66996121406555,1.3982357661458122,1739141201.255586,40.66996121406555,0.0,1739141201.2555873,40.66996121406555,-0.27092940390527936,1739141201.2555888,40.66996121406555,4.292029099398755,1739141201.2555904,40.66996121406555,1.6522993155185715 +1739141201.275546,40.689961194992065,42.898130540571586,1739141201.275549,40.689961194992065,4.37156352144941,1739141201.2755523,40.689961194992065,66.95674750890913,1739141201.2755554,40.689961194992065,39.40137208086985,1739141201.2755568,40.689961194992065,0.1086714395270115,1739141201.275559,40.689961194992065,-2.2577804440932137,1739141201.2755604,40.689961194992065,-1.4526986424245467,1739141201.275562,40.689961194992065,-0.36518821139443824,1739141201.2755635,40.689961194992065,1.3982357661458122,1739141201.2755654,40.689961194992065,0.0,1739141201.2755668,40.689961194992065,-0.2540635493727592,1739141201.2755685,40.689961194992065,4.292029099398755,1739141201.2755697,40.689961194992065,1.6522993155185715 +1739141201.2954743,40.70996117591858,42.898130540571586,1739141201.295477,40.70996117591858,4.37156352144941,1739141201.2954805,40.70996117591858,66.95674750890913,1739141201.2954836,40.70996117591858,39.40137208086985,1739141201.2954853,40.70996117591858,0.1086714395270115,1739141201.295487,40.70996117591858,-2.2577804440932137,1739141201.2954886,40.70996117591858,-1.4526986424245467,1739141201.29549,40.70996117591858,-0.36518821139443824,1739141201.2954917,40.70996117591858,1.3982357661458122,1739141201.2954934,40.70996117591858,0.0,1739141201.2954953,40.70996117591858,-0.2540635493727592,1739141201.2954967,40.70996117591858,4.292029099398755,1739141201.2954981,40.70996117591858,1.6522993155185715 +1739141201.3156965,40.72996115684509,42.898130540571586,1739141201.3156993,40.72996115684509,4.37156352144941,1739141201.3157027,40.72996115684509,66.95674750890913,1739141201.3157058,40.72996115684509,39.40137208086985,1739141201.3157074,40.72996115684509,0.1086714395270115,1739141201.3157094,40.72996115684509,-2.2577804440932137,1739141201.3157113,40.72996115684509,-1.4526986424245467,1739141201.3157125,40.72996115684509,-0.36518821139443824,1739141201.3157141,40.72996115684509,1.3982357661458122,1739141201.3157158,40.72996115684509,0.0,1739141201.315718,40.72996115684509,-0.2540635493727592,1739141201.3157194,40.72996115684509,4.292029099398755,1739141201.315721,40.72996115684509,1.6522993155185715 +1739141201.335523,40.749961137771606,42.898130540571586,1739141201.335526,40.749961137771606,4.37156352144941,1739141201.3355293,40.749961137771606,66.95674750890913,1739141201.3355322,40.749961137771606,39.40137208086985,1739141201.335534,40.749961137771606,0.1086714395270115,1739141201.3355362,40.749961137771606,-2.2577804440932137,1739141201.3355377,40.749961137771606,-1.4526986424245467,1739141201.3355389,40.749961137771606,-0.36518821139443824,1739141201.3355405,40.749961137771606,1.3982357661458122,1739141201.3355422,40.749961137771606,0.0,1739141201.3355439,40.749961137771606,-0.2540635493727592,1739141201.3355453,40.749961137771606,4.292029099398755,1739141201.335547,40.749961137771606,1.6522993155185715 +1739141201.3557556,40.76996111869812,42.82488524013349,1739141201.3557591,40.76996111869812,4.2070823738587375,1739141201.3557625,40.76996111869812,67.15738682362483,1739141201.3557656,40.76996111869812,39.304316087201315,1739141201.355767,40.76996111869812,0.09024676635024682,1739141201.355769,40.76996111869812,-2.2782806664808417,1739141201.3557706,40.76996111869812,-1.5491913924447185,1739141201.355772,40.76996111869812,-0.40303405593932173,1739141201.3557734,40.76996111869812,1.3452961502774148,1739141201.355775,40.76996111869812,0.0,1739141201.3557768,40.76996111869812,-0.2903166355376815,1739141201.3557782,40.76996111869812,4.294946725399292,1739141201.35578,40.76996111869812,1.6183494028270335 +1739141201.3756313,40.789961099624634,42.82488524013349,1739141201.3756344,40.789961099624634,4.2070823738587375,1739141201.3756378,40.789961099624634,67.15738682362483,1739141201.375641,40.789961099624634,39.304316087201315,1739141201.3756425,40.789961099624634,0.09024676635024682,1739141201.3756444,40.789961099624634,-2.2782806664808417,1739141201.3756459,40.789961099624634,-1.5491913924447185,1739141201.3756475,40.789961099624634,-0.40303405593932173,1739141201.3756487,40.789961099624634,1.3452961502774148,1739141201.3756506,40.789961099624634,0.0,1739141201.3756523,40.789961099624634,-0.27305325254961876,1739141201.375654,40.789961099624634,4.294946725399292,1739141201.3756552,40.789961099624634,1.6183494028270335 +1739141201.3955216,40.80996108055115,42.82488524013349,1739141201.3955243,40.80996108055115,4.2070823738587375,1739141201.3955276,40.80996108055115,67.15738682362483,1739141201.3955305,40.80996108055115,39.304316087201315,1739141201.3955321,40.80996108055115,0.09024676635024682,1739141201.3955338,40.80996108055115,-2.2782806664808417,1739141201.3955355,40.80996108055115,-1.5491913924447185,1739141201.395537,40.80996108055115,-0.40303405593932173,1739141201.3955383,40.80996108055115,1.3452961502774148,1739141201.3955402,40.80996108055115,0.0,1739141201.3955417,40.80996108055115,-0.27305325254961876,1739141201.3955433,40.80996108055115,4.294946725399292,1739141201.3955448,40.80996108055115,1.6183494028270335 +1739141201.415679,40.82996106147766,42.82488524013349,1739141201.415682,40.82996106147766,4.2070823738587375,1739141201.4156857,40.82996106147766,67.15738682362483,1739141201.4156888,40.82996106147766,39.304316087201315,1739141201.41569,40.82996106147766,0.09024676635024682,1739141201.415692,40.82996106147766,-2.2782806664808417,1739141201.4156935,40.82996106147766,-1.5491913924447185,1739141201.4156952,40.82996106147766,-0.40303405593932173,1739141201.4156964,40.82996106147766,1.3452961502774148,1739141201.4156985,40.82996106147766,0.0,1739141201.4157002,40.82996106147766,-0.27305325254961876,1739141201.4157019,40.82996106147766,4.294946725399292,1739141201.4157033,40.82996106147766,1.6183494028270335 +1739141201.4354455,40.849961042404175,42.82488524013349,1739141201.4354484,40.849961042404175,4.2070823738587375,1739141201.4354522,40.849961042404175,67.15738682362483,1739141201.435455,40.849961042404175,39.304316087201315,1739141201.4354568,40.849961042404175,0.09024676635024682,1739141201.4354587,40.849961042404175,-2.2782806664808417,1739141201.43546,40.849961042404175,-1.5491913924447185,1739141201.4354615,40.849961042404175,-0.40303405593932173,1739141201.4354632,40.849961042404175,1.3452961502774148,1739141201.4354649,40.849961042404175,0.0,1739141201.4354668,40.849961042404175,-0.27305325254961876,1739141201.4354682,40.849961042404175,4.294946725399292,1739141201.4354696,40.849961042404175,1.6183494028270335 +1739141201.4557023,40.86996102333069,42.82488524013349,1739141201.455706,40.86996102333069,4.2070823738587375,1739141201.455709,40.86996102333069,67.15738682362483,1739141201.4557123,40.86996102333069,39.304316087201315,1739141201.4557137,40.86996102333069,0.09024676635024682,1739141201.455716,40.86996102333069,-2.2782806664808417,1739141201.4557173,40.86996102333069,-1.5491913924447185,1739141201.455719,40.86996102333069,-0.40303405593932173,1739141201.4557204,40.86996102333069,1.3452961502774148,1739141201.4557223,40.86996102333069,0.0,1739141201.4557238,40.86996102333069,-0.27305325254961876,1739141201.4557252,40.86996102333069,4.294946725399292,1739141201.4557269,40.86996102333069,1.6183494028270335 +1739141201.4754417,40.8899610042572,42.753542243018416,1739141201.4754446,40.8899610042572,4.045825836463239,1739141201.475448,40.8899610042572,67.46947395877814,1739141201.475451,40.8899610042572,39.096128723479616,1739141201.4754524,40.8899610042572,0.055021453913269604,1739141201.4754548,40.8899610042572,-2.31263140870489,1739141201.475456,40.8899610042572,-1.7346374371091768,1739141201.4754574,40.8899610042572,-0.45119375457973687,1739141201.475459,40.8899610042572,1.2491155701794519,1739141201.4754608,40.8899610042572,0.0,1739141201.4754627,40.8899610042572,-0.39244235414725226,1739141201.4754639,40.8899610042572,4.296751361191159,1739141201.4754655,40.8899610042572,1.5847059427849253 +1739141201.4954545,40.909960985183716,42.753542243018416,1739141201.4954572,40.909960985183716,4.045825836463239,1739141201.4954603,40.909960985183716,67.46947395877814,1739141201.4954634,40.909960985183716,39.096128723479616,1739141201.495465,40.909960985183716,0.055021453913269604,1739141201.4954667,40.909960985183716,-2.31263140870489,1739141201.4954684,40.909960985183716,-1.7346374371091768,1739141201.4954698,40.909960985183716,-0.45119375457973687,1739141201.495471,40.909960985183716,1.2491155701794519,1739141201.495473,40.909960985183716,0.0,1739141201.4954743,40.909960985183716,-0.3355903726054734,1739141201.495476,40.909960985183716,4.296751361191159,1739141201.4954774,40.909960985183716,1.5847059427849253 +1739141201.5155485,40.92996096611023,42.753542243018416,1739141201.5155518,40.92996096611023,4.045825836463239,1739141201.5155554,40.92996096611023,67.46947395877814,1739141201.5155587,40.92996096611023,39.096128723479616,1739141201.5155604,40.92996096611023,0.055021453913269604,1739141201.5155623,40.92996096611023,-2.31263140870489,1739141201.5155637,40.92996096611023,-1.7346374371091768,1739141201.5155654,40.92996096611023,-0.45119375457973687,1739141201.5155666,40.92996096611023,1.2491155701794519,1739141201.5155687,40.92996096611023,0.0,1739141201.5155702,40.92996096611023,-0.3355903726054734,1739141201.5155716,40.92996096611023,4.296751361191159,1739141201.5155733,40.92996096611023,1.5847059427849253 +1739141201.5355053,40.94996094703674,42.753542243018416,1739141201.535508,40.94996094703674,4.045825836463239,1739141201.535511,40.94996094703674,67.46947395877814,1739141201.5355144,40.94996094703674,39.096128723479616,1739141201.5355158,40.94996094703674,0.055021453913269604,1739141201.535518,40.94996094703674,-2.31263140870489,1739141201.5355196,40.94996094703674,-1.7346374371091768,1739141201.535521,40.94996094703674,-0.45119375457973687,1739141201.5355225,40.94996094703674,1.2491155701794519,1739141201.5355244,40.94996094703674,0.0,1739141201.5355258,40.94996094703674,-0.3355903726054734,1739141201.5355272,40.94996094703674,4.296751361191159,1739141201.5355287,40.94996094703674,1.5847059427849253 +1739141201.5557382,40.96996092796326,42.753542243018416,1739141201.5557418,40.96996092796326,4.045825836463239,1739141201.5557451,40.96996092796326,67.46947395877814,1739141201.5557485,40.96996092796326,39.096128723479616,1739141201.55575,40.96996092796326,0.055021453913269604,1739141201.555752,40.96996092796326,-2.31263140870489,1739141201.5557535,40.96996092796326,-1.7346374371091768,1739141201.5557547,40.96996092796326,-0.45119375457973687,1739141201.5557563,40.96996092796326,1.2491155701794519,1739141201.555758,40.96996092796326,0.0,1739141201.5557597,40.96996092796326,-0.3355903726054734,1739141201.555761,40.96996092796326,4.296751361191159,1739141201.5557628,40.96996092796326,1.5847059427849253 +1739141201.5754383,40.98996090888977,42.6838941887436,1739141201.5754411,40.98996090888977,3.88784982796237,1739141201.5754447,40.98996090888977,67.47205254306847,1739141201.5754478,40.98996090888977,39.1923541260384,1739141201.5754492,40.98996090888977,0.07040688598194594,1739141201.5754511,40.98996090888977,-2.3116346453475622,1739141201.5754526,40.98996090888977,-1.6561283353938168,1739141201.5754542,40.98996090888977,-0.47131886564183395,1739141201.5754557,40.98996090888977,1.288964776957355,1739141201.5754576,40.98996090888977,0.0,1739141201.5754592,40.98996090888977,-0.19586117492739286,1739141201.575461,40.98996090888977,4.297412973664053,1739141201.5754623,40.98996090888977,1.5513636983032975 +1739141201.595564,41.009960889816284,42.6838941887436,1739141201.5955665,41.009960889816284,3.88784982796237,1739141201.5955698,41.009960889816284,67.47205254306847,1739141201.5955727,41.009960889816284,39.1923541260384,1739141201.5955746,41.009960889816284,0.07040688598194594,1739141201.5955763,41.009960889816284,-2.3116346453475622,1739141201.595578,41.009960889816284,-1.6561283353938168,1739141201.5955794,41.009960889816284,-0.47131886564183395,1739141201.5955806,41.009960889816284,1.288964776957355,1739141201.5955825,41.009960889816284,0.0,1739141201.595584,41.009960889816284,-0.26239892134594256,1739141201.5955856,41.009960889816284,4.297412973664053,1739141201.595587,41.009960889816284,1.5513636983032975 +1739141201.6156423,41.0299608707428,42.6838941887436,1739141201.6156461,41.0299608707428,3.88784982796237,1739141201.6156492,41.0299608707428,67.47205254306847,1739141201.6156523,41.0299608707428,39.1923541260384,1739141201.6156542,41.0299608707428,0.07040688598194594,1739141201.615656,41.0299608707428,-2.3116346453475622,1739141201.6156578,41.0299608707428,-1.6561283353938168,1739141201.615659,41.0299608707428,-0.47131886564183395,1739141201.6156604,41.0299608707428,1.288964776957355,1739141201.6156623,41.0299608707428,0.0,1739141201.6156642,41.0299608707428,-0.26239892134594256,1739141201.6156654,41.0299608707428,4.297412973664053,1739141201.6156669,41.0299608707428,1.5513636983032975 +1739141201.6350791,41.04996085166931,42.6838941887436,1739141201.6350818,41.04996085166931,3.88784982796237,1739141201.6350844,41.04996085166931,67.47205254306847,1739141201.6350865,41.04996085166931,39.1923541260384,1739141201.635088,41.04996085166931,0.07040688598194594,1739141201.6350894,41.04996085166931,-2.3116346453475622,1739141201.6350906,41.04996085166931,-1.6561283353938168,1739141201.635092,41.04996085166931,-0.47131886564183395,1739141201.635093,41.04996085166931,1.288964776957355,1739141201.635095,41.04996085166931,0.0,1739141201.635096,41.04996085166931,-0.26239892134594256,1739141201.6350973,41.04996085166931,4.297412973664053,1739141201.6350987,41.04996085166931,1.5513636983032975 +1739141201.6552925,41.069960832595825,42.6838941887436,1739141201.6552951,41.069960832595825,3.88784982796237,1739141201.6552985,41.069960832595825,67.47205254306847,1739141201.6553013,41.069960832595825,39.1923541260384,1739141201.655303,41.069960832595825,0.07040688598194594,1739141201.655305,41.069960832595825,-2.3116346453475622,1739141201.6553063,41.069960832595825,-1.6561283353938168,1739141201.6553078,41.069960832595825,-0.47131886564183395,1739141201.655309,41.069960832595825,1.288964776957355,1739141201.6553109,41.069960832595825,0.0,1739141201.6553123,41.069960832595825,-0.26239892134594256,1739141201.6553137,41.069960832595825,4.297412973664053,1739141201.6553152,41.069960832595825,1.5513636983032975 +1739141201.6757066,41.08996081352234,42.6838941887436,1739141201.6757102,41.08996081352234,3.88784982796237,1739141201.6757138,41.08996081352234,67.47205254306847,1739141201.675717,41.08996081352234,39.1923541260384,1739141201.675719,41.08996081352234,0.07040688598194594,1739141201.6757214,41.08996081352234,-2.3116346453475622,1739141201.6757233,41.08996081352234,-1.6561283353938168,1739141201.6757247,41.08996081352234,-0.47131886564183395,1739141201.6757264,41.08996081352234,1.288964776957355,1739141201.6757283,41.08996081352234,0.0,1739141201.6757305,41.08996081352234,-0.26239892134594256,1739141201.675732,41.08996081352234,4.297412973664053,1739141201.6757338,41.08996081352234,1.5513636983032975 +1739141201.6969745,41.10996079444885,42.615659149374636,1739141201.6969795,41.10996079444885,3.733024016187768,1739141201.6969843,41.10996079444885,68.28002539125558,1739141201.6969893,41.10996079444885,38.48299856895671,1739141201.6969917,41.10996079444885,-0.018400143104328616,1739141201.6969945,41.10996079444885,-2.4045120452539304,1739141201.696997,41.10996079444885,-2.266826733305987,1739141201.696999,41.10996079444885,-0.5525138361703423,1739141201.6970012,41.10996079444885,1.0096058816912519,1739141201.697004,41.10996079444885,0.0,1739141201.6970062,41.10996079444885,-0.736640352493501,1739141201.6970086,41.10996079444885,4.296898379053646,1739141201.6970108,41.10996079444885,1.5204168684457096 +1739141201.7170606,41.129960775375366,42.615659149374636,1739141201.7170649,41.129960775375366,3.733024016187768,1739141201.7170699,41.129960775375366,68.28002539125558,1739141201.7170746,41.129960775375366,38.48299856895671,1739141201.717077,41.129960775375366,-0.018400143104328616,1739141201.7170799,41.129960775375366,-2.4045120452539304,1739141201.717082,41.129960775375366,-2.266826733305987,1739141201.7170844,41.129960775375366,-0.5525138361703423,1739141201.7170866,41.129960775375366,1.0096058816912519,1739141201.7170892,41.129960775375366,0.0,1739141201.7170918,41.129960775375366,-0.5108109867544577,1739141201.7170942,41.129960775375366,4.296898379053646,1739141201.717096,41.129960775375366,1.5204168684457096 +1739141201.7374282,41.14996075630188,42.615659149374636,1739141201.7374322,41.14996075630188,3.733024016187768,1739141201.737437,41.14996075630188,68.28002539125558,1739141201.737441,41.14996075630188,38.48299856895671,1739141201.737443,41.14996075630188,-0.018400143104328616,1739141201.7374454,41.14996075630188,-2.4045120452539304,1739141201.7374477,41.14996075630188,-2.266826733305987,1739141201.7374496,41.14996075630188,-0.5525138361703423,1739141201.7374516,41.14996075630188,1.0096058816912519,1739141201.737454,41.14996075630188,0.0,1739141201.7374558,41.14996075630188,-0.5108109867544577,1739141201.7374578,41.14996075630188,4.296898379053646,1739141201.7374597,41.14996075630188,1.5204168684457096 +1739141201.7557979,41.169960737228394,42.615659149374636,1739141201.7558007,41.169960737228394,3.733024016187768,1739141201.755804,41.169960737228394,68.28002539125558,1739141201.7558076,41.169960737228394,38.48299856895671,1739141201.7558093,41.169960737228394,-0.018400143104328616,1739141201.7558112,41.169960737228394,-2.4045120452539304,1739141201.755813,41.169960737228394,-2.266826733305987,1739141201.7558143,41.169960737228394,-0.5525138361703423,1739141201.755816,41.169960737228394,1.0096058816912519,1739141201.755818,41.169960737228394,0.0,1739141201.7558198,41.169960737228394,-0.5108109867544577,1739141201.7558212,41.169960737228394,4.296898379053646,1739141201.755823,41.169960737228394,1.5204168684457096 +1739141201.7752955,41.18996071815491,42.615659149374636,1739141201.7752984,41.18996071815491,3.733024016187768,1739141201.7753017,41.18996071815491,68.28002539125558,1739141201.7753046,41.18996071815491,38.48299856895671,1739141201.7753062,41.18996071815491,-0.018400143104328616,1739141201.775308,41.18996071815491,-2.4045120452539304,1739141201.7753093,41.18996071815491,-2.266826733305987,1739141201.7753108,41.18996071815491,-0.5525138361703423,1739141201.7753122,41.18996071815491,1.0096058816912519,1739141201.7753136,41.18996071815491,0.0,1739141201.7753153,41.18996071815491,-0.5108109867544577,1739141201.7753165,41.18996071815491,4.296898379053646,1739141201.775318,41.18996071815491,1.5204168684457096 +1739141201.7953255,41.20996069908142,42.54925112953671,1739141201.7953286,41.20996069908142,3.5827741334979635,1739141201.7953312,41.20996069908142,68.28284527134065,1739141201.7953343,41.20996069908142,38.65444830450122,1739141201.795336,41.20996069908142,-0.0020223324941926676,1739141201.7953374,41.20996069908142,-2.3976177022130454,1739141201.795339,41.20996069908142,-2.108058213388381,1739141201.7953403,41.20996069908142,-0.5708030300272223,1739141201.7953415,41.20996069908142,1.07580309364141,1739141201.7953434,41.20996069908142,0.0,1739141201.7953448,41.20996069908142,-0.27303699892911965,1739141201.7953465,41.20996069908142,4.295166616563127,1739141201.7953477,41.20996069908142,1.4620658576200023 +1739141201.815503,41.229960680007935,42.54925112953671,1739141201.8155057,41.229960680007935,3.5827741334979635,1739141201.8155096,41.229960680007935,68.28284527134065,1739141201.8155124,41.229960680007935,38.65444830450122,1739141201.8155136,41.229960680007935,-0.0020223324941926676,1739141201.815516,41.229960680007935,-2.3976177022130454,1739141201.8155174,41.229960680007935,-2.108058213388381,1739141201.8155186,41.229960680007935,-0.5708030300272223,1739141201.81552,41.229960680007935,1.07580309364141,1739141201.8155217,41.229960680007935,0.0,1739141201.8155234,41.229960680007935,-0.38626276397859227,1739141201.8155246,41.229960680007935,4.295166616563127,1739141201.8155262,41.229960680007935,1.4620658576200023 +1739141201.8352835,41.24996066093445,42.54925112953671,1739141201.8352864,41.24996066093445,3.5827741334979635,1739141201.8352892,41.24996066093445,68.28284527134065,1739141201.8352923,41.24996066093445,38.65444830450122,1739141201.835294,41.24996066093445,-0.0020223324941926676,1739141201.8352954,41.24996066093445,-2.3976177022130454,1739141201.835297,41.24996066093445,-2.108058213388381,1739141201.8352985,41.24996066093445,-0.5708030300272223,1739141201.8352997,41.24996066093445,1.07580309364141,1739141201.8353016,41.24996066093445,0.0,1739141201.8353033,41.24996066093445,-0.38626276397859227,1739141201.835305,41.24996066093445,4.295166616563127,1739141201.8353062,41.24996066093445,1.4620658576200023 +1739141201.8555105,41.26996064186096,42.54925112953671,1739141201.8555133,41.26996064186096,3.5827741334979635,1739141201.8555164,41.26996064186096,68.28284527134065,1739141201.8555193,41.26996064186096,38.65444830450122,1739141201.8555207,41.26996064186096,-0.0020223324941926676,1739141201.855523,41.26996064186096,-2.3976177022130454,1739141201.8555245,41.26996064186096,-2.108058213388381,1739141201.855526,41.26996064186096,-0.5708030300272223,1739141201.8555274,41.26996064186096,1.07580309364141,1739141201.855529,41.26996064186096,0.0,1739141201.8555307,41.26996064186096,-0.38626276397859227,1739141201.8555322,41.26996064186096,4.295166616563127,1739141201.8555336,41.26996064186096,1.4620658576200023 +1739141201.8762631,41.289960622787476,42.54925112953671,1739141201.876267,41.289960622787476,3.5827741334979635,1739141201.8762712,41.289960622787476,68.28284527134065,1739141201.8762755,41.289960622787476,38.65444830450122,1739141201.8762774,41.289960622787476,-0.0020223324941926676,1739141201.87628,41.289960622787476,-2.3976177022130454,1739141201.8762822,41.289960622787476,-2.108058213388381,1739141201.876284,41.289960622787476,-0.5708030300272223,1739141201.8762858,41.289960622787476,1.07580309364141,1739141201.876288,41.289960622787476,0.0,1739141201.87629,41.289960622787476,-0.38626276397859227,1739141201.8762918,41.289960622787476,4.295166616563127,1739141201.876294,41.289960622787476,1.4620658576200023 +1739141201.8982687,41.30996060371399,42.54925112953671,1739141201.8982737,41.30996060371399,3.5827741334979635,1739141201.8982794,41.30996060371399,68.28284527134065,1739141201.898285,41.30996060371399,38.65444830450122,1739141201.8982878,41.30996060371399,-0.0020223324941926676,1739141201.8982913,41.30996060371399,-2.3976177022130454,1739141201.8982942,41.30996060371399,-2.108058213388381,1739141201.8982968,41.30996060371399,-0.5708030300272223,1739141201.8982992,41.30996060371399,1.07580309364141,1739141201.8983028,41.30996060371399,0.0,1739141201.8983057,41.30996060371399,-0.38626276397859227,1739141201.898308,41.30996060371399,4.295166616563127,1739141201.8983107,41.30996060371399,1.4620658576200023 +1739141201.9180837,41.3299605846405,42.484552279769325,1739141201.9180884,41.3299605846405,3.4373013724353036,1739141201.9180944,41.3299605846405,68.71089584771818,1739141201.9180999,41.3299605846405,38.32466024712599,1739141201.9181025,41.3299605846405,-0.03310084161417288,1739141201.9181058,41.3299605846405,-2.4463118961999357,1739141201.9181087,41.3299605846405,-2.382125594666249,1739141201.9181113,41.3299605846405,-0.6108,1739141201.9181137,41.3299605846405,0.96410072241916,1739141201.918117,41.3299605846405,0.0,1739141201.91812,41.3299605846405,-0.537915888606174,1739141201.9181225,41.3299605846405,4.292156099887886,1739141201.9181252,41.3299605846405,1.4298008013182002 +1739141201.938028,41.34996056556702,42.484552279769325,1739141201.938033,41.34996056556702,3.4373013724353036,1739141201.9380393,41.34996056556702,68.71089584771818,1739141201.938045,41.34996056556702,38.32466024712599,1739141201.9380484,41.34996056556702,-0.03310084161417288,1739141201.938052,41.34996056556702,-2.4463118961999357,1739141201.9380543,41.34996056556702,-2.382125594666249,1739141201.9380572,41.34996056556702,-0.6108,1739141201.9380596,41.34996056556702,0.96410072241916,1739141201.938063,41.34996056556702,0.0,1739141201.938066,41.34996056556702,-0.4657000788990402,1739141201.9380684,41.34996056556702,4.292156099887886,1739141201.938071,41.34996056556702,1.4298008013182002 +1739141201.9575741,41.36996054649353,42.484552279769325,1739141201.9575787,41.36996054649353,3.4373013724353036,1739141201.9575846,41.36996054649353,68.71089584771818,1739141201.95759,41.36996054649353,38.32466024712599,1739141201.9575927,41.36996054649353,-0.03310084161417288,1739141201.957596,41.36996054649353,-2.4463118961999357,1739141201.957599,41.36996054649353,-2.382125594666249,1739141201.9576018,41.36996054649353,-0.6108,1739141201.9576044,41.36996054649353,0.96410072241916,1739141201.9576077,41.36996054649353,0.0,1739141201.9576106,41.36996054649353,-0.4657000788990402,1739141201.957613,41.36996054649353,4.292156099887886,1739141201.9576156,41.36996054649353,1.4298008013182002 +1739141201.9762654,41.389960527420044,42.484552279769325,1739141201.9762688,41.389960527420044,3.4373013724353036,1739141201.976273,41.389960527420044,68.71089584771818,1739141201.9762769,41.389960527420044,38.32466024712599,1739141201.9762788,41.389960527420044,-0.03310084161417288,1739141201.9762814,41.389960527420044,-2.4463118961999357,1739141201.976283,41.389960527420044,-2.382125594666249,1739141201.9762847,41.389960527420044,-0.6108,1739141201.9762864,41.389960527420044,0.96410072241916,1739141201.9762888,41.389960527420044,0.0,1739141201.9762905,41.389960527420044,-0.4657000788990402,1739141201.9762924,41.389960527420044,4.292156099887886,1739141201.976294,41.389960527420044,1.4298008013182002 +1739141201.995986,41.40996050834656,42.484552279769325,1739141201.9959888,41.40996050834656,3.4373013724353036,1739141201.9959917,41.40996050834656,68.71089584771818,1739141201.9959946,41.40996050834656,38.32466024712599,1739141201.995996,41.40996050834656,-0.03310084161417288,1739141201.9959977,41.40996050834656,-2.4463118961999357,1739141201.9959993,41.40996050834656,-2.382125594666249,1739141201.9960005,41.40996050834656,-0.6108,1739141201.9960017,41.40996050834656,0.96410072241916,1739141201.9960034,41.40996050834656,0.0,1739141201.9960048,41.40996050834656,-0.4657000788990402,1739141201.9960063,41.40996050834656,4.292156099887886,1739141201.9960074,41.40996050834656,1.4298008013182002 +1739141202.0214198,41.42996048927307,42.421148853608585,1739141202.0214343,41.42996048927307,3.2961107008111608,1739141202.0214553,41.42996048927307,68.95235765834246,1739141202.0214784,41.42996048927307,38.23566304344889,1739141202.0214891,41.42996048927307,-0.03979955586943839,1739141202.0214965,41.42996048927307,-2.4686722523696187,1739141202.0215018,41.42996048927307,-2.439790829078976,1739141202.0215065,41.42996048927307,-0.6108,1739141202.0215113,41.42996048927307,0.9421171964684766,1739141202.0215173,41.42996048927307,0.0,1739141202.0215228,41.42996048927307,-0.4108058738774463,1739141202.021532,41.42996048927307,4.287833166502522,1739141202.0215485,41.42996048927307,1.3790631810333807 +1739141202.0404797,41.449960470199585,42.421148853608585,1739141202.0404835,41.449960470199585,3.2961107008111608,1739141202.0404882,41.449960470199585,68.95235765834246,1739141202.0404925,41.449960470199585,38.23566304344889,1739141202.040495,41.449960470199585,-0.03979955586943839,1739141202.0404973,41.449960470199585,-2.4686722523696187,1739141202.0404994,41.449960470199585,-2.439790829078976,1739141202.0405018,41.449960470199585,-0.6108,1739141202.0405037,41.449960470199585,0.9421171964684766,1739141202.0405064,41.449960470199585,0.0,1739141202.0405087,41.449960470199585,-0.4369459845649041,1739141202.0405107,41.449960470199585,4.287833166502522,1739141202.0405128,41.449960470199585,1.3790631810333807 +1739141202.0567765,41.4699604511261,42.421148853608585,1739141202.0567808,41.4699604511261,3.2961107008111608,1739141202.056785,41.4699604511261,68.95235765834246,1739141202.056789,41.4699604511261,38.23566304344889,1739141202.0567913,41.4699604511261,-0.03979955586943839,1739141202.0567942,41.4699604511261,-2.4686722523696187,1739141202.056796,41.4699604511261,-2.439790829078976,1739141202.056798,41.4699604511261,-0.6108,1739141202.0568,41.4699604511261,0.9421171964684766,1739141202.0568025,41.4699604511261,0.0,1739141202.056805,41.4699604511261,-0.4369459845649041,1739141202.0568068,41.4699604511261,4.287833166502522,1739141202.056809,41.4699604511261,1.3790631810333807 +1739141202.076725,41.48996043205261,42.421148853608585,1739141202.0767288,41.48996043205261,3.2961107008111608,1739141202.076733,41.48996043205261,68.95235765834246,1739141202.0767372,41.48996043205261,38.23566304344889,1739141202.0767395,41.48996043205261,-0.03979955586943839,1739141202.076742,41.48996043205261,-2.4686722523696187,1739141202.0767438,41.48996043205261,-2.439790829078976,1739141202.0767462,41.48996043205261,-0.6108,1739141202.0767481,41.48996043205261,0.9421171964684766,1739141202.0767503,41.48996043205261,0.0,1739141202.0767527,41.48996043205261,-0.4369459845649041,1739141202.0767546,41.48996043205261,4.287833166502522,1739141202.0767567,41.48996043205261,1.3790631810333807 +1739141202.096844,41.509960412979126,42.421148853608585,1739141202.0968478,41.509960412979126,3.2961107008111608,1739141202.0968523,41.509960412979126,68.95235765834246,1739141202.096856,41.509960412979126,38.23566304344889,1739141202.096858,41.509960412979126,-0.03979955586943839,1739141202.0968606,41.509960412979126,-2.4686722523696187,1739141202.0968628,41.509960412979126,-2.439790829078976,1739141202.0968647,41.509960412979126,-0.6108,1739141202.0968666,41.509960412979126,0.9421171964684766,1739141202.0968688,41.509960412979126,0.0,1739141202.0968714,41.509960412979126,-0.4369459845649041,1739141202.0968735,41.509960412979126,4.287833166502522,1739141202.0968754,41.509960412979126,1.3790631810333807 +1739141202.1169045,41.52996039390564,42.421148853608585,1739141202.1169076,41.52996039390564,3.2961107008111608,1739141202.116911,41.52996039390564,68.95235765834246,1739141202.116914,41.52996039390564,38.23566304344889,1739141202.1169155,41.52996039390564,-0.03979955586943839,1739141202.1169171,41.52996039390564,-2.4686722523696187,1739141202.1169193,41.52996039390564,-2.439790829078976,1739141202.116921,41.52996039390564,-0.6108,1739141202.1169221,41.52996039390564,0.9421171964684766,1739141202.1169238,41.52996039390564,0.0,1739141202.1169257,41.52996039390564,-0.4369459845649041,1739141202.1169271,41.52996039390564,4.287833166502522,1739141202.1169286,41.52996039390564,1.3790631810333807 +1739141202.1361206,41.54996037483215,42.35929653446644,1739141202.1361227,41.54996037483215,3.160172103244676,1739141202.136125,41.54996037483215,69.11108887407964,1739141202.1361277,41.54996037483215,38.219070179303365,1739141202.1361291,41.54996037483215,-0.041198264145946975,1739141202.1361306,41.54996037483215,-2.4833858531508404,1739141202.1361318,41.54996037483215,-2.42771132344583,1739141202.136133,41.54996037483215,-0.6108,1739141202.1361341,41.54996037483215,0.9466803356766574,1739141202.1361353,41.54996037483215,0.0,1739141202.1361368,41.54996037483215,-0.3378203439894332,1739141202.136138,41.54996037483215,4.282161465102958,1739141202.1361392,41.54996037483215,1.3317033892342258 +1739141202.1581714,41.56996035575867,42.35929653446644,1739141202.1581762,41.56996035575867,3.160172103244676,1739141202.158182,41.56996035575867,69.11108887407964,1739141202.1581872,41.56996035575867,38.219070179303365,1739141202.15819,41.56996035575867,-0.041198264145946975,1739141202.158193,41.56996035575867,-2.4833858531508404,1739141202.1581957,41.56996035575867,-2.42771132344583,1739141202.158198,41.56996035575867,-0.6108,1739141202.1582003,41.56996035575867,0.9466803356766574,1739141202.1582034,41.56996035575867,0.0,1739141202.1582062,41.56996035575867,-0.3850230535575684,1739141202.1582088,41.56996035575867,4.282161465102958,1739141202.158211,41.56996035575867,1.3317033892342258 +1739141202.1786957,41.58996033668518,42.35929653446644,1739141202.1786995,41.58996033668518,3.160172103244676,1739141202.1787045,41.58996033668518,69.11108887407964,1739141202.1787088,41.58996033668518,38.219070179303365,1739141202.178711,41.58996033668518,-0.041198264145946975,1739141202.1787136,41.58996033668518,-2.4833858531508404,1739141202.178716,41.58996033668518,-2.42771132344583,1739141202.1787179,41.58996033668518,-0.6108,1739141202.17872,41.58996033668518,0.9466803356766574,1739141202.1787226,41.58996033668518,0.0,1739141202.1787248,41.58996033668518,-0.3850230535575684,1739141202.178727,41.58996033668518,4.282161465102958,1739141202.178729,41.58996033668518,1.3317033892342258 +1739141202.196262,41.609960317611694,42.35929653446644,1739141202.1962645,41.609960317611694,3.160172103244676,1739141202.1962676,41.609960317611694,69.11108887407964,1739141202.19627,41.609960317611694,38.219070179303365,1739141202.1962717,41.609960317611694,-0.041198264145946975,1739141202.196273,41.609960317611694,-2.4833858531508404,1739141202.196275,41.609960317611694,-2.42771132344583,1739141202.1962762,41.609960317611694,-0.6108,1739141202.1962776,41.609960317611694,0.9466803356766574,1739141202.196279,41.609960317611694,0.0,1739141202.1962805,41.609960317611694,-0.3850230535575684,1739141202.1962821,41.609960317611694,4.282161465102958,1739141202.1962833,41.609960317611694,1.3317033892342258 +1739141202.2168021,41.62996029853821,42.35929653446644,1739141202.2168064,41.62996029853821,3.160172103244676,1739141202.216811,41.62996029853821,69.11108887407964,1739141202.2168155,41.62996029853821,38.219070179303365,1739141202.2168176,41.62996029853821,-0.041198264145946975,1739141202.2168205,41.62996029853821,-2.4833858531508404,1739141202.2168226,41.62996029853821,-2.42771132344583,1739141202.2168248,41.62996029853821,-0.6108,1739141202.216827,41.62996029853821,0.9466803356766574,1739141202.2168295,41.62996029853821,0.0,1739141202.2168317,41.62996029853821,-0.3850230535575684,1739141202.2168336,41.62996029853821,4.282161465102958,1739141202.2168357,41.62996029853821,1.3317033892342258 +1739141202.2360487,41.64996027946472,42.298627783898134,1739141202.2360516,41.64996027946472,3.0290284488636825,1739141202.236055,41.64996027946472,69.26918086939594,1739141202.2360573,41.64996027946472,38.183118461983476,1739141202.236059,41.64996027946472,-0.044290884990668855,1739141202.2360609,41.64996027946472,-2.5001650033971594,1739141202.2360623,41.64996027946472,-2.426881284404138,1739141202.2360635,41.64996027946472,-0.6108,1739141202.2360647,41.64996027946472,0.9469947005162332,1739141202.2360663,41.64996027946472,0.0,1739141202.2360678,41.64996027946472,-0.30678172601697057,1739141202.2360911,41.64996027946472,4.275129539085201,1739141202.2360923,41.64996027946472,1.2910342201644318 +1739141202.2560036,41.669960260391235,42.298627783898134,1739141202.2560055,41.669960260391235,3.0290284488636825,1739141202.2560081,41.669960260391235,69.26918086939594,1739141202.2560108,41.669960260391235,38.183118461983476,1739141202.2560122,41.669960260391235,-0.044290884990668855,1739141202.2560136,41.669960260391235,-2.5001650033971594,1739141202.2560148,41.669960260391235,-2.426881284404138,1739141202.256016,41.669960260391235,-0.6108,1739141202.2560172,41.669960260391235,0.9469947005162332,1739141202.2560186,41.669960260391235,0.0,1739141202.25602,41.669960260391235,-0.34403951964819857,1739141202.2560213,41.669960260391235,4.275129539085201,1739141202.2560225,41.669960260391235,1.2910342201644318 +1739141202.2755268,41.68996024131775,42.298627783898134,1739141202.2755287,41.68996024131775,3.0290284488636825,1739141202.2755313,41.68996024131775,69.26918086939594,1739141202.275534,41.68996024131775,38.183118461983476,1739141202.275535,41.68996024131775,-0.044290884990668855,1739141202.2755365,41.68996024131775,-2.5001650033971594,1739141202.275538,41.68996024131775,-2.426881284404138,1739141202.275539,41.68996024131775,-0.6108,1739141202.27554,41.68996024131775,0.9469947005162332,1739141202.2755415,41.68996024131775,0.0,1739141202.2755425,41.68996024131775,-0.34403951964819857,1739141202.2755437,41.68996024131775,4.275129539085201,1739141202.275545,41.68996024131775,1.2910342201644318 +1739141202.2958896,41.70996022224426,42.298627783898134,1739141202.2958922,41.70996022224426,3.0290284488636825,1739141202.2958949,41.70996022224426,69.26918086939594,1739141202.2958975,41.70996022224426,38.183118461983476,1739141202.295899,41.70996022224426,-0.044290884990668855,1739141202.2959003,41.70996022224426,-2.5001650033971594,1739141202.2959018,41.70996022224426,-2.426881284404138,1739141202.2959027,41.70996022224426,-0.6108,1739141202.295904,41.70996022224426,0.9469947005162332,1739141202.2959056,41.70996022224426,0.0,1739141202.2959068,41.70996022224426,-0.34403951964819857,1739141202.2959082,41.70996022224426,4.275129539085201,1739141202.2959094,41.70996022224426,1.2910342201644318 +1739141202.3231432,41.729960203170776,42.298627783898134,1739141202.323152,41.729960203170776,3.0290284488636825,1739141202.323162,41.729960203170776,69.26918086939594,1739141202.323172,41.729960203170776,38.183118461983476,1739141202.323177,41.729960203170776,-0.044290884990668855,1739141202.323183,41.729960203170776,-2.5001650033971594,1739141202.323188,41.729960203170776,-2.426881284404138,1739141202.3231928,41.729960203170776,-0.6108,1739141202.3231971,41.729960203170776,0.9469947005162332,1739141202.3232028,41.729960203170776,0.0,1739141202.3232079,41.729960203170776,-0.34403951964819857,1739141202.3232129,41.729960203170776,4.275129539085201,1739141202.3232174,41.729960203170776,1.2910342201644318 +1739141202.344521,41.74996018409729,42.298627783898134,1739141202.3445299,41.74996018409729,3.0290284488636825,1739141202.34454,41.74996018409729,69.26918086939594,1739141202.3445501,41.74996018409729,38.183118461983476,1739141202.3445547,41.74996018409729,-0.044290884990668855,1739141202.3445606,41.74996018409729,-2.5001650033971594,1739141202.3445654,41.74996018409729,-2.426881284404138,1739141202.3445702,41.74996018409729,-0.6108,1739141202.3445745,41.74996018409729,0.9469947005162332,1739141202.3445804,41.74996018409729,0.0,1739141202.3445854,41.74996018409729,-0.34403951964819857,1739141202.3445902,41.74996018409729,4.275129539085201,1739141202.3445945,41.74996018409729,1.2910342201644318 +1739141202.382181,41.77996015548706,42.238675353151066,1739141202.382196,41.77996015548706,2.9019947059815348,1739141202.3822167,41.77996015548706,69.27969907590925,1739141202.3822324,41.77996015548706,38.264778442542564,1739141202.382254,41.77996015548706,-0.03760807421722626,1739141202.3822794,41.77996015548706,-2.504698108663078,1739141202.38229,41.77996015548706,-2.3186020349539005,1739141202.3822982,41.77996015548706,-0.6108,1739141202.382309,41.77996015548706,0.988911849662935,1739141202.3823307,41.77996015548706,0.0,1739141202.382339,41.77996015548706,-0.20518253105430745,1739141202.3823495,41.77996015548706,4.266723521455816,1739141202.3823612,41.77996015548706,1.260216789269175 +1739141202.3944879,41.799960136413574,42.238675353151066,1739141202.3944948,41.799960136413574,2.9019947059815348,1739141202.394502,41.799960136413574,69.27969907590925,1739141202.3945093,41.799960136413574,38.264778442542564,1739141202.3945143,41.799960136413574,-0.03760807421722626,1739141202.3945203,41.799960136413574,-2.504698108663078,1739141202.394526,41.799960136413574,-2.3186020349539005,1739141202.394531,41.799960136413574,-0.6108,1739141202.3945363,41.799960136413574,0.988911849662935,1739141202.3945415,41.799960136413574,0.0,1739141202.394547,41.799960136413574,-0.2713049396062399,1739141202.394552,41.799960136413574,4.266723521455816,1739141202.3945572,41.799960136413574,1.260216789269175 +1739141202.4225662,41.81996011734009,42.238675353151066,1739141202.4225812,41.81996011734009,2.9019947059815348,1739141202.4226015,41.81996011734009,69.27969907590925,1739141202.4226224,41.81996011734009,38.264778442542564,1739141202.4226334,41.81996011734009,-0.03760807421722626,1739141202.4226487,41.81996011734009,-2.504698108663078,1739141202.4226613,41.81996011734009,-2.3186020349539005,1739141202.422674,41.81996011734009,-0.6108,1739141202.422686,41.81996011734009,0.988911849662935,1739141202.4227,41.81996011734009,0.0,1739141202.4227128,41.81996011734009,-0.2713049396062399,1739141202.422726,41.81996011734009,4.266723521455816,1739141202.422739,41.81996011734009,1.260216789269175 +1739141202.4347072,41.8399600982666,42.238675353151066,1739141202.4347115,41.8399600982666,2.9019947059815348,1739141202.4347165,41.8399600982666,69.27969907590925,1739141202.4347208,41.8399600982666,38.264778442542564,1739141202.4347231,41.8399600982666,-0.03760807421722626,1739141202.434726,41.8399600982666,-2.504698108663078,1739141202.4347281,41.8399600982666,-2.3186020349539005,1739141202.4347305,41.8399600982666,-0.6108,1739141202.4347324,41.8399600982666,0.988911849662935,1739141202.434735,41.8399600982666,0.0,1739141202.4347377,41.8399600982666,-0.2713049396062399,1739141202.4347398,41.8399600982666,4.266723521455816,1739141202.4347417,41.8399600982666,1.260216789269175 +1739141202.4534147,41.859960079193115,42.238675353151066,1739141202.4534173,41.859960079193115,2.9019947059815348,1739141202.45342,41.859960079193115,69.27969907590925,1739141202.4534233,41.859960079193115,38.264778442542564,1739141202.453425,41.859960079193115,-0.03760807421722626,1739141202.4534264,41.859960079193115,-2.504698108663078,1739141202.453428,41.859960079193115,-2.3186020349539005,1739141202.4534292,41.859960079193115,-0.6108,1739141202.4534304,41.859960079193115,0.988911849662935,1739141202.4534323,41.859960079193115,0.0,1739141202.4534335,41.859960079193115,-0.2713049396062399,1739141202.453435,41.859960079193115,4.266723521455816,1739141202.4534361,41.859960079193115,1.260216789269175 +1739141202.4726403,41.87996006011963,42.179046770013706,1739141202.472643,41.87996006011963,2.778548839185964,1739141202.472646,41.87996006011963,69.56606314811945,1739141202.4726484,41.87996006011963,38.07078276655967,1739141202.47265,41.87996006011963,-0.05382881965813372,1739141202.4726515,41.87996006011963,-2.5379930919676377,1739141202.4726532,41.87996006011963,-2.4435589745039095,1739141202.4726543,41.87996006011963,-0.6108,1739141202.4726553,41.87996006011963,0.9406982522532905,1739141202.472657,41.87996006011963,0.0,1739141202.4726582,41.87996006011963,-0.3050008738908191,1739141202.4726593,41.87996006011963,4.25692664978525,1739141202.4726608,41.87996006011963,1.2296534351359292 +1739141202.4931157,41.89996004104614,42.179046770013706,1739141202.4931183,41.89996004104614,2.778548839185964,1739141202.493121,41.89996004104614,69.56606314811945,1739141202.4931235,41.89996004104614,38.07078276655967,1739141202.493125,41.89996004104614,-0.05382881965813372,1739141202.4931264,41.89996004104614,-2.5379930919676377,1739141202.4931278,41.89996004104614,-2.4435589745039095,1739141202.4931293,41.89996004104614,-0.6108,1739141202.4931302,41.89996004104614,0.9406982522532905,1739141202.4931319,41.89996004104614,0.0,1739141202.493133,41.89996004104614,-0.28895518288263866,1739141202.4931343,41.89996004104614,4.25692664978525,1739141202.4931357,41.89996004104614,1.2296534351359292 +1739141202.5126624,41.919960021972656,42.179046770013706,1739141202.5126655,41.919960021972656,2.778548839185964,1739141202.5126686,41.919960021972656,69.56606314811945,1739141202.5126712,41.919960021972656,38.07078276655967,1739141202.5126727,41.919960021972656,-0.05382881965813372,1739141202.5126743,41.919960021972656,-2.5379930919676377,1739141202.5126758,41.919960021972656,-2.4435589745039095,1739141202.5126772,41.919960021972656,-0.6108,1739141202.5126781,41.919960021972656,0.9406982522532905,1739141202.5126796,41.919960021972656,0.0,1739141202.5126812,41.919960021972656,-0.28895518288263866,1739141202.5126822,41.919960021972656,4.25692664978525,1739141202.5126836,41.919960021972656,1.2296534351359292 +1739141202.536225,41.93996000289917,42.179046770013706,1739141202.5362315,41.93996000289917,2.778548839185964,1739141202.5362394,41.93996000289917,69.56606314811945,1739141202.5362468,41.93996000289917,38.07078276655967,1739141202.5362506,41.93996000289917,-0.05382881965813372,1739141202.5362556,41.93996000289917,-2.5379930919676377,1739141202.5362594,41.93996000289917,-2.4435589745039095,1739141202.5362628,41.93996000289917,-0.6108,1739141202.536266,41.93996000289917,0.9406982522532905,1739141202.5362706,41.93996000289917,0.0,1739141202.5362742,41.93996000289917,-0.28895518288263866,1739141202.5362778,41.93996000289917,4.25692664978525,1739141202.536281,41.93996000289917,1.2296534351359292 +1739141202.558905,41.959959983825684,42.179046770013706,1739141202.5589118,41.959959983825684,2.778548839185964,1739141202.5589194,41.959959983825684,69.56606314811945,1739141202.5589268,41.959959983825684,38.07078276655967,1739141202.5589306,41.959959983825684,-0.05382881965813372,1739141202.558935,41.959959983825684,-2.5379930919676377,1739141202.558939,41.959959983825684,-2.4435589745039095,1739141202.5589426,41.959959983825684,-0.6108,1739141202.558946,41.959959983825684,0.9406982522532905,1739141202.5589504,41.959959983825684,0.0,1739141202.5589545,41.959959983825684,-0.28895518288263866,1739141202.558958,41.959959983825684,4.25692664978525,1739141202.5589614,41.959959983825684,1.2296534351359292 +1739141202.5846195,41.9799599647522,42.11962182600618,1739141202.5846252,41.9799599647522,2.6587325731359206,1739141202.584631,41.9799599647522,69.70888653740577,1739141202.5846367,41.9799599647522,38.01903061517814,1739141202.58464,41.9799599647522,-0.05743312561039852,1739141202.5846436,41.9799599647522,-2.5565608890177356,1739141202.5846465,41.9799599647522,-2.440078287740125,1739141202.5846488,41.9799599647522,-0.6108,1739141202.5846515,41.9799599647522,0.9420088747970196,1739141202.5846548,41.9799599647522,0.0,1739141202.5846577,41.9799599647522,-0.22858199736296914,1739141202.5846605,41.9799599647522,4.245719129806404,1739141202.5846632,41.9799599647522,1.1993400224831927 +1739141202.599958,41.99995994567871,42.11962182600618,1739141202.5999632,41.99995994567871,2.6587325731359206,1739141202.5999684,41.99995994567871,69.70888653740577,1739141202.5999742,41.99995994567871,38.01903061517814,1739141202.599977,41.99995994567871,-0.05743312561039852,1739141202.59998,41.99995994567871,-2.5565608890177356,1739141202.5999827,41.99995994567871,-2.440078287740125,1739141202.5999854,41.99995994567871,-0.6108,1739141202.5999877,41.99995994567871,0.9420088747970196,1739141202.599991,41.99995994567871,0.0,1739141202.5999942,41.99995994567871,-0.25733114768617316,1739141202.5999966,41.99995994567871,4.245719129806404,1739141202.5999992,41.99995994567871,1.1993400224831927 +1739141202.6189635,42.019959926605225,42.11962182600618,1739141202.6189687,42.019959926605225,2.6587325731359206,1739141202.6189744,42.019959926605225,69.70888653740577,1739141202.6189802,42.019959926605225,38.01903061517814,1739141202.6189833,42.019959926605225,-0.05743312561039852,1739141202.6189866,42.019959926605225,-2.5565608890177356,1739141202.6189892,42.019959926605225,-2.440078287740125,1739141202.618992,42.019959926605225,-0.6108,1739141202.6189947,42.019959926605225,0.9420088747970196,1739141202.618998,42.019959926605225,0.0,1739141202.619001,42.019959926605225,-0.25733114768617316,1739141202.6190033,42.019959926605225,4.245719129806404,1739141202.619006,42.019959926605225,1.1993400224831927 +1739141202.6439111,42.03995990753174,42.11962182600618,1739141202.6439185,42.03995990753174,2.6587325731359206,1739141202.6439278,42.03995990753174,69.70888653740577,1739141202.643939,42.03995990753174,38.01903061517814,1739141202.643945,42.03995990753174,-0.05743312561039852,1739141202.6439528,42.03995990753174,-2.5565608890177356,1739141202.64396,42.03995990753174,-2.440078287740125,1739141202.643967,42.03995990753174,-0.6108,1739141202.6439738,42.03995990753174,0.9420088747970196,1739141202.6439812,42.03995990753174,0.0,1739141202.6439888,42.03995990753174,-0.25733114768617316,1739141202.643996,42.03995990753174,4.245719129806404,1739141202.644003,42.03995990753174,1.1993400224831927 +1739141202.6613472,42.05995988845825,42.11962182600618,1739141202.6613572,42.05995988845825,2.6587325731359206,1739141202.6613696,42.05995988845825,69.70888653740577,1739141202.6613822,42.05995988845825,38.01903061517814,1739141202.6613903,42.05995988845825,-0.05743312561039852,1739141202.6613948,42.05995988845825,-2.5565608890177356,1739141202.661398,42.05995988845825,-2.440078287740125,1739141202.6614006,42.05995988845825,-0.6108,1739141202.6614032,42.05995988845825,0.9420088747970196,1739141202.6614063,42.05995988845825,0.0,1739141202.6614094,42.05995988845825,-0.25733114768617316,1739141202.6614118,42.05995988845825,4.245719129806404,1739141202.6614144,42.05995988845825,1.1993400224831927 +1739141202.6791017,42.079959869384766,42.11962182600618,1739141202.6791098,42.079959869384766,2.6587325731359206,1739141202.6791198,42.079959869384766,69.70888653740577,1739141202.6791296,42.079959869384766,38.01903061517814,1739141202.679132,42.079959869384766,-0.05743312561039852,1739141202.6791353,42.079959869384766,-2.5565608890177356,1739141202.6791375,42.079959869384766,-2.440078287740125,1739141202.6791396,42.079959869384766,-0.6108,1739141202.679142,42.079959869384766,0.9420088747970196,1739141202.6791446,42.079959869384766,0.0,1739141202.6791472,42.079959869384766,-0.25733114768617316,1739141202.6791496,42.079959869384766,4.245719129806404,1739141202.6791515,42.079959869384766,1.1993400224831927 +1739141202.699769,42.09995985031128,42.06029216801477,1739141202.699774,42.09995985031128,2.5425877596598694,1739141202.6997793,42.09995985031128,69.86541329563887,1739141202.6997857,42.09995985031128,37.9528341346295,1739141202.6997893,42.09995985031128,-0.061547031181217786,1739141202.6997938,42.09995985031128,-2.5765464794520265,1739141202.699798,42.09995985031128,-2.4436569287505066,1739141202.699802,42.09995985031128,-0.6108,1739141202.699806,42.09995985031128,0.9406613948199338,1739141202.6998103,42.09995985031128,0.0,1739141202.6998146,42.09995985031128,-0.2025019505998233,1739141202.6998188,42.09995985031128,4.233077971197378,1739141202.6998231,42.09995985031128,1.169272499932111 +1739141202.7186162,42.11995983123779,42.06029216801477,1739141202.7186208,42.11995983123779,2.5425877596598694,1739141202.7186255,42.11995983123779,69.86541329563887,1739141202.7186315,42.11995983123779,37.9528341346295,1739141202.7186346,42.11995983123779,-0.061547031181217786,1739141202.7186387,42.11995983123779,-2.5765464794520265,1739141202.7186422,42.11995983123779,-2.4436569287505066,1739141202.7186458,42.11995983123779,-0.6108,1739141202.7186494,42.11995983123779,0.9406613948199338,1739141202.7186532,42.11995983123779,0.0,1739141202.7186568,42.11995983123779,-0.22861110511217708,1739141202.7186604,42.11995983123779,4.233077971197378,1739141202.718664,42.11995983123779,1.169272499932111 +1739141202.7377057,42.13995981216431,42.06029216801477,1739141202.7377083,42.13995981216431,2.5425877596598694,1739141202.7377117,42.13995981216431,69.86541329563887,1739141202.7377148,42.13995981216431,37.9528341346295,1739141202.737716,42.13995981216431,-0.061547031181217786,1739141202.7377174,42.13995981216431,-2.5765464794520265,1739141202.737719,42.13995981216431,-2.4436569287505066,1739141202.7377203,42.13995981216431,-0.6108,1739141202.7377217,42.13995981216431,0.9406613948199338,1739141202.737723,42.13995981216431,0.0,1739141202.7377248,42.13995981216431,-0.22861110511217708,1739141202.737726,42.13995981216431,4.233077971197378,1739141202.7377272,42.13995981216431,1.169272499932111 +1739141202.7602036,42.15995979309082,42.06029216801477,1739141202.7602074,42.15995979309082,2.5425877596598694,1739141202.7602122,42.15995979309082,69.86541329563887,1739141202.760218,42.15995979309082,37.9528341346295,1739141202.760221,42.15995979309082,-0.061547031181217786,1739141202.7602248,42.15995979309082,-2.5765464794520265,1739141202.7602286,42.15995979309082,-2.4436569287505066,1739141202.7602322,42.15995979309082,-0.6108,1739141202.7602358,42.15995979309082,0.9406613948199338,1739141202.7602396,42.15995979309082,0.0,1739141202.7602432,42.15995979309082,-0.22861110511217708,1739141202.7602468,42.15995979309082,4.233077971197378,1739141202.7602503,42.15995979309082,1.169272499932111 +1739141202.7785923,42.179959774017334,42.06029216801477,1739141202.7785962,42.179959774017334,2.5425877596598694,1739141202.778601,42.179959774017334,69.86541329563887,1739141202.7786067,42.179959774017334,37.9528341346295,1739141202.77861,42.179959774017334,-0.061547031181217786,1739141202.7786138,42.179959774017334,-2.5765464794520265,1739141202.7786174,42.179959774017334,-2.4436569287505066,1739141202.778621,42.179959774017334,-0.6108,1739141202.7786245,42.179959774017334,0.9406613948199338,1739141202.778628,42.179959774017334,0.0,1739141202.7786317,42.179959774017334,-0.22861110511217708,1739141202.7786353,42.179959774017334,4.233077971197378,1739141202.7786388,42.179959774017334,1.169272499932111 +1739141202.798825,42.19995975494385,42.00096124138342,1739141202.798829,42.19995975494385,2.4301567651384532,1739141202.798834,42.19995975494385,70.05019822161685,1739141202.7988396,42.19995975494385,37.85770953473912,1739141202.7988427,42.19995975494385,-0.0674587294794893,1739141202.7988472,42.19995975494385,-2.59910565525357,1739141202.7988508,42.19995975494385,-2.466097167317676,1739141202.7988544,42.19995975494385,-0.6108,1739141202.798858,42.19995975494385,0.9322557099278155,1739141202.7988615,42.19995975494385,0.0,1739141202.7988653,42.19995975494385,-0.1877185173416421,1739141202.7988687,42.19995975494385,4.21897679257393,1739141202.7988722,42.19995975494385,1.1394468978400192 +1739141202.8185558,42.21995973587036,42.00096124138342,1739141202.8185587,42.21995973587036,2.4301567651384532,1739141202.8185618,42.21995973587036,70.05019822161685,1739141202.8185651,42.21995973587036,37.85770953473912,1739141202.8185666,42.21995973587036,-0.0674587294794893,1739141202.8185685,42.21995973587036,-2.59910565525357,1739141202.8185697,42.21995973587036,-2.466097167317676,1739141202.8185713,42.21995973587036,-0.6108,1739141202.8185723,42.21995973587036,0.9322557099278155,1739141202.8185742,42.21995973587036,0.0,1739141202.8185756,42.21995973587036,-0.2071911879122037,1739141202.8185768,42.21995973587036,4.21897679257393,1739141202.8185782,42.21995973587036,1.1394468978400192 +1739141202.8371673,42.239959716796875,42.00096124138342,1739141202.83717,42.239959716796875,2.4301567651384532,1739141202.8371727,42.239959716796875,70.05019822161685,1739141202.8371754,42.239959716796875,37.85770953473912,1739141202.8371768,42.239959716796875,-0.0674587294794893,1739141202.8371785,42.239959716796875,-2.59910565525357,1739141202.83718,42.239959716796875,-2.466097167317676,1739141202.837181,42.239959716796875,-0.6108,1739141202.8371825,42.239959716796875,0.9322557099278155,1739141202.8371842,42.239959716796875,0.0,1739141202.8371859,42.239959716796875,-0.2071911879122037,1739141202.837187,42.239959716796875,4.21897679257393,1739141202.8371882,42.239959716796875,1.1394468978400192 +1739141202.8579392,42.25995969772339,42.00096124138342,1739141202.8579419,42.25995969772339,2.4301567651384532,1739141202.8579445,42.25995969772339,70.05019822161685,1739141202.8579473,42.25995969772339,37.85770953473912,1739141202.857949,42.25995969772339,-0.0674587294794893,1739141202.8579507,42.25995969772339,-2.59910565525357,1739141202.857952,42.25995969772339,-2.466097167317676,1739141202.8579533,42.25995969772339,-0.6108,1739141202.8579545,42.25995969772339,0.9322557099278155,1739141202.8579564,42.25995969772339,0.0,1739141202.8579576,42.25995969772339,-0.2071911879122037,1739141202.8579588,42.25995969772339,4.21897679257393,1739141202.8579602,42.25995969772339,1.1394468978400192 +1739141202.8773992,42.2799596786499,42.00096124138342,1739141202.8774025,42.2799596786499,2.4301567651384532,1739141202.8774056,42.2799596786499,70.05019822161685,1739141202.8774085,42.2799596786499,37.85770953473912,1739141202.8774104,42.2799596786499,-0.0674587294794893,1739141202.877412,42.2799596786499,-2.59910565525357,1739141202.8774133,42.2799596786499,-2.466097167317676,1739141202.877415,42.2799596786499,-0.6108,1739141202.8774161,42.2799596786499,0.9322557099278155,1739141202.877418,42.2799596786499,0.0,1739141202.8774195,42.2799596786499,-0.2071911879122037,1739141202.8774211,42.2799596786499,4.21897679257393,1739141202.8774223,42.2799596786499,1.1394468978400192 +1739141202.896767,42.299959659576416,42.00096124138342,1739141202.89677,42.299959659576416,2.4301567651384532,1739141202.8967733,42.299959659576416,70.05019822161685,1739141202.8967762,42.299959659576416,37.85770953473912,1739141202.8967776,42.299959659576416,-0.0674587294794893,1739141202.8967798,42.299959659576416,-2.59910565525357,1739141202.8967812,42.299959659576416,-2.466097167317676,1739141202.8967829,42.299959659576416,-0.6108,1739141202.8967843,42.299959659576416,0.9322557099278155,1739141202.896786,42.299959659576416,0.0,1739141202.8967876,42.299959659576416,-0.2071911879122037,1739141202.896789,42.299959659576416,4.21897679257393,1739141202.8967905,42.299959659576416,1.1394468978400192 +1739141202.916697,42.31995964050293,41.941544270014745,1739141202.9166996,42.31995964050293,2.3214827963211446,1739141202.9167025,42.31995964050293,70.05519014995284,1739141202.9167058,42.31995964050293,37.941319017133324,1739141202.9167073,42.31995964050293,-0.06226265995216636,1739141202.9167092,42.31995964050293,-2.6041912416368085,1739141202.9167106,42.31995964050293,-2.331502721984619,1739141202.916712,42.31995964050293,-0.6108,1739141202.9167132,42.31995964050293,0.9838219367230138,1739141202.916715,42.31995964050293,0.0,1739141202.9167166,42.31995964050293,-0.052261138723402725,1739141202.9167178,42.31995964050293,4.203385592056693,1739141202.9167192,42.31995964050293,1.109859326200306 +1739141202.9366214,42.33995962142944,41.941544270014745,1739141202.936624,42.33995962142944,2.3214827963211446,1739141202.9366271,42.33995962142944,70.05519014995284,1739141202.93663,42.33995962142944,37.941319017133324,1739141202.9366314,42.33995962142944,-0.06226265995216636,1739141202.9366336,42.33995962142944,-2.6041912416368085,1739141202.936635,42.33995962142944,-2.331502721984619,1739141202.9366364,42.33995962142944,-0.6108,1739141202.9366376,42.33995962142944,0.9838219367230138,1739141202.9366393,42.33995962142944,0.0,1739141202.9366407,42.33995962142944,-0.12603738947729226,1739141202.936642,42.33995962142944,4.203385592056693,1739141202.9366434,42.33995962142944,1.109859326200306 +1739141202.956676,42.35995960235596,41.941544270014745,1739141202.9566793,42.35995960235596,2.3214827963211446,1739141202.956683,42.35995960235596,70.05519014995284,1739141202.956686,42.35995960235596,37.941319017133324,1739141202.9566877,42.35995960235596,-0.06226265995216636,1739141202.9566894,42.35995960235596,-2.6041912416368085,1739141202.956691,42.35995960235596,-2.331502721984619,1739141202.9566925,42.35995960235596,-0.6108,1739141202.9566936,42.35995960235596,0.9838219367230138,1739141202.9566956,42.35995960235596,0.0,1739141202.956697,42.35995960235596,-0.12603738947729226,1739141202.9566987,42.35995960235596,4.203385592056693,1739141202.9567,42.35995960235596,1.109859326200306 +1739141202.9771998,42.37995958328247,41.941544270014745,1739141202.9772027,42.37995958328247,2.3214827963211446,1739141202.9772055,42.37995958328247,70.05519014995284,1739141202.9772084,42.37995958328247,37.941319017133324,1739141202.9772098,42.37995958328247,-0.06226265995216636,1739141202.9772115,42.37995958328247,-2.6041912416368085,1739141202.9772127,42.37995958328247,-2.331502721984619,1739141202.977214,42.37995958328247,-0.6108,1739141202.9772155,42.37995958328247,0.9838219367230138,1739141202.9772172,42.37995958328247,0.0,1739141202.9772189,42.37995958328247,-0.12603738947729226,1739141202.9772203,42.37995958328247,4.203385592056693,1739141202.9772217,42.37995958328247,1.109859326200306 +1739141202.9971442,42.399959564208984,41.941544270014745,1739141202.9971478,42.399959564208984,2.3214827963211446,1739141202.9971511,42.399959564208984,70.05519014995284,1739141202.9971545,42.399959564208984,37.941319017133324,1739141202.9971561,42.399959564208984,-0.06226265995216636,1739141202.9971578,42.399959564208984,-2.6041912416368085,1739141202.9971595,42.399959564208984,-2.331502721984619,1739141202.9971611,42.399959564208984,-0.6108,1739141202.9971626,42.399959564208984,0.9838219367230138,1739141202.9971642,42.399959564208984,0.0,1739141202.997166,42.399959564208984,-0.12603738947729226,1739141202.9971673,42.399959564208984,4.203385592056693,1739141202.9971688,42.399959564208984,1.109859326200306 +1739141203.0167463,42.4199595451355,41.88158974407971,1739141203.0167494,42.4199595451355,2.215949028342137,1739141203.0167532,42.4199595451355,70.31473120347475,1739141203.016756,42.4199595451355,37.723430036366736,1739141203.0167575,42.4199595451355,-0.07521633483332982,1739141203.0167596,42.4199595451355,-2.6379784402075357,1739141203.016761,42.4199595451355,-2.44524310444733,1739141203.0167623,42.4199595451355,-0.6108,1739141203.0167637,42.4199595451355,0.9400647624153512,1739141203.0167654,42.4199595451355,0.0,1739141203.0167675,42.4199595451355,-0.18331377450458192,1739141203.016769,42.4199595451355,4.1862704789977085,1739141203.0167706,42.4199595451355,1.0961040542345233 +1739141203.037119,42.43995952606201,41.88158974407971,1739141203.0371222,42.43995952606201,2.215949028342137,1739141203.0371258,42.43995952606201,70.31473120347475,1739141203.037129,42.43995952606201,37.723430036366736,1739141203.0371308,42.43995952606201,-0.07521633483332982,1739141203.0371325,42.43995952606201,-2.6379784402075357,1739141203.0371346,42.43995952606201,-2.44524310444733,1739141203.037136,42.43995952606201,-0.6108,1739141203.0371375,42.43995952606201,0.9400647624153512,1739141203.0371392,42.43995952606201,0.0,1739141203.037141,42.43995952606201,-0.1560392918191721,1739141203.0371425,42.43995952606201,4.1862704789977085,1739141203.037144,42.43995952606201,1.0961040542345233 +1739141203.0571532,42.459959506988525,41.88158974407971,1739141203.0571568,42.459959506988525,2.215949028342137,1739141203.0571601,42.459959506988525,70.31473120347475,1739141203.0571632,42.459959506988525,37.723430036366736,1739141203.057165,42.459959506988525,-0.07521633483332982,1739141203.0571666,42.459959506988525,-2.6379784402075357,1739141203.0571685,42.459959506988525,-2.44524310444733,1739141203.0571697,42.459959506988525,-0.6108,1739141203.057171,42.459959506988525,0.9400647624153512,1739141203.057173,42.459959506988525,0.0,1739141203.0571742,42.459959506988525,-0.1560392918191721,1739141203.0571756,42.459959506988525,4.1862704789977085,1739141203.057177,42.459959506988525,1.0961040542345233 +1739141203.0771027,42.47995948791504,41.88158974407971,1739141203.077106,42.47995948791504,2.215949028342137,1739141203.0771096,42.47995948791504,70.31473120347475,1739141203.077113,42.47995948791504,37.723430036366736,1739141203.0771146,42.47995948791504,-0.07521633483332982,1739141203.0771165,42.47995948791504,-2.6379784402075357,1739141203.0771184,42.47995948791504,-2.44524310444733,1739141203.07712,42.47995948791504,-0.6108,1739141203.0771217,42.47995948791504,0.9400647624153512,1739141203.0771236,42.47995948791504,0.0,1739141203.077125,42.47995948791504,-0.1560392918191721,1739141203.0771267,42.47995948791504,4.1862704789977085,1739141203.0771284,42.47995948791504,1.0961040542345233 +1739141203.1033835,42.49995946884155,41.88158974407971,1739141203.1033938,42.49995946884155,2.215949028342137,1739141203.1034045,42.49995946884155,70.31473120347475,1739141203.1034143,42.49995946884155,37.723430036366736,1739141203.103419,42.49995946884155,-0.07521633483332982,1739141203.1034253,42.49995946884155,-2.6379784402075357,1739141203.1034305,42.49995946884155,-2.44524310444733,1739141203.1034355,42.49995946884155,-0.6108,1739141203.10344,42.49995946884155,0.9400647624153512,1739141203.1034458,42.49995946884155,0.0,1739141203.1034513,42.49995946884155,-0.1560392918191721,1739141203.1034563,42.49995946884155,4.1862704789977085,1739141203.1034608,42.49995946884155,1.0961040542345233 +1739141203.1291747,42.519959449768066,41.88158974407971,1739141203.1291828,42.519959449768066,2.215949028342137,1739141203.1291926,42.519959449768066,70.31473120347475,1739141203.129203,42.519959449768066,37.723430036366736,1739141203.129209,42.519959449768066,-0.07521633483332982,1739141203.129217,42.519959449768066,-2.6379784402075357,1739141203.1292243,42.519959449768066,-2.44524310444733,1739141203.1292312,42.519959449768066,-0.6108,1739141203.1292381,42.519959449768066,0.9400647624153512,1739141203.1292472,42.519959449768066,0.0,1739141203.1292543,42.519959449768066,-0.1560392918191721,1739141203.1292608,42.519959449768066,4.1862704789977085,1739141203.1292684,42.519959449768066,1.0961040542345233 +1739141203.1444583,42.53995943069458,41.82076361751371,1739141203.1444654,42.53995943069458,2.113186415075929,1739141203.144473,42.53995943069458,70.44416406068916,1739141203.1444795,42.53995943069458,37.65529516441643,1739141203.1444826,42.53995943069458,-0.07858934829621614,1739141203.1444867,42.53995943069458,-2.65722302504031,1739141203.14449,42.53995943069458,-2.426573908879684,1739141203.1444943,42.53995943069458,-0.6108,1739141203.144498,42.53995943069458,0.9471111408713602,1739141203.1445022,42.53995943069458,0.0,1739141203.1445057,42.53995943069458,-0.10363237992553881,1739141203.1445098,42.53995943069458,4.167593361518875,1739141203.1445155,42.53995943069458,1.0756992055936554 +1739141203.1648426,42.559959411621094,41.82076361751371,1739141203.1648488,42.559959411621094,2.113186415075929,1739141203.164856,42.559959411621094,70.44416406068916,1739141203.1648622,42.559959411621094,37.65529516441643,1739141203.1648684,42.559959411621094,-0.07858934829621614,1739141203.1648726,42.559959411621094,-2.65722302504031,1739141203.164876,42.559959411621094,-2.426573908879684,1739141203.16488,42.559959411621094,-0.6108,1739141203.1648831,42.559959411621094,0.9471111408713602,1739141203.1648872,42.559959411621094,0.0,1739141203.1648912,42.559959411621094,-0.12858806472229523,1739141203.1648946,42.559959411621094,4.167593361518875,1739141203.1648974,42.559959411621094,1.0756992055936554 +1739141203.183531,42.57995939254761,41.82076361751371,1739141203.183538,42.57995939254761,2.113186415075929,1739141203.183545,42.57995939254761,70.44416406068916,1739141203.1835535,42.57995939254761,37.65529516441643,1739141203.1835582,42.57995939254761,-0.07858934829621614,1739141203.1835628,42.57995939254761,-2.65722302504031,1739141203.1835666,42.57995939254761,-2.426573908879684,1739141203.1835701,42.57995939254761,-0.6108,1739141203.1835735,42.57995939254761,0.9471111408713602,1739141203.1835775,42.57995939254761,0.0,1739141203.1835814,42.57995939254761,-0.12858806472229523,1739141203.1835847,42.57995939254761,4.167593361518875,1739141203.1835878,42.57995939254761,1.0756992055936554 +1739141203.2041337,42.59995937347412,41.82076361751371,1739141203.2041385,42.59995937347412,2.113186415075929,1739141203.2041438,42.59995937347412,70.44416406068916,1739141203.2041485,42.59995937347412,37.65529516441643,1739141203.2041512,42.59995937347412,-0.07858934829621614,1739141203.2041535,42.59995937347412,-2.65722302504031,1739141203.2041564,42.59995937347412,-2.426573908879684,1739141203.204159,42.59995937347412,-0.6108,1739141203.2041612,42.59995937347412,0.9471111408713602,1739141203.2041636,42.59995937347412,0.0,1739141203.2041657,42.59995937347412,-0.12858806472229523,1739141203.2041676,42.59995937347412,4.167593361518875,1739141203.2041698,42.59995937347412,1.0756992055936554 +1739141203.2228327,42.619959354400635,41.82076361751371,1739141203.2228377,42.619959354400635,2.113186415075929,1739141203.2228425,42.619959354400635,70.44416406068916,1739141203.222847,42.619959354400635,37.65529516441643,1739141203.2228496,42.619959354400635,-0.07858934829621614,1739141203.222853,42.619959354400635,-2.65722302504031,1739141203.2228556,42.619959354400635,-2.426573908879684,1739141203.2228584,42.619959354400635,-0.6108,1739141203.222861,42.619959354400635,0.9471111408713602,1739141203.2228642,42.619959354400635,0.0,1739141203.2228668,42.619959354400635,-0.12858806472229523,1739141203.2228699,42.619959354400635,4.167593361518875,1739141203.2228723,42.619959354400635,1.0756992055936554 +1739141203.2416224,42.63995933532715,41.75888124254921,1739141203.2416263,42.63995933532715,2.0131223823104865,1739141203.241632,42.63995933532715,70.52888018057408,1739141203.2416372,42.63995933532715,37.611454768820735,1739141203.24164,42.63995933532715,-0.08072549665918735,1739141203.241645,42.63995933532715,-2.674068806048821,1739141203.2416499,42.63995933532715,-2.3814811034223817,1739141203.2416523,42.63995933532715,-0.6108,1739141203.2416534,42.63995933532715,0.9643492962480366,1739141203.2416553,42.63995933532715,0.0,1739141203.2416568,42.63995933532715,-0.06970010802014456,1739141203.2416584,42.63995933532715,4.147311583392119,1739141203.2416599,42.63995933532715,1.0620913024202157 +1739141203.2607603,42.65995931625366,41.75888124254921,1739141203.2607634,42.65995931625366,2.0131223823104865,1739141203.2607663,42.65995931625366,70.52888018057408,1739141203.2607691,42.65995931625366,37.611454768820735,1739141203.2607703,42.65995931625366,-0.08072549665918735,1739141203.260772,42.65995931625366,-2.674068806048821,1739141203.2607734,42.65995931625366,-2.3814811034223817,1739141203.2607746,42.65995931625366,-0.6108,1739141203.260776,42.65995931625366,0.9643492962480366,1739141203.2607775,42.65995931625366,0.0,1739141203.2607787,42.65995931625366,-0.0977420061721791,1739141203.26078,42.65995931625366,4.147311583392119,1739141203.2607813,42.65995931625366,1.0620913024202157 +1739141203.280737,42.679959297180176,41.75888124254921,1739141203.2807393,42.679959297180176,2.0131223823104865,1739141203.2807422,42.679959297180176,70.52888018057408,1739141203.280745,42.679959297180176,37.611454768820735,1739141203.2807465,42.679959297180176,-0.08072549665918735,1739141203.2807481,42.679959297180176,-2.674068806048821,1739141203.2807496,42.679959297180176,-2.3814811034223817,1739141203.2807508,42.679959297180176,-0.6108,1739141203.2807522,42.679959297180176,0.9643492962480366,1739141203.2807539,42.679959297180176,0.0,1739141203.2807555,42.679959297180176,-0.0977420061721791,1739141203.2807567,42.679959297180176,4.147311583392119,1739141203.280758,42.679959297180176,1.0620913024202157 +1739141203.3008957,42.69995927810669,41.75888124254921,1739141203.3008988,42.69995927810669,2.0131223823104865,1739141203.3009021,42.69995927810669,70.52888018057408,1739141203.3009048,42.69995927810669,37.611454768820735,1739141203.3009062,42.69995927810669,-0.08072549665918735,1739141203.300908,42.69995927810669,-2.674068806048821,1739141203.3009093,42.69995927810669,-2.3814811034223817,1739141203.3009105,42.69995927810669,-0.6108,1739141203.300912,42.69995927810669,0.9643492962480366,1739141203.3009133,42.69995927810669,0.0,1739141203.300915,42.69995927810669,-0.0977420061721791,1739141203.3009162,42.69995927810669,4.147311583392119,1739141203.3009179,42.69995927810669,1.0620913024202157 +1739141203.3216836,42.7199592590332,41.75888124254921,1739141203.3216863,42.7199592590332,2.0131223823104865,1739141203.3216891,42.7199592590332,70.52888018057408,1739141203.3216918,42.7199592590332,37.611454768820735,1739141203.321693,42.7199592590332,-0.08072549665918735,1739141203.3216944,42.7199592590332,-2.674068806048821,1739141203.321696,42.7199592590332,-2.3814811034223817,1739141203.3216975,42.7199592590332,-0.6108,1739141203.321699,42.7199592590332,0.9643492962480366,1739141203.3217003,42.7199592590332,0.0,1739141203.321702,42.7199592590332,-0.0977420061721791,1739141203.3217032,42.7199592590332,4.147311583392119,1739141203.3217044,42.7199592590332,1.0620913024202157 +1739141203.3516126,42.73995923995972,41.75888124254921,1739141203.3516204,42.73995923995972,2.0131223823104865,1739141203.351629,42.73995923995972,70.52888018057408,1739141203.3516374,42.73995923995972,37.611454768820735,1739141203.351642,42.73995923995972,-0.08072549665918735,1739141203.3516467,42.73995923995972,-2.674068806048821,1739141203.3516505,42.73995923995972,-2.3814811034223817,1739141203.351654,42.73995923995972,-0.6108,1739141203.3516576,42.73995923995972,0.9643492962480366,1739141203.3516624,42.73995923995972,0.0,1739141203.3516665,42.73995923995972,-0.0977420061721791,1739141203.35167,42.73995923995972,4.147311583392119,1739141203.3516738,42.73995923995972,1.0620913024202157 +1739141203.3677373,42.75995922088623,41.695619724009894,1739141203.3677447,42.75995922088623,1.9154801437871711,1739141203.3677526,42.75995922088623,70.70249637520207,1739141203.3677597,42.75995922088623,37.46843649279306,1739141203.3677635,42.75995922088623,-0.08673121110386516,1739141203.3677683,42.75995922088623,-2.69924520949107,1739141203.367772,42.75995922088623,-2.410576004408037,1739141203.367776,42.75995922088623,-0.6108,1739141203.3677795,42.75995922088623,0.9531912914792261,1739141203.3677838,42.75995922088623,0.0,1739141203.3677878,42.75995922088623,-0.09965419723239279,1739141203.3677914,42.75995922088623,4.125377502426807,1739141203.3677952,42.75995922088623,1.0519349210852202 +1739141203.3999116,42.789959192276,41.695619724009894,1739141203.3999171,42.789959192276,1.9154801437871711,1739141203.3999236,42.789959192276,70.70249637520207,1739141203.399931,42.789959192276,37.46843649279306,1739141203.399935,42.789959192276,-0.08673121110386516,1739141203.3999405,42.789959192276,-2.69924520949107,1739141203.3999453,42.789959192276,-2.410576004408037,1739141203.39995,42.789959192276,-0.6108,1739141203.3999548,42.789959192276,0.9531912914792261,1739141203.3999596,42.789959192276,0.0,1739141203.3999648,42.789959192276,-0.09874362960599414,1739141203.3999696,42.789959192276,4.125377502426807,1739141203.399974,42.789959192276,1.0519349210852202 +1739141203.4162564,42.809959173202515,41.695619724009894,1739141203.4162614,42.809959173202515,1.9154801437871711,1739141203.41627,42.809959173202515,70.70249637520207,1739141203.4162767,42.809959173202515,37.46843649279306,1739141203.4162798,42.809959173202515,-0.08673121110386516,1739141203.4162834,42.809959173202515,-2.69924520949107,1739141203.4162872,42.809959173202515,-2.410576004408037,1739141203.4162905,42.809959173202515,-0.6108,1739141203.416294,42.809959173202515,0.9531912914792261,1739141203.4162977,42.809959173202515,0.0,1739141203.416301,42.809959173202515,-0.09874362960599414,1739141203.4163043,42.809959173202515,4.125377502426807,1739141203.416308,42.809959173202515,1.0519349210852202 +1739141203.4387226,42.82995915412903,41.695619724009894,1739141203.4387271,42.82995915412903,1.9154801437871711,1739141203.4387324,42.82995915412903,70.70249637520207,1739141203.4387372,42.82995915412903,37.46843649279306,1739141203.4387395,42.82995915412903,-0.08673121110386516,1739141203.4387422,42.82995915412903,-2.69924520949107,1739141203.4387445,42.82995915412903,-2.410576004408037,1739141203.4387472,42.82995915412903,-0.6108,1739141203.438749,42.82995915412903,0.9531912914792261,1739141203.438752,42.82995915412903,0.0,1739141203.4387543,42.82995915412903,-0.09874362960599414,1739141203.4387572,42.82995915412903,4.125377502426807,1739141203.4387593,42.82995915412903,1.0519349210852202 +1739141203.4564621,42.8599591255188,41.63081871227869,1739141203.4564652,42.8599591255188,1.8202698688322627,1739141203.4564686,42.8599591255188,70.8552486793972,1739141203.4564714,42.8599591255188,37.34820085271855,1739141203.456473,42.8599591255188,-0.09151196589125789,1739141203.4564748,42.8599591255188,-2.721732388067431,1739141203.4564764,42.8599591255188,-2.4124239518843487,1739141203.4564779,42.8599591255188,-0.6108,1739141203.4564793,42.8599591255188,0.9524869728434517,1739141203.4564812,42.8599591255188,0.0,1739141203.456483,42.8599591255188,-0.07945629880880475,1739141203.456484,42.8599591255188,4.101738000859786,1739141203.4564857,42.8599591255188,1.0411277194770463 +1739141203.475877,42.869959115982056,41.63081871227869,1739141203.4758818,42.869959115982056,1.8202698688322627,1739141203.475885,42.869959115982056,70.8552486793972,1739141203.4758875,42.869959115982056,37.34820085271855,1739141203.475889,42.869959115982056,-0.09151196589125789,1739141203.4758906,42.869959115982056,-2.721732388067431,1739141203.475892,42.869959115982056,-2.4124239518843487,1739141203.4758933,42.869959115982056,-0.6108,1739141203.4758947,42.869959115982056,0.9524869728434517,1739141203.4758964,42.869959115982056,0.0,1739141203.4758978,42.869959115982056,-0.08864074663359456,1739141203.4758992,42.869959115982056,4.101738000859786,1739141203.4759004,42.869959115982056,1.0411277194770463 +1739141203.49879,42.88995909690857,41.63081871227869,1739141203.4987946,42.88995909690857,1.8202698688322627,1739141203.4987993,42.88995909690857,70.8552486793972,1739141203.498805,42.88995909690857,37.34820085271855,1739141203.4988081,42.88995909690857,-0.09151196589125789,1739141203.4988127,42.88995909690857,-2.721732388067431,1739141203.498817,42.88995909690857,-2.4124239518843487,1739141203.4988205,42.88995909690857,-0.6108,1739141203.4988241,42.88995909690857,0.9524869728434517,1739141203.498844,42.88995909690857,0.0,1739141203.4988475,42.88995909690857,-0.08864074663359456,1739141203.4988508,42.88995909690857,4.101738000859786,1739141203.4988544,42.88995909690857,1.0411277194770463 +1739141203.5157003,42.90995907783508,41.63081871227869,1739141203.5157032,42.90995907783508,1.8202698688322627,1739141203.515706,42.90995907783508,70.8552486793972,1739141203.5157087,42.90995907783508,37.34820085271855,1739141203.51571,42.90995907783508,-0.09151196589125789,1739141203.5157123,42.90995907783508,-2.721732388067431,1739141203.5157135,42.90995907783508,-2.4124239518843487,1739141203.515715,42.90995907783508,-0.6108,1739141203.515716,42.90995907783508,0.9524869728434517,1739141203.5157177,42.90995907783508,0.0,1739141203.5157194,42.90995907783508,-0.08864074663359456,1739141203.5157206,42.90995907783508,4.101738000859786,1739141203.515722,42.90995907783508,1.0411277194770463 +1739141203.5353122,42.9299590587616,41.63081871227869,1739141203.5353148,42.9299590587616,1.8202698688322627,1739141203.5353174,42.9299590587616,70.8552486793972,1739141203.53532,42.9299590587616,37.34820085271855,1739141203.5353212,42.9299590587616,-0.09151196589125789,1739141203.535323,42.9299590587616,-2.721732388067431,1739141203.5353243,42.9299590587616,-2.4124239518843487,1739141203.5353258,42.9299590587616,-0.6108,1739141203.5353267,42.9299590587616,0.9524869728434517,1739141203.5353286,42.9299590587616,0.0,1739141203.5353298,42.9299590587616,-0.08864074663359456,1739141203.535331,42.9299590587616,4.101738000859786,1739141203.5353324,42.9299590587616,1.0411277194770463 +1739141203.5554156,42.94995903968811,41.63081871227869,1739141203.555418,42.94995903968811,1.8202698688322627,1739141203.5554209,42.94995903968811,70.8552486793972,1739141203.5554235,42.94995903968811,37.34820085271855,1739141203.5554247,42.94995903968811,-0.09151196589125789,1739141203.5554266,42.94995903968811,-2.721732388067431,1739141203.555428,42.94995903968811,-2.4124239518843487,1739141203.5554295,42.94995903968811,-0.6108,1739141203.5554307,42.94995903968811,0.9524869728434517,1739141203.5554326,42.94995903968811,0.0,1739141203.5554338,42.94995903968811,-0.08864074663359456,1739141203.555435,42.94995903968811,4.101738000859786,1739141203.5554364,42.94995903968811,1.0411277194770463 +1739141203.5765467,42.969959020614624,41.56436700485335,1739141203.5765507,42.969959020614624,1.7275868912026846,1739141203.5765557,42.969959020614624,71.01506671140876,1739141203.5765615,42.969959020614624,37.21734767090268,1739141203.5765646,42.969959020614624,-0.09635808478577307,1739141203.5765686,42.969959020614624,-2.7443173155617893,1739141203.576572,42.969959020614624,-2.413467934481689,1739141203.5765755,42.969959020614624,-0.6108,1739141203.576579,42.969959020614624,0.9520893039515743,1739141203.5765827,42.969959020614624,0.0,1739141203.5765862,42.969959020614624,-0.0710251904824844,1739141203.5765898,42.969959020614624,4.076333916183328,1739141203.5765936,42.969959020614624,1.0315028586963704 +1739141203.595157,42.98995900154114,41.56436700485335,1739141203.5951595,42.98995900154114,1.7275868912026846,1739141203.5951624,42.98995900154114,71.01506671140876,1739141203.5951653,42.98995900154114,37.21734767090268,1739141203.5951664,42.98995900154114,-0.09635808478577307,1739141203.595168,42.98995900154114,-2.7443173155617893,1739141203.5951693,42.98995900154114,-2.413467934481689,1739141203.5951705,42.98995900154114,-0.6108,1739141203.595172,42.98995900154114,0.9520893039515743,1739141203.5951734,42.98995900154114,0.0,1739141203.5951746,42.98995900154114,-0.07941355474479606,1739141203.595176,42.98995900154114,4.076333916183328,1739141203.5951774,42.98995900154114,1.0315028586963704 +1739141203.61519,43.00995898246765,41.56436700485335,1739141203.6151924,43.00995898246765,1.7275868912026846,1739141203.6151953,43.00995898246765,71.01506671140876,1739141203.615198,43.00995898246765,37.21734767090268,1739141203.6151993,43.00995898246765,-0.09635808478577307,1739141203.615201,43.00995898246765,-2.7443173155617893,1739141203.6152022,43.00995898246765,-2.413467934481689,1739141203.6152036,43.00995898246765,-0.6108,1739141203.6152048,43.00995898246765,0.9520893039515743,1739141203.6152065,43.00995898246765,0.0,1739141203.6152077,43.00995898246765,-0.07941355474479606,1739141203.6152089,43.00995898246765,4.076333916183328,1739141203.6152103,43.00995898246765,1.0315028586963704 +1739141203.6350412,43.029958963394165,41.56436700485335,1739141203.6350436,43.029958963394165,1.7275868912026846,1739141203.635047,43.029958963394165,71.01506671140876,1739141203.6350496,43.029958963394165,37.21734767090268,1739141203.635051,43.029958963394165,-0.09635808478577307,1739141203.6350524,43.029958963394165,-2.7443173155617893,1739141203.635054,43.029958963394165,-2.413467934481689,1739141203.6350553,43.029958963394165,-0.6108,1739141203.6350567,43.029958963394165,0.9520893039515743,1739141203.6350582,43.029958963394165,0.0,1739141203.6350596,43.029958963394165,-0.07941355474479606,1739141203.635061,43.029958963394165,4.076333916183328,1739141203.6350622,43.029958963394165,1.0315028586963704 +1739141203.6550844,43.04995894432068,41.56436700485335,1739141203.655087,43.04995894432068,1.7275868912026846,1739141203.65509,43.04995894432068,71.01506671140876,1739141203.655093,43.04995894432068,37.21734767090268,1739141203.6550946,43.04995894432068,-0.09635808478577307,1739141203.655096,43.04995894432068,-2.7443173155617893,1739141203.6550972,43.04995894432068,-2.413467934481689,1739141203.6550987,43.04995894432068,-0.6108,1739141203.6550999,43.04995894432068,0.9520893039515743,1739141203.6551018,43.04995894432068,0.0,1739141203.655103,43.04995894432068,-0.07941355474479606,1739141203.6551044,43.04995894432068,4.076333916183328,1739141203.6551058,43.04995894432068,1.0315028586963704 +1739141203.6758358,43.06995892524719,41.56436700485335,1739141203.6758387,43.06995892524719,1.7275868912026846,1739141203.6758423,43.06995892524719,71.01506671140876,1739141203.675845,43.06995892524719,37.21734767090268,1739141203.6758463,43.06995892524719,-0.09635808478577307,1739141203.6758482,43.06995892524719,-2.7443173155617893,1739141203.6758497,43.06995892524719,-2.413467934481689,1739141203.675851,43.06995892524719,-0.6108,1739141203.6758525,43.06995892524719,0.9520893039515743,1739141203.675854,43.06995892524719,0.0,1739141203.6758556,43.06995892524719,-0.07941355474479606,1739141203.6758568,43.06995892524719,4.076333916183328,1739141203.6758583,43.06995892524719,1.0315028586963704 +1739141203.6953866,43.089958906173706,41.496108198801245,1739141203.6953895,43.089958906173706,1.6374718377646662,1739141203.6953926,43.089958906173706,71.13690214062645,1739141203.695395,43.089958906173706,37.120914178180676,1739141203.6953964,43.089958906173706,-0.0990576789125108,1739141203.695398,43.089958906173706,-2.763758579871811,1739141203.6953998,43.089958906173706,-2.3785141633279765,1739141203.695401,43.089958906173706,-0.6108,1739141203.6954021,43.089958906173706,0.965494442266378,1739141203.6954038,43.089958906173706,0.0,1739141203.695405,43.089958906173706,-0.03768116849658329,1739141203.6954064,43.089958906173706,4.049146275079782,1739141203.6954076,43.089958906173706,1.023048185570282 +1739141203.7152553,43.10995888710022,41.496108198801245,1739141203.715258,43.10995888710022,1.6374718377646662,1739141203.7152607,43.10995888710022,71.13690214062645,1739141203.7152636,43.10995888710022,37.120914178180676,1739141203.7152648,43.10995888710022,-0.0990576789125108,1739141203.7152662,43.10995888710022,-2.763758579871811,1739141203.715268,43.10995888710022,-2.3785141633279765,1739141203.715269,43.10995888710022,-0.6108,1739141203.7152703,43.10995888710022,0.965494442266378,1739141203.715272,43.10995888710022,0.0,1739141203.7152731,43.10995888710022,-0.05755374330390395,1739141203.7152746,43.10995888710022,4.049146275079782,1739141203.7152758,43.10995888710022,1.023048185570282 +1739141203.7351093,43.12995886802673,41.496108198801245,1739141203.7351127,43.12995886802673,1.6374718377646662,1739141203.7351153,43.12995886802673,71.13690214062645,1739141203.735118,43.12995886802673,37.120914178180676,1739141203.7351196,43.12995886802673,-0.0990576789125108,1739141203.7351213,43.12995886802673,-2.763758579871811,1739141203.7351227,43.12995886802673,-2.3785141633279765,1739141203.7351239,43.12995886802673,-0.6108,1739141203.7351253,43.12995886802673,0.965494442266378,1739141203.735127,43.12995886802673,0.0,1739141203.7351286,43.12995886802673,-0.05755374330390395,1739141203.7351298,43.12995886802673,4.049146275079782,1739141203.735131,43.12995886802673,1.023048185570282 +1739141203.7550912,43.14995884895325,41.496108198801245,1739141203.7550936,43.14995884895325,1.6374718377646662,1739141203.7550964,43.14995884895325,71.13690214062645,1739141203.755099,43.14995884895325,37.120914178180676,1739141203.7551007,43.14995884895325,-0.0990576789125108,1739141203.7551022,43.14995884895325,-2.763758579871811,1739141203.7551038,43.14995884895325,-2.3785141633279765,1739141203.755105,43.14995884895325,-0.6108,1739141203.7551064,43.14995884895325,0.965494442266378,1739141203.7551084,43.14995884895325,0.0,1739141203.7551098,43.14995884895325,-0.05755374330390395,1739141203.7551112,43.14995884895325,4.049146275079782,1739141203.7551124,43.14995884895325,1.023048185570282 +1739141203.7751372,43.16995882987976,41.496108198801245,1739141203.7751398,43.16995882987976,1.6374718377646662,1739141203.7751427,43.16995882987976,71.13690214062645,1739141203.7751453,43.16995882987976,37.120914178180676,1739141203.7751467,43.16995882987976,-0.0990576789125108,1739141203.775148,43.16995882987976,-2.763758579871811,1739141203.7751493,43.16995882987976,-2.3785141633279765,1739141203.7751508,43.16995882987976,-0.6108,1739141203.775152,43.16995882987976,0.965494442266378,1739141203.7751536,43.16995882987976,0.0,1739141203.7751553,43.16995882987976,-0.05755374330390395,1739141203.7751565,43.16995882987976,4.049146275079782,1739141203.7751575,43.16995882987976,1.023048185570282 +1739141203.7948904,43.189958810806274,41.42591788498981,1739141203.794893,43.189958810806274,1.5499312610844678,1739141203.7948961,43.189958810806274,71.1382341780642,1739141203.7948987,43.189958810806274,37.13858298590394,1739141203.7949,43.189958810806274,-0.09858727398385082,1739141203.7949018,43.189958810806274,-2.774511563284948,1739141203.794903,43.189958810806274,-2.253302119133801,1739141203.7949042,43.189958810806274,-0.6108,1739141203.7949057,43.189958810806274,1.015082494154963,1739141203.794907,43.189958810806274,0.0,1739141203.7949085,43.189958810806274,0.049209910080637444,1739141203.7949097,43.189958810806274,4.021403244702146,1739141203.794911,43.189958810806274,1.0167124444160767 +1739141203.8151839,43.20995879173279,41.42591788498981,1739141203.8151867,43.20995879173279,1.5499312610844678,1739141203.81519,43.20995879173279,71.1382341780642,1739141203.815193,43.20995879173279,37.13858298590394,1739141203.8151944,43.20995879173279,-0.09858727398385082,1739141203.8151963,43.20995879173279,-2.774511563284948,1739141203.815198,43.20995879173279,-2.253302119133801,1739141203.8151991,43.20995879173279,-0.6108,1739141203.8152006,43.20995879173279,1.015082494154963,1739141203.8152022,43.20995879173279,0.0,1739141203.815204,43.20995879173279,-0.0016299502611136774,1739141203.815205,43.20995879173279,4.021403244702146,1739141203.8152063,43.20995879173279,1.0167124444160767 +1739141203.8365483,43.2299587726593,41.42591788498981,1739141203.8365526,43.2299587726593,1.5499312610844678,1739141203.8365574,43.2299587726593,71.1382341780642,1739141203.8365617,43.2299587726593,37.13858298590394,1739141203.8365638,43.2299587726593,-0.09858727398385082,1739141203.836566,43.2299587726593,-2.774511563284948,1739141203.836568,43.2299587726593,-2.253302119133801,1739141203.8365698,43.2299587726593,-0.6108,1739141203.8365717,43.2299587726593,1.015082494154963,1739141203.8365736,43.2299587726593,0.0,1739141203.8365757,43.2299587726593,-0.0016299502611136774,1739141203.8365772,43.2299587726593,4.021403244702146,1739141203.836579,43.2299587726593,1.0167124444160767 +1739141203.8559391,43.249958753585815,41.42591788498981,1739141203.8559425,43.249958753585815,1.5499312610844678,1739141203.8559463,43.249958753585815,71.1382341780642,1739141203.8559499,43.249958753585815,37.13858298590394,1739141203.8559518,43.249958753585815,-0.09858727398385082,1739141203.855954,43.249958753585815,-2.774511563284948,1739141203.855956,43.249958753585815,-2.253302119133801,1739141203.8559577,43.249958753585815,-0.6108,1739141203.8559592,43.249958753585815,1.015082494154963,1739141203.8559613,43.249958753585815,0.0,1739141203.8559637,43.249958753585815,-0.0016299502611136774,1739141203.8559651,43.249958753585815,4.021403244702146,1739141203.855967,43.249958753585815,1.0167124444160767 +1739141203.8788905,43.26995873451233,41.42591788498981,1739141203.8788936,43.26995873451233,1.5499312610844678,1739141203.8788974,43.26995873451233,71.1382341780642,1739141203.878901,43.26995873451233,37.13858298590394,1739141203.8789027,43.26995873451233,-0.09858727398385082,1739141203.8789048,43.26995873451233,-2.774511563284948,1739141203.8789067,43.26995873451233,-2.253302119133801,1739141203.8789082,43.26995873451233,-0.6108,1739141203.87891,43.26995873451233,1.015082494154963,1739141203.8789122,43.26995873451233,0.0,1739141203.878914,43.26995873451233,-0.0016299502611136774,1739141203.8789158,43.26995873451233,4.021403244702146,1739141203.8789177,43.26995873451233,1.0167124444160767 +1739141203.8959193,43.28995871543884,41.42591788498981,1739141203.8959231,43.28995871543884,1.5499312610844678,1739141203.8959272,43.28995871543884,71.1382341780642,1739141203.8959308,43.28995871543884,37.13858298590394,1739141203.8959327,43.28995871543884,-0.09858727398385082,1739141203.895935,43.28995871543884,-2.774511563284948,1739141203.8959367,43.28995871543884,-2.253302119133801,1739141203.8959386,43.28995871543884,-0.6108,1739141203.89594,43.28995871543884,1.015082494154963,1739141203.8959422,43.28995871543884,0.0,1739141203.8959439,43.28995871543884,-0.0016299502611136774,1739141203.8959458,43.28995871543884,4.021403244702146,1739141203.8959472,43.28995871543884,1.0167124444160767 +1739141203.9162445,43.309958696365356,41.35348179916213,1739141203.9162483,43.309958696365356,1.464557559479596,1739141203.9162524,43.309958696365356,71.13956909244948,1739141203.9162562,43.309958696365356,37.13323950660268,1739141203.916258,43.309958696365356,-0.09873850453011301,1739141203.9162602,43.309958696365356,-2.7868362929209773,1739141203.9162621,43.309958696365356,-2.147018757114277,1739141203.9162638,43.309958696365356,-0.6108,1739141203.9162657,43.309958696365356,1.059167507237641,1739141203.9162679,43.309958696365356,0.0,1739141203.9162695,43.309958696365356,0.07998011797678052,1739141203.9162714,43.309958696365356,3.993660214324508,1739141203.916273,43.309958696365356,1.0180493459302458 +1739141203.9358578,43.32995867729187,41.35348179916213,1739141203.935861,43.32995867729187,1.464557559479596,1739141203.9358647,43.32995867729187,71.13956909244948,1739141203.9358685,43.32995867729187,37.13323950660268,1739141203.9358704,43.32995867729187,-0.09873850453011301,1739141203.9358726,43.32995867729187,-2.7868362929209773,1739141203.9358742,43.32995867729187,-2.147018757114277,1739141203.9358761,43.32995867729187,-0.6108,1739141203.9358776,43.32995867729187,1.059167507237641,1739141203.9358797,43.32995867729187,0.0,1739141203.9358814,43.32995867729187,0.04111816130739521,1739141203.9358833,43.32995867729187,3.993660214324508,1739141203.935885,43.32995867729187,1.0180493459302458 +1739141203.9557958,43.349958658218384,41.35348179916213,1739141203.9558,43.349958658218384,1.464557559479596,1739141203.9558039,43.349958658218384,71.13956909244948,1739141203.9558077,43.349958658218384,37.13323950660268,1739141203.9558096,43.349958658218384,-0.09873850453011301,1739141203.9558117,43.349958658218384,-2.7868362929209773,1739141203.955814,43.349958658218384,-2.147018757114277,1739141203.9558158,43.349958658218384,-0.6108,1739141203.9558172,43.349958658218384,1.059167507237641,1739141203.9558196,43.349958658218384,0.0,1739141203.9558213,43.349958658218384,0.04111816130739521,1739141203.9558232,43.349958658218384,3.993660214324508,1739141203.9558246,43.349958658218384,1.0180493459302458 +1739141203.9781208,43.3699586391449,41.35348179916213,1739141203.9781249,43.3699586391449,1.464557559479596,1739141203.97813,43.3699586391449,71.13956909244948,1739141203.9781363,43.3699586391449,37.13323950660268,1739141203.9781399,43.3699586391449,-0.09873850453011301,1739141203.9781442,43.3699586391449,-2.7868362929209773,1739141203.978148,43.3699586391449,-2.147018757114277,1739141203.9781523,43.3699586391449,-0.6108,1739141203.978156,43.3699586391449,1.059167507237641,1739141203.9781601,43.3699586391449,0.0,1739141203.9781642,43.3699586391449,0.04111816130739521,1739141203.978168,43.3699586391449,3.993660214324508,1739141203.978172,43.3699586391449,1.0180493459302458 +1739141203.9950433,43.38995862007141,41.35348179916213,1739141203.9950457,43.38995862007141,1.464557559479596,1739141203.9950485,43.38995862007141,71.13956909244948,1739141203.9950507,43.38995862007141,37.13323950660268,1739141203.9950523,43.38995862007141,-0.09873850453011301,1739141203.9950538,43.38995862007141,-2.7868362929209773,1739141203.9950552,43.38995862007141,-2.147018757114277,1739141203.9950566,43.38995862007141,-0.6108,1739141203.9950576,43.38995862007141,1.059167507237641,1739141203.9950593,43.38995862007141,0.0,1739141203.9950607,43.38995862007141,0.04111816130739521,1739141203.9950619,43.38995862007141,3.993660214324508,1739141203.995063,43.38995862007141,1.0180493459302458 +1739141204.0150754,43.409958600997925,41.27852564882235,1739141204.0150776,43.409958600997925,1.3810272711794864,1739141204.0150805,43.409958600997925,71.14091194010894,1739141204.015083,43.409958600997925,37.117338629869316,1739141204.0150843,43.409958600997925,-0.09912451159122779,1739141204.015086,43.409958600997925,-2.7998451895386314,1739141204.0150871,43.409958600997925,-2.049581269096706,1739141204.0150883,43.409958600997925,-0.6108,1739141204.0150895,43.409958600997925,1.1012635740550578,1739141204.015091,43.409958600997925,0.0,1739141204.0150921,43.409958600997925,0.11221611696548543,1739141204.0150933,43.409958600997925,3.9659171839468668,1739141204.0150945,43.409958600997925,1.022903643363212 +1739141204.0350695,43.42995858192444,41.27852564882235,1739141204.035072,43.42995858192444,1.3810272711794864,1739141204.0350752,43.42995858192444,71.14091194010894,1739141204.0350776,43.42995858192444,37.117338629869316,1739141204.0350792,43.42995858192444,-0.09912451159122779,1739141204.035081,43.42995858192444,-2.7998451895386314,1739141204.0350826,43.42995858192444,-2.049581269096706,1739141204.0350838,43.42995858192444,-0.6108,1739141204.035085,43.42995858192444,1.1012635740550578,1739141204.0350866,43.42995858192444,0.0,1739141204.035088,43.42995858192444,0.07835993069184588,1739141204.0350895,43.42995858192444,3.9659171839468668,1739141204.0350907,43.42995858192444,1.022903643363212 +1739141204.0548918,43.44995856285095,41.27852564882235,1739141204.054894,43.44995856285095,1.3810272711794864,1739141204.0548968,43.44995856285095,71.14091194010894,1739141204.0548997,43.44995856285095,37.117338629869316,1739141204.0549014,43.44995856285095,-0.09912451159122779,1739141204.0549028,43.44995856285095,-2.7998451895386314,1739141204.0549045,43.44995856285095,-2.049581269096706,1739141204.054906,43.44995856285095,-0.6108,1739141204.0549068,43.44995856285095,1.1012635740550578,1739141204.0549085,43.44995856285095,0.0,1739141204.05491,43.44995856285095,0.07835993069184588,1739141204.0549111,43.44995856285095,3.9659171839468668,1739141204.0549126,43.44995856285095,1.022903643363212 +1739141204.0751498,43.469958543777466,41.27852564882235,1739141204.0751522,43.469958543777466,1.3810272711794864,1739141204.0751553,43.469958543777466,71.14091194010894,1739141204.075158,43.469958543777466,37.117338629869316,1739141204.0751593,43.469958543777466,-0.09912451159122779,1739141204.075161,43.469958543777466,-2.7998451895386314,1739141204.0751626,43.469958543777466,-2.049581269096706,1739141204.0751638,43.469958543777466,-0.6108,1739141204.075165,43.469958543777466,1.1012635740550578,1739141204.0751667,43.469958543777466,0.0,1739141204.075168,43.469958543777466,0.07835993069184588,1739141204.0751693,43.469958543777466,3.9659171839468668,1739141204.0751705,43.469958543777466,1.022903643363212 +1739141204.0952854,43.48995852470398,41.27852564882235,1739141204.095288,43.48995852470398,1.3810272711794864,1739141204.0952911,43.48995852470398,71.14091194010894,1739141204.0952942,43.48995852470398,37.117338629869316,1739141204.0952957,43.48995852470398,-0.09912451159122779,1739141204.0952976,43.48995852470398,-2.7998451895386314,1739141204.095299,43.48995852470398,-2.049581269096706,1739141204.0953004,43.48995852470398,-0.6108,1739141204.095302,43.48995852470398,1.1012635740550578,1739141204.095304,43.48995852470398,0.0,1739141204.0953054,43.48995852470398,0.07835993069184588,1739141204.095307,43.48995852470398,3.9659171839468668,1739141204.0953083,43.48995852470398,1.022903643363212 +1739141204.1157346,43.50995850563049,41.27852564882235,1739141204.1157377,43.50995850563049,1.3810272711794864,1739141204.115741,43.50995850563049,71.14091194010894,1739141204.115744,43.50995850563049,37.117338629869316,1739141204.1157458,43.50995850563049,-0.09912451159122779,1739141204.115748,43.50995850563049,-2.7998451895386314,1739141204.1157494,43.50995850563049,-2.049581269096706,1739141204.115751,43.50995850563049,-0.6108,1739141204.1157525,43.50995850563049,1.1012635740550578,1739141204.1157541,43.50995850563049,0.0,1739141204.1157558,43.50995850563049,0.07835993069184588,1739141204.1157572,43.50995850563049,3.9659171839468668,1739141204.115759,43.50995850563049,1.022903643363212 +1739141204.1357274,43.52995848655701,41.200793255559375,1739141204.1357312,43.52995848655701,1.2990953041264852,1739141204.1357355,43.52995848655701,71.14226698738473,1739141204.135739,43.52995848655701,37.09033082276244,1739141204.135741,43.52995848655701,-0.09962933041565543,1739141204.1357431,43.52995848655701,-2.8135995894536903,1739141204.135745,43.52995848655701,-1.960932993679148,1739141204.135747,43.52995848655701,-0.6108,1739141204.1357493,43.52995848655701,1.1410142209678593,1739141204.1357512,43.52995848655701,0.0,1739141204.135753,43.52995848655701,0.13792007080401467,1739141204.1357548,43.52995848655701,3.9381741535692254,1739141204.1357563,43.52995848655701,1.0314561358138807 +1739141204.155574,43.54995846748352,41.200793255559375,1739141204.155577,43.54995846748352,1.2990953041264852,1739141204.1555805,43.54995846748352,71.14226698738473,1739141204.1555834,43.54995846748352,37.09033082276244,1739141204.155585,43.54995846748352,-0.09962933041565543,1739141204.1555867,43.54995846748352,-2.8135995894536903,1739141204.1555884,43.54995846748352,-1.960932993679148,1739141204.1555903,43.54995846748352,-0.6108,1739141204.155592,43.54995846748352,1.1410142209678593,1739141204.1555936,43.54995846748352,0.0,1739141204.1555955,43.54995846748352,0.10955808515397858,1739141204.155597,43.54995846748352,3.9381741535692254,1739141204.1555986,43.54995846748352,1.0314561358138807 +1739141204.1759312,43.569958448410034,41.200793255559375,1739141204.1759348,43.569958448410034,1.2990953041264852,1739141204.1759386,43.569958448410034,71.14226698738473,1739141204.175942,43.569958448410034,37.09033082276244,1739141204.1759436,43.569958448410034,-0.09962933041565543,1739141204.1759455,43.569958448410034,-2.8135995894536903,1739141204.1759472,43.569958448410034,-1.960932993679148,1739141204.1759489,43.569958448410034,-0.6108,1739141204.1759503,43.569958448410034,1.1410142209678593,1739141204.1759522,43.569958448410034,0.0,1739141204.1759539,43.569958448410034,0.10955808515397858,1739141204.1759555,43.569958448410034,3.9381741535692254,1739141204.175957,43.569958448410034,1.0314561358138807 +1739141204.1956718,43.58995842933655,41.200793255559375,1739141204.1956751,43.58995842933655,1.2990953041264852,1739141204.195679,43.58995842933655,71.14226698738473,1739141204.1956823,43.58995842933655,37.09033082276244,1739141204.195684,43.58995842933655,-0.09962933041565543,1739141204.1956856,43.58995842933655,-2.8135995894536903,1739141204.1956875,43.58995842933655,-1.960932993679148,1739141204.195689,43.58995842933655,-0.6108,1739141204.1956909,43.58995842933655,1.1410142209678593,1739141204.1956925,43.58995842933655,0.0,1739141204.1956944,43.58995842933655,0.10955808515397858,1739141204.1956959,43.58995842933655,3.9381741535692254,1739141204.1956973,43.58995842933655,1.0314561358138807 +1739141204.2154038,43.60995841026306,41.200793255559375,1739141204.215407,43.60995841026306,1.2990953041264852,1739141204.2154105,43.60995841026306,71.14226698738473,1739141204.215414,43.60995841026306,37.09033082276244,1739141204.2154155,43.60995841026306,-0.09962933041565543,1739141204.2154176,43.60995841026306,-2.8135995894536903,1739141204.215419,43.60995841026306,-1.960932993679148,1739141204.2154207,43.60995841026306,-0.6108,1739141204.2154222,43.60995841026306,1.1410142209678593,1739141204.215424,43.60995841026306,0.0,1739141204.2154257,43.60995841026306,0.10955808515397858,1739141204.2154274,43.60995841026306,3.9381741535692254,1739141204.2154288,43.60995841026306,1.0314561358138807 +1739141204.2358482,43.629958391189575,41.12003757514063,1739141204.235852,43.629958391189575,1.2185741765830667,1739141204.2358558,43.629958391189575,71.73409722865901,1739141204.2358592,43.629958391189575,36.46272336162887,1739141204.235861,43.629958391189575,-0.104,1739141204.235863,43.629958391189575,-2.864899094102029,1739141204.2358649,43.629958391189575,-2.2876758550356975,1739141204.2358663,43.629958391189575,-0.6108,1739141204.235868,43.629958391189575,1.001221134838605,1739141204.23587,43.629958391189575,0.0,1739141204.2358718,43.629958391189575,-0.18011686538498367,1739141204.2358732,43.629958391189575,3.910431123191584,1739141204.235875,43.629958391189575,1.0433974786786706 +1739141204.25548,43.64995837211609,41.12003757514063,1739141204.2554834,43.64995837211609,1.2185741765830667,1739141204.255487,43.64995837211609,71.73409722865901,1739141204.25549,43.64995837211609,36.46272336162887,1739141204.2554917,43.64995837211609,-0.104,1739141204.2554936,43.64995837211609,-2.864899094102029,1739141204.2554953,43.64995837211609,-2.2876758550356975,1739141204.255497,43.64995837211609,-0.6108,1739141204.2554984,43.64995837211609,1.001221134838605,1739141204.2555006,43.64995837211609,0.0,1739141204.2555027,43.64995837211609,-0.04217634384006552,1739141204.255504,43.64995837211609,3.910431123191584,1739141204.2555053,43.64995837211609,1.0433974786786706 +1739141204.2755747,43.6699583530426,41.12003757514063,1739141204.275578,43.6699583530426,1.2185741765830667,1739141204.2755818,43.6699583530426,71.73409722865901,1739141204.275585,43.6699583530426,36.46272336162887,1739141204.2755868,43.6699583530426,-0.104,1739141204.2755888,43.6699583530426,-2.864899094102029,1739141204.2755907,43.6699583530426,-2.2876758550356975,1739141204.275592,43.6699583530426,-0.6108,1739141204.2755938,43.6699583530426,1.001221134838605,1739141204.2755961,43.6699583530426,0.0,1739141204.2755976,43.6699583530426,-0.04217634384006552,1739141204.275599,43.6699583530426,3.910431123191584,1739141204.2756007,43.6699583530426,1.0433974786786706 +1739141204.2955415,43.689958333969116,41.12003757514063,1739141204.2955449,43.689958333969116,1.2185741765830667,1739141204.2955484,43.689958333969116,71.73409722865901,1739141204.2955518,43.689958333969116,36.46272336162887,1739141204.2955534,43.689958333969116,-0.104,1739141204.2955554,43.689958333969116,-2.864899094102029,1739141204.2955568,43.689958333969116,-2.2876758550356975,1739141204.2955585,43.689958333969116,-0.6108,1739141204.29556,43.689958333969116,1.001221134838605,1739141204.2955618,43.689958333969116,0.0,1739141204.2955635,43.689958333969116,-0.04217634384006552,1739141204.295565,43.689958333969116,3.910431123191584,1739141204.2955663,43.689958333969116,1.0433974786786706 +1739141204.3156555,43.70995831489563,41.12003757514063,1739141204.315659,43.70995831489563,1.2185741765830667,1739141204.3156626,43.70995831489563,71.73409722865901,1739141204.3156657,43.70995831489563,36.46272336162887,1739141204.3156674,43.70995831489563,-0.104,1739141204.3156695,43.70995831489563,-2.864899094102029,1739141204.315671,43.70995831489563,-2.2876758550356975,1739141204.3156729,43.70995831489563,-0.6108,1739141204.315674,43.70995831489563,1.001221134838605,1739141204.315676,43.70995831489563,0.0,1739141204.3156776,43.70995831489563,-0.04217634384006552,1739141204.3156793,43.70995831489563,3.910431123191584,1739141204.3156805,43.70995831489563,1.0433974786786706 +1739141204.3386803,43.729958295822144,41.12003757514063,1739141204.3386853,43.729958295822144,1.2185741765830667,1739141204.3386908,43.729958295822144,71.73409722865901,1739141204.3386972,43.729958295822144,36.46272336162887,1739141204.3387008,43.729958295822144,-0.104,1739141204.338705,43.729958295822144,-2.864899094102029,1739141204.3387094,43.729958295822144,-2.2876758550356975,1739141204.3387134,43.729958295822144,-0.6108,1739141204.3387175,43.729958295822144,1.001221134838605,1739141204.3387215,43.729958295822144,0.0,1739141204.3387258,43.729958295822144,-0.04217634384006552,1739141204.33873,43.729958295822144,3.910431123191584,1739141204.3387344,43.729958295822144,1.0433974786786706 +1739141204.355693,43.74995827674866,41.03675462038544,1739141204.3556962,43.74995827674866,1.14001153467595,1739141204.3556995,43.74995827674866,71.89091961139903,1739141204.3557029,43.74995827674866,36.321859545602074,1739141204.3557045,43.74995827674866,-0.104,1739141204.3557065,43.74995827674866,-2.8836244521718326,1739141204.3557084,43.74995827674866,-2.265264971899433,1739141204.35571,43.74995827674866,-0.6108,1739141204.3557115,43.74995827674866,1.010236784135294,1739141204.3557134,43.74995827674866,0.0,1739141204.355715,43.74995827674866,-0.01480918575515645,1739141204.3557167,43.74995827674866,3.8826880928139427,1739141204.3557181,43.74995827674866,1.03807795644093 +1739141204.3756542,43.76995825767517,41.03675462038544,1739141204.3756568,43.76995825767517,1.14001153467595,1739141204.3756597,43.76995825767517,71.89091961139903,1739141204.3756623,43.76995825767517,36.321859545602074,1739141204.3756635,43.76995825767517,-0.104,1739141204.3756652,43.76995825767517,-2.8836244521718326,1739141204.3756664,43.76995825767517,-2.265264971899433,1739141204.3756678,43.76995825767517,-0.6108,1739141204.3756688,43.76995825767517,1.010236784135294,1739141204.3756702,43.76995825767517,0.0,1739141204.3756716,43.76995825767517,-0.027841172305635986,1739141204.3756726,43.76995825767517,3.8826880928139427,1739141204.375674,43.76995825767517,1.03807795644093 +1739141204.3951077,43.789958238601685,41.03675462038544,1739141204.3951101,43.789958238601685,1.14001153467595,1739141204.395113,43.789958238601685,71.89091961139903,1739141204.3951159,43.789958238601685,36.321859545602074,1739141204.395117,43.789958238601685,-0.104,1739141204.395119,43.789958238601685,-2.8836244521718326,1739141204.3951201,43.789958238601685,-2.265264971899433,1739141204.3951213,43.789958238601685,-0.6108,1739141204.3951225,43.789958238601685,1.010236784135294,1739141204.3951242,43.789958238601685,0.0,1739141204.3951254,43.789958238601685,-0.027841172305635986,1739141204.3951268,43.789958238601685,3.8826880928139427,1739141204.395128,43.789958238601685,1.03807795644093 +1739141204.4151487,43.8099582195282,41.03675462038544,1739141204.4151514,43.8099582195282,1.14001153467595,1739141204.415154,43.8099582195282,71.89091961139903,1739141204.4151568,43.8099582195282,36.321859545602074,1739141204.415158,43.8099582195282,-0.104,1739141204.4151595,43.8099582195282,-2.8836244521718326,1739141204.4151611,43.8099582195282,-2.265264971899433,1739141204.415162,43.8099582195282,-0.6108,1739141204.4151633,43.8099582195282,1.010236784135294,1739141204.415165,43.8099582195282,0.0,1739141204.4151661,43.8099582195282,-0.027841172305635986,1739141204.4151676,43.8099582195282,3.8826880928139427,1739141204.4151688,43.8099582195282,1.03807795644093 +1739141204.4351475,43.82995820045471,41.03675462038544,1739141204.4351504,43.82995820045471,1.14001153467595,1739141204.4351535,43.82995820045471,71.89091961139903,1739141204.435156,43.82995820045471,36.321859545602074,1739141204.4351578,43.82995820045471,-0.104,1739141204.4351592,43.82995820045471,-2.8836244521718326,1739141204.4351606,43.82995820045471,-2.265264971899433,1739141204.4351618,43.82995820045471,-0.6108,1739141204.435163,43.82995820045471,1.010236784135294,1739141204.4351647,43.82995820045471,0.0,1739141204.4351661,43.82995820045471,-0.027841172305635986,1739141204.4351676,43.82995820045471,3.8826880928139427,1739141204.435169,43.82995820045471,1.03807795644093 +1739141204.4550834,43.849958181381226,40.951671337182646,1739141204.4550855,43.849958181381226,1.0640998554675374,1739141204.4550884,43.849958181381226,71.98653928095764,1739141204.4550912,43.849958181381226,36.23544915083185,1739141204.4550924,43.849958181381226,-0.104,1739141204.455094,43.849958181381226,-2.898801517019872,1739141204.4550953,43.849958181381226,-2.2028809539214254,1739141204.4550965,43.849958181381226,-0.6108,1739141204.455098,43.849958181381226,1.035762997014561,1739141204.4550996,43.849958181381226,0.0,1739141204.4551013,43.849958181381226,0.02675116103036525,1739141204.4551024,43.849958181381226,3.8549450624363013,1739141204.4551036,43.849958181381226,1.035008198178134 +1739141204.475327,43.86995816230774,40.951671337182646,1739141204.47533,43.86995816230774,1.0640998554675374,1739141204.4753332,43.86995816230774,71.98653928095764,1739141204.4753358,43.86995816230774,36.23544915083185,1739141204.4753375,43.86995816230774,-0.104,1739141204.475339,43.86995816230774,-2.898801517019872,1739141204.4753406,43.86995816230774,-2.2028809539214254,1739141204.4753418,43.86995816230774,-0.6108,1739141204.475343,43.86995816230774,1.035762997014561,1739141204.4753447,43.86995816230774,0.0,1739141204.4753458,43.86995816230774,0.0007547988364269287,1739141204.4753473,43.86995816230774,3.8549450624363013,1739141204.4753485,43.86995816230774,1.035008198178134 +1739141204.4952254,43.88995814323425,40.951671337182646,1739141204.495228,43.88995814323425,1.0640998554675374,1739141204.4952312,43.88995814323425,71.98653928095764,1739141204.495234,43.88995814323425,36.23544915083185,1739141204.495236,43.88995814323425,-0.104,1739141204.4952376,43.88995814323425,-2.898801517019872,1739141204.4952393,43.88995814323425,-2.2028809539214254,1739141204.4952404,43.88995814323425,-0.6108,1739141204.4952416,43.88995814323425,1.035762997014561,1739141204.4952435,43.88995814323425,0.0,1739141204.495245,43.88995814323425,0.0007547988364269287,1739141204.4952466,43.88995814323425,3.8549450624363013,1739141204.4952478,43.88995814323425,1.035008198178134 +1739141204.515539,43.90995812416077,40.951671337182646,1739141204.515542,43.90995812416077,1.0640998554675374,1739141204.5155456,43.90995812416077,71.98653928095764,1739141204.5155487,43.90995812416077,36.23544915083185,1739141204.5155504,43.90995812416077,-0.104,1739141204.5155523,43.90995812416077,-2.898801517019872,1739141204.515554,43.90995812416077,-2.2028809539214254,1739141204.5155556,43.90995812416077,-0.6108,1739141204.515557,43.90995812416077,1.035762997014561,1739141204.5155592,43.90995812416077,0.0,1739141204.5155609,43.90995812416077,0.0007547988364269287,1739141204.5155625,43.90995812416077,3.8549450624363013,1739141204.515564,43.90995812416077,1.035008198178134 +1739141204.5364199,43.92995810508728,40.951671337182646,1739141204.5364232,43.92995810508728,1.0640998554675374,1739141204.536427,43.92995810508728,71.98653928095764,1739141204.5364306,43.92995810508728,36.23544915083185,1739141204.5364323,43.92995810508728,-0.104,1739141204.5364347,43.92995810508728,-2.898801517019872,1739141204.5364366,43.92995810508728,-2.2028809539214254,1739141204.536438,43.92995810508728,-0.6108,1739141204.5364397,43.92995810508728,1.035762997014561,1739141204.5364418,43.92995810508728,0.0,1739141204.5364437,43.92995810508728,0.0007547988364269287,1739141204.5364451,43.92995810508728,3.8549450624363013,1739141204.536447,43.92995810508728,1.035008198178134 +1739141204.556039,43.949958086013794,40.951671337182646,1739141204.556043,43.949958086013794,1.0640998554675374,1739141204.5560465,43.949958086013794,71.98653928095764,1739141204.55605,43.949958086013794,36.23544915083185,1739141204.556052,43.949958086013794,-0.104,1739141204.5560544,43.949958086013794,-2.898801517019872,1739141204.556056,43.949958086013794,-2.2028809539214254,1739141204.556058,43.949958086013794,-0.6108,1739141204.5560596,43.949958086013794,1.035762997014561,1739141204.5560617,43.949958086013794,0.0,1739141204.5560634,43.949958086013794,0.0007547988364269287,1739141204.5560653,43.949958086013794,3.8549450624363013,1739141204.556067,43.949958086013794,1.035008198178134 +1739141204.5759904,43.96995806694031,40.864635260981665,1739141204.575996,43.96995806694031,0.9906800822543556,1739141204.5760021,43.96995806694031,72.12493282793235,1739141204.5760121,43.96995806694031,36.09610233127621,1739141204.5760171,43.96995806694031,-0.104,1739141204.5760207,43.96995806694031,-2.915939078969716,1739141204.5760226,43.96995806694031,-2.171852958924745,1739141204.5760243,43.96995806694031,-0.6108,1739141204.5760262,43.96995806694031,1.048698161049569,1739141204.576028,43.96995806694031,0.0,1739141204.5760303,43.96995806694031,0.024842585836219608,1739141204.5760317,43.96995806694031,3.82720203205866,1739141204.5760336,43.96995806694031,1.0353259557051115 +1739141204.595901,43.98995804786682,40.864635260981665,1739141204.5959046,43.98995804786682,0.9906800822543556,1739141204.5959084,43.98995804786682,72.12493282793235,1739141204.595912,43.98995804786682,36.09610233127621,1739141204.595914,43.98995804786682,-0.104,1739141204.5959163,43.98995804786682,-2.915939078969716,1739141204.5959182,43.98995804786682,-2.171852958924745,1739141204.59592,43.98995804786682,-0.6108,1739141204.5959218,43.98995804786682,1.048698161049569,1739141204.595924,43.98995804786682,0.0,1739141204.5959258,43.98995804786682,0.013372205344457377,1739141204.5959272,43.98995804786682,3.82720203205866,1739141204.5959291,43.98995804786682,1.0353259557051115 +1739141204.61597,44.009958028793335,40.864635260981665,1739141204.6159735,44.009958028793335,0.9906800822543556,1739141204.6159773,44.009958028793335,72.12493282793235,1739141204.615981,44.009958028793335,36.09610233127621,1739141204.6159828,44.009958028793335,-0.104,1739141204.6159852,44.009958028793335,-2.915939078969716,1739141204.6159873,44.009958028793335,-2.171852958924745,1739141204.615989,44.009958028793335,-0.6108,1739141204.6159906,44.009958028793335,1.048698161049569,1739141204.615993,44.009958028793335,0.0,1739141204.6159947,44.009958028793335,0.013372205344457377,1739141204.6159964,44.009958028793335,3.82720203205866,1739141204.6159983,44.009958028793335,1.0353259557051115 +1739141204.6361685,44.02995800971985,40.864635260981665,1739141204.6361718,44.02995800971985,0.9906800822543556,1739141204.6361754,44.02995800971985,72.12493282793235,1739141204.636179,44.02995800971985,36.09610233127621,1739141204.6361806,44.02995800971985,-0.104,1739141204.636183,44.02995800971985,-2.915939078969716,1739141204.636185,44.02995800971985,-2.171852958924745,1739141204.6361864,44.02995800971985,-0.6108,1739141204.6361878,44.02995800971985,1.048698161049569,1739141204.6361904,44.02995800971985,0.0,1739141204.6361923,44.02995800971985,0.013372205344457377,1739141204.6361938,44.02995800971985,3.82720203205866,1739141204.6361957,44.02995800971985,1.0353259557051115 +1739141204.655927,44.04995799064636,40.864635260981665,1739141204.6559303,44.04995799064636,0.9906800822543556,1739141204.655934,44.04995799064636,72.12493282793235,1739141204.6559381,44.04995799064636,36.09610233127621,1739141204.65594,44.04995799064636,-0.104,1739141204.6559422,44.04995799064636,-2.915939078969716,1739141204.655944,44.04995799064636,-2.171852958924745,1739141204.6559458,44.04995799064636,-0.6108,1739141204.6559472,44.04995799064636,1.048698161049569,1739141204.6559496,44.04995799064636,0.0,1739141204.6559513,44.04995799064636,0.013372205344457377,1739141204.6559532,44.04995799064636,3.82720203205866,1739141204.6559548,44.04995799064636,1.0353259557051115 +1739141204.6763844,44.069957971572876,40.77552138105827,1739141204.6763878,44.069957971572876,0.9196437466690046,1739141204.6763914,44.069957971572876,72.24278457680369,1739141204.6763952,44.069957971572876,35.97354575085276,1739141204.6763968,44.069957971572876,-0.104,1739141204.676399,44.069957971572876,-2.9315649805577424,1739141204.6764007,44.069957971572876,-2.1260635535046672,1739141204.6764023,44.069957971572876,-0.6108,1739141204.676404,44.069957971572876,1.0680828479030282,1739141204.676406,44.069957971572876,0.0,1739141204.676408,44.069957971572876,0.04738536652341663,1739141204.6764095,44.069957971572876,3.7994590016810186,1739141204.6764114,44.069957971572876,1.0368942328891486 +1739141204.6959355,44.08995795249939,40.77552138105827,1739141204.6959395,44.08995795249939,0.9196437466690046,1739141204.6959434,44.08995795249939,72.24278457680369,1739141204.6959472,44.08995795249939,35.97354575085276,1739141204.695949,44.08995795249939,-0.104,1739141204.6959515,44.08995795249939,-2.9315649805577424,1739141204.6959531,44.08995795249939,-2.1260635535046672,1739141204.695955,44.08995795249939,-0.6108,1739141204.6959565,44.08995795249939,1.0680828479030282,1739141204.6959586,44.08995795249939,0.0,1739141204.6959605,44.08995795249939,0.031188615013879595,1739141204.6959622,44.08995795249939,3.7994590016810186,1739141204.6959639,44.08995795249939,1.0368942328891486 +1739141204.7157254,44.1099579334259,40.77552138105827,1739141204.7157292,44.1099579334259,0.9196437466690046,1739141204.715733,44.1099579334259,72.24278457680369,1739141204.7157366,44.1099579334259,35.97354575085276,1739141204.7157383,44.1099579334259,-0.104,1739141204.7157407,44.1099579334259,-2.9315649805577424,1739141204.7157428,44.1099579334259,-2.1260635535046672,1739141204.7157445,44.1099579334259,-0.6108,1739141204.7157462,44.1099579334259,1.0680828479030282,1739141204.7157483,44.1099579334259,0.0,1739141204.7157505,44.1099579334259,0.031188615013879595,1739141204.7157521,44.1099579334259,3.7994590016810186,1739141204.7157538,44.1099579334259,1.0368942328891486 +1739141204.7363358,44.12995791435242,40.77552138105827,1739141204.736339,44.12995791435242,0.9196437466690046,1739141204.7363431,44.12995791435242,72.24278457680369,1739141204.7363467,44.12995791435242,35.97354575085276,1739141204.7363486,44.12995791435242,-0.104,1739141204.736351,44.12995791435242,-2.9315649805577424,1739141204.7363527,44.12995791435242,-2.1260635535046672,1739141204.7363544,44.12995791435242,-0.6108,1739141204.7363558,44.12995791435242,1.0680828479030282,1739141204.7363582,44.12995791435242,0.0,1739141204.7363598,44.12995791435242,0.031188615013879595,1739141204.7363615,44.12995791435242,3.7994590016810186,1739141204.7363632,44.12995791435242,1.0368942328891486 +1739141204.756473,44.15995788574219,40.77552138105827,1739141204.7564762,44.15995788574219,0.9196437466690046,1739141204.7564802,44.15995788574219,72.24278457680369,1739141204.756484,44.15995788574219,35.97354575085276,1739141204.756486,44.15995788574219,-0.104,1739141204.7564878,44.15995788574219,-2.9315649805577424,1739141204.7564898,44.15995788574219,-2.1260635535046672,1739141204.7564914,44.15995788574219,-0.6108,1739141204.756493,44.15995788574219,1.0680828479030282,1739141204.7564955,44.15995788574219,0.0,1739141204.7564971,44.15995788574219,0.031188615013879595,1739141204.7564986,44.15995788574219,3.7994590016810186,1739141204.7565005,44.15995788574219,1.0368942328891486 +1739141204.7782748,44.169957876205444,40.77552138105827,1739141204.7782798,44.169957876205444,0.9196437466690046,1739141204.778285,44.169957876205444,72.24278457680369,1739141204.7782912,44.169957876205444,35.97354575085276,1739141204.7782948,44.169957876205444,-0.104,1739141204.7782993,44.169957876205444,-2.9315649805577424,1739141204.7783034,44.169957876205444,-2.1260635535046672,1739141204.7783077,44.169957876205444,-0.6108,1739141204.7783115,44.169957876205444,1.0680828479030282,1739141204.7783158,44.169957876205444,0.0,1739141204.7783196,44.169957876205444,0.031188615013879595,1739141204.7783237,44.169957876205444,3.7994590016810186,1739141204.7783275,44.169957876205444,1.0368942328891486 +1739141204.7955523,44.18995785713196,40.68425284169525,1739141204.7955554,44.18995785713196,0.8509429277244625,1739141204.7955587,44.18995785713196,72.41576580103238,1739141204.795562,44.18995785713196,35.789880824505865,1739141204.7955637,44.18995785713196,-0.10314447402432877,1739141204.7955656,44.18995785713196,-2.9490714067613992,1739141204.795567,44.18995785713196,-2.1131217469963346,1739141204.7955687,44.18995785713196,-0.6108,1739141204.7955701,44.18995785713196,1.0736263527376135,1739141204.795572,44.18995785713196,0.0,1739141204.7955737,44.18995785713196,0.03497030910517166,1739141204.7955751,44.18995785713196,3.771715971303377,1739141204.7955763,44.18995785713196,1.040456851242163 +1739141204.8153992,44.20995783805847,40.68425284169525,1739141204.8154023,44.20995783805847,0.8509429277244625,1739141204.8154056,44.20995783805847,72.41576580103238,1739141204.8154087,44.20995783805847,35.789880824505865,1739141204.8154104,44.20995783805847,-0.10314447402432877,1739141204.8154125,44.20995783805847,-2.9490714067613992,1739141204.815414,44.20995783805847,-2.1131217469963346,1739141204.8154156,44.20995783805847,-0.6108,1739141204.8154168,44.20995783805847,1.0736263527376135,1739141204.815419,44.20995783805847,0.0,1739141204.8154204,44.20995783805847,0.033169501495450504,1739141204.8154216,44.20995783805847,3.771715971303377,1739141204.8154233,44.20995783805847,1.040456851242163 +1739141204.835472,44.229957818984985,40.68425284169525,1739141204.8354752,44.229957818984985,0.8509429277244625,1739141204.8354783,44.229957818984985,72.41576580103238,1739141204.8354814,44.229957818984985,35.789880824505865,1739141204.8354828,44.229957818984985,-0.10314447402432877,1739141204.8354847,44.229957818984985,-2.9490714067613992,1739141204.835486,44.229957818984985,-2.1131217469963346,1739141204.8354876,44.229957818984985,-0.6108,1739141204.8354888,44.229957818984985,1.0736263527376135,1739141204.8354902,44.229957818984985,0.0,1739141204.835492,44.229957818984985,0.033169501495450504,1739141204.835493,44.229957818984985,3.771715971303377,1739141204.8354948,44.229957818984985,1.040456851242163 +1739141204.8550854,44.2499577999115,40.68425284169525,1739141204.8550878,44.2499577999115,0.8509429277244625,1739141204.8550906,44.2499577999115,72.41576580103238,1739141204.8550935,44.2499577999115,35.789880824505865,1739141204.8550951,44.2499577999115,-0.10314447402432877,1739141204.8550966,44.2499577999115,-2.9490714067613992,1739141204.855098,44.2499577999115,-2.1131217469963346,1739141204.8550994,44.2499577999115,-0.6108,1739141204.8551006,44.2499577999115,1.0736263527376135,1739141204.8551025,44.2499577999115,0.0,1739141204.855104,44.2499577999115,0.033169501495450504,1739141204.8551052,44.2499577999115,3.771715971303377,1739141204.8551066,44.2499577999115,1.040456851242163 +1739141204.8760297,44.26995778083801,40.68425284169525,1739141204.8760328,44.26995778083801,0.8509429277244625,1739141204.8760357,44.26995778083801,72.41576580103238,1739141204.8760383,44.26995778083801,35.789880824505865,1739141204.8760405,44.26995778083801,-0.10314447402432877,1739141204.8760421,44.26995778083801,-2.9490714067613992,1739141204.8760436,44.26995778083801,-2.1131217469963346,1739141204.876045,44.26995778083801,-0.6108,1739141204.8760464,44.26995778083801,1.0736263527376135,1739141204.876048,44.26995778083801,0.0,1739141204.8760498,44.26995778083801,0.033169501495450504,1739141204.876051,44.26995778083801,3.771715971303377,1739141204.8760521,44.26995778083801,1.040456851242163 +1739141204.8959713,44.289957761764526,40.59079440491641,1739141204.8959742,44.289957761764526,0.7845735312497837,1739141204.895977,44.289957761764526,72.53510374856238,1739141204.89598,44.289957761764526,35.659666787961385,1739141204.8959813,44.289957761764526,-0.102,1739141204.8959827,44.289957761764526,-2.9637019346198934,1739141204.8959842,44.289957761764526,-2.063476500790405,1739141204.8959856,44.289957761764526,-0.6108,1739141204.8959868,44.289957761764526,1.0951596279110953,1739141204.8959885,44.289957761764526,0.0,1739141204.8959897,44.289957761764526,0.06735381397997817,1739141204.895991,44.289957761764526,3.743972940925736,1739141204.8959923,44.289957761764526,1.0440840661030666 +1739141204.9151318,44.30995774269104,40.59079440491641,1739141204.9151344,44.30995774269104,0.7845735312497837,1739141204.9151375,44.30995774269104,72.53510374856238,1739141204.9151404,44.30995774269104,35.659666787961385,1739141204.9151418,44.30995774269104,-0.102,1739141204.9151435,44.30995774269104,-2.9637019346198934,1739141204.9151447,44.30995774269104,-2.063476500790405,1739141204.9151459,44.30995774269104,-0.6108,1739141204.9151473,44.30995774269104,1.0951596279110953,1739141204.9151487,44.30995774269104,0.0,1739141204.9151502,44.30995774269104,0.05107556180802875,1739141204.9151514,44.30995774269104,3.743972940925736,1739141204.9151523,44.30995774269104,1.0440840661030666 +1739141204.9358225,44.329957723617554,40.59079440491641,1739141204.9358253,44.329957723617554,0.7845735312497837,1739141204.9358287,44.329957723617554,72.53510374856238,1739141204.9358315,44.329957723617554,35.659666787961385,1739141204.9358327,44.329957723617554,-0.102,1739141204.9358346,44.329957723617554,-2.9637019346198934,1739141204.935836,44.329957723617554,-2.063476500790405,1739141204.9358375,44.329957723617554,-0.6108,1739141204.9358387,44.329957723617554,1.0951596279110953,1739141204.9358406,44.329957723617554,0.0,1739141204.935842,44.329957723617554,0.05107556180802875,1739141204.9358435,44.329957723617554,3.743972940925736,1739141204.9358451,44.329957723617554,1.0440840661030666 +1739141204.9550908,44.34995770454407,40.59079440491641,1739141204.9550936,44.34995770454407,0.7845735312497837,1739141204.9550962,44.34995770454407,72.53510374856238,1739141204.955099,44.34995770454407,35.659666787961385,1739141204.9551003,44.34995770454407,-0.102,1739141204.955102,44.34995770454407,-2.9637019346198934,1739141204.9551034,44.34995770454407,-2.063476500790405,1739141204.9551048,44.34995770454407,-0.6108,1739141204.955106,44.34995770454407,1.0951596279110953,1739141204.9551077,44.34995770454407,0.0,1739141204.9551091,44.34995770454407,0.05107556180802875,1739141204.9551105,44.34995770454407,3.743972940925736,1739141204.955112,44.34995770454407,1.0440840661030666 +1739141204.9752982,44.36995768547058,40.59079440491641,1739141204.975301,44.36995768547058,0.7845735312497837,1739141204.9753044,44.36995768547058,72.53510374856238,1739141204.9753072,44.36995768547058,35.659666787961385,1739141204.975309,44.36995768547058,-0.102,1739141204.9753103,44.36995768547058,-2.9637019346198934,1739141204.9753118,44.36995768547058,-2.063476500790405,1739141204.9753134,44.36995768547058,-0.6108,1739141204.9753144,44.36995768547058,1.0951596279110953,1739141204.975316,44.36995768547058,0.0,1739141204.9753175,44.36995768547058,0.05107556180802875,1739141204.9753187,44.36995768547058,3.743972940925736,1739141204.97532,44.36995768547058,1.0440840661030666 +1739141204.9951537,44.389957666397095,40.59079440491641,1739141204.9951568,44.389957666397095,0.7845735312497837,1739141204.9951599,44.389957666397095,72.53510374856238,1739141204.9951627,44.389957666397095,35.659666787961385,1739141204.9951642,44.389957666397095,-0.102,1739141204.995166,44.389957666397095,-2.9637019346198934,1739141204.9951675,44.389957666397095,-2.063476500790405,1739141204.9951687,44.389957666397095,-0.6108,1739141204.99517,44.389957666397095,1.0951596279110953,1739141204.9951715,44.389957666397095,0.0,1739141204.9951732,44.389957666397095,0.05107556180802875,1739141204.9951744,44.389957666397095,3.743972940925736,1739141204.9951756,44.389957666397095,1.0440840661030666 +1739141205.015377,44.40995764732361,40.49510815597043,1739141205.01538,44.40995764732361,0.720539932799471,1739141205.0153828,44.40995764732361,72.6552133745094,1739141205.015386,44.40995764732361,35.522333637977674,1739141205.0153873,44.40995764732361,-0.1014989666955135,1739141205.0153892,44.40995764732361,-2.9777663126048255,1739141205.0153904,44.40995764732361,-2.012843006268045,1739141205.0153918,44.40995764732361,-0.6003612470251389,1739141205.015393,44.40995764732361,1.117566472957007,1739141205.0153944,44.40995764732361,0.0,1739141205.015396,44.40995764732361,0.08289086587306545,1739141205.0153973,44.40995764732361,3.7162299105480945,1739141205.0153987,44.40995764732361,1.0498257594449791 +1739141205.0357254,44.42995762825012,40.49510815597043,1739141205.0357285,44.42995762825012,0.720539932799471,1739141205.0357318,44.42995762825012,72.6552133745094,1739141205.0357344,44.42995762825012,35.522333637977674,1739141205.035736,44.42995762825012,-0.1014989666955135,1739141205.0357375,44.42995762825012,-2.9777663126048255,1739141205.0357392,44.42995762825012,-2.012843006268045,1739141205.0357404,44.42995762825012,-0.6003612470251389,1739141205.0357418,44.42995762825012,1.117566472957007,1739141205.0357432,44.42995762825012,0.0,1739141205.0357447,44.42995762825012,0.06774071351202782,1739141205.0357463,44.42995762825012,3.7162299105480945,1739141205.0357478,44.42995762825012,1.0498257594449791 +1739141205.0549016,44.449957609176636,40.49510815597043,1739141205.0549042,44.449957609176636,0.720539932799471,1739141205.054907,44.449957609176636,72.6552133745094,1739141205.05491,44.449957609176636,35.522333637977674,1739141205.0549114,44.449957609176636,-0.1014989666955135,1739141205.0549133,44.449957609176636,-2.9777663126048255,1739141205.0549147,44.449957609176636,-2.012843006268045,1739141205.0549161,44.449957609176636,-0.6003612470251389,1739141205.0549173,44.449957609176636,1.117566472957007,1739141205.0549192,44.449957609176636,0.0,1739141205.0549207,44.449957609176636,0.06774071351202782,1739141205.0549219,44.449957609176636,3.7162299105480945,1739141205.0549233,44.449957609176636,1.0498257594449791 +1739141205.075441,44.46995759010315,40.49510815597043,1739141205.075444,44.46995759010315,0.720539932799471,1739141205.075447,44.46995759010315,72.6552133745094,1739141205.07545,44.46995759010315,35.522333637977674,1739141205.0754514,44.46995759010315,-0.1014989666955135,1739141205.0754533,44.46995759010315,-2.9777663126048255,1739141205.0754545,44.46995759010315,-2.012843006268045,1739141205.0754557,44.46995759010315,-0.6003612470251389,1739141205.075457,44.46995759010315,1.117566472957007,1739141205.0754585,44.46995759010315,0.0,1739141205.0754602,44.46995759010315,0.06774071351202782,1739141205.0754614,44.46995759010315,3.7162299105480945,1739141205.0754626,44.46995759010315,1.0498257594449791 +1739141205.0950797,44.48995757102966,40.49510815597043,1739141205.0950823,44.48995757102966,0.720539932799471,1739141205.0950851,44.48995757102966,72.6552133745094,1739141205.0950878,44.48995757102966,35.522333637977674,1739141205.0950894,44.48995757102966,-0.1014989666955135,1739141205.095091,44.48995757102966,-2.9777663126048255,1739141205.0950925,44.48995757102966,-2.012843006268045,1739141205.095094,44.48995757102966,-0.6003612470251389,1739141205.0950954,44.48995757102966,1.117566472957007,1739141205.0950968,44.48995757102966,0.0,1739141205.0950983,44.48995757102966,0.06774071351202782,1739141205.0950997,44.48995757102966,3.7162299105480945,1739141205.0951009,44.48995757102966,1.0498257594449791 +1739141205.115264,44.50995755195618,40.39708664320925,1739141205.1152666,44.50995755195618,0.6588105398694255,1739141205.1152697,44.50995755195618,72.71876397505125,1739141205.1152725,44.50995755195618,35.436622668123,1739141205.1152742,44.50995755195618,-0.101,1739141205.1152759,44.50995755195618,-2.9896007071581603,1739141205.115277,44.50995755195618,-1.930637198892673,1739141205.1152785,44.50995755195618,-0.5813807029436522,1739141205.11528,44.50995755195618,1.1549255145384163,1739141205.1152813,44.50995755195618,0.0,1739141205.115283,44.50995755195618,0.12495950686251034,1739141205.1152842,44.50995755195618,3.688486880170453,1739141205.1152854,44.50995755195618,1.0572130657396126 +1739141205.1357424,44.52995753288269,40.39708664320925,1739141205.1357465,44.52995753288269,0.6588105398694255,1739141205.13575,44.52995753288269,72.71876397505125,1739141205.1357534,44.52995753288269,35.436622668123,1739141205.1357555,44.52995753288269,-0.101,1739141205.1357577,44.52995753288269,-2.9896007071581603,1739141205.135759,44.52995753288269,-1.930637198892673,1739141205.1357605,44.52995753288269,-0.5813807029436522,1739141205.1357622,44.52995753288269,1.1549255145384163,1739141205.135764,44.52995753288269,0.0,1739141205.1357658,44.52995753288269,0.0977124487988037,1739141205.1357675,44.52995753288269,3.688486880170453,1739141205.1357691,44.52995753288269,1.0572130657396126 +1739141205.155406,44.549957513809204,40.39708664320925,1739141205.1554089,44.549957513809204,0.6588105398694255,1739141205.155412,44.549957513809204,72.71876397505125,1739141205.1554153,44.549957513809204,35.436622668123,1739141205.1554172,44.549957513809204,-0.101,1739141205.1554189,44.549957513809204,-2.9896007071581603,1739141205.1554203,44.549957513809204,-1.930637198892673,1739141205.1554217,44.549957513809204,-0.5813807029436522,1739141205.1554232,44.549957513809204,1.1549255145384163,1739141205.155425,44.549957513809204,0.0,1739141205.1554265,44.549957513809204,0.0977124487988037,1739141205.155428,44.549957513809204,3.688486880170453,1739141205.1554294,44.549957513809204,1.0572130657396126 +1739141205.175438,44.56995749473572,40.39708664320925,1739141205.1754405,44.56995749473572,0.6588105398694255,1739141205.1754436,44.56995749473572,72.71876397505125,1739141205.1754467,44.56995749473572,35.436622668123,1739141205.1754484,44.56995749473572,-0.101,1739141205.17545,44.56995749473572,-2.9896007071581603,1739141205.1754518,44.56995749473572,-1.930637198892673,1739141205.175453,44.56995749473572,-0.5813807029436522,1739141205.1754544,44.56995749473572,1.1549255145384163,1739141205.175456,44.56995749473572,0.0,1739141205.1754575,44.56995749473572,0.0977124487988037,1739141205.1754591,44.56995749473572,3.688486880170453,1739141205.1754603,44.56995749473572,1.0572130657396126 +1739141205.1955168,44.58995747566223,40.39708664320925,1739141205.19552,44.58995747566223,0.6588105398694255,1739141205.1955233,44.58995747566223,72.71876397505125,1739141205.1955264,44.58995747566223,35.436622668123,1739141205.195528,44.58995747566223,-0.101,1739141205.1955297,44.58995747566223,-2.9896007071581603,1739141205.1955314,44.58995747566223,-1.930637198892673,1739141205.1955328,44.58995747566223,-0.5813807029436522,1739141205.195534,44.58995747566223,1.1549255145384163,1739141205.195536,44.58995747566223,0.0,1739141205.1955373,44.58995747566223,0.0977124487988037,1739141205.195539,44.58995747566223,3.688486880170453,1739141205.1955402,44.58995747566223,1.0572130657396126 +1739141205.2154138,44.609957456588745,40.39708664320925,1739141205.2154167,44.609957456588745,0.6588105398694255,1739141205.2154195,44.609957456588745,72.71876397505125,1739141205.2154226,44.609957456588745,35.436622668123,1739141205.2154243,44.609957456588745,-0.101,1739141205.215426,44.609957456588745,-2.9896007071581603,1739141205.2154276,44.609957456588745,-1.930637198892673,1739141205.2154288,44.609957456588745,-0.5813807029436522,1739141205.2154303,44.609957456588745,1.1549255145384163,1739141205.215432,44.609957456588745,0.0,1739141205.2154338,44.609957456588745,0.0977124487988037,1739141205.215435,44.609957456588745,3.688486880170453,1739141205.2154362,44.609957456588745,1.0572130657396126 +1739141205.235658,44.62995743751526,40.29654599984664,1739141205.2356613,44.62995743751526,0.5993252263598494,1739141205.2356644,44.62995743751526,72.89973432889822,1739141205.2356677,44.62995743751526,35.223621872938146,1739141205.2356696,44.62995743751526,-0.10010018855981159,1739141205.2356715,44.62995743751526,-3.0045822416401853,1739141205.2356732,44.62995743751526,-1.909628017871647,1739141205.2356744,44.62995743751526,-0.552914967812033,1739141205.2356758,44.62995743751526,1.1646720261043324,1739141205.2356777,44.62995743751526,0.0,1739141205.2356791,44.62995743751526,0.0959339484039042,1739141205.2356806,44.62995743751526,3.6607438497928118,1739141205.235682,44.62995743751526,1.0678911723274098 +1739141205.255338,44.64995741844177,40.29654599984664,1739141205.255341,44.64995741844177,0.5993252263598494,1739141205.2553444,44.64995741844177,72.89973432889822,1739141205.2553475,44.64995741844177,35.223621872938146,1739141205.255349,44.64995741844177,-0.10010018855981159,1739141205.2553508,44.64995741844177,-3.0045822416401853,1739141205.2553523,44.64995741844177,-1.909628017871647,1739141205.255354,44.64995741844177,-0.552914967812033,1739141205.2553554,44.64995741844177,1.1646720261043324,1739141205.2553573,44.64995741844177,0.0,1739141205.2553587,44.64995741844177,0.09678085377692258,1739141205.25536,44.64995741844177,3.6607438497928118,1739141205.2553613,44.64995741844177,1.0678911723274098 +1739141205.2753582,44.669957399368286,40.29654599984664,1739141205.2753623,44.669957399368286,0.5993252263598494,1739141205.2753658,44.669957399368286,72.89973432889822,1739141205.2753692,44.669957399368286,35.223621872938146,1739141205.2753716,44.669957399368286,-0.10010018855981159,1739141205.2753735,44.669957399368286,-3.0045822416401853,1739141205.2753754,44.669957399368286,-1.909628017871647,1739141205.2753768,44.669957399368286,-0.552914967812033,1739141205.2753787,44.669957399368286,1.1646720261043324,1739141205.2753804,44.669957399368286,0.0,1739141205.2753823,44.669957399368286,0.09678085377692258,1739141205.275384,44.669957399368286,3.6607438497928118,1739141205.2753856,44.669957399368286,1.0678911723274098 +1739141205.2951734,44.6899573802948,40.29654599984664,1739141205.295176,44.6899573802948,0.5993252263598494,1739141205.2951794,44.6899573802948,72.89973432889822,1739141205.295182,44.6899573802948,35.223621872938146,1739141205.295184,44.6899573802948,-0.10010018855981159,1739141205.2951856,44.6899573802948,-3.0045822416401853,1739141205.2951875,44.6899573802948,-1.909628017871647,1739141205.2951887,44.6899573802948,-0.552914967812033,1739141205.2951903,44.6899573802948,1.1646720261043324,1739141205.295192,44.6899573802948,0.0,1739141205.2951937,44.6899573802948,0.09678085377692258,1739141205.295195,44.6899573802948,3.6607438497928118,1739141205.2951965,44.6899573802948,1.0678911723274098 +1739141205.3151658,44.70995736122131,40.29654599984664,1739141205.3151689,44.70995736122131,0.5993252263598494,1739141205.315172,44.70995736122131,72.89973432889822,1739141205.3151748,44.70995736122131,35.223621872938146,1739141205.3151765,44.70995736122131,-0.10010018855981159,1739141205.3151782,44.70995736122131,-3.0045822416401853,1739141205.3151798,44.70995736122131,-1.909628017871647,1739141205.3151813,44.70995736122131,-0.552914967812033,1739141205.315183,44.70995736122131,1.1646720261043324,1739141205.3151846,44.70995736122131,0.0,1739141205.3151863,44.70995736122131,0.09678085377692258,1739141205.3151875,44.70995736122131,3.6607438497928118,1739141205.315189,44.70995736122131,1.0678911723274098 +1739141205.3356187,44.72995734214783,40.193367017063196,1739141205.335622,44.72995734214783,0.5420819143709306,1739141205.3356254,44.72995734214783,72.90120144993958,1739141205.335629,44.72995734214783,35.190371681803214,1739141205.3356307,44.72995734214783,-0.1,1739141205.3356323,44.72995734214783,-3.013950899788882,1739141205.335634,44.72995734214783,-1.7946489738395743,1739141205.3356354,44.72995734214783,-0.5359575521407858,1739141205.3356369,44.72995734214783,1.2194880534273587,1739141205.3356388,44.72995734214783,0.0,1739141205.3356404,44.72995734214783,0.18120380668453462,1739141205.3356416,44.72995734214783,3.6330008194151704,1739141205.335643,44.72995734214783,1.0784856729716747 +1739141205.3553092,44.74995732307434,40.193367017063196,1739141205.3553123,44.74995732307434,0.5420819143709306,1739141205.3553154,44.74995732307434,72.90120144993958,1739141205.3553185,44.74995732307434,35.190371681803214,1739141205.35532,44.74995732307434,-0.1,1739141205.355322,44.74995732307434,-3.013950899788882,1739141205.3553233,44.74995732307434,-1.7946489738395743,1739141205.355325,44.74995732307434,-0.5359575521407858,1739141205.3553262,44.74995732307434,1.2194880534273587,1739141205.355328,44.74995732307434,0.0,1739141205.3553295,44.74995732307434,0.14100238045568392,1739141205.3553312,44.74995732307434,3.6330008194151704,1739141205.3553324,44.74995732307434,1.0784856729716747 +1739141205.3772967,44.769957304000854,40.193367017063196,1739141205.3773003,44.769957304000854,0.5420819143709306,1739141205.3773048,44.769957304000854,72.90120144993958,1739141205.37731,44.769957304000854,35.190371681803214,1739141205.3773131,44.769957304000854,-0.1,1739141205.377317,44.769957304000854,-3.013950899788882,1739141205.3773205,44.769957304000854,-1.7946489738395743,1739141205.3773239,44.769957304000854,-0.5359575521407858,1739141205.3773272,44.769957304000854,1.2194880534273587,1739141205.3773308,44.769957304000854,0.0,1739141205.377334,44.769957304000854,0.14100238045568392,1739141205.3773375,44.769957304000854,3.6330008194151704,1739141205.3773406,44.769957304000854,1.0784856729716747 +1739141205.3952174,44.78995728492737,40.193367017063196,1739141205.39522,44.78995728492737,0.5420819143709306,1739141205.3952224,44.78995728492737,72.90120144993958,1739141205.3952248,44.78995728492737,35.190371681803214,1739141205.395226,44.78995728492737,-0.1,1739141205.3952277,44.78995728492737,-3.013950899788882,1739141205.3952289,44.78995728492737,-1.7946489738395743,1739141205.3952303,44.78995728492737,-0.5359575521407858,1739141205.3952312,44.78995728492737,1.2194880534273587,1739141205.3952327,44.78995728492737,0.0,1739141205.395234,44.78995728492737,0.14100238045568392,1739141205.3952353,44.78995728492737,3.6330008194151704,1739141205.3952365,44.78995728492737,1.0784856729716747 +1739141205.415431,44.80995726585388,40.193367017063196,1739141205.4154334,44.80995726585388,0.5420819143709306,1739141205.4154363,44.80995726585388,72.90120144993958,1739141205.4154391,44.80995726585388,35.190371681803214,1739141205.4154403,44.80995726585388,-0.1,1739141205.4154422,44.80995726585388,-3.013950899788882,1739141205.4154437,44.80995726585388,-1.7946489738395743,1739141205.415445,44.80995726585388,-0.5359575521407858,1739141205.415446,44.80995726585388,1.2194880534273587,1739141205.4154477,44.80995726585388,0.0,1739141205.4154491,44.80995726585388,0.14100238045568392,1739141205.41545,44.80995726585388,3.6330008194151704,1739141205.415451,44.80995726585388,1.0784856729716747 +1739141205.4353538,44.829957246780396,40.193367017063196,1739141205.4353566,44.829957246780396,0.5420819143709306,1739141205.4353595,44.829957246780396,72.90120144993958,1739141205.435362,44.829957246780396,35.190371681803214,1739141205.4353638,44.829957246780396,-0.1,1739141205.4353654,44.829957246780396,-3.013950899788882,1739141205.4353666,44.829957246780396,-1.7946489738395743,1739141205.4353678,44.829957246780396,-0.5359575521407858,1739141205.4353693,44.829957246780396,1.2194880534273587,1739141205.4353707,44.829957246780396,0.0,1739141205.4353724,44.829957246780396,0.14100238045568392,1739141205.4353733,44.829957246780396,3.6330008194151704,1739141205.4353745,44.829957246780396,1.0784856729716747 +1739141205.455096,44.84995722770691,40.08736795554843,1739141205.4550986,44.84995722770691,0.48706410540416645,1739141205.4551015,44.84995722770691,73.08525737209091,1739141205.4551046,44.84995722770691,34.95889365229706,1739141205.4551058,44.84995722770691,-0.1,1739141205.4551077,44.84995722770691,-3.027617267733538,1739141205.455109,44.84995722770691,-1.7685223296613133,1739141205.45511,44.84995722770691,-0.5049095279967323,1739141205.4551115,44.84995722770691,1.2322993321523485,1739141205.455113,44.84995722770691,0.0,1739141205.4551146,44.84995722770691,0.13528256892550206,1739141205.4551158,44.84995722770691,3.605257789037529,1739141205.4551167,44.84995722770691,1.0942930420899517 +1739141205.475323,44.86995720863342,40.08736795554843,1739141205.475326,44.86995720863342,0.48706410540416645,1739141205.4753296,44.86995720863342,73.08525737209091,1739141205.4753325,44.86995720863342,34.95889365229706,1739141205.475334,44.86995720863342,-0.1,1739141205.4753356,44.86995720863342,-3.027617267733538,1739141205.475337,44.86995720863342,-1.7685223296613133,1739141205.4753382,44.86995720863342,-0.5049095279967323,1739141205.4753394,44.86995720863342,1.2322993321523485,1739141205.475341,44.86995720863342,0.0,1739141205.4753425,44.86995720863342,0.13800629006239684,1739141205.475344,44.86995720863342,3.605257789037529,1739141205.4753451,44.86995720863342,1.0942930420899517 +1739141205.4951432,44.88995718955994,40.08736795554843,1739141205.495146,44.88995718955994,0.48706410540416645,1739141205.4951494,44.88995718955994,73.08525737209091,1739141205.4951525,44.88995718955994,34.95889365229706,1739141205.495154,44.88995718955994,-0.1,1739141205.495156,44.88995718955994,-3.027617267733538,1739141205.4951577,44.88995718955994,-1.7685223296613133,1739141205.4951594,44.88995718955994,-0.5049095279967323,1739141205.4951608,44.88995718955994,1.2322993321523485,1739141205.4951625,44.88995718955994,0.0,1739141205.4951644,44.88995718955994,0.13800629006239684,1739141205.495166,44.88995718955994,3.605257789037529,1739141205.4951675,44.88995718955994,1.0942930420899517 +1739141205.5151856,44.90995717048645,40.08736795554843,1739141205.5151885,44.90995717048645,0.48706410540416645,1739141205.5151916,44.90995717048645,73.08525737209091,1739141205.5151947,44.90995717048645,34.95889365229706,1739141205.5151963,44.90995717048645,-0.1,1739141205.5151985,44.90995717048645,-3.027617267733538,1739141205.5152,44.90995717048645,-1.7685223296613133,1739141205.5152018,44.90995717048645,-0.5049095279967323,1739141205.5152032,44.90995717048645,1.2322993321523485,1739141205.515205,44.90995717048645,0.0,1739141205.5152066,44.90995717048645,0.13800629006239684,1739141205.515208,44.90995717048645,3.605257789037529,1739141205.5152094,44.90995717048645,1.0942930420899517 +1739141205.5355496,44.929957151412964,40.08736795554843,1739141205.535553,44.929957151412964,0.48706410540416645,1739141205.5355566,44.929957151412964,73.08525737209091,1739141205.5355597,44.929957151412964,34.95889365229706,1739141205.5355613,44.929957151412964,-0.1,1739141205.535563,44.929957151412964,-3.027617267733538,1739141205.5355647,44.929957151412964,-1.7685223296613133,1739141205.535566,44.929957151412964,-0.5049095279967323,1739141205.5355673,44.929957151412964,1.2322993321523485,1739141205.5355694,44.929957151412964,0.0,1739141205.5355709,44.929957151412964,0.13800629006239684,1739141205.5355725,44.929957151412964,3.605257789037529,1739141205.5355737,44.929957151412964,1.0942930420899517 +1739141205.5554612,44.94995713233948,39.97836069458286,1739141205.555464,44.94995713233948,0.43425533027629903,1739141205.555467,44.94995713233948,73.22969667575744,1739141205.55547,44.94995713233948,34.76913090076166,1739141205.5554717,44.94995713233948,-0.09918060598941589,1739141205.5554733,44.94995713233948,-3.0395462797099815,1739141205.555475,44.94995713233948,-1.718546186312564,1739141205.5554762,44.94995713233948,-0.4772647521207955,1739141205.5554776,44.94995713233948,1.2571814330630582,1739141205.555479,44.94995713233948,0.0,1739141205.5554805,44.94995713233948,0.15666406878126726,1739141205.555482,44.94995713233948,3.5780235588723084,1739141205.555483,44.94995713233948,1.1094020252528627 +1739141205.575472,44.96995711326599,39.97836069458286,1739141205.5754755,44.96995711326599,0.43425533027629903,1739141205.5754786,44.96995711326599,73.22969667575744,1739141205.5754817,44.96995711326599,34.76913090076166,1739141205.575483,44.96995711326599,-0.09918060598941589,1739141205.575485,44.96995711326599,-3.0395462797099815,1739141205.5754864,44.96995711326599,-1.718546186312564,1739141205.5754879,44.96995711326599,-0.4772647521207955,1739141205.575489,44.96995711326599,1.2571814330630582,1739141205.5754907,44.96995711326599,0.0,1739141205.5754926,44.96995711326599,0.1477794078101955,1739141205.575494,44.96995711326599,3.5780235588723084,1739141205.5754955,44.96995711326599,1.1094020252528627 +1739141205.595618,44.989957094192505,39.97836069458286,1739141205.5956209,44.989957094192505,0.43425533027629903,1739141205.5956242,44.989957094192505,73.22969667575744,1739141205.5956278,44.989957094192505,34.76913090076166,1739141205.5956295,44.989957094192505,-0.09918060598941589,1739141205.5956316,44.989957094192505,-3.0395462797099815,1739141205.5956335,44.989957094192505,-1.718546186312564,1739141205.5956352,44.989957094192505,-0.4772647521207955,1739141205.5956368,44.989957094192505,1.2571814330630582,1739141205.5956385,44.989957094192505,0.0,1739141205.5956407,44.989957094192505,0.1477794078101955,1739141205.595642,44.989957094192505,3.5780235588723084,1739141205.5956438,44.989957094192505,1.1094020252528627 +1739141205.6156216,45.00995707511902,39.97836069458286,1739141205.6156247,45.00995707511902,0.43425533027629903,1739141205.6156282,45.00995707511902,73.22969667575744,1739141205.6156316,45.00995707511902,34.76913090076166,1739141205.6156335,45.00995707511902,-0.09918060598941589,1739141205.6156352,45.00995707511902,-3.0395462797099815,1739141205.615637,45.00995707511902,-1.718546186312564,1739141205.6156385,45.00995707511902,-0.4772647521207955,1739141205.6156402,45.00995707511902,1.2571814330630582,1739141205.6156418,45.00995707511902,0.0,1739141205.6156435,45.00995707511902,0.1477794078101955,1739141205.615645,45.00995707511902,3.5780235588723084,1739141205.6156464,45.00995707511902,1.1094020252528627 +1739141205.6354477,45.02995705604553,39.97836069458286,1739141205.6354513,45.02995705604553,0.43425533027629903,1739141205.6354554,45.02995705604553,73.22969667575744,1739141205.6354592,45.02995705604553,34.76913090076166,1739141205.6354609,45.02995705604553,-0.09918060598941589,1739141205.6354628,45.02995705604553,-3.0395462797099815,1739141205.6354644,45.02995705604553,-1.718546186312564,1739141205.635466,45.02995705604553,-0.4772647521207955,1739141205.6354675,45.02995705604553,1.2571814330630582,1739141205.6354697,45.02995705604553,0.0,1739141205.6354713,45.02995705604553,0.1477794078101955,1739141205.635473,45.02995705604553,3.5780235588723084,1739141205.6354747,45.02995705604553,1.1094020252528627 +1739141205.655554,45.049957036972046,39.97836069458286,1739141205.6555572,45.049957036972046,0.43425533027629903,1739141205.655561,45.049957036972046,73.22969667575744,1739141205.6555643,45.049957036972046,34.76913090076166,1739141205.6555657,45.049957036972046,-0.09918060598941589,1739141205.655568,45.049957036972046,-3.0395462797099815,1739141205.6555693,45.049957036972046,-1.718546186312564,1739141205.6555712,45.049957036972046,-0.4772647521207955,1739141205.6555727,45.049957036972046,1.2571814330630582,1739141205.6555748,45.049957036972046,0.0,1739141205.6555765,45.049957036972046,0.1477794078101955,1739141205.6555781,45.049957036972046,3.5780235588723084,1739141205.6555796,45.049957036972046,1.1094020252528627 +1739141205.6777935,45.06995701789856,39.86642411589704,1739141205.6777978,45.06995701789856,0.38364529135518755,1739141205.6778028,45.06995701789856,73.23799547065128,1739141205.6778083,45.06995701789856,34.71203525007919,1739141205.6778114,45.06995701789856,-0.099,1739141205.6778154,45.06995701789856,-3.048227161897799,1739141205.6778193,45.06995701789856,-1.6159776555677046,1739141205.6778228,45.06995701789856,-0.45944843081803843,1739141205.6778262,45.06995701789856,1.309833028130532,1739141205.6778302,45.06995701789856,0.0,1739141205.6778338,45.06995701789856,0.2172430851059767,1739141205.6778374,45.06995701789856,3.5524127966512373,1739141205.677841,45.06995701789856,1.12566790111786 +1739141205.6951623,45.08995699882507,39.86642411589704,1739141205.695165,45.08995699882507,0.38364529135518755,1739141205.6951678,45.08995699882507,73.23799547065128,1739141205.6951704,45.08995699882507,34.71203525007919,1739141205.6951718,45.08995699882507,-0.099,1739141205.6951737,45.08995699882507,-3.048227161897799,1739141205.6951752,45.08995699882507,-1.6159776555677046,1739141205.6951764,45.08995699882507,-0.45944843081803843,1739141205.6951776,45.08995699882507,1.309833028130532,1739141205.695179,45.08995699882507,0.0,1739141205.6951802,45.08995699882507,0.18416512701267185,1739141205.6951816,45.08995699882507,3.5524127966512373,1739141205.6951828,45.08995699882507,1.12566790111786 +1739141205.7151854,45.10995697975159,39.86642411589704,1739141205.715188,45.10995697975159,0.38364529135518755,1739141205.715191,45.10995697975159,73.23799547065128,1739141205.7151933,45.10995697975159,34.71203525007919,1739141205.7151947,45.10995697975159,-0.099,1739141205.7151961,45.10995697975159,-3.048227161897799,1739141205.7151978,45.10995697975159,-1.6159776555677046,1739141205.7151992,45.10995697975159,-0.45944843081803843,1739141205.7152002,45.10995697975159,1.309833028130532,1739141205.7152019,45.10995697975159,0.0,1739141205.715203,45.10995697975159,0.18416512701267185,1739141205.7152042,45.10995697975159,3.5524127966512373,1739141205.7152057,45.10995697975159,1.12566790111786 +1739141205.7352982,45.1299569606781,39.86642411589704,1739141205.735301,45.1299569606781,0.38364529135518755,1739141205.735304,45.1299569606781,73.23799547065128,1739141205.7353067,45.1299569606781,34.71203525007919,1739141205.735308,45.1299569606781,-0.099,1739141205.7353098,45.1299569606781,-3.048227161897799,1739141205.735311,45.1299569606781,-1.6159776555677046,1739141205.7353125,45.1299569606781,-0.45944843081803843,1739141205.7353137,45.1299569606781,1.309833028130532,1739141205.735315,45.1299569606781,0.0,1739141205.7353165,45.1299569606781,0.18416512701267185,1739141205.7353177,45.1299569606781,3.5524127966512373,1739141205.7353191,45.1299569606781,1.12566790111786 +1739141205.7550309,45.149956941604614,39.86642411589704,1739141205.755033,45.149956941604614,0.38364529135518755,1739141205.755036,45.149956941604614,73.23799547065128,1739141205.755039,45.149956941604614,34.71203525007919,1739141205.7550402,45.149956941604614,-0.099,1739141205.755042,45.149956941604614,-3.048227161897799,1739141205.7550433,45.149956941604614,-1.6159776555677046,1739141205.7550447,45.149956941604614,-0.45944843081803843,1739141205.7550457,45.149956941604614,1.309833028130532,1739141205.755047,45.149956941604614,0.0,1739141205.7550488,45.149956941604614,0.18416512701267185,1739141205.75505,45.149956941604614,3.5524127966512373,1739141205.7550514,45.149956941604614,1.12566790111786 +1739141205.7752028,45.16995692253113,39.75139556953641,1739141205.775206,45.16995692253113,0.3350481726509926,1739141205.7752094,45.16995692253113,73.50620731383935,1739141205.7752128,45.16995692253113,34.381432386928076,1739141205.7752144,45.16995692253113,-0.098,1739141205.775216,45.16995692253113,-3.0611241168136196,1739141205.7752178,45.16995692253113,-1.624594278504993,1739141205.775219,45.16995692253113,-0.42697455778159,1739141205.7752202,45.16995692253113,1.3053262642832633,1739141205.775222,45.16995692253113,0.0,1739141205.7752235,45.16995692253113,0.13585521043562326,1739141205.775225,45.16995692253113,3.528383973782513,1739141205.775226,45.16995692253113,1.1464663201762235 +1739141205.7950842,45.18995690345764,39.75139556953641,1739141205.795087,45.18995690345764,0.3350481726509926,1739141205.79509,45.18995690345764,73.50620731383935,1739141205.7950926,45.18995690345764,34.381432386928076,1739141205.795094,45.18995690345764,-0.098,1739141205.7950954,45.18995690345764,-3.0611241168136196,1739141205.7950974,45.18995690345764,-1.624594278504993,1739141205.7950985,45.18995690345764,-0.42697455778159,1739141205.7950997,45.18995690345764,1.3053262642832633,1739141205.7951012,45.18995690345764,0.0,1739141205.7951028,45.18995690345764,0.15885994410703974,1739141205.7951038,45.18995690345764,3.528383973782513,1739141205.795105,45.18995690345764,1.1464663201762235 +1739141205.8150702,45.209956884384155,39.75139556953641,1739141205.8150728,45.209956884384155,0.3350481726509926,1739141205.8150756,45.209956884384155,73.50620731383935,1739141205.8150785,45.209956884384155,34.381432386928076,1739141205.8150797,45.209956884384155,-0.098,1739141205.8150811,45.209956884384155,-3.0611241168136196,1739141205.8150826,45.209956884384155,-1.624594278504993,1739141205.8150837,45.209956884384155,-0.42697455778159,1739141205.8150852,45.209956884384155,1.3053262642832633,1739141205.8150866,45.209956884384155,0.0,1739141205.8150878,45.209956884384155,0.15885994410703974,1739141205.8150892,45.209956884384155,3.528383973782513,1739141205.8150902,45.209956884384155,1.1464663201762235 +1739141205.835122,45.22995686531067,39.75139556953641,1739141205.835125,45.22995686531067,0.3350481726509926,1739141205.8351278,45.22995686531067,73.50620731383935,1739141205.835131,45.22995686531067,34.381432386928076,1739141205.8351324,45.22995686531067,-0.098,1739141205.835134,45.22995686531067,-3.0611241168136196,1739141205.8351355,45.22995686531067,-1.624594278504993,1739141205.8351371,45.22995686531067,-0.42697455778159,1739141205.835138,45.22995686531067,1.3053262642832633,1739141205.8351398,45.22995686531067,0.0,1739141205.8351417,45.22995686531067,0.15885994410703974,1739141205.8351429,45.22995686531067,3.528383973782513,1739141205.8351445,45.22995686531067,1.1464663201762235 +1739141205.8551369,45.24995684623718,39.75139556953641,1739141205.8551395,45.24995684623718,0.3350481726509926,1739141205.8551424,45.24995684623718,73.50620731383935,1739141205.8551452,45.24995684623718,34.381432386928076,1739141205.8551466,45.24995684623718,-0.098,1739141205.8551483,45.24995684623718,-3.0611241168136196,1739141205.8551495,45.24995684623718,-1.624594278504993,1739141205.8551512,45.24995684623718,-0.42697455778159,1739141205.8551521,45.24995684623718,1.3053262642832633,1739141205.855154,45.24995684623718,0.0,1739141205.8551552,45.24995684623718,0.15885994410703974,1739141205.8551564,45.24995684623718,3.528383973782513,1739141205.8551579,45.24995684623718,1.1464663201762235 +1739141205.8753772,45.269956827163696,39.75139556953641,1739141205.87538,45.269956827163696,0.3350481726509926,1739141205.875383,45.269956827163696,73.50620731383935,1739141205.8753855,45.269956827163696,34.381432386928076,1739141205.8753872,45.269956827163696,-0.098,1739141205.8753889,45.269956827163696,-3.0611241168136196,1739141205.8753903,45.269956827163696,-1.624594278504993,1739141205.8753915,45.269956827163696,-0.42697455778159,1739141205.8753927,45.269956827163696,1.3053262642832633,1739141205.8753943,45.269956827163696,0.0,1739141205.8753958,45.269956827163696,0.15885994410703974,1739141205.8753972,45.269956827163696,3.528383973782513,1739141205.8753986,45.269956827163696,1.1464663201762235 +1739141205.8955913,45.28995680809021,39.63331376527277,1739141205.8955948,45.28995680809021,0.2883917589688414,1739141205.8955982,45.28995680809021,73.51533762456098,1739141205.8956015,45.28995680809021,34.32073247637488,1739141205.8956032,45.28995680809021,-0.098,1739141205.8956053,45.28995680809021,-3.068989041086459,1739141205.8956068,45.28995680809021,-1.530328622152919,1739141205.8956084,45.28995680809021,-0.41162902481669755,1739141205.8956099,45.28995680809021,1.3554849446215658,1739141205.8956118,45.28995680809021,0.0,1739141205.8956134,45.28995680809021,0.2218004352614741,1739141205.8956149,45.28995680809021,3.5056015715470465,1739141205.8956163,45.28995680809021,1.1636561867867465 +1739141205.9159043,45.309956789016724,39.63331376527277,1739141205.9159079,45.309956789016724,0.2883917589688414,1739141205.9159117,45.309956789016724,73.51533762456098,1739141205.9159155,45.309956789016724,34.32073247637488,1739141205.9159176,45.309956789016724,-0.098,1739141205.9159195,45.309956789016724,-3.068989041086459,1739141205.9159214,45.309956789016724,-1.530328622152919,1739141205.915923,45.309956789016724,-0.41162902481669755,1739141205.9159248,45.309956789016724,1.3554849446215658,1739141205.9159267,45.309956789016724,0.0,1739141205.9159286,45.309956789016724,0.19182875783481923,1739141205.9159303,45.309956789016724,3.5056015715470465,1739141205.915932,45.309956789016724,1.1636561867867465 +1739141205.9375226,45.32995676994324,39.63331376527277,1739141205.9375272,45.32995676994324,0.2883917589688414,1739141205.9375327,45.32995676994324,73.51533762456098,1739141205.9375374,45.32995676994324,34.32073247637488,1739141205.93754,45.32995676994324,-0.098,1739141205.937543,45.32995676994324,-3.068989041086459,1739141205.9375453,45.32995676994324,-1.530328622152919,1739141205.9375472,45.32995676994324,-0.41162902481669755,1739141205.9375496,45.32995676994324,1.3554849446215658,1739141205.9375522,45.32995676994324,0.0,1739141205.9375546,45.32995676994324,0.19182875783481923,1739141205.937557,45.32995676994324,3.5056015715470465,1739141205.9375591,45.32995676994324,1.1636561867867465 +1739141205.956852,45.34995675086975,39.63331376527277,1739141205.9568563,45.34995675086975,0.2883917589688414,1739141205.9568615,45.34995675086975,73.51533762456098,1739141205.9568663,45.34995675086975,34.32073247637488,1739141205.9568686,45.34995675086975,-0.098,1739141205.9568715,45.34995675086975,-3.068989041086459,1739141205.9568737,45.34995675086975,-1.530328622152919,1739141205.956876,45.34995675086975,-0.41162902481669755,1739141205.9568782,45.34995675086975,1.3554849446215658,1739141205.9568806,45.34995675086975,0.0,1739141205.9568832,45.34995675086975,0.19182875783481923,1739141205.9568853,45.34995675086975,3.5056015715470465,1739141205.9568875,45.34995675086975,1.1636561867867465 +1739141205.9767632,45.369956731796265,39.63331376527277,1739141205.9767675,45.369956731796265,0.2883917589688414,1739141205.9767728,45.369956731796265,73.51533762456098,1739141205.9767776,45.369956731796265,34.32073247637488,1739141205.97678,45.369956731796265,-0.098,1739141205.9767828,45.369956731796265,-3.068989041086459,1739141205.9767852,45.369956731796265,-1.530328622152919,1739141205.9767876,45.369956731796265,-0.41162902481669755,1739141205.9767895,45.369956731796265,1.3554849446215658,1739141205.976792,45.369956731796265,0.0,1739141205.9767947,45.369956731796265,0.19182875783481923,1739141205.9767966,45.369956731796265,3.5056015715470465,1739141205.976799,45.369956731796265,1.1636561867867465 +1739141205.995856,45.38995671272278,39.51223495660372,1739141205.9958594,45.38995671272278,0.24362371597668897,1739141205.995863,45.38995671272278,73.7323066118755,1739141205.9958663,45.38995671272278,34.03903232099566,1739141205.9958682,45.38995671272278,-0.09702977704731161,1739141205.9958699,45.38995671272278,-3.079432588403568,1739141205.9958718,45.38995671272278,-1.518038548147774,1739141205.9958732,45.38995671272278,-0.3855507428795682,1739141205.995875,45.38995671272278,1.3621649548452985,1739141205.9958768,45.38995671272278,0.0,1739141205.9958787,45.38995671272278,0.16338710355917752,1739141205.9958801,45.38995671272278,3.4842387316121317,1739141205.9958818,45.38995671272278,1.1852341996273126 +1739141206.0157537,45.40995669364929,39.51223495660372,1739141206.0157568,45.40995669364929,0.24362371597668897,1739141206.0157607,45.40995669364929,73.7323066118755,1739141206.0157638,45.40995669364929,34.03903232099566,1739141206.0157654,45.40995669364929,-0.09702977704731161,1739141206.0157676,45.40995669364929,-3.079432588403568,1739141206.015769,45.40995669364929,-1.518038548147774,1739141206.0157707,45.40995669364929,-0.3855507428795682,1739141206.015772,45.40995669364929,1.3621649548452985,1739141206.0157743,45.40995669364929,0.0,1739141206.015776,45.40995669364929,0.17693075521798596,1739141206.0157776,45.40995669364929,3.4842387316121317,1739141206.015779,45.40995669364929,1.1852341996273126 +1739141206.0358481,45.429956674575806,39.51223495660372,1739141206.035851,45.429956674575806,0.24362371597668897,1739141206.0358543,45.429956674575806,73.7323066118755,1739141206.0358577,45.429956674575806,34.03903232099566,1739141206.035859,45.429956674575806,-0.09702977704731161,1739141206.0358613,45.429956674575806,-3.079432588403568,1739141206.035863,45.429956674575806,-1.518038548147774,1739141206.0358646,45.429956674575806,-0.3855507428795682,1739141206.0358658,45.429956674575806,1.3621649548452985,1739141206.035868,45.429956674575806,0.0,1739141206.0358696,45.429956674575806,0.17693075521798596,1739141206.035871,45.429956674575806,3.4842387316121317,1739141206.0358725,45.429956674575806,1.1852341996273126 +1739141206.055601,45.44995665550232,39.51223495660372,1739141206.0556042,45.44995665550232,0.24362371597668897,1739141206.0556078,45.44995665550232,73.7323066118755,1739141206.0556114,45.44995665550232,34.03903232099566,1739141206.0556133,45.44995665550232,-0.09702977704731161,1739141206.0556152,45.44995665550232,-3.079432588403568,1739141206.055617,45.44995665550232,-1.518038548147774,1739141206.0556185,45.44995665550232,-0.3855507428795682,1739141206.0556204,45.44995665550232,1.3621649548452985,1739141206.0556223,45.44995665550232,0.0,1739141206.0556245,45.44995665550232,0.17693075521798596,1739141206.055626,45.44995665550232,3.4842387316121317,1739141206.0556276,45.44995665550232,1.1852341996273126 +1739141206.0758698,45.46995663642883,39.51223495660372,1739141206.0758731,45.46995663642883,0.24362371597668897,1739141206.0758777,45.46995663642883,73.7323066118755,1739141206.0758812,45.46995663642883,34.03903232099566,1739141206.075883,45.46995663642883,-0.09702977704731161,1739141206.0758853,45.46995663642883,-3.079432588403568,1739141206.0758872,45.46995663642883,-1.518038548147774,1739141206.0758889,45.46995663642883,-0.3855507428795682,1739141206.0758905,45.46995663642883,1.3621649548452985,1739141206.0758924,45.46995663642883,0.0,1739141206.0758946,45.46995663642883,0.17693075521798596,1739141206.075896,45.46995663642883,3.4842387316121317,1739141206.075898,45.46995663642883,1.1852341996273126 +1739141206.0956905,45.48995661735535,39.51223495660372,1739141206.0956962,45.48995661735535,0.24362371597668897,1739141206.0957024,45.48995661735535,73.7323066118755,1739141206.095709,45.48995661735535,34.03903232099566,1739141206.0957136,45.48995661735535,-0.09702977704731161,1739141206.0957212,45.48995661735535,-3.079432588403568,1739141206.095725,45.48995661735535,-1.518038548147774,1739141206.0957289,45.48995661735535,-0.3855507428795682,1739141206.095733,45.48995661735535,1.3621649548452985,1739141206.095737,45.48995661735535,0.0,1739141206.0957422,45.48995661735535,0.17693075521798596,1739141206.095748,45.48995661735535,3.4842387316121317,1739141206.0957541,45.48995661735535,1.1852341996273126 +1739141206.1164782,45.50995659828186,39.38815380430732,1739141206.1164818,45.50995659828186,0.20066246780481745,1739141206.1164854,45.50995659828186,73.7423811981726,1739141206.1164885,45.50995659828186,33.9719965724545,1739141206.1164901,45.50995659828186,-0.097,1739141206.1164923,45.50995659828186,-3.0866896458602957,1739141206.116494,45.50995659828186,-1.4338939667247894,1739141206.1164956,45.50995659828186,-0.3723469937128633,1739141206.116497,45.50995659828186,1.4087927686261539,1739141206.116499,45.50995659828186,0.0,1739141206.116501,45.50995659828186,0.22969944618282728,1739141206.1165025,45.50995659828186,3.4640202281859924,1739141206.116504,45.50995659828186,1.2042212830743366 +1739141206.1353376,45.529956579208374,39.38815380430732,1739141206.1353416,45.529956579208374,0.20066246780481745,1739141206.1353457,45.529956579208374,73.7423811981726,1739141206.135349,45.529956579208374,33.9719965724545,1739141206.1353507,45.529956579208374,-0.097,1739141206.1353528,45.529956579208374,-3.0866896458602957,1739141206.1353545,45.529956579208374,-1.4338939667247894,1739141206.135357,45.529956579208374,-0.3723469937128633,1739141206.1353586,45.529956579208374,1.4087927686261539,1739141206.1353605,45.529956579208374,0.0,1739141206.1353624,45.529956579208374,0.20457148555181726,1739141206.135364,45.529956579208374,3.4640202281859924,1739141206.1353657,45.529956579208374,1.2042212830743366 +1739141206.15547,45.54995656013489,39.38815380430732,1739141206.155473,45.54995656013489,0.20066246780481745,1739141206.1554766,45.54995656013489,73.7423811981726,1739141206.15548,45.54995656013489,33.9719965724545,1739141206.1554816,45.54995656013489,-0.097,1739141206.1554837,45.54995656013489,-3.0866896458602957,1739141206.1554852,45.54995656013489,-1.4338939667247894,1739141206.1554868,45.54995656013489,-0.3723469937128633,1739141206.1554883,45.54995656013489,1.4087927686261539,1739141206.1554904,45.54995656013489,0.0,1739141206.155492,45.54995656013489,0.20457148555181726,1739141206.1554937,45.54995656013489,3.4640202281859924,1739141206.1554952,45.54995656013489,1.2042212830743366 +1739141206.1775649,45.5699565410614,39.38815380430732,1739141206.17757,45.5699565410614,0.20066246780481745,1739141206.1775753,45.5699565410614,73.7423811981726,1739141206.1775813,45.5699565410614,33.9719965724545,1739141206.1775842,45.5699565410614,-0.097,1739141206.1775877,45.5699565410614,-3.0866896458602957,1739141206.177591,45.5699565410614,-1.4338939667247894,1739141206.1775944,45.5699565410614,-0.3723469937128633,1739141206.1775973,45.5699565410614,1.4087927686261539,1739141206.1776009,45.5699565410614,0.0,1739141206.1776037,45.5699565410614,0.20457148555181726,1739141206.1776068,45.5699565410614,3.4640202281859924,1739141206.17761,45.5699565410614,1.2042212830743366 +1739141206.1953232,45.589956521987915,39.38815380430732,1739141206.1953266,45.589956521987915,0.20066246780481745,1739141206.1953301,45.589956521987915,73.7423811981726,1739141206.1953337,45.589956521987915,33.9719965724545,1739141206.1953354,45.589956521987915,-0.097,1739141206.1953378,45.589956521987915,-3.0866896458602957,1739141206.1953392,45.589956521987915,-1.4338939667247894,1739141206.195341,45.589956521987915,-0.3723469937128633,1739141206.1953425,45.589956521987915,1.4087927686261539,1739141206.1953444,45.589956521987915,0.0,1739141206.195346,45.589956521987915,0.20457148555181726,1739141206.1953478,45.589956521987915,3.4640202281859924,1739141206.1953492,45.589956521987915,1.2042212830743366 +1739141206.2154586,45.60995650291443,39.26107488909417,1739141206.2154622,45.60995650291443,0.15943690276212852,1739141206.2154658,45.60995650291443,73.97122504736362,1739141206.2154691,45.60995650291443,33.67526490601713,1739141206.2154706,45.60995650291443,-0.096,1739141206.215473,45.60995650291443,-3.09589488185907,1739141206.2154746,45.60995650291443,-1.4252927894944476,1739141206.2154763,45.60995650291443,-0.3485184749657549,1739141206.2154777,45.60995650291443,1.4136480265371818,1739141206.2154799,45.60995650291443,0.0,1739141206.2154815,45.60995650291443,0.17063665262862196,1739141206.2154832,45.60995650291443,3.445031355165193,1739141206.2154846,45.60995650291443,1.2268519215870668 +1739141206.2353196,45.62995648384094,39.26107488909417,1739141206.2353232,45.62995648384094,0.15943690276212852,1739141206.2353272,45.62995648384094,73.97122504736362,1739141206.2353308,45.62995648384094,33.67526490601713,1739141206.2353325,45.62995648384094,-0.096,1739141206.2353349,45.62995648384094,-3.09589488185907,1739141206.235337,45.62995648384094,-1.4252927894944476,1739141206.2353384,45.62995648384094,-0.3485184749657549,1739141206.2353404,45.62995648384094,1.4136480265371818,1739141206.2353423,45.62995648384094,0.0,1739141206.2353446,45.62995648384094,0.186796104950115,1739141206.235346,45.62995648384094,3.445031355165193,1739141206.235348,45.62995648384094,1.2268519215870668 +1739141206.255468,45.649956464767456,39.26107488909417,1739141206.255471,45.649956464767456,0.15943690276212852,1739141206.2554748,45.649956464767456,73.97122504736362,1739141206.255478,45.649956464767456,33.67526490601713,1739141206.2554798,45.649956464767456,-0.096,1739141206.255482,45.649956464767456,-3.09589488185907,1739141206.2554836,45.649956464767456,-1.4252927894944476,1739141206.2554853,45.649956464767456,-0.3485184749657549,1739141206.2554867,45.649956464767456,1.4136480265371818,1739141206.2554884,45.649956464767456,0.0,1739141206.2554905,45.649956464767456,0.186796104950115,1739141206.2554924,45.649956464767456,3.445031355165193,1739141206.2554939,45.649956464767456,1.2268519215870668 +1739141206.2756984,45.66995644569397,39.26107488909417,1739141206.2757015,45.66995644569397,0.15943690276212852,1739141206.2757049,45.66995644569397,73.97122504736362,1739141206.2757082,45.66995644569397,33.67526490601713,1739141206.2757096,45.66995644569397,-0.096,1739141206.2757118,45.66995644569397,-3.09589488185907,1739141206.2757134,45.66995644569397,-1.4252927894944476,1739141206.275715,45.66995644569397,-0.3485184749657549,1739141206.2757165,45.66995644569397,1.4136480265371818,1739141206.2757187,45.66995644569397,0.0,1739141206.2757204,45.66995644569397,0.186796104950115,1739141206.275722,45.66995644569397,3.445031355165193,1739141206.2757235,45.66995644569397,1.2268519215870668 +1739141206.2958152,45.68995642662048,39.26107488909417,1739141206.2958188,45.68995642662048,0.15943690276212852,1739141206.2958224,45.68995642662048,73.97122504736362,1739141206.2958257,45.68995642662048,33.67526490601713,1739141206.2958272,45.68995642662048,-0.096,1739141206.2958293,45.68995642662048,-3.09589488185907,1739141206.295831,45.68995642662048,-1.4252927894944476,1739141206.2958326,45.68995642662048,-0.3485184749657549,1739141206.295834,45.68995642662048,1.4136480265371818,1739141206.2958362,45.68995642662048,0.0,1739141206.2958379,45.68995642662048,0.186796104950115,1739141206.2958395,45.68995642662048,3.445031355165193,1739141206.295841,45.68995642662048,1.2268519215870668 +1739141206.3157501,45.709956407547,39.26107488909417,1739141206.315754,45.709956407547,0.15943690276212852,1739141206.3157582,45.709956407547,73.97122504736362,1739141206.3157625,45.709956407547,33.67526490601713,1739141206.3157644,45.709956407547,-0.096,1739141206.3157668,45.709956407547,-3.09589488185907,1739141206.3157687,45.709956407547,-1.4252927894944476,1739141206.3157706,45.709956407547,-0.3485184749657549,1739141206.3157725,45.709956407547,1.4136480265371818,1739141206.3157744,45.709956407547,0.0,1739141206.3157763,45.709956407547,0.186796104950115,1739141206.3157783,45.709956407547,3.445031355165193,1739141206.31578,45.709956407547,1.2268519215870668 +1739141206.3354466,45.72995638847351,39.13097050584864,1739141206.3354497,45.72995638847351,0.11990228509206613,1739141206.335453,45.72995638847351,74.13272435705755,1739141206.3354566,45.72995638847351,33.452361791942856,1739141206.3354583,45.72995638847351,-0.09435461073822396,1739141206.3354604,45.72995638847351,-3.1038800162409594,1739141206.3354619,45.72995638847351,-1.3918232977223848,1739141206.3354635,45.72995638847351,-0.32967835127417694,1739141206.335465,45.72995638847351,1.4327009124410908,1739141206.3354669,45.72995638847351,0.0,1739141206.3354685,45.72995638847351,0.18409020997642106,1739141206.33547,45.72995638847351,3.4267477029437496,1739141206.3354716,45.72995638847351,1.247322180404952 +1739141206.3555305,45.749956369400024,39.13097050584864,1739141206.3555343,45.749956369400024,0.11990228509206613,1739141206.3555381,45.749956369400024,74.13272435705755,1739141206.3555417,45.749956369400024,33.452361791942856,1739141206.3555436,45.749956369400024,-0.09435461073822396,1739141206.3555455,45.749956369400024,-3.1038800162409594,1739141206.3555474,45.749956369400024,-1.3918232977223848,1739141206.3555489,45.749956369400024,-0.32967835127417694,1739141206.3555505,45.749956369400024,1.4327009124410908,1739141206.3555524,45.749956369400024,0.0,1739141206.3555543,45.749956369400024,0.18537873203613886,1739141206.355556,45.749956369400024,3.4267477029437496,1739141206.3555577,45.749956369400024,1.247322180404952 +1739141206.3783028,45.76995635032654,39.13097050584864,1739141206.3783073,45.76995635032654,0.11990228509206613,1739141206.3783133,45.76995635032654,74.13272435705755,1739141206.37832,45.76995635032654,33.452361791942856,1739141206.3783236,45.76995635032654,-0.09435461073822396,1739141206.3783283,45.76995635032654,-3.1038800162409594,1739141206.3783324,45.76995635032654,-1.3918232977223848,1739141206.3783367,45.76995635032654,-0.32967835127417694,1739141206.378341,45.76995635032654,1.4327009124410908,1739141206.3783453,45.76995635032654,0.0,1739141206.3783495,45.76995635032654,0.18537873203613886,1739141206.3783538,45.76995635032654,3.4267477029437496,1739141206.3783581,45.76995635032654,1.247322180404952 +1739141206.3956861,45.78995633125305,39.13097050584864,1739141206.3956897,45.78995633125305,0.11990228509206613,1739141206.3956935,45.78995633125305,74.13272435705755,1739141206.3956969,45.78995633125305,33.452361791942856,1739141206.3956988,45.78995633125305,-0.09435461073822396,1739141206.3957007,45.78995633125305,-3.1038800162409594,1739141206.3957026,45.78995633125305,-1.3918232977223848,1739141206.3957043,45.78995633125305,-0.32967835127417694,1739141206.395706,45.78995633125305,1.4327009124410908,1739141206.3957078,45.78995633125305,0.0,1739141206.3957095,45.78995633125305,0.18537873203613886,1739141206.395711,45.78995633125305,3.4267477029437496,1739141206.3957129,45.78995633125305,1.247322180404952 +1739141206.415348,45.809956312179565,39.13097050584864,1739141206.4153512,45.809956312179565,0.11990228509206613,1739141206.4153547,45.809956312179565,74.13272435705755,1739141206.4153583,45.809956312179565,33.452361791942856,1739141206.4153597,45.809956312179565,-0.09435461073822396,1739141206.4153621,45.809956312179565,-3.1038800162409594,1739141206.4153636,45.809956312179565,-1.3918232977223848,1739141206.4153655,45.809956312179565,-0.32967835127417694,1739141206.415367,45.809956312179565,1.4327009124410908,1739141206.415369,45.809956312179565,0.0,1739141206.4153705,45.809956312179565,0.18537873203613886,1739141206.4153721,45.809956312179565,3.4267477029437496,1739141206.4153738,45.809956312179565,1.247322180404952 +1739141206.4353805,45.82995629310608,38.99803233406831,1739141206.4353836,45.82995629310608,0.08206551628415859,1739141206.435387,45.82995629310608,74.28235899833055,1739141206.4353902,45.82995629310608,33.24191395973452,1739141206.435392,45.82995629310608,-0.09202299121519536,1739141206.4353938,45.82995629310608,-3.1113577894934985,1739141206.435396,45.82995629310608,-1.3569830698404293,1739141206.4353974,45.82995629310608,-0.3131108951619148,1739141206.4353986,45.82995629310608,1.4528069372427503,1739141206.4354007,45.82995629310608,0.0,1739141206.4354024,45.82995629310608,0.18505472041186885,1739141206.435404,45.82995629310608,3.409702994184936,1739141206.4354055,45.82995629310608,1.2675979255041538 +1739141206.455522,45.84995627403259,38.99803233406831,1739141206.4555256,45.84995627403259,0.08206551628415859,1739141206.4555295,45.84995627403259,74.28235899833055,1739141206.4555328,45.84995627403259,33.24191395973452,1739141206.4555347,45.84995627403259,-0.09202299121519536,1739141206.4555366,45.84995627403259,-3.1113577894934985,1739141206.4555385,45.84995627403259,-1.3569830698404293,1739141206.45554,45.84995627403259,-0.3131108951619148,1739141206.4555416,45.84995627403259,1.4528069372427503,1739141206.4555435,45.84995627403259,0.0,1739141206.4555454,45.84995627403259,0.1852090117385965,1739141206.4555469,45.84995627403259,3.409702994184936,1739141206.4555485,45.84995627403259,1.2675979255041538 +1739141206.4764245,45.869956254959106,38.99803233406831,1739141206.4764278,45.869956254959106,0.08206551628415859,1739141206.4764314,45.869956254959106,74.28235899833055,1739141206.476435,45.869956254959106,33.24191395973452,1739141206.4764369,45.869956254959106,-0.09202299121519536,1739141206.4764388,45.869956254959106,-3.1113577894934985,1739141206.4764407,45.869956254959106,-1.3569830698404293,1739141206.476442,45.869956254959106,-0.3131108951619148,1739141206.4764435,45.869956254959106,1.4528069372427503,1739141206.4764457,45.869956254959106,0.0,1739141206.4764476,45.869956254959106,0.1852090117385965,1739141206.476449,45.869956254959106,3.409702994184936,1739141206.4764504,45.869956254959106,1.2675979255041538 +1739141206.4957657,45.88995623588562,38.99803233406831,1739141206.4957693,45.88995623588562,0.08206551628415859,1739141206.4957736,45.88995623588562,74.28235899833055,1739141206.4957767,45.88995623588562,33.24191395973452,1739141206.4957783,45.88995623588562,-0.09202299121519536,1739141206.4957805,45.88995623588562,-3.1113577894934985,1739141206.4957821,45.88995623588562,-1.3569830698404293,1739141206.495784,45.88995623588562,-0.3131108951619148,1739141206.4957855,45.88995623588562,1.4528069372427503,1739141206.4957874,45.88995623588562,0.0,1739141206.495789,45.88995623588562,0.1852090117385965,1739141206.4957905,45.88995623588562,3.409702994184936,1739141206.4957924,45.88995623588562,1.2675979255041538 +1739141206.5156045,45.909956216812134,38.99803233406831,1739141206.5156076,45.909956216812134,0.08206551628415859,1739141206.5156114,45.909956216812134,74.28235899833055,1739141206.515615,45.909956216812134,33.24191395973452,1739141206.5156167,45.909956216812134,-0.09202299121519536,1739141206.5156186,45.909956216812134,-3.1113577894934985,1739141206.5156205,45.909956216812134,-1.3569830698404293,1739141206.515622,45.909956216812134,-0.3131108951619148,1739141206.5156233,45.909956216812134,1.4528069372427503,1739141206.5156252,45.909956216812134,0.0,1739141206.5156271,45.909956216812134,0.1852090117385965,1739141206.5156288,45.909956216812134,3.409702994184936,1739141206.5156302,45.909956216812134,1.2675979255041538 +1739141206.5355837,45.92995619773865,38.99803233406831,1739141206.535587,45.92995619773865,0.08206551628415859,1739141206.5355904,45.92995619773865,74.28235899833055,1739141206.535594,45.92995619773865,33.24191395973452,1739141206.5355961,45.92995619773865,-0.09202299121519536,1739141206.535598,45.92995619773865,-3.1113577894934985,1739141206.5355997,45.92995619773865,-1.3569830698404293,1739141206.5356011,45.92995619773865,-0.3131108951619148,1739141206.5356026,45.92995619773865,1.4528069372427503,1739141206.5356047,45.92995619773865,0.0,1739141206.5356064,45.92995619773865,0.1852090117385965,1739141206.5356078,45.92995619773865,3.409702994184936,1739141206.5356092,45.92995619773865,1.2675979255041538 +1739141206.5552964,45.94995617866516,38.86232785418771,1739141206.5553,45.94995617866516,0.04586396687961969,1739141206.5553036,45.94995617866516,74.40603616504228,1739141206.5553071,45.94995617866516,33.05737402812791,1739141206.5553088,45.94995617866516,-0.09001914538812829,1739141206.555311,45.94995617866516,-3.1181887978705167,1739141206.5553126,45.94995617866516,-1.3159022514428587,1739141206.5553145,45.94995617866516,-0.2987517450259787,1739141206.555316,45.94995617866516,1.476877159691978,1739141206.5553179,45.94995617866516,0.0,1739141206.5553198,45.94995617866516,0.1924225983820352,1739141206.5553215,45.94995617866516,3.3936066088582058,1739141206.5553231,45.94995617866516,1.2878896042846772 +1739141206.5755215,45.969956159591675,38.86232785418771,1739141206.5755248,45.969956159591675,0.04586396687961969,1739141206.5755284,45.969956159591675,74.40603616504228,1739141206.5755317,45.969956159591675,33.05737402812791,1739141206.5755336,45.969956159591675,-0.09001914538812829,1739141206.5755355,45.969956159591675,-3.1181887978705167,1739141206.5755372,45.969956159591675,-1.3159022514428587,1739141206.5755389,45.969956159591675,-0.2987517450259787,1739141206.5755403,45.969956159591675,1.476877159691978,1739141206.5755422,45.969956159591675,0.0,1739141206.575544,45.969956159591675,0.18898755540730083,1739141206.5755455,45.969956159591675,3.3936066088582058,1739141206.5755472,45.969956159591675,1.2878896042846772 +1739141206.5955868,45.98995614051819,38.86232785418771,1739141206.5955904,45.98995614051819,0.04586396687961969,1739141206.595594,45.98995614051819,74.40603616504228,1739141206.5955973,45.98995614051819,33.05737402812791,1739141206.5955992,45.98995614051819,-0.09001914538812829,1739141206.5956008,45.98995614051819,-3.1181887978705167,1739141206.5956028,45.98995614051819,-1.3159022514428587,1739141206.5956042,45.98995614051819,-0.2987517450259787,1739141206.5956059,45.98995614051819,1.476877159691978,1739141206.5956078,45.98995614051819,0.0,1739141206.5956097,45.98995614051819,0.18898755540730083,1739141206.595611,45.98995614051819,3.3936066088582058,1739141206.5956128,45.98995614051819,1.2878896042846772 +1739141206.6155422,46.0099561214447,38.86232785418771,1739141206.6155455,46.0099561214447,0.04586396687961969,1739141206.615549,46.0099561214447,74.40603616504228,1739141206.6155524,46.0099561214447,33.05737402812791,1739141206.6155543,46.0099561214447,-0.09001914538812829,1739141206.6155562,46.0099561214447,-3.1181887978705167,1739141206.6155584,46.0099561214447,-1.3159022514428587,1739141206.61556,46.0099561214447,-0.2987517450259787,1739141206.6155615,46.0099561214447,1.476877159691978,1739141206.6155632,46.0099561214447,0.0,1739141206.615565,46.0099561214447,0.18898755540730083,1739141206.6155665,46.0099561214447,3.3936066088582058,1739141206.6155682,46.0099561214447,1.2878896042846772 +1739141206.6357696,46.029956102371216,38.86232785418771,1739141206.6357727,46.029956102371216,0.04586396687961969,1739141206.6357763,46.029956102371216,74.40603616504228,1739141206.6357796,46.029956102371216,33.05737402812791,1739141206.635781,46.029956102371216,-0.09001914538812829,1739141206.6357832,46.029956102371216,-3.1181887978705167,1739141206.6357849,46.029956102371216,-1.3159022514428587,1739141206.6357865,46.029956102371216,-0.2987517450259787,1739141206.635788,46.029956102371216,1.476877159691978,1739141206.6357899,46.029956102371216,0.0,1739141206.6357918,46.029956102371216,0.18898755540730083,1739141206.6357934,46.029956102371216,3.3936066088582058,1739141206.6357949,46.029956102371216,1.2878896042846772 +1739141206.6553016,46.04995608329773,38.72388219628387,1739141206.6553051,46.04995608329773,0.011262729970244578,1739141206.6553087,46.04995608329773,74.55596060557939,1739141206.655312,46.04995608329773,32.8452800891284,1739141206.6553142,46.04995608329773,-0.0883062407130272,1739141206.6553166,46.04995608329773,-3.124656747898884,1739141206.6553183,46.04995608329773,-1.2811796522454988,1739141206.6553197,46.04995608329773,-0.2837921540743113,1739141206.6553214,46.04995608329773,1.497532675759302,1739141206.6553235,46.04995608329773,0.0,1739141206.655325,46.04995608329773,0.1888540033492174,1739141206.6553264,46.04995608329773,3.378199264918338,1739141206.655328,46.04995608329773,1.3086150761601805 +1739141206.6755893,46.06995606422424,38.72388219628387,1739141206.6755924,46.06995606422424,0.011262729970244578,1739141206.6755958,46.06995606422424,74.55596060557939,1739141206.675599,46.06995606422424,32.8452800891284,1739141206.675601,46.06995606422424,-0.0883062407130272,1739141206.675603,46.06995606422424,-3.124656747898884,1739141206.6756048,46.06995606422424,-1.2811796522454988,1739141206.6756063,46.06995606422424,-0.2837921540743113,1739141206.675608,46.06995606422424,1.497532675759302,1739141206.6756098,46.06995606422424,0.0,1739141206.6756115,46.06995606422424,0.18891759959912147,1739141206.675613,46.06995606422424,3.378199264918338,1739141206.6756144,46.06995606422424,1.3086150761601805 +1739141206.6955407,46.08995604515076,38.72388219628387,1739141206.6955438,46.08995604515076,0.011262729970244578,1739141206.6955476,46.08995604515076,74.55596060557939,1739141206.6955512,46.08995604515076,32.8452800891284,1739141206.695553,46.08995604515076,-0.0883062407130272,1739141206.695555,46.08995604515076,-3.124656747898884,1739141206.6955569,46.08995604515076,-1.2811796522454988,1739141206.6955585,46.08995604515076,-0.2837921540743113,1739141206.6955602,46.08995604515076,1.497532675759302,1739141206.695562,46.08995604515076,0.0,1739141206.695564,46.08995604515076,0.18891759959912147,1739141206.6955655,46.08995604515076,3.378199264918338,1739141206.6955674,46.08995604515076,1.3086150761601805 +1739141206.7154243,46.10995602607727,38.72388219628387,1739141206.7154276,46.10995602607727,0.011262729970244578,1739141206.7154315,46.10995602607727,74.55596060557939,1739141206.7154348,46.10995602607727,32.8452800891284,1739141206.7154367,46.10995602607727,-0.0883062407130272,1739141206.7154388,46.10995602607727,-3.124656747898884,1739141206.7154408,46.10995602607727,-1.2811796522454988,1739141206.715442,46.10995602607727,-0.2837921540743113,1739141206.7154434,46.10995602607727,1.497532675759302,1739141206.7154455,46.10995602607727,0.0,1739141206.7154472,46.10995602607727,0.18891759959912147,1739141206.7154489,46.10995602607727,3.378199264918338,1739141206.7154503,46.10995602607727,1.3086150761601805 +1739141206.7359872,46.129956007003784,38.72388219628387,1739141206.735991,46.129956007003784,0.011262729970244578,1739141206.7359946,46.129956007003784,74.55596060557939,1739141206.7359982,46.129956007003784,32.8452800891284,1739141206.7360003,46.129956007003784,-0.0883062407130272,1739141206.7360022,46.129956007003784,-3.124656747898884,1739141206.736004,46.129956007003784,-1.2811796522454988,1739141206.7360055,46.129956007003784,-0.2837921540743113,1739141206.7360072,46.129956007003784,1.497532675759302,1739141206.7360091,46.129956007003784,0.0,1739141206.7360113,46.129956007003784,0.18891759959912147,1739141206.7360132,46.129956007003784,3.378199264918338,1739141206.7360146,46.129956007003784,1.3086150761601805 +1739141206.755277,46.1499559879303,38.72388219628387,1739141206.7552805,46.1499559879303,0.011262729970244578,1739141206.7552843,46.1499559879303,74.55596060557939,1739141206.755288,46.1499559879303,32.8452800891284,1739141206.7552896,46.1499559879303,-0.0883062407130272,1739141206.755292,46.1499559879303,-3.124656747898884,1739141206.7552936,46.1499559879303,-1.2811796522454988,1739141206.7552953,46.1499559879303,-0.2837921540743113,1739141206.7552967,46.1499559879303,1.497532675759302,1739141206.7552989,46.1499559879303,0.0,1739141206.7553005,46.1499559879303,0.18891759959912147,1739141206.7553022,46.1499559879303,3.378199264918338,1739141206.7553036,46.1499559879303,1.3086150761601805 +1739141206.7757156,46.16995596885681,38.58271320494714,1739141206.7757185,46.16995596885681,-0.02177310641959007,1739141206.775722,46.16995596885681,74.32534465196052,1739141206.7757254,46.16995596885681,33.013788852449544,1739141206.775727,46.16995596885681,-0.08966495001991498,1739141206.7757292,46.16995596885681,-3.1294020623512386,1739141206.7757306,46.16995596885681,-1.1599950346126913,1739141206.7757323,46.16995596885681,-0.28634427438679666,1739141206.7757337,46.16995596885681,1.5719120082254199,1739141206.7757359,46.16995596885681,0.0,1739141206.7757373,46.16995596885681,0.291395282108574,1739141206.775739,46.16995596885681,3.3636017453050746,1739141206.7757404,46.16995596885681,1.3293156469271115 +1739141206.7955182,46.189955949783325,38.58271320494714,1739141206.7955215,46.189955949783325,-0.02177310641959007,1739141206.795525,46.189955949783325,74.32534465196052,1739141206.7955287,46.189955949783325,33.013788852449544,1739141206.7955303,46.189955949783325,-0.08966495001991498,1739141206.7955325,46.189955949783325,-3.1294020623512386,1739141206.7955341,46.189955949783325,-1.1599950346126913,1739141206.7955356,46.189955949783325,-0.28634427438679666,1739141206.7955372,46.189955949783325,1.5719120082254199,1739141206.7955391,46.189955949783325,0.0,1739141206.795541,46.189955949783325,0.24259636129830842,1739141206.7955425,46.189955949783325,3.3636017453050746,1739141206.7955441,46.189955949783325,1.3293156469271115 +1739141206.8155127,46.20995593070984,38.58271320494714,1739141206.815516,46.20995593070984,-0.02177310641959007,1739141206.8155198,46.20995593070984,74.32534465196052,1739141206.8155236,46.20995593070984,33.013788852449544,1739141206.815525,46.20995593070984,-0.08966495001991498,1739141206.8155274,46.20995593070984,-3.1294020623512386,1739141206.815529,46.20995593070984,-1.1599950346126913,1739141206.815531,46.20995593070984,-0.28634427438679666,1739141206.8155322,46.20995593070984,1.5719120082254199,1739141206.8155344,46.20995593070984,0.0,1739141206.8155358,46.20995593070984,0.24259636129830842,1739141206.8155375,46.20995593070984,3.3636017453050746,1739141206.8155391,46.20995593070984,1.3293156469271115 +1739141206.8353617,46.22995591163635,38.58271320494714,1739141206.8353648,46.22995591163635,-0.02177310641959007,1739141206.8353682,46.22995591163635,74.32534465196052,1739141206.8353715,46.22995591163635,33.013788852449544,1739141206.8353732,46.22995591163635,-0.08966495001991498,1739141206.835375,46.22995591163635,-3.1294020623512386,1739141206.835377,46.22995591163635,-1.1599950346126913,1739141206.8353784,46.22995591163635,-0.28634427438679666,1739141206.8353796,46.22995591163635,1.5719120082254199,1739141206.8353817,46.22995591163635,0.0,1739141206.835384,46.22995591163635,0.24259636129830842,1739141206.8353853,46.22995591163635,3.3636017453050746,1739141206.835387,46.22995591163635,1.3293156469271115 +1739141206.8555617,46.249955892562866,38.58271320494714,1739141206.8555648,46.249955892562866,-0.02177310641959007,1739141206.8555684,46.249955892562866,74.32534465196052,1739141206.8555717,46.249955892562866,33.013788852449544,1739141206.8555734,46.249955892562866,-0.08966495001991498,1739141206.8555753,46.249955892562866,-3.1294020623512386,1739141206.8555772,46.249955892562866,-1.1599950346126913,1739141206.855579,46.249955892562866,-0.28634427438679666,1739141206.8555803,46.249955892562866,1.5719120082254199,1739141206.8555825,46.249955892562866,0.0,1739141206.8555841,46.249955892562866,0.24259636129830842,1739141206.8555858,46.249955892562866,3.3636017453050746,1739141206.8555872,46.249955892562866,1.3293156469271115 +1739141206.8759084,46.26995587348938,38.438601521759,1739141206.8759115,46.26995587348938,-0.05331470383920678,1739141206.875915,46.26995587348938,74.25695052243822,1739141206.8759186,46.26995587348938,33.00281345242365,1739141206.87592,46.26995587348938,-0.08957571912539555,1739141206.8759224,46.26995587348938,-3.134921959851801,1739141206.875924,46.26995587348938,-1.0853183530971386,1739141206.8759258,46.26995587348938,-0.2812541948070705,1739141206.8759272,46.26995587348938,1.6195743869726233,1739141206.875929,46.26995587348938,0.0,1739141206.8759308,46.26995587348938,0.28308008039280114,1739141206.8759325,46.26995587348938,3.3492714080893142,1739141206.875934,46.26995587348938,1.355772277683579 +1739141206.8952546,46.289955854415894,38.438601521759,1739141206.8952582,46.289955854415894,-0.05331470383920678,1739141206.8952622,46.289955854415894,74.25695052243822,1739141206.8952656,46.289955854415894,33.00281345242365,1739141206.8952672,46.289955854415894,-0.08957571912539555,1739141206.8952694,46.289955854415894,-3.134921959851801,1739141206.895271,46.289955854415894,-1.0853183530971386,1739141206.8952727,46.289955854415894,-0.2812541948070705,1739141206.8952742,46.289955854415894,1.6195743869726233,1739141206.8952763,46.289955854415894,0.0,1739141206.895278,46.289955854415894,0.26380210928904435,1739141206.89528,46.289955854415894,3.3492714080893142,1739141206.8952813,46.289955854415894,1.355772277683579 +1739141206.9155698,46.30995583534241,38.438601521759,1739141206.9155726,46.30995583534241,-0.05331470383920678,1739141206.9155765,46.30995583534241,74.25695052243822,1739141206.9155803,46.30995583534241,33.00281345242365,1739141206.915582,46.30995583534241,-0.08957571912539555,1739141206.915584,46.30995583534241,-3.134921959851801,1739141206.9155858,46.30995583534241,-1.0853183530971386,1739141206.9155877,46.30995583534241,-0.2812541948070705,1739141206.915589,46.30995583534241,1.6195743869726233,1739141206.915591,46.30995583534241,0.0,1739141206.9155927,46.30995583534241,0.26380210928904435,1739141206.9155943,46.30995583534241,3.3492714080893142,1739141206.9155958,46.30995583534241,1.355772277683579 +1739141206.9357743,46.32995581626892,38.438601521759,1739141206.935777,46.32995581626892,-0.05331470383920678,1739141206.935781,46.32995581626892,74.25695052243822,1739141206.9357848,46.32995581626892,33.00281345242365,1739141206.9357862,46.32995581626892,-0.08957571912539555,1739141206.9357886,46.32995581626892,-3.134921959851801,1739141206.93579,46.32995581626892,-1.0853183530971386,1739141206.9357917,46.32995581626892,-0.2812541948070705,1739141206.9357932,46.32995581626892,1.6195743869726233,1739141206.9357948,46.32995581626892,0.0,1739141206.9357967,46.32995581626892,0.26380210928904435,1739141206.9357982,46.32995581626892,3.3492714080893142,1739141206.9358,46.32995581626892,1.355772277683579 +1739141206.9555151,46.349955797195435,38.438601521759,1739141206.9555185,46.349955797195435,-0.05331470383920678,1739141206.955522,46.349955797195435,74.25695052243822,1739141206.9555254,46.349955797195435,33.00281345242365,1739141206.955527,46.349955797195435,-0.08957571912539555,1739141206.955529,46.349955797195435,-3.134921959851801,1739141206.9555306,46.349955797195435,-1.0853183530971386,1739141206.9555323,46.349955797195435,-0.2812541948070705,1739141206.9555337,46.349955797195435,1.6195743869726233,1739141206.955536,46.349955797195435,0.0,1739141206.9555376,46.349955797195435,0.26380210928904435,1739141206.9555392,46.349955797195435,3.3492714080893142,1739141206.9555407,46.349955797195435,1.355772277683579 +1739141206.9764833,46.36995577812195,38.438601521759,1739141206.9764874,46.36995577812195,-0.05331470383920678,1739141206.9764926,46.36995577812195,74.25695052243822,1739141206.9764977,46.36995577812195,33.00281345242365,1739141206.9765007,46.36995577812195,-0.08957571912539555,1739141206.9765043,46.36995577812195,-3.134921959851801,1739141206.9765081,46.36995577812195,-1.0853183530971386,1739141206.9765115,46.36995577812195,-0.2812541948070705,1739141206.9765148,46.36995577812195,1.6195743869726233,1739141206.9765184,46.36995577812195,0.0,1739141206.9765217,46.36995577812195,0.26380210928904435,1739141206.976525,46.36995577812195,3.3492714080893142,1739141206.9765284,46.36995577812195,1.355772277683579 +1739141206.9962866,46.38995575904846,38.29106275673214,1739141206.9962904,46.38995575904846,-0.08340221632028921,1739141206.9962952,46.38995575904846,74.39085453324078,1739141206.9963002,46.38995575904846,32.78231504441353,1739141206.9963033,46.38995575904846,-0.08780092777752846,1739141206.9963071,46.38995575904846,-3.140794158041969,1739141206.9963105,46.38995575904846,-1.054628530763117,1739141206.9963138,46.38995575904846,-0.26620287922307867,1739141206.9963171,46.38995575904846,1.6395787016045809,1739141206.996321,46.38995575904846,0.0,1739141206.9963245,46.38995575904846,0.24688208582356957,1739141206.9963279,46.38995575904846,3.335026423859277,1739141206.9963312,46.38995575904846,1.3846394577249304 +1739141207.0161812,46.409955739974976,38.29106275673214,1739141207.0161848,46.409955739974976,-0.08340221632028921,1739141207.0161893,46.409955739974976,74.39085453324078,1739141207.016194,46.409955739974976,32.78231504441353,1739141207.0161963,46.409955739974976,-0.08780092777752846,1739141207.0161994,46.409955739974976,-3.140794158041969,1739141207.016202,46.409955739974976,-1.054628530763117,1739141207.0162044,46.409955739974976,-0.26620287922307867,1739141207.0162065,46.409955739974976,1.6395787016045809,1739141207.0162091,46.409955739974976,0.0,1739141207.0162115,46.409955739974976,0.2549392438796505,1739141207.0162137,46.409955739974976,3.335026423859277,1739141207.016216,46.409955739974976,1.3846394577249304 +1739141207.035956,46.42995572090149,38.29106275673214,1739141207.0359597,46.42995572090149,-0.08340221632028921,1739141207.0359643,46.42995572090149,74.39085453324078,1739141207.0359688,46.42995572090149,32.78231504441353,1739141207.0359712,46.42995572090149,-0.08780092777752846,1739141207.035974,46.42995572090149,-3.140794158041969,1739141207.0359766,46.42995572090149,-1.054628530763117,1739141207.035979,46.42995572090149,-0.26620287922307867,1739141207.035981,46.42995572090149,1.6395787016045809,1739141207.0359838,46.42995572090149,0.0,1739141207.0359864,46.42995572090149,0.2549392438796505,1739141207.0359886,46.42995572090149,3.335026423859277,1739141207.0359907,46.42995572090149,1.3846394577249304 +1739141207.0565777,46.449955701828,38.29106275673214,1739141207.0565825,46.449955701828,-0.08340221632028921,1739141207.0565865,46.449955701828,74.39085453324078,1739141207.0565906,46.449955701828,32.78231504441353,1739141207.0565927,46.449955701828,-0.08780092777752846,1739141207.0565948,46.449955701828,-3.140794158041969,1739141207.0565972,46.449955701828,-1.054628530763117,1739141207.0565996,46.449955701828,-0.26620287922307867,1739141207.0566015,46.449955701828,1.6395787016045809,1739141207.0566037,46.449955701828,0.0,1739141207.056606,46.449955701828,0.2549392438796505,1739141207.056608,46.449955701828,3.335026423859277,1739141207.05661,46.449955701828,1.3846394577249304 +1739141207.0765405,46.46995568275452,38.29106275673214,1739141207.0765443,46.46995568275452,-0.08340221632028921,1739141207.076549,46.46995568275452,74.39085453324078,1739141207.0765545,46.46995568275452,32.78231504441353,1739141207.0765574,46.46995568275452,-0.08780092777752846,1739141207.0765615,46.46995568275452,-3.140794158041969,1739141207.0765648,46.46995568275452,-1.054628530763117,1739141207.0765681,46.46995568275452,-0.26620287922307867,1739141207.0765717,46.46995568275452,1.6395787016045809,1739141207.0765753,46.46995568275452,0.0,1739141207.0765786,46.46995568275452,0.2549392438796505,1739141207.076582,46.46995568275452,3.335026423859277,1739141207.0765853,46.46995568275452,1.3846394577249304 +1739141207.0961618,46.48995566368103,38.14004266202615,1739141207.096166,46.48995566368103,-0.11198398656124642,1739141207.0961702,46.48995566368103,74.39350762016151,1739141207.0961742,46.48995566368103,32.69614453412572,1739141207.0961769,46.48995566368103,-0.0871060043074655,1739141207.0961797,46.48995566368103,3.13702280152995,1739141207.0961823,46.48995566368103,-0.9969551107776375,1739141207.0961845,46.48995566368103,-0.2577137708472355,1739141207.0961869,46.48995566368103,1.6778424088319825,1739141207.0961895,46.48995566368103,0.0,1739141207.0961916,46.48995566368103,0.2748389141666598,1739141207.0961945,46.48995566368103,3.3211928369799417,1739141207.096197,46.48995566368103,1.4124795328690223 +1739141207.1158547,46.509955644607544,38.14004266202615,1739141207.1158574,46.509955644607544,-0.11198398656124642,1739141207.1158602,46.509955644607544,74.39350762016151,1739141207.1158628,46.509955644607544,32.69614453412572,1739141207.115864,46.509955644607544,-0.0871060043074655,1739141207.1158657,46.509955644607544,3.13702280152995,1739141207.115867,46.509955644607544,-0.9969551107776375,1739141207.115868,46.509955644607544,-0.2577137708472355,1739141207.1158693,46.509955644607544,1.6778424088319825,1739141207.1158707,46.509955644607544,0.0,1739141207.115872,46.509955644607544,0.26536287596296027,1739141207.1158733,46.509955644607544,3.3211928369799417,1739141207.1158745,46.509955644607544,1.4124795328690223 +1739141207.1350164,46.52995562553406,38.14004266202615,1739141207.1350193,46.52995562553406,-0.11198398656124642,1739141207.135022,46.52995562553406,74.39350762016151,1739141207.1350243,46.52995562553406,32.69614453412572,1739141207.1350257,46.52995562553406,-0.0871060043074655,1739141207.1350272,46.52995562553406,3.13702280152995,1739141207.1350284,46.52995562553406,-0.9969551107776375,1739141207.13503,46.52995562553406,-0.2577137708472355,1739141207.135031,46.52995562553406,1.6778424088319825,1739141207.1350327,46.52995562553406,0.0,1739141207.135034,46.52995562553406,0.26536287596296027,1739141207.1350353,46.52995562553406,3.3211928369799417,1739141207.1350367,46.52995562553406,1.4124795328690223 +1739141207.1550763,46.54995560646057,38.14004266202615,1739141207.1550786,46.54995560646057,-0.11198398656124642,1739141207.1550815,46.54995560646057,74.39350762016151,1739141207.155084,46.54995560646057,32.69614453412572,1739141207.155085,46.54995560646057,-0.0871060043074655,1739141207.1550865,46.54995560646057,3.13702280152995,1739141207.155088,46.54995560646057,-0.9969551107776375,1739141207.155089,46.54995560646057,-0.2577137708472355,1739141207.15509,46.54995560646057,1.6778424088319825,1739141207.1550915,46.54995560646057,0.0,1739141207.1550927,46.54995560646057,0.26536287596296027,1739141207.1550937,46.54995560646057,3.3211928369799417,1739141207.155095,46.54995560646057,1.4124795328690223 +1739141207.1752474,46.569955587387085,38.14004266202615,1739141207.1752505,46.569955587387085,-0.11198398656124642,1739141207.1752534,46.569955587387085,74.39350762016151,1739141207.175256,46.569955587387085,32.69614453412572,1739141207.175258,46.569955587387085,-0.0871060043074655,1739141207.1752594,46.569955587387085,3.13702280152995,1739141207.175261,46.569955587387085,-0.9969551107776375,1739141207.1752622,46.569955587387085,-0.2577137708472355,1739141207.1752634,46.569955587387085,1.6778424088319825,1739141207.1752656,46.569955587387085,0.0,1739141207.1752667,46.569955587387085,0.26536287596296027,1739141207.1752682,46.569955587387085,3.3211928369799417,1739141207.1752694,46.569955587387085,1.4124795328690223 +1739141207.1950824,46.5899555683136,38.14004266202615,1739141207.1950848,46.5899555683136,-0.11198398656124642,1739141207.1950877,46.5899555683136,74.39350762016151,1739141207.1950908,46.5899555683136,32.69614453412572,1739141207.1950922,46.5899555683136,-0.0871060043074655,1739141207.1950939,46.5899555683136,3.13702280152995,1739141207.195095,46.5899555683136,-0.9969551107776375,1739141207.1950963,46.5899555683136,-0.2577137708472355,1739141207.1950977,46.5899555683136,1.6778424088319825,1739141207.195099,46.5899555683136,0.0,1739141207.1951003,46.5899555683136,0.26536287596296027,1739141207.1951017,46.5899555683136,3.3211928369799417,1739141207.1951027,46.5899555683136,1.4124795328690223 +1739141207.2149436,46.60995554924011,37.98555308920282,1739141207.2149463,46.60995554924011,-0.1390676634835426,1739141207.2149491,46.60995554924011,74.39621519393027,1739141207.214952,46.60995554924011,32.605655824130785,1739141207.2149532,46.60995554924011,-0.08576249318609253,1739141207.214955,46.60995554924011,3.131684764386119,1739141207.2149563,46.60995554924011,-0.9436912639895019,1739141207.2149575,46.60995554924011,-0.24980159832314525,1739141207.2149587,46.60995554924011,1.7139732722685366,1739141207.21496,46.60995554924011,0.0,1739141207.2149613,46.60995554924011,0.27847269015553433,1739141207.2149625,46.60995554924011,3.307998886794142,1739141207.2149637,46.60995554924011,1.44174335389467 +1739141207.2349536,46.629955530166626,37.98555308920282,1739141207.2349567,46.629955530166626,-0.1390676634835426,1739141207.2349596,46.629955530166626,74.39621519393027,1739141207.2349627,46.629955530166626,32.605655824130785,1739141207.234964,46.629955530166626,-0.08576249318609253,1739141207.2349656,46.629955530166626,3.131684764386119,1739141207.234967,46.629955530166626,-0.9436912639895019,1739141207.2349684,46.629955530166626,-0.24980159832314525,1739141207.2349696,46.629955530166626,1.7139732722685366,1739141207.234971,46.629955530166626,0.0,1739141207.2349727,46.629955530166626,0.27222991837386656,1739141207.234974,46.629955530166626,3.307998886794142,1739141207.2349753,46.629955530166626,1.44174335389467 +1739141207.2549186,46.64995551109314,37.98555308920282,1739141207.254921,46.64995551109314,-0.1390676634835426,1739141207.2549238,46.64995551109314,74.39621519393027,1739141207.2549267,46.64995551109314,32.605655824130785,1739141207.254928,46.64995551109314,-0.08576249318609253,1739141207.2549298,46.64995551109314,3.131684764386119,1739141207.254931,46.64995551109314,-0.9436912639895019,1739141207.2549322,46.64995551109314,-0.24980159832314525,1739141207.2549336,46.64995551109314,1.7139732722685366,1739141207.2549348,46.64995551109314,0.0,1739141207.2549362,46.64995551109314,0.27222991837386656,1739141207.2549376,46.64995551109314,3.307998886794142,1739141207.2549386,46.64995551109314,1.44174335389467 +1739141207.27522,46.66995549201965,37.98555308920282,1739141207.2752235,46.66995549201965,-0.1390676634835426,1739141207.275227,46.66995549201965,74.39621519393027,1739141207.2752304,46.66995549201965,32.605655824130785,1739141207.275232,46.66995549201965,-0.08576249318609253,1739141207.2752335,46.66995549201965,3.131684764386119,1739141207.2752352,46.66995549201965,-0.9436912639895019,1739141207.2752366,46.66995549201965,-0.24980159832314525,1739141207.2752378,46.66995549201965,1.7139732722685366,1739141207.2752397,46.66995549201965,0.0,1739141207.2752411,46.66995549201965,0.27222991837386656,1739141207.2752428,46.66995549201965,3.307998886794142,1739141207.2752442,46.66995549201965,1.44174335389467 +1739141207.295058,46.68995547294617,37.98555308920282,1739141207.2950604,46.68995547294617,-0.1390676634835426,1739141207.2950633,46.68995547294617,74.39621519393027,1739141207.295066,46.68995547294617,32.605655824130785,1739141207.2950673,46.68995547294617,-0.08576249318609253,1739141207.2950692,46.68995547294617,3.131684764386119,1739141207.295071,46.68995547294617,-0.9436912639895019,1739141207.2950726,46.68995547294617,-0.24980159832314525,1739141207.2950737,46.68995547294617,1.7139732722685366,1739141207.2950757,46.68995547294617,0.0,1739141207.2950768,46.68995547294617,0.27222991837386656,1739141207.2950785,46.68995547294617,3.307998886794142,1739141207.2950797,46.68995547294617,1.44174335389467 +1739141207.315102,46.70995545387268,37.82753794225987,1739141207.3151047,46.70995545387268,-0.16464622778445825,1739141207.3151076,46.70995545387268,74.63552573629927,1739141207.3151104,46.70995545387268,32.277237493309926,1739141207.3151119,46.70995545387268,-0.08295803958863374,1739141207.3151138,46.70995545387268,3.1268759204221928,1739141207.3151152,46.70995545387268,-0.9293347489167355,1739141207.315117,46.70995545387268,-0.23117747892897783,1739141207.315118,46.70995545387268,1.723844260988546,1739141207.3151195,46.70995545387268,0.0,1739141207.315121,46.70995545387268,0.23436048992805936,1739141207.3151221,46.70995545387268,3.29508858218896,1739141207.3151238,46.70995545387268,1.4714507008875102 +1739141207.3353148,46.729955434799194,37.82753794225987,1739141207.3353179,46.729955434799194,-0.16464622778445825,1739141207.3353212,46.729955434799194,74.63552573629927,1739141207.3353238,46.729955434799194,32.277237493309926,1739141207.3353255,46.729955434799194,-0.08295803958863374,1739141207.3353271,46.729955434799194,3.1268759204221928,1739141207.3353288,46.729955434799194,-0.9293347489167355,1739141207.3353302,46.729955434799194,-0.23117747892897783,1739141207.3353317,46.729955434799194,1.723844260988546,1739141207.3353333,46.729955434799194,0.0,1739141207.335335,46.729955434799194,0.25239356010103586,1739141207.3353364,46.729955434799194,3.29508858218896,1739141207.3353376,46.729955434799194,1.4714507008875102 +1739141207.3551004,46.74995541572571,37.82753794225987,1739141207.3551035,46.74995541572571,-0.16464622778445825,1739141207.3551064,46.74995541572571,74.63552573629927,1739141207.3551095,46.74995541572571,32.277237493309926,1739141207.3551106,46.74995541572571,-0.08295803958863374,1739141207.3551126,46.74995541572571,3.1268759204221928,1739141207.3551137,46.74995541572571,-0.9293347489167355,1739141207.3551152,46.74995541572571,-0.23117747892897783,1739141207.3551166,46.74995541572571,1.723844260988546,1739141207.3551183,46.74995541572571,0.0,1739141207.3551197,46.74995541572571,0.25239356010103586,1739141207.355121,46.74995541572571,3.29508858218896,1739141207.355122,46.74995541572571,1.4714507008875102 +1739141207.3754208,46.76995539665222,37.82753794225987,1739141207.375424,46.76995539665222,-0.16464622778445825,1739141207.3754272,46.76995539665222,74.63552573629927,1739141207.3754303,46.76995539665222,32.277237493309926,1739141207.375432,46.76995539665222,-0.08295803958863374,1739141207.3754337,46.76995539665222,3.1268759204221928,1739141207.3754354,46.76995539665222,-0.9293347489167355,1739141207.3754368,46.76995539665222,-0.23117747892897783,1739141207.375438,46.76995539665222,1.723844260988546,1739141207.37544,46.76995539665222,0.0,1739141207.3754413,46.76995539665222,0.25239356010103586,1739141207.375443,46.76995539665222,3.29508858218896,1739141207.3754442,46.76995539665222,1.4714507008875102 +1739141207.395089,46.789955377578735,37.82753794225987,1739141207.3950918,46.789955377578735,-0.16464622778445825,1739141207.3950949,46.789955377578735,74.63552573629927,1739141207.3950975,46.789955377578735,32.277237493309926,1739141207.3950992,46.789955377578735,-0.08295803958863374,1739141207.3951008,46.789955377578735,3.1268759204221928,1739141207.3951023,46.789955377578735,-0.9293347489167355,1739141207.3951037,46.789955377578735,-0.23117747892897783,1739141207.395105,46.789955377578735,1.723844260988546,1739141207.3951066,46.789955377578735,0.0,1739141207.395108,46.789955377578735,0.25239356010103586,1739141207.3951097,46.789955377578735,3.29508858218896,1739141207.3951108,46.789955377578735,1.4714507008875102 +1739141207.4152353,46.80995535850525,37.82753794225987,1739141207.4152381,46.80995535850525,-0.16464622778445825,1739141207.4152412,46.80995535850525,74.63552573629927,1739141207.4152443,46.80995535850525,32.277237493309926,1739141207.4152458,46.80995535850525,-0.08295803958863374,1739141207.4152474,46.80995535850525,3.1268759204221928,1739141207.4152489,46.80995535850525,-0.9293347489167355,1739141207.4152505,46.80995535850525,-0.23117747892897783,1739141207.4152515,46.80995535850525,1.723844260988546,1739141207.4152532,46.80995535850525,0.0,1739141207.4152548,46.80995535850525,0.25239356010103586,1739141207.415256,46.80995535850525,3.29508858218896,1739141207.4152575,46.80995535850525,1.4714507008875102 +1739141207.435367,46.82995533943176,37.66612214614476,1739141207.4353702,46.82995533943176,-0.18867759662401706,1739141207.4353733,46.82995533943176,74.89438796213791,1739141207.4353762,46.82995533943176,31.93703976868746,1739141207.4353776,46.82995533943176,-0.0800711792810036,1739141207.4353795,46.82995533943176,3.122637888575176,1739141207.435381,46.82995533943176,-0.9136658972071663,1739141207.4353824,46.82995533943176,-0.2133484259474181,1739141207.4353836,46.82995533943176,1.7346824539556938,1739141207.4353852,46.82995533943176,0.0,1739141207.435387,46.82995533943176,0.2213178718881492,1739141207.435388,46.82995533943176,3.2827713151036884,1739141207.4353895,46.82995533943176,1.4985666279072787 +1739141207.4562335,46.849955320358276,37.66612214614476,1739141207.4562373,46.849955320358276,-0.18867759662401706,1739141207.456242,46.849955320358276,74.89438796213791,1739141207.456248,46.849955320358276,31.93703976868746,1739141207.4562514,46.849955320358276,-0.0800711792810036,1739141207.4562552,46.849955320358276,3.122637888575176,1739141207.456259,46.849955320358276,-0.9136658972071663,1739141207.4562626,46.849955320358276,-0.2133484259474181,1739141207.4562662,46.849955320358276,1.7346824539556938,1739141207.4562697,46.849955320358276,0.0,1739141207.4562733,46.849955320358276,0.23611582604841508,1739141207.456277,46.849955320358276,3.2827713151036884,1739141207.4562805,46.849955320358276,1.4985666279072787 +1739141207.4770699,46.86995530128479,37.66612214614476,1739141207.4770737,46.86995530128479,-0.18867759662401706,1739141207.4770782,46.86995530128479,74.89438796213791,1739141207.4770837,46.86995530128479,31.93703976868746,1739141207.4770865,46.86995530128479,-0.0800711792810036,1739141207.4770901,46.86995530128479,3.122637888575176,1739141207.4770935,46.86995530128479,-0.9136658972071663,1739141207.4770968,46.86995530128479,-0.2133484259474181,1739141207.4770997,46.86995530128479,1.7346824539556938,1739141207.4771035,46.86995530128479,0.0,1739141207.477107,46.86995530128479,0.23611582604841508,1739141207.47711,46.86995530128479,3.2827713151036884,1739141207.4771132,46.86995530128479,1.4985666279072787 +1739141207.4948955,46.889955282211304,37.66612214614476,1739141207.4948978,46.889955282211304,-0.18867759662401706,1739141207.4949005,46.889955282211304,74.89438796213791,1739141207.4949033,46.889955282211304,31.93703976868746,1739141207.4949045,46.889955282211304,-0.0800711792810036,1739141207.4949062,46.889955282211304,3.122637888575176,1739141207.4949074,46.889955282211304,-0.9136658972071663,1739141207.4949086,46.889955282211304,-0.2133484259474181,1739141207.49491,46.889955282211304,1.7346824539556938,1739141207.4949114,46.889955282211304,0.0,1739141207.4949129,46.889955282211304,0.23611582604841508,1739141207.4949138,46.889955282211304,3.2827713151036884,1739141207.494915,46.889955282211304,1.4985666279072787 +1739141207.5152314,46.90995526313782,37.66612214614476,1739141207.5152342,46.90995526313782,-0.18867759662401706,1739141207.5152378,46.90995526313782,74.89438796213791,1739141207.515241,46.90995526313782,31.93703976868746,1739141207.5152426,46.90995526313782,-0.0800711792810036,1739141207.515245,46.90995526313782,3.122637888575176,1739141207.5152466,46.90995526313782,-0.9136658972071663,1739141207.515248,46.90995526313782,-0.2133484259474181,1739141207.5152495,46.90995526313782,1.7346824539556938,1739141207.5152514,46.90995526313782,0.0,1739141207.515253,46.90995526313782,0.23611582604841508,1739141207.5152543,46.90995526313782,3.2827713151036884,1739141207.5152557,46.90995526313782,1.4985666279072787 +1739141207.536166,46.92995524406433,37.50151054068959,1739141207.5361698,46.92995524406433,-0.21117249377171898,1739141207.5361738,46.92995524406433,74.99240265825883,1739141207.5361779,46.92995524406433,31.76146693697087,1739141207.53618,46.92995524406433,-0.0785688614274399,1739141207.536182,46.92995524406433,3.11849525925427,1739141207.536184,46.92995524406433,-0.8731996276292167,1739141207.5361857,46.92995524406433,-0.20311796621470032,1739141207.5361876,46.92995524406433,1.7629893822000475,1739141207.53619,46.92995524406433,0.0,1739141207.536192,46.92995524406433,0.24079691929394298,1739141207.5361936,46.92995524406433,3.271171353207392,1739141207.5361955,46.92995524406433,1.524421556041314 +1739141207.556583,46.949955224990845,37.50151054068959,1739141207.5565877,46.949955224990845,-0.21117249377171898,1739141207.556593,46.949955224990845,74.99240265825883,1739141207.5565972,46.949955224990845,31.76146693697087,1739141207.5565996,46.949955224990845,-0.0785688614274399,1739141207.5566025,46.949955224990845,3.11849525925427,1739141207.5566046,46.949955224990845,-0.8731996276292167,1739141207.5566068,46.949955224990845,-0.20311796621470032,1739141207.5566094,46.949955224990845,1.7629893822000475,1739141207.5566118,46.949955224990845,0.0,1739141207.5566142,46.949955224990845,0.23856782615873362,1739141207.5566165,46.949955224990845,3.271171353207392,1739141207.5566185,46.949955224990845,1.524421556041314 +1739141207.5797248,46.96995520591736,37.50151054068959,1739141207.5797312,46.96995520591736,-0.21117249377171898,1739141207.579739,46.96995520591736,74.99240265825883,1739141207.5797482,46.96995520591736,31.76146693697087,1739141207.5797532,46.96995520591736,-0.0785688614274399,1739141207.5797594,46.96995520591736,3.11849525925427,1739141207.579765,46.96995520591736,-0.8731996276292167,1739141207.5797708,46.96995520591736,-0.20311796621470032,1739141207.5797765,46.96995520591736,1.7629893822000475,1739141207.5797825,46.96995520591736,0.0,1739141207.579788,46.96995520591736,0.23856782615873362,1739141207.5797937,46.96995520591736,3.271171353207392,1739141207.5797994,46.96995520591736,1.524421556041314 +1739141207.5975115,46.98995518684387,37.50151054068959,1739141207.5975156,46.98995518684387,-0.21117249377171898,1739141207.5975204,46.98995518684387,74.99240265825883,1739141207.5975258,46.98995518684387,31.76146693697087,1739141207.5975292,46.98995518684387,-0.0785688614274399,1739141207.5975332,46.98995518684387,3.11849525925427,1739141207.5975368,46.98995518684387,-0.8731996276292167,1739141207.5975406,46.98995518684387,-0.20311796621470032,1739141207.5975442,46.98995518684387,1.7629893822000475,1739141207.5975478,46.98995518684387,0.0,1739141207.5975516,46.98995518684387,0.23856782615873362,1739141207.597555,46.98995518684387,3.271171353207392,1739141207.5975585,46.98995518684387,1.524421556041314 +1739141207.6172273,47.009955167770386,37.50151054068959,1739141207.617231,47.009955167770386,-0.21117249377171898,1739141207.6172354,47.009955167770386,74.99240265825883,1739141207.61724,47.009955167770386,31.76146693697087,1739141207.6172428,47.009955167770386,-0.0785688614274399,1739141207.6172462,47.009955167770386,3.11849525925427,1739141207.6172493,47.009955167770386,-0.8731996276292167,1739141207.6172523,47.009955167770386,-0.20311796621470032,1739141207.6172554,47.009955167770386,1.7629893822000475,1739141207.6172585,47.009955167770386,0.0,1739141207.6172616,47.009955167770386,0.23856782615873362,1739141207.6172647,47.009955167770386,3.271171353207392,1739141207.6172676,47.009955167770386,1.524421556041314 +1739141207.6371596,47.0299551486969,37.50151054068959,1739141207.6371639,47.0299551486969,-0.21117249377171898,1739141207.6371682,47.0299551486969,74.99240265825883,1739141207.6371732,47.0299551486969,31.76146693697087,1739141207.637176,47.0299551486969,-0.0785688614274399,1739141207.6371796,47.0299551486969,3.11849525925427,1739141207.637183,47.0299551486969,-0.8731996276292167,1739141207.637186,47.0299551486969,-0.20311796621470032,1739141207.6371894,47.0299551486969,1.7629893822000475,1739141207.6371927,47.0299551486969,0.0,1739141207.637196,47.0299551486969,0.23856782615873362,1739141207.6371992,47.0299551486969,3.271171353207392,1739141207.6372025,47.0299551486969,1.524421556041314 +1739141207.6571681,47.04995512962341,37.3338231159173,1739141207.6571717,47.04995512962341,-0.2321845013105035,1739141207.657176,47.04995512962341,75.17737870406377,1739141207.6571813,47.04995512962341,31.49795480435221,1739141207.657184,47.04995512962341,-0.07661381735710401,1739141207.6571877,47.04995512962341,3.114941289953236,1739141207.6571908,47.04995512962341,-0.8465749216590738,1739141207.657194,47.04995512962341,-0.1905121972681439,1739141207.657197,47.04995512962341,1.7818653467641763,1739141207.6572003,47.04995512962341,0.0,1739141207.6572037,47.04995512962341,0.2246215983265035,1739141207.6572073,47.04995512962341,3.2604669699136792,1739141207.6572106,47.04995512962341,1.5506026842476806 +1739141207.6749804,47.06995511054993,37.3338231159173,1739141207.6749845,47.06995511054993,-0.2321845013105035,1739141207.6749878,47.06995511054993,75.17737870406377,1739141207.674991,47.06995511054993,31.49795480435221,1739141207.674996,47.06995511054993,-0.07661381735710401,1739141207.6749995,47.06995511054993,3.114941289953236,1739141207.6750026,47.06995511054993,-0.8465749216590738,1739141207.6750045,47.06995511054993,-0.1905121972681439,1739141207.6750226,47.06995511054993,1.7818653467641763,1739141207.6750324,47.06995511054993,0.0,1739141207.6750355,47.06995511054993,0.23126266251649574,1739141207.675037,47.06995511054993,3.2604669699136792,1739141207.6750386,47.06995511054993,1.5506026842476806 +1739141207.695026,47.08995509147644,37.3338231159173,1739141207.6950285,47.08995509147644,-0.2321845013105035,1739141207.695031,47.08995509147644,75.17737870406377,1739141207.6950338,47.08995509147644,31.49795480435221,1739141207.6950352,47.08995509147644,-0.07661381735710401,1739141207.6950366,47.08995509147644,3.114941289953236,1739141207.6950378,47.08995509147644,-0.8465749216590738,1739141207.6950393,47.08995509147644,-0.1905121972681439,1739141207.6950402,47.08995509147644,1.7818653467641763,1739141207.695042,47.08995509147644,0.0,1739141207.6950433,47.08995509147644,0.23126266251649574,1739141207.6950443,47.08995509147644,3.2604669699136792,1739141207.6950457,47.08995509147644,1.5506026842476806 +1739141207.7150183,47.109955072402954,37.3338231159173,1739141207.7150207,47.109955072402954,-0.2321845013105035,1739141207.7150233,47.109955072402954,75.17737870406377,1739141207.715026,47.109955072402954,31.49795480435221,1739141207.7150276,47.109955072402954,-0.07661381735710401,1739141207.715029,47.109955072402954,3.114941289953236,1739141207.7150302,47.109955072402954,-0.8465749216590738,1739141207.7150316,47.109955072402954,-0.1905121972681439,1739141207.7150326,47.109955072402954,1.7818653467641763,1739141207.715034,47.109955072402954,0.0,1739141207.7150357,47.109955072402954,0.23126266251649574,1739141207.7150366,47.109955072402954,3.2604669699136792,1739141207.715038,47.109955072402954,1.5506026842476806 +1739141207.7353392,47.12995505332947,37.3338231159173,1739141207.7353432,47.12995505332947,-0.2321845013105035,1739141207.7353468,47.12995505332947,75.17737870406377,1739141207.7353494,47.12995505332947,31.49795480435221,1739141207.735351,47.12995505332947,-0.07661381735710401,1739141207.7353528,47.12995505332947,3.114941289953236,1739141207.7353544,47.12995505332947,-0.8465749216590738,1739141207.7353563,47.12995505332947,-0.1905121972681439,1739141207.7353578,47.12995505332947,1.7818653467641763,1739141207.7353592,47.12995505332947,0.0,1739141207.7353609,47.12995505332947,0.23126266251649574,1739141207.7353623,47.12995505332947,3.2604669699136792,1739141207.7353635,47.12995505332947,1.5506026842476806 +1739141207.755199,47.14995503425598,37.16311293646668,1739141207.755202,47.14995503425598,-0.2517550333403884,1739141207.7552052,47.14995503425598,75.27999554096844,1739141207.755208,47.14995503425598,31.319577010409613,1739141207.7552094,47.14995503425598,-0.07521544539382508,1739141207.7552114,47.14995503425598,3.1113907501940985,1739141207.7552128,47.14995503425598,-0.8090411319489949,1739141207.755214,47.14995503425598,-0.18157389930043324,1739141207.7552154,47.14995503425598,1.8088192405122068,1739141207.755217,47.14995503425598,0.0,1739141207.7552187,47.14995503425598,0.23450509136546305,1739141207.75522,47.14995503425598,3.250223786471403,1739141207.7552214,47.14995503425598,1.57585816365565 +1739141207.775083,47.169955015182495,37.16311293646668,1739141207.7750862,47.169955015182495,-0.2517550333403884,1739141207.7750895,47.169955015182495,75.27999554096844,1739141207.7750924,47.169955015182495,31.319577010409613,1739141207.775094,47.169955015182495,-0.07521544539382508,1739141207.7750962,47.169955015182495,3.1113907501940985,1739141207.7750976,47.169955015182495,-0.8090411319489949,1739141207.775099,47.169955015182495,-0.18157389930043324,1739141207.7751005,47.169955015182495,1.8088192405122068,1739141207.7751024,47.169955015182495,0.0,1739141207.775104,47.169955015182495,0.23296107685655687,1739141207.7751052,47.169955015182495,3.250223786471403,1739141207.7751067,47.169955015182495,1.57585816365565 +1739141207.7951863,47.18995499610901,37.16311293646668,1739141207.795189,47.18995499610901,-0.2517550333403884,1739141207.795192,47.18995499610901,75.27999554096844,1739141207.795195,47.18995499610901,31.319577010409613,1739141207.7951968,47.18995499610901,-0.07521544539382508,1739141207.7951984,47.18995499610901,3.1113907501940985,1739141207.7952003,47.18995499610901,-0.8090411319489949,1739141207.7952015,47.18995499610901,-0.18157389930043324,1739141207.7952027,47.18995499610901,1.8088192405122068,1739141207.7952046,47.18995499610901,0.0,1739141207.795206,47.18995499610901,0.23296107685655687,1739141207.7952075,47.18995499610901,3.250223786471403,1739141207.795209,47.18995499610901,1.57585816365565 +1739141207.8151639,47.20995497703552,37.16311293646668,1739141207.8151667,47.20995497703552,-0.2517550333403884,1739141207.8151696,47.20995497703552,75.27999554096844,1739141207.8151724,47.20995497703552,31.319577010409613,1739141207.8151736,47.20995497703552,-0.07521544539382508,1739141207.8151755,47.20995497703552,3.1113907501940985,1739141207.815177,47.20995497703552,-0.8090411319489949,1739141207.8151782,47.20995497703552,-0.18157389930043324,1739141207.8151796,47.20995497703552,1.8088192405122068,1739141207.815181,47.20995497703552,0.0,1739141207.8151827,47.20995497703552,0.23296107685655687,1739141207.8151839,47.20995497703552,3.250223786471403,1739141207.815185,47.20995497703552,1.57585816365565 +1739141207.8353844,47.229954957962036,37.16311293646668,1739141207.8353875,47.229954957962036,-0.2517550333403884,1739141207.835391,47.229954957962036,75.27999554096844,1739141207.8353941,47.229954957962036,31.319577010409613,1739141207.8353956,47.229954957962036,-0.07521544539382508,1739141207.8353975,47.229954957962036,3.1113907501940985,1739141207.8353987,47.229954957962036,-0.8090411319489949,1739141207.8354003,47.229954957962036,-0.18157389930043324,1739141207.8354018,47.229954957962036,1.8088192405122068,1739141207.8354034,47.229954957962036,0.0,1739141207.835405,47.229954957962036,0.23296107685655687,1739141207.8354065,47.229954957962036,3.250223786471403,1739141207.835408,47.229954957962036,1.57585816365565 +1739141207.8551726,47.24995493888855,37.16311293646668,1739141207.8551753,47.24995493888855,-0.2517550333403884,1739141207.8551784,47.24995493888855,75.27999554096844,1739141207.855181,47.24995493888855,31.319577010409613,1739141207.8551824,47.24995493888855,-0.07521544539382508,1739141207.8551843,47.24995493888855,3.1113907501940985,1739141207.8551857,47.24995493888855,-0.8090411319489949,1739141207.8551872,47.24995493888855,-0.18157389930043324,1739141207.8551884,47.24995493888855,1.8088192405122068,1739141207.85519,47.24995493888855,0.0,1739141207.8551915,47.24995493888855,0.23296107685655687,1739141207.8551931,47.24995493888855,3.250223786471403,1739141207.8551946,47.24995493888855,1.57585816365565 +1739141207.8754892,47.26995491981506,36.98943951085071,1739141207.8754923,47.26995491981506,-0.2699075902191401,1739141207.8754954,47.26995491981506,75.56529230775331,1739141207.8754985,47.26995491981506,30.957793470980608,1739141207.8754997,47.26995491981506,-0.07254799541974549,1739141207.8755016,47.26995491981506,3.1088836377094458,1739141207.875503,47.26995491981506,-0.7917739768580485,1739141207.8755047,47.26995491981506,-0.16679315221654772,1739141207.875506,47.26995491981506,1.8213557495869308,1739141207.8755076,47.26995491981506,0.0,1739141207.875509,47.26995491981506,0.20821364480877588,1739141207.8755105,47.26995491981506,3.2404627337084726,1739141207.875512,47.26995491981506,1.6013576074399594 +1739141207.8952146,47.28995490074158,36.98943951085071,1739141207.8952174,47.28995490074158,-0.2699075902191401,1739141207.8952205,47.28995490074158,75.56529230775331,1739141207.8952236,47.28995490074158,30.957793470980608,1739141207.8952248,47.28995490074158,-0.07254799541974549,1739141207.8952267,47.28995490074158,3.1088836377094458,1739141207.8952281,47.28995490074158,-0.7917739768580485,1739141207.8952293,47.28995490074158,-0.16679315221654772,1739141207.895231,47.28995490074158,1.8213557495869308,1739141207.8952324,47.28995490074158,0.0,1739141207.895234,47.28995490074158,0.21999814214697144,1739141207.8952355,47.28995490074158,3.2404627337084726,1739141207.895237,47.28995490074158,1.6013576074399594 +1739141207.9150987,47.30995488166809,36.98943951085071,1739141207.9151013,47.30995488166809,-0.2699075902191401,1739141207.9151042,47.30995488166809,75.56529230775331,1739141207.9151075,47.30995488166809,30.957793470980608,1739141207.9151092,47.30995488166809,-0.07254799541974549,1739141207.9151108,47.30995488166809,3.1088836377094458,1739141207.9151125,47.30995488166809,-0.7917739768580485,1739141207.9151137,47.30995488166809,-0.16679315221654772,1739141207.915115,47.30995488166809,1.8213557495869308,1739141207.9151168,47.30995488166809,0.0,1739141207.915118,47.30995488166809,0.21999814214697144,1739141207.9151194,47.30995488166809,3.2404627337084726,1739141207.9151206,47.30995488166809,1.6013576074399594 +1739141207.9353454,47.329954862594604,36.98943951085071,1739141207.9353487,47.329954862594604,-0.2699075902191401,1739141207.935352,47.329954862594604,75.56529230775331,1739141207.935355,47.329954862594604,30.957793470980608,1739141207.9353564,47.329954862594604,-0.07254799541974549,1739141207.9353585,47.329954862594604,3.1088836377094458,1739141207.93536,47.329954862594604,-0.7917739768580485,1739141207.9353616,47.329954862594604,-0.16679315221654772,1739141207.9353628,47.329954862594604,1.8213557495869308,1739141207.935365,47.329954862594604,0.0,1739141207.9353662,47.329954862594604,0.21999814214697144,1739141207.9353676,47.329954862594604,3.2404627337084726,1739141207.935369,47.329954862594604,1.6013576074399594 +1739141207.9552083,47.34995484352112,36.98943951085071,1739141207.955211,47.34995484352112,-0.2699075902191401,1739141207.955214,47.34995484352112,75.56529230775331,1739141207.9552166,47.34995484352112,30.957793470980608,1739141207.955218,47.34995484352112,-0.07254799541974549,1739141207.9552202,47.34995484352112,3.1088836377094458,1739141207.9552217,47.34995484352112,-0.7917739768580485,1739141207.9552233,47.34995484352112,-0.16679315221654772,1739141207.9552245,47.34995484352112,1.8213557495869308,1739141207.9552264,47.34995484352112,0.0,1739141207.9552276,47.34995484352112,0.21999814214697144,1739141207.955229,47.34995484352112,3.2404627337084726,1739141207.9552302,47.34995484352112,1.6013576074399594 +1739141207.9753218,47.36995482444763,36.812872829452495,1739141207.9753244,47.36995482444763,-0.2866498833489377,1739141207.9753277,47.36995482444763,75.67395440731298,1739141207.9753306,47.36995482444763,30.776891654738705,1739141207.9753318,47.36995482444763,-0.07096705710529223,1739141207.9753337,47.36995482444763,3.105874997584678,1739141207.9753354,47.36995482444763,-0.754423769085433,1739141207.9753368,47.36995482444763,-0.15867970630545136,1739141207.975338,47.36995482444763,1.8487712407751755,1739141207.97534,47.36995482444763,0.0,1739141207.9753413,47.36995482444763,0.22636165309591116,1739141207.9753425,47.36995482444763,3.231110144632493,1739141207.975344,47.36995482444763,1.625439832502023 +1739141207.9954185,47.389954805374146,36.812872829452495,1739141207.9954214,47.389954805374146,-0.2866498833489377,1739141207.995425,47.389954805374146,75.67395440731298,1739141207.9954283,47.389954805374146,30.776891654738705,1739141207.9954305,47.389954805374146,-0.07096705710529223,1739141207.9954324,47.389954805374146,3.105874997584678,1739141207.9954343,47.389954805374146,-0.754423769085433,1739141207.9954357,47.389954805374146,-0.15867970630545136,1739141207.9954371,47.389954805374146,1.8487712407751755,1739141207.995439,47.389954805374146,0.0,1739141207.9954407,47.389954805374146,0.22333140827315257,1739141207.995442,47.389954805374146,3.231110144632493,1739141207.9954433,47.389954805374146,1.625439832502023 +1739141208.0155125,47.40995478630066,36.812872829452495,1739141208.0155158,47.40995478630066,-0.2866498833489377,1739141208.0155191,47.40995478630066,75.67395440731298,1739141208.0155225,47.40995478630066,30.776891654738705,1739141208.0155241,47.40995478630066,-0.07096705710529223,1739141208.0155258,47.40995478630066,3.105874997584678,1739141208.0155277,47.40995478630066,-0.754423769085433,1739141208.0155292,47.40995478630066,-0.15867970630545136,1739141208.0155308,47.40995478630066,1.8487712407751755,1739141208.0155325,47.40995478630066,0.0,1739141208.0155342,47.40995478630066,0.22333140827315257,1739141208.0155356,47.40995478630066,3.231110144632493,1739141208.0155373,47.40995478630066,1.625439832502023 +1739141208.035665,47.42995476722717,36.812872829452495,1739141208.035668,47.42995476722717,-0.2866498833489377,1739141208.0356712,47.42995476722717,75.67395440731298,1739141208.0356746,47.42995476722717,30.776891654738705,1739141208.0356762,47.42995476722717,-0.07096705710529223,1739141208.0356781,47.42995476722717,3.105874997584678,1739141208.0356798,47.42995476722717,-0.754423769085433,1739141208.0356812,47.42995476722717,-0.15867970630545136,1739141208.0356827,47.42995476722717,1.8487712407751755,1739141208.0356843,47.42995476722717,0.0,1739141208.0356863,47.42995476722717,0.22333140827315257,1739141208.0356877,47.42995476722717,3.231110144632493,1739141208.0356889,47.42995476722717,1.625439832502023 +1739141208.0578246,47.44995474815369,36.812872829452495,1739141208.0578294,47.44995474815369,-0.2866498833489377,1739141208.0578349,47.44995474815369,75.67395440731298,1739141208.0578408,47.44995474815369,30.776891654738705,1739141208.0578444,47.44995474815369,-0.07096705710529223,1739141208.057849,47.44995474815369,3.105874997584678,1739141208.0578532,47.44995474815369,-0.754423769085433,1739141208.057857,47.44995474815369,-0.15867970630545136,1739141208.0578609,47.44995474815369,1.8487712407751755,1739141208.0578654,47.44995474815369,0.0,1739141208.0578692,47.44995474815369,0.22333140827315257,1739141208.0578737,47.44995474815369,3.231110144632493,1739141208.0578775,47.44995474815369,1.625439832502023 +1739141208.0775988,47.4699547290802,36.812872829452495,1739141208.0776029,47.4699547290802,-0.2866498833489377,1739141208.077608,47.4699547290802,75.67395440731298,1739141208.0776148,47.4699547290802,30.776891654738705,1739141208.0776181,47.4699547290802,-0.07096705710529223,1739141208.0776224,47.4699547290802,3.105874997584678,1739141208.0776267,47.4699547290802,-0.754423769085433,1739141208.0776305,47.4699547290802,-0.15867970630545136,1739141208.0776343,47.4699547290802,1.8487712407751755,1739141208.0776384,47.4699547290802,0.0,1739141208.0776424,47.4699547290802,0.22333140827315257,1739141208.0776463,47.4699547290802,3.231110144632493,1739141208.07765,47.4699547290802,1.625439832502023 +1739141208.0976715,47.489954710006714,36.633499379736634,1739141208.0976758,47.489954710006714,-0.30202577831825916,1739141208.0976815,47.489954710006714,75.97025519372046,1739141208.0976875,47.489954710006714,30.406948175376982,1739141208.097691,47.489954710006714,-0.06711162220152572,1739141208.0976956,47.489954710006714,3.1038827262931954,1739141208.0976996,47.489954710006714,-0.736660379567319,1739141208.0977037,47.489954710006714,-0.14560439203955788,1739141208.0977075,47.489954710006714,1.8619541975835043,1739141208.0977116,47.489954710006714,0.0,1739141208.0977159,47.489954710006714,0.2016203711014114,1739141208.09772,47.489954710006714,3.22238530910261,1739141208.0977237,47.489954710006714,1.6499952321881128 +1739141208.1177704,47.50995469093323,36.633499379736634,1739141208.1177752,47.50995469093323,-0.30202577831825916,1739141208.117781,47.50995469093323,75.97025519372046,1739141208.1177871,47.50995469093323,30.406948175376982,1739141208.1177907,47.50995469093323,-0.06711162220152572,1739141208.117795,47.50995469093323,3.1038827262931954,1739141208.1177993,47.50995469093323,-0.736660379567319,1739141208.1178033,47.50995469093323,-0.14560439203955788,1739141208.1178071,47.50995469093323,1.8619541975835043,1739141208.1178117,47.50995469093323,0.0,1739141208.1178155,47.50995469093323,0.2119589653953915,1739141208.1178195,47.50995469093323,3.22238530910261,1739141208.1178236,47.50995469093323,1.6499952321881128 +1739141208.137804,47.52995467185974,36.633499379736634,1739141208.1378086,47.52995467185974,-0.30202577831825916,1739141208.1378143,47.52995467185974,75.97025519372046,1739141208.1378205,47.52995467185974,30.406948175376982,1739141208.137824,47.52995467185974,-0.06711162220152572,1739141208.1378284,47.52995467185974,3.1038827262931954,1739141208.1378322,47.52995467185974,-0.736660379567319,1739141208.1378362,47.52995467185974,-0.14560439203955788,1739141208.13784,47.52995467185974,1.8619541975835043,1739141208.1378443,47.52995467185974,0.0,1739141208.1378484,47.52995467185974,0.2119589653953915,1739141208.1378522,47.52995467185974,3.22238530910261,1739141208.137856,47.52995467185974,1.6499952321881128 +1739141208.1553185,47.549954652786255,36.633499379736634,1739141208.1553216,47.549954652786255,-0.30202577831825916,1739141208.1553252,47.549954652786255,75.97025519372046,1739141208.1553283,47.549954652786255,30.406948175376982,1739141208.1553297,47.549954652786255,-0.06711162220152572,1739141208.1553316,47.549954652786255,3.1038827262931954,1739141208.1553333,47.549954652786255,-0.736660379567319,1739141208.155335,47.549954652786255,-0.14560439203955788,1739141208.1553364,47.549954652786255,1.8619541975835043,1739141208.1553383,47.549954652786255,0.0,1739141208.1553397,47.549954652786255,0.2119589653953915,1739141208.1553414,47.549954652786255,3.22238530910261,1739141208.1553428,47.549954652786255,1.6499952321881128 +1739141208.1754076,47.56995463371277,36.633499379736634,1739141208.1754105,47.56995463371277,-0.30202577831825916,1739141208.1754143,47.56995463371277,75.97025519372046,1739141208.1754174,47.56995463371277,30.406948175376982,1739141208.175419,47.56995463371277,-0.06711162220152572,1739141208.1754212,47.56995463371277,3.1038827262931954,1739141208.1754227,47.56995463371277,-0.736660379567319,1739141208.1754243,47.56995463371277,-0.14560439203955788,1739141208.1754255,47.56995463371277,1.8619541975835043,1739141208.1754277,47.56995463371277,0.0,1739141208.175429,47.56995463371277,0.2119589653953915,1739141208.1754308,47.56995463371277,3.22238530910261,1739141208.175432,47.56995463371277,1.6499952321881128 +1739141208.1953294,47.58995461463928,36.45138617165204,1739141208.1953328,47.58995461463928,-0.31606573624847556,1739141208.195336,47.58995461463928,76.3220719825978,1739141208.1953394,47.58995461463928,29.985837503483623,1739141208.195341,47.58995461463928,-0.06282549215341436,1739141208.195343,47.58995461463928,3.102445030204031,1739141208.1953447,47.58995461463928,-0.720858600743852,1739141208.195346,47.58995461463928,-0.13214592648092835,1739141208.1953475,47.58995461463928,1.873760345268276,1739141208.1953492,47.58995461463928,0.0,1739141208.195351,47.58995461463928,0.19038629631707735,1739141208.1953523,47.58995461463928,3.21408361383655,1739141208.1953535,47.58995461463928,1.673101344258432 +1739141208.2154362,47.609954595565796,36.45138617165204,1739141208.2154393,47.609954595565796,-0.31606573624847556,1739141208.215443,47.609954595565796,76.3220719825978,1739141208.2154462,47.609954595565796,29.985837503483623,1739141208.215448,47.609954595565796,-0.06282549215341436,1739141208.2154496,47.609954595565796,3.102445030204031,1739141208.2154512,47.609954595565796,-0.720858600743852,1739141208.2154527,47.609954595565796,-0.13214592648092835,1739141208.2154539,47.609954595565796,1.873760345268276,1739141208.2154558,47.609954595565796,0.0,1739141208.2154574,47.609954595565796,0.20065900100984413,1739141208.215459,47.609954595565796,3.21408361383655,1739141208.2154603,47.609954595565796,1.673101344258432 +1739141208.2350967,47.62995457649231,36.45138617165204,1739141208.235099,47.62995457649231,-0.31606573624847556,1739141208.2351024,47.62995457649231,76.3220719825978,1739141208.2351055,47.62995457649231,29.985837503483623,1739141208.2351072,47.62995457649231,-0.06282549215341436,1739141208.2351089,47.62995457649231,3.102445030204031,1739141208.2351103,47.62995457649231,-0.720858600743852,1739141208.235112,47.62995457649231,-0.13214592648092835,1739141208.2351134,47.62995457649231,1.873760345268276,1739141208.2351153,47.62995457649231,0.0,1739141208.235117,47.62995457649231,0.20065900100984413,1739141208.2351184,47.62995457649231,3.21408361383655,1739141208.2351198,47.62995457649231,1.673101344258432 +1739141208.2552166,47.64995455741882,36.45138617165204,1739141208.2552202,47.64995455741882,-0.31606573624847556,1739141208.2552238,47.64995455741882,76.3220719825978,1739141208.2552269,47.64995455741882,29.985837503483623,1739141208.2552288,47.64995455741882,-0.06282549215341436,1739141208.2552304,47.64995455741882,3.102445030204031,1739141208.2552323,47.64995455741882,-0.720858600743852,1739141208.2552338,47.64995455741882,-0.13214592648092835,1739141208.255235,47.64995455741882,1.873760345268276,1739141208.2552369,47.64995455741882,0.0,1739141208.2552383,47.64995455741882,0.20065900100984413,1739141208.2552402,47.64995455741882,3.21408361383655,1739141208.2552416,47.64995455741882,1.673101344258432 +1739141208.2769597,47.66995453834534,36.45138617165204,1739141208.2769647,47.66995453834534,-0.31606573624847556,1739141208.2769701,47.66995453834534,76.3220719825978,1739141208.2769763,47.66995453834534,29.985837503483623,1739141208.2769797,47.66995453834534,-0.06282549215341436,1739141208.276984,47.66995453834534,3.102445030204031,1739141208.2769883,47.66995453834534,-0.720858600743852,1739141208.276992,47.66995453834534,-0.13214592648092835,1739141208.276996,47.66995453834534,1.873760345268276,1739141208.2770002,47.66995453834534,0.0,1739141208.2770042,47.66995453834534,0.20065900100984413,1739141208.277008,47.66995453834534,3.21408361383655,1739141208.2770119,47.66995453834534,1.673101344258432 +1739141208.297768,47.68995451927185,36.45138617165204,1739141208.2977722,47.68995451927185,-0.31606573624847556,1739141208.2977777,47.68995451927185,76.3220719825978,1739141208.2977839,47.68995451927185,29.985837503483623,1739141208.2977872,47.68995451927185,-0.06282549215341436,1739141208.2977917,47.68995451927185,3.102445030204031,1739141208.2977955,47.68995451927185,-0.720858600743852,1739141208.2977993,47.68995451927185,-0.13214592648092835,1739141208.2978032,47.68995451927185,1.873760345268276,1739141208.2978077,47.68995451927185,0.0,1739141208.2978117,47.68995451927185,0.20065900100984413,1739141208.2978156,47.68995451927185,3.21408361383655,1739141208.2978196,47.68995451927185,1.673101344258432 +1739141208.3177474,47.709954500198364,36.26671217275545,1739141208.3177521,47.709954500198364,-0.32882026541231113,1739141208.3177576,47.709954500198364,76.3259628911038,1739141208.3177638,47.709954500198364,29.916924966445322,1739141208.3177671,47.709954500198364,-0.062282873751537966,1739141208.3177714,47.709954500198364,3.0996414818627516,1739141208.3177752,47.709954500198364,-0.6775705188187239,1739141208.3177795,47.709954500198364,-0.12875558238944573,1739141208.3177834,47.709954500198364,1.9064874629566742,1739141208.3177874,47.709954500198364,0.0,1739141208.3177915,47.709954500198364,0.22175929403864192,1739141208.3177953,47.709954500198364,3.20645820341377,1739141208.3177993,47.709954500198364,1.694775932522471 +1739141208.337691,47.72995448112488,36.26671217275545,1739141208.337696,47.72995448112488,-0.32882026541231113,1739141208.3377016,47.72995448112488,76.3259628911038,1739141208.3377078,47.72995448112488,29.916924966445322,1739141208.337711,47.72995448112488,-0.062282873751537966,1739141208.3377156,47.72995448112488,3.0996414818627516,1739141208.3377194,47.72995448112488,-0.6775705188187239,1739141208.3377237,47.72995448112488,-0.12875558238944573,1739141208.3377275,47.72995448112488,1.9064874629566742,1739141208.3377316,47.72995448112488,0.0,1739141208.3377357,47.72995448112488,0.2117115304342032,1739141208.3377397,47.72995448112488,3.20645820341377,1739141208.3377435,47.72995448112488,1.694775932522471 +1739141208.3573596,47.74995446205139,36.26671217275545,1739141208.3573642,47.74995446205139,-0.32882026541231113,1739141208.3573697,47.74995446205139,76.3259628911038,1739141208.3573759,47.74995446205139,29.916924966445322,1739141208.357379,47.74995446205139,-0.062282873751537966,1739141208.3573837,47.74995446205139,3.0996414818627516,1739141208.3573875,47.74995446205139,-0.6775705188187239,1739141208.3573914,47.74995446205139,-0.12875558238944573,1739141208.3573952,47.74995446205139,1.9064874629566742,1739141208.3573992,47.74995446205139,0.0,1739141208.3574033,47.74995446205139,0.2117115304342032,1739141208.3574076,47.74995446205139,3.20645820341377,1739141208.3574116,47.74995446205139,1.694775932522471 +1739141208.3778787,47.769954442977905,36.26671217275545,1739141208.3778834,47.769954442977905,-0.32882026541231113,1739141208.377889,47.769954442977905,76.3259628911038,1739141208.3778954,47.769954442977905,29.916924966445322,1739141208.3778987,47.769954442977905,-0.062282873751537966,1739141208.3779032,47.769954442977905,3.0996414818627516,1739141208.3779073,47.769954442977905,-0.6775705188187239,1739141208.377911,47.769954442977905,-0.12875558238944573,1739141208.377915,47.769954442977905,1.9064874629566742,1739141208.3779192,47.769954442977905,0.0,1739141208.3779233,47.769954442977905,0.2117115304342032,1739141208.377927,47.769954442977905,3.20645820341377,1739141208.3779314,47.769954442977905,1.694775932522471 +1739141208.3979857,47.78995442390442,36.26671217275545,1739141208.3979905,47.78995442390442,-0.32882026541231113,1739141208.397996,47.78995442390442,76.3259628911038,1739141208.3980021,47.78995442390442,29.916924966445322,1739141208.3980057,47.78995442390442,-0.062282873751537966,1739141208.39801,47.78995442390442,3.0996414818627516,1739141208.3980143,47.78995442390442,-0.6775705188187239,1739141208.3980184,47.78995442390442,-0.12875558238944573,1739141208.3980222,47.78995442390442,1.9064874629566742,1739141208.3980262,47.78995442390442,0.0,1739141208.39803,47.78995442390442,0.2117115304342032,1739141208.3980343,47.78995442390442,3.20645820341377,1739141208.3980384,47.78995442390442,1.694775932522471 +1739141208.4154403,47.80995440483093,36.07947640784794,1739141208.4154432,47.80995440483093,-0.3403533863877728,1739141208.4154465,47.80995440483093,76.32990637528783,1739141208.4154496,47.80995440483093,29.84319599258474,1739141208.415451,47.80995440483093,-0.061702330650273536,1739141208.415453,47.80995440483093,3.0969401016836646,1739141208.4154544,47.80995440483093,-0.6368016678919267,1739141208.415456,47.80995440483093,-0.12542808179092144,1739141208.4154572,47.80995440483093,1.9378324695616964,1739141208.4154592,47.80995440483093,0.0,1739141208.4154608,47.80995440483093,0.2271416021685906,1739141208.4154623,47.80995440483093,3.1991284944053757,1739141208.4154637,47.80995440483093,1.7180385242704326 +1739141208.43532,47.829954385757446,36.07947640784794,1739141208.4353235,47.829954385757446,-0.3403533863877728,1739141208.4353268,47.829954385757446,76.32990637528783,1739141208.4353297,47.829954385757446,29.84319599258474,1739141208.4353316,47.829954385757446,-0.061702330650273536,1739141208.4353335,47.829954385757446,3.0969401016836646,1739141208.435335,47.829954385757446,-0.6368016678919267,1739141208.4353366,47.829954385757446,-0.12542808179092144,1739141208.435338,47.829954385757446,1.9378324695616964,1739141208.43534,47.829954385757446,0.0,1739141208.4353418,47.829954385757446,0.21979394529126384,1739141208.4353433,47.829954385757446,3.1991284944053757,1739141208.4353452,47.829954385757446,1.7180385242704326 +1739141208.4553962,47.84995436668396,36.07947640784794,1739141208.4553998,47.84995436668396,-0.3403533863877728,1739141208.4554036,47.84995436668396,76.32990637528783,1739141208.455407,47.84995436668396,29.84319599258474,1739141208.4554086,47.84995436668396,-0.061702330650273536,1739141208.455411,47.84995436668396,3.0969401016836646,1739141208.4554124,47.84995436668396,-0.6368016678919267,1739141208.4554143,47.84995436668396,-0.12542808179092144,1739141208.4554157,47.84995436668396,1.9378324695616964,1739141208.4554179,47.84995436668396,0.0,1739141208.4554195,47.84995436668396,0.21979394529126384,1739141208.4554214,47.84995436668396,3.1991284944053757,1739141208.4554229,47.84995436668396,1.7180385242704326 +1739141208.4779546,47.869954347610474,36.07947640784794,1739141208.4779594,47.869954347610474,-0.3403533863877728,1739141208.4779654,47.869954347610474,76.32990637528783,1739141208.4779723,47.869954347610474,29.84319599258474,1739141208.4779758,47.869954347610474,-0.061702330650273536,1739141208.4779806,47.869954347610474,3.0969401016836646,1739141208.477985,47.869954347610474,-0.6368016678919267,1739141208.4779894,47.869954347610474,-0.12542808179092144,1739141208.4779937,47.869954347610474,1.9378324695616964,1739141208.4779983,47.869954347610474,0.0,1739141208.4780028,47.869954347610474,0.21979394529126384,1739141208.4780073,47.869954347610474,3.1991284944053757,1739141208.4780116,47.869954347610474,1.7180385242704326 +1739141208.49824,47.88995432853699,36.07947640784794,1739141208.498245,47.88995432853699,-0.3403533863877728,1739141208.4982512,47.88995432853699,76.32990637528783,1739141208.498258,47.88995432853699,29.84319599258474,1739141208.498262,47.88995432853699,-0.061702330650273536,1739141208.498267,47.88995432853699,3.0969401016836646,1739141208.4982712,47.88995432853699,-0.6368016678919267,1739141208.4982755,47.88995432853699,-0.12542808179092144,1739141208.49828,47.88995432853699,1.9378324695616964,1739141208.4982846,47.88995432853699,0.0,1739141208.4982889,47.88995432853699,0.21979394529126384,1739141208.4982932,47.88995432853699,3.1991284944053757,1739141208.4982977,47.88995432853699,1.7180385242704326 +1739141208.5183043,47.9099543094635,36.07947640784794,1739141208.518309,47.9099543094635,-0.3403533863877728,1739141208.5183153,47.9099543094635,76.32990637528783,1739141208.5183222,47.9099543094635,29.84319599258474,1739141208.518326,47.9099543094635,-0.061702330650273536,1739141208.5183308,47.9099543094635,3.0969401016836646,1739141208.5183353,47.9099543094635,-0.6368016678919267,1739141208.5183396,47.9099543094635,-0.12542808179092144,1739141208.5183442,47.9099543094635,1.9378324695616964,1739141208.5183485,47.9099543094635,0.0,1739141208.5183532,47.9099543094635,0.21979394529126384,1739141208.5183578,47.9099543094635,3.1991284944053757,1739141208.518362,47.9099543094635,1.7180385242704326 +1739141208.5380878,47.929954290390015,35.88956996623156,1739141208.5380929,47.929954290390015,-0.35066580556882077,1739141208.538099,47.929954290390015,76.6280707600722,1739141208.5381062,47.929954290390015,29.4729080828559,1739141208.53811,47.929954290390015,-0.058,1739141208.5381148,47.929954290390015,3.0960139524301624,1739141208.538119,47.929954290390015,-0.6152826753861241,1739141208.5381236,47.929954290390015,-0.11447330478726474,1739141208.538128,47.929954290390015,1.95458454464233,1739141208.5381324,47.929954290390015,0.0,1739141208.5381374,47.929954290390015,0.2058638342873907,1739141208.5381415,47.929954290390015,3.191949742896657,1739141208.5381458,47.929954290390015,1.742087320848951 +1739141208.558274,47.94995427131653,35.88956996623156,1739141208.5582793,47.94995427131653,-0.35066580556882077,1739141208.5582855,47.94995427131653,76.6280707600722,1739141208.5582924,47.94995427131653,29.4729080828559,1739141208.5582967,47.94995427131653,-0.058,1739141208.5583014,47.94995427131653,3.0960139524301624,1739141208.558306,47.94995427131653,-0.6152826753861241,1739141208.5583105,47.94995427131653,-0.11447330478726474,1739141208.5583148,47.94995427131653,1.95458454464233,1739141208.558319,47.94995427131653,0.0,1739141208.5583236,47.94995427131653,0.2124972237933791,1739141208.5583284,47.94995427131653,3.191949742896657,1739141208.5583327,47.94995427131653,1.742087320848951 +1739141208.5783842,47.96995425224304,35.88956996623156,1739141208.5783887,47.96995425224304,-0.35066580556882077,1739141208.5783947,47.96995425224304,76.6280707600722,1739141208.5784016,47.96995425224304,29.4729080828559,1739141208.5784054,47.96995425224304,-0.058,1739141208.5784101,47.96995425224304,3.0960139524301624,1739141208.5784147,47.96995425224304,-0.6152826753861241,1739141208.578419,47.96995425224304,-0.11447330478726474,1739141208.5784233,47.96995425224304,1.95458454464233,1739141208.5784278,47.96995425224304,0.0,1739141208.5784326,47.96995425224304,0.2124972237933791,1739141208.5784369,47.96995425224304,3.191949742896657,1739141208.5784414,47.96995425224304,1.742087320848951 +1739141208.5958169,47.989954233169556,35.88956996623156,1739141208.5958211,47.989954233169556,-0.35066580556882077,1739141208.5958252,47.989954233169556,76.6280707600722,1739141208.595829,47.989954233169556,29.4729080828559,1739141208.5958314,47.989954233169556,-0.058,1739141208.5958335,47.989954233169556,3.0960139524301624,1739141208.5958354,47.989954233169556,-0.6152826753861241,1739141208.595837,47.989954233169556,-0.11447330478726474,1739141208.5958393,47.989954233169556,1.95458454464233,1739141208.5958412,47.989954233169556,0.0,1739141208.595843,47.989954233169556,0.2124972237933791,1739141208.5958447,47.989954233169556,3.191949742896657,1739141208.5958464,47.989954233169556,1.742087320848951 +1739141208.615594,48.00995421409607,35.88956996623156,1739141208.6155977,48.00995421409607,-0.35066580556882077,1739141208.6156025,48.00995421409607,76.6280707600722,1739141208.6156063,48.00995421409607,29.4729080828559,1739141208.615608,48.00995421409607,-0.058,1739141208.6156104,48.00995421409607,3.0960139524301624,1739141208.6156123,48.00995421409607,-0.6152826753861241,1739141208.615614,48.00995421409607,-0.11447330478726474,1739141208.6156156,48.00995421409607,1.95458454464233,1739141208.6156175,48.00995421409607,0.0,1739141208.6156194,48.00995421409607,0.2124972237933791,1739141208.6156209,48.00995421409607,3.191949742896657,1739141208.6156228,48.00995421409607,1.742087320848951 +1739141208.6361754,48.02995419502258,35.696995570811744,1739141208.6361785,48.02995419502258,-0.3597596835539667,1739141208.636182,48.02995419502258,76.74812551796379,1739141208.6361852,48.02995419502258,29.28326770300419,1739141208.6361868,48.02995419502258,-0.057114010076947865,1739141208.6361895,48.02995419502258,3.0944404586768246,1739141208.6361911,48.02995419502258,-0.5814286146680195,1739141208.6361928,48.02995419502258,-0.1082634934077206,1739141208.6361942,48.02995419502258,1.9812328174134308,1739141208.6361964,48.02995419502258,0.0,1739141208.636198,48.02995419502258,0.21908777457989836,1739141208.6361997,48.02995419502258,3.1851176836976776,1739141208.6362011,48.02995419502258,1.76528340191867 +1739141208.6555312,48.0499541759491,35.696995570811744,1739141208.6555352,48.0499541759491,-0.3597596835539667,1739141208.655539,48.0499541759491,76.74812551796379,1739141208.6555426,48.0499541759491,29.28326770300419,1739141208.6555443,48.0499541759491,-0.057114010076947865,1739141208.6555467,48.0499541759491,3.0944404586768246,1739141208.6555483,48.0499541759491,-0.5814286146680195,1739141208.65555,48.0499541759491,-0.1082634934077206,1739141208.6555514,48.0499541759491,1.9812328174134308,1739141208.6555536,48.0499541759491,0.0,1739141208.6555552,48.0499541759491,0.21594941549476077,1739141208.6555572,48.0499541759491,3.1851176836976776,1739141208.6555588,48.0499541759491,1.76528340191867 +1739141208.6758077,48.06995415687561,35.696995570811744,1739141208.675811,48.06995415687561,-0.3597596835539667,1739141208.6758146,48.06995415687561,76.74812551796379,1739141208.6758182,48.06995415687561,29.28326770300419,1739141208.67582,48.06995415687561,-0.057114010076947865,1739141208.675822,48.06995415687561,3.0944404586768246,1739141208.675824,48.06995415687561,-0.5814286146680195,1739141208.6758254,48.06995415687561,-0.1082634934077206,1739141208.6758273,48.06995415687561,1.9812328174134308,1739141208.675829,48.06995415687561,0.0,1739141208.6758308,48.06995415687561,0.21594941549476077,1739141208.6758325,48.06995415687561,3.1851176836976776,1739141208.6758342,48.06995415687561,1.76528340191867 +1739141208.6960132,48.089954137802124,35.696995570811744,1739141208.6960173,48.089954137802124,-0.3597596835539667,1739141208.6960216,48.089954137802124,76.74812551796379,1739141208.6960256,48.089954137802124,29.28326770300419,1739141208.6960273,48.089954137802124,-0.057114010076947865,1739141208.69603,48.089954137802124,3.0944404586768246,1739141208.6960318,48.089954137802124,-0.5814286146680195,1739141208.6960332,48.089954137802124,-0.1082634934077206,1739141208.6960351,48.089954137802124,1.9812328174134308,1739141208.696037,48.089954137802124,0.0,1739141208.696039,48.089954137802124,0.21594941549476077,1739141208.6960406,48.089954137802124,3.1851176836976776,1739141208.6960423,48.089954137802124,1.76528340191867 +1739141208.715743,48.10995411872864,35.696995570811744,1739141208.7157466,48.10995411872864,-0.3597596835539667,1739141208.7157507,48.10995411872864,76.74812551796379,1739141208.7157545,48.10995411872864,29.28326770300419,1739141208.715756,48.10995411872864,-0.057114010076947865,1739141208.7157583,48.10995411872864,3.0944404586768246,1739141208.7157602,48.10995411872864,-0.5814286146680195,1739141208.7157617,48.10995411872864,-0.1082634934077206,1739141208.7157636,48.10995411872864,1.9812328174134308,1739141208.7157655,48.10995411872864,0.0,1739141208.7157676,48.10995411872864,0.21594941549476077,1739141208.715769,48.10995411872864,3.1851176836976776,1739141208.7157707,48.10995411872864,1.76528340191867 +1739141208.7362175,48.12995409965515,35.696995570811744,1739141208.736221,48.12995409965515,-0.3597596835539667,1739141208.7362251,48.12995409965515,76.74812551796379,1739141208.7362287,48.12995409965515,29.28326770300419,1739141208.7362301,48.12995409965515,-0.057114010076947865,1739141208.7362325,48.12995409965515,3.0944404586768246,1739141208.736234,48.12995409965515,-0.5814286146680195,1739141208.7362359,48.12995409965515,-0.1082634934077206,1739141208.7362373,48.12995409965515,1.9812328174134308,1739141208.7362394,48.12995409965515,0.0,1739141208.736241,48.12995409965515,0.21594941549476077,1739141208.7362428,48.12995409965515,3.1851176836976776,1739141208.7362442,48.12995409965515,1.76528340191867 +1739141208.755865,48.149954080581665,35.5017933858543,1739141208.7558687,48.149954080581665,-0.36768327206935414,1739141208.7558727,48.149954080581665,76.88318977844924,1739141208.755876,48.149954080581665,29.077318661642888,1739141208.755878,48.149954080581665,-0.055439652618847805,1739141208.7558799,48.149954080581665,3.0930286662154454,1739141208.7558823,48.149954080581665,-0.5502771668424298,1739141208.755884,48.149954080581665,-0.10211158882819188,1739141208.7558856,48.149954080581665,2.0060745756346514,1739141208.7558875,48.149954080581665,0.0,1739141208.7558894,48.149954080581665,0.218261730063509,1739141208.7558908,48.149954080581665,3.17868564283609,1739141208.7558925,48.149954080581665,1.7889139482967857 +1739141208.7762296,48.16995406150818,35.5017933858543,1739141208.776233,48.16995406150818,-0.36768327206935414,1739141208.7762363,48.16995406150818,76.88318977844924,1739141208.7762396,48.16995406150818,29.077318661642888,1739141208.7762413,48.16995406150818,-0.055439652618847805,1739141208.7762437,48.16995406150818,3.0930286662154454,1739141208.7762456,48.16995406150818,-0.5502771668424298,1739141208.776247,48.16995406150818,-0.10211158882819188,1739141208.7762487,48.16995406150818,2.0060745756346514,1739141208.7762506,48.16995406150818,0.0,1739141208.7762527,48.16995406150818,0.21716062733786567,1739141208.7762542,48.16995406150818,3.17868564283609,1739141208.7762558,48.16995406150818,1.7889139482967857 +1739141208.795608,48.18995404243469,35.5017933858543,1739141208.7956114,48.18995404243469,-0.36768327206935414,1739141208.7956152,48.18995404243469,76.88318977844924,1739141208.7956188,48.18995404243469,29.077318661642888,1739141208.7956207,48.18995404243469,-0.055439652618847805,1739141208.7956226,48.18995404243469,3.0930286662154454,1739141208.7956245,48.18995404243469,-0.5502771668424298,1739141208.7956262,48.18995404243469,-0.10211158882819188,1739141208.7956278,48.18995404243469,2.0060745756346514,1739141208.79563,48.18995404243469,0.0,1739141208.795632,48.18995404243469,0.21716062733786567,1739141208.795634,48.18995404243469,3.17868564283609,1739141208.7956355,48.18995404243469,1.7889139482967857 +1739141208.8158,48.209954023361206,35.5017933858543,1739141208.8158038,48.209954023361206,-0.36768327206935414,1739141208.8158076,48.209954023361206,76.88318977844924,1739141208.8158112,48.209954023361206,29.077318661642888,1739141208.8158126,48.209954023361206,-0.055439652618847805,1739141208.815815,48.209954023361206,3.0930286662154454,1739141208.8158166,48.209954023361206,-0.5502771668424298,1739141208.8158183,48.209954023361206,-0.10211158882819188,1739141208.8158197,48.209954023361206,2.0060745756346514,1739141208.8158221,48.209954023361206,0.0,1739141208.8158236,48.209954023361206,0.21716062733786567,1739141208.8158257,48.209954023361206,3.17868564283609,1739141208.8158274,48.209954023361206,1.7889139482967857 +1739141208.836018,48.22995400428772,35.5017933858543,1739141208.8360217,48.22995400428772,-0.36768327206935414,1739141208.8360257,48.22995400428772,76.88318977844924,1739141208.8360288,48.22995400428772,29.077318661642888,1739141208.8360307,48.22995400428772,-0.055439652618847805,1739141208.836033,48.22995400428772,3.0930286662154454,1739141208.8360348,48.22995400428772,-0.5502771668424298,1739141208.8360364,48.22995400428772,-0.10211158882819188,1739141208.8360379,48.22995400428772,2.0060745756346514,1739141208.83604,48.22995400428772,0.0,1739141208.8360417,48.22995400428772,0.21716062733786567,1739141208.8360434,48.22995400428772,3.17868564283609,1739141208.8360453,48.22995400428772,1.7889139482967857 +1739141208.8557742,48.24995398521423,35.30394236041365,1739141208.8557777,48.24995398521423,-0.3744602974587323,1739141208.8557816,48.24995398521423,77.19278753959715,1739141208.8557851,48.24995398521423,28.696505510349915,1739141208.855787,48.24995398521423,-0.05220090179786255,1739141208.8557894,48.24995398521423,3.092859045633695,1739141208.855791,48.24995398521423,-0.5262071922290451,1739141208.8557925,48.24995398521423,-0.09231728015282545,1739141208.8557944,48.24995398521423,2.025482320139728,1739141208.8557968,48.24995398521423,0.0,1739141208.8557982,48.24995398521423,0.20888412305029055,1739141208.8558002,48.24995398521423,3.172487243321482,1739141208.8558016,48.24995398521423,1.8126570026027455 +1739141208.8761804,48.26995396614075,35.30394236041365,1739141208.8761835,48.26995396614075,-0.3744602974587323,1739141208.876187,48.26995396614075,77.19278753959715,1739141208.8761907,48.26995396614075,28.696505510349915,1739141208.8761923,48.26995396614075,-0.05220090179786255,1739141208.8761945,48.26995396614075,3.092859045633695,1739141208.8761964,48.26995396614075,-0.5262071922290451,1739141208.8761978,48.26995396614075,-0.09231728015282545,1739141208.8761995,48.26995396614075,2.025482320139728,1739141208.8762014,48.26995396614075,0.0,1739141208.8762033,48.26995396614075,0.2128253175369823,1739141208.8762047,48.26995396614075,3.172487243321482,1739141208.8762064,48.26995396614075,1.8126570026027455 +1739141208.8957808,48.28995394706726,35.30394236041365,1739141208.8957844,48.28995394706726,-0.3744602974587323,1739141208.8957884,48.28995394706726,77.19278753959715,1739141208.8957918,48.28995394706726,28.696505510349915,1739141208.8957937,48.28995394706726,-0.05220090179786255,1739141208.8957963,48.28995394706726,3.092859045633695,1739141208.895798,48.28995394706726,-0.5262071922290451,1739141208.8957996,48.28995394706726,-0.09231728015282545,1739141208.895801,48.28995394706726,2.025482320139728,1739141208.8958032,48.28995394706726,0.0,1739141208.8958046,48.28995394706726,0.2128253175369823,1739141208.8958066,48.28995394706726,3.172487243321482,1739141208.895808,48.28995394706726,1.8126570026027455 +1739141208.9154055,48.309953927993774,35.30394236041365,1739141208.9154103,48.309953927993774,-0.3744602974587323,1739141208.9154146,48.309953927993774,77.19278753959715,1739141208.9154184,48.309953927993774,28.696505510349915,1739141208.9154205,48.309953927993774,-0.05220090179786255,1739141208.915423,48.309953927993774,3.092859045633695,1739141208.9154248,48.309953927993774,-0.5262071922290451,1739141208.915427,48.309953927993774,-0.09231728015282545,1739141208.9154284,48.309953927993774,2.025482320139728,1739141208.915431,48.309953927993774,0.0,1739141208.9154327,48.309953927993774,0.2128253175369823,1739141208.9154341,48.309953927993774,3.172487243321482,1739141208.9154358,48.309953927993774,1.8126570026027455 +1739141208.935664,48.32995390892029,35.30394236041365,1739141208.9356673,48.32995390892029,-0.3744602974587323,1739141208.9356706,48.32995390892029,77.19278753959715,1739141208.9356742,48.32995390892029,28.696505510349915,1739141208.9356759,48.32995390892029,-0.05220090179786255,1739141208.935678,48.32995390892029,3.092859045633695,1739141208.9356797,48.32995390892029,-0.5262071922290451,1739141208.9356818,48.32995390892029,-0.09231728015282545,1739141208.9356833,48.32995390892029,2.025482320139728,1739141208.9356854,48.32995390892029,0.0,1739141208.935687,48.32995390892029,0.2128253175369823,1739141208.9356887,48.32995390892029,3.172487243321482,1739141208.9356904,48.32995390892029,1.8126570026027455 +1739141208.9557378,48.3499538898468,35.30394236041365,1739141208.9557416,48.3499538898468,-0.3744602974587323,1739141208.9557457,48.3499538898468,77.19278753959715,1739141208.9557493,48.3499538898468,28.696505510349915,1739141208.9557512,48.3499538898468,-0.05220090179786255,1739141208.9557536,48.3499538898468,3.092859045633695,1739141208.9557552,48.3499538898468,-0.5262071922290451,1739141208.9557571,48.3499538898468,-0.09231728015282545,1739141208.9557586,48.3499538898468,2.025482320139728,1739141208.9557607,48.3499538898468,0.0,1739141208.9557626,48.3499538898468,0.2128253175369823,1739141208.9557643,48.3499538898468,3.172487243321482,1739141208.955766,48.3499538898468,1.8126570026027455 +1739141208.9756262,48.369953870773315,35.10346694090853,1739141208.9756296,48.369953870773315,-0.3801133051253238,1739141208.9756331,48.369953870773315,77.41590326200122,1739141208.9756365,48.369953870773315,28.403633280199863,1739141208.9756384,48.369953870773315,-0.050663449826314585,1739141208.9756403,48.369953870773315,3.09245938798433,1739141208.9756422,48.369953870773315,-0.49722310171279577,1739141208.9756436,48.369953870773315,-0.08484374422813483,1739141208.975645,48.369953870773315,2.049101677861935,1739141208.9756472,48.369953870773315,0.0,1739141208.975649,48.369953870773315,0.21352206162449253,1739141208.9756505,48.369953870773315,3.166652119940384,1739141208.9756525,48.369953870773315,1.8359113993019969 +1739141208.995696,48.38995385169983,35.10346694090853,1739141208.9956994,48.38995385169983,-0.3801133051253238,1739141208.9957035,48.38995385169983,77.41590326200122,1739141208.9957068,48.38995385169983,28.403633280199863,1739141208.995709,48.38995385169983,-0.050663449826314585,1739141208.995711,48.38995385169983,3.09245938798433,1739141208.9957128,48.38995385169983,-0.49722310171279577,1739141208.9957147,48.38995385169983,-0.08484374422813483,1739141208.995716,48.38995385169983,2.049101677861935,1739141208.9957182,48.38995385169983,0.0,1739141208.99572,48.38995385169983,0.213190278559938,1739141208.9957218,48.38995385169983,3.166652119940384,1739141208.9957235,48.38995385169983,1.8359113993019969 +1739141209.015656,48.40995383262634,35.10346694090853,1739141209.01566,48.40995383262634,-0.3801133051253238,1739141209.0156639,48.40995383262634,77.41590326200122,1739141209.0156674,48.40995383262634,28.403633280199863,1739141209.0156693,48.40995383262634,-0.050663449826314585,1739141209.0156715,48.40995383262634,3.09245938798433,1739141209.0156734,48.40995383262634,-0.49722310171279577,1739141209.015675,48.40995383262634,-0.08484374422813483,1739141209.0156767,48.40995383262634,2.049101677861935,1739141209.0156786,48.40995383262634,0.0,1739141209.0156806,48.40995383262634,0.213190278559938,1739141209.0156822,48.40995383262634,3.166652119940384,1739141209.015684,48.40995383262634,1.8359113993019969 +1739141209.0359387,48.429953813552856,35.10346694090853,1739141209.0359418,48.429953813552856,-0.3801133051253238,1739141209.0359454,48.429953813552856,77.41590326200122,1739141209.0359488,48.429953813552856,28.403633280199863,1739141209.0359507,48.429953813552856,-0.050663449826314585,1739141209.0359526,48.429953813552856,3.09245938798433,1739141209.0359545,48.429953813552856,-0.49722310171279577,1739141209.035956,48.429953813552856,-0.08484374422813483,1739141209.0359576,48.429953813552856,2.049101677861935,1739141209.0359595,48.429953813552856,0.0,1739141209.0359614,48.429953813552856,0.213190278559938,1739141209.035963,48.429953813552856,3.166652119940384,1739141209.0359647,48.429953813552856,1.8359113993019969 +1739141209.0557156,48.44995379447937,35.10346694090853,1739141209.0557194,48.44995379447937,-0.3801133051253238,1739141209.0557237,48.44995379447937,77.41590326200122,1739141209.0557272,48.44995379447937,28.403633280199863,1739141209.0557292,48.44995379447937,-0.050663449826314585,1739141209.055731,48.44995379447937,3.09245938798433,1739141209.055733,48.44995379447937,-0.49722310171279577,1739141209.0557349,48.44995379447937,-0.08484374422813483,1739141209.0557363,48.44995379447937,2.049101677861935,1739141209.0557384,48.44995379447937,0.0,1739141209.05574,48.44995379447937,0.213190278559938,1739141209.055742,48.44995379447937,3.166652119940384,1739141209.0557435,48.44995379447937,1.8359113993019969 +1739141209.0751476,48.469953775405884,34.90040061188828,1739141209.0751505,48.469953775405884,-0.38469143718538135,1739141209.0751545,48.469953775405884,77.70826309261268,1739141209.0751576,48.469953775405884,28.041278523652597,1739141209.0751595,48.469953775405884,-0.048,1739141209.075162,48.469953775405884,3.092545355159858,1739141209.0751636,48.469953775405884,-0.471114384635019,1739141209.0751653,48.469953775405884,-0.07670270801525354,1739141209.0751667,48.469953775405884,2.070613578356586,1739141209.0751688,48.469953775405884,0.0,1739141209.0751705,48.469953775405884,0.20970853741800688,1739141209.0751722,48.469953775405884,3.1612010362980305,1739141209.0751739,48.469953775405884,1.8592470681380011 +1739141209.0951242,48.4899537563324,34.90040061188828,1739141209.0951276,48.4899537563324,-0.38469143718538135,1739141209.0951312,48.4899537563324,77.70826309261268,1739141209.0951347,48.4899537563324,28.041278523652597,1739141209.0951362,48.4899537563324,-0.048,1739141209.0951388,48.4899537563324,3.092545355159858,1739141209.0951405,48.4899537563324,-0.471114384635019,1739141209.095142,48.4899537563324,-0.07670270801525354,1739141209.0951433,48.4899537563324,2.070613578356586,1739141209.0951452,48.4899537563324,0.0,1739141209.095147,48.4899537563324,0.21136651021858488,1739141209.0951488,48.4899537563324,3.1612010362980305,1739141209.09515,48.4899537563324,1.8592470681380011 +1739141209.1153228,48.50995373725891,34.90040061188828,1739141209.115326,48.50995373725891,-0.38469143718538135,1739141209.115329,48.50995373725891,77.70826309261268,1739141209.1153324,48.50995373725891,28.041278523652597,1739141209.115334,48.50995373725891,-0.048,1739141209.115336,48.50995373725891,3.092545355159858,1739141209.1153374,48.50995373725891,-0.471114384635019,1739141209.115339,48.50995373725891,-0.07670270801525354,1739141209.1153402,48.50995373725891,2.070613578356586,1739141209.1153421,48.50995373725891,0.0,1739141209.1153436,48.50995373725891,0.21136651021858488,1739141209.1153452,48.50995373725891,3.1612010362980305,1739141209.1153467,48.50995373725891,1.8592470681380011 +1739141209.1349719,48.529953718185425,34.90040061188828,1739141209.1349745,48.529953718185425,-0.38469143718538135,1739141209.1349778,48.529953718185425,77.70826309261268,1739141209.1349807,48.529953718185425,28.041278523652597,1739141209.134982,48.529953718185425,-0.048,1739141209.134984,48.529953718185425,3.092545355159858,1739141209.1349854,48.529953718185425,-0.471114384635019,1739141209.1349866,48.529953718185425,-0.07670270801525354,1739141209.1349883,48.529953718185425,2.070613578356586,1739141209.13499,48.529953718185425,0.0,1739141209.1349916,48.529953718185425,0.21136651021858488,1739141209.134993,48.529953718185425,3.1612010362980305,1739141209.1349947,48.529953718185425,1.8592470681380011 +1739141209.1553075,48.54995369911194,34.90040061188828,1739141209.1553106,48.54995369911194,-0.38469143718538135,1739141209.1553144,48.54995369911194,77.70826309261268,1739141209.1553173,48.54995369911194,28.041278523652597,1739141209.1553187,48.54995369911194,-0.048,1739141209.1553211,48.54995369911194,3.092545355159858,1739141209.1553223,48.54995369911194,-0.471114384635019,1739141209.155324,48.54995369911194,-0.07670270801525354,1739141209.1553254,48.54995369911194,2.070613578356586,1739141209.1553273,48.54995369911194,0.0,1739141209.1553288,48.54995369911194,0.21136651021858488,1739141209.15533,48.54995369911194,3.1612010362980305,1739141209.1553314,48.54995369911194,1.8592470681380011 +1739141209.1753728,48.56995368003845,34.90040061188828,1739141209.1753757,48.56995368003845,-0.38469143718538135,1739141209.1753788,48.56995368003845,77.70826309261268,1739141209.1753817,48.56995368003845,28.041278523652597,1739141209.1753836,48.56995368003845,-0.048,1739141209.1753857,48.56995368003845,3.092545355159858,1739141209.1753871,48.56995368003845,-0.471114384635019,1739141209.1753886,48.56995368003845,-0.07670270801525354,1739141209.17539,48.56995368003845,2.070613578356586,1739141209.1753917,48.56995368003845,0.0,1739141209.1753936,48.56995368003845,0.21136651021858488,1739141209.1753948,48.56995368003845,3.1612010362980305,1739141209.1753964,48.56995368003845,1.8592470681380011 +1739141209.1954565,48.589953660964966,34.69475796442384,1739141209.1954598,48.589953660964966,-0.38824202522491724,1739141209.1954634,48.589953660964966,77.72245243528772,1739141209.1954665,48.589953660964966,27.957741813160254,1739141209.195468,48.589953660964966,-0.04774107799256864,1739141209.19547,48.589953660964966,3.0910938200460403,1739141209.1954715,48.589953660964966,-0.4383048629158728,1739141209.1954732,48.589953660964966,-0.07396160896176662,1739141209.1954746,48.589953660964966,2.0979670128466372,1739141209.1954765,48.589953660964966,0.0,1739141209.195478,48.589953660964966,0.2194558348029864,1739141209.1954796,48.589953660964966,3.156115887967607,1739141209.1954808,48.589953660964966,1.8823632392938292 +1739141209.2153265,48.60995364189148,34.69475796442384,1739141209.2153296,48.60995364189148,-0.38824202522491724,1739141209.2153327,48.60995364189148,77.72245243528772,1739141209.2153358,48.60995364189148,27.957741813160254,1739141209.2153375,48.60995364189148,-0.04774107799256864,1739141209.2153392,48.60995364189148,3.0910938200460403,1739141209.2153409,48.60995364189148,-0.4383048629158728,1739141209.2153423,48.60995364189148,-0.07396160896176662,1739141209.215344,48.60995364189148,2.0979670128466372,1739141209.2153456,48.60995364189148,0.0,1739141209.2153475,48.60995364189148,0.21560377355280802,1739141209.215349,48.60995364189148,3.156115887967607,1739141209.2153504,48.60995364189148,1.8823632392938292 +1739141209.2349336,48.62995362281799,34.69475796442384,1739141209.234936,48.62995362281799,-0.38824202522491724,1739141209.234939,48.62995362281799,77.72245243528772,1739141209.2349422,48.62995362281799,27.957741813160254,1739141209.234944,48.62995362281799,-0.04774107799256864,1739141209.2349458,48.62995362281799,3.0910938200460403,1739141209.2349477,48.62995362281799,-0.4383048629158728,1739141209.2349489,48.62995362281799,-0.07396160896176662,1739141209.2349503,48.62995362281799,2.0979670128466372,1739141209.234952,48.62995362281799,0.0,1739141209.2349536,48.62995362281799,0.21560377355280802,1739141209.2349553,48.62995362281799,3.156115887967607,1739141209.2349567,48.62995362281799,1.8823632392938292 +1739141209.255436,48.64995360374451,34.69475796442384,1739141209.255439,48.64995360374451,-0.38824202522491724,1739141209.2554421,48.64995360374451,77.72245243528772,1739141209.2554452,48.64995360374451,27.957741813160254,1739141209.2554464,48.64995360374451,-0.04774107799256864,1739141209.2554486,48.64995360374451,3.0910938200460403,1739141209.2554505,48.64995360374451,-0.4383048629158728,1739141209.2554517,48.64995360374451,-0.07396160896176662,1739141209.255453,48.64995360374451,2.0979670128466372,1739141209.255455,48.64995360374451,0.0,1739141209.2554564,48.64995360374451,0.21560377355280802,1739141209.2554584,48.64995360374451,3.156115887967607,1739141209.2554598,48.64995360374451,1.8823632392938292 +1739141209.2747397,48.66995358467102,34.69475796442384,1739141209.2747426,48.66995358467102,-0.38824202522491724,1739141209.2747462,48.66995358467102,77.72245243528772,1739141209.2747493,48.66995358467102,27.957741813160254,1739141209.2747507,48.66995358467102,-0.04774107799256864,1739141209.2747526,48.66995358467102,3.0910938200460403,1739141209.274754,48.66995358467102,-0.4383048629158728,1739141209.2747552,48.66995358467102,-0.07396160896176662,1739141209.274757,48.66995358467102,2.0979670128466372,1739141209.2747583,48.66995358467102,0.0,1739141209.27476,48.66995358467102,0.21560377355280802,1739141209.2747612,48.66995358467102,3.156115887967607,1739141209.274763,48.66995358467102,1.8823632392938292 +1739141209.2953832,48.689953565597534,34.486537282092485,1739141209.2953863,48.689953565597534,-0.390798088375222,1739141209.2953897,48.689953565597534,77.99394859023452,1739141209.2953925,48.689953565597534,27.615563940272562,1739141209.295394,48.689953565597534,-0.045,1739141209.295396,48.689953565597534,3.091307699325609,1739141209.2953975,48.689953565597534,-0.4119343869030038,1739141209.295399,48.689953565597534,-0.06683166460678178,1739141209.2954004,48.689953565597534,2.1202138942590953,1739141209.2954023,48.689953565597534,0.0,1739141209.295404,48.689953565597534,0.21308737879621795,1739141209.2954056,48.689953565597534,3.151220597757799,1739141209.2954068,48.689953565597534,1.9059282316468584 +1739141209.315317,48.70995354652405,34.486537282092485,1739141209.31532,48.70995354652405,-0.390798088375222,1739141209.3153236,48.70995354652405,77.99394859023452,1739141209.3153272,48.70995354652405,27.615563940272562,1739141209.3153286,48.70995354652405,-0.045,1739141209.3153305,48.70995354652405,3.091307699325609,1739141209.3153322,48.70995354652405,-0.4119343869030038,1739141209.3153334,48.70995354652405,-0.06683166460678178,1739141209.3153348,48.70995354652405,2.1202138942590953,1739141209.3153365,48.70995354652405,0.0,1739141209.3153381,48.70995354652405,0.21428566261223692,1739141209.31534,48.70995354652405,3.151220597757799,1739141209.3153412,48.70995354652405,1.9059282316468584 +1739141209.335572,48.72995352745056,34.486537282092485,1739141209.3355746,48.72995352745056,-0.390798088375222,1739141209.3355782,48.72995352745056,77.99394859023452,1739141209.3355813,48.72995352745056,27.615563940272562,1739141209.3355827,48.72995352745056,-0.045,1739141209.3355844,48.72995352745056,3.091307699325609,1739141209.335586,48.72995352745056,-0.4119343869030038,1739141209.3355873,48.72995352745056,-0.06683166460678178,1739141209.335589,48.72995352745056,2.1202138942590953,1739141209.3355904,48.72995352745056,0.0,1739141209.335592,48.72995352745056,0.21428566261223692,1739141209.3355935,48.72995352745056,3.151220597757799,1739141209.335595,48.72995352745056,1.9059282316468584 +1739141209.3551338,48.749953508377075,34.486537282092485,1739141209.3551373,48.749953508377075,-0.390798088375222,1739141209.3551407,48.749953508377075,77.99394859023452,1739141209.3551438,48.749953508377075,27.615563940272562,1739141209.3551452,48.749953508377075,-0.045,1739141209.3551471,48.749953508377075,3.091307699325609,1739141209.3551488,48.749953508377075,-0.4119343869030038,1739141209.35515,48.749953508377075,-0.06683166460678178,1739141209.355152,48.749953508377075,2.1202138942590953,1739141209.3551536,48.749953508377075,0.0,1739141209.3551552,48.749953508377075,0.21428566261223692,1739141209.3551567,48.749953508377075,3.151220597757799,1739141209.3551583,48.749953508377075,1.9059282316468584 +1739141209.3756158,48.76995348930359,34.486537282092485,1739141209.3756182,48.76995348930359,-0.390798088375222,1739141209.3756213,48.76995348930359,77.99394859023452,1739141209.3756244,48.76995348930359,27.615563940272562,1739141209.3756256,48.76995348930359,-0.045,1739141209.3756275,48.76995348930359,3.091307699325609,1739141209.375629,48.76995348930359,-0.4119343869030038,1739141209.3756304,48.76995348930359,-0.06683166460678178,1739141209.3756318,48.76995348930359,2.1202138942590953,1739141209.3756337,48.76995348930359,0.0,1739141209.3756351,48.76995348930359,0.21428566261223692,1739141209.3756366,48.76995348930359,3.151220597757799,1739141209.375638,48.76995348930359,1.9059282316468584 +1739141209.3957472,48.7899534702301,34.486537282092485,1739141209.3957508,48.7899534702301,-0.390798088375222,1739141209.3957546,48.7899534702301,77.99394859023452,1739141209.3957582,48.7899534702301,27.615563940272562,1739141209.3957596,48.7899534702301,-0.045,1739141209.3957617,48.7899534702301,3.091307699325609,1739141209.3957634,48.7899534702301,-0.4119343869030038,1739141209.3957653,48.7899534702301,-0.06683166460678178,1739141209.3957667,48.7899534702301,2.1202138942590953,1739141209.395769,48.7899534702301,0.0,1739141209.3957708,48.7899534702301,0.21428566261223692,1739141209.3957725,48.7899534702301,3.151220597757799,1739141209.395774,48.7899534702301,1.9059282316468584 +1739141209.4156206,48.809953451156616,34.27571858692918,1739141209.4156244,48.809953451156616,-0.39237515870198436,1739141209.4156282,48.809953451156616,78.22270251316097,1739141209.415632,48.809953451156616,27.31650911011952,1739141209.4156337,48.809953451156616,-0.04330518768496632,1739141209.415636,48.809953451156616,3.091475228089416,1739141209.4156377,48.809953451156616,-0.38363092681557387,1739141209.4156394,48.809953451156616,-0.06067426070905295,1739141209.4156408,48.809953451156616,2.144354042090555,1739141209.4156427,48.809953451156616,0.0,1739141209.4156446,48.809953451156616,0.21562914535448374,1739141209.4156463,48.809953451156616,3.146559511355149,1739141209.4156477,48.809953451156616,1.9293646507424405 +1739141209.4353423,48.82995343208313,34.27571858692918,1739141209.4353454,48.82995343208313,-0.39237515870198436,1739141209.435349,48.82995343208313,78.22270251316097,1739141209.4353523,48.82995343208313,27.31650911011952,1739141209.4353538,48.82995343208313,-0.04330518768496632,1739141209.4353561,48.82995343208313,3.091475228089416,1739141209.435358,48.82995343208313,-0.38363092681557387,1739141209.4353592,48.82995343208313,-0.06067426070905295,1739141209.435361,48.82995343208313,2.144354042090555,1739141209.4353628,48.82995343208313,0.0,1739141209.4353647,48.82995343208313,0.21498939134811446,1739141209.4353664,48.82995343208313,3.146559511355149,1739141209.4353678,48.82995343208313,1.9293646507424405 +1739141209.4555056,48.849953413009644,34.27571858692918,1739141209.455509,48.849953413009644,-0.39237515870198436,1739141209.4555128,48.849953413009644,78.22270251316097,1739141209.455516,48.849953413009644,27.31650911011952,1739141209.4555178,48.849953413009644,-0.04330518768496632,1739141209.4555197,48.849953413009644,3.091475228089416,1739141209.4555216,48.849953413009644,-0.38363092681557387,1739141209.455523,48.849953413009644,-0.06067426070905295,1739141209.4555247,48.849953413009644,2.144354042090555,1739141209.4555266,48.849953413009644,0.0,1739141209.4555283,48.849953413009644,0.21498939134811446,1739141209.4555297,48.849953413009644,3.146559511355149,1739141209.4555314,48.849953413009644,1.9293646507424405 +1739141209.4756334,48.86995339393616,34.27571858692918,1739141209.4756365,48.86995339393616,-0.39237515870198436,1739141209.47564,48.86995339393616,78.22270251316097,1739141209.4756434,48.86995339393616,27.31650911011952,1739141209.475645,48.86995339393616,-0.04330518768496632,1739141209.475647,48.86995339393616,3.091475228089416,1739141209.475649,48.86995339393616,-0.38363092681557387,1739141209.4756505,48.86995339393616,-0.06067426070905295,1739141209.475652,48.86995339393616,2.144354042090555,1739141209.4756541,48.86995339393616,0.0,1739141209.4756558,48.86995339393616,0.21498939134811446,1739141209.4756572,48.86995339393616,3.146559511355149,1739141209.475659,48.86995339393616,1.9293646507424405 +1739141209.4968898,48.88995337486267,34.27571858692918,1739141209.4968975,48.88995337486267,-0.39237515870198436,1739141209.4969058,48.88995337486267,78.22270251316097,1739141209.4969106,48.88995337486267,27.31650911011952,1739141209.4969127,48.88995337486267,-0.04330518768496632,1739141209.4969158,48.88995337486267,3.091475228089416,1739141209.496918,48.88995337486267,-0.38363092681557387,1739141209.4969203,48.88995337486267,-0.06067426070905295,1739141209.4969223,48.88995337486267,2.144354042090555,1739141209.4969249,48.88995337486267,0.0,1739141209.4969273,48.88995337486267,0.21498939134811446,1739141209.4969292,48.88995337486267,3.146559511355149,1739141209.4969313,48.88995337486267,1.9293646507424405 +1739141209.5164678,48.909953355789185,34.06231499988855,1739141209.516472,48.909953355789185,-0.39299939734135325,1739141209.5164773,48.909953355789185,78.45259761067076,1739141209.5164826,48.909953355789185,27.016142477796745,1739141209.5164852,48.909953355789185,-0.040319477070879475,1739141209.5164878,48.909953355789185,3.091581694966447,1739141209.5164905,48.909953355789185,-0.35668836871213483,1739141209.5164928,48.909953355789185,-0.05503110603452059,1739141209.516495,48.909953355789185,2.167588771166323,1739141209.5164979,48.909953355789185,0.0,1739141209.5165005,48.909953355789185,0.21449152574713456,1739141209.5165029,48.909953355789185,3.142161544816269,1739141209.5165052,48.909953355789185,1.9528601664431477 +1739141209.5364654,48.9299533367157,34.06231499988855,1739141209.53647,48.9299533367157,-0.39299939734135325,1739141209.536475,48.9299533367157,78.45259761067076,1739141209.5364797,48.9299533367157,27.016142477796745,1739141209.5364823,48.9299533367157,-0.040319477070879475,1739141209.5364852,48.9299533367157,3.091581694966447,1739141209.5364876,48.9299533367157,-0.35668836871213483,1739141209.53649,48.9299533367157,-0.05503110603452059,1739141209.5364923,48.9299533367157,2.167588771166323,1739141209.5364952,48.9299533367157,0.0,1739141209.5364976,48.9299533367157,0.21472860472317534,1739141209.5364997,48.9299533367157,3.142161544816269,1739141209.5365021,48.9299533367157,1.9528601664431477 +1739141209.556892,48.94995331764221,34.06231499988855,1739141209.5568964,48.94995331764221,-0.39299939734135325,1739141209.5569015,48.94995331764221,78.45259761067076,1739141209.5569065,48.94995331764221,27.016142477796745,1739141209.556909,48.94995331764221,-0.040319477070879475,1739141209.5569122,48.94995331764221,3.091581694966447,1739141209.5569148,48.94995331764221,-0.35668836871213483,1739141209.556917,48.94995331764221,-0.05503110603452059,1739141209.556919,48.94995331764221,2.167588771166323,1739141209.5569222,48.94995331764221,0.0,1739141209.5569243,48.94995331764221,0.21472860472317534,1739141209.5569267,48.94995331764221,3.142161544816269,1739141209.556929,48.94995331764221,1.9528601664431477 +1739141209.5766416,48.969953298568726,34.06231499988855,1739141209.5766466,48.969953298568726,-0.39299939734135325,1739141209.576652,48.969953298568726,78.45259761067076,1739141209.5766573,48.969953298568726,27.016142477796745,1739141209.57666,48.969953298568726,-0.040319477070879475,1739141209.576663,48.969953298568726,3.091581694966447,1739141209.5766656,48.969953298568726,-0.35668836871213483,1739141209.5766678,48.969953298568726,-0.05503110603452059,1739141209.5766702,48.969953298568726,2.167588771166323,1739141209.576673,48.969953298568726,0.0,1739141209.5766757,48.969953298568726,0.21472860472317534,1739141209.5766785,48.969953298568726,3.142161544816269,1739141209.5766807,48.969953298568726,1.9528601664431477 +1739141209.5963187,48.98995327949524,34.06231499988855,1739141209.5963223,48.98995327949524,-0.39299939734135325,1739141209.596326,48.98995327949524,78.45259761067076,1739141209.5963297,48.98995327949524,27.016142477796745,1739141209.5963318,48.98995327949524,-0.040319477070879475,1739141209.596334,48.98995327949524,3.091581694966447,1739141209.596336,48.98995327949524,-0.35668836871213483,1739141209.5963373,48.98995327949524,-0.05503110603452059,1739141209.596339,48.98995327949524,2.167588771166323,1739141209.5963411,48.98995327949524,0.0,1739141209.5963433,48.98995327949524,0.21472860472317534,1739141209.596345,48.98995327949524,3.142161544816269,1739141209.5963464,48.98995327949524,1.9528601664431477 +1739141209.6151042,49.00995326042175,34.06231499988855,1739141209.6151066,49.00995326042175,-0.39299939734135325,1739141209.6151094,49.00995326042175,78.45259761067076,1739141209.6151123,49.00995326042175,27.016142477796745,1739141209.6151135,49.00995326042175,-0.040319477070879475,1739141209.6151152,49.00995326042175,3.091581694966447,1739141209.6151166,49.00995326042175,-0.35668836871213483,1739141209.6151178,49.00995326042175,-0.05503110603452059,1739141209.6151192,49.00995326042175,2.167588771166323,1739141209.6151206,49.00995326042175,0.0,1739141209.615122,49.00995326042175,0.21472860472317534,1739141209.6151235,49.00995326042175,3.142161544816269,1739141209.6151247,49.00995326042175,1.9528601664431477 +1739141209.6349893,49.02995324134827,33.84632330502231,1739141209.6349916,49.02995324134827,-0.39271888422951307,1739141209.6349945,49.02995324134827,78.59977298806854,1739141209.6349971,49.02995324134827,26.798444393449852,1739141209.6349988,49.02995324134827,-0.03850690938756073,1739141209.6350005,49.02995324134827,3.091376950360734,1739141209.635002,49.02995324134827,-0.3295974042418508,1739141209.635003,49.02995324134827,-0.05082659243261871,1739141209.6350045,49.02995324134827,2.1912053272753256,1739141209.635006,49.02995324134827,0.0,1739141209.6350071,49.02995324134827,0.2149313195333222,1739141209.6350086,49.02995324134827,3.138100473733557,1739141209.6350098,49.02995324134827,1.9763705386521995 +1739141209.6550965,49.04995322227478,33.84632330502231,1739141209.6550996,49.04995322227478,-0.39271888422951307,1739141209.655103,49.04995322227478,78.59977298806854,1739141209.6551056,49.04995322227478,26.798444393449852,1739141209.655107,49.04995322227478,-0.03850690938756073,1739141209.655109,49.04995322227478,3.091376950360734,1739141209.6551104,49.04995322227478,-0.3295974042418508,1739141209.6551118,49.04995322227478,-0.05082659243261871,1739141209.655113,49.04995322227478,2.1912053272753256,1739141209.6551147,49.04995322227478,0.0,1739141209.655116,49.04995322227478,0.2148347886231261,1739141209.6551173,49.04995322227478,3.138100473733557,1739141209.6551187,49.04995322227478,1.9763705386521995 +1739141209.676715,49.069953203201294,33.84632330502231,1739141209.6767192,49.069953203201294,-0.39271888422951307,1739141209.676724,49.069953203201294,78.59977298806854,1739141209.6767294,49.069953203201294,26.798444393449852,1739141209.6767323,49.069953203201294,-0.03850690938756073,1739141209.6767364,49.069953203201294,3.091376950360734,1739141209.6767397,49.069953203201294,-0.3295974042418508,1739141209.676743,49.069953203201294,-0.05082659243261871,1739141209.6767461,49.069953203201294,2.1912053272753256,1739141209.6767497,49.069953203201294,0.0,1739141209.676753,49.069953203201294,0.2148347886231261,1739141209.6767566,49.069953203201294,3.138100473733557,1739141209.67676,49.069953203201294,1.9763705386521995 +1739141209.6964958,49.08995318412781,33.84632330502231,1739141209.6965,49.08995318412781,-0.39271888422951307,1739141209.6965046,49.08995318412781,78.59977298806854,1739141209.6965096,49.08995318412781,26.798444393449852,1739141209.696513,49.08995318412781,-0.03850690938756073,1739141209.6965165,49.08995318412781,3.091376950360734,1739141209.6965199,49.08995318412781,-0.3295974042418508,1739141209.6965234,49.08995318412781,-0.05082659243261871,1739141209.6965265,49.08995318412781,2.1912053272753256,1739141209.69653,49.08995318412781,0.0,1739141209.6965337,49.08995318412781,0.2148347886231261,1739141209.696537,49.08995318412781,3.138100473733557,1739141209.6965404,49.08995318412781,1.9763705386521995 +1739141209.7147353,49.10995316505432,33.84632330502231,1739141209.7147381,49.10995316505432,-0.39271888422951307,1739141209.714741,49.10995316505432,78.59977298806854,1739141209.7147436,49.10995316505432,26.798444393449852,1739141209.714745,49.10995316505432,-0.03850690938756073,1739141209.7147467,49.10995316505432,3.091376950360734,1739141209.714748,49.10995316505432,-0.3295974042418508,1739141209.7147493,49.10995316505432,-0.05082659243261871,1739141209.7147505,49.10995316505432,2.1912053272753256,1739141209.714752,49.10995316505432,0.0,1739141209.7147536,49.10995316505432,0.2148347886231261,1739141209.7147548,49.10995316505432,3.138100473733557,1739141209.714756,49.10995316505432,1.9763705386521995 +1739141209.736818,49.129953145980835,33.62774927259029,1739141209.7368224,49.129953145980835,-0.391565194062224,1739141209.7368274,49.129953145980835,79.02422249785786,1739141209.736833,49.129953145980835,26.303494273292053,1739141209.7368364,49.129953145980835,-0.034,1739141209.7368405,49.129953145980835,3.0928120561451333,1739141209.736844,49.129953145980835,-0.3034897113009999,1739141209.7368476,49.129953145980835,-0.043342526938407934,1739141209.7368515,49.129953145980835,2.214208154715503,1739141209.7368553,49.129953145980835,0.0,1739141209.7368588,49.129953145980835,0.21387195840568762,1739141209.7368627,49.129953145980835,3.1342108472796113,1739141209.7368662,49.129953145980835,1.9998777055010464 +1739141209.756725,49.14995312690735,33.62774927259029,1739141209.7567296,49.14995312690735,-0.391565194062224,1739141209.7567346,49.14995312690735,79.02422249785786,1739141209.7567403,49.14995312690735,26.303494273292053,1739141209.7567437,49.14995312690735,-0.034,1739141209.7567477,49.14995312690735,3.0928120561451333,1739141209.7567513,49.14995312690735,-0.3034897113009999,1739141209.756755,49.14995312690735,-0.043342526938407934,1739141209.7567587,49.14995312690735,2.214208154715503,1739141209.7567627,49.14995312690735,0.0,1739141209.7567666,49.14995312690735,0.21433044921445643,1739141209.7567704,49.14995312690735,3.1342108472796113,1739141209.756774,49.14995312690735,1.9998777055010464 +1739141209.776901,49.16995310783386,33.62774927259029,1739141209.7769055,49.16995310783386,-0.391565194062224,1739141209.7769103,49.16995310783386,79.02422249785786,1739141209.7769163,49.16995310783386,26.303494273292053,1739141209.7769196,49.16995310783386,-0.034,1739141209.7769241,49.16995310783386,3.0928120561451333,1739141209.7769277,49.16995310783386,-0.3034897113009999,1739141209.7769313,49.16995310783386,-0.043342526938407934,1739141209.776935,49.16995310783386,2.214208154715503,1739141209.776939,49.16995310783386,0.0,1739141209.7769427,49.16995310783386,0.21433044921445643,1739141209.7769465,49.16995310783386,3.1342108472796113,1739141209.7769504,49.16995310783386,1.9998777055010464 +1739141209.7967944,49.189953088760376,33.62774927259029,1739141209.796799,49.189953088760376,-0.391565194062224,1739141209.7968042,49.189953088760376,79.02422249785786,1739141209.79681,49.189953088760376,26.303494273292053,1739141209.7968132,49.189953088760376,-0.034,1739141209.7968173,49.189953088760376,3.0928120561451333,1739141209.7968209,49.189953088760376,-0.3034897113009999,1739141209.7968252,49.189953088760376,-0.043342526938407934,1739141209.7968287,49.189953088760376,2.214208154715503,1739141209.7968326,49.189953088760376,0.0,1739141209.7968364,49.189953088760376,0.21433044921445643,1739141209.79684,49.189953088760376,3.1342108472796113,1739141209.7968438,49.189953088760376,1.9998777055010464 +1739141209.815333,49.20995306968689,33.62774927259029,1739141209.815336,49.20995306968689,-0.391565194062224,1739141209.8153393,49.20995306968689,79.02422249785786,1739141209.8153424,49.20995306968689,26.303494273292053,1739141209.8153439,49.20995306968689,-0.034,1739141209.8153458,49.20995306968689,3.0928120561451333,1739141209.8153474,49.20995306968689,-0.3034897113009999,1739141209.8153486,49.20995306968689,-0.043342526938407934,1739141209.81535,49.20995306968689,2.214208154715503,1739141209.8153517,49.20995306968689,0.0,1739141209.8153534,49.20995306968689,0.21433044921445643,1739141209.8153546,49.20995306968689,3.1342108472796113,1739141209.8153563,49.20995306968689,1.9998777055010464 +1739141209.8371334,49.2299530506134,33.62774927259029,1739141209.837138,49.2299530506134,-0.391565194062224,1739141209.8371432,49.2299530506134,79.02422249785786,1739141209.8371491,49.2299530506134,26.303494273292053,1739141209.8371522,49.2299530506134,-0.034,1739141209.8371565,49.2299530506134,3.0928120561451333,1739141209.8371603,49.2299530506134,-0.3034897113009999,1739141209.837164,49.2299530506134,-0.043342526938407934,1739141209.8371675,49.2299530506134,2.214208154715503,1739141209.8371716,49.2299530506134,0.0,1739141209.8371754,49.2299530506134,0.21433044921445643,1739141209.8371792,49.2299530506134,3.1342108472796113,1739141209.837183,49.2299530506134,1.9998777055010464 +1739141209.8569431,49.24995303153992,33.40659712819528,1739141209.8569472,49.24995303153992,-0.38956397777906826,1739141209.8569524,49.24995303153992,79.05053960304087,1739141209.856958,49.24995303153992,26.206794209347677,1739141209.8569613,49.24995303153992,-0.03367822939862869,1739141209.8569653,49.24995303153992,3.0922029231732444,1739141209.8569689,49.24995303153992,-0.27679534424537616,1739141209.8569727,49.24995303153992,-0.04090647355813942,1739141209.8569763,49.24995303153992,2.237977584944926,1739141209.8569803,49.24995303153992,0.0,1739141209.8569841,49.24995303153992,0.2149187406540817,1739141209.8569877,49.24995303153992,3.1306103346606684,1739141209.8569913,49.24995303153992,2.02333898321156 +1739141209.8770669,49.26995301246643,33.40659712819528,1739141209.8770711,49.26995301246643,-0.38956397777906826,1739141209.8770761,49.26995301246643,79.05053960304087,1739141209.8770819,49.26995301246643,26.206794209347677,1739141209.877085,49.26995301246643,-0.03367822939862869,1739141209.8770893,49.26995301246643,3.0922029231732444,1739141209.8770928,49.26995301246643,-0.27679534424537616,1739141209.8770967,49.26995301246643,-0.04090647355813942,1739141209.8771002,49.26995301246643,2.237977584944926,1739141209.8771043,49.26995301246643,0.0,1739141209.8771083,49.26995301246643,0.21463860173336613,1739141209.877112,49.26995301246643,3.1306103346606684,1739141209.8771157,49.26995301246643,2.02333898321156 +1739141209.8968885,49.289952993392944,33.40659712819528,1739141209.8968928,49.289952993392944,-0.38956397777906826,1739141209.8968978,49.289952993392944,79.05053960304087,1739141209.8969038,49.289952993392944,26.206794209347677,1739141209.8969069,49.289952993392944,-0.03367822939862869,1739141209.8969111,49.289952993392944,3.0922029231732444,1739141209.896915,49.289952993392944,-0.27679534424537616,1739141209.8969188,49.289952993392944,-0.04090647355813942,1739141209.8969223,49.289952993392944,2.237977584944926,1739141209.8969264,49.289952993392944,0.0,1739141209.89693,49.289952993392944,0.21463860173336613,1739141209.8969338,49.289952993392944,3.1306103346606684,1739141209.8969374,49.289952993392944,2.02333898321156 +1739141209.9166143,49.30995297431946,33.40659712819528,1739141209.9166188,49.30995297431946,-0.38956397777906826,1739141209.9166236,49.30995297431946,79.05053960304087,1739141209.9166296,49.30995297431946,26.206794209347677,1739141209.9166327,49.30995297431946,-0.03367822939862869,1739141209.916637,49.30995297431946,3.0922029231732444,1739141209.9166408,49.30995297431946,-0.27679534424537616,1739141209.9166446,49.30995297431946,-0.04090647355813942,1739141209.9166481,49.30995297431946,2.237977584944926,1739141209.916652,49.30995297431946,0.0,1739141209.9166558,49.30995297431946,0.21463860173336613,1739141209.9166594,49.30995297431946,3.1306103346606684,1739141209.916663,49.30995297431946,2.02333898321156 +1739141209.9370363,49.32995295524597,33.40659712819528,1739141209.9370406,49.32995295524597,-0.38956397777906826,1739141209.9370458,49.32995295524597,79.05053960304087,1739141209.9370515,49.32995295524597,26.206794209347677,1739141209.9370549,49.32995295524597,-0.03367822939862869,1739141209.9370592,49.32995295524597,3.0922029231732444,1739141209.9370627,49.32995295524597,-0.27679534424537616,1739141209.9370666,49.32995295524597,-0.04090647355813942,1739141209.9370701,49.32995295524597,2.237977584944926,1739141209.937074,49.32995295524597,0.0,1739141209.9370778,49.32995295524597,0.21463860173336613,1739141209.9370813,49.32995295524597,3.1306103346606684,1739141209.9370852,49.32995295524597,2.02333898321156 +1739141209.956912,49.349952936172485,33.18287224078224,1739141209.9569168,49.349952936172485,-0.38675286986909896,1739141209.9569218,49.349952936172485,79.39517695095624,1739141209.9569275,49.349952936172485,25.791714110262006,1739141209.9569309,49.349952936172485,-0.030510377010786377,1739141209.956935,49.349952936172485,3.0934314575964468,1739141209.9569387,49.349952936172485,-0.24946414932528618,1739141209.9569423,49.349952936172485,-0.03498782509320526,1739141209.956946,49.349952936172485,2.262578454796842,1739141209.95695,49.349952936172485,0.0,1739141209.9569535,49.349952936172485,0.21676872772615718,1739141209.956957,49.349952936172485,3.1271504104672885,1739141209.956961,49.349952936172485,2.046824073288248 +1739141209.9768565,49.369952917099,33.18287224078224,1739141209.9768605,49.369952917099,-0.38675286986909896,1739141209.9768653,49.369952917099,79.39517695095624,1739141209.9768713,49.369952917099,25.791714110262006,1739141209.9768746,49.369952917099,-0.030510377010786377,1739141209.9768786,49.369952917099,3.0934314575964468,1739141209.9768822,49.369952917099,-0.24946414932528618,1739141209.976886,49.369952917099,-0.03498782509320526,1739141209.9768896,49.369952917099,2.262578454796842,1739141209.9768934,49.369952917099,0.0,1739141209.9768972,49.369952917099,0.21575438150859405,1739141209.9769008,49.369952917099,3.1271504104672885,1739141209.9769044,49.369952917099,2.046824073288248 +1739141209.9971104,49.38995289802551,33.18287224078224,1739141209.9971144,49.38995289802551,-0.38675286986909896,1739141209.9971194,49.38995289802551,79.39517695095624,1739141209.9971256,49.38995289802551,25.791714110262006,1739141209.9971287,49.38995289802551,-0.030510377010786377,1739141209.997133,49.38995289802551,3.0934314575964468,1739141209.9971368,49.38995289802551,-0.24946414932528618,1739141209.9971404,49.38995289802551,-0.03498782509320526,1739141209.9971442,49.38995289802551,2.262578454796842,1739141209.9971483,49.38995289802551,0.0,1739141209.9971523,49.38995289802551,0.21575438150859405,1739141209.997156,49.38995289802551,3.1271504104672885,1739141209.9971597,49.38995289802551,2.046824073288248 +1739141210.0149152,49.409952878952026,33.18287224078224,1739141210.0149183,49.409952878952026,-0.38675286986909896,1739141210.0149214,49.409952878952026,79.39517695095624,1739141210.0149245,49.409952878952026,25.791714110262006,1739141210.0149257,49.409952878952026,-0.030510377010786377,1739141210.0149279,49.409952878952026,3.0934314575964468,1739141210.014929,49.409952878952026,-0.24946414932528618,1739141210.0149307,49.409952878952026,-0.03498782509320526,1739141210.0149322,49.409952878952026,2.262578454796842,1739141210.014934,49.409952878952026,0.0,1739141210.0149355,49.409952878952026,0.21575438150859405,1739141210.0149372,49.409952878952026,3.1271504104672885,1739141210.0149384,49.409952878952026,2.046824073288248 +1739141210.0370154,49.42995285987854,33.18287224078224,1739141210.03702,49.42995285987854,-0.38675286986909896,1739141210.037025,49.42995285987854,79.39517695095624,1739141210.037031,49.42995285987854,25.791714110262006,1739141210.037034,49.42995285987854,-0.030510377010786377,1739141210.037038,49.42995285987854,3.0934314575964468,1739141210.037042,49.42995285987854,-0.24946414932528618,1739141210.0370455,49.42995285987854,-0.03498782509320526,1739141210.0370493,49.42995285987854,2.262578454796842,1739141210.037053,49.42995285987854,0.0,1739141210.037057,49.42995285987854,0.21575438150859405,1739141210.0370605,49.42995285987854,3.1271504104672885,1739141210.037064,49.42995285987854,2.046824073288248 +1739141210.0568812,49.449952840805054,33.18287224078224,1739141210.0568855,49.449952840805054,-0.38675286986909896,1739141210.056891,49.449952840805054,79.39517695095624,1739141210.0568964,49.449952840805054,25.791714110262006,1739141210.0568995,49.449952840805054,-0.030510377010786377,1739141210.0569038,49.449952840805054,3.0934314575964468,1739141210.056908,49.449952840805054,-0.24946414932528618,1739141210.0569117,49.449952840805054,-0.03498782509320526,1739141210.0569155,49.449952840805054,2.262578454796842,1739141210.0569193,49.449952840805054,0.0,1739141210.0569232,49.449952840805054,0.21575438150859405,1739141210.0569267,49.449952840805054,3.1271504104672885,1739141210.0569305,49.449952840805054,2.046824073288248 +1739141210.0770397,49.46995282173157,32.95656510448297,1739141210.0770435,49.46995282173157,-0.38314560440432643,1739141210.0770483,49.46995282173157,79.6361333404995,1739141210.077054,49.46995282173157,25.479828938176485,1739141210.0770574,49.46995282173157,-0.0288446917792862,1739141210.0770614,49.46995282173157,3.0942409666033472,1739141210.077065,49.46995282173157,-0.2219992617331398,1739141210.0770688,49.46995282173157,-0.03042983604432492,1739141210.0770724,49.46995282173157,2.287572078003608,1739141210.0770762,49.46995282173157,0.0,1739141210.07708,49.46995282173157,0.21832845379261265,1739141210.0770836,49.46995282173157,3.1239040368055475,1739141210.0770872,49.46995282173157,2.070469373529986 +1739141210.0967784,49.48995280265808,32.95656510448297,1739141210.096783,49.48995280265808,-0.38314560440432643,1739141210.096788,49.48995280265808,79.6361333404995,1739141210.0967937,49.48995280265808,25.479828938176485,1739141210.0967972,49.48995280265808,-0.0288446917792862,1739141210.0968013,49.48995280265808,3.0942409666033472,1739141210.096805,49.48995280265808,-0.2219992617331398,1739141210.096809,49.48995280265808,-0.03042983604432492,1739141210.0968125,49.48995280265808,2.287572078003608,1739141210.0968163,49.48995280265808,0.0,1739141210.0968206,49.48995280265808,0.2171027044736218,1739141210.0968242,49.48995280265808,3.1239040368055475,1739141210.096828,49.48995280265808,2.070469373529986 +1739141210.1150973,49.509952783584595,32.95656510448297,1739141210.1151004,49.509952783584595,-0.38314560440432643,1739141210.1151037,49.509952783584595,79.6361333404995,1739141210.1151068,49.509952783584595,25.479828938176485,1739141210.1151083,49.509952783584595,-0.0288446917792862,1739141210.1151102,49.509952783584595,3.0942409666033472,1739141210.1151116,49.509952783584595,-0.2219992617331398,1739141210.1151133,49.509952783584595,-0.03042983604432492,1739141210.1151145,49.509952783584595,2.287572078003608,1739141210.1151164,49.509952783584595,0.0,1739141210.1151178,49.509952783584595,0.2171027044736218,1739141210.1151192,49.509952783584595,3.1239040368055475,1739141210.1151206,49.509952783584595,2.070469373529986 +1739141210.135199,49.52995276451111,32.95656510448297,1739141210.1352015,49.52995276451111,-0.38314560440432643,1739141210.1352046,49.52995276451111,79.6361333404995,1739141210.1352074,49.52995276451111,25.479828938176485,1739141210.1352088,49.52995276451111,-0.0288446917792862,1739141210.1352108,49.52995276451111,3.0942409666033472,1739141210.1352122,49.52995276451111,-0.2219992617331398,1739141210.1352139,49.52995276451111,-0.03042983604432492,1739141210.135215,49.52995276451111,2.287572078003608,1739141210.1352167,49.52995276451111,0.0,1739141210.1352181,49.52995276451111,0.2171027044736218,1739141210.1352198,49.52995276451111,3.1239040368055475,1739141210.135221,49.52995276451111,2.070469373529986 +1739141210.156891,49.54995274543762,32.95656510448297,1739141210.156895,49.54995274543762,-0.38314560440432643,1739141210.1569002,49.54995274543762,79.6361333404995,1739141210.156906,49.54995274543762,25.479828938176485,1739141210.1569092,49.54995274543762,-0.0288446917792862,1739141210.1569138,49.54995274543762,3.0942409666033472,1739141210.1569176,49.54995274543762,-0.2219992617331398,1739141210.1569214,49.54995274543762,-0.03042983604432492,1739141210.156925,49.54995274543762,2.287572078003608,1739141210.156929,49.54995274543762,0.0,1739141210.1569328,49.54995274543762,0.2171027044736218,1739141210.1569364,49.54995274543762,3.1239040368055475,1739141210.15694,49.54995274543762,2.070469373529986 +1739141210.1766398,49.569952726364136,32.72766589664321,1739141210.1766431,49.569952726364136,-0.37877531254273133,1739141210.1766474,49.569952726364136,79.79873780159598,1739141210.1766522,49.569952726364136,25.24594741912448,1739141210.176655,49.569952726364136,-0.026844374302797253,1739141210.1766586,49.569952726364136,3.094588517171554,1739141210.176662,49.569952726364136,-0.19688453841884956,1739141210.1766653,49.569952726364136,-0.02695246824097909,1739141210.1766684,49.569952726364136,2.3106685921953702,1739141210.1766717,49.569952726364136,0.0,1739141210.176675,49.569952726364136,0.21583247796431154,1739141210.1766782,49.569952726364136,3.120877896734427,1739141210.1766813,49.569952726364136,2.0942312441625615 +1739141210.1970181,49.58995270729065,32.72766589664321,1739141210.1970222,49.58995270729065,-0.37877531254273133,1739141210.1970267,49.58995270729065,79.79873780159598,1739141210.197032,49.58995270729065,25.24594741912448,1739141210.1970348,49.58995270729065,-0.026844374302797253,1739141210.1970382,49.58995270729065,3.094588517171554,1739141210.1970415,49.58995270729065,-0.19688453841884956,1739141210.1970444,49.58995270729065,-0.02695246824097909,1739141210.1970477,49.58995270729065,2.3106685921953702,1739141210.197051,49.58995270729065,0.0,1739141210.1970544,49.58995270729065,0.21643734803280879,1739141210.1970575,49.58995270729065,3.120877896734427,1739141210.1970608,49.58995270729065,2.0942312441625615 +1739141210.214907,49.60995268821716,32.72766589664321,1739141210.2149096,49.60995268821716,-0.37877531254273133,1739141210.2149122,49.60995268821716,79.79873780159598,1739141210.214915,49.60995268821716,25.24594741912448,1739141210.2149165,49.60995268821716,-0.026844374302797253,1739141210.214918,49.60995268821716,3.094588517171554,1739141210.2149193,49.60995268821716,-0.19688453841884956,1739141210.2149208,49.60995268821716,-0.02695246824097909,1739141210.2149217,49.60995268821716,2.3106685921953702,1739141210.2149234,49.60995268821716,0.0,1739141210.2149248,49.60995268821716,0.21643734803280879,1739141210.2149258,49.60995268821716,3.120877896734427,1739141210.2149272,49.60995268821716,2.0942312441625615 +1739141210.2349622,49.62995266914368,32.72766589664321,1739141210.2349656,49.62995266914368,-0.37877531254273133,1739141210.2349691,49.62995266914368,79.79873780159598,1739141210.2349722,49.62995266914368,25.24594741912448,1739141210.2349734,49.62995266914368,-0.026844374302797253,1739141210.2349753,49.62995266914368,3.094588517171554,1739141210.2349768,49.62995266914368,-0.19688453841884956,1739141210.2349782,49.62995266914368,-0.02695246824097909,1739141210.23498,49.62995266914368,2.3106685921953702,1739141210.2349818,49.62995266914368,0.0,1739141210.2349832,49.62995266914368,0.21643734803280879,1739141210.2349846,49.62995266914368,3.120877896734427,1739141210.234986,49.62995266914368,2.0942312441625615 +1739141210.2549,49.64995265007019,32.72766589664321,1739141210.2549026,49.64995265007019,-0.37877531254273133,1739141210.2549055,49.64995265007019,79.79873780159598,1739141210.254908,49.64995265007019,25.24594741912448,1739141210.2549098,49.64995265007019,-0.026844374302797253,1739141210.2549112,49.64995265007019,3.094588517171554,1739141210.2549129,49.64995265007019,-0.19688453841884956,1739141210.254914,49.64995265007019,-0.02695246824097909,1739141210.254915,49.64995265007019,2.3106685921953702,1739141210.2549167,49.64995265007019,0.0,1739141210.254918,49.64995265007019,0.21643734803280879,1739141210.2549195,49.64995265007019,3.120877896734427,1739141210.2549207,49.64995265007019,2.0942312441625615 +1739141210.276904,49.669952630996704,32.72766589664321,1739141210.276908,49.669952630996704,-0.37877531254273133,1739141210.2769127,49.669952630996704,79.79873780159598,1739141210.276918,49.669952630996704,25.24594741912448,1739141210.2769208,49.669952630996704,-0.026844374302797253,1739141210.2769246,49.669952630996704,3.094588517171554,1739141210.2769282,49.669952630996704,-0.19688453841884956,1739141210.2769315,49.669952630996704,-0.02695246824097909,1739141210.2769349,49.669952630996704,2.3106685921953702,1739141210.2769384,49.669952630996704,0.0,1739141210.2769418,49.669952630996704,0.21643734803280879,1739141210.2769454,49.669952630996704,3.120877896734427,1739141210.2769487,49.669952630996704,2.0942312441625615 +1739141210.2950342,49.68995261192322,32.496171241557306,1739141210.295037,49.68995261192322,-0.3736739622278611,1739141210.2950397,49.68995261192322,80.44927706903869,1739141210.2950423,49.68995261192322,24.52442364955291,1739141210.295044,49.68995261192322,-0.019493450563101263,1739141210.2950456,49.68995261192322,3.097192384380865,1739141210.2950473,49.68995261192322,-0.16595252076198036,1739141210.2950485,49.68995261192322,-0.020015899335823706,1739141210.2950494,49.68995261192322,2.3394356464928276,1739141210.295051,49.68995261192322,0.0,1739141210.2950523,49.68995261192322,0.22614737073577607,1739141210.2950535,49.68995261192322,3.11799095095625,1739141210.295055,49.68995261192322,2.1179120984015993 +1739141210.3146486,49.70995259284973,32.496171241557306,1739141210.3146515,49.70995259284973,-0.3736739622278611,1739141210.314654,49.70995259284973,80.44927706903869,1739141210.314657,49.70995259284973,24.52442364955291,1739141210.3146584,49.70995259284973,-0.019493450563101263,1739141210.31466,49.70995259284973,3.097192384380865,1739141210.3146613,49.70995259284973,-0.16595252076198036,1739141210.314663,49.70995259284973,-0.020015899335823706,1739141210.314664,49.70995259284973,2.3394356464928276,1739141210.3146658,49.70995259284973,0.0,1739141210.314667,49.70995259284973,0.22152354809122832,1739141210.314668,49.70995259284973,3.11799095095625,1739141210.3146694,49.70995259284973,2.1179120984015993 +1739141210.3350072,49.729952573776245,32.496171241557306,1739141210.3350103,49.729952573776245,-0.3736739622278611,1739141210.3350136,49.729952573776245,80.44927706903869,1739141210.3350165,49.729952573776245,24.52442364955291,1739141210.335018,49.729952573776245,-0.019493450563101263,1739141210.3350198,49.729952573776245,3.097192384380865,1739141210.335022,49.729952573776245,-0.16595252076198036,1739141210.3350236,49.729952573776245,-0.020015899335823706,1739141210.3350246,49.729952573776245,2.3394356464928276,1739141210.3350265,49.729952573776245,0.0,1739141210.335028,49.729952573776245,0.22152354809122832,1739141210.3350294,49.729952573776245,3.11799095095625,1739141210.3350306,49.729952573776245,2.1179120984015993 +1739141210.3547015,49.74995255470276,32.496171241557306,1739141210.3547046,49.74995255470276,-0.3736739622278611,1739141210.3547077,49.74995255470276,80.44927706903869,1739141210.3547103,49.74995255470276,24.52442364955291,1739141210.3547115,49.74995255470276,-0.019493450563101263,1739141210.3547137,49.74995255470276,3.097192384380865,1739141210.354715,49.74995255470276,-0.16595252076198036,1739141210.3547163,49.74995255470276,-0.020015899335823706,1739141210.3547175,49.74995255470276,2.3394356464928276,1739141210.354719,49.74995255470276,0.0,1739141210.3547206,49.74995255470276,0.22152354809122832,1739141210.3547218,49.74995255470276,3.11799095095625,1739141210.354723,49.74995255470276,2.1179120984015993 +1739141210.3775692,49.77995252609253,32.496171241557306,1739141210.3775728,49.77995252609253,-0.3736739622278611,1739141210.3775775,49.77995252609253,80.44927706903869,1739141210.3775826,49.77995252609253,24.52442364955291,1739141210.3775856,49.77995252609253,-0.019493450563101263,1739141210.3775895,49.77995252609253,3.097192384380865,1739141210.3775928,49.77995252609253,-0.16595252076198036,1739141210.3775961,49.77995252609253,-0.020015899335823706,1739141210.3775995,49.77995252609253,2.3394356464928276,1739141210.377603,49.77995252609253,0.0,1739141210.3776064,49.77995252609253,0.22152354809122832,1739141210.37761,49.77995252609253,3.11799095095625,1739141210.3776133,49.77995252609253,2.1179120984015993 +1739141210.3949597,49.789952516555786,32.26206842545065,1739141210.394962,49.789952516555786,-0.3678519931735096,1739141210.3949652,49.789952516555786,80.47854574302109,1739141210.3949864,49.789952516555786,24.422689179994943,1739141210.394988,49.789952516555786,-0.018469901636317662,1739141210.3949897,49.789952516555786,3.0970545551391524,1739141210.3949912,49.789952516555786,-0.143172557115756,1739141210.3949924,49.789952516555786,-0.017856270387860605,1739141210.3949938,49.789952516555786,2.3608499654000203,1739141210.394995,49.789952516555786,0.0,1739141210.3949964,49.789952516555786,0.2162875126554999,1739141210.3949978,49.789952516555786,3.115300708462461,1739141210.3949988,49.789952516555786,2.1420691012914927 +1739141210.4149635,49.8099524974823,32.26206842545065,1739141210.4149663,49.8099524974823,-0.3678519931735096,1739141210.4149692,49.8099524974823,80.47854574302109,1739141210.414972,49.8099524974823,24.422689179994943,1739141210.4149737,49.8099524974823,-0.018469901636317662,1739141210.4149752,49.8099524974823,3.0970545551391524,1739141210.4149768,49.8099524974823,-0.143172557115756,1739141210.414978,49.8099524974823,-0.017856270387860605,1739141210.4149792,49.8099524974823,2.3608499654000203,1739141210.414981,49.8099524974823,0.0,1739141210.4149823,49.8099524974823,0.2187808641085276,1739141210.4149837,49.8099524974823,3.115300708462461,1739141210.414985,49.8099524974823,2.1420691012914927 +1739141210.434741,49.82995247840881,32.26206842545065,1739141210.4347441,49.82995247840881,-0.3678519931735096,1739141210.434747,49.82995247840881,80.47854574302109,1739141210.4347496,49.82995247840881,24.422689179994943,1739141210.434751,49.82995247840881,-0.018469901636317662,1739141210.4347527,49.82995247840881,3.0970545551391524,1739141210.4347541,49.82995247840881,-0.143172557115756,1739141210.4347553,49.82995247840881,-0.017856270387860605,1739141210.4347565,49.82995247840881,2.3608499654000203,1739141210.4347582,49.82995247840881,0.0,1739141210.4347596,49.82995247840881,0.2187808641085276,1739141210.434761,49.82995247840881,3.115300708462461,1739141210.4347625,49.82995247840881,2.1420691012914927 +1739141210.4550874,49.84995245933533,32.26206842545065,1739141210.4550903,49.84995245933533,-0.3678519931735096,1739141210.4550936,49.84995245933533,80.47854574302109,1739141210.4550962,49.84995245933533,24.422689179994943,1739141210.4550977,49.84995245933533,-0.018469901636317662,1739141210.4550993,49.84995245933533,3.0970545551391524,1739141210.455101,49.84995245933533,-0.143172557115756,1739141210.4551022,49.84995245933533,-0.017856270387860605,1739141210.4551034,49.84995245933533,2.3608499654000203,1739141210.4551048,49.84995245933533,0.0,1739141210.4551065,49.84995245933533,0.2187808641085276,1739141210.455108,49.84995245933533,3.115300708462461,1739141210.4551091,49.84995245933533,2.1420691012914927 +1739141210.4772208,49.86995244026184,32.26206842545065,1739141210.477224,49.86995244026184,-0.3678519931735096,1739141210.4772289,49.86995244026184,80.47854574302109,1739141210.4772336,49.86995244026184,24.422689179994943,1739141210.4772365,49.86995244026184,-0.018469901636317662,1739141210.47724,49.86995244026184,3.0970545551391524,1739141210.4772432,49.86995244026184,-0.143172557115756,1739141210.4772465,49.86995244026184,-0.017856270387860605,1739141210.4772496,49.86995244026184,2.3608499654000203,1739141210.477253,49.86995244026184,0.0,1739141210.4772563,49.86995244026184,0.2187808641085276,1739141210.4772592,49.86995244026184,3.115300708462461,1739141210.4772625,49.86995244026184,2.1420691012914927 +1739141210.4950252,49.889952421188354,32.26206842545065,1739141210.4950278,49.889952421188354,-0.3678519931735096,1739141210.4950306,49.889952421188354,80.47854574302109,1739141210.495033,49.889952421188354,24.422689179994943,1739141210.4950345,49.889952421188354,-0.018469901636317662,1739141210.495036,49.889952421188354,3.0970545551391524,1739141210.4950376,49.889952421188354,-0.143172557115756,1739141210.4950385,49.889952421188354,-0.017856270387860605,1739141210.4950397,49.889952421188354,2.3608499654000203,1739141210.4950411,49.889952421188354,0.0,1739141210.4950426,49.889952421188354,0.2187808641085276,1739141210.4950435,49.889952421188354,3.115300708462461,1739141210.495045,49.889952421188354,2.1420691012914927 +1739141210.514971,49.90995240211487,32.02533377163607,1739141210.5149739,49.90995240211487,-0.36135585993535013,1739141210.5149765,49.90995240211487,81.02715680313679,1739141210.5149791,49.90995240211487,23.802364442554087,1739141210.5149806,49.90995240211487,-0.015,1739141210.5149825,49.90995240211487,3.09949700225216,1739141210.5149837,49.90995240211487,-0.1095415105393789,1739141210.5149856,49.90995240211487,-0.012419677173500818,1739141210.5149865,49.90995240211487,2.3928236872216306,1739141210.514988,49.90995240211487,0.0,1739141210.5149894,49.90995240211487,0.23417554651011016,1739141210.5149906,49.90995240211487,3.112806999630823,1739141210.5149915,49.90995240211487,2.1659789455171885 +1739141210.5348885,49.92995238304138,32.02533377163607,1739141210.534891,49.92995238304138,-0.36135585993535013,1739141210.5348938,49.92995238304138,81.02715680313679,1739141210.5348969,49.92995238304138,23.802364442554087,1739141210.5348983,49.92995238304138,-0.015,1739141210.5349,49.92995238304138,3.09949700225216,1739141210.5349011,49.92995238304138,-0.1095415105393789,1739141210.5349026,49.92995238304138,-0.012419677173500818,1739141210.5349038,49.92995238304138,2.3928236872216306,1739141210.5349054,49.92995238304138,0.0,1739141210.5349066,49.92995238304138,0.22684474170444213,1739141210.5349078,49.92995238304138,3.112806999630823,1739141210.5349092,49.92995238304138,2.1659789455171885 +1739141210.5549085,49.949952363967896,32.02533377163607,1739141210.554911,49.949952363967896,-0.36135585993535013,1739141210.5549138,49.949952363967896,81.02715680313679,1739141210.5549169,49.949952363967896,23.802364442554087,1739141210.554918,49.949952363967896,-0.015,1739141210.55492,49.949952363967896,3.09949700225216,1739141210.5549214,49.949952363967896,-0.1095415105393789,1739141210.5549226,49.949952363967896,-0.012419677173500818,1739141210.5549238,49.949952363967896,2.3928236872216306,1739141210.5549252,49.949952363967896,0.0,1739141210.5549266,49.949952363967896,0.22684474170444213,1739141210.5549278,49.949952363967896,3.112806999630823,1739141210.5549293,49.949952363967896,2.1659789455171885 +1739141210.5761867,49.96995234489441,32.02533377163607,1739141210.5761902,49.96995234489441,-0.36135585993535013,1739141210.5761945,49.96995234489441,81.02715680313679,1739141210.5761995,49.96995234489441,23.802364442554087,1739141210.5762024,49.96995234489441,-0.015,1739141210.576206,49.96995234489441,3.09949700225216,1739141210.5762093,49.96995234489441,-0.1095415105393789,1739141210.5762126,49.96995234489441,-0.012419677173500818,1739141210.5762157,49.96995234489441,2.3928236872216306,1739141210.5762193,49.96995234489441,0.0,1739141210.5762227,49.96995234489441,0.22684474170444213,1739141210.576226,49.96995234489441,3.112806999630823,1739141210.5762293,49.96995234489441,2.1659789455171885 +1739141210.5951061,49.98995232582092,32.02533377163607,1739141210.5951085,49.98995232582092,-0.36135585993535013,1739141210.5951118,49.98995232582092,81.02715680313679,1739141210.5951145,49.98995232582092,23.802364442554087,1739141210.5951161,49.98995232582092,-0.015,1739141210.5951176,49.98995232582092,3.09949700225216,1739141210.595119,49.98995232582092,-0.1095415105393789,1739141210.5951204,49.98995232582092,-0.012419677173500818,1739141210.5951216,49.98995232582092,2.3928236872216306,1739141210.595123,49.98995232582092,0.0,1739141210.5951245,49.98995232582092,0.22684474170444213,1739141210.595126,49.98995232582092,3.112806999630823,1739141210.5951273,49.98995232582092,2.1659789455171885 +1739141210.6148422,50.00995230674744,31.78594734588006,1739141210.614845,50.00995230674744,-0.3542026383662078,1739141210.6148481,50.00995230674744,81.0331414637807,1739141210.6148508,50.00995230674744,23.722048988497782,1739141210.6148522,50.00995230674744,-0.01568151458384067,1739141210.6148539,50.00995230674744,3.0996374528342425,1739141210.614855,50.00995230674744,-0.08750829938725262,1739141210.6148567,50.00995230674744,-0.010317012945258533,1739141210.614858,50.00995230674744,2.4140055267239355,1739141210.6148593,50.00995230674744,0.0,1739141210.614861,50.00995230674744,0.21997887502719893,1739141210.6148624,50.00995230674744,3.1104799761588944,1739141210.6148636,50.00995230674744,2.1907571897410008 +1739141210.6349983,50.02995228767395,31.78594734588006,1739141210.6350014,50.02995228767395,-0.3542026383662078,1739141210.6350045,50.02995228767395,81.0331414637807,1739141210.6350071,50.02995228767395,23.722048988497782,1739141210.6350088,50.02995228767395,-0.01568151458384067,1739141210.6350105,50.02995228767395,3.0996374528342425,1739141210.6350121,50.02995228767395,-0.08750829938725262,1739141210.6350133,50.02995228767395,-0.010317012945258533,1739141210.6350148,50.02995228767395,2.4140055267239355,1739141210.6350164,50.02995228767395,0.0,1739141210.6350176,50.02995228767395,0.22324833698293478,1739141210.635019,50.02995228767395,3.1104799761588944,1739141210.6350203,50.02995228767395,2.1907571897410008 +1739141210.6546853,50.049952268600464,31.78594734588006,1739141210.6546884,50.049952268600464,-0.3542026383662078,1739141210.654691,50.049952268600464,81.0331414637807,1739141210.6546938,50.049952268600464,23.722048988497782,1739141210.6546955,50.049952268600464,-0.01568151458384067,1739141210.6546972,50.049952268600464,3.0996374528342425,1739141210.6546986,50.049952268600464,-0.08750829938725262,1739141210.6546998,50.049952268600464,-0.010317012945258533,1739141210.654701,50.049952268600464,2.4140055267239355,1739141210.654703,50.049952268600464,0.0,1739141210.6547043,50.049952268600464,0.22324833698293478,1739141210.6547055,50.049952268600464,3.1104799761588944,1739141210.6547067,50.049952268600464,2.1907571897410008 +1739141210.6747375,50.06995224952698,31.78594734588006,1739141210.6747406,50.06995224952698,-0.3542026383662078,1739141210.674744,50.06995224952698,81.0331414637807,1739141210.674747,50.06995224952698,23.722048988497782,1739141210.6747482,50.06995224952698,-0.01568151458384067,1739141210.67475,50.06995224952698,3.0996374528342425,1739141210.6747518,50.06995224952698,-0.08750829938725262,1739141210.674753,50.06995224952698,-0.010317012945258533,1739141210.6747544,50.06995224952698,2.4140055267239355,1739141210.674756,50.06995224952698,0.0,1739141210.6747575,50.06995224952698,0.22324833698293478,1739141210.674759,50.06995224952698,3.1104799761588944,1739141210.67476,50.06995224952698,2.1907571897410008 +1739141210.694656,50.08995223045349,31.78594734588006,1739141210.694659,50.08995223045349,-0.3542026383662078,1739141210.694662,50.08995223045349,81.0331414637807,1739141210.694665,50.08995223045349,23.722048988497782,1739141210.6946664,50.08995223045349,-0.01568151458384067,1739141210.6946683,50.08995223045349,3.0996374528342425,1739141210.6946695,50.08995223045349,-0.08750829938725262,1739141210.6946712,50.08995223045349,-0.010317012945258533,1739141210.694672,50.08995223045349,2.4140055267239355,1739141210.694674,50.08995223045349,0.0,1739141210.6946752,50.08995223045349,0.22324833698293478,1739141210.6946764,50.08995223045349,3.1104799761588944,1739141210.6946778,50.08995223045349,2.1907571897410008 +1739141210.7149832,50.109952211380005,31.78594734588006,1739141210.7149856,50.109952211380005,-0.3542026383662078,1739141210.7149887,50.109952211380005,81.0331414637807,1739141210.7149916,50.109952211380005,23.722048988497782,1739141210.714993,50.109952211380005,-0.01568151458384067,1739141210.7149947,50.109952211380005,3.0996374528342425,1739141210.7149963,50.109952211380005,-0.08750829938725262,1739141210.7149975,50.109952211380005,-0.010317012945258533,1739141210.7149985,50.109952211380005,2.4140055267239355,1739141210.7150004,50.109952211380005,0.0,1739141210.7150016,50.109952211380005,0.22324833698293478,1739141210.7150028,50.109952211380005,3.1104799761588944,1739141210.715004,50.109952211380005,2.1907571897410008 +1739141210.7350771,50.12995219230652,31.543873280448572,1739141210.7350802,50.12995219230652,-0.3464285939206153,1739141210.7350836,50.12995219230652,81.03919331541648,1739141210.7350864,50.12995219230652,23.642967416882858,1739141210.735088,50.12995219230652,-0.016595752405978513,1739141210.7350898,50.12995219230652,3.09987067355511,1739141210.7350912,50.12995219230652,-0.06675316294046162,1739141210.7350924,50.12995219230652,-0.00819826602589244,1739141210.7350938,50.12995219230652,2.4341301546506258,1739141210.7350955,50.12995219230652,0.0,1739141210.7350972,50.12995219230652,0.21519125655675259,1739141210.7350986,50.12995219230652,3.108312220035275,1739141210.7350998,50.12995219230652,2.215102191212422 +1739141210.7546642,50.14995217323303,31.543873280448572,1739141210.754667,50.14995217323303,-0.3464285939206153,1739141210.75467,50.14995217323303,81.03919331541648,1739141210.754673,50.14995217323303,23.642967416882858,1739141210.7546744,50.14995217323303,-0.016595752405978513,1739141210.7546759,50.14995217323303,3.09987067355511,1739141210.7546775,50.14995217323303,-0.06675316294046162,1739141210.7546787,50.14995217323303,-0.00819826602589244,1739141210.7546802,50.14995217323303,2.4341301546506258,1739141210.7546816,50.14995217323303,0.0,1739141210.754683,50.14995217323303,0.21902796343820397,1739141210.7546842,50.14995217323303,3.108312220035275,1739141210.7546854,50.14995217323303,2.215102191212422 +1739141210.776823,50.169952154159546,31.543873280448572,1739141210.7768269,50.169952154159546,-0.3464285939206153,1739141210.7768312,50.169952154159546,81.03919331541648,1739141210.7768366,50.169952154159546,23.642967416882858,1739141210.7768395,50.169952154159546,-0.016595752405978513,1739141210.7768433,50.169952154159546,3.09987067355511,1739141210.7768466,50.169952154159546,-0.06675316294046162,1739141210.77685,50.169952154159546,-0.00819826602589244,1739141210.7768533,50.169952154159546,2.4341301546506258,1739141210.776857,50.169952154159546,0.0,1739141210.7768602,50.169952154159546,0.21902796343820397,1739141210.7768636,50.169952154159546,3.108312220035275,1739141210.776867,50.169952154159546,2.215102191212422 +1739141210.7946706,50.18995213508606,31.543873280448572,1739141210.7946737,50.18995213508606,-0.3464285939206153,1739141210.7946768,50.18995213508606,81.03919331541648,1739141210.7946796,50.18995213508606,23.642967416882858,1739141210.7946808,50.18995213508606,-0.016595752405978513,1739141210.7946827,50.18995213508606,3.09987067355511,1739141210.794684,50.18995213508606,-0.06675316294046162,1739141210.7946854,50.18995213508606,-0.00819826602589244,1739141210.7946866,50.18995213508606,2.4341301546506258,1739141210.7946885,50.18995213508606,0.0,1739141210.79469,50.18995213508606,0.21902796343820397,1739141210.794691,50.18995213508606,3.108312220035275,1739141210.7946923,50.18995213508606,2.215102191212422 +1739141210.8149798,50.20995211601257,31.543873280448572,1739141210.8149822,50.20995211601257,-0.3464285939206153,1739141210.8149853,50.20995211601257,81.03919331541648,1739141210.8149881,50.20995211601257,23.642967416882858,1739141210.8149893,50.20995211601257,-0.016595752405978513,1739141210.814991,50.20995211601257,3.09987067355511,1739141210.8149924,50.20995211601257,-0.06675316294046162,1739141210.814994,50.20995211601257,-0.00819826602589244,1739141210.8149953,50.20995211601257,2.4341301546506258,1739141210.8149967,50.20995211601257,0.0,1739141210.814998,50.20995211601257,0.21902796343820397,1739141210.8149993,50.20995211601257,3.108312220035275,1739141210.8150005,50.20995211601257,2.215102191212422 +1739141210.8349903,50.22995209693909,31.299153695728762,1739141210.8349931,50.22995209693909,-0.3380480450186756,1739141210.8349962,50.22995209693909,81.5801064353542,1739141210.834999,50.22995209693909,23.030137247959253,1739141210.8350005,50.22995209693909,-0.021332062518895786,1739141210.8350027,50.22995209693909,3.1033098365459972,1739141210.835004,50.22995209693909,-0.024413091268395543,1739141210.8350055,50.22995209693909,-0.0027380382845920443,1739141210.8350067,50.22995209693909,2.47570572147729,1739141210.8350081,50.22995209693909,0.0,1739141210.8350098,50.22995209693909,0.2526198981076075,1739141210.835011,50.22995209693909,3.106260034964197,1739141210.8350124,50.22995209693909,2.2390819907268495 +1739141210.8549566,50.2499520778656,31.299153695728762,1739141210.8549592,50.2499520778656,-0.3380480450186756,1739141210.8549619,50.2499520778656,81.5801064353542,1739141210.8549647,50.2499520778656,23.030137247959253,1739141210.8549662,50.2499520778656,-0.021332062518895786,1739141210.8549678,50.2499520778656,3.1033098365459972,1739141210.8549693,50.2499520778656,-0.024413091268395543,1739141210.8549705,50.2499520778656,-0.0027380382845920443,1739141210.8549716,50.2499520778656,2.47570572147729,1739141210.854973,50.2499520778656,0.0,1739141210.8549747,50.2499520778656,0.2366237307504404,1739141210.8549762,50.2499520778656,3.106260034964197,1739141210.8549776,50.2499520778656,2.2390819907268495 +1739141210.8750548,50.269952058792114,31.299153695728762,1739141210.875058,50.269952058792114,-0.3380480450186756,1739141210.875061,50.269952058792114,81.5801064353542,1739141210.875064,50.269952058792114,23.030137247959253,1739141210.8750653,50.269952058792114,-0.021332062518895786,1739141210.875067,50.269952058792114,3.1033098365459972,1739141210.8750684,50.269952058792114,-0.024413091268395543,1739141210.8750696,50.269952058792114,-0.0027380382845920443,1739141210.875071,50.269952058792114,2.47570572147729,1739141210.8750725,50.269952058792114,0.0,1739141210.8750741,50.269952058792114,0.2366237307504404,1739141210.8750756,50.269952058792114,3.106260034964197,1739141210.8750768,50.269952058792114,2.2390819907268495 +1739141210.89485,50.28995203971863,31.299153695728762,1739141210.8948536,50.28995203971863,-0.3380480450186756,1739141210.8948567,50.28995203971863,81.5801064353542,1739141210.8948598,50.28995203971863,23.030137247959253,1739141210.8948612,50.28995203971863,-0.021332062518895786,1739141210.8948631,50.28995203971863,3.1033098365459972,1739141210.8948643,50.28995203971863,-0.024413091268395543,1739141210.894866,50.28995203971863,-0.0027380382845920443,1739141210.8948674,50.28995203971863,2.47570572147729,1739141210.8948693,50.28995203971863,0.0,1739141210.8948708,50.28995203971863,0.2366237307504404,1739141210.8948724,50.28995203971863,3.106260034964197,1739141210.8948736,50.28995203971863,2.2390819907268495 +1739141210.915865,50.30995202064514,31.299153695728762,1739141210.9158692,50.30995202064514,-0.3380480450186756,1739141210.9158747,50.30995202064514,81.5801064353542,1739141210.9158792,50.30995202064514,23.030137247959253,1739141210.9158812,50.30995202064514,-0.021332062518895786,1739141210.9158838,50.30995202064514,3.1033098365459972,1739141210.9158862,50.30995202064514,-0.024413091268395543,1739141210.9158878,50.30995202064514,-0.0027380382845920443,1739141210.9158897,50.30995202064514,2.47570572147729,1739141210.915892,50.30995202064514,0.0,1739141210.9158943,50.30995202064514,0.2366237307504404,1739141210.9158962,50.30995202064514,3.106260034964197,1739141210.915898,50.30995202064514,2.2390819907268495 +1739141210.936553,50.329952001571655,31.299153695728762,1739141210.9365563,50.329952001571655,-0.3380480450186756,1739141210.9365604,50.329952001571655,81.5801064353542,1739141210.936564,50.329952001571655,23.030137247959253,1739141210.936566,50.329952001571655,-0.021332062518895786,1739141210.9365685,50.329952001571655,3.1033098365459972,1739141210.9365706,50.329952001571655,-0.024413091268395543,1739141210.936572,50.329952001571655,-0.0027380382845920443,1739141210.936574,50.329952001571655,2.47570572147729,1739141210.936576,50.329952001571655,0.0,1739141210.9365778,50.329952001571655,0.2366237307504404,1739141210.9365795,50.329952001571655,3.106260034964197,1739141210.9365811,50.329952001571655,2.2390819907268495 +1739141210.9554985,50.34995198249817,31.051711775234367,1739141210.9555018,50.34995198249817,-0.32908956096894926,1739141210.9555056,50.34995198249817,81.61772656575339,1739141210.9555094,50.34995198249817,22.914442230034958,1739141210.9555113,50.34995198249817,-0.022,1739141210.9555137,50.34995198249817,3.103871904942301,1739141210.9555154,50.34995198249817,-0.004553845377249382,1739141210.9555173,50.34995198249817,-0.0005274290021621095,1739141210.9555187,50.34995198249817,2.4954502996071635,1739141210.9555209,50.34995198249817,0.0,1739141210.9555225,50.34995198249817,0.22463193279491736,1739141210.9555244,50.34995198249817,3.1044311350676796,1739141210.955526,50.34995198249817,2.26510798398084 +1739141210.9757254,50.36995196342468,31.051711775234367,1739141210.97573,50.36995196342468,-0.32908956096894926,1739141210.975734,50.36995196342468,81.61772656575339,1739141210.9757383,50.36995196342468,22.914442230034958,1739141210.9757407,50.36995196342468,-0.022,1739141210.975744,50.36995196342468,3.103871904942301,1739141210.9757464,50.36995196342468,-0.004553845377249382,1739141210.9757488,50.36995196342468,-0.0005274290021621095,1739141210.9757514,50.36995196342468,2.4954502996071635,1739141210.975754,50.36995196342468,0.0,1739141210.975757,50.36995196342468,0.23034231562632357,1739141210.975759,50.36995196342468,3.1044311350676796,1739141210.9757612,50.36995196342468,2.26510798398084 +1739141210.9958186,50.389951944351196,31.051711775234367,1739141210.9958227,50.389951944351196,-0.32908956096894926,1739141210.995827,50.389951944351196,81.61772656575339,1739141210.9958315,50.389951944351196,22.914442230034958,1739141210.9958334,50.389951944351196,-0.022,1739141210.995836,50.389951944351196,3.103871904942301,1739141210.9958382,50.389951944351196,-0.004553845377249382,1739141210.9958408,50.389951944351196,-0.0005274290021621095,1739141210.9958432,50.389951944351196,2.4954502996071635,1739141210.9958456,50.389951944351196,0.0,1739141210.9958482,50.389951944351196,0.23034231562632357,1739141210.9958506,50.389951944351196,3.1044311350676796,1739141210.9958527,50.389951944351196,2.26510798398084 +1739141211.0166168,50.40995192527771,31.051711775234367,1739141211.016622,50.40995192527771,-0.32908956096894926,1739141211.0166276,50.40995192527771,81.61772656575339,1739141211.0166342,50.40995192527771,22.914442230034958,1739141211.0166378,50.40995192527771,-0.022,1739141211.0166426,50.40995192527771,3.103871904942301,1739141211.0166457,50.40995192527771,-0.004553845377249382,1739141211.0166488,50.40995192527771,-0.0005274290021621095,1739141211.0166516,50.40995192527771,2.4954502996071635,1739141211.0166554,50.40995192527771,0.0,1739141211.016659,50.40995192527771,0.23034231562632357,1739141211.0166624,50.40995192527771,3.1044311350676796,1739141211.0166662,50.40995192527771,2.26510798398084 +1739141211.0358198,50.429951906204224,31.051711775234367,1739141211.0358233,50.429951906204224,-0.32908956096894926,1739141211.0358276,50.429951906204224,81.61772656575339,1739141211.0358324,50.429951906204224,22.914442230034958,1739141211.0358343,50.429951906204224,-0.022,1739141211.0358372,50.429951906204224,3.103871904942301,1739141211.0358398,50.429951906204224,-0.004553845377249382,1739141211.035842,50.429951906204224,-0.0005274290021621095,1739141211.0358446,50.429951906204224,2.4954502996071635,1739141211.035847,50.429951906204224,0.0,1739141211.0358496,50.429951906204224,0.23034231562632357,1739141211.0358517,50.429951906204224,3.1044311350676796,1739141211.035854,50.429951906204224,2.26510798398084 +1739141211.0574872,50.44995188713074,30.80147276881152,1739141211.0574915,50.44995188713074,-0.31959058095160575,1739141211.057496,50.44995188713074,82.2793925331513,1739141211.0575016,50.44995188713074,22.177366978331836,1739141211.0575042,50.44995188713074,-0.018985548480812714,1739141211.057508,50.44995188713074,3.1067503885771983,1739141211.0575116,50.44995188713074,0.03467846172035224,1739141211.0575154,50.44995188713074,0.0035765586839486816,1739141211.0575185,50.44995188713074,2.465560949155883,1739141211.057522,50.44995188713074,0.0,1739141211.0575259,50.44995188713074,0.1252833844467951,1739141211.057529,50.44995188713074,3.102731710184579,1739141211.0575323,50.44995188713074,2.2902494772514306 +1739141211.0861182,50.459951877593994,30.80147276881152,1739141211.0861225,50.459951877593994,-0.31959058095160575,1739141211.0861278,50.459951877593994,82.2793925331513,1739141211.0861332,50.459951877593994,22.177366978331836,1739141211.0861368,50.459951877593994,-0.018985548480812714,1739141211.0861406,50.459951877593994,3.1067503885771983,1739141211.086144,50.459951877593994,0.03467846172035224,1739141211.086147,50.459951877593994,0.0035765586839486816,1739141211.0861502,50.459951877593994,2.465560949155883,1739141211.0861537,50.459951877593994,0.0,1739141211.086157,50.459951877593994,0.17531147190445262,1739141211.0861602,50.459951877593994,3.102731710184579,1739141211.0861633,50.459951877593994,2.2902494772514306 +1739141211.1240819,50.489951848983765,30.80147276881152,1739141211.124087,50.489951848983765,-0.31959058095160575,1739141211.1240928,50.489951848983765,82.2793925331513,1739141211.124099,50.489951848983765,22.177366978331836,1739141211.124102,50.489951848983765,-0.018985548480812714,1739141211.1241064,50.489951848983765,3.1067503885771983,1739141211.1241102,50.489951848983765,0.03467846172035224,1739141211.1241133,50.489951848983765,0.0035765586839486816,1739141211.124116,50.489951848983765,2.465560949155883,1739141211.1241198,50.489951848983765,0.0,1739141211.1241229,50.489951848983765,0.17531147190445262,1739141211.124127,50.489951848983765,3.102731710184579,1739141211.1241302,50.489951848983765,2.2902494772514306 +1739141211.149396,50.519951820373535,30.80147276881152,1739141211.1493995,50.519951820373535,-0.31959058095160575,1739141211.1494038,50.519951820373535,82.2793925331513,1739141211.149409,50.519951820373535,22.177366978331836,1739141211.1494122,50.519951820373535,-0.018985548480812714,1739141211.149416,50.519951820373535,3.1067503885771983,1739141211.149419,50.519951820373535,0.03467846172035224,1739141211.1494224,50.519951820373535,0.0035765586839486816,1739141211.1494257,50.519951820373535,2.465560949155883,1739141211.149429,50.519951820373535,0.0,1739141211.1494324,50.519951820373535,0.17531147190445262,1739141211.1494358,50.519951820373535,3.102731710184579,1739141211.1494389,50.519951820373535,2.2902494772514306 +1739141211.1669204,50.53995180130005,30.80147276881152,1739141211.1669233,50.53995180130005,-0.31959058095160575,1739141211.1669264,50.53995180130005,82.2793925331513,1739141211.1669292,50.53995180130005,22.177366978331836,1739141211.1669307,50.53995180130005,-0.018985548480812714,1739141211.1669326,50.53995180130005,3.1067503885771983,1739141211.1669338,50.53995180130005,0.03467846172035224,1739141211.166935,50.53995180130005,0.0035765586839486816,1739141211.1669364,50.53995180130005,2.465560949155883,1739141211.166938,50.53995180130005,0.0,1739141211.1669395,50.53995180130005,0.17531147190445262,1739141211.1669407,50.53995180130005,3.102731710184579,1739141211.1669421,50.53995180130005,2.2902494772514306 +1739141211.187429,50.55995178222656,30.548831687902258,1739141211.1874316,50.55995178222656,-0.30958711917897563,1739141211.1874344,50.55995178222656,82.29227722827767,1739141211.187437,50.55995178222656,22.108395382151627,1739141211.1874382,50.55995178222656,-0.018375180373023253,1739141211.1874402,50.55995178222656,3.107104333438473,1739141211.1874413,50.55995178222656,0.05000348960124083,1739141211.187443,50.55995178222656,0.005384118403794028,1739141211.187444,50.55995178222656,2.450493262766769,1739141211.1874459,50.55995178222656,0.0,1739141211.187447,50.55995178222656,0.11085247659663158,1739141211.187448,50.55995178222656,3.101183543974923,1739141211.1874497,50.55995178222656,2.3089460111663653 +1739141211.206802,50.579951763153076,30.548831687902258,1739141211.2068043,50.579951763153076,-0.30958711917897563,1739141211.2068071,50.579951763153076,82.29227722827767,1739141211.2068095,50.579951763153076,22.108395382151627,1739141211.206811,50.579951763153076,-0.018375180373023253,1739141211.2068126,50.579951763153076,3.107104333438473,1739141211.206814,50.579951763153076,0.05000348960124083,1739141211.2068152,50.579951763153076,0.005384118403794028,1739141211.2068162,50.579951763153076,2.450493262766769,1739141211.2068179,50.579951763153076,0.0,1739141211.2068193,50.579951763153076,0.1415472516004037,1739141211.2068202,50.579951763153076,3.101183543974923,1739141211.2068217,50.579951763153076,2.3089460111663653 +1739141211.226824,50.59995174407959,30.548831687902258,1739141211.2268264,50.59995174407959,-0.30958711917897563,1739141211.2268293,50.59995174407959,82.29227722827767,1739141211.2268322,50.59995174407959,22.108395382151627,1739141211.2268333,50.59995174407959,-0.018375180373023253,1739141211.2268353,50.59995174407959,3.107104333438473,1739141211.2268364,50.59995174407959,0.05000348960124083,1739141211.2268379,50.59995174407959,0.005384118403794028,1739141211.226839,50.59995174407959,2.450493262766769,1739141211.2268405,50.59995174407959,0.0,1739141211.226842,50.59995174407959,0.1415472516004037,1739141211.226843,50.59995174407959,3.101183543974923,1739141211.2268443,50.59995174407959,2.3089460111663653 +1739141211.2473207,50.6199517250061,30.548831687902258,1739141211.2473233,50.6199517250061,-0.30958711917897563,1739141211.2473264,50.6199517250061,82.29227722827767,1739141211.247329,50.6199517250061,22.108395382151627,1739141211.2473302,50.6199517250061,-0.018375180373023253,1739141211.247332,50.6199517250061,3.107104333438473,1739141211.2473333,50.6199517250061,0.05000348960124083,1739141211.2473347,50.6199517250061,0.005384118403794028,1739141211.247336,50.6199517250061,2.450493262766769,1739141211.2473376,50.6199517250061,0.0,1739141211.247339,50.6199517250061,0.1415472516004037,1739141211.2473402,50.6199517250061,3.101183543974923,1739141211.2473416,50.6199517250061,2.3089460111663653 +1739141211.2670197,50.63995170593262,30.548831687902258,1739141211.2670226,50.63995170593262,-0.30958711917897563,1739141211.2670255,50.63995170593262,82.29227722827767,1739141211.2670283,50.63995170593262,22.108395382151627,1739141211.2670295,50.63995170593262,-0.018375180373023253,1739141211.2670312,50.63995170593262,3.107104333438473,1739141211.2670329,50.63995170593262,0.05000348960124083,1739141211.267034,50.63995170593262,0.005384118403794028,1739141211.2670355,50.63995170593262,2.450493262766769,1739141211.267037,50.63995170593262,0.0,1739141211.2670383,50.63995170593262,0.1415472516004037,1739141211.2670398,50.63995170593262,3.101183543974923,1739141211.2670407,50.63995170593262,2.3089460111663653 +1739141211.2870302,50.65995168685913,30.548831687902258,1739141211.2870328,50.65995168685913,-0.30958711917897563,1739141211.2870357,50.65995168685913,82.29227722827767,1739141211.2870386,50.65995168685913,22.108395382151627,1739141211.28704,50.65995168685913,-0.018375180373023253,1739141211.2870414,50.65995168685913,3.107104333438473,1739141211.287043,50.65995168685913,0.05000348960124083,1739141211.2870445,50.65995168685913,0.005384118403794028,1739141211.287046,50.65995168685913,2.450493262766769,1739141211.2870474,50.65995168685913,0.0,1739141211.2870488,50.65995168685913,0.1415472516004037,1739141211.28705,50.65995168685913,3.101183543974923,1739141211.2870512,50.65995168685913,2.3089460111663653 +1739141211.307271,50.679951667785645,30.294282008521726,1739141211.3072743,50.679951667785645,-0.2991242808860033,1739141211.3072777,50.679951667785645,82.30525926192607,1739141211.3072808,50.679951667785645,22.04889231192005,1739141211.3072827,50.679951667785645,-0.01784725278500044,1739141211.3072848,50.679951667785645,3.107492628494537,1739141211.3072865,50.679951667785645,0.06410946227348116,1739141211.3072882,50.679951667785645,0.0072336091571328165,1739141211.3072896,50.679951667785645,2.4367055607365313,1739141211.3072917,50.679951667785645,0.0,1739141211.3072934,50.679951667785645,0.08561946325858516,1739141211.307295,50.679951667785645,3.099721881512458,1739141211.3072965,50.679951667785645,2.3244538040111813 +1739141211.3276944,50.69995164871216,30.294282008521726,1739141211.3276975,50.69995164871216,-0.2991242808860033,1739141211.3277009,50.69995164871216,82.30525926192607,1739141211.327704,50.69995164871216,22.04889231192005,1739141211.3277056,50.69995164871216,-0.01784725278500044,1739141211.3277075,50.69995164871216,3.107492628494537,1739141211.3277094,50.69995164871216,0.06410946227348116,1739141211.3277109,50.69995164871216,0.0072336091571328165,1739141211.3277123,50.69995164871216,2.4367055607365313,1739141211.3277142,50.69995164871216,0.0,1739141211.3277164,50.69995164871216,0.11225175672535004,1739141211.3277178,50.69995164871216,3.099721881512458,1739141211.3277194,50.69995164871216,2.3244538040111813 +1739141211.3479493,50.71995162963867,30.294282008521726,1739141211.3479524,50.71995162963867,-0.2991242808860033,1739141211.347956,50.71995162963867,82.30525926192607,1739141211.347959,50.71995162963867,22.04889231192005,1739141211.347961,50.71995162963867,-0.01784725278500044,1739141211.3479626,50.71995162963867,3.107492628494537,1739141211.3479645,50.71995162963867,0.06410946227348116,1739141211.3479662,50.71995162963867,0.0072336091571328165,1739141211.3479679,50.71995162963867,2.4367055607365313,1739141211.3479695,50.71995162963867,0.0,1739141211.3479714,50.71995162963867,0.11225175672535004,1739141211.3479729,50.71995162963867,3.099721881512458,1739141211.3479745,50.71995162963867,2.3244538040111813 +1739141211.3673103,50.739951610565186,30.294282008521726,1739141211.3673139,50.739951610565186,-0.2991242808860033,1739141211.3673172,50.739951610565186,82.30525926192607,1739141211.3673203,50.739951610565186,22.04889231192005,1739141211.3673222,50.739951610565186,-0.01784725278500044,1739141211.367324,50.739951610565186,3.107492628494537,1739141211.3673258,50.739951610565186,0.06410946227348116,1739141211.3673277,50.739951610565186,0.0072336091571328165,1739141211.3673294,50.739951610565186,2.4367055607365313,1739141211.3673313,50.739951610565186,0.0,1739141211.367333,50.739951610565186,0.11225175672535004,1739141211.3673344,50.739951610565186,3.099721881512458,1739141211.367336,50.739951610565186,2.3244538040111813 +1739141211.389306,50.7599515914917,30.294282008521726,1739141211.3893108,50.7599515914917,-0.2991242808860033,1739141211.3893166,50.7599515914917,82.30525926192607,1739141211.389323,50.7599515914917,22.04889231192005,1739141211.3893266,50.7599515914917,-0.01784725278500044,1739141211.389331,50.7599515914917,3.107492628494537,1739141211.3893354,50.7599515914917,0.06410946227348116,1739141211.3893394,50.7599515914917,0.0072336091571328165,1739141211.3893433,50.7599515914917,2.4367055607365313,1739141211.3893476,50.7599515914917,0.0,1739141211.3893518,50.7599515914917,0.11225175672535004,1739141211.3893561,50.7599515914917,3.099721881512458,1739141211.3893602,50.7599515914917,2.3244538040111813 +1739141211.4074156,50.77995157241821,30.038243997454714,1739141211.4074192,50.77995157241821,-0.2882346847898347,1739141211.4074237,50.77995157241821,82.69149982631717,1739141211.407427,50.77995157241821,21.62734763191268,1739141211.4074295,50.77995157241821,-0.016,1739141211.4074316,50.77995157241821,3.109237044054286,1739141211.4074333,50.77995157241821,0.0917035239002295,1739141211.407435,50.77995157241821,0.009945035876174327,1739141211.4074364,50.77995157241821,2.409958005661595,1739141211.4074383,50.77995157241821,0.0,1739141211.4074404,50.77995157241821,0.03871673107133428,1739141211.4074416,50.77995157241821,3.0983395919076964,1739141211.4074438,50.77995157241821,2.336224578215026 +1739141211.4313116,50.79995155334473,30.038243997454714,1739141211.4313214,50.79995155334473,-0.2882346847898347,1739141211.4313319,50.79995155334473,82.69149982631717,1739141211.4313416,50.79995155334473,21.62734763191268,1739141211.4313467,50.79995155334473,-0.016,1739141211.431353,50.79995155334473,3.109237044054286,1739141211.431358,50.79995155334473,0.0917035239002295,1739141211.4313629,50.79995155334473,0.009945035876174327,1739141211.4313676,50.79995155334473,2.409958005661595,1739141211.4313736,50.79995155334473,0.0,1739141211.4313788,50.79995155334473,0.07373342744656863,1739141211.4313834,50.79995155334473,3.0983395919076964,1739141211.431388,50.79995155334473,2.336224578215026 +1739141211.4526048,50.81995153427124,30.038243997454714,1739141211.452614,50.81995153427124,-0.2882346847898347,1739141211.4526248,50.81995153427124,82.69149982631717,1739141211.4526346,50.81995153427124,21.62734763191268,1739141211.4526396,50.81995153427124,-0.016,1739141211.452645,50.81995153427124,3.109237044054286,1739141211.45265,50.81995153427124,0.0917035239002295,1739141211.4526548,50.81995153427124,0.009945035876174327,1739141211.4526591,50.81995153427124,2.409958005661595,1739141211.4526646,50.81995153427124,0.0,1739141211.4526696,50.81995153427124,0.07373342744656863,1739141211.4526744,50.81995153427124,3.0983395919076964,1739141211.452679,50.81995153427124,2.336224578215026 +1739141211.470843,50.839951515197754,30.038243997454714,1739141211.4708524,50.839951515197754,-0.2882346847898347,1739141211.4708622,50.839951515197754,82.69149982631717,1739141211.4708714,50.839951515197754,21.62734763191268,1739141211.4708765,50.839951515197754,-0.016,1739141211.4708827,50.839951515197754,3.109237044054286,1739141211.4708874,50.839951515197754,0.0917035239002295,1739141211.470892,50.839951515197754,0.009945035876174327,1739141211.4708967,50.839951515197754,2.409958005661595,1739141211.4709027,50.839951515197754,0.0,1739141211.4709077,50.839951515197754,0.07373342744656863,1739141211.4709125,50.839951515197754,3.0983395919076964,1739141211.4709167,50.839951515197754,2.336224578215026 +1739141211.491796,50.85995149612427,30.038243997454714,1739141211.491811,50.85995149612427,-0.2882346847898347,1739141211.4918284,50.85995149612427,82.69149982631717,1739141211.4918525,50.85995149612427,21.62734763191268,1739141211.4918587,50.85995149612427,-0.016,1739141211.4918647,50.85995149612427,3.109237044054286,1739141211.4918692,50.85995149612427,0.0917035239002295,1739141211.4918733,50.85995149612427,0.009945035876174327,1739141211.4918773,50.85995149612427,2.409958005661595,1739141211.4918826,50.85995149612427,0.0,1739141211.4918869,50.85995149612427,0.07373342744656863,1739141211.4918911,50.85995149612427,3.0983395919076964,1739141211.4918952,50.85995149612427,2.336224578215026 +1739141211.51508,50.87995147705078,30.038243997454714,1739141211.515086,50.87995147705078,-0.2882346847898347,1739141211.5150921,50.87995147705078,82.69149982631717,1739141211.5150986,50.87995147705078,21.62734763191268,1739141211.5151017,50.87995147705078,-0.016,1739141211.5151055,50.87995147705078,3.109237044054286,1739141211.5151088,50.87995147705078,0.0917035239002295,1739141211.5151122,50.87995147705078,0.009945035876174327,1739141211.515115,50.87995147705078,2.409958005661595,1739141211.5151188,50.87995147705078,0.0,1739141211.515122,50.87995147705078,0.07373342744656863,1739141211.515125,50.87995147705078,3.0983395919076964,1739141211.515128,50.87995147705078,2.336224578215026 +1739141211.5331593,50.90995144844055,29.781168514264245,1739141211.5331635,50.90995144844055,-0.2769558288824374,1739141211.5331688,50.90995144844055,82.69792671339692,1739141211.5331743,50.90995144844055,21.598787870489456,1739141211.5331767,50.90995144844055,-0.016,1739141211.53318,50.90995144844055,3.1097110510060664,1739141211.5331821,50.90995144844055,0.10369647959180932,1739141211.5331845,50.90995144844055,0.011882890521034807,1739141211.533187,50.90995144844055,2.3984246836713083,1739141211.5331898,50.90995144844055,0.0,1739141211.5331922,50.90995144844055,0.03763069448754232,1739141211.5331945,50.90995144844055,3.097044009487512,1739141211.5331967,50.90995144844055,2.3436022029961814 +1739141211.5538208,50.929951429367065,29.781168514264245,1739141211.5538247,50.929951429367065,-0.2769558288824374,1739141211.553829,50.929951429367065,82.69792671339692,1739141211.5538325,50.929951429367065,21.598787870489456,1739141211.5538344,50.929951429367065,-0.016,1739141211.5538366,50.929951429367065,3.1097110510060664,1739141211.5538385,50.929951429367065,0.10369647959180932,1739141211.5538404,50.929951429367065,0.011882890521034807,1739141211.553842,50.929951429367065,2.3984246836713083,1739141211.5538442,50.929951429367065,0.0,1739141211.5538461,50.929951429367065,0.05482248067512696,1739141211.553848,50.929951429367065,3.097044009487512,1739141211.5538497,50.929951429367065,2.3436022029961814 +1739141211.572859,50.94995141029358,29.781168514264245,1739141211.572862,50.94995141029358,-0.2769558288824374,1739141211.572865,50.94995141029358,82.69792671339692,1739141211.5728683,50.94995141029358,21.598787870489456,1739141211.5728698,50.94995141029358,-0.016,1739141211.572872,50.94995141029358,3.1097110510060664,1739141211.5728738,50.94995141029358,0.10369647959180932,1739141211.5728753,50.94995141029358,0.011882890521034807,1739141211.5728765,50.94995141029358,2.3984246836713083,1739141211.5728784,50.94995141029358,0.0,1739141211.5728798,50.94995141029358,0.05482248067512696,1739141211.5728812,50.94995141029358,3.097044009487512,1739141211.572883,50.94995141029358,2.3436022029961814 +1739141211.5919955,50.96995139122009,29.781168514264245,1739141211.5919993,50.96995139122009,-0.2769558288824374,1739141211.5920033,50.96995139122009,82.69792671339692,1739141211.5920064,50.96995139122009,21.598787870489456,1739141211.5920079,50.96995139122009,-0.016,1739141211.59201,50.96995139122009,3.1097110510060664,1739141211.5920115,50.96995139122009,0.10369647959180932,1739141211.5920131,50.96995139122009,0.011882890521034807,1739141211.5920146,50.96995139122009,2.3984246836713083,1739141211.5920165,50.96995139122009,0.0,1739141211.5920181,50.96995139122009,0.05482248067512696,1739141211.5920198,50.96995139122009,3.097044009487512,1739141211.5920212,50.96995139122009,2.3436022029961814 +1739141211.6116028,50.989951372146606,29.781168514264245,1739141211.6116054,50.989951372146606,-0.2769558288824374,1739141211.6116085,50.989951372146606,82.69792671339692,1739141211.6116111,50.989951372146606,21.598787870489456,1739141211.6116123,50.989951372146606,-0.016,1739141211.6116142,50.989951372146606,3.1097110510060664,1739141211.6116154,50.989951372146606,0.10369647959180932,1739141211.6116326,50.989951372146606,0.011882890521034807,1739141211.611634,50.989951372146606,2.3984246836713083,1739141211.6116354,50.989951372146606,0.0,1739141211.6116366,50.989951372146606,0.05482248067512696,1739141211.6116383,50.989951372146606,3.097044009487512,1739141211.6116395,50.989951372146606,2.3436022029961814 +1739141211.6324108,51.00995135307312,29.523325389327233,1739141211.6324134,51.00995135307312,-0.26531862524735494,1739141211.6324165,51.00995135307312,83.26917166206937,1739141211.632419,51.00995135307312,21.009485691837746,1739141211.6324203,51.00995135307312,-0.017,1739141211.632422,51.00995135307312,3.112434452763302,1739141211.6324232,51.00995135307312,0.14113028401558383,1739141211.6324246,51.00995135307312,0.014940241503843236,1739141211.6324258,51.00995135307312,2.362779353511363,1739141211.632427,51.00995135307312,0.0,1739141211.6324282,51.00995135307312,-0.02472158824267072,1739141211.6324296,51.00995135307312,3.095864167830999,1739141211.6324306,51.00995135307312,2.3496227947761503 +1739141211.6520543,51.029951333999634,29.523325389327233,1739141211.6520574,51.029951333999634,-0.26531862524735494,1739141211.652061,51.029951333999634,83.26917166206937,1739141211.652064,51.029951333999634,21.009485691837746,1739141211.6520815,51.029951333999634,-0.017,1739141211.6520832,51.029951333999634,3.112434452763302,1739141211.6520846,51.029951333999634,0.14113028401558383,1739141211.652086,51.029951333999634,0.014940241503843236,1739141211.6520872,51.029951333999634,2.362779353511363,1739141211.6520889,51.029951333999634,0.0,1739141211.6521122,51.029951333999634,0.013156558735212709,1739141211.6521137,51.029951333999634,3.095864167830999,1739141211.652115,51.029951333999634,2.3496227947761503 +1739141211.6713555,51.04995131492615,29.523325389327233,1739141211.6713576,51.04995131492615,-0.26531862524735494,1739141211.6713603,51.04995131492615,83.26917166206937,1739141211.6713629,51.04995131492615,21.009485691837746,1739141211.671364,51.04995131492615,-0.017,1739141211.671366,51.04995131492615,3.112434452763302,1739141211.6713674,51.04995131492615,0.14113028401558383,1739141211.6713686,51.04995131492615,0.014940241503843236,1739141211.67137,51.04995131492615,2.362779353511363,1739141211.6713715,51.04995131492615,0.0,1739141211.671373,51.04995131492615,0.013156558735212709,1739141211.671374,51.04995131492615,3.095864167830999,1739141211.6713753,51.04995131492615,2.3496227947761503 +1739141211.691518,51.06995129585266,29.523325389327233,1739141211.6915202,51.06995129585266,-0.26531862524735494,1739141211.6915228,51.06995129585266,83.26917166206937,1739141211.691526,51.06995129585266,21.009485691837746,1739141211.691527,51.06995129585266,-0.017,1739141211.6915286,51.06995129585266,3.112434452763302,1739141211.69153,51.06995129585266,0.14113028401558383,1739141211.6915312,51.06995129585266,0.014940241503843236,1739141211.6915324,51.06995129585266,2.362779353511363,1739141211.6915338,51.06995129585266,0.0,1739141211.691535,51.06995129585266,0.013156558735212709,1739141211.6915364,51.06995129585266,3.095864167830999,1739141211.6915376,51.06995129585266,2.3496227947761503 +1739141211.7113369,51.089951276779175,29.523325389327233,1739141211.7113392,51.089951276779175,-0.26531862524735494,1739141211.711342,51.089951276779175,83.26917166206937,1739141211.7113447,51.089951276779175,21.009485691837746,1739141211.711346,51.089951276779175,-0.017,1739141211.7113478,51.089951276779175,3.112434452763302,1739141211.711349,51.089951276779175,0.14113028401558383,1739141211.7113504,51.089951276779175,0.014940241503843236,1739141211.7113519,51.089951276779175,2.362779353511363,1739141211.7113533,51.089951276779175,0.0,1739141211.7113547,51.089951276779175,0.013156558735212709,1739141211.711356,51.089951276779175,3.095864167830999,1739141211.711357,51.089951276779175,2.3496227947761503 +1739141211.7330263,51.10995125770569,29.26509404877087,1739141211.7330296,51.10995125770569,-0.2533751636981316,1739141211.7330341,51.10995125770569,83.83882693991468,1739141211.7330394,51.10995125770569,20.436550280501024,1739141211.7330425,51.10995125770569,-0.017,1739141211.733046,51.10995125770569,3.1148250786992624,1739141211.7330494,51.10995125770569,0.17684224761352374,1739141211.7330527,51.10995125770569,0.017412174464501006,1739141211.733056,51.10995125770569,2.3292674822057076,1739141211.7330594,51.10995125770569,0.0,1739141211.7330627,51.10995125770569,-0.05291254542936362,1739141211.733066,51.10995125770569,3.09480017796735,1739141211.7330694,51.10995125770569,2.3507185337450727 +1739141211.7530708,51.1299512386322,29.26509404877087,1739141211.7530746,51.1299512386322,-0.2533751636981316,1739141211.753079,51.1299512386322,83.83882693991468,1739141211.753084,51.1299512386322,20.436550280501024,1739141211.753087,51.1299512386322,-0.017,1739141211.7530906,51.1299512386322,3.1148250786992624,1739141211.753094,51.1299512386322,0.17684224761352374,1739141211.7530973,51.1299512386322,0.017412174464501006,1739141211.7531006,51.1299512386322,2.3292674822057076,1739141211.7531042,51.1299512386322,0.0,1739141211.7531075,51.1299512386322,-0.021451051539365107,1739141211.7531106,51.1299512386322,3.09480017796735,1739141211.7531137,51.1299512386322,2.3507185337450727 +1739141211.7735248,51.149951219558716,29.26509404877087,1739141211.7735283,51.149951219558716,-0.2533751636981316,1739141211.7735326,51.149951219558716,83.83882693991468,1739141211.7735379,51.149951219558716,20.436550280501024,1739141211.773541,51.149951219558716,-0.017,1739141211.7735445,51.149951219558716,3.1148250786992624,1739141211.7735474,51.149951219558716,0.17684224761352374,1739141211.7735507,51.149951219558716,0.017412174464501006,1739141211.773554,51.149951219558716,2.3292674822057076,1739141211.7735577,51.149951219558716,0.0,1739141211.773561,51.149951219558716,-0.021451051539365107,1739141211.7735643,51.149951219558716,3.09480017796735,1739141211.7735674,51.149951219558716,2.3507185337450727 +1739141211.7937343,51.16995120048523,29.26509404877087,1739141211.793738,51.16995120048523,-0.2533751636981316,1739141211.7937422,51.16995120048523,83.83882693991468,1739141211.7937474,51.16995120048523,20.436550280501024,1739141211.7937503,51.16995120048523,-0.017,1739141211.7937539,51.16995120048523,3.1148250786992624,1739141211.793757,51.16995120048523,0.17684224761352374,1739141211.7937603,51.16995120048523,0.017412174464501006,1739141211.7937634,51.16995120048523,2.3292674822057076,1739141211.7937667,51.16995120048523,0.0,1739141211.79377,51.16995120048523,-0.021451051539365107,1739141211.7937732,51.16995120048523,3.09480017796735,1739141211.7937763,51.16995120048523,2.3507185337450727 +1739141211.8137286,51.18995118141174,29.26509404877087,1739141211.8137321,51.18995118141174,-0.2533751636981316,1739141211.8137367,51.18995118141174,83.83882693991468,1739141211.8137417,51.18995118141174,20.436550280501024,1739141211.8137445,51.18995118141174,-0.017,1739141211.8137486,51.18995118141174,3.1148250786992624,1739141211.8137517,51.18995118141174,0.17684224761352374,1739141211.813755,51.18995118141174,0.017412174464501006,1739141211.8137581,51.18995118141174,2.3292674822057076,1739141211.8137617,51.18995118141174,0.0,1739141211.8137653,51.18995118141174,-0.021451051539365107,1739141211.8137686,51.18995118141174,3.09480017796735,1739141211.813772,51.18995118141174,2.3507185337450727 +1739141211.8338976,51.20995116233826,29.26509404877087,1739141211.8339007,51.20995116233826,-0.2533751636981316,1739141211.8339052,51.20995116233826,83.83882693991468,1739141211.8339102,51.20995116233826,20.436550280501024,1739141211.8339128,51.20995116233826,-0.017,1739141211.8339167,51.20995116233826,3.1148250786992624,1739141211.8339198,51.20995116233826,0.17684224761352374,1739141211.8339233,51.20995116233826,0.017412174464501006,1739141211.8339264,51.20995116233826,2.3292674822057076,1739141211.8339298,51.20995116233826,0.0,1739141211.8339329,51.20995116233826,-0.021451051539365107,1739141211.8339362,51.20995116233826,3.09480017796735,1739141211.8339393,51.20995116233826,2.3507185337450727 +1739141211.853536,51.22995114326477,29.006980458875795,1739141211.8535392,51.22995114326477,-0.24117286581840158,1739141211.8535438,51.22995114326477,83.85766923197703,1739141211.8535485,51.22995114326477,20.42662297218901,1739141211.8535514,51.22995114326477,-0.017,1739141211.8535552,51.22995114326477,3.115472310523297,1739141211.8535583,51.22995114326477,0.18580567744736537,1739141211.8535616,51.22995114326477,0.019368993795999503,1739141211.8535647,51.22995114326477,2.320931145313692,1739141211.853568,51.22995114326477,0.0,1739141211.8535714,51.22995114326477,-0.03169270968860249,1739141211.8535745,51.22995114326477,3.093823235164446,1739141211.8535774,51.22995114326477,2.3477468724949633 +1739141211.8730545,51.249951124191284,29.006980458875795,1739141211.8730578,51.249951124191284,-0.24117286581840158,1739141211.8730621,51.249951124191284,83.85766923197703,1739141211.8730674,51.249951124191284,20.42662297218901,1739141211.87307,51.249951124191284,-0.017,1739141211.8730733,51.249951124191284,3.115472310523297,1739141211.8730767,51.249951124191284,0.18580567744736537,1739141211.8730798,51.249951124191284,0.019368993795999503,1739141211.873083,51.249951124191284,2.320931145313692,1739141211.8730865,51.249951124191284,0.0,1739141211.8730896,51.249951124191284,-0.02681572718127123,1739141211.8730927,51.249951124191284,3.093823235164446,1739141211.873096,51.249951124191284,2.3477468724949633 +1739141211.89362,51.2699511051178,29.006980458875795,1739141211.8936234,51.2699511051178,-0.24117286581840158,1739141211.893628,51.2699511051178,83.85766923197703,1739141211.8936331,51.2699511051178,20.42662297218901,1739141211.8936357,51.2699511051178,-0.017,1739141211.8936393,51.2699511051178,3.115472310523297,1739141211.8936427,51.2699511051178,0.18580567744736537,1739141211.8936458,51.2699511051178,0.019368993795999503,1739141211.8936489,51.2699511051178,2.320931145313692,1739141211.8936522,51.2699511051178,0.0,1739141211.8936555,51.2699511051178,-0.02681572718127123,1739141211.8936589,51.2699511051178,3.093823235164446,1739141211.893662,51.2699511051178,2.3477468724949633 +1739141211.914412,51.28995108604431,29.006980458875795,1739141211.9144154,51.28995108604431,-0.24117286581840158,1739141211.9144197,51.28995108604431,83.85766923197703,1739141211.914425,51.28995108604431,20.42662297218901,1739141211.9144278,51.28995108604431,-0.017,1739141211.9144316,51.28995108604431,3.115472310523297,1739141211.9144347,51.28995108604431,0.18580567744736537,1739141211.9144382,51.28995108604431,0.019368993795999503,1739141211.914441,51.28995108604431,2.320931145313692,1739141211.9144444,51.28995108604431,0.0,1739141211.9144478,51.28995108604431,-0.02681572718127123,1739141211.914451,51.28995108604431,3.093823235164446,1739141211.914454,51.28995108604431,2.3477468724949633 +1739141211.931325,51.309951066970825,29.006980458875795,1739141211.9313276,51.309951066970825,-0.24117286581840158,1739141211.9313302,51.309951066970825,83.85766923197703,1739141211.931333,51.309951066970825,20.42662297218901,1739141211.9313345,51.309951066970825,-0.017,1739141211.9313362,51.309951066970825,3.115472310523297,1739141211.9313374,51.309951066970825,0.18580567744736537,1739141211.9313388,51.309951066970825,0.019368993795999503,1739141211.93134,51.309951066970825,2.320931145313692,1739141211.9313416,51.309951066970825,0.0,1739141211.9313428,51.309951066970825,-0.02681572718127123,1739141211.9313443,51.309951066970825,3.093823235164446,1739141211.9313455,51.309951066970825,2.3477468724949633 +1739141211.9522521,51.32995104789734,28.749177360344163,1739141211.9522543,51.32995104789734,-0.22874543490086463,1739141211.9522576,51.32995104789734,83.87648885816984,1739141211.95226,51.32995104789734,20.41673203728068,1739141211.9522614,51.32995104789734,-0.017,1739141211.952263,51.32995104789734,3.1161859615357015,1739141211.9522645,51.32995104789734,0.19343233119782163,1739141211.952266,51.32995104789734,0.021382457587829903,1739141211.952267,51.32995104789734,2.3138615589643368,1739141211.9522688,51.32995104789734,0.0,1739141211.95227,51.32995104789734,-0.03463031930694179,1739141211.9522715,51.32995104789734,3.0929770165246673,1739141211.9522727,51.32995104789734,2.344770642066801 +1739141211.9720697,51.34995102882385,28.749177360344163,1739141211.972072,51.34995102882385,-0.22874543490086463,1739141211.9720747,51.34995102882385,83.87648885816984,1739141211.9720771,51.34995102882385,20.41673203728068,1739141211.9720783,51.34995102882385,-0.017,1739141211.9720798,51.34995102882385,3.1161859615357015,1739141211.9720812,51.34995102882385,0.19343233119782163,1739141211.9720826,51.34995102882385,0.021382457587829903,1739141211.972084,51.34995102882385,2.3138615589643368,1739141211.9720855,51.34995102882385,0.0,1739141211.9720867,51.34995102882385,-0.03090908310246432,1739141211.972088,51.34995102882385,3.0929770165246673,1739141211.9720893,51.34995102882385,2.344770642066801 +1739141211.9914763,51.369951009750366,28.749177360344163,1739141211.9914784,51.369951009750366,-0.22874543490086463,1739141211.9914813,51.369951009750366,83.87648885816984,1739141211.991484,51.369951009750366,20.41673203728068,1739141211.991485,51.369951009750366,-0.017,1739141211.9914868,51.369951009750366,3.1161859615357015,1739141211.9914882,51.369951009750366,0.19343233119782163,1739141211.9914892,51.369951009750366,0.021382457587829903,1739141211.9914906,51.369951009750366,2.3138615589643368,1739141211.991492,51.369951009750366,0.0,1739141211.9914937,51.369951009750366,-0.03090908310246432,1739141211.991495,51.369951009750366,3.0929770165246673,1739141211.9914958,51.369951009750366,2.344770642066801 +1739141212.01138,51.38995099067688,28.749177360344163,1739141212.0113823,51.38995099067688,-0.22874543490086463,1739141212.0113847,51.38995099067688,83.87648885816984,1739141212.0113876,51.38995099067688,20.41673203728068,1739141212.011389,51.38995099067688,-0.017,1739141212.0113904,51.38995099067688,3.1161859615357015,1739141212.0113916,51.38995099067688,0.19343233119782163,1739141212.011393,51.38995099067688,0.021382457587829903,1739141212.0113943,51.38995099067688,2.3138615589643368,1739141212.0113957,51.38995099067688,0.0,1739141212.0113971,51.38995099067688,-0.03090908310246432,1739141212.011398,51.38995099067688,3.0929770165246673,1739141212.0113995,51.38995099067688,2.344770642066801 +1739141212.0313332,51.409950971603394,28.749177360344163,1739141212.0313354,51.409950971603394,-0.22874543490086463,1739141212.0313382,51.409950971603394,83.87648885816984,1739141212.0313408,51.409950971603394,20.41673203728068,1739141212.031342,51.409950971603394,-0.017,1739141212.031344,51.409950971603394,3.1161859615357015,1739141212.0313451,51.409950971603394,0.19343233119782163,1739141212.0313463,51.409950971603394,0.021382457587829903,1739141212.0313478,51.409950971603394,2.3138615589643368,1739141212.031349,51.409950971603394,0.0,1739141212.0313506,51.409950971603394,-0.03090908310246432,1739141212.0313516,51.409950971603394,3.0929770165246673,1739141212.0313528,51.409950971603394,2.344770642066801 +1739141212.0522254,51.42995095252991,28.749177360344163,1739141212.0522282,51.42995095252991,-0.22874543490086463,1739141212.0522308,51.42995095252991,83.87648885816984,1739141212.0522337,51.42995095252991,20.41673203728068,1739141212.0522351,51.42995095252991,-0.017,1739141212.0522366,51.42995095252991,3.1161859615357015,1739141212.052238,51.42995095252991,0.19343233119782163,1739141212.0522394,51.42995095252991,0.021382457587829903,1739141212.0522406,51.42995095252991,2.3138615589643368,1739141212.0522425,51.42995095252991,0.0,1739141212.052244,51.42995095252991,-0.03090908310246432,1739141212.0522451,51.42995095252991,3.0929770165246673,1739141212.0522466,51.42995095252991,2.344770642066801 +1739141212.0728903,51.44995093345642,28.491737927152883,1739141212.0728948,51.44995093345642,-0.21613268234666538,1739141212.0728993,51.44995093345642,84.05315596310379,1739141212.072903,51.44995093345642,20.250443241144872,1739141212.072904,51.44995093345642,-0.0156131203740443,1739141212.0729063,51.44995093345642,3.1172663778789547,1739141212.0729084,51.44995093345642,0.20629076948192482,1739141212.0729108,51.44995093345642,0.02331225903784719,1739141212.0729122,51.44995093345642,2.301991053942843,1739141212.0729141,51.44995093345642,0.0,1739141212.0729156,51.44995093345642,-0.046970623381266716,1739141212.072917,51.44995093345642,3.092239816913404,1739141212.072919,51.44995093345642,2.3413133209897063 +1739141212.0924368,51.469950914382935,28.491737927152883,1739141212.09244,51.469950914382935,-0.21613268234666538,1739141212.0924435,51.469950914382935,84.05315596310379,1739141212.0924475,51.469950914382935,20.250443241144872,1739141212.0924494,51.469950914382935,-0.0156131203740443,1739141212.092451,51.469950914382935,3.1172663778789547,1739141212.0924525,51.469950914382935,0.20629076948192482,1739141212.0924544,51.469950914382935,0.02331225903784719,1739141212.0924556,51.469950914382935,2.301991053942843,1739141212.0924578,51.469950914382935,0.0,1739141212.0924592,51.469950914382935,-0.039322267046863146,1739141212.0924613,51.469950914382935,3.092239816913404,1739141212.0924628,51.469950914382935,2.3413133209897063 +1739141212.1124754,51.48995089530945,28.491737927152883,1739141212.1124783,51.48995089530945,-0.21613268234666538,1739141212.112481,51.48995089530945,84.05315596310379,1739141212.1124835,51.48995089530945,20.250443241144872,1739141212.112485,51.48995089530945,-0.0156131203740443,1739141212.1124866,51.48995089530945,3.1172663778789547,1739141212.112488,51.48995089530945,0.20629076948192482,1739141212.1124895,51.48995089530945,0.02331225903784719,1739141212.1124904,51.48995089530945,2.301991053942843,1739141212.112492,51.48995089530945,0.0,1739141212.1124935,51.48995089530945,-0.039322267046863146,1739141212.112495,51.48995089530945,3.092239816913404,1739141212.1124961,51.48995089530945,2.3413133209897063 +1739141212.1342943,51.50995087623596,28.491737927152883,1739141212.1342988,51.50995087623596,-0.21613268234666538,1739141212.1343043,51.50995087623596,84.05315596310379,1739141212.1343093,51.50995087623596,20.250443241144872,1739141212.1343122,51.50995087623596,-0.0156131203740443,1739141212.1343162,51.50995087623596,3.1172663778789547,1739141212.1343195,51.50995087623596,0.20629076948192482,1739141212.134323,51.50995087623596,0.02331225903784719,1739141212.134326,51.50995087623596,2.301991053942843,1739141212.1343296,51.50995087623596,0.0,1739141212.134333,51.50995087623596,-0.039322267046863146,1739141212.1343362,51.50995087623596,3.092239816913404,1739141212.1343398,51.50995087623596,2.3413133209897063 +1739141212.152093,51.529950857162476,28.491737927152883,1739141212.1520958,51.529950857162476,-0.21613268234666538,1739141212.152099,51.529950857162476,84.05315596310379,1739141212.1521013,51.529950857162476,20.250443241144872,1739141212.1521027,51.529950857162476,-0.0156131203740443,1739141212.1521041,51.529950857162476,3.1172663778789547,1739141212.1521056,51.529950857162476,0.20629076948192482,1739141212.152107,51.529950857162476,0.02331225903784719,1739141212.152108,51.529950857162476,2.301991053942843,1739141212.1521096,51.529950857162476,0.0,1739141212.1521108,51.529950857162476,-0.039322267046863146,1739141212.1521122,51.529950857162476,3.092239816913404,1739141212.1521134,51.529950857162476,2.3413133209897063 +1739141212.1724288,51.54995083808899,28.234730596743454,1739141212.1724317,51.54995083808899,-0.2033590159416523,1739141212.172435,51.54995083808899,84.70510416707207,1739141212.1724377,51.54995083808899,19.611620371791357,1739141212.1724396,51.54995083808899,-0.012,1739141212.1724412,51.54995083808899,3.119404880491791,1739141212.172443,51.54995083808899,0.24000485196166713,1739141212.172444,51.54995083808899,0.024775913332497485,1739141212.1724455,51.54995083808899,2.2711556323434605,1739141212.1724472,51.54995083808899,0.0,1739141212.1724484,51.54995083808899,-0.08984785228271897,1739141212.1724498,51.54995083808899,3.091575391331149,1739141212.1724508,51.54995083808899,2.3369436701139863 +1739141212.1915348,51.5699508190155,28.234730596743454,1739141212.1915376,51.5699508190155,-0.2033590159416523,1739141212.191541,51.5699508190155,84.70510416707207,1739141212.1915438,51.5699508190155,19.611620371791357,1739141212.191545,51.5699508190155,-0.012,1739141212.191547,51.5699508190155,3.119404880491791,1739141212.1915486,51.5699508190155,0.24000485196166713,1739141212.1915505,51.5699508190155,0.024775913332497485,1739141212.1915517,51.5699508190155,2.2711556323434605,1739141212.1915534,51.5699508190155,0.0,1739141212.1915548,51.5699508190155,-0.06578803777052578,1739141212.1915565,51.5699508190155,3.091575391331149,1739141212.1915576,51.5699508190155,2.3369436701139863 +1739141212.212326,51.58995079994202,28.234730596743454,1739141212.212329,51.58995079994202,-0.2033590159416523,1739141212.2123318,51.58995079994202,84.70510416707207,1739141212.2123349,51.58995079994202,19.611620371791357,1739141212.212336,51.58995079994202,-0.012,1739141212.212338,51.58995079994202,3.119404880491791,1739141212.2123392,51.58995079994202,0.24000485196166713,1739141212.2123406,51.58995079994202,0.024775913332497485,1739141212.2123418,51.58995079994202,2.2711556323434605,1739141212.2123435,51.58995079994202,0.0,1739141212.212345,51.58995079994202,-0.06578803777052578,1739141212.212346,51.58995079994202,3.091575391331149,1739141212.2123475,51.58995079994202,2.3369436701139863 +1739141212.2322714,51.60995078086853,28.234730596743454,1739141212.2322738,51.60995078086853,-0.2033590159416523,1739141212.2322767,51.60995078086853,84.70510416707207,1739141212.2322795,51.60995078086853,19.611620371791357,1739141212.232281,51.60995078086853,-0.012,1739141212.2322829,51.60995078086853,3.119404880491791,1739141212.2322843,51.60995078086853,0.24000485196166713,1739141212.232286,51.60995078086853,0.024775913332497485,1739141212.2322872,51.60995078086853,2.2711556323434605,1739141212.2322888,51.60995078086853,0.0,1739141212.2322903,51.60995078086853,-0.06578803777052578,1739141212.2322917,51.60995078086853,3.091575391331149,1739141212.2322931,51.60995078086853,2.3369436701139863 +1739141212.253474,51.629950761795044,28.234730596743454,1739141212.2534778,51.629950761795044,-0.2033590159416523,1739141212.2534826,51.629950761795044,84.70510416707207,1739141212.2534878,51.629950761795044,19.611620371791357,1739141212.2534912,51.629950761795044,-0.012,1739141212.253495,51.629950761795044,3.119404880491791,1739141212.2534983,51.629950761795044,0.24000485196166713,1739141212.2535017,51.629950761795044,0.024775913332497485,1739141212.253505,51.629950761795044,2.2711556323434605,1739141212.2535086,51.629950761795044,0.0,1739141212.253512,51.629950761795044,-0.06578803777052578,1739141212.2535152,51.629950761795044,3.091575391331149,1739141212.2535186,51.629950761795044,2.3369436701139863 +1739141212.273245,51.64995074272156,28.234730596743454,1739141212.2732487,51.64995074272156,-0.2033590159416523,1739141212.2732532,51.64995074272156,84.70510416707207,1739141212.2732582,51.64995074272156,19.611620371791357,1739141212.273261,51.64995074272156,-0.012,1739141212.2732646,51.64995074272156,3.119404880491791,1739141212.273268,51.64995074272156,0.24000485196166713,1739141212.2732713,51.64995074272156,0.024775913332497485,1739141212.2732744,51.64995074272156,2.2711556323434605,1739141212.2732778,51.64995074272156,0.0,1739141212.273281,51.64995074272156,-0.06578803777052578,1739141212.2732844,51.64995074272156,3.091575391331149,1739141212.2732875,51.64995074272156,2.3369436701139863 +1739141212.2941394,51.66995072364807,27.978397885622606,1739141212.2941427,51.66995072364807,-0.19045138748540325,1739141212.2941468,51.66995072364807,84.73483876156209,1739141212.2941518,51.66995072364807,19.604921560652453,1739141212.2941751,51.66995072364807,-0.012,1739141212.294179,51.66995072364807,3.1202843735452612,1739141212.2941823,51.66995072364807,0.24585614561455787,1739141212.2941856,51.66995072364807,0.026916701489708504,1739141212.294189,51.66995072364807,2.265846168798805,1739141212.2941923,51.66995072364807,0.0,1739141212.2941957,51.66995072364807,-0.06126514944199413,1739141212.29422,51.66995072364807,3.0909255220867276,1739141212.2942233,51.66995072364807,2.329265075663615 +1739141212.3134558,51.689950704574585,27.978397885622606,1739141212.3134596,51.689950704574585,-0.19045138748540325,1739141212.3134644,51.689950704574585,84.73483876156209,1739141212.3134694,51.689950704574585,19.604921560652453,1739141212.3134723,51.689950704574585,-0.012,1739141212.3134758,51.689950704574585,3.1202843735452612,1739141212.3134954,51.689950704574585,0.24585614561455787,1739141212.3134983,51.689950704574585,0.026916701489708504,1739141212.3135014,51.689950704574585,2.265846168798805,1739141212.3135047,51.689950704574585,0.0,1739141212.3135078,51.689950704574585,-0.06341890686480989,1739141212.313511,51.689950704574585,3.0909255220867276,1739141212.313514,51.689950704574585,2.329265075663615 +1739141212.3343086,51.7099506855011,27.978397885622606,1739141212.3343124,51.7099506855011,-0.19045138748540325,1739141212.3343167,51.7099506855011,84.73483876156209,1739141212.3343217,51.7099506855011,19.604921560652453,1739141212.3343246,51.7099506855011,-0.012,1739141212.3343277,51.7099506855011,3.1202843735452612,1739141212.3343313,51.7099506855011,0.24585614561455787,1739141212.3343344,51.7099506855011,0.026916701489708504,1739141212.3343372,51.7099506855011,2.265846168798805,1739141212.3343406,51.7099506855011,0.0,1739141212.334344,51.7099506855011,-0.06341890686480989,1739141212.3343472,51.7099506855011,3.0909255220867276,1739141212.33435,51.7099506855011,2.329265075663615 +1739141212.3541665,51.72995066642761,27.978397885622606,1739141212.3541706,51.72995066642761,-0.19045138748540325,1739141212.354175,51.72995066642761,84.73483876156209,1739141212.3541799,51.72995066642761,19.604921560652453,1739141212.354183,51.72995066642761,-0.012,1739141212.3541865,51.72995066642761,3.1202843735452612,1739141212.3541899,51.72995066642761,0.24585614561455787,1739141212.3541932,51.72995066642761,0.026916701489708504,1739141212.3541965,51.72995066642761,2.265846168798805,1739141212.3542,51.72995066642761,0.0,1739141212.3542032,51.72995066642761,-0.06341890686480989,1739141212.3542066,51.72995066642761,3.0909255220867276,1739141212.3542094,51.72995066642761,2.329265075663615 +1739141212.3741684,51.749950647354126,27.978397885622606,1739141212.3741724,51.749950647354126,-0.19045138748540325,1739141212.374177,51.749950647354126,84.73483876156209,1739141212.3741822,51.749950647354126,19.604921560652453,1739141212.3741848,51.749950647354126,-0.012,1739141212.3741882,51.749950647354126,3.1202843735452612,1739141212.3741915,51.749950647354126,0.24585614561455787,1739141212.3741946,51.749950647354126,0.026916701489708504,1739141212.3741977,51.749950647354126,2.265846168798805,1739141212.374201,51.749950647354126,0.0,1739141212.3742042,51.749950647354126,-0.06341890686480989,1739141212.3742073,51.749950647354126,3.0909255220867276,1739141212.3742104,51.749950647354126,2.329265075663615 +1739141212.3941727,51.76995062828064,27.72285614559708,1739141212.394177,51.76995062828064,-0.177427952302307,1739141212.394182,51.76995062828064,84.76448160340505,1739141212.3941872,51.76995062828064,19.59602639718683,1739141212.3941903,51.76995062828064,-0.012,1739141212.3941941,51.76995062828064,3.121239685173185,1739141212.394198,51.76995062828064,0.2506440580502944,1739141212.3942013,51.76995062828064,0.029132834526320952,1739141212.3942044,51.76995062828064,2.261510852327421,1739141212.3942084,51.76995062828064,0.0,1739141212.3942122,51.76995062828064,-0.058492349832751894,1739141212.3942156,51.76995062828064,3.0903996304898347,1739141212.394219,51.76995062828064,2.322349182871168 +1739141212.4132729,51.78995060920715,27.72285614559708,1739141212.4132767,51.78995060920715,-0.177427952302307,1739141212.413281,51.78995060920715,84.76448160340505,1739141212.4132862,51.78995060920715,19.59602639718683,1739141212.4132886,51.78995060920715,-0.012,1739141212.4132922,51.78995060920715,3.121239685173185,1739141212.4132955,51.78995060920715,0.2506440580502944,1739141212.4132984,51.78995060920715,0.029132834526320952,1739141212.4133015,51.78995060920715,2.261510852327421,1739141212.4133048,51.78995060920715,0.0,1739141212.413308,51.78995060920715,-0.06083833054374699,1739141212.413311,51.78995060920715,3.0903996304898347,1739141212.4133143,51.78995060920715,2.322349182871168 +1739141212.4335349,51.80995059013367,27.72285614559708,1739141212.433539,51.80995059013367,-0.177427952302307,1739141212.433543,51.80995059013367,84.76448160340505,1739141212.4335477,51.80995059013367,19.59602639718683,1739141212.4335504,51.80995059013367,-0.012,1739141212.433554,51.80995059013367,3.121239685173185,1739141212.433557,51.80995059013367,0.2506440580502944,1739141212.4335601,51.80995059013367,0.029132834526320952,1739141212.433563,51.80995059013367,2.261510852327421,1739141212.433566,51.80995059013367,0.0,1739141212.4335692,51.80995059013367,-0.06083833054374699,1739141212.433572,51.80995059013367,3.0903996304898347,1739141212.4335752,51.80995059013367,2.322349182871168 +1739141212.4535737,51.82995057106018,27.72285614559708,1739141212.4535778,51.82995057106018,-0.177427952302307,1739141212.453582,51.82995057106018,84.76448160340505,1739141212.4535873,51.82995057106018,19.59602639718683,1739141212.45359,51.82995057106018,-0.012,1739141212.4536097,51.82995057106018,3.121239685173185,1739141212.4536128,51.82995057106018,0.2506440580502944,1739141212.453616,51.82995057106018,0.029132834526320952,1739141212.453619,51.82995057106018,2.261510852327421,1739141212.4536223,51.82995057106018,0.0,1739141212.4536254,51.82995057106018,-0.06083833054374699,1739141212.4536283,51.82995057106018,3.0903996304898347,1739141212.4536314,51.82995057106018,2.322349182871168 +1739141212.4735804,51.849950551986694,27.72285614559708,1739141212.4735844,51.849950551986694,-0.177427952302307,1739141212.473589,51.849950551986694,84.76448160340505,1739141212.4735942,51.849950551986694,19.59602639718683,1739141212.4735973,51.849950551986694,-0.012,1739141212.473601,51.849950551986694,3.121239685173185,1739141212.473605,51.849950551986694,0.2506440580502944,1739141212.473608,51.849950551986694,0.029132834526320952,1739141212.4736114,51.849950551986694,2.261510852327421,1739141212.473615,51.849950551986694,0.0,1739141212.4736183,51.849950551986694,-0.06083833054374699,1739141212.4736216,51.849950551986694,3.0903996304898347,1739141212.473625,51.849950551986694,2.322349182871168 +1739141212.4922953,51.86995053291321,27.72285614559708,1739141212.4922986,51.86995053291321,-0.177427952302307,1739141212.4923012,51.86995053291321,84.76448160340505,1739141212.492304,51.86995053291321,19.59602639718683,1739141212.4923058,51.86995053291321,-0.012,1739141212.4923074,51.86995053291321,3.121239685173185,1739141212.4923089,51.86995053291321,0.2506440580502944,1739141212.4923103,51.86995053291321,0.029132834526320952,1739141212.4923112,51.86995053291321,2.261510852327421,1739141212.4923134,51.86995053291321,0.0,1739141212.4923146,51.86995053291321,-0.06083833054374699,1739141212.4923162,51.86995053291321,3.0903996304898347,1739141212.4923172,51.86995053291321,2.322349182871168 +1739141212.5123081,51.88995051383972,27.46806369964373,1739141212.512311,51.88995051383972,-0.1643237736360721,1739141212.5123138,51.88995051383972,85.2984375589199,1739141212.5123165,51.88995051383972,19.08191432585362,1739141212.512318,51.88995051383972,-0.011,1739141212.5123196,51.88995051383972,3.123311713610835,1739141212.5123212,51.88995051383972,0.2794926896816978,1739141212.5123227,51.88995051383972,0.03051029212800533,1739141212.5123239,51.88995051383972,2.2355642476497732,1739141212.5123255,51.88995051383972,0.0,1739141212.512327,51.88995051383972,-0.09774688772559936,1739141212.5123281,51.88995051383972,3.0899832195375043,1739141212.5123296,51.88995051383972,2.3157356231757067 +1739141212.531941,51.909950494766235,27.46806369964373,1739141212.5319443,51.909950494766235,-0.1643237736360721,1739141212.531947,51.909950494766235,85.2984375589199,1739141212.5319495,51.909950494766235,19.08191432585362,1739141212.5319512,51.909950494766235,-0.011,1739141212.5319526,51.909950494766235,3.123311713610835,1739141212.5319543,51.909950494766235,0.2794926896816978,1739141212.5319555,51.909950494766235,0.03051029212800533,1739141212.5319571,51.909950494766235,2.2355642476497732,1739141212.531959,51.909950494766235,0.0,1739141212.5319605,51.909950494766235,-0.08017137552593345,1739141212.531962,51.909950494766235,3.0899832195375043,1739141212.531963,51.909950494766235,2.3157356231757067 +1739141212.5518818,51.92995047569275,27.46806369964373,1739141212.5518842,51.92995047569275,-0.1643237736360721,1739141212.5518873,51.92995047569275,85.2984375589199,1739141212.5518901,51.92995047569275,19.08191432585362,1739141212.5518918,51.92995047569275,-0.011,1739141212.5518935,51.92995047569275,3.123311713610835,1739141212.551895,51.92995047569275,0.2794926896816978,1739141212.551896,51.92995047569275,0.03051029212800533,1739141212.5518973,51.92995047569275,2.2355642476497732,1739141212.5518992,51.92995047569275,0.0,1739141212.5519006,51.92995047569275,-0.08017137552593345,1739141212.5519023,51.92995047569275,3.0899832195375043,1739141212.5519035,51.92995047569275,2.3157356231757067 +1739141212.593841,51.969950437545776,27.46806369964373,1739141212.5938458,51.969950437545776,-0.1643237736360721,1739141212.5938509,51.969950437545776,85.2984375589199,1739141212.5938551,51.969950437545776,19.08191432585362,1739141212.5938578,51.969950437545776,-0.011,1739141212.5938606,51.969950437545776,3.123311713610835,1739141212.593863,51.969950437545776,0.2794926896816978,1739141212.5938647,51.969950437545776,0.03051029212800533,1739141212.5938668,51.969950437545776,2.2355642476497732,1739141212.593869,51.969950437545776,0.0,1739141212.5938714,51.969950437545776,-0.08017137552593345,1739141212.5938735,51.969950437545776,3.0899832195375043,1739141212.5938756,51.969950437545776,2.3157356231757067 +1739141212.6125839,51.98995041847229,27.21412303575522,1739141212.6125867,51.98995041847229,-0.15116515963912747,1739141212.61259,51.98995041847229,85.32738679460319,1739141212.6125934,51.98995041847229,19.07974724129385,1739141212.6125948,51.98995041847229,-0.011,1739141212.6125968,51.98995041847229,3.1243631459685295,1739141212.6125982,51.98995041847229,0.2824372939989755,1739141212.6125998,51.98995041847229,0.032770916966276896,1739141212.6126013,51.98995041847229,2.232932656898634,1739141212.6126032,51.98995041847229,0.0,1739141212.6126049,51.98995041847229,-0.0681521289684758,1739141212.6126065,51.98995041847229,3.0896398757174044,1739141212.612608,51.98995041847229,2.3068082394678715 +1739141212.6315129,52.009950399398804,27.21412303575522,1739141212.6315155,52.009950399398804,-0.15116515963912747,1739141212.631518,52.009950399398804,85.32738679460319,1739141212.6315205,52.009950399398804,19.07974724129385,1739141212.6315217,52.009950399398804,-0.011,1739141212.6315234,52.009950399398804,3.1243631459685295,1739141212.6315248,52.009950399398804,0.2824372939989755,1739141212.6315262,52.009950399398804,0.032770916966276896,1739141212.6315274,52.009950399398804,2.232932656898634,1739141212.6315289,52.009950399398804,0.0,1739141212.6315305,52.009950399398804,-0.07387558256923743,1739141212.6315317,52.009950399398804,3.0896398757174044,1739141212.6315331,52.009950399398804,2.3068082394678715 +1739141212.6560805,52.01995038986206,27.21412303575522,1739141212.656087,52.01995038986206,-0.15116515963912747,1739141212.6560946,52.01995038986206,85.32738679460319,1739141212.6561017,52.01995038986206,19.07974724129385,1739141212.6561053,52.01995038986206,-0.011,1739141212.6561096,52.01995038986206,3.1243631459685295,1739141212.6561131,52.01995038986206,0.2824372939989755,1739141212.6561167,52.01995038986206,0.032770916966276896,1739141212.65612,52.01995038986206,2.232932656898634,1739141212.656124,52.01995038986206,0.0,1739141212.6561277,52.01995038986206,-0.07387558256923743,1739141212.656131,52.01995038986206,3.0896398757174044,1739141212.6561346,52.01995038986206,2.3068082394678715 +1739141212.6740787,52.04995036125183,27.21412303575522,1739141212.674083,52.04995036125183,-0.15116515963912747,1739141212.6740875,52.04995036125183,85.32738679460319,1739141212.674092,52.04995036125183,19.07974724129385,1739141212.674094,52.04995036125183,-0.011,1739141212.6740968,52.04995036125183,3.1243631459685295,1739141212.674099,52.04995036125183,0.2824372939989755,1739141212.6741009,52.04995036125183,0.032770916966276896,1739141212.6741028,52.04995036125183,2.232932656898634,1739141212.6741054,52.04995036125183,0.0,1739141212.6741078,52.04995036125183,-0.07387558256923743,1739141212.67411,52.04995036125183,3.0896398757174044,1739141212.674112,52.04995036125183,2.3068082394678715 +1739141212.6928964,52.069950342178345,27.21412303575522,1739141212.6929002,52.069950342178345,-0.15116515963912747,1739141212.6929045,52.069950342178345,85.32738679460319,1739141212.692908,52.069950342178345,19.07974724129385,1739141212.6929097,52.069950342178345,-0.011,1739141212.692912,52.069950342178345,3.1243631459685295,1739141212.692914,52.069950342178345,0.2824372939989755,1739141212.692916,52.069950342178345,0.032770916966276896,1739141212.6929176,52.069950342178345,2.232932656898634,1739141212.6929195,52.069950342178345,0.0,1739141212.6929216,52.069950342178345,-0.07387558256923743,1739141212.6929233,52.069950342178345,3.0896398757174044,1739141212.6929252,52.069950342178345,2.3068082394678715 +1739141212.7121782,52.08995032310486,27.21412303575522,1739141212.7121816,52.08995032310486,-0.15116515963912747,1739141212.712185,52.08995032310486,85.32738679460319,1739141212.7121882,52.08995032310486,19.07974724129385,1739141212.7121897,52.08995032310486,-0.011,1739141212.7121918,52.08995032310486,3.1243631459685295,1739141212.7121933,52.08995032310486,0.2824372939989755,1739141212.712195,52.08995032310486,0.032770916966276896,1739141212.7121964,52.08995032310486,2.232932656898634,1739141212.7121983,52.08995032310486,0.0,1739141212.7122,52.08995032310486,-0.07387558256923743,1739141212.712201,52.08995032310486,3.0896398757174044,1739141212.7122028,52.08995032310486,2.3068082394678715 +1739141212.731811,52.10995030403137,26.961111856103575,1739141212.731814,52.10995030403137,-0.13797839104343979,1739141212.731817,52.10995030403137,85.75213212487368,1739141212.7318199,52.10995030403137,18.678928206455776,1739141212.731821,52.10995030403137,-0.01,1739141212.7318234,52.10995030403137,3.126141631006133,1739141212.7318246,52.10995030403137,0.30439864286437085,1739141212.731826,52.10995030403137,0.034071547634804536,1739141212.7318273,52.10995030403137,2.213403275568503,1739141212.731829,52.10995030403137,0.0,1739141212.7318306,52.10995030403137,-0.09593594829214515,1739141212.7318318,52.10995030403137,3.089384313196913,1739141212.731833,52.10995030403137,2.2988342825544437 +1739141212.7516437,52.11995029449463,26.961111856103575,1739141212.7516468,52.11995029449463,-0.13797839104343979,1739141212.7516496,52.11995029449463,85.75213212487368,1739141212.7516522,52.11995029449463,18.678928206455776,1739141212.751654,52.11995029449463,-0.01,1739141212.7516553,52.11995029449463,3.126141631006133,1739141212.751657,52.11995029449463,0.30439864286437085,1739141212.7516584,52.11995029449463,0.034071547634804536,1739141212.7516596,52.11995029449463,2.213403275568503,1739141212.7516613,52.11995029449463,0.0,1739141212.7516625,52.11995029449463,-0.08543100698594053,1739141212.751664,52.11995029449463,3.089384313196913,1739141212.7516654,52.11995029449463,2.2988342825544437 +1739141212.771853,52.1499502658844,26.961111856103575,1739141212.7718563,52.1499502658844,-0.13797839104343979,1739141212.7718596,52.1499502658844,85.75213212487368,1739141212.771863,52.1499502658844,18.678928206455776,1739141212.7718647,52.1499502658844,-0.01,1739141212.7718663,52.1499502658844,3.126141631006133,1739141212.7718687,52.1499502658844,0.30439864286437085,1739141212.77187,52.1499502658844,0.034071547634804536,1739141212.7718716,52.1499502658844,2.213403275568503,1739141212.7718732,52.1499502658844,0.0,1739141212.7718751,52.1499502658844,-0.08543100698594053,1739141212.7718773,52.1499502658844,3.089384313196913,1739141212.7718787,52.1499502658844,2.2988342825544437 +1739141212.7914975,52.16995024681091,26.961111856103575,1739141212.7915,52.16995024681091,-0.13797839104343979,1739141212.791503,52.16995024681091,85.75213212487368,1739141212.7915056,52.16995024681091,18.678928206455776,1739141212.791507,52.16995024681091,-0.01,1739141212.7915087,52.16995024681091,3.126141631006133,1739141212.7915103,52.16995024681091,0.30439864286437085,1739141212.7915115,52.16995024681091,0.034071547634804536,1739141212.7915127,52.16995024681091,2.213403275568503,1739141212.7915144,52.16995024681091,0.0,1739141212.7915158,52.16995024681091,-0.08543100698594053,1739141212.7915173,52.16995024681091,3.089384313196913,1739141212.7915184,52.16995024681091,2.2988342825544437 +1739141212.811759,52.18995022773743,26.961111856103575,1739141212.8117619,52.18995022773743,-0.13797839104343979,1739141212.811765,52.18995022773743,85.75213212487368,1739141212.8117678,52.18995022773743,18.678928206455776,1739141212.8117692,52.18995022773743,-0.01,1739141212.8117712,52.18995022773743,3.126141631006133,1739141212.8117726,52.18995022773743,0.30439864286437085,1739141212.8117745,52.18995022773743,0.034071547634804536,1739141212.8117754,52.18995022773743,2.213403275568503,1739141212.8117774,52.18995022773743,0.0,1739141212.8117788,52.18995022773743,-0.08543100698594053,1739141212.8117805,52.18995022773743,3.089384313196913,1739141212.8117814,52.18995022773743,2.2988342825544437 +1739141212.8326535,52.20995020866394,26.7090511580965,1739141212.8326564,52.20995020866394,-0.1247782518897651,1739141212.8326595,52.20995020866394,85.78616031910462,1739141212.8326623,52.20995020866394,18.672903754125254,1739141212.8326638,52.20995020866394,-0.01,1739141212.8326657,52.20995020866394,3.127310878719876,1739141212.8326669,52.20995020866394,0.30673518622461454,1739141212.832668,52.20995020866394,0.036468596558293404,1739141212.8326695,52.20995020866394,2.211335556891058,1739141212.8326714,52.20995020866394,0.0,1739141212.832673,52.20995020866394,-0.07155790058785838,1739141212.8326743,52.20995020866394,3.0891360673520314,1739141212.8326757,52.20995020866394,2.289499701920968 +1739141212.8533702,52.229950189590454,26.7090511580965,1739141212.8533738,52.229950189590454,-0.1247782518897651,1739141212.8533783,52.229950189590454,85.78616031910462,1739141212.8533835,52.229950189590454,18.672903754125254,1739141212.8533862,52.229950189590454,-0.01,1739141212.85339,52.229950189590454,3.127310878719876,1739141212.8533933,52.229950189590454,0.30673518622461454,1739141212.8533967,52.229950189590454,0.036468596558293404,1739141212.8534,52.229950189590454,2.211335556891058,1739141212.8534036,52.229950189590454,0.0,1739141212.8534071,52.229950189590454,-0.07816414502990998,1739141212.8534105,52.229950189590454,3.0891360673520314,1739141212.8534138,52.229950189590454,2.289499701920968 +1739141212.8712537,52.24995017051697,26.7090511580965,1739141212.8712566,52.24995017051697,-0.1247782518897651,1739141212.8712595,52.24995017051697,85.78616031910462,1739141212.8712618,52.24995017051697,18.672903754125254,1739141212.871264,52.24995017051697,-0.01,1739141212.8712656,52.24995017051697,3.127310878719876,1739141212.871267,52.24995017051697,0.30673518622461454,1739141212.8712683,52.24995017051697,0.036468596558293404,1739141212.8712697,52.24995017051697,2.211335556891058,1739141212.8712711,52.24995017051697,0.0,1739141212.8712726,52.24995017051697,-0.07816414502990998,1739141212.8712738,52.24995017051697,3.0891360673520314,1739141212.871275,52.24995017051697,2.289499701920968 +1739141212.8922718,52.26995015144348,26.7090511580965,1739141212.8922744,52.26995015144348,-0.1247782518897651,1739141212.892277,52.26995015144348,85.78616031910462,1739141212.8922799,52.26995015144348,18.672903754125254,1739141212.892281,52.26995015144348,-0.01,1739141212.892283,52.26995015144348,3.127310878719876,1739141212.8922842,52.26995015144348,0.30673518622461454,1739141212.8922853,52.26995015144348,0.036468596558293404,1739141212.8922865,52.26995015144348,2.211335556891058,1739141212.8922882,52.26995015144348,0.0,1739141212.8922896,52.26995015144348,-0.07816414502990998,1739141212.8922908,52.26995015144348,3.0891360673520314,1739141212.892292,52.26995015144348,2.289499701920968 +1739141212.912708,52.289950132369995,26.7090511580965,1739141212.9127107,52.289950132369995,-0.1247782518897651,1739141212.9127135,52.289950132369995,85.78616031910462,1739141212.9127164,52.289950132369995,18.672903754125254,1739141212.9127178,52.289950132369995,-0.01,1739141212.9127192,52.289950132369995,3.127310878719876,1739141212.912721,52.289950132369995,0.30673518622461454,1739141212.9127219,52.289950132369995,0.036468596558293404,1739141212.9127233,52.289950132369995,2.211335556891058,1739141212.9127247,52.289950132369995,0.0,1739141212.9127262,52.289950132369995,-0.07816414502990998,1739141212.9127274,52.289950132369995,3.0891360673520314,1739141212.9127285,52.289950132369995,2.289499701920968 +1739141212.9325643,52.30995011329651,26.7090511580965,1739141212.9325683,52.30995011329651,-0.1247782518897651,1739141212.9325736,52.30995011329651,85.78616031910462,1739141212.932579,52.30995011329651,18.672903754125254,1739141212.9325824,52.30995011329651,-0.01,1739141212.9325867,52.30995011329651,3.127310878719876,1739141212.9325902,52.30995011329651,0.30673518622461454,1739141212.932594,52.30995011329651,0.036468596558293404,1739141212.932598,52.30995011329651,2.211335556891058,1739141212.932602,52.30995011329651,0.0,1739141212.9326057,52.30995011329651,-0.07816414502990998,1739141212.9326096,52.30995011329651,3.0891360673520314,1739141212.9326131,52.30995011329651,2.289499701920968 +1739141212.9536152,52.32995009422302,26.45796898446322,1739141212.953619,52.32995009422302,-0.11158043565940723,1739141212.9536235,52.32995009422302,85.94772804583896,1739141212.953629,52.32995009422302,18.53661429276921,1739141212.9536316,52.32995009422302,-0.01,1739141212.9536357,52.32995009422302,3.1287697373054586,1739141212.9536393,52.32995009422302,0.31475826574012167,1739141212.9536426,52.32995009422302,0.03851626526220568,1739141212.9536457,52.32995009422302,2.2042502437748697,1739141212.9536495,52.32995009422302,0.0,1739141212.953653,52.32995009422302,-0.07560448184857659,1739141212.9536564,52.32995009422302,3.0890271341556095,1739141212.9536595,52.32995009422302,2.2810736134615404 +1739141212.9726398,52.349950075149536,26.45796898446322,1739141212.9726431,52.349950075149536,-0.11158043565940723,1739141212.9726474,52.349950075149536,85.94772804583896,1739141212.9726524,52.349950075149536,18.53661429276921,1739141212.9726553,52.349950075149536,-0.01,1739141212.9726589,52.349950075149536,3.1287697373054586,1739141212.9726791,52.349950075149536,0.31475826574012167,1739141212.972682,52.349950075149536,0.03851626526220568,1739141212.972685,52.349950075149536,2.2042502437748697,1739141212.9726884,52.349950075149536,0.0,1739141212.9726915,52.349950075149536,-0.0768233696866707,1739141212.9726946,52.349950075149536,3.0890271341556095,1739141212.9726973,52.349950075149536,2.2810736134615404 +1739141212.992928,52.36995005607605,26.45796898446322,1739141212.9929311,52.36995005607605,-0.11158043565940723,1739141212.9929354,52.36995005607605,85.94772804583896,1739141212.99294,52.36995005607605,18.53661429276921,1739141212.9929428,52.36995005607605,-0.01,1739141212.9929461,52.36995005607605,3.1287697373054586,1739141212.9929492,52.36995005607605,0.31475826574012167,1739141212.9929523,52.36995005607605,0.03851626526220568,1739141212.9929552,52.36995005607605,2.2042502437748697,1739141212.9929583,52.36995005607605,0.0,1739141212.9929612,52.36995005607605,-0.0768233696866707,1739141212.9929643,52.36995005607605,3.0890271341556095,1739141212.9929674,52.36995005607605,2.2810736134615404 +1739141213.0130534,52.38995003700256,26.45796898446322,1739141213.0130568,52.38995003700256,-0.11158043565940723,1739141213.0130608,52.38995003700256,85.94772804583896,1739141213.0130656,52.38995003700256,18.53661429276921,1739141213.0130682,52.38995003700256,-0.01,1739141213.0130715,52.38995003700256,3.1287697373054586,1739141213.0130749,52.38995003700256,0.31475826574012167,1739141213.013078,52.38995003700256,0.03851626526220568,1739141213.013081,52.38995003700256,2.2042502437748697,1739141213.0130842,52.38995003700256,0.0,1739141213.0130873,52.38995003700256,-0.0768233696866707,1739141213.0130904,52.38995003700256,3.0890271341556095,1739141213.0130935,52.38995003700256,2.2810736134615404 +1739141213.0331948,52.40995001792908,26.45796898446322,1739141213.033198,52.40995001792908,-0.11158043565940723,1739141213.0332026,52.40995001792908,85.94772804583896,1739141213.033208,52.40995001792908,18.53661429276921,1739141213.0332105,52.40995001792908,-0.01,1739141213.033214,52.40995001792908,3.1287697373054586,1739141213.0332172,52.40995001792908,0.31475826574012167,1739141213.0332203,52.40995001792908,0.03851626526220568,1739141213.0332234,52.40995001792908,2.2042502437748697,1739141213.0332267,52.40995001792908,0.0,1739141213.03323,52.40995001792908,-0.0768233696866707,1739141213.0332332,52.40995001792908,3.0890271341556095,1739141213.0332365,52.40995001792908,2.2810736134615404 +1739141213.0530028,52.42994999885559,26.207816877979532,1739141213.0530062,52.42994999885559,-0.09841505089200098,1739141213.0530102,52.42994999885559,86.47189457303303,1739141213.053015,52.42994999885559,18.03764303174504,1739141213.0530176,52.42994999885559,-0.006,1739141213.0530212,52.42994999885559,3.130281864910092,1739141213.0530243,52.42994999885559,0.33715464092375386,1739141213.0530274,52.42994999885559,0.03878359019974852,1739141213.0530303,52.42994999885559,2.1845915457833325,1739141213.0530336,52.42994999885559,0.0,1739141213.0530365,52.42994999885559,-0.09833364084083232,1739141213.0530393,52.42994999885559,3.089006265723749,1739141213.0530427,52.42994999885559,2.2726821952434566 +1739141213.072697,52.449949979782104,26.207816877979532,1739141213.0727005,52.449949979782104,-0.09841505089200098,1739141213.0727046,52.449949979782104,86.47189457303303,1739141213.0727093,52.449949979782104,18.03764303174504,1739141213.0727124,52.449949979782104,-0.006,1739141213.0727158,52.449949979782104,3.130281864910092,1739141213.072719,52.449949979782104,0.33715464092375386,1739141213.0727224,52.449949979782104,0.03878359019974852,1739141213.0727255,52.449949979782104,2.1845915457833325,1739141213.0727289,52.449949979782104,0.0,1739141213.0727322,52.449949979782104,-0.08809064946012413,1739141213.0727353,52.449949979782104,3.089006265723749,1739141213.0727386,52.449949979782104,2.2726821952434566 +1739141213.0930638,52.46994996070862,26.207816877979532,1739141213.093067,52.46994996070862,-0.09841505089200098,1739141213.0930712,52.46994996070862,86.47189457303303,1739141213.0930758,52.46994996070862,18.03764303174504,1739141213.0930784,52.46994996070862,-0.006,1739141213.093082,52.46994996070862,3.130281864910092,1739141213.0930848,52.46994996070862,0.33715464092375386,1739141213.093088,52.46994996070862,0.03878359019974852,1739141213.093091,52.46994996070862,2.1845915457833325,1739141213.093094,52.46994996070862,0.0,1739141213.0930972,52.46994996070862,-0.08809064946012413,1739141213.0931003,52.46994996070862,3.089006265723749,1739141213.0931034,52.46994996070862,2.2726821952434566 +1739141213.1130903,52.48994994163513,26.207816877979532,1739141213.1130934,52.48994994163513,-0.09841505089200098,1739141213.1130977,52.48994994163513,86.47189457303303,1739141213.1131024,52.48994994163513,18.03764303174504,1739141213.1131048,52.48994994163513,-0.006,1739141213.1131084,52.48994994163513,3.130281864910092,1739141213.1131115,52.48994994163513,0.33715464092375386,1739141213.1131146,52.48994994163513,0.03878359019974852,1739141213.1131175,52.48994994163513,2.1845915457833325,1739141213.1131206,52.48994994163513,0.0,1739141213.113124,52.48994994163513,-0.08809064946012413,1739141213.1131268,52.48994994163513,3.089006265723749,1739141213.1131303,52.48994994163513,2.2726821952434566 +1739141213.1325493,52.49994993209839,26.207816877979532,1739141213.1325526,52.49994993209839,-0.09841505089200098,1739141213.1325572,52.49994993209839,86.47189457303303,1739141213.132562,52.49994993209839,18.03764303174504,1739141213.1325648,52.49994993209839,-0.006,1739141213.1325684,52.49994993209839,3.130281864910092,1739141213.132572,52.49994993209839,0.33715464092375386,1739141213.132575,52.49994993209839,0.03878359019974852,1739141213.1325781,52.49994993209839,2.1845915457833325,1739141213.1325815,52.49994993209839,0.0,1739141213.1325848,52.49994993209839,-0.08809064946012413,1739141213.1325877,52.49994993209839,3.089006265723749,1739141213.132591,52.49994993209839,2.2726821952434566 +1739141213.1519456,52.52994990348816,26.207816877979532,1739141213.1519477,52.52994990348816,-0.09841505089200098,1739141213.1519506,52.52994990348816,86.47189457303303,1739141213.1519532,52.52994990348816,18.03764303174504,1739141213.1519544,52.52994990348816,-0.006,1739141213.151956,52.52994990348816,3.130281864910092,1739141213.1519573,52.52994990348816,0.33715464092375386,1739141213.1519582,52.52994990348816,0.03878359019974852,1739141213.1519597,52.52994990348816,2.1845915457833325,1739141213.151961,52.52994990348816,0.0,1739141213.1519623,52.52994990348816,-0.08809064946012413,1739141213.1519637,52.52994990348816,3.089006265723749,1739141213.1519647,52.52994990348816,2.2726821952434566 +1739141213.1718316,52.54994988441467,25.958669255423356,1739141213.1718342,52.54994988441467,-0.08530048508220478,1739141213.171837,52.54994988441467,86.47737582072926,1739141213.17184,52.54994988441467,18.06170243394731,1739141213.1718416,52.54994988441467,-0.006007804821636778,1739141213.1718433,52.54994988441467,3.1315520877043777,1739141213.1718447,52.54994988441467,0.3359473358649399,1739141213.171846,52.54994988441467,0.04136571037324973,1739141213.171847,52.54994988441467,2.1856467879325283,1739141213.171849,52.54994988441467,0.0,1739141213.1718502,52.54994988441467,-0.06727746383238456,1739141213.1718516,52.54994988441467,3.0890000790902774,1739141213.171853,52.54994988441467,2.2628352974910273 +1739141213.1922064,52.56994986534119,25.958669255423356,1739141213.1922092,52.56994986534119,-0.08530048508220478,1739141213.1922128,52.56994986534119,86.47737582072926,1739141213.1922162,52.56994986534119,18.06170243394731,1739141213.1922176,52.56994986534119,-0.006007804821636778,1739141213.1922197,52.56994986534119,3.1315520877043777,1739141213.1922214,52.56994986534119,0.3359473358649399,1739141213.192223,52.56994986534119,0.04136571037324973,1739141213.1922243,52.56994986534119,2.1856467879325283,1739141213.1922264,52.56994986534119,0.0,1739141213.1922278,52.56994986534119,-0.07718850955849899,1739141213.192229,52.56994986534119,3.0890000790902774,1739141213.1922307,52.56994986534119,2.2628352974910273 +1739141213.2137022,52.5899498462677,25.958669255423356,1739141213.2137065,52.5899498462677,-0.08530048508220478,1739141213.213712,52.5899498462677,86.47737582072926,1739141213.213718,52.5899498462677,18.06170243394731,1739141213.2137213,52.5899498462677,-0.006007804821636778,1739141213.2137258,52.5899498462677,3.1315520877043777,1739141213.2137296,52.5899498462677,0.3359473358649399,1739141213.2137337,52.5899498462677,0.04136571037324973,1739141213.2137375,52.5899498462677,2.1856467879325283,1739141213.2137415,52.5899498462677,0.0,1739141213.2137456,52.5899498462677,-0.07718850955849899,1739141213.2137494,52.5899498462677,3.0890000790902774,1739141213.2137535,52.5899498462677,2.2628352974910273 +1739141213.231473,52.609949827194214,25.958669255423356,1739141213.2314758,52.609949827194214,-0.08530048508220478,1739141213.231479,52.609949827194214,86.47737582072926,1739141213.231482,52.609949827194214,18.06170243394731,1739141213.2314842,52.609949827194214,-0.006007804821636778,1739141213.2314858,52.609949827194214,3.1315520877043777,1739141213.2314875,52.609949827194214,0.3359473358649399,1739141213.231489,52.609949827194214,0.04136571037324973,1739141213.2314904,52.609949827194214,2.1856467879325283,1739141213.231492,52.609949827194214,0.0,1739141213.231494,52.609949827194214,-0.07718850955849899,1739141213.2314951,52.609949827194214,3.0890000790902774,1739141213.2314968,52.609949827194214,2.2628352974910273 +1739141213.2538247,52.62994980812073,25.958669255423356,1739141213.253829,52.62994980812073,-0.08530048508220478,1739141213.2538345,52.62994980812073,86.47737582072926,1739141213.2538407,52.62994980812073,18.06170243394731,1739141213.2538443,52.62994980812073,-0.006007804821636778,1739141213.2538488,52.62994980812073,3.1315520877043777,1739141213.2538526,52.62994980812073,0.3359473358649399,1739141213.2538567,52.62994980812073,0.04136571037324973,1739141213.2538607,52.62994980812073,2.1856467879325283,1739141213.2538648,52.62994980812073,0.0,1739141213.2538688,52.62994980812073,-0.07718850955849899,1739141213.2538726,52.62994980812073,3.0890000790902774,1739141213.2538767,52.62994980812073,2.2628352974910273 +1739141213.273944,52.64994978904724,25.710517141260162,1739141213.273948,52.64994978904724,-0.07224276394753026,1739141213.2739532,52.64994978904724,87.04337161629634,1739141213.2739594,52.64994978904724,17.520782678673516,1739141213.273963,52.64994978904724,-0.002041567897511164,1739141213.2739673,52.64994978904724,3.1330210109970484,1739141213.2739716,52.64994978904724,0.35992569891719256,1739141213.2739754,52.64994978904724,0.04120739982270132,1739141213.2739792,52.64994978904724,2.1647837075013454,1739141213.2739832,52.64994978904724,0.0,1739141213.273987,52.64994978904724,-0.1010723584982973,1739141213.273991,52.64994978904724,3.0890600706233684,1739141213.273995,52.64994978904724,2.254482798918295 +1739141213.2914875,52.669949769973755,25.710517141260162,1739141213.29149,52.669949769973755,-0.07224276394753026,1739141213.2914934,52.669949769973755,87.04337161629634,1739141213.2914968,52.669949769973755,17.520782678673516,1739141213.2914987,52.669949769973755,-0.002041567897511164,1739141213.2915006,52.669949769973755,3.1330210109970484,1739141213.2915022,52.669949769973755,0.35992569891719256,1739141213.2915037,52.669949769973755,0.04120739982270132,1739141213.291505,52.669949769973755,2.1647837075013454,1739141213.2915072,52.669949769973755,0.0,1739141213.2915087,52.669949769973755,-0.08969909141694954,1739141213.29151,52.669949769973755,3.0890600706233684,1739141213.2915115,52.669949769973755,2.254482798918295 +1739141213.3114643,52.68994975090027,25.710517141260162,1739141213.3114672,52.68994975090027,-0.07224276394753026,1739141213.3114703,52.68994975090027,87.04337161629634,1739141213.3114736,52.68994975090027,17.520782678673516,1739141213.3114753,52.68994975090027,-0.002041567897511164,1739141213.3114772,52.68994975090027,3.1330210109970484,1739141213.3114789,52.68994975090027,0.35992569891719256,1739141213.3114803,52.68994975090027,0.04120739982270132,1739141213.311482,52.68994975090027,2.1647837075013454,1739141213.3114836,52.68994975090027,0.0,1739141213.3114853,52.68994975090027,-0.08969909141694954,1739141213.3114867,52.68994975090027,3.0890600706233684,1739141213.3114882,52.68994975090027,2.254482798918295 +1739141213.3337913,52.70994973182678,25.710517141260162,1739141213.3337955,52.70994973182678,-0.07224276394753026,1739141213.333801,52.70994973182678,87.04337161629634,1739141213.333807,52.70994973182678,17.520782678673516,1739141213.3338108,52.70994973182678,-0.002041567897511164,1739141213.333815,52.70994973182678,3.1330210109970484,1739141213.333819,52.70994973182678,0.35992569891719256,1739141213.3338227,52.70994973182678,0.04120739982270132,1739141213.3338268,52.70994973182678,2.1647837075013454,1739141213.3338306,52.70994973182678,0.0,1739141213.3338346,52.70994973182678,-0.08969909141694954,1739141213.3338387,52.70994973182678,3.0890600706233684,1739141213.3338428,52.70994973182678,2.254482798918295 +1739141213.3513582,52.729949712753296,25.710517141260162,1739141213.351361,52.729949712753296,-0.07224276394753026,1739141213.3513644,52.729949712753296,87.04337161629634,1739141213.3513675,52.729949712753296,17.520782678673516,1739141213.3513691,52.729949712753296,-0.002041567897511164,1739141213.3513713,52.729949712753296,3.1330210109970484,1739141213.3513727,52.729949712753296,0.35992569891719256,1739141213.3513744,52.729949712753296,0.04120739982270132,1739141213.3513758,52.729949712753296,2.1647837075013454,1739141213.3513777,52.729949712753296,0.0,1739141213.3513792,52.729949712753296,-0.08969909141694954,1739141213.3513808,52.729949712753296,3.0890600706233684,1739141213.351382,52.729949712753296,2.254482798918295 +1739141213.37184,52.74994969367981,25.710517141260162,1739141213.3718426,52.74994969367981,-0.07224276394753026,1739141213.3718457,52.74994969367981,87.04337161629634,1739141213.3718488,52.74994969367981,17.520782678673516,1739141213.3718505,52.74994969367981,-0.002041567897511164,1739141213.3718526,52.74994969367981,3.1330210109970484,1739141213.371854,52.74994969367981,0.35992569891719256,1739141213.3718555,52.74994969367981,0.04120739982270132,1739141213.371857,52.74994969367981,2.1647837075013454,1739141213.3718586,52.74994969367981,0.0,1739141213.3718603,52.74994969367981,-0.08969909141694954,1739141213.3718617,52.74994969367981,3.0890600706233684,1739141213.3718631,52.74994969367981,2.254482798918295 +1739141213.3919613,52.76994967460632,25.463378458408314,1739141213.3919644,52.76994967460632,-0.05925638223057472,1739141213.3919678,52.76994967460632,87.05449285702468,1739141213.3919709,52.76994967460632,17.53979701016984,1739141213.3919723,52.76994967460632,-0.0022505165952729535,1739141213.3919744,52.76994967460632,3.134398320762772,1739141213.3919759,52.76994967460632,0.35853626861692545,1739141213.3919775,52.76994967460632,0.04385285254711978,1739141213.391979,52.76994967460632,2.165987168326046,1739141213.3919811,52.76994967460632,0.0,1739141213.3919826,52.76994967460632,-0.06822365265182476,1739141213.3919842,52.76994967460632,3.0891347684156956,1739141213.3919857,52.76994967460632,2.2444372254983707 +1739141213.4145513,52.78994965553284,25.463378458408314,1739141213.4145555,52.78994965553284,-0.05925638223057472,1739141213.414561,52.78994965553284,87.05449285702468,1739141213.4145672,52.78994965553284,17.53979701016984,1739141213.4145708,52.78994965553284,-0.0022505165952729535,1739141213.414575,52.78994965553284,3.134398320762772,1739141213.414579,52.78994965553284,0.35853626861692545,1739141213.414583,52.78994965553284,0.04385285254711978,1739141213.4145868,52.78994965553284,2.165987168326046,1739141213.414591,52.78994965553284,0.0,1739141213.4145951,52.78994965553284,-0.07845005717232478,1739141213.414599,52.78994965553284,3.0891347684156956,1739141213.4146028,52.78994965553284,2.2444372254983707 +1739141213.4320855,52.80994963645935,25.463378458408314,1739141213.4320886,52.80994963645935,-0.05925638223057472,1739141213.4320917,52.80994963645935,87.05449285702468,1739141213.432095,52.80994963645935,17.53979701016984,1739141213.4320965,52.80994963645935,-0.0022505165952729535,1739141213.4320984,52.80994963645935,3.134398320762772,1739141213.4321,52.80994963645935,0.35853626861692545,1739141213.4321015,52.80994963645935,0.04385285254711978,1739141213.4321027,52.80994963645935,2.165987168326046,1739141213.4321043,52.80994963645935,0.0,1739141213.4321063,52.80994963645935,-0.07845005717232478,1739141213.4321077,52.80994963645935,3.0891347684156956,1739141213.432109,52.80994963645935,2.2444372254983707 +1739141213.4514256,52.829949617385864,25.463378458408314,1739141213.4514287,52.829949617385864,-0.05925638223057472,1739141213.451432,52.829949617385864,87.05449285702468,1739141213.451435,52.829949617385864,17.53979701016984,1739141213.4514365,52.829949617385864,-0.0022505165952729535,1739141213.451439,52.829949617385864,3.134398320762772,1739141213.4514406,52.829949617385864,0.35853626861692545,1739141213.4514422,52.829949617385864,0.04385285254711978,1739141213.4514434,52.829949617385864,2.165987168326046,1739141213.4514456,52.829949617385864,0.0,1739141213.4514472,52.829949617385864,-0.07845005717232478,1739141213.4514487,52.829949617385864,3.0891347684156956,1739141213.4514503,52.829949617385864,2.2444372254983707 +1739141213.4741,52.84994959831238,25.463378458408314,1739141213.4741046,52.84994959831238,-0.05925638223057472,1739141213.47411,52.84994959831238,87.05449285702468,1739141213.474116,52.84994959831238,17.53979701016984,1739141213.4741194,52.84994959831238,-0.0022505165952729535,1739141213.474124,52.84994959831238,3.134398320762772,1739141213.4741278,52.84994959831238,0.35853626861692545,1739141213.4741318,52.84994959831238,0.04385285254711978,1739141213.4741356,52.84994959831238,2.165987168326046,1739141213.4741397,52.84994959831238,0.0,1739141213.4741437,52.84994959831238,-0.07845005717232478,1739141213.4741476,52.84994959831238,3.0891347684156956,1739141213.4741516,52.84994959831238,2.2444372254983707 +1739141213.4914796,52.86994957923889,25.217251588032983,1739141213.4914827,52.86994957923889,-0.046352169069868054,1739141213.4914863,52.86994957923889,87.75890629976787,1739141213.4914896,52.86994957923889,16.860867258684564,1739141213.491491,52.86994957923889,0.0024797670197900484,1739141213.4914932,52.86994957923889,3.135749052059348,1739141213.4914947,52.86994957923889,0.3877239310047217,1739141213.491496,52.86994957923889,0.042638600377701535,1739141213.4914978,52.86994957923889,2.1408461743866285,1739141213.4914997,52.86994957923889,0.0,1739141213.4915013,52.86994957923889,-0.11024254373900086,1739141213.4915028,52.86994957923889,3.0893346531438954,1739141213.4915044,52.86994957923889,2.2359494312454293 +1739141213.5140693,52.889949560165405,25.217251588032983,1739141213.5140734,52.889949560165405,-0.046352169069868054,1739141213.5140786,52.889949560165405,87.75890629976787,1739141213.5140848,52.889949560165405,16.860867258684564,1739141213.5140884,52.889949560165405,0.0024797670197900484,1739141213.5140927,52.889949560165405,3.135749052059348,1739141213.5140967,52.889949560165405,0.3877239310047217,1739141213.5141006,52.889949560165405,0.042638600377701535,1739141213.5141044,52.889949560165405,2.1408461743866285,1739141213.5141087,52.889949560165405,0.0,1739141213.5141125,52.889949560165405,-0.09510325685880083,1739141213.5141163,52.889949560165405,3.0893346531438954,1739141213.51412,52.889949560165405,2.2359494312454293 +1739141213.5316887,52.90994954109192,25.217251588032983,1739141213.5316916,52.90994954109192,-0.046352169069868054,1739141213.5316947,52.90994954109192,87.75890629976787,1739141213.5316978,52.90994954109192,16.860867258684564,1739141213.5316992,52.90994954109192,0.0024797670197900484,1739141213.531701,52.90994954109192,3.135749052059348,1739141213.5317025,52.90994954109192,0.3877239310047217,1739141213.531704,52.90994954109192,0.042638600377701535,1739141213.5317056,52.90994954109192,2.1408461743866285,1739141213.531707,52.90994954109192,0.0,1739141213.531709,52.90994954109192,-0.09510325685880083,1739141213.5317101,52.90994954109192,3.0893346531438954,1739141213.5317118,52.90994954109192,2.2359494312454293 +1739141213.55145,52.92994952201843,25.217251588032983,1739141213.5514529,52.92994952201843,-0.046352169069868054,1739141213.5514562,52.92994952201843,87.75890629976787,1739141213.5514593,52.92994952201843,16.860867258684564,1739141213.5514612,52.92994952201843,0.0024797670197900484,1739141213.551463,52.92994952201843,3.135749052059348,1739141213.5514648,52.92994952201843,0.3877239310047217,1739141213.5514662,52.92994952201843,0.042638600377701535,1739141213.5514677,52.92994952201843,2.1408461743866285,1739141213.5514693,52.92994952201843,0.0,1739141213.551471,52.92994952201843,-0.09510325685880083,1739141213.5514727,52.92994952201843,3.0893346531438954,1739141213.551474,52.92994952201843,2.2359494312454293 +1739141213.5717852,52.949949502944946,25.217251588032983,1739141213.5717883,52.949949502944946,-0.046352169069868054,1739141213.5717916,52.949949502944946,87.75890629976787,1739141213.5717947,52.949949502944946,16.860867258684564,1739141213.5717964,52.949949502944946,0.0024797670197900484,1739141213.5717983,52.949949502944946,3.135749052059348,1739141213.5718002,52.949949502944946,0.3877239310047217,1739141213.571802,52.949949502944946,0.042638600377701535,1739141213.571803,52.949949502944946,2.1408461743866285,1739141213.571805,52.949949502944946,0.0,1739141213.5718067,52.949949502944946,-0.09510325685880083,1739141213.5718083,52.949949502944946,3.0893346531438954,1739141213.5718098,52.949949502944946,2.2359494312454293 +1739141213.5917895,52.96994948387146,25.217251588032983,1739141213.5917923,52.96994948387146,-0.046352169069868054,1739141213.5917957,52.96994948387146,87.75890629976787,1739141213.5917988,52.96994948387146,16.860867258684564,1739141213.5918007,52.96994948387146,0.0024797670197900484,1739141213.5918026,52.96994948387146,3.135749052059348,1739141213.5918043,52.96994948387146,0.3877239310047217,1739141213.5918062,52.96994948387146,0.042638600377701535,1739141213.5918076,52.96994948387146,2.1408461743866285,1739141213.5918095,52.96994948387146,0.0,1739141213.5918112,52.96994948387146,-0.09510325685880083,1739141213.5918126,52.96994948387146,3.0893346531438954,1739141213.591814,52.96994948387146,2.2359494312454293 +1739141213.6139503,52.989949464797974,24.97218101933978,1739141213.6139543,52.989949464797974,-0.033560017277872944,1739141213.6139598,52.989949464797974,87.78757955630498,1739141213.6139657,52.989949464797974,16.864330068203667,1739141213.613969,52.989949464797974,0.0024501703572336105,1739141213.6139736,52.989949464797974,3.1371512854546584,1739141213.6139774,52.989949464797974,0.38562922842757213,1739141213.6139815,52.989949464797974,0.04504830349397441,1739141213.6139853,52.989949464797974,2.1426407004808365,1739141213.6139894,52.989949464797974,0.0,1739141213.6139932,52.989949464797974,-0.07122702822261087,1739141213.6139972,52.989949464797974,3.0895713576242145,1739141213.614001,52.989949464797974,2.2252373670669785 +1739141213.6318512,53.00994944572449,24.97218101933978,1739141213.631854,53.00994944572449,-0.033560017277872944,1739141213.6318572,53.00994944572449,87.78757955630498,1739141213.6318603,53.00994944572449,16.864330068203667,1739141213.6318617,53.00994944572449,0.0024501703572336105,1739141213.6318636,53.00994944572449,3.1371512854546584,1739141213.631865,53.00994944572449,0.38562922842757213,1739141213.6318667,53.00994944572449,0.04504830349397441,1739141213.631868,53.00994944572449,2.1426407004808365,1739141213.6318698,53.00994944572449,0.0,1739141213.6318715,53.00994944572449,-0.08259666658614195,1739141213.6318727,53.00994944572449,3.0895713576242145,1739141213.6318743,53.00994944572449,2.2252373670669785 +1739141213.6515238,53.029949426651,24.97218101933978,1739141213.651527,53.029949426651,-0.033560017277872944,1739141213.6515303,53.029949426651,87.78757955630498,1739141213.6515334,53.029949426651,16.864330068203667,1739141213.6515348,53.029949426651,0.0024501703572336105,1739141213.651537,53.029949426651,3.1371512854546584,1739141213.6515384,53.029949426651,0.38562922842757213,1739141213.6515398,53.029949426651,0.04504830349397441,1739141213.6515412,53.029949426651,2.1426407004808365,1739141213.6515431,53.029949426651,0.0,1739141213.6515446,53.029949426651,-0.08259666658614195,1739141213.6515458,53.029949426651,3.0895713576242145,1739141213.6515474,53.029949426651,2.2252373670669785 +1739141213.6717117,53.049949407577515,24.97218101933978,1739141213.6717153,53.049949407577515,-0.033560017277872944,1739141213.6717355,53.049949407577515,87.78757955630498,1739141213.6717412,53.049949407577515,16.864330068203667,1739141213.6717432,53.049949407577515,0.0024501703572336105,1739141213.6717477,53.049949407577515,3.1371512854546584,1739141213.6717515,53.049949407577515,0.38562922842757213,1739141213.6717534,53.049949407577515,0.04504830349397441,1739141213.6717565,53.049949407577515,2.1426407004808365,1739141213.67176,53.049949407577515,0.0,1739141213.6717634,53.049949407577515,-0.08259666658614195,1739141213.6717653,53.049949407577515,3.0895713576242145,1739141213.6717687,53.049949407577515,2.2252373670669785 +1739141213.6930726,53.06994938850403,24.97218101933978,1739141213.6930757,53.06994938850403,-0.033560017277872944,1739141213.693079,53.06994938850403,87.78757955630498,1739141213.6930823,53.06994938850403,16.864330068203667,1739141213.693084,53.06994938850403,0.0024501703572336105,1739141213.6930857,53.06994938850403,3.1371512854546584,1739141213.6930873,53.06994938850403,0.38562922842757213,1739141213.6930888,53.06994938850403,0.04504830349397441,1739141213.6930902,53.06994938850403,2.1426407004808365,1739141213.693092,53.06994938850403,0.0,1739141213.6930935,53.06994938850403,-0.08259666658614195,1739141213.6930952,53.06994938850403,3.0895713576242145,1739141213.6930966,53.06994938850403,2.2252373670669785 +1739141213.711972,53.08994936943054,24.72817925775384,1739141213.711975,53.08994936943054,-0.020881571547405997,1739141213.7119784,53.08994936943054,88.5247187768231,1739141213.7119815,53.08994936943054,16.15401430376317,1739141213.7119834,53.08994936943054,0.008,1739141213.711985,53.08994936943054,3.138224225005878,1739141213.711987,53.08994936943054,0.41496835496724344,1739141213.7119882,53.08994936943054,0.04334683357475541,1739141213.7119894,53.08994936943054,2.117642390448975,1739141213.7119913,53.08994936943054,0.0,1739141213.711993,53.08994936943054,-0.11327039739646713,1739141213.7119946,53.08994936943054,3.0898080621045336,1739141213.7119958,53.08994936943054,2.216306242067727 +1739141213.738681,53.0999493598938,24.72817925775384,1739141213.7386904,53.0999493598938,-0.020881571547405997,1739141213.7387004,53.0999493598938,88.5247187768231,1739141213.73871,53.0999493598938,16.15401430376317,1739141213.738715,53.0999493598938,0.008,1739141213.7387207,53.0999493598938,3.138224225005878,1739141213.7387257,53.0999493598938,0.41496835496724344,1739141213.7387302,53.0999493598938,0.04334683357475541,1739141213.7387345,53.0999493598938,2.117642390448975,1739141213.7387402,53.0999493598938,0.0,1739141213.738745,53.0999493598938,-0.09866385161875213,1739141213.7387497,53.0999493598938,3.0898080621045336,1739141213.7387543,53.0999493598938,2.216306242067727 +1739141213.7624035,53.11994934082031,24.72817925775384,1739141213.7624173,53.11994934082031,-0.020881571547405997,1739141213.7624347,53.11994934082031,88.5247187768231,1739141213.762454,53.11994934082031,16.15401430376317,1739141213.762465,53.11994934082031,0.008,1739141213.762505,53.11994934082031,3.138224225005878,1739141213.7625105,53.11994934082031,0.41496835496724344,1739141213.7625148,53.11994934082031,0.04334683357475541,1739141213.7625194,53.11994934082031,2.117642390448975,1739141213.762525,53.11994934082031,0.0,1739141213.7625299,53.11994934082031,-0.09866385161875213,1739141213.7625344,53.11994934082031,3.0898080621045336,1739141213.7625387,53.11994934082031,2.216306242067727 +1739141213.7850683,53.14994931221008,24.72817925775384,1739141213.7850788,53.14994931221008,-0.020881571547405997,1739141213.785089,53.14994931221008,88.5247187768231,1739141213.7850993,53.14994931221008,16.15401430376317,1739141213.7851048,53.14994931221008,0.008,1739141213.7851112,53.14994931221008,3.138224225005878,1739141213.785117,53.14994931221008,0.41496835496724344,1739141213.7851222,53.14994931221008,0.04334683357475541,1739141213.7851267,53.14994931221008,2.117642390448975,1739141213.7851322,53.14994931221008,0.0,1739141213.7851377,53.14994931221008,-0.09866385161875213,1739141213.7851422,53.14994931221008,3.0898080621045336,1739141213.7851472,53.14994931221008,2.216306242067727 +1739141213.8024476,53.15994930267334,24.72817925775384,1739141213.8024542,53.15994930267334,-0.020881571547405997,1739141213.8024614,53.15994930267334,88.5247187768231,1739141213.8024921,53.15994930267334,16.15401430376317,1739141213.8025036,53.15994930267334,0.008,1739141213.8025174,53.15994930267334,3.138224225005878,1739141213.802529,53.15994930267334,0.41496835496724344,1739141213.802538,53.15994930267334,0.04334683357475541,1739141213.8025413,53.15994930267334,2.117642390448975,1739141213.8025453,53.15994930267334,0.0,1739141213.802549,53.15994930267334,-0.09866385161875213,1739141213.802552,53.15994930267334,3.0898080621045336,1739141213.8025553,53.15994930267334,2.216306242067727 +1739141213.8217673,53.18994927406311,24.72817925775384,1739141213.8217723,53.18994927406311,-0.020881571547405997,1739141213.8217776,53.18994927406311,88.5247187768231,1739141213.8217828,53.18994927406311,16.15401430376317,1739141213.8217854,53.18994927406311,0.008,1739141213.8217883,53.18994927406311,3.138224225005878,1739141213.821791,53.18994927406311,0.41496835496724344,1739141213.8217936,53.18994927406311,0.04334683357475541,1739141213.821796,53.18994927406311,2.117642390448975,1739141213.8217988,53.18994927406311,0.0,1739141213.8218014,53.18994927406311,-0.09866385161875213,1739141213.8218038,53.18994927406311,3.0898080621045336,1739141213.8218064,53.18994927406311,2.216306242067727 +1739141213.8410168,53.209949254989624,24.485279028694254,1739141213.841022,53.209949254989624,-0.008318007356384882,1739141213.8410268,53.209949254989624,88.5517058293771,1739141213.8410313,53.209949254989624,16.16030188936609,1739141213.8410337,53.209949254989624,0.008,1739141213.8410363,53.209949254989624,3.139632529713789,1739141213.8410382,53.209949254989624,0.41264862548666387,1739141213.8410404,53.209949254989624,0.04572357983519064,1739141213.8410428,53.209949254989624,2.1196082453512215,1739141213.8410451,53.209949254989624,0.0,1739141213.8410475,53.209949254989624,-0.07373607483958412,1739141213.8410494,53.209949254989624,3.0900447665848527,1739141213.8410513,53.209949254989624,2.205214696015419 +1739141213.8606093,53.22994923591614,24.485279028694254,1739141213.8606129,53.22994923591614,-0.008318007356384882,1739141213.8606167,53.22994923591614,88.5517058293771,1739141213.8606205,53.22994923591614,16.16030188936609,1739141213.8606226,53.22994923591614,0.008,1739141213.8606248,53.22994923591614,3.139632529713789,1739141213.8606267,53.22994923591614,0.41264862548666387,1739141213.8606284,53.22994923591614,0.04572357983519064,1739141213.8606303,53.22994923591614,2.1196082453512215,1739141213.8606324,53.22994923591614,0.0,1739141213.8606346,53.22994923591614,-0.08560645066419736,1739141213.8606365,53.22994923591614,3.0900447665848527,1739141213.8606381,53.22994923591614,2.205214696015419 +1739141213.8798597,53.24994921684265,24.485279028694254,1739141213.879862,53.24994921684265,-0.008318007356384882,1739141213.879865,53.24994921684265,88.5517058293771,1739141213.8798673,53.24994921684265,16.16030188936609,1739141213.8798687,53.24994921684265,0.008,1739141213.8798702,53.24994921684265,3.139632529713789,1739141213.8798716,53.24994921684265,0.41264862548666387,1739141213.879873,53.24994921684265,0.04572357983519064,1739141213.8798742,53.24994921684265,2.1196082453512215,1739141213.879876,53.24994921684265,0.0,1739141213.879877,53.24994921684265,-0.08560645066419736,1739141213.8798783,53.24994921684265,3.0900447665848527,1739141213.8798795,53.24994921684265,2.205214696015419 +1739141213.900398,53.269949197769165,24.485279028694254,1739141213.9004006,53.269949197769165,-0.008318007356384882,1739141213.900404,53.269949197769165,88.5517058293771,1739141213.9004066,53.269949197769165,16.16030188936609,1739141213.9004078,53.269949197769165,0.008,1739141213.9004097,53.269949197769165,3.139632529713789,1739141213.900411,53.269949197769165,0.41264862548666387,1739141213.900412,53.269949197769165,0.04572357983519064,1739141213.9004138,53.269949197769165,2.1196082453512215,1739141213.9004152,53.269949197769165,0.0,1739141213.9004166,53.269949197769165,-0.08560645066419736,1739141213.9004178,53.269949197769165,3.0900447665848527,1739141213.9004192,53.269949197769165,2.205214696015419 +1739141213.925473,53.28994917869568,24.485279028694254,1739141213.9254825,53.28994917869568,-0.008318007356384882,1739141213.9254932,53.28994917869568,88.5517058293771,1739141213.9255035,53.28994917869568,16.16030188936609,1739141213.9255083,53.28994917869568,0.008,1739141213.9255142,53.28994917869568,3.139632529713789,1739141213.925519,53.28994917869568,0.41264862548666387,1739141213.9255238,53.28994917869568,0.04572357983519064,1739141213.9255285,53.28994917869568,2.1196082453512215,1739141213.9255342,53.28994917869568,0.0,1739141213.9255395,53.28994917869568,-0.08560645066419736,1739141213.9255443,53.28994917869568,3.0900447665848527,1739141213.925549,53.28994917869568,2.205214696015419 +1739141213.9431844,53.30994915962219,24.243486733264056,1739141213.9431903,53.30994915962219,0.004125018154690352,1739141213.9431973,53.30994915962219,88.20112103610475,1739141213.9432046,53.30994915962219,16.538636664275515,1739141213.943208,53.30994915962219,0.0052403672519024174,1739141213.943212,53.30994915962219,3.141447894239587,1739141213.9432156,53.30994915962219,0.39354708144177525,1739141213.9432187,53.30994915962219,0.050908210759775085,1739141213.9432218,53.30994915962219,2.1358653896758617,1739141213.9432259,53.30994915962219,0.0,1739141213.9432294,53.30994915962219,-0.03689944609073783,1739141213.9432325,53.30994915962219,3.09034782106246,1739141213.9432359,53.30994915962219,2.195958659054575 +1739141213.9617686,53.329949140548706,24.243486733264056,1739141213.9617739,53.329949140548706,0.004125018154690352,1739141213.9617803,53.329949140548706,88.20112103610475,1739141213.9617856,53.329949140548706,16.538636664275515,1739141213.9617882,53.329949140548706,0.0052403672519024174,1739141213.9617918,53.329949140548706,3.141447894239587,1739141213.9617944,53.329949140548706,0.39354708144177525,1739141213.9617968,53.329949140548706,0.050908210759775085,1739141213.9617991,53.329949140548706,2.1358653896758617,1739141213.9618022,53.329949140548706,0.0,1739141213.961805,53.329949140548706,-0.06009326937871329,1739141213.9618077,53.329949140548706,3.09034782106246,1739141213.96181,53.329949140548706,2.195958659054575 +1739141213.9809065,53.34994912147522,24.243486733264056,1739141213.9809098,53.34994912147522,0.004125018154690352,1739141213.9809139,53.34994912147522,88.20112103610475,1739141213.9809175,53.34994912147522,16.538636664275515,1739141213.9809194,53.34994912147522,0.0052403672519024174,1739141213.9809215,53.34994912147522,3.141447894239587,1739141213.9809234,53.34994912147522,0.39354708144177525,1739141213.980925,53.34994912147522,0.050908210759775085,1739141213.9809268,53.34994912147522,2.1358653896758617,1739141213.9809291,53.34994912147522,0.0,1739141213.9809308,53.34994912147522,-0.06009326937871329,1739141213.9809327,53.34994912147522,3.09034782106246,1739141213.9809344,53.34994912147522,2.195958659054575 +1739141214.0004458,53.36994910240173,24.243486733264056,1739141214.0004485,53.36994910240173,0.004125018154690352,1739141214.0004513,53.36994910240173,88.20112103610475,1739141214.000454,53.36994910240173,16.538636664275515,1739141214.0004551,53.36994910240173,0.0052403672519024174,1739141214.0004568,53.36994910240173,3.141447894239587,1739141214.0004582,53.36994910240173,0.39354708144177525,1739141214.0004594,53.36994910240173,0.050908210759775085,1739141214.0004609,53.36994910240173,2.1358653896758617,1739141214.0004623,53.36994910240173,0.0,1739141214.0004637,53.36994910240173,-0.06009326937871329,1739141214.0004652,53.36994910240173,3.09034782106246,1739141214.0004663,53.36994910240173,2.195958659054575 +1739141214.0196931,53.38994908332825,24.243486733264056,1739141214.0196955,53.38994908332825,0.004125018154690352,1739141214.0196981,53.38994908332825,88.20112103610475,1739141214.0197008,53.38994908332825,16.538636664275515,1739141214.0197022,53.38994908332825,0.0052403672519024174,1739141214.0197039,53.38994908332825,3.141447894239587,1739141214.0197053,53.38994908332825,0.39354708144177525,1739141214.0197062,53.38994908332825,0.050908210759775085,1739141214.0197077,53.38994908332825,2.1358653896758617,1739141214.019709,53.38994908332825,0.0,1739141214.0197105,53.38994908332825,-0.06009326937871329,1739141214.0197115,53.38994908332825,3.09034782106246,1739141214.0197127,53.38994908332825,2.195958659054575 +1739141214.0398524,53.40994906425476,24.243486733264056,1739141214.0398545,53.40994906425476,0.004125018154690352,1739141214.0398574,53.40994906425476,88.20112103610475,1739141214.0398602,53.40994906425476,16.538636664275515,1739141214.0398614,53.40994906425476,0.0052403672519024174,1739141214.0398633,53.40994906425476,3.141447894239587,1739141214.0398645,53.40994906425476,0.39354708144177525,1739141214.0398662,53.40994906425476,0.050908210759775085,1739141214.0398674,53.40994906425476,2.1358653896758617,1739141214.0398688,53.40994906425476,0.0,1739141214.0398705,53.40994906425476,-0.06009326937871329,1739141214.0398717,53.40994906425476,3.09034782106246,1739141214.0398731,53.40994906425476,2.195958659054575 +1739141214.0598626,53.429949045181274,24.002531244174328,1739141214.059865,53.429949045181274,0.01643553471461079,1739141214.0598679,53.429949045181274,88.60534034054294,1739141214.0598707,53.429949045181274,16.152794175854147,1739141214.059872,53.429949045181274,0.008,1739141214.0598736,53.429949045181274,-3.1405180275999016,1739141214.0598748,53.429949045181274,0.40691419582545435,1739141214.0598762,53.429949045181274,0.050712143855183245,1739141214.0598774,53.429949045181274,2.124475723416113,1739141214.0598788,53.429949045181274,0.0,1739141214.0598803,53.429949045181274,-0.07015438158915244,1739141214.0598814,53.429949045181274,3.0908061256151558,1739141214.0598826,53.429949045181274,2.189839096797453 +1739141214.0798767,53.44994902610779,24.002531244174328,1739141214.0798788,53.44994902610779,0.01643553471461079,1739141214.0798817,53.44994902610779,88.60534034054294,1739141214.0798843,53.44994902610779,16.152794175854147,1739141214.0798857,53.44994902610779,0.008,1739141214.0798874,53.44994902610779,-3.1405180275999016,1739141214.0798888,53.44994902610779,0.40691419582545435,1739141214.07989,53.44994902610779,0.050712143855183245,1739141214.0798912,53.44994902610779,2.124475723416113,1739141214.0798926,53.44994902610779,0.0,1739141214.079894,53.44994902610779,-0.06536337338133968,1739141214.0798953,53.44994902610779,3.0908061256151558,1739141214.0798967,53.44994902610779,2.189839096797453 +1739141214.0996735,53.4699490070343,24.002531244174328,1739141214.0996761,53.4699490070343,0.01643553471461079,1739141214.099679,53.4699490070343,88.60534034054294,1739141214.0996819,53.4699490070343,16.152794175854147,1739141214.099683,53.4699490070343,0.008,1739141214.099685,53.4699490070343,-3.1405180275999016,1739141214.0996864,53.4699490070343,0.40691419582545435,1739141214.0996876,53.4699490070343,0.050712143855183245,1739141214.099689,53.4699490070343,2.124475723416113,1739141214.0996907,53.4699490070343,0.0,1739141214.0996923,53.4699490070343,-0.06536337338133968,1739141214.0996935,53.4699490070343,3.0908061256151558,1739141214.0996947,53.4699490070343,2.189839096797453 +1739141214.1196654,53.489948987960815,24.002531244174328,1739141214.119668,53.489948987960815,0.01643553471461079,1739141214.1196709,53.489948987960815,88.60534034054294,1739141214.1196733,53.489948987960815,16.152794175854147,1739141214.119675,53.489948987960815,0.008,1739141214.1196768,53.489948987960815,-3.1405180275999016,1739141214.1196783,53.489948987960815,0.40691419582545435,1739141214.1196795,53.489948987960815,0.050712143855183245,1739141214.119681,53.489948987960815,2.124475723416113,1739141214.1196823,53.489948987960815,0.0,1739141214.119684,53.489948987960815,-0.06536337338133968,1739141214.1196854,53.489948987960815,3.0908061256151558,1739141214.1196866,53.489948987960815,2.189839096797453 +1739141214.139799,53.50994896888733,24.002531244174328,1739141214.1398015,53.50994896888733,0.01643553471461079,1739141214.1398046,53.50994896888733,88.60534034054294,1739141214.1398075,53.50994896888733,16.152794175854147,1739141214.1398087,53.50994896888733,0.008,1739141214.1398106,53.50994896888733,-3.1405180275999016,1739141214.139812,53.50994896888733,0.40691419582545435,1739141214.1398134,53.50994896888733,0.050712143855183245,1739141214.1398146,53.50994896888733,2.124475723416113,1739141214.1398163,53.50994896888733,0.0,1739141214.1398175,53.50994896888733,-0.06536337338133968,1739141214.1398184,53.50994896888733,3.0908061256151558,1739141214.1398199,53.50994896888733,2.189839096797453 +1739141214.1597276,53.52994894981384,23.76231719025209,1739141214.1597304,53.52994894981384,0.028593104879706566,1739141214.1597333,53.52994894981384,88.82799181485812,1739141214.1597364,53.52994894981384,15.951724302050241,1739141214.1597378,53.52994894981384,0.008241672632049215,1739141214.1597395,53.52994894981384,-3.138987040100248,1739141214.1597407,53.52994894981384,0.41307996403006514,1739141214.1597419,53.52994894981384,0.051997313559538766,1739141214.1597433,53.52994894981384,2.119242569404902,1739141214.1597447,53.52994894981384,0.0,1739141214.1597466,53.52994894981384,-0.0616208498678933,1739141214.1597478,53.52994894981384,3.0912866154180882,1739141214.159749,53.52994894981384,2.182645574217082 +1739141214.1796606,53.549948930740356,23.76231719025209,1739141214.1796632,53.549948930740356,0.028593104879706566,1739141214.1796658,53.549948930740356,88.82799181485812,1739141214.1796687,53.549948930740356,15.951724302050241,1739141214.1796703,53.549948930740356,0.008241672632049215,1739141214.1796718,53.549948930740356,-3.138987040100248,1739141214.1796734,53.549948930740356,0.41307996403006514,1739141214.1796746,53.549948930740356,0.051997313559538766,1739141214.1796758,53.549948930740356,2.119242569404902,1739141214.1796772,53.549948930740356,0.0,1739141214.1796787,53.549948930740356,-0.06340300481217964,1739141214.17968,53.549948930740356,3.0912866154180882,1739141214.1796813,53.549948930740356,2.182645574217082 +1739141214.1996675,53.56994891166687,23.76231719025209,1739141214.19967,53.56994891166687,0.028593104879706566,1739141214.1996732,53.56994891166687,88.82799181485812,1739141214.1996756,53.56994891166687,15.951724302050241,1739141214.1996772,53.56994891166687,0.008241672632049215,1739141214.1996787,53.56994891166687,-3.138987040100248,1739141214.19968,53.56994891166687,0.41307996403006514,1739141214.1996813,53.56994891166687,0.051997313559538766,1739141214.1996825,53.56994891166687,2.119242569404902,1739141214.1996841,53.56994891166687,0.0,1739141214.1996853,53.56994891166687,-0.06340300481217964,1739141214.1996868,53.56994891166687,3.0912866154180882,1739141214.1996882,53.56994891166687,2.182645574217082 +1739141214.2197247,53.589948892593384,23.76231719025209,1739141214.2197268,53.589948892593384,0.028593104879706566,1739141214.2197297,53.589948892593384,88.82799181485812,1739141214.2197325,53.589948892593384,15.951724302050241,1739141214.219734,53.589948892593384,0.008241672632049215,1739141214.2197359,53.589948892593384,-3.138987040100248,1739141214.2197373,53.589948892593384,0.41307996403006514,1739141214.2197387,53.589948892593384,0.051997313559538766,1739141214.2197402,53.589948892593384,2.119242569404902,1739141214.2197416,53.589948892593384,0.0,1739141214.2197435,53.589948892593384,-0.06340300481217964,1739141214.2197447,53.589948892593384,3.0912866154180882,1739141214.219746,53.589948892593384,2.182645574217082 +1739141214.2396932,53.6099488735199,23.76231719025209,1739141214.2396955,53.6099488735199,0.028593104879706566,1739141214.2396982,53.6099488735199,88.82799181485812,1739141214.239701,53.6099488735199,15.951724302050241,1739141214.2397025,53.6099488735199,0.008241672632049215,1739141214.2397041,53.6099488735199,-3.138987040100248,1739141214.2397053,53.6099488735199,0.41307996403006514,1739141214.2397065,53.6099488735199,0.051997313559538766,1739141214.239708,53.6099488735199,2.119242569404902,1739141214.2397099,53.6099488735199,0.0,1739141214.2397113,53.6099488735199,-0.06340300481217964,1739141214.2397127,53.6099488735199,3.0912866154180882,1739141214.2397141,53.6099488735199,2.182645574217082 +1739141214.259669,53.62994885444641,23.76231719025209,1739141214.2596714,53.62994885444641,0.028593104879706566,1739141214.2596743,53.62994885444641,88.82799181485812,1739141214.259677,53.62994885444641,15.951724302050241,1739141214.2596781,53.62994885444641,0.008241672632049215,1739141214.2596798,53.62994885444641,-3.138987040100248,1739141214.259681,53.62994885444641,0.41307996403006514,1739141214.2596824,53.62994885444641,0.051997313559538766,1739141214.2596836,53.62994885444641,2.119242569404902,1739141214.2596853,53.62994885444641,0.0,1739141214.2596867,53.62994885444641,-0.06340300481217964,1739141214.2596881,53.62994885444641,3.0912866154180882,1739141214.2596896,53.62994885444641,2.182645574217082 +1739141214.279708,53.649948835372925,23.522870856835254,1739141214.2797103,53.649948835372925,0.04058921272339955,1739141214.2797134,53.649948835372925,89.04894902858058,1739141214.279716,53.649948835372925,15.75148968395211,1739141214.2797177,53.649948835372925,0.009,1739141214.279719,53.649948835372925,-3.1375278627832905,1739141214.2797208,53.649948835372925,0.41802887217362694,1739141214.279722,53.649948835372925,0.053151858632968105,1739141214.2797232,53.649948835372925,2.1150515442492464,1739141214.279725,53.649948835372925,0.0,1739141214.2797265,53.649948835372925,-0.0582190064116857,1739141214.279728,53.649948835372925,3.091841107458554,1739141214.2797291,53.649948835372925,2.1757391225609934 +1739141214.2997937,53.66994881629944,23.522870856835254,1739141214.2997959,53.66994881629944,0.04058921272339955,1739141214.299799,53.66994881629944,89.04894902858058,1739141214.2998016,53.66994881629944,15.75148968395211,1739141214.2998028,53.66994881629944,0.009,1739141214.299805,53.66994881629944,-3.1375278627832905,1739141214.299806,53.66994881629944,0.41802887217362694,1739141214.2998078,53.66994881629944,0.053151858632968105,1739141214.299809,53.66994881629944,2.1150515442492464,1739141214.2998106,53.66994881629944,0.0,1739141214.2998118,53.66994881629944,-0.06068757831174709,1739141214.299813,53.66994881629944,3.091841107458554,1739141214.2998145,53.66994881629944,2.1757391225609934 +1739141214.3237448,53.68994879722595,23.522870856835254,1739141214.3237529,53.68994879722595,0.04058921272339955,1739141214.3237631,53.68994879722595,89.04894902858058,1739141214.323773,53.68994879722595,15.75148968395211,1739141214.3237777,53.68994879722595,0.009,1739141214.3237836,53.68994879722595,-3.1375278627832905,1739141214.3237884,53.68994879722595,0.41802887217362694,1739141214.3237934,53.68994879722595,0.053151858632968105,1739141214.3237977,53.68994879722595,2.1150515442492464,1739141214.3238034,53.68994879722595,0.0,1739141214.3238087,53.68994879722595,-0.06068757831174709,1739141214.3238132,53.68994879722595,3.091841107458554,1739141214.323818,53.68994879722595,2.1757391225609934 +1739141214.3448567,53.709948778152466,23.522870856835254,1739141214.344866,53.709948778152466,0.04058921272339955,1739141214.3448765,53.709948778152466,89.04894902858058,1739141214.3448865,53.709948778152466,15.75148968395211,1739141214.3448915,53.709948778152466,0.009,1739141214.344897,53.709948778152466,-3.1375278627832905,1739141214.3449018,53.709948778152466,0.41802887217362694,1739141214.3449066,53.709948778152466,0.053151858632968105,1739141214.3449109,53.709948778152466,2.1150515442492464,1739141214.3449168,53.709948778152466,0.0,1739141214.3449216,53.709948778152466,-0.06068757831174709,1739141214.344926,53.709948778152466,3.091841107458554,1739141214.3449306,53.709948778152466,2.1757391225609934 +1739141214.3653219,53.71994876861572,23.522870856835254,1739141214.3653316,53.71994876861572,0.04058921272339955,1739141214.3653424,53.71994876861572,89.04894902858058,1739141214.3653524,53.71994876861572,15.75148968395211,1739141214.3653574,53.71994876861572,0.009,1739141214.3653631,53.71994876861572,-3.1375278627832905,1739141214.3653681,53.71994876861572,0.41802887217362694,1739141214.3653727,53.71994876861572,0.053151858632968105,1739141214.365377,53.71994876861572,2.1150515442492464,1739141214.365383,53.71994876861572,0.0,1739141214.3653877,53.71994876861572,-0.06068757831174709,1739141214.3653924,53.71994876861572,3.091841107458554,1739141214.365397,53.71994876861572,2.1757391225609934 +1739141214.383494,53.74994874000549,23.284162698728537,1739141214.3835003,53.74994874000549,0.052408241641567876,1739141214.3835075,53.74994874000549,89.27011616926322,1739141214.3835142,53.74994874000549,15.550170661075462,1739141214.3835177,53.74994874000549,0.009,1739141214.3835223,53.74994874000549,-3.135980055900965,1739141214.3835256,53.74994874000549,0.423120018838158,1739141214.383529,53.74994874000549,0.05431955545167839,1739141214.3835323,53.74994874000549,2.110748711960417,1739141214.383536,53.74994874000549,0.0,1739141214.3835397,53.74994874000549,-0.05627145389019745,1739141214.3835428,53.74994874000549,3.092469650327041,1739141214.383546,53.74994874000549,2.1691230832923276 +1739141214.4021332,53.76994872093201,23.284162698728537,1739141214.4021378,53.76994872093201,0.052408241641567876,1739141214.4021432,53.76994872093201,89.27011616926322,1739141214.4021482,53.76994872093201,15.550170661075462,1739141214.4021509,53.76994872093201,0.009,1739141214.4021542,53.76994872093201,-3.135980055900965,1739141214.4021568,53.76994872093201,0.423120018838158,1739141214.4021595,53.76994872093201,0.05431955545167839,1739141214.4021618,53.76994872093201,2.110748711960417,1739141214.402165,53.76994872093201,0.0,1739141214.4021678,53.76994872093201,-0.0583743713319107,1739141214.4021704,53.76994872093201,3.092469650327041,1739141214.402173,53.76994872093201,2.1691230832923276 +1739141214.423947,53.78994870185852,23.284162698728537,1739141214.423952,53.78994870185852,0.052408241641567876,1739141214.4239578,53.78994870185852,89.27011616926322,1739141214.423963,53.78994870185852,15.550170661075462,1739141214.4239657,53.78994870185852,0.009,1739141214.423969,53.78994870185852,-3.135980055900965,1739141214.4239717,53.78994870185852,0.423120018838158,1739141214.423974,53.78994870185852,0.05431955545167839,1739141214.4239764,53.78994870185852,2.110748711960417,1739141214.4239798,53.78994870185852,0.0,1739141214.4239829,53.78994870185852,-0.0583743713319107,1739141214.4239855,53.78994870185852,3.092469650327041,1739141214.4239879,53.78994870185852,2.1691230832923276 +1739141214.4413366,53.809948682785034,23.284162698728537,1739141214.44134,53.809948682785034,0.052408241641567876,1739141214.4413435,53.809948682785034,89.27011616926322,1739141214.4413471,53.809948682785034,15.550170661075462,1739141214.4413488,53.809948682785034,0.009,1739141214.4413512,53.809948682785034,-3.135980055900965,1739141214.4413528,53.809948682785034,0.423120018838158,1739141214.4413545,53.809948682785034,0.05431955545167839,1739141214.4413562,53.809948682785034,2.110748711960417,1739141214.4413586,53.809948682785034,0.0,1739141214.4413605,53.809948682785034,-0.0583743713319107,1739141214.4413621,53.809948682785034,3.092469650327041,1739141214.441364,53.809948682785034,2.1691230832923276 +1739141214.4609897,53.82994866371155,23.284162698728537,1739141214.4609923,53.82994866371155,0.052408241641567876,1739141214.460995,53.82994866371155,89.27011616926322,1739141214.4609978,53.82994866371155,15.550170661075462,1739141214.4609993,53.82994866371155,0.009,1739141214.461001,53.82994866371155,-3.135980055900965,1739141214.4610023,53.82994866371155,0.423120018838158,1739141214.4610038,53.82994866371155,0.05431955545167839,1739141214.4610047,53.82994866371155,2.110748711960417,1739141214.4610066,53.82994866371155,0.0,1739141214.461008,53.82994866371155,-0.0583743713319107,1739141214.4610093,53.82994866371155,3.092469650327041,1739141214.4610107,53.82994866371155,2.1691230832923276 +1739141214.480234,53.84994864463806,23.284162698728537,1739141214.4802363,53.84994864463806,0.052408241641567876,1739141214.4802392,53.84994864463806,89.27011616926322,1739141214.4802413,53.84994864463806,15.550170661075462,1739141214.480243,53.84994864463806,0.009,1739141214.4802444,53.84994864463806,-3.135980055900965,1739141214.4802458,53.84994864463806,0.423120018838158,1739141214.480247,53.84994864463806,0.05431955545167839,1739141214.480248,53.84994864463806,2.110748711960417,1739141214.4802496,53.84994864463806,0.0,1739141214.4802508,53.84994864463806,-0.0583743713319107,1739141214.4802518,53.84994864463806,3.092469650327041,1739141214.4802532,53.84994864463806,2.1691230832923276 +1739141214.5003963,53.869948625564575,23.046159379998016,1739141214.5003989,53.869948625564575,0.06403936247850606,1739141214.5004015,53.869948625564575,89.3063885758825,1739141214.500404,53.869948625564575,15.532947082737474,1739141214.5004053,53.869948625564575,0.009,1739141214.5004067,53.869948625564575,-3.13426710816923,1739141214.5004084,53.869948625564575,0.4190699325853843,1739141214.5004096,53.869948625564575,0.05700603292573335,1739141214.5004106,53.869948625564575,2.1141709690357526,1739141214.5004122,53.869948625564575,0.0,1739141214.5004134,53.869948625564575,-0.03971898135528512,1739141214.5004146,53.869948625564575,3.0931130044409207,1739141214.5004158,53.869948625564575,2.162773473865234 +1739141214.5206666,53.88994860649109,23.046159379998016,1739141214.520669,53.88994860649109,0.06403936247850606,1739141214.5206716,53.88994860649109,89.3063885758825,1739141214.520674,53.88994860649109,15.532947082737474,1739141214.5206754,53.88994860649109,0.009,1739141214.5206769,53.88994860649109,-3.13426710816923,1739141214.520678,53.88994860649109,0.4190699325853843,1739141214.5206797,53.88994860649109,0.05700603292573335,1739141214.5206807,53.88994860649109,2.1141709690357526,1739141214.5206823,53.88994860649109,0.0,1739141214.5206835,53.88994860649109,-0.048602504829481585,1739141214.5206845,53.88994860649109,3.0931130044409207,1739141214.520686,53.88994860649109,2.162773473865234 +1739141214.5408144,53.9099485874176,23.046159379998016,1739141214.5408165,53.9099485874176,0.06403936247850606,1739141214.5408192,53.9099485874176,89.3063885758825,1739141214.540822,53.9099485874176,15.532947082737474,1739141214.5408232,53.9099485874176,0.009,1739141214.540825,53.9099485874176,-3.13426710816923,1739141214.540826,53.9099485874176,0.4190699325853843,1739141214.5408278,53.9099485874176,0.05700603292573335,1739141214.5408287,53.9099485874176,2.1141709690357526,1739141214.5408301,53.9099485874176,0.0,1739141214.5408316,53.9099485874176,-0.048602504829481585,1739141214.5408328,53.9099485874176,3.0931130044409207,1739141214.5408337,53.9099485874176,2.162773473865234 +1739141214.5666535,53.929948568344116,23.046159379998016,1739141214.5666668,53.929948568344116,0.06403936247850606,1739141214.5666888,53.929948568344116,89.3063885758825,1739141214.5667055,53.929948568344116,15.532947082737474,1739141214.5667133,53.929948568344116,0.009,1739141214.5667233,53.929948568344116,-3.13426710816923,1739141214.566735,53.929948568344116,0.4190699325853843,1739141214.5667436,53.929948568344116,0.05700603292573335,1739141214.566758,53.929948568344116,2.1141709690357526,1739141214.5667744,53.929948568344116,0.0,1739141214.5667799,53.929948568344116,-0.048602504829481585,1739141214.5667846,53.929948568344116,3.0931130044409207,1739141214.5667894,53.929948568344116,2.162773473865234 +1739141214.5830796,53.94994854927063,23.046159379998016,1739141214.583086,53.94994854927063,0.06403936247850606,1739141214.5830934,53.94994854927063,89.3063885758825,1739141214.583101,53.94994854927063,15.532947082737474,1739141214.5831044,53.94994854927063,0.009,1739141214.5831087,53.94994854927063,-3.13426710816923,1739141214.583112,53.94994854927063,0.4190699325853843,1739141214.583115,53.94994854927063,0.05700603292573335,1739141214.583118,53.94994854927063,2.1141709690357526,1739141214.5831223,53.94994854927063,0.0,1739141214.5831258,53.94994854927063,-0.048602504829481585,1739141214.583129,53.94994854927063,3.0931130044409207,1739141214.5831318,53.94994854927063,2.162773473865234 +1739141214.6022923,53.969948530197144,22.808790323435183,1739141214.602297,53.969948530197144,0.07547613887599702,1739141214.6023028,53.969948530197144,89.8065834972954,1739141214.6023085,53.969948530197144,15.048460458476553,1739141214.6023114,53.969948530197144,0.009,1739141214.6023147,53.969948530197144,-3.1330267144966992,1739141214.6023173,53.969948530197144,0.43650617833988786,1739141214.60232,53.969948530197144,0.0556556880467106,1739141214.602322,53.969948530197144,2.0994769883382,1739141214.602325,53.969948530197144,0.0,1739141214.6023276,53.969948530197144,-0.06665846890058061,1739141214.60233,53.969948530197144,3.0938825515430746,1739141214.6023324,53.969948530197144,2.157537374814568 +1739141214.622673,53.98994851112366,22.808790323435183,1739141214.6226761,53.98994851112366,0.07547613887599702,1739141214.6226797,53.98994851112366,89.8065834972954,1739141214.622683,53.98994851112366,15.048460458476553,1739141214.6226847,53.98994851112366,0.009,1739141214.6226866,53.98994851112366,-3.1330267144966992,1739141214.6226883,53.98994851112366,0.43650617833988786,1739141214.6226897,53.98994851112366,0.0556556880467106,1739141214.6226912,53.98994851112366,2.0994769883382,1739141214.6226928,53.98994851112366,0.0,1739141214.6226947,53.98994851112366,-0.05806038647636802,1739141214.6226962,53.98994851112366,3.0938825515430746,1739141214.6226974,53.98994851112366,2.157537374814568 +1739141214.6413865,54.00994849205017,22.808790323435183,1739141214.641389,54.00994849205017,0.07547613887599702,1739141214.6413918,54.00994849205017,89.8065834972954,1739141214.6413946,54.00994849205017,15.048460458476553,1739141214.6413963,54.00994849205017,0.009,1739141214.641398,54.00994849205017,-3.1330267144966992,1739141214.6413996,54.00994849205017,0.43650617833988786,1739141214.6414008,54.00994849205017,0.0556556880467106,1739141214.641402,54.00994849205017,2.0994769883382,1739141214.6414037,54.00994849205017,0.0,1739141214.641405,54.00994849205017,-0.05806038647636802,1739141214.6414065,54.00994849205017,3.0938825515430746,1739141214.6414077,54.00994849205017,2.157537374814568 +1739141214.6609378,54.029948472976685,22.808790323435183,1739141214.6609428,54.029948472976685,0.07547613887599702,1739141214.660947,54.029948472976685,89.8065834972954,1739141214.6609502,54.029948472976685,15.048460458476553,1739141214.6609519,54.029948472976685,0.009,1739141214.6609535,54.029948472976685,-3.1330267144966992,1739141214.6609554,54.029948472976685,0.43650617833988786,1739141214.6609566,54.029948472976685,0.0556556880467106,1739141214.6609583,54.029948472976685,2.0994769883382,1739141214.6609597,54.029948472976685,0.0,1739141214.6609616,54.029948472976685,-0.05806038647636802,1739141214.660963,54.029948472976685,3.0938825515430746,1739141214.6609645,54.029948472976685,2.157537374814568 +1739141214.6802647,54.0499484539032,22.808790323435183,1739141214.6802676,54.0499484539032,0.07547613887599702,1739141214.6802704,54.0499484539032,89.8065834972954,1739141214.680273,54.0499484539032,15.048460458476553,1739141214.6802747,54.0499484539032,0.009,1739141214.6802764,54.0499484539032,-3.1330267144966992,1739141214.6802778,54.0499484539032,0.43650617833988786,1739141214.6802793,54.0499484539032,0.0556556880467106,1739141214.6802807,54.0499484539032,2.0994769883382,1739141214.680282,54.0499484539032,0.0,1739141214.6802835,54.0499484539032,-0.05806038647636802,1739141214.680285,54.0499484539032,3.0938825515430746,1739141214.6802862,54.0499484539032,2.157537374814568 +1739141214.700495,54.06994843482971,22.808790323435183,1739141214.7004979,54.06994843482971,0.07547613887599702,1739141214.700501,54.06994843482971,89.8065834972954,1739141214.700504,54.06994843482971,15.048460458476553,1739141214.7005055,54.06994843482971,0.009,1739141214.7005076,54.06994843482971,-3.1330267144966992,1739141214.700509,54.06994843482971,0.43650617833988786,1739141214.7005107,54.06994843482971,0.0556556880467106,1739141214.7005117,54.06994843482971,2.0994769883382,1739141214.7005134,54.06994843482971,0.0,1739141214.700515,54.06994843482971,-0.05806038647636802,1739141214.7005165,54.06994843482971,3.0938825515430746,1739141214.7005177,54.06994843482971,2.157537374814568 +1739141214.7205405,54.089948415756226,22.572061484306275,1739141214.7205434,54.089948415756226,0.08669212439000695,1739141214.7205462,54.089948415756226,90.60071932040674,1739141214.7205493,54.089948415756226,14.273906953459631,1739141214.7205513,54.089948415756226,0.009,1739141214.7205532,54.089948415756226,-3.1322303484999496,1739141214.7205546,54.089948415756226,0.4666759756254263,1739141214.7205558,54.089948415756226,0.05203936606844531,1739141214.7205567,54.089948415756226,2.0742929354731476,1739141214.7205584,54.089948415756226,0.0,1739141214.7205596,54.089948415756226,-0.09367757387896763,1739141214.7205613,54.089948415756226,3.0946892145379454,1739141214.7205627,54.089948415756226,2.1510099354497583 +1739141214.740476,54.10994839668274,22.572061484306275,1739141214.7404792,54.10994839668274,0.08669212439000695,1739141214.7404826,54.10994839668274,90.60071932040674,1739141214.7404852,54.10994839668274,14.273906953459631,1739141214.7404866,54.10994839668274,0.009,1739141214.7404883,54.10994839668274,-3.1322303484999496,1739141214.7404895,54.10994839668274,0.4666759756254263,1739141214.7404907,54.10994839668274,0.05203936606844531,1739141214.7404923,54.10994839668274,2.0742929354731476,1739141214.7404938,54.10994839668274,0.0,1739141214.7404954,54.10994839668274,-0.07671699997661063,1739141214.7404969,54.10994839668274,3.0946892145379454,1739141214.740498,54.10994839668274,2.1510099354497583 +1739141214.7603214,54.12994837760925,22.572061484306275,1739141214.7603235,54.12994837760925,0.08669212439000695,1739141214.7603261,54.12994837760925,90.60071932040674,1739141214.7603292,54.12994837760925,14.273906953459631,1739141214.7603304,54.12994837760925,0.009,1739141214.7603323,54.12994837760925,-3.1322303484999496,1739141214.7603335,54.12994837760925,0.4666759756254263,1739141214.7603347,54.12994837760925,0.05203936606844531,1739141214.7603362,54.12994837760925,2.0742929354731476,1739141214.7603376,54.12994837760925,0.0,1739141214.7603393,54.12994837760925,-0.07671699997661063,1739141214.7603405,54.12994837760925,3.0946892145379454,1739141214.7603414,54.12994837760925,2.1510099354497583 +1739141214.7803528,54.14994835853577,22.572061484306275,1739141214.7803552,54.14994835853577,0.08669212439000695,1739141214.780358,54.14994835853577,90.60071932040674,1739141214.7803612,54.14994835853577,14.273906953459631,1739141214.7803626,54.14994835853577,0.009,1739141214.7803643,54.14994835853577,-3.1322303484999496,1739141214.7803655,54.14994835853577,0.4666759756254263,1739141214.780367,54.14994835853577,0.05203936606844531,1739141214.780368,54.14994835853577,2.0742929354731476,1739141214.78037,54.14994835853577,0.0,1739141214.7803714,54.14994835853577,-0.07671699997661063,1739141214.7803726,54.14994835853577,3.0946892145379454,1739141214.780374,54.14994835853577,2.1510099354497583 +1739141214.8003232,54.16994833946228,22.572061484306275,1739141214.8003256,54.16994833946228,0.08669212439000695,1739141214.8003285,54.16994833946228,90.60071932040674,1739141214.800331,54.16994833946228,14.273906953459631,1739141214.8003325,54.16994833946228,0.009,1739141214.800334,54.16994833946228,-3.1322303484999496,1739141214.8003356,54.16994833946228,0.4666759756254263,1739141214.8003368,54.16994833946228,0.05203936606844531,1739141214.8003383,54.16994833946228,2.0742929354731476,1739141214.8003397,54.16994833946228,0.0,1739141214.8003411,54.16994833946228,-0.07671699997661063,1739141214.8003426,54.16994833946228,3.0946892145379454,1739141214.8003435,54.16994833946228,2.1510099354497583 +1739141214.8203392,54.189948320388794,22.33613641666878,1739141214.8203416,54.189948320388794,0.09767931219556569,1739141214.8203442,54.189948320388794,90.61653728712626,1739141214.820347,54.189948320388794,14.283725290896188,1739141214.8203485,54.189948320388794,0.009,1739141214.82035,54.189948320388794,-3.130580333673067,1739141214.8203511,54.189948320388794,0.45964385953032444,1739141214.8203526,54.189948320388794,0.05442901538916492,1739141214.8203537,54.189948320388794,2.0801358166794834,1739141214.8203554,54.189948320388794,0.0,1739141214.8203568,54.189948320388794,-0.04924838437266887,1739141214.820358,54.189948320388794,3.0954958775328163,1739141214.8203595,54.189948320388794,2.1424645007310676 +1739141214.8403058,54.20994830131531,22.33613641666878,1739141214.840308,54.20994830131531,0.09767931219556569,1739141214.8403108,54.20994830131531,90.61653728712626,1739141214.8403134,54.20994830131531,14.283725290896188,1739141214.8403146,54.20994830131531,0.009,1739141214.8403165,54.20994830131531,-3.130580333673067,1739141214.8403177,54.20994830131531,0.45964385953032444,1739141214.840319,54.20994830131531,0.05442901538916492,1739141214.84032,54.20994830131531,2.0801358166794834,1739141214.8403218,54.20994830131531,0.0,1739141214.8403232,54.20994830131531,-0.062328684051584204,1739141214.8403246,54.20994830131531,3.0954958775328163,1739141214.8403258,54.20994830131531,2.1424645007310676 +1739141214.8603349,54.22994828224182,22.33613641666878,1739141214.8603368,54.22994828224182,0.09767931219556569,1739141214.86034,54.22994828224182,90.61653728712626,1739141214.8603427,54.22994828224182,14.283725290896188,1739141214.8603444,54.22994828224182,0.009,1739141214.8603458,54.22994828224182,-3.130580333673067,1739141214.8603475,54.22994828224182,0.45964385953032444,1739141214.860349,54.22994828224182,0.05442901538916492,1739141214.8603501,54.22994828224182,2.0801358166794834,1739141214.860352,54.22994828224182,0.0,1739141214.8603535,54.22994828224182,-0.062328684051584204,1739141214.860355,54.22994828224182,3.0954958775328163,1739141214.860356,54.22994828224182,2.1424645007310676 +1739141214.8803756,54.249948263168335,22.33613641666878,1739141214.880378,54.249948263168335,0.09767931219556569,1739141214.8803809,54.249948263168335,90.61653728712626,1739141214.8803835,54.249948263168335,14.283725290896188,1739141214.8803847,54.249948263168335,0.009,1739141214.8803866,54.249948263168335,-3.130580333673067,1739141214.8803878,54.249948263168335,0.45964385953032444,1739141214.8803895,54.249948263168335,0.05442901538916492,1739141214.8803906,54.249948263168335,2.0801358166794834,1739141214.880392,54.249948263168335,0.0,1739141214.8803937,54.249948263168335,-0.062328684051584204,1739141214.880395,54.249948263168335,3.0954958775328163,1739141214.8803964,54.249948263168335,2.1424645007310676 +1739141214.9004912,54.26994824409485,22.33613641666878,1739141214.9004936,54.26994824409485,0.09767931219556569,1739141214.9004965,54.26994824409485,90.61653728712626,1739141214.900499,54.26994824409485,14.283725290896188,1739141214.9005005,54.26994824409485,0.009,1739141214.9005022,54.26994824409485,-3.130580333673067,1739141214.9005036,54.26994824409485,0.45964385953032444,1739141214.900505,54.26994824409485,0.05442901538916492,1739141214.9005063,54.26994824409485,2.0801358166794834,1739141214.9005082,54.26994824409485,0.0,1739141214.9005096,54.26994824409485,-0.062328684051584204,1739141214.900511,54.26994824409485,3.0954958775328163,1739141214.9005122,54.26994824409485,2.1424645007310676 +1739141214.92041,54.28994822502136,22.33613641666878,1739141214.920412,54.28994822502136,0.09767931219556569,1739141214.920415,54.28994822502136,90.61653728712626,1739141214.9204175,54.28994822502136,14.283725290896188,1739141214.9204187,54.28994822502136,0.009,1739141214.9204206,54.28994822502136,-3.130580333673067,1739141214.9204218,54.28994822502136,0.45964385953032444,1739141214.9204233,54.28994822502136,0.05442901538916492,1739141214.9204242,54.28994822502136,2.0801358166794834,1739141214.9204257,54.28994822502136,0.0,1739141214.9204273,54.28994822502136,-0.062328684051584204,1739141214.9204285,54.28994822502136,3.0954958775328163,1739141214.9204297,54.28994822502136,2.1424645007310676 +1739141214.9403565,54.309948205947876,22.101028478952294,1739141214.9403589,54.309948205947876,0.10843837404252366,1739141214.940362,54.309948205947876,90.63230027801511,1739141214.9403648,54.309948205947876,14.287657659580917,1739141214.940366,54.309948205947876,0.009,1739141214.9403677,54.309948205947876,-3.12886664733367,1739141214.9403691,54.309948205947876,0.45308389247778147,1739141214.9403708,54.309948205947876,0.05698235602893574,1739141214.9403718,54.309948205947876,2.0856012331027878,1739141214.9403732,54.309948205947876,0.0,1739141214.9403746,54.309948205947876,-0.039361286175518866,1739141214.9403758,54.309948205947876,3.096302540527687,1739141214.9403772,54.309948205947876,2.1358993808732065 +1739141214.9603338,54.32994818687439,22.101028478952294,1739141214.9603364,54.32994818687439,0.10843837404252366,1739141214.9603393,54.32994818687439,90.63230027801511,1739141214.9603422,54.32994818687439,14.287657659580917,1739141214.9603436,54.32994818687439,0.009,1739141214.9603453,54.32994818687439,-3.12886664733367,1739141214.9603467,54.32994818687439,0.45308389247778147,1739141214.9603481,54.32994818687439,0.05698235602893574,1739141214.960349,54.32994818687439,2.0856012331027878,1739141214.9603508,54.32994818687439,0.0,1739141214.9603522,54.32994818687439,-0.050298147770418744,1739141214.9603534,54.32994818687439,3.096302540527687,1739141214.9603546,54.32994818687439,2.1358993808732065 +1739141214.9803154,54.3499481678009,22.101028478952294,1739141214.9803176,54.3499481678009,0.10843837404252366,1739141214.9803205,54.3499481678009,90.63230027801511,1739141214.980323,54.3499481678009,14.287657659580917,1739141214.9803243,54.3499481678009,0.009,1739141214.980326,54.3499481678009,-3.12886664733367,1739141214.9803274,54.3499481678009,0.45308389247778147,1739141214.9803288,54.3499481678009,0.05698235602893574,1739141214.98033,54.3499481678009,2.0856012331027878,1739141214.9803314,54.3499481678009,0.0,1739141214.9803329,54.3499481678009,-0.050298147770418744,1739141214.980334,54.3499481678009,3.096302540527687,1739141214.9803355,54.3499481678009,2.1358993808732065 +1739141215.0004365,54.36994814872742,22.101028478952294,1739141215.0004406,54.36994814872742,0.10843837404252366,1739141215.000445,54.36994814872742,90.63230027801511,1739141215.0004487,54.36994814872742,14.287657659580917,1739141215.0004508,54.36994814872742,0.009,1739141215.0004532,54.36994814872742,-3.12886664733367,1739141215.0004554,54.36994814872742,0.45308389247778147,1739141215.0004575,54.36994814872742,0.05698235602893574,1739141215.0004592,54.36994814872742,2.0856012331027878,1739141215.0004625,54.36994814872742,0.0,1739141215.0004647,54.36994814872742,-0.050298147770418744,1739141215.0004663,54.36994814872742,3.096302540527687,1739141215.0004685,54.36994814872742,2.1358993808732065 +1739141215.022542,54.38994812965393,22.101028478952294,1739141215.0225477,54.38994812965393,0.10843837404252366,1739141215.0225515,54.38994812965393,90.63230027801511,1739141215.0225544,54.38994812965393,14.287657659580917,1739141215.0225556,54.38994812965393,0.009,1739141215.0225575,54.38994812965393,-3.12886664733367,1739141215.022559,54.38994812965393,0.45308389247778147,1739141215.0225604,54.38994812965393,0.05698235602893574,1739141215.0225613,54.38994812965393,2.0856012331027878,1739141215.0225627,54.38994812965393,0.0,1739141215.0225642,54.38994812965393,-0.050298147770418744,1739141215.0225654,54.38994812965393,3.096302540527687,1739141215.0225666,54.38994812965393,2.1358993808732065 +1739141215.040451,54.409948110580444,21.866585039179412,1739141215.0404537,54.409948110580444,0.11897751157963743,1739141215.0404565,54.409948110580444,90.64801852761744,1739141215.0404592,54.409948110580444,14.2881495115834,1739141215.0404606,54.409948110580444,0.009,1739141215.0404623,54.409948110580444,-3.1270817704522575,1739141215.0404637,54.409948110580444,0.44687250915721777,1739141215.0404649,54.409948110580444,0.05973610259132221,1739141215.040466,54.409948110580444,2.0907894631360286,1739141215.0404677,54.409948110580444,0.0,1739141215.040469,54.409948110580444,-0.030077816593949314,1739141215.0404704,54.409948110580444,3.097109203522558,1739141215.0404716,54.409948110580444,2.1304960136716034 +1739141215.0621545,54.42994809150696,21.866585039179412,1739141215.0621593,54.42994809150696,0.11897751157963743,1739141215.0621638,54.42994809150696,90.64801852761744,1739141215.062168,54.42994809150696,14.2881495115834,1739141215.06217,54.42994809150696,0.009,1739141215.0621727,54.42994809150696,-3.1270817704522575,1739141215.062175,54.42994809150696,0.44687250915721777,1739141215.062177,54.42994809150696,0.05973610259132221,1739141215.0621793,54.42994809150696,2.0907894631360286,1739141215.0621817,54.42994809150696,0.0,1739141215.0621839,54.42994809150696,-0.0397065505355747,1739141215.0621862,54.42994809150696,3.097109203522558,1739141215.0621889,54.42994809150696,2.1304960136716034 +1739141215.0824015,54.44994807243347,21.866585039179412,1739141215.0824058,54.44994807243347,0.11897751157963743,1739141215.0824103,54.44994807243347,90.64801852761744,1739141215.082415,54.44994807243347,14.2881495115834,1739141215.0824175,54.44994807243347,0.009,1739141215.08242,54.44994807243347,-3.1270817704522575,1739141215.082423,54.44994807243347,0.44687250915721777,1739141215.0824256,54.44994807243347,0.05973610259132221,1739141215.082428,54.44994807243347,2.0907894631360286,1739141215.0824306,54.44994807243347,0.0,1739141215.082433,54.44994807243347,-0.0397065505355747,1739141215.0824354,54.44994807243347,3.097109203522558,1739141215.0824375,54.44994807243347,2.1304960136716034 +1739141215.1029503,54.469948053359985,21.866585039179412,1739141215.1029541,54.469948053359985,0.11897751157963743,1739141215.1029587,54.469948053359985,90.64801852761744,1739141215.1029637,54.469948053359985,14.2881495115834,1739141215.1029668,54.469948053359985,0.009,1739141215.1029704,54.469948053359985,-3.1270817704522575,1739141215.1029737,54.469948053359985,0.44687250915721777,1739141215.1029773,54.469948053359985,0.05973610259132221,1739141215.1029806,54.469948053359985,2.0907894631360286,1739141215.102984,54.469948053359985,0.0,1739141215.1029875,54.469948053359985,-0.0397065505355747,1739141215.1029909,54.469948053359985,3.097109203522558,1739141215.1029942,54.469948053359985,2.1304960136716034 +1739141215.121974,54.4899480342865,21.866585039179412,1739141215.1219769,54.4899480342865,0.11897751157963743,1739141215.1219795,54.4899480342865,90.64801852761744,1739141215.1219819,54.4899480342865,14.2881495115834,1739141215.1219838,54.4899480342865,0.009,1739141215.1219852,54.4899480342865,-3.1270817704522575,1739141215.1219866,54.4899480342865,0.44687250915721777,1739141215.1219878,54.4899480342865,0.05973610259132221,1739141215.1219888,54.4899480342865,2.0907894631360286,1739141215.1219904,54.4899480342865,0.0,1739141215.1219916,54.4899480342865,-0.0397065505355747,1739141215.121993,54.4899480342865,3.097109203522558,1739141215.1219943,54.4899480342865,2.1304960136716034 +1739141215.140733,54.50994801521301,21.866585039179412,1739141215.1407356,54.50994801521301,0.11897751157963743,1739141215.1407385,54.50994801521301,90.64801852761744,1739141215.140741,54.50994801521301,14.2881495115834,1739141215.1407423,54.50994801521301,0.009,1739141215.1407442,54.50994801521301,-3.1270817704522575,1739141215.1407456,54.50994801521301,0.44687250915721777,1739141215.1407473,54.50994801521301,0.05973610259132221,1739141215.1407485,54.50994801521301,2.0907894631360286,1739141215.1407502,54.50994801521301,0.0,1739141215.1407516,54.50994801521301,-0.0397065505355747,1739141215.1407528,54.50994801521301,3.097109203522558,1739141215.1407542,54.50994801521301,2.1304960136716034 +1739141215.1607413,54.529947996139526,21.632657560590623,1739141215.1607442,54.529947996139526,0.12929724454967673,1739141215.1607473,54.529947996139526,91.01093106555554,1739141215.16075,54.529947996139526,13.937711221067449,1739141215.1607513,54.529947996139526,0.008,1739141215.1607533,54.529947996139526,-3.1258307243875847,1739141215.1607552,54.529947996139526,0.45659400213811013,1739141215.1607566,54.529947996139526,0.059199216027214306,1739141215.1607575,54.529947996139526,2.0826750122403626,1739141215.1607592,54.529947996139526,0.0,1739141215.1607606,54.529947996139526,-0.04726231736127823,1739141215.1607618,54.529947996139526,3.097990225338867,1739141215.160763,54.529947996139526,2.1263393436015736 +1739141215.1801603,54.54994797706604,21.632657560590623,1739141215.1801622,54.54994797706604,0.12929724454967673,1739141215.1801648,54.54994797706604,91.01093106555554,1739141215.1801672,54.54994797706604,13.937711221067449,1739141215.1801684,54.54994797706604,0.008,1739141215.18017,54.54994797706604,-3.1258307243875847,1739141215.1801713,54.54994797706604,0.45659400213811013,1739141215.1801722,54.54994797706604,0.059199216027214306,1739141215.1801736,54.54994797706604,2.0826750122403626,1739141215.180175,54.54994797706604,0.0,1739141215.180176,54.54994797706604,-0.04366433136121106,1739141215.1801775,54.54994797706604,3.097990225338867,1739141215.1801784,54.54994797706604,2.1263393436015736 +1739141215.2002494,54.569947957992554,21.632657560590623,1739141215.2002516,54.569947957992554,0.12929724454967673,1739141215.2002544,54.569947957992554,91.01093106555554,1739141215.200257,54.569947957992554,13.937711221067449,1739141215.2002583,54.569947957992554,0.008,1739141215.2002602,54.569947957992554,-3.1258307243875847,1739141215.2002614,54.569947957992554,0.45659400213811013,1739141215.2002625,54.569947957992554,0.059199216027214306,1739141215.2002637,54.569947957992554,2.0826750122403626,1739141215.2002652,54.569947957992554,0.0,1739141215.2002668,54.569947957992554,-0.04366433136121106,1739141215.200268,54.569947957992554,3.097990225338867,1739141215.2002692,54.569947957992554,2.1263393436015736 +1739141215.2202904,54.58994793891907,21.632657560590623,1739141215.2202928,54.58994793891907,0.12929724454967673,1739141215.2202954,54.58994793891907,91.01093106555554,1739141215.220298,54.58994793891907,13.937711221067449,1739141215.2202995,54.58994793891907,0.008,1739141215.2203012,54.58994793891907,-3.1258307243875847,1739141215.2203023,54.58994793891907,0.45659400213811013,1739141215.2203035,54.58994793891907,0.059199216027214306,1739141215.220305,54.58994793891907,2.0826750122403626,1739141215.2203064,54.58994793891907,0.0,1739141215.2203078,54.58994793891907,-0.04366433136121106,1739141215.220309,54.58994793891907,3.097990225338867,1739141215.2203102,54.58994793891907,2.1263393436015736 +1739141215.2403414,54.60994791984558,21.632657560590623,1739141215.2403438,54.60994791984558,0.12929724454967673,1739141215.240347,54.60994791984558,91.01093106555554,1739141215.2403495,54.60994791984558,13.937711221067449,1739141215.2403507,54.60994791984558,0.008,1739141215.2403526,54.60994791984558,-3.1258307243875847,1739141215.240354,54.60994791984558,0.45659400213811013,1739141215.2403553,54.60994791984558,0.059199216027214306,1739141215.2403567,54.60994791984558,2.0826750122403626,1739141215.2403579,54.60994791984558,0.0,1739141215.2403593,54.60994791984558,-0.04366433136121106,1739141215.2403605,54.60994791984558,3.097990225338867,1739141215.2403617,54.60994791984558,2.1263393436015736 +1739141215.2605028,54.629947900772095,21.399219482437456,1739141215.2605052,54.629947900772095,0.13938775549374327,1739141215.2605078,54.629947900772095,91.33634910970854,1739141215.260511,54.629947900772095,13.626721062103902,1739141215.2605124,54.629947900772095,0.008,1739141215.2605138,54.629947900772095,-3.1246900778946536,1739141215.260515,54.629947900772095,0.4631612411897165,1739141215.2605164,54.629947900772095,0.058856216071218416,1739141215.2605174,54.629947900772095,2.0772112219168664,1739141215.260519,54.629947900772095,0.0,1739141215.2605202,54.629947900772095,-0.044913822880215046,1739141215.2605214,54.629947900772095,3.0988786830373196,1739141215.2605228,54.629947900772095,2.1215300485384243 +1739141215.2803247,54.64994788169861,21.399219482437456,1739141215.2803268,54.64994788169861,0.13938775549374327,1739141215.28033,54.64994788169861,91.33634910970854,1739141215.2803326,54.64994788169861,13.626721062103902,1739141215.2803338,54.64994788169861,0.008,1739141215.2803357,54.64994788169861,-3.1246900778946536,1739141215.2803369,54.64994788169861,0.4631612411897165,1739141215.2803385,54.64994788169861,0.058856216071218416,1739141215.2803395,54.64994788169861,2.0772112219168664,1739141215.280341,54.64994788169861,0.0,1739141215.2803426,54.64994788169861,-0.04431882662155795,1739141215.2803438,54.64994788169861,3.0988786830373196,1739141215.2803452,54.64994788169861,2.1215300485384243 +1739141215.30029,54.66994786262512,21.399219482437456,1739141215.3002923,54.66994786262512,0.13938775549374327,1739141215.3002949,54.66994786262512,91.33634910970854,1739141215.3002977,54.66994786262512,13.626721062103902,1739141215.300299,54.66994786262512,0.008,1739141215.3003006,54.66994786262512,-3.1246900778946536,1739141215.300302,54.66994786262512,0.4631612411897165,1739141215.3003035,54.66994786262512,0.058856216071218416,1739141215.3003044,54.66994786262512,2.0772112219168664,1739141215.3003058,54.66994786262512,0.0,1739141215.3003073,54.66994786262512,-0.04431882662155795,1739141215.3003085,54.66994786262512,3.0988786830373196,1739141215.3003097,54.66994786262512,2.1215300485384243 +1739141215.3203394,54.689947843551636,21.399219482437456,1739141215.3203416,54.689947843551636,0.13938775549374327,1739141215.3203442,54.689947843551636,91.33634910970854,1739141215.3203468,54.689947843551636,13.626721062103902,1739141215.3203483,54.689947843551636,0.008,1739141215.3203497,54.689947843551636,-3.1246900778946536,1739141215.320351,54.689947843551636,0.4631612411897165,1739141215.3203523,54.689947843551636,0.058856216071218416,1739141215.3203533,54.689947843551636,2.0772112219168664,1739141215.3203547,54.689947843551636,0.0,1739141215.3203564,54.689947843551636,-0.04431882662155795,1739141215.3203573,54.689947843551636,3.0988786830373196,1739141215.3203588,54.689947843551636,2.1215300485384243 +1739141215.3402812,54.70994782447815,21.399219482437456,1739141215.3402839,54.70994782447815,0.13938775549374327,1739141215.3402867,54.70994782447815,91.33634910970854,1739141215.3402894,54.70994782447815,13.626721062103902,1739141215.3402908,54.70994782447815,0.008,1739141215.3402925,54.70994782447815,-3.1246900778946536,1739141215.3402936,54.70994782447815,0.4631612411897165,1739141215.3402948,54.70994782447815,0.058856216071218416,1739141215.340296,54.70994782447815,2.0772112219168664,1739141215.3402975,54.70994782447815,0.0,1739141215.3402987,54.70994782447815,-0.04431882662155795,1739141215.3403,54.70994782447815,3.0988786830373196,1739141215.3403013,54.70994782447815,2.1215300485384243 +1739141215.3603013,54.72994780540466,21.399219482437456,1739141215.3603036,54.72994780540466,0.13938775549374327,1739141215.3603065,54.72994780540466,91.33634910970854,1739141215.3603094,54.72994780540466,13.626721062103902,1739141215.3603108,54.72994780540466,0.008,1739141215.3603122,54.72994780540466,-3.1246900778946536,1739141215.3603137,54.72994780540466,0.4631612411897165,1739141215.3603148,54.72994780540466,0.058856216071218416,1739141215.3603163,54.72994780540466,2.0772112219168664,1739141215.3603177,54.72994780540466,0.0,1739141215.360319,54.72994780540466,-0.04431882662155795,1739141215.3603203,54.72994780540466,3.0988786830373196,1739141215.3603215,54.72994780540466,2.1215300485384243 +1739141215.3803244,54.74994778633118,21.166304023505656,1739141215.3803267,54.74994778633118,0.14924836191212165,1739141215.3803294,54.74994778633118,91.36244550171531,1739141215.3803322,54.74994778633118,13.615218100484357,1739141215.380334,54.74994778633118,0.007950582055421847,1739141215.3803356,54.74994778633118,-3.122882590819816,1739141215.380337,54.74994778633118,0.45691017242882465,1739141215.3803382,54.74994778633118,0.0615120661421812,1739141215.3803394,54.74994778633118,2.082411636909371,1739141215.380341,54.74994778633118,0.0,1739141215.3803422,54.74994778633118,-0.0251041588714346,1739141215.3803434,54.74994778633118,3.0997671407357723,1739141215.3803449,54.74994778633118,2.1166656421373267 +1739141215.400458,54.76994776725769,21.166304023505656,1739141215.4004605,54.76994776725769,0.14924836191212165,1739141215.4004638,54.76994776725769,91.36244550171531,1739141215.4004667,54.76994776725769,13.615218100484357,1739141215.400468,54.76994776725769,0.007950582055421847,1739141215.4004705,54.76994776725769,-3.122882590819816,1739141215.4004722,54.76994776725769,0.45691017242882465,1739141215.4004734,54.76994776725769,0.0615120661421812,1739141215.4004743,54.76994776725769,2.082411636909371,1739141215.400476,54.76994776725769,0.0,1739141215.4004774,54.76994776725769,-0.03425400522795563,1739141215.4004796,54.76994776725769,3.0997671407357723,1739141215.400481,54.76994776725769,2.1166656421373267 +1739141215.4202738,54.789947748184204,21.166304023505656,1739141215.420276,54.789947748184204,0.14924836191212165,1739141215.4202788,54.789947748184204,91.36244550171531,1739141215.4202814,54.789947748184204,13.615218100484357,1739141215.4202828,54.789947748184204,0.007950582055421847,1739141215.4202845,54.789947748184204,-3.122882590819816,1739141215.4202857,54.789947748184204,0.45691017242882465,1739141215.420287,54.789947748184204,0.0615120661421812,1739141215.4202883,54.789947748184204,2.082411636909371,1739141215.4202898,54.789947748184204,0.0,1739141215.4202914,54.789947748184204,-0.03425400522795563,1739141215.4202926,54.789947748184204,3.0997671407357723,1739141215.4202938,54.789947748184204,2.1166656421373267 +1739141215.4402864,54.80994772911072,21.166304023505656,1739141215.4402888,54.80994772911072,0.14924836191212165,1739141215.4402916,54.80994772911072,91.36244550171531,1739141215.4402945,54.80994772911072,13.615218100484357,1739141215.4402957,54.80994772911072,0.007950582055421847,1739141215.4402974,54.80994772911072,-3.122882590819816,1739141215.4402988,54.80994772911072,0.45691017242882465,1739141215.4403,54.80994772911072,0.0615120661421812,1739141215.4403014,54.80994772911072,2.082411636909371,1739141215.4403028,54.80994772911072,0.0,1739141215.4403043,54.80994772911072,-0.03425400522795563,1739141215.4403055,54.80994772911072,3.0997671407357723,1739141215.4403067,54.80994772911072,2.1166656421373267 +1739141215.4603362,54.82994771003723,21.166304023505656,1739141215.4603384,54.82994771003723,0.14924836191212165,1739141215.4603412,54.82994771003723,91.36244550171531,1739141215.4603438,54.82994771003723,13.615218100484357,1739141215.460345,54.82994771003723,0.007950582055421847,1739141215.4603467,54.82994771003723,-3.122882590819816,1739141215.4603481,54.82994771003723,0.45691017242882465,1739141215.4603493,54.82994771003723,0.0615120661421812,1739141215.4603505,54.82994771003723,2.082411636909371,1739141215.4603522,54.82994771003723,0.0,1739141215.4603536,54.82994771003723,-0.03425400522795563,1739141215.4603548,54.82994771003723,3.0997671407357723,1739141215.460356,54.82994771003723,2.1166656421373267 +1739141215.4802995,54.849947690963745,20.93385208711587,1739141215.4803019,54.849947690963745,0.15887677802423728,1739141215.4803047,54.849947690963745,91.50647844695837,1739141215.480307,54.849947690963745,13.482182123730986,1739141215.4803085,54.849947690963745,0.007,1739141215.48031,54.849947690963745,-3.1212138990687466,1739141215.4803114,54.849947690963745,0.45621534652095913,1739141215.4803126,54.849947690963745,0.0630637131016645,1739141215.4803138,54.849947690963745,2.082990482767531,1739141215.4803154,54.849947690963745,0.0,1739141215.480317,54.849947690963745,-0.02615344638986296,1739141215.4803185,54.849947690963745,3.1007225969936574,1739141215.4803195,54.849947690963745,2.1130013400548595 +1739141215.5002759,54.86994767189026,20.93385208711587,1739141215.5002782,54.86994767189026,0.15887677802423728,1739141215.5002809,54.86994767189026,91.50647844695837,1739141215.5002837,54.86994767189026,13.482182123730986,1739141215.500285,54.86994767189026,0.007,1739141215.5002868,54.86994767189026,-3.1212138990687466,1739141215.5002882,54.86994767189026,0.45621534652095913,1739141215.5002897,54.86994767189026,0.0630637131016645,1739141215.5002909,54.86994767189026,2.082990482767531,1739141215.5002923,54.86994767189026,0.0,1739141215.5002937,54.86994767189026,-0.03001085728732855,1739141215.5002952,54.86994767189026,3.1007225969936574,1739141215.5002964,54.86994767189026,2.1130013400548595 +1739141215.5202734,54.88994765281677,20.93385208711587,1739141215.5202756,54.88994765281677,0.15887677802423728,1739141215.5202787,54.88994765281677,91.50647844695837,1739141215.5202813,54.88994765281677,13.482182123730986,1739141215.5202825,54.88994765281677,0.007,1739141215.5202842,54.88994765281677,-3.1212138990687466,1739141215.5202856,54.88994765281677,0.45621534652095913,1739141215.5202868,54.88994765281677,0.0630637131016645,1739141215.520288,54.88994765281677,2.082990482767531,1739141215.5202894,54.88994765281677,0.0,1739141215.5202909,54.88994765281677,-0.03001085728732855,1739141215.520292,54.88994765281677,3.1007225969936574,1739141215.5202932,54.88994765281677,2.1130013400548595 +1739141215.5403311,54.909947633743286,20.93385208711587,1739141215.5403333,54.909947633743286,0.15887677802423728,1739141215.540336,54.909947633743286,91.50647844695837,1739141215.5403388,54.909947633743286,13.482182123730986,1739141215.54034,54.909947633743286,0.007,1739141215.5403419,54.909947633743286,-3.1212138990687466,1739141215.540343,54.909947633743286,0.45621534652095913,1739141215.5403442,54.909947633743286,0.0630637131016645,1739141215.5403457,54.909947633743286,2.082990482767531,1739141215.540347,54.909947633743286,0.0,1739141215.5403488,54.909947633743286,-0.03001085728732855,1739141215.5403497,54.909947633743286,3.1007225969936574,1739141215.540351,54.909947633743286,2.1130013400548595 +1739141215.560513,54.9299476146698,20.93385208711587,1739141215.5605154,54.9299476146698,0.15887677802423728,1739141215.560518,54.9299476146698,91.50647844695837,1739141215.560521,54.9299476146698,13.482182123730986,1739141215.5605223,54.9299476146698,0.007,1739141215.560524,54.9299476146698,-3.1212138990687466,1739141215.5605254,54.9299476146698,0.45621534652095913,1739141215.5605266,54.9299476146698,0.0630637131016645,1739141215.5605278,54.9299476146698,2.082990482767531,1739141215.5605295,54.9299476146698,0.0,1739141215.560531,54.9299476146698,-0.03001085728732855,1739141215.5605323,54.9299476146698,3.1007225969936574,1739141215.5605335,54.9299476146698,2.1130013400548595 +1739141215.5803213,54.94994759559631,20.93385208711587,1739141215.5803237,54.94994759559631,0.15887677802423728,1739141215.5803263,54.94994759559631,91.50647844695837,1739141215.5803292,54.94994759559631,13.482182123730986,1739141215.5803308,54.94994759559631,0.007,1739141215.5803325,54.94994759559631,-3.1212138990687466,1739141215.5803337,54.94994759559631,0.45621534652095913,1739141215.5803351,54.94994759559631,0.0630637131016645,1739141215.5803363,54.94994759559631,2.082990482767531,1739141215.580338,54.94994759559631,0.0,1739141215.5803392,54.94994759559631,-0.03001085728732855,1739141215.5803404,54.94994759559631,3.1007225969936574,1739141215.5803418,54.94994759559631,2.1130013400548595 +1739141215.6007123,54.96994757652283,20.7017687683798,1739141215.600715,54.96994757652283,0.16825773218788953,1739141215.600718,54.96994757652283,91.81302709081638,1739141215.600721,54.96994757652283,13.185265111157213,1739141215.600722,54.96994757652283,0.00629286419792489,1739141215.600724,54.96994757652283,-3.120048087798813,1739141215.6007254,54.96994757652283,0.46110353685750355,1739141215.6007268,54.96994757652283,0.06264165198693057,1739141215.600728,54.96994757652283,2.078921640339488,1739141215.6007297,54.96994757652283,0.0,1739141215.6007311,54.96994757652283,-0.03165135123669048,1739141215.6007323,54.96994757652283,3.1017674595071085,1739141215.6007335,54.96994757652283,2.1097918035910066 +1739141215.620367,54.98994755744934,20.7017687683798,1739141215.6203697,54.98994755744934,0.16825773218788953,1739141215.6203723,54.98994755744934,91.81302709081638,1739141215.6203754,54.98994755744934,13.185265111157213,1739141215.6203766,54.98994755744934,0.00629286419792489,1739141215.6203783,54.98994755744934,-3.120048087798813,1739141215.62038,54.98994755744934,0.46110353685750355,1739141215.620381,54.98994755744934,0.06264165198693057,1739141215.6203825,54.98994755744934,2.078921640339488,1739141215.620384,54.98994755744934,0.0,1739141215.6203852,54.98994755744934,-0.0308701632515187,1739141215.6203866,54.98994755744934,3.1017674595071085,1739141215.6203878,54.98994755744934,2.1097918035910066 +1739141215.6404214,55.009947538375854,20.7017687683798,1739141215.640424,55.009947538375854,0.16825773218788953,1739141215.640427,55.009947538375854,91.81302709081638,1739141215.6404295,55.009947538375854,13.185265111157213,1739141215.6404312,55.009947538375854,0.00629286419792489,1739141215.6404328,55.009947538375854,-3.120048087798813,1739141215.6404343,55.009947538375854,0.46110353685750355,1739141215.6404355,55.009947538375854,0.06264165198693057,1739141215.6404366,55.009947538375854,2.078921640339488,1739141215.6404383,55.009947538375854,0.0,1739141215.6404395,55.009947538375854,-0.0308701632515187,1739141215.6404412,55.009947538375854,3.1017674595071085,1739141215.6404421,55.009947538375854,2.1097918035910066 +1739141215.6606495,55.02994751930237,20.7017687683798,1739141215.6606526,55.02994751930237,0.16825773218788953,1739141215.660655,55.02994751930237,91.81302709081638,1739141215.6606576,55.02994751930237,13.185265111157213,1739141215.6606588,55.02994751930237,0.00629286419792489,1739141215.6606605,55.02994751930237,-3.120048087798813,1739141215.6606827,55.02994751930237,0.46110353685750355,1739141215.6606843,55.02994751930237,0.06264165198693057,1739141215.6606855,55.02994751930237,2.078921640339488,1739141215.6606867,55.02994751930237,0.0,1739141215.6606882,55.02994751930237,-0.0308701632515187,1739141215.6606896,55.02994751930237,3.1017674595071085,1739141215.660691,55.02994751930237,2.1097918035910066 +1739141215.6846743,55.04994750022888,20.7017687683798,1739141215.6846864,55.04994750022888,0.16825773218788953,1739141215.6847014,55.04994750022888,91.81302709081638,1739141215.6847215,55.04994750022888,13.185265111157213,1739141215.684736,55.04994750022888,0.00629286419792489,1739141215.684747,55.04994750022888,-3.120048087798813,1739141215.6847546,55.04994750022888,0.46110353685750355,1739141215.684763,55.04994750022888,0.06264165198693057,1739141215.6847703,55.04994750022888,2.078921640339488,1739141215.684779,55.04994750022888,0.0,1739141215.6847892,55.04994750022888,-0.0308701632515187,1739141215.6848037,55.04994750022888,3.1017674595071085,1739141215.6848187,55.04994750022888,2.1097918035910066 +1739141215.7040756,55.069947481155396,20.470040665738363,1739141215.7040813,55.069947481155396,0.17738024828131937,1739141215.704089,55.069947481155396,92.04373395437348,1739141215.7040951,55.069947481155396,12.964711996962558,1739141215.7040987,55.069947481155396,0.006,1739141215.7041028,55.069947481155396,-3.1187621449589744,1739141215.704106,55.069947481155396,0.4621817425617161,1739141215.704109,55.069947481155396,0.06297155197151386,1739141215.704112,55.069947481155396,2.0780252315874987,1739141215.704116,55.069947481155396,0.0,1739141215.7041194,55.069947481155396,-0.026120806457359466,1739141215.7041228,55.069947481155396,3.10281977378924,1739141215.704126,55.069947481155396,2.106407637648035 +1739141215.7236567,55.08994746208191,20.470040665738363,1739141215.7236624,55.08994746208191,0.17738024828131937,1739141215.7236686,55.08994746208191,92.04373395437348,1739141215.7236738,55.08994746208191,12.964711996962558,1739141215.7236767,55.08994746208191,0.006,1739141215.72368,55.08994746208191,-3.1187621449589744,1739141215.7236829,55.08994746208191,0.4621817425617161,1739141215.7236853,55.08994746208191,0.06297155197151386,1739141215.723688,55.08994746208191,2.0780252315874987,1739141215.723691,55.08994746208191,0.0,1739141215.7236938,55.08994746208191,-0.028382406060536436,1739141215.7236965,55.08994746208191,3.10281977378924,1739141215.7236989,55.08994746208191,2.106407637648035 +1739141215.745377,55.10994744300842,20.470040665738363,1739141215.7453861,55.10994744300842,0.17738024828131937,1739141215.7453969,55.10994744300842,92.04373395437348,1739141215.7454066,55.10994744300842,12.964711996962558,1739141215.7454119,55.10994744300842,0.006,1739141215.7454178,55.10994744300842,-3.1187621449589744,1739141215.7454228,55.10994744300842,0.4621817425617161,1739141215.7454274,55.10994744300842,0.06297155197151386,1739141215.745432,55.10994744300842,2.0780252315874987,1739141215.7454371,55.10994744300842,0.0,1739141215.7454424,55.10994744300842,-0.028382406060536436,1739141215.7454472,55.10994744300842,3.10281977378924,1739141215.7454517,55.10994744300842,2.106407637648035 +1739141215.7711859,55.12994742393494,20.470040665738363,1739141215.7711916,55.12994742393494,0.17738024828131937,1739141215.7711995,55.12994742393494,92.04373395437348,1739141215.771217,55.12994742393494,12.964711996962558,1739141215.771226,55.12994742393494,0.006,1739141215.7712345,55.12994742393494,-3.1187621449589744,1739141215.7712379,55.12994742393494,0.4621817425617161,1739141215.7712407,55.12994742393494,0.06297155197151386,1739141215.7712433,55.12994742393494,2.0780252315874987,1739141215.7712462,55.12994742393494,0.0,1739141215.7712488,55.12994742393494,-0.028382406060536436,1739141215.7712517,55.12994742393494,3.10281977378924,1739141215.771254,55.12994742393494,2.106407637648035 +1739141215.7891407,55.14994740486145,20.470040665738363,1739141215.789146,55.14994740486145,0.17738024828131937,1739141215.7891512,55.14994740486145,92.04373395437348,1739141215.7891564,55.14994740486145,12.964711996962558,1739141215.7891588,55.14994740486145,0.006,1739141215.789162,55.14994740486145,-3.1187621449589744,1739141215.7891645,55.14994740486145,0.4621817425617161,1739141215.789167,55.14994740486145,0.06297155197151386,1739141215.7891693,55.14994740486145,2.0780252315874987,1739141215.7891724,55.14994740486145,0.0,1739141215.789175,55.14994740486145,-0.028382406060536436,1739141215.7891777,55.14994740486145,3.10281977378924,1739141215.7891803,55.14994740486145,2.106407637648035 +1739141215.8109388,55.169947385787964,20.470040665738363,1739141215.8109443,55.169947385787964,0.17738024828131937,1739141215.8109498,55.169947385787964,92.04373395437348,1739141215.8109553,55.169947385787964,12.964711996962558,1739141215.8109581,55.169947385787964,0.006,1739141215.8109612,55.169947385787964,-3.1187621449589744,1739141215.8109639,55.169947385787964,0.4621817425617161,1739141215.8109665,55.169947385787964,0.06297155197151386,1739141215.8109689,55.169947385787964,2.0780252315874987,1739141215.8109722,55.169947385787964,0.0,1739141215.810975,55.169947385787964,-0.028382406060536436,1739141215.8109775,55.169947385787964,3.10281977378924,1739141215.8109834,55.169947385787964,2.106407637648035 +1739141215.829344,55.18994736671448,20.238656992441506,1739141215.8293495,55.18994736671448,0.18624534646510682,1739141215.8293552,55.18994736671448,92.94354045482126,1739141215.8293607,55.18994736671448,12.074104124151793,1739141215.8293638,55.18994736671448,0.0038907129165406287,1739141215.8293667,55.18994736671448,-3.1192614465894146,1739141215.8293695,55.18994736671448,0.4901234422638891,1739141215.8293722,55.18994736671448,0.056433119872541904,1739141215.8293746,55.18994736671448,2.054929118149395,1739141215.8293777,55.18994736671448,0.0,1739141215.8293803,55.18994736671448,-0.06662767177598422,1739141215.829383,55.18994736671448,3.1038720880713715,1739141215.8293855,55.18994736671448,2.103344749534599 +1739141215.8473027,55.20994734764099,20.238656992441506,1739141215.8473053,55.20994734764099,0.18624534646510682,1739141215.8473089,55.20994734764099,92.94354045482126,1739141215.847312,55.20994734764099,12.074104124151793,1739141215.8473134,55.20994734764099,0.0038907129165406287,1739141215.8473158,55.20994734764099,-3.1192614465894146,1739141215.8473172,55.20994734764099,0.4901234422638891,1739141215.847319,55.20994734764099,0.056433119872541904,1739141215.8473203,55.20994734764099,2.054929118149395,1739141215.8473222,55.20994734764099,0.0,1739141215.8473237,55.20994734764099,-0.048415631385203994,1739141215.847325,55.20994734764099,3.1038720880713715,1739141215.8473265,55.20994734764099,2.103344749534599 +1739141215.8668308,55.229947328567505,20.238656992441506,1739141215.866833,55.229947328567505,0.18624534646510682,1739141215.8668356,55.229947328567505,92.94354045482126,1739141215.866838,55.229947328567505,12.074104124151793,1739141215.8668394,55.229947328567505,0.0038907129165406287,1739141215.8668408,55.229947328567505,-3.1192614465894146,1739141215.8668418,55.229947328567505,0.4901234422638891,1739141215.8668432,55.229947328567505,0.056433119872541904,1739141215.8668442,55.229947328567505,2.054929118149395,1739141215.8668454,55.229947328567505,0.0,1739141215.8668468,55.229947328567505,-0.048415631385203994,1739141215.866848,55.229947328567505,3.1038720880713715,1739141215.866849,55.229947328567505,2.103344749534599 +1739141215.887014,55.24994730949402,20.238656992441506,1739141215.8870163,55.24994730949402,0.18624534646510682,1739141215.8870187,55.24994730949402,92.94354045482126,1739141215.8870213,55.24994730949402,12.074104124151793,1739141215.8870225,55.24994730949402,0.0038907129165406287,1739141215.8870244,55.24994730949402,-3.1192614465894146,1739141215.8870254,55.24994730949402,0.4901234422638891,1739141215.8870268,55.24994730949402,0.056433119872541904,1739141215.8870277,55.24994730949402,2.054929118149395,1739141215.8870292,55.24994730949402,0.0,1739141215.8870306,55.24994730949402,-0.048415631385203994,1739141215.8870316,55.24994730949402,3.1038720880713715,1739141215.8870327,55.24994730949402,2.103344749534599 +1739141215.9098978,55.26994729042053,20.238656992441506,1739141215.9099014,55.26994729042053,0.18624534646510682,1739141215.909906,55.26994729042053,92.94354045482126,1739141215.9099324,55.26994729042053,12.074104124151793,1739141215.9099355,55.26994729042053,0.0038907129165406287,1739141215.9099393,55.26994729042053,-3.1192614465894146,1739141215.9099429,55.26994729042053,0.4901234422638891,1739141215.9099643,55.26994729042053,0.056433119872541904,1739141215.9099677,55.26994729042053,2.054929118149395,1739141215.909971,55.26994729042053,0.0,1739141215.9099743,55.26994729042053,-0.048415631385203994,1739141215.9099777,55.26994729042053,3.1038720880713715,1739141215.909981,55.26994729042053,2.103344749534599 +1739141215.9273422,55.289947271347046,20.00772549844243,1739141215.9273446,55.289947271347046,0.19484978465246794,1739141215.9273472,55.289947271347046,92.96872059210534,1739141215.9273498,55.289947271347046,12.06530847405271,1739141215.9273512,55.289947271347046,0.00381617350892127,1739141215.927353,55.289947271347046,-3.1175449632240393,1739141215.927354,55.289947271347046,0.4820744809049328,1739141215.927355,55.289947271347046,0.058649387817035714,1739141215.9273565,55.289947271347046,2.0615557980302124,1739141215.927358,55.289947271347046,0.0,1739141215.9273593,55.289947271347046,-0.025338395730828057,1739141215.9273603,55.289947271347046,3.104924402353503,1739141215.9273615,55.289947271347046,2.0978833590860257 +1739141215.947082,55.30994725227356,20.00772549844243,1739141215.9470842,55.30994725227356,0.19484978465246794,1739141215.947087,55.30994725227356,92.96872059210534,1739141215.94709,55.30994725227356,12.06530847405271,1739141215.947091,55.30994725227356,0.00381617350892127,1739141215.9470928,55.30994725227356,-3.1175449632240393,1739141215.9470942,55.30994725227356,0.4820744809049328,1739141215.9470954,55.30994725227356,0.058649387817035714,1739141215.9470966,55.30994725227356,2.0615557980302124,1739141215.947098,55.30994725227356,0.0,1739141215.9470994,55.30994725227356,-0.03632756105581336,1739141215.9471006,55.30994725227356,3.104924402353503,1739141215.9471016,55.30994725227356,2.0978833590860257 +1739141215.9668853,55.32994723320007,20.00772549844243,1739141215.9668884,55.32994723320007,0.19484978465246794,1739141215.9668918,55.32994723320007,92.96872059210534,1739141215.9668949,55.32994723320007,12.06530847405271,1739141215.9668963,55.32994723320007,0.00381617350892127,1739141215.9668982,55.32994723320007,-3.1175449632240393,1739141215.9668996,55.32994723320007,0.4820744809049328,1739141215.9669015,55.32994723320007,0.058649387817035714,1739141215.9669027,55.32994723320007,2.0615557980302124,1739141215.9669049,55.32994723320007,0.0,1739141215.9669063,55.32994723320007,-0.03632756105581336,1739141215.9669077,55.32994723320007,3.104924402353503,1739141215.966909,55.32994723320007,2.0978833590860257 +1739141215.9869726,55.34994721412659,20.00772549844243,1739141215.9869757,55.34994721412659,0.19484978465246794,1739141215.9869788,55.34994721412659,92.96872059210534,1739141215.9869819,55.34994721412659,12.06530847405271,1739141215.9869835,55.34994721412659,0.00381617350892127,1739141215.9869852,55.34994721412659,-3.1175449632240393,1739141215.9869866,55.34994721412659,0.4820744809049328,1739141215.9869883,55.34994721412659,0.058649387817035714,1739141215.9869895,55.34994721412659,2.0615557980302124,1739141215.9869914,55.34994721412659,0.0,1739141215.9869928,55.34994721412659,-0.03632756105581336,1739141215.9869945,55.34994721412659,3.104924402353503,1739141215.9869957,55.34994721412659,2.0978833590860257 +1739141216.0070558,55.3699471950531,20.00772549844243,1739141216.007059,55.3699471950531,0.19484978465246794,1739141216.0070632,55.3699471950531,92.96872059210534,1739141216.0070658,55.3699471950531,12.06530847405271,1739141216.0070674,55.3699471950531,0.00381617350892127,1739141216.007069,55.3699471950531,-3.1175449632240393,1739141216.0070708,55.3699471950531,0.4820744809049328,1739141216.007072,55.3699471950531,0.058649387817035714,1739141216.0070732,55.3699471950531,2.0615557980302124,1739141216.007075,55.3699471950531,0.0,1739141216.0070765,55.3699471950531,-0.03632756105581336,1739141216.0070782,55.3699471950531,3.104924402353503,1739141216.0070794,55.3699471950531,2.0978833590860257 +1739141216.0270944,55.389947175979614,20.00772549844243,1739141216.0270972,55.389947175979614,0.19484978465246794,1739141216.027101,55.389947175979614,92.96872059210534,1739141216.027104,55.389947175979614,12.06530847405271,1739141216.0271056,55.389947175979614,0.00381617350892127,1739141216.0271075,55.389947175979614,-3.1175449632240393,1739141216.0271091,55.389947175979614,0.4820744809049328,1739141216.0271106,55.389947175979614,0.058649387817035714,1739141216.0271122,55.389947175979614,2.0615557980302124,1739141216.027114,55.389947175979614,0.0,1739141216.0271158,55.389947175979614,-0.03632756105581336,1739141216.027117,55.389947175979614,3.104924402353503,1739141216.0271187,55.389947175979614,2.0978833590860257 +1739141216.0471277,55.40994715690613,19.777287780330543,1739141216.047131,55.40994715690613,0.2031929880865384,1739141216.0471344,55.40994715690613,92.99384664658298,1739141216.0471375,55.40994715690613,12.051462444117236,1739141216.0471392,55.40994715690613,0.0036988342721799732,1739141216.047141,55.40994715690613,-3.1157766631269608,1739141216.047143,55.40994715690613,0.47447197659763507,1739141216.0471442,55.40994715690613,0.06100040002289581,1739141216.0471458,55.40994715690613,2.0678345347498563,1739141216.0471475,55.40994715690613,0.0,1739141216.047149,55.40994715690613,-0.01716299211904109,1739141216.0471506,55.40994715690613,3.1059767166356345,1739141216.047152,55.40994715690613,2.094123516635715 +1739141216.0674858,55.42994713783264,19.777287780330543,1739141216.0674894,55.42994713783264,0.2031929880865384,1739141216.0674932,55.42994713783264,92.99384664658298,1739141216.067497,55.42994713783264,12.051462444117236,1739141216.0674987,55.42994713783264,0.0036988342721799732,1739141216.067501,55.42994713783264,-3.1157766631269608,1739141216.0675025,55.42994713783264,0.47447197659763507,1739141216.0675046,55.42994713783264,0.06100040002289581,1739141216.067506,55.42994713783264,2.0678345347498563,1739141216.0675082,55.42994713783264,0.0,1739141216.0675097,55.42994713783264,-0.026288981885858487,1739141216.0675116,55.42994713783264,3.1059767166356345,1739141216.067513,55.42994713783264,2.094123516635715 +1739141216.0874183,55.449947118759155,19.777287780330543,1739141216.087422,55.449947118759155,0.2031929880865384,1739141216.0874255,55.449947118759155,92.99384664658298,1739141216.0874293,55.449947118759155,12.051462444117236,1739141216.0874312,55.449947118759155,0.0036988342721799732,1739141216.0874336,55.449947118759155,-3.1157766631269608,1739141216.0874352,55.449947118759155,0.47447197659763507,1739141216.087437,55.449947118759155,0.06100040002289581,1739141216.0874386,55.449947118759155,2.0678345347498563,1739141216.0874405,55.449947118759155,0.0,1739141216.0874422,55.449947118759155,-0.026288981885858487,1739141216.087444,55.449947118759155,3.1059767166356345,1739141216.0874457,55.449947118759155,2.094123516635715 +1739141216.1075706,55.46994709968567,19.777287780330543,1739141216.1075742,55.46994709968567,0.2031929880865384,1739141216.107582,55.46994709968567,92.99384664658298,1739141216.1075854,55.46994709968567,12.051462444117236,1739141216.1075876,55.46994709968567,0.0036988342721799732,1739141216.1075897,55.46994709968567,-3.1157766631269608,1739141216.1075914,55.46994709968567,0.47447197659763507,1739141216.1075933,55.46994709968567,0.06100040002289581,1739141216.1075947,55.46994709968567,2.0678345347498563,1739141216.107597,55.46994709968567,0.0,1739141216.107599,55.46994709968567,-0.026288981885858487,1739141216.107601,55.46994709968567,3.1059767166356345,1739141216.1076024,55.46994709968567,2.094123516635715 +1739141216.1272812,55.48994708061218,19.777287780330543,1739141216.1272848,55.48994708061218,0.2031929880865384,1739141216.1272888,55.48994708061218,92.99384664658298,1739141216.1272924,55.48994708061218,12.051462444117236,1739141216.1272943,55.48994708061218,0.0036988342721799732,1739141216.1272962,55.48994708061218,-3.1157766631269608,1739141216.127298,55.48994708061218,0.47447197659763507,1739141216.1273,55.48994708061218,0.06100040002289581,1739141216.1273017,55.48994708061218,2.0678345347498563,1739141216.1273036,55.48994708061218,0.0,1739141216.1273055,55.48994708061218,-0.026288981885858487,1739141216.1273074,55.48994708061218,3.1059767166356345,1739141216.127309,55.48994708061218,2.094123516635715 +1739141216.147569,55.509947061538696,19.547214692129216,1739141216.1475725,55.509947061538696,0.21128056196708922,1739141216.1475763,55.509947061538696,93.0189327007708,1739141216.14758,55.509947061538696,12.034757445725768,1739141216.1475816,55.509947061538696,0.003557266489201423,1739141216.147584,55.509947061538696,-3.1139491842699374,1739141216.1475859,55.509947061538696,0.46720527106645343,1739141216.1475873,55.509947061538696,0.06351965170824335,1739141216.1475892,55.509947061538696,2.0738538164418876,1739141216.147591,55.509947061538696,0.0,1739141216.147593,55.509947061538696,-0.009464600869190931,1739141216.1475945,55.509947061538696,3.107029030917766,1739141216.1475964,55.509947061538696,2.0913300313211667 +1739141216.1673641,55.52994704246521,19.547214692129216,1739141216.167368,55.52994704246521,0.21128056196708922,1739141216.167372,55.52994704246521,93.0189327007708,1739141216.167376,55.52994704246521,12.034757445725768,1739141216.167378,55.52994704246521,0.003557266489201423,1739141216.1673806,55.52994704246521,-3.1139491842699374,1739141216.1673822,55.52994704246521,0.46720527106645343,1739141216.1673841,55.52994704246521,0.06351965170824335,1739141216.1673856,55.52994704246521,2.0738538164418876,1739141216.1673877,55.52994704246521,0.0,1739141216.1673899,55.52994704246521,-0.017476214879279084,1739141216.1673915,55.52994704246521,3.107029030917766,1739141216.1673932,55.52994704246521,2.0913300313211667 +1739141216.1873415,55.549947023391724,19.547214692129216,1739141216.1873453,55.549947023391724,0.21128056196708922,1739141216.1873488,55.549947023391724,93.0189327007708,1739141216.1873522,55.549947023391724,12.034757445725768,1739141216.1873538,55.549947023391724,0.003557266489201423,1739141216.1873562,55.549947023391724,-3.1139491842699374,1739141216.187358,55.549947023391724,0.46720527106645343,1739141216.1873598,55.549947023391724,0.06351965170824335,1739141216.1873612,55.549947023391724,2.0738538164418876,1739141216.1873634,55.549947023391724,0.0,1739141216.187365,55.549947023391724,-0.017476214879279084,1739141216.1873667,55.549947023391724,3.107029030917766,1739141216.1873682,55.549947023391724,2.0913300313211667 +1739141216.2074819,55.56994700431824,19.547214692129216,1739141216.2074854,55.56994700431824,0.21128056196708922,1739141216.2074893,55.56994700431824,93.0189327007708,1739141216.2074928,55.56994700431824,12.034757445725768,1739141216.2074947,55.56994700431824,0.003557266489201423,1739141216.2074966,55.56994700431824,-3.1139491842699374,1739141216.2074986,55.56994700431824,0.46720527106645343,1739141216.2075002,55.56994700431824,0.06351965170824335,1739141216.2075021,55.56994700431824,2.0738538164418876,1739141216.2075038,55.56994700431824,0.0,1739141216.207506,55.56994700431824,-0.017476214879279084,1739141216.2075076,55.56994700431824,3.107029030917766,1739141216.2075093,55.56994700431824,2.0913300313211667 +1739141216.227384,55.58994698524475,19.547214692129216,1739141216.2273881,55.58994698524475,0.21128056196708922,1739141216.2273917,55.58994698524475,93.0189327007708,1739141216.2273955,55.58994698524475,12.034757445725768,1739141216.2273974,55.58994698524475,0.003557266489201423,1739141216.2273996,55.58994698524475,-3.1139491842699374,1739141216.2274015,55.58994698524475,0.46720527106645343,1739141216.2274032,55.58994698524475,0.06351965170824335,1739141216.2274048,55.58994698524475,2.0738538164418876,1739141216.2274067,55.58994698524475,0.0,1739141216.2274086,55.58994698524475,-0.017476214879279084,1739141216.2274103,55.58994698524475,3.107029030917766,1739141216.2274122,55.58994698524475,2.0913300313211667 +1739141216.2473333,55.609946966171265,19.547214692129216,1739141216.2473366,55.609946966171265,0.21128056196708922,1739141216.2473402,55.609946966171265,93.0189327007708,1739141216.2473435,55.609946966171265,12.034757445725768,1739141216.2473454,55.609946966171265,0.003557266489201423,1739141216.2473474,55.609946966171265,-3.1139491842699374,1739141216.2473493,55.609946966171265,0.46720527106645343,1739141216.247351,55.609946966171265,0.06351965170824335,1739141216.2473526,55.609946966171265,2.0738538164418876,1739141216.2473545,55.609946966171265,0.0,1739141216.2473564,55.609946966171265,-0.017476214879279084,1739141216.2473578,55.609946966171265,3.107029030917766,1739141216.2473598,55.609946966171265,2.0913300313211667 +1739141216.267511,55.62994694709778,19.317382667027484,1739141216.2675142,55.62994694709778,0.21911750753391424,1739141216.2675183,55.62994694709778,93.14209043284488,1739141216.2675219,55.62994694709778,11.91686630255146,1739141216.2675235,55.62994694709778,0.003,1739141216.2675257,55.62994694709778,-3.112397920130466,1739141216.2675276,55.62994694709778,0.46395073896856914,1739141216.2675295,55.62994694709778,0.06499364218939584,1739141216.267531,55.62994694709778,2.0765553440267803,1739141216.2675333,55.62994694709778,0.0,1739141216.2675354,55.62994694709778,-0.008968786216966722,1739141216.2675369,55.62994694709778,3.1080813451998974,1739141216.2675388,55.62994694709778,2.0895752887733408 +1739141216.2873135,55.64994692802429,19.317382667027484,1739141216.2873175,55.64994692802429,0.21911750753391424,1739141216.2873216,55.64994692802429,93.14209043284488,1739141216.2873251,55.64994692802429,11.91686630255146,1739141216.287327,55.64994692802429,0.003,1739141216.2873292,55.64994692802429,-3.112397920130466,1739141216.287331,55.64994692802429,0.46395073896856914,1739141216.2873328,55.64994692802429,0.06499364218939584,1739141216.2873344,55.64994692802429,2.0765553440267803,1739141216.2873366,55.64994692802429,0.0,1739141216.2873387,55.64994692802429,-0.01301994474656043,1739141216.2873406,55.64994692802429,3.1080813451998974,1739141216.287342,55.64994692802429,2.0895752887733408 +1739141216.3075137,55.669946908950806,19.317382667027484,1739141216.3075168,55.669946908950806,0.21911750753391424,1739141216.3075213,55.669946908950806,93.14209043284488,1739141216.307525,55.669946908950806,11.91686630255146,1739141216.3075266,55.669946908950806,0.003,1739141216.307529,55.669946908950806,-3.112397920130466,1739141216.3075306,55.669946908950806,0.46395073896856914,1739141216.3075323,55.669946908950806,0.06499364218939584,1739141216.307534,55.669946908950806,2.0765553440267803,1739141216.3075364,55.669946908950806,0.0,1739141216.3075383,55.669946908950806,-0.01301994474656043,1739141216.3075402,55.669946908950806,3.1080813451998974,1739141216.307542,55.669946908950806,2.0895752887733408 +1739141216.327285,55.68994688987732,19.317382667027484,1739141216.3272886,55.68994688987732,0.21911750753391424,1739141216.3272924,55.68994688987732,93.14209043284488,1739141216.3272963,55.68994688987732,11.91686630255146,1739141216.3272982,55.68994688987732,0.003,1739141216.3273003,55.68994688987732,-3.112397920130466,1739141216.3273022,55.68994688987732,0.46395073896856914,1739141216.3273036,55.68994688987732,0.06499364218939584,1739141216.3273056,55.68994688987732,2.0765553440267803,1739141216.3273072,55.68994688987732,0.0,1739141216.3273091,55.68994688987732,-0.01301994474656043,1739141216.3273108,55.68994688987732,3.1080813451998974,1739141216.3273125,55.68994688987732,2.0895752887733408 +1739141216.3472893,55.70994687080383,19.317382667027484,1739141216.347293,55.70994687080383,0.21911750753391424,1739141216.347297,55.70994687080383,93.14209043284488,1739141216.3473008,55.70994687080383,11.91686630255146,1739141216.3473027,55.70994687080383,0.003,1739141216.347305,55.70994687080383,-3.112397920130466,1739141216.3473067,55.70994687080383,0.46395073896856914,1739141216.3473086,55.70994687080383,0.06499364218939584,1739141216.34731,55.70994687080383,2.0765553440267803,1739141216.3473122,55.70994687080383,0.0,1739141216.347314,55.70994687080383,-0.01301994474656043,1739141216.3473158,55.70994687080383,3.1080813451998974,1739141216.3473172,55.70994687080383,2.0895752887733408 +1739141216.367483,55.72994685173035,19.087723396072114,1739141216.3674865,55.72994685173035,0.22670099908461694,1739141216.3674903,55.72994685173035,93.36227408150215,1739141216.3674939,55.72994685173035,11.700851335861724,1739141216.3674958,55.72994685173035,0.0017466498811909543,1739141216.3674977,55.72994685173035,-3.1111488006212373,1739141216.3674996,55.72994685173035,0.4640689206426304,1739141216.3675013,55.72994685173035,0.06524563917418978,1739141216.367503,55.72994685173035,2.0764571820322533,1739141216.3675048,55.72994685173035,0.0,1739141216.367507,55.72994685173035,-0.010557897328508944,1739141216.3675086,55.72994685173035,3.109200808439919,1739141216.3675103,55.72994685173035,2.0881874834788348 +1739141216.3874502,55.74994683265686,19.087723396072114,1739141216.3874538,55.74994683265686,0.22670099908461694,1739141216.387458,55.74994683265686,93.36227408150215,1739141216.3874617,55.74994683265686,11.700851335861724,1739141216.3874636,55.74994683265686,0.0017466498811909543,1739141216.387466,55.74994683265686,-3.1111488006212373,1739141216.3874679,55.74994683265686,0.4640689206426304,1739141216.3874695,55.74994683265686,0.06524563917418978,1739141216.3874712,55.74994683265686,2.0764571820322533,1739141216.387473,55.74994683265686,0.0,1739141216.3874753,55.74994683265686,-0.011730301446581493,1739141216.387477,55.74994683265686,3.109200808439919,1739141216.3874788,55.74994683265686,2.0881874834788348 +1739141216.4078493,55.769946813583374,19.087723396072114,1739141216.4078526,55.769946813583374,0.22670099908461694,1739141216.4078567,55.769946813583374,93.36227408150215,1739141216.40786,55.769946813583374,11.700851335861724,1739141216.4078617,55.769946813583374,0.0017466498811909543,1739141216.4078643,55.769946813583374,-3.1111488006212373,1739141216.407866,55.769946813583374,0.4640689206426304,1739141216.4078677,55.769946813583374,0.06524563917418978,1739141216.4078693,55.769946813583374,2.0764571820322533,1739141216.4078712,55.769946813583374,0.0,1739141216.4078736,55.769946813583374,-0.011730301446581493,1739141216.407875,55.769946813583374,3.109200808439919,1739141216.407877,55.769946813583374,2.0881874834788348 +1739141216.4274032,55.78994679450989,19.087723396072114,1739141216.4274068,55.78994679450989,0.22670099908461694,1739141216.4274106,55.78994679450989,93.36227408150215,1739141216.4274142,55.78994679450989,11.700851335861724,1739141216.427416,55.78994679450989,0.0017466498811909543,1739141216.4274185,55.78994679450989,-3.1111488006212373,1739141216.4274201,55.78994679450989,0.4640689206426304,1739141216.427422,55.78994679450989,0.06524563917418978,1739141216.4274235,55.78994679450989,2.0764571820322533,1739141216.4274256,55.78994679450989,0.0,1739141216.4274273,55.78994679450989,-0.011730301446581493,1739141216.4274292,55.78994679450989,3.109200808439919,1739141216.4274306,55.78994679450989,2.0881874834788348 +1739141216.447393,55.8099467754364,19.087723396072114,1739141216.4473968,55.8099467754364,0.22670099908461694,1739141216.4474003,55.8099467754364,93.36227408150215,1739141216.4474041,55.8099467754364,11.700851335861724,1739141216.4474058,55.8099467754364,0.0017466498811909543,1739141216.447408,55.8099467754364,-3.1111488006212373,1739141216.4474099,55.8099467754364,0.4640689206426304,1739141216.4474115,55.8099467754364,0.06524563917418978,1739141216.4474132,55.8099467754364,2.0764571820322533,1739141216.447415,55.8099467754364,0.0,1739141216.4474168,55.8099467754364,-0.011730301446581493,1739141216.4474187,55.8099467754364,3.109200808439919,1739141216.4474201,55.8099467754364,2.0881874834788348 +1739141216.467514,55.829946756362915,19.087723396072114,1739141216.4675176,55.829946756362915,0.22670099908461694,1739141216.4675214,55.829946756362915,93.36227408150215,1739141216.4675255,55.829946756362915,11.700851335861724,1739141216.4675272,55.829946756362915,0.0017466498811909543,1739141216.4675293,55.829946756362915,-3.1111488006212373,1739141216.467532,55.829946756362915,0.4640689206426304,1739141216.4675338,55.829946756362915,0.06524563917418978,1739141216.4675357,55.829946756362915,2.0764571820322533,1739141216.4675376,55.829946756362915,0.0,1739141216.4675398,55.829946756362915,-0.011730301446581493,1739141216.4675417,55.829946756362915,3.109200808439919,1739141216.4675434,55.829946756362915,2.0881874834788348 +1739141216.4873602,55.84994673728943,18.85820156319514,1739141216.4873636,55.84994673728943,0.23401977860004664,1739141216.4873674,55.84994673728943,93.68301585167187,1739141216.487371,55.84994673728943,11.383899974711397,1739141216.4873729,55.84994673728943,0.0002046726608541786,1739141216.487375,55.84994673728943,-3.110320316279491,1739141216.487377,55.84994673728943,0.46729053388132635,1739141216.4873784,55.84994673728943,0.06416762124850342,1739141216.4873803,55.84994673728943,2.073783088602376,1739141216.4873822,55.84994673728943,0.0,1739141216.4873843,55.84994673728943,-0.014427672999439253,1739141216.4873857,55.84994673728943,3.1103351936705828,1739141216.4873874,55.84994673728943,2.0869262983159516 +1739141216.5075693,55.86994671821594,18.85820156319514,1739141216.507573,55.86994671821594,0.23401977860004664,1739141216.5075774,55.86994671821594,93.68301585167187,1739141216.5075808,55.86994671821594,11.383899974711397,1739141216.5075824,55.86994671821594,0.0002046726608541786,1739141216.507585,55.86994671821594,-3.110320316279491,1739141216.5075867,55.86994671821594,0.46729053388132635,1739141216.5075884,55.86994671821594,0.06416762124850342,1739141216.50759,55.86994671821594,2.073783088602376,1739141216.5075922,55.86994671821594,0.0,1739141216.5075943,55.86994671821594,-0.013143209713575743,1739141216.5075958,55.86994671821594,3.1103351936705828,1739141216.5075977,55.86994671821594,2.0869262983159516 +1739141216.527449,55.889946699142456,18.85820156319514,1739141216.5274525,55.889946699142456,0.23401977860004664,1739141216.5274565,55.889946699142456,93.68301585167187,1739141216.52746,55.889946699142456,11.383899974711397,1739141216.527462,55.889946699142456,0.0002046726608541786,1739141216.527464,55.889946699142456,-3.110320316279491,1739141216.5274658,55.889946699142456,0.46729053388132635,1739141216.5274675,55.889946699142456,0.06416762124850342,1739141216.5274692,55.889946699142456,2.073783088602376,1739141216.527471,55.889946699142456,0.0,1739141216.527473,55.889946699142456,-0.013143209713575743,1739141216.5274744,55.889946699142456,3.1103351936705828,1739141216.5274763,55.889946699142456,2.0869262983159516 +1739141216.547323,55.90994668006897,18.85820156319514,1739141216.5473268,55.90994668006897,0.23401977860004664,1739141216.5473306,55.90994668006897,93.68301585167187,1739141216.5473342,55.90994668006897,11.383899974711397,1739141216.5473359,55.90994668006897,0.0002046726608541786,1739141216.5473382,55.90994668006897,-3.110320316279491,1739141216.54734,55.90994668006897,0.46729053388132635,1739141216.5473416,55.90994668006897,0.06416762124850342,1739141216.5473433,55.90994668006897,2.073783088602376,1739141216.5473454,55.90994668006897,0.0,1739141216.5473473,55.90994668006897,-0.013143209713575743,1739141216.5473487,55.90994668006897,3.1103351936705828,1739141216.5473502,55.90994668006897,2.0869262983159516 +1739141216.5673974,55.92994666099548,18.85820156319514,1739141216.567401,55.92994666099548,0.23401977860004664,1739141216.567405,55.92994666099548,93.68301585167187,1739141216.5674086,55.92994666099548,11.383899974711397,1739141216.5674107,55.92994666099548,0.0002046726608541786,1739141216.567413,55.92994666099548,-3.110320316279491,1739141216.5674148,55.92994666099548,0.46729053388132635,1739141216.5674167,55.92994666099548,0.06416762124850342,1739141216.5674183,55.92994666099548,2.073783088602376,1739141216.5674205,55.92994666099548,0.0,1739141216.5674224,55.92994666099548,-0.013143209713575743,1739141216.5674243,55.92994666099548,3.1103351936705828,1739141216.5674257,55.92994666099548,2.0869262983159516 +1739141216.59319,55.949946641922,18.628820857841504,1739141216.5931985,55.949946641922,0.2410735985947854,1739141216.5932093,55.949946641922,94.09706456898068,1739141216.593219,55.949946641922,10.974210319145348,1739141216.593224,55.949946641922,-0.0023565806737887705,1739141216.5932305,55.949946641922,-3.109801596002971,1739141216.5932355,55.949946641922,0.4738652785145927,1739141216.59324,55.949946641922,0.06203960029386447,1739141216.5932455,55.949946641922,2.068336416144802,1739141216.5932622,55.949946641922,0.0,1739141216.5932782,55.949946641922,-0.020774210364866954,1739141216.593288,55.949946641922,3.1114695789012465,1739141216.5932949,55.949946641922,2.085476814860473 +1739141216.6154642,55.96994662284851,18.628820857841504,1739141216.615468,55.96994662284851,0.2410735985947854,1739141216.6154723,55.96994662284851,94.09706456898068,1739141216.6154764,55.96994662284851,10.974210319145348,1739141216.6154785,55.96994662284851,-0.0023565806737887705,1739141216.6154811,55.96994662284851,-3.109801596002971,1739141216.615483,55.96994662284851,0.4738652785145927,1739141216.6154852,55.96994662284851,0.06203960029386447,1739141216.6154873,55.96994662284851,2.068336416144802,1739141216.6154895,55.96994662284851,0.0,1739141216.6154916,55.96994662284851,-0.01714039871567108,1739141216.6154933,55.96994662284851,3.1114695789012465,1739141216.6154954,55.96994662284851,2.085476814860473 +1739141216.6348996,55.99994659423828,18.628820857841504,1739141216.634903,55.99994659423828,0.2410735985947854,1739141216.6349065,55.99994659423828,94.09706456898068,1739141216.63491,55.99994659423828,10.974210319145348,1739141216.6349118,55.99994659423828,-0.0023565806737887705,1739141216.6349137,55.99994659423828,-3.109801596002971,1739141216.6349154,55.99994659423828,0.4738652785145927,1739141216.6349168,55.99994659423828,0.06203960029386447,1739141216.6349185,55.99994659423828,2.068336416144802,1739141216.6349204,55.99994659423828,0.0,1739141216.6349223,55.99994659423828,-0.01714039871567108,1739141216.6349237,55.99994659423828,3.1114695789012465,1739141216.6349251,55.99994659423828,2.085476814860473 +1739141216.6568756,56.019946575164795,18.628820857841504,1739141216.656879,56.019946575164795,0.2410735985947854,1739141216.6568825,56.019946575164795,94.09706456898068,1739141216.656885,56.019946575164795,10.974210319145348,1739141216.6569078,56.019946575164795,-0.0023565806737887705,1739141216.65691,56.019946575164795,-3.109801596002971,1739141216.6569114,56.019946575164795,0.4738652785145927,1739141216.6569126,56.019946575164795,0.06203960029386447,1739141216.6569142,56.019946575164795,2.068336416144802,1739141216.6569161,56.019946575164795,0.0,1739141216.6569178,56.019946575164795,-0.01714039871567108,1739141216.656919,56.019946575164795,3.1114695789012465,1739141216.6569207,56.019946575164795,2.085476814860473 +1739141216.676269,56.03994655609131,18.628820857841504,1739141216.6762724,56.03994655609131,0.2410735985947854,1739141216.6762755,56.03994655609131,94.09706456898068,1739141216.6762786,56.03994655609131,10.974210319145348,1739141216.67628,56.03994655609131,-0.0023565806737887705,1739141216.676282,56.03994655609131,-3.109801596002971,1739141216.6762834,56.03994655609131,0.4738652785145927,1739141216.6762853,56.03994655609131,0.06203960029386447,1739141216.6762865,56.03994655609131,2.068336416144802,1739141216.6762884,56.03994655609131,0.0,1739141216.6762896,56.03994655609131,-0.01714039871567108,1739141216.6762908,56.03994655609131,3.1114695789012465,1739141216.6762924,56.03994655609131,2.085476814860473 +1739141216.6947758,56.05994653701782,18.399619807244157,1739141216.6947784,56.05994653701782,0.24786165957662476,1739141216.6947808,56.05994653701782,94.13282672093484,1739141216.694784,56.05994653701782,10.944295812036511,1739141216.6947854,56.05994653701782,-0.0026058682330290755,1739141216.694787,56.05994653701782,-3.1080094908203346,1739141216.6947885,56.05994653701782,0.46645209989414615,1739141216.6947896,56.05994653701782,0.06436928322888327,1739141216.6947906,56.05994653701782,2.074478697329665,1739141216.6947923,56.05994653701782,0.0,1739141216.6947937,56.05994653701782,-0.001693650970060875,1739141216.694795,56.05994653701782,3.1126039641319103,1739141216.6947963,56.05994653701782,2.083527946138745 +1739141216.7147963,56.079946517944336,18.399619807244157,1739141216.714799,56.079946517944336,0.24786165957662476,1739141216.7148015,56.079946517944336,94.13282672093484,1739141216.7148042,56.079946517944336,10.944295812036511,1739141216.714806,56.079946517944336,-0.0026058682330290755,1739141216.7148077,56.079946517944336,-3.1080094908203346,1739141216.7148094,56.079946517944336,0.46645209989414615,1739141216.7148106,56.079946517944336,0.06436928322888327,1739141216.7148116,56.079946517944336,2.074478697329665,1739141216.7148132,56.079946517944336,0.0,1739141216.714815,56.079946517944336,-0.009049248809079646,1739141216.7148163,56.079946517944336,3.1126039641319103,1739141216.7148175,56.079946517944336,2.083527946138745 +1739141216.7344098,56.09994649887085,18.399619807244157,1739141216.7344122,56.09994649887085,0.24786165957662476,1739141216.7344153,56.09994649887085,94.13282672093484,1739141216.7344182,56.09994649887085,10.944295812036511,1739141216.7344198,56.09994649887085,-0.0026058682330290755,1739141216.7344217,56.09994649887085,-3.1080094908203346,1739141216.7344236,56.09994649887085,0.46645209989414615,1739141216.734425,56.09994649887085,0.06436928322888327,1739141216.7344263,56.09994649887085,2.074478697329665,1739141216.7344282,56.09994649887085,0.0,1739141216.7344296,56.09994649887085,-0.009049248809079646,1739141216.7344308,56.09994649887085,3.1126039641319103,1739141216.7344322,56.09994649887085,2.083527946138745 +1739141216.7553537,56.11994647979736,18.399619807244157,1739141216.7553575,56.11994647979736,0.24786165957662476,1739141216.7553608,56.11994647979736,94.13282672093484,1739141216.7553637,56.11994647979736,10.944295812036511,1739141216.7553651,56.11994647979736,-0.0026058682330290755,1739141216.7553673,56.11994647979736,-3.1080094908203346,1739141216.7553685,56.11994647979736,0.46645209989414615,1739141216.75537,56.11994647979736,0.06436928322888327,1739141216.7553716,56.11994647979736,2.074478697329665,1739141216.7553732,56.11994647979736,0.0,1739141216.755375,56.11994647979736,-0.009049248809079646,1739141216.7553763,56.11994647979736,3.1126039641319103,1739141216.755378,56.11994647979736,2.083527946138745 +1739141216.7750146,56.13994646072388,18.399619807244157,1739141216.775017,56.13994646072388,0.24786165957662476,1739141216.77502,56.13994646072388,94.13282672093484,1739141216.7750225,56.13994646072388,10.944295812036511,1739141216.775024,56.13994646072388,-0.0026058682330290755,1739141216.7750256,56.13994646072388,-3.1080094908203346,1739141216.7750273,56.13994646072388,0.46645209989414615,1739141216.7750282,56.13994646072388,0.06436928322888327,1739141216.7750294,56.13994646072388,2.074478697329665,1739141216.775031,56.13994646072388,0.0,1739141216.7750323,56.13994646072388,-0.009049248809079646,1739141216.775034,56.13994646072388,3.1126039641319103,1739141216.775035,56.13994646072388,2.083527946138745 +1739141216.7951903,56.15994644165039,18.399619807244157,1739141216.7951932,56.15994644165039,0.24786165957662476,1739141216.7951958,56.15994644165039,94.13282672093484,1739141216.7951992,56.15994644165039,10.944295812036511,1739141216.7952008,56.15994644165039,-0.0026058682330290755,1739141216.7952027,56.15994644165039,-3.1080094908203346,1739141216.7952044,56.15994644165039,0.46645209989414615,1739141216.7952058,56.15994644165039,0.06436928322888327,1739141216.7952075,56.15994644165039,2.074478697329665,1739141216.795209,56.15994644165039,0.0,1739141216.7952106,56.15994644165039,-0.009049248809079646,1739141216.7952123,56.15994644165039,3.1126039641319103,1739141216.795214,56.15994644165039,2.083527946138745 +1739141216.8150282,56.179946422576904,18.170560341080915,1739141216.8150308,56.179946422576904,0.2543854557078431,1739141216.8150334,56.179946422576904,94.55548782121421,1739141216.815036,56.179946422576904,10.52418462195556,1739141216.8150375,56.179946422576904,-0.006134028627495241,1739141216.815039,56.179946422576904,-3.1075348518737385,1739141216.8150403,56.179946422576904,0.47337536273261627,1739141216.8150415,56.179946422576904,0.06209973065774438,1739141216.8150427,56.179946422576904,2.068741780123429,1739141216.8150444,56.179946422576904,0.0,1739141216.815046,56.179946422576904,-0.018388307081402305,1739141216.8150475,56.179946422576904,3.113738349362574,1739141216.8150487,56.179946422576904,2.0826829143774064 +1739141216.8344543,56.19994640350342,18.170560341080915,1739141216.8344567,56.19994640350342,0.2543854557078431,1739141216.8344593,56.19994640350342,94.55548782121421,1739141216.834462,56.19994640350342,10.52418462195556,1739141216.8344636,56.19994640350342,-0.006134028627495241,1739141216.834465,56.19994640350342,-3.1075348518737385,1739141216.8344662,56.19994640350342,0.47337536273261627,1739141216.8344784,56.19994640350342,0.06209973065774438,1739141216.83448,56.19994640350342,2.068741780123429,1739141216.834482,56.19994640350342,0.0,1739141216.8344831,56.19994640350342,-0.01394113425397725,1739141216.8344846,56.19994640350342,3.113738349362574,1739141216.8344855,56.19994640350342,2.0826829143774064 +1739141216.8572915,56.21994638442993,18.170560341080915,1739141216.857295,56.21994638442993,0.2543854557078431,1739141216.8572996,56.21994638442993,94.55548782121421,1739141216.8573046,56.21994638442993,10.52418462195556,1739141216.8573077,56.21994638442993,-0.006134028627495241,1739141216.8573115,56.21994638442993,-3.1075348518737385,1739141216.8573148,56.21994638442993,0.47337536273261627,1739141216.8573182,56.21994638442993,0.06209973065774438,1739141216.8573215,56.21994638442993,2.068741780123429,1739141216.857325,56.21994638442993,0.0,1739141216.8573284,56.21994638442993,-0.01394113425397725,1739141216.8573318,56.21994638442993,3.113738349362574,1739141216.857335,56.21994638442993,2.0826829143774064 +1739141216.8746026,56.239946365356445,18.170560341080915,1739141216.874606,56.239946365356445,0.2543854557078431,1739141216.874609,56.239946365356445,94.55548782121421,1739141216.8746116,56.239946365356445,10.52418462195556,1739141216.8746133,56.239946365356445,-0.006134028627495241,1739141216.874615,56.239946365356445,-3.1075348518737385,1739141216.8746166,56.239946365356445,0.47337536273261627,1739141216.874618,56.239946365356445,0.06209973065774438,1739141216.8746195,56.239946365356445,2.068741780123429,1739141216.8746214,56.239946365356445,0.0,1739141216.8746233,56.239946365356445,-0.01394113425397725,1739141216.8746245,56.239946365356445,3.113738349362574,1739141216.8746257,56.239946365356445,2.0826829143774064 +1739141216.8945816,56.25994634628296,18.170560341080915,1739141216.894585,56.25994634628296,0.2543854557078431,1739141216.8945904,56.25994634628296,94.55548782121421,1739141216.8945982,56.25994634628296,10.52418462195556,1739141216.8946004,56.25994634628296,-0.006134028627495241,1739141216.8946025,56.25994634628296,-3.1075348518737385,1739141216.8946037,56.25994634628296,0.47337536273261627,1739141216.8946056,56.25994634628296,0.06209973065774438,1739141216.8946066,56.25994634628296,2.068741780123429,1739141216.8946085,56.25994634628296,0.0,1739141216.89461,56.25994634628296,-0.01394113425397725,1739141216.8946111,56.25994634628296,3.113738349362574,1739141216.8946126,56.25994634628296,2.0826829143774064 +1739141216.91475,56.27994632720947,17.941629862530007,1739141216.9147525,56.27994632720947,0.2606456877342236,1739141216.9147553,56.27994632720947,94.5813632255225,1739141216.914758,56.27994632720947,10.503006568948772,1739141216.9147592,56.27994632720947,-0.006313503652976503,1739141216.914761,56.27994632720947,-3.1057197967680397,1739141216.9147623,56.27994632720947,0.4655996606022835,1739141216.9147635,56.27994632720947,0.06453016258507305,1739141216.914765,56.27994632720947,2.0751861647981187,1739141216.9147663,56.27994632720947,0.0,1739141216.9147675,56.27994632720947,0.0013505285052367423,1739141216.914769,56.27994632720947,3.114872734593238,1739141216.9147701,56.27994632720947,2.0811173841014874 +1739141216.9346082,56.299946308135986,17.941629862530007,1739141216.934611,56.299946308135986,0.2606456877342236,1739141216.934615,56.299946308135986,94.5813632255225,1739141216.934618,56.299946308135986,10.503006568948772,1739141216.9346197,56.299946308135986,-0.006313503652976503,1739141216.9346213,56.299946308135986,-3.1057197967680397,1739141216.9346228,56.299946308135986,0.4655996606022835,1739141216.9346242,56.299946308135986,0.06453016258507305,1739141216.9346256,56.299946308135986,2.0751861647981187,1739141216.934627,56.299946308135986,0.0,1739141216.9346292,56.299946308135986,-0.005931219303368707,1739141216.9346304,56.299946308135986,3.114872734593238,1739141216.9346318,56.299946308135986,2.0811173841014874 +1739141216.9548752,56.3199462890625,17.941629862530007,1739141216.9548774,56.3199462890625,0.2606456877342236,1739141216.9548802,56.3199462890625,94.5813632255225,1739141216.9548833,56.3199462890625,10.503006568948772,1739141216.9548845,56.3199462890625,-0.006313503652976503,1739141216.9548862,56.3199462890625,-3.1057197967680397,1739141216.9548874,56.3199462890625,0.4655996606022835,1739141216.9548888,56.3199462890625,0.06453016258507305,1739141216.95489,56.3199462890625,2.0751861647981187,1739141216.9548914,56.3199462890625,0.0,1739141216.954893,56.3199462890625,-0.005931219303368707,1739141216.9548943,56.3199462890625,3.114872734593238,1739141216.9548953,56.3199462890625,2.0811173841014874 +1739141216.9745743,56.339946269989014,17.941629862530007,1739141216.9745774,56.339946269989014,0.2606456877342236,1739141216.974581,56.339946269989014,94.5813632255225,1739141216.974584,56.339946269989014,10.503006568948772,1739141216.9745858,56.339946269989014,-0.006313503652976503,1739141216.974588,56.339946269989014,-3.1057197967680397,1739141216.974589,56.339946269989014,0.4655996606022835,1739141216.9745908,56.339946269989014,0.06453016258507305,1739141216.974592,56.339946269989014,2.0751861647981187,1739141216.974594,56.339946269989014,0.0,1739141216.9745955,56.339946269989014,-0.005931219303368707,1739141216.974597,56.339946269989014,3.114872734593238,1739141216.9745982,56.339946269989014,2.0811173841014874 +1739141216.999726,56.35994625091553,17.941629862530007,1739141216.9997349,56.35994625091553,0.2606456877342236,1739141216.9997451,56.35994625091553,94.5813632255225,1739141216.9997547,56.35994625091553,10.503006568948772,1739141216.999914,56.35994625091553,-0.006313503652976503,1739141216.9999275,56.35994625091553,-3.1057197967680397,1739141216.999934,56.35994625091553,0.4655996606022835,1739141216.9999402,56.35994625091553,0.06453016258507305,1739141216.9999545,56.35994625091553,2.0751861647981187,1739141216.9999695,56.35994625091553,0.0,1739141216.9999778,56.35994625091553,-0.005931219303368707,1739141216.999992,56.35994625091553,3.114872734593238,1739141217.000004,56.35994625091553,2.0811173841014874 +1739141217.0282757,56.37994623184204,17.941629862530007,1739141217.0282817,56.37994623184204,0.2606456877342236,1739141217.0282888,56.37994623184204,94.5813632255225,1739141217.0282972,56.37994623184204,10.503006568948772,1739141217.0283017,56.37994623184204,-0.006313503652976503,1739141217.028308,56.37994623184204,-3.1057197967680397,1739141217.0283136,56.37994623184204,0.4655996606022835,1739141217.0283186,56.37994623184204,0.06453016258507305,1739141217.0283241,56.37994623184204,2.0751861647981187,1739141217.0283296,56.37994623184204,0.0,1739141217.0283353,56.37994623184204,-0.005931219303368707,1739141217.0283425,56.37994623184204,3.114872734593238,1739141217.0283496,56.37994623184204,2.0811173841014874 +1739141217.0435061,56.40994620323181,17.71280429911106,1739141217.0435092,56.40994620323181,0.26664327751233863,1739141217.0435133,56.40994620323181,95.18219759245528,1739141217.0435169,56.40994620323181,9.903696903564464,1739141217.0435188,56.40994620323181,-0.009,1739141217.043521,56.40994620323181,-3.1063096344076433,1739141217.043523,56.40994620323181,0.47533144450977316,1739141217.043525,56.40994620323181,0.05978011204193555,1739141217.0435264,56.40994620323181,2.0671237619620464,1739141217.0435286,56.40994620323181,0.0,1739141217.0435305,56.40994620323181,-0.020358839820151374,1739141217.0435321,56.40994620323181,3.1160071198239017,1739141217.0435338,56.40994620323181,2.080612302866001 +1739141217.0639172,56.429946184158325,17.71280429911106,1739141217.0639205,56.429946184158325,0.26664327751233863,1739141217.0639243,56.429946184158325,95.18219759245528,1739141217.063928,56.429946184158325,9.903696903564464,1739141217.0639296,56.429946184158325,-0.009,1739141217.063932,56.429946184158325,-3.1063096344076433,1739141217.0639336,56.429946184158325,0.47533144450977316,1739141217.0639353,56.429946184158325,0.05978011204193555,1739141217.063937,56.429946184158325,2.0671237619620464,1739141217.063939,56.429946184158325,0.0,1739141217.0639408,56.429946184158325,-0.013488540903954682,1739141217.0639424,56.429946184158325,3.1160071198239017,1739141217.063944,56.429946184158325,2.080612302866001 +1739141217.0832298,56.44994616508484,17.71280429911106,1739141217.083233,56.44994616508484,0.26664327751233863,1739141217.083237,56.44994616508484,95.18219759245528,1739141217.083241,56.44994616508484,9.903696903564464,1739141217.0832434,56.44994616508484,-0.009,1739141217.0832458,56.44994616508484,-3.1063096344076433,1739141217.0832481,56.44994616508484,0.47533144450977316,1739141217.0832498,56.44994616508484,0.05978011204193555,1739141217.0832517,56.44994616508484,2.0671237619620464,1739141217.0832539,56.44994616508484,0.0,1739141217.083256,56.44994616508484,-0.013488540903954682,1739141217.0832582,56.44994616508484,3.1160071198239017,1739141217.0832598,56.44994616508484,2.080612302866001 +1739141217.1035738,56.46994614601135,17.71280429911106,1739141217.1035771,56.46994614601135,0.26664327751233863,1739141217.103581,56.46994614601135,95.18219759245528,1739141217.103585,56.46994614601135,9.903696903564464,1739141217.103587,56.46994614601135,-0.009,1739141217.103589,56.46994614601135,-3.1063096344076433,1739141217.1035912,56.46994614601135,0.47533144450977316,1739141217.1035926,56.46994614601135,0.05978011204193555,1739141217.1035945,56.46994614601135,2.0671237619620464,1739141217.1035967,56.46994614601135,0.0,1739141217.1035986,56.46994614601135,-0.013488540903954682,1739141217.1036005,56.46994614601135,3.1160071198239017,1739141217.1036022,56.46994614601135,2.080612302866001 +1739141217.123396,56.489946126937866,17.71280429911106,1739141217.1233997,56.489946126937866,0.26664327751233863,1739141217.1234033,56.489946126937866,95.18219759245528,1739141217.123407,56.489946126937866,9.903696903564464,1739141217.1234086,56.489946126937866,-0.009,1739141217.123411,56.489946126937866,-3.1063096344076433,1739141217.1234128,56.489946126937866,0.47533144450977316,1739141217.1234145,56.489946126937866,0.05978011204193555,1739141217.1234164,56.489946126937866,2.0671237619620464,1739141217.1234183,56.489946126937866,0.0,1739141217.1234202,56.489946126937866,-0.013488540903954682,1739141217.123422,56.489946126937866,3.1160071198239017,1739141217.1234238,56.489946126937866,2.080612302866001 +1739141217.1436563,56.50994610786438,17.484078721803446,1739141217.14366,56.50994610786438,0.2723786233984056,1739141217.143664,56.50994610786438,95.22337966706243,1739141217.143668,56.50994610786438,9.8669028494553,1739141217.1436703,56.50994610786438,-0.009,1739141217.1436734,56.50994610786438,-3.1046694229435077,1739141217.1436756,56.50994610786438,0.4675246560936805,1739141217.1436777,56.50994610786438,0.06179084494112792,1739141217.1436791,56.50994610786438,2.07358889022189,1739141217.1436813,56.50994610786438,0.0,1739141217.1436834,56.50994610786438,0.0016463602367801505,1739141217.1436853,56.50994610786438,3.1171415050545654,1739141217.1436875,56.50994610786438,2.079149629366673 +1739141217.1631677,56.529946088790894,17.484078721803446,1739141217.1631708,56.529946088790894,0.2723786233984056,1739141217.163174,56.529946088790894,95.22337966706243,1739141217.163177,56.529946088790894,9.8669028494553,1739141217.1631784,56.529946088790894,-0.009,1739141217.1631804,56.529946088790894,-3.1046694229435077,1739141217.1631818,56.529946088790894,0.4675246560936805,1739141217.1631835,56.529946088790894,0.06179084494112792,1739141217.1631844,56.529946088790894,2.07358889022189,1739141217.163186,56.529946088790894,0.0,1739141217.1631877,56.529946088790894,-0.005560739144783167,1739141217.163189,56.529946088790894,3.1171415050545654,1739141217.1631908,56.529946088790894,2.079149629366673 +1739141217.1830456,56.54994606971741,17.484078721803446,1739141217.1830487,56.54994606971741,0.2723786233984056,1739141217.1830518,56.54994606971741,95.22337966706243,1739141217.183055,56.54994606971741,9.8669028494553,1739141217.1830564,56.54994606971741,-0.009,1739141217.1830583,56.54994606971741,-3.1046694229435077,1739141217.18306,56.54994606971741,0.4675246560936805,1739141217.1830616,56.54994606971741,0.06179084494112792,1739141217.1830628,56.54994606971741,2.07358889022189,1739141217.183065,56.54994606971741,0.0,1739141217.1830664,56.54994606971741,-0.005560739144783167,1739141217.1830676,56.54994606971741,3.1171415050545654,1739141217.183069,56.54994606971741,2.079149629366673 +1739141217.2029543,56.56994605064392,17.484078721803446,1739141217.2029574,56.56994605064392,0.2723786233984056,1739141217.2029607,56.56994605064392,95.22337966706243,1739141217.2029634,56.56994605064392,9.8669028494553,1739141217.2029648,56.56994605064392,-0.009,1739141217.2029665,56.56994605064392,-3.1046694229435077,1739141217.2029681,56.56994605064392,0.4675246560936805,1739141217.2029693,56.56994605064392,0.06179084494112792,1739141217.2029707,56.56994605064392,2.07358889022189,1739141217.2029724,56.56994605064392,0.0,1739141217.2029738,56.56994605064392,-0.005560739144783167,1739141217.202975,56.56994605064392,3.1171415050545654,1739141217.2029767,56.56994605064392,2.079149629366673 +1739141217.2227173,56.589946031570435,17.484078721803446,1739141217.2227206,56.589946031570435,0.2723786233984056,1739141217.2227232,56.589946031570435,95.22337966706243,1739141217.2227266,56.589946031570435,9.8669028494553,1739141217.222728,56.589946031570435,-0.009,1739141217.2227297,56.589946031570435,-3.1046694229435077,1739141217.2227314,56.589946031570435,0.4675246560936805,1739141217.2227328,56.589946031570435,0.06179084494112792,1739141217.222734,56.589946031570435,2.07358889022189,1739141217.2227356,56.589946031570435,0.0,1739141217.222737,56.589946031570435,-0.005560739144783167,1739141217.2227385,56.589946031570435,3.1171415050545654,1739141217.2227397,56.589946031570435,2.079149629366673 +1739141217.2428532,56.60994601249695,17.25546383032741,1739141217.2428558,56.60994601249695,0.277851689808573,1739141217.2428586,56.60994601249695,95.26454129366094,1739141217.2428615,56.60994601249695,9.827370592438614,1739141217.2428632,56.60994601249695,-0.009022283114926997,1739141217.2428648,56.60994601249695,-3.1029917010118027,1739141217.2428663,56.60994601249695,0.45997939222038836,1739141217.2428677,56.60994601249695,0.06391928425045175,1739141217.242869,56.60994601249695,2.0798566539870373,1739141217.2428706,56.60994601249695,0.0,1739141217.2428718,56.60994601249695,0.007441809052157113,1739141217.2428732,56.60994601249695,3.1182758902852292,1739141217.2428744,56.60994601249695,2.078606537645492 +1739141217.2627103,56.62994599342346,17.25546383032741,1739141217.262714,56.62994599342346,0.277851689808573,1739141217.2627172,56.62994599342346,95.26454129366094,1739141217.26272,56.62994599342346,9.827370592438614,1739141217.2627215,56.62994599342346,-0.009022283114926997,1739141217.2627234,56.62994599342346,-3.1029917010118027,1739141217.2627249,56.62994599342346,0.45997939222038836,1739141217.2627263,56.62994599342346,0.06391928425045175,1739141217.2627277,56.62994599342346,2.0798566539870373,1739141217.2627294,56.62994599342346,0.0,1739141217.2627308,56.62994599342346,0.001250116341545482,1739141217.2627327,56.62994599342346,3.1182758902852292,1739141217.2627344,56.62994599342346,2.078606537645492 +1739141217.2828312,56.649945974349976,17.25546383032741,1739141217.2828338,56.649945974349976,0.277851689808573,1739141217.2828372,56.649945974349976,95.26454129366094,1739141217.28284,56.649945974349976,9.827370592438614,1739141217.2828417,56.649945974349976,-0.009022283114926997,1739141217.2828434,56.649945974349976,-3.1029917010118027,1739141217.282845,56.649945974349976,0.45997939222038836,1739141217.2828462,56.649945974349976,0.06391928425045175,1739141217.2828474,56.649945974349976,2.0798566539870373,1739141217.282849,56.649945974349976,0.0,1739141217.2828505,56.649945974349976,0.001250116341545482,1739141217.2828522,56.649945974349976,3.1182758902852292,1739141217.2828534,56.649945974349976,2.078606537645492 +1739141217.302817,56.66994595527649,17.25546383032741,1739141217.3028197,56.66994595527649,0.277851689808573,1739141217.3028228,56.66994595527649,95.26454129366094,1739141217.3028255,56.66994595527649,9.827370592438614,1739141217.3028271,56.66994595527649,-0.009022283114926997,1739141217.3028288,56.66994595527649,-3.1029917010118027,1739141217.30283,56.66994595527649,0.45997939222038836,1739141217.3028314,56.66994595527649,0.06391928425045175,1739141217.3028326,56.66994595527649,2.0798566539870373,1739141217.3028343,56.66994595527649,0.0,1739141217.302836,56.66994595527649,0.001250116341545482,1739141217.3028371,56.66994595527649,3.1182758902852292,1739141217.3028386,56.66994595527649,2.078606537645492 +1739141217.3226652,56.689945936203,17.25546383032741,1739141217.322668,56.689945936203,0.277851689808573,1739141217.3226712,56.689945936203,95.26454129366094,1739141217.322674,56.689945936203,9.827370592438614,1739141217.3226752,56.689945936203,-0.009022283114926997,1739141217.322677,56.689945936203,-3.1029917010118027,1739141217.3226783,56.689945936203,0.45997939222038836,1739141217.3226798,56.689945936203,0.06391928425045175,1739141217.3226812,56.689945936203,2.0798566539870373,1739141217.3226829,56.689945936203,0.0,1739141217.3226845,56.689945936203,0.001250116341545482,1739141217.3226857,56.689945936203,3.1182758902852292,1739141217.322687,56.689945936203,2.078606537645492 +1739141217.3489947,56.70994591712952,17.25546383032741,1739141217.3490074,56.70994591712952,0.277851689808573,1739141217.3490217,56.70994591712952,95.26454129366094,1739141217.3490338,56.70994591712952,9.827370592438614,1739141217.3490393,56.70994591712952,-0.009022283114926997,1739141217.3490465,56.70994591712952,-3.1029917010118027,1739141217.349052,56.70994591712952,0.45997939222038836,1739141217.3490589,56.70994591712952,0.06391928425045175,1739141217.3490653,56.70994591712952,2.0798566539870373,1739141217.3490736,56.70994591712952,0.0,1739141217.3490798,56.70994591712952,0.001250116341545482,1739141217.349085,56.70994591712952,3.1182758902852292,1739141217.3490899,56.70994591712952,2.078606537645492 +1739141217.3700387,56.71994590759277,17.026857986127983,1739141217.370044,56.71994590759277,0.28306506341614224,1739141217.3700497,56.71994590759277,95.77276741409902,1739141217.3700552,56.71994590759277,9.318369677855985,1739141217.3700578,56.71994590759277,-0.01,1739141217.3700612,56.71994590759277,-3.1035924679816462,1739141217.3700635,56.71994590759277,0.46397154321721706,1739141217.3700662,56.71994590759277,0.05987274702133887,1739141217.3700688,56.71994590759277,2.076538063629198,1739141217.3700721,56.71994590759277,0.0,1739141217.370075,56.71994590759277,-0.005581064586431124,1739141217.3700771,56.71994590759277,3.119410275515893,1739141217.3700798,56.71994590759277,2.0788661832916047 +1739141217.3880417,56.749945878982544,17.026857986127983,1739141217.3880482,56.749945878982544,0.28306506341614224,1739141217.3880568,56.749945878982544,95.77276741409902,1739141217.388062,56.749945878982544,9.318369677855985,1739141217.3880641,56.749945878982544,-0.01,1739141217.388067,56.749945878982544,-3.1035924679816462,1739141217.3880696,56.749945878982544,0.46397154321721706,1739141217.3880723,56.749945878982544,0.05987274702133887,1739141217.3880742,56.749945878982544,2.076538063629198,1739141217.3880773,56.749945878982544,0.0,1739141217.3880801,56.749945878982544,-0.002328119662406536,1739141217.3880827,56.749945878982544,3.119410275515893,1739141217.3880854,56.749945878982544,2.0788661832916047 +1739141217.4074605,56.76994585990906,17.026857986127983,1739141217.4074662,56.76994585990906,0.28306506341614224,1739141217.4074717,56.76994585990906,95.77276741409902,1739141217.4074764,56.76994585990906,9.318369677855985,1739141217.407479,56.76994585990906,-0.01,1739141217.407482,56.76994585990906,-3.1035924679816462,1739141217.407484,56.76994585990906,0.46397154321721706,1739141217.407487,56.76994585990906,0.05987274702133887,1739141217.4074893,56.76994585990906,2.076538063629198,1739141217.4074922,56.76994585990906,0.0,1739141217.4074953,56.76994585990906,-0.002328119662406536,1739141217.4074974,56.76994585990906,3.119410275515893,1739141217.4074998,56.76994585990906,2.0788661832916047 +1739141217.4285536,56.78994584083557,17.026857986127983,1739141217.4285586,56.78994584083557,0.28306506341614224,1739141217.428565,56.78994584083557,95.77276741409902,1739141217.4285698,56.78994584083557,9.318369677855985,1739141217.4285727,56.78994584083557,-0.01,1739141217.428576,56.78994584083557,-3.1035924679816462,1739141217.4285786,56.78994584083557,0.46397154321721706,1739141217.4285808,56.78994584083557,0.05987274702133887,1739141217.4285836,56.78994584083557,2.076538063629198,1739141217.4285865,56.78994584083557,0.0,1739141217.4285893,56.78994584083557,-0.002328119662406536,1739141217.4285913,56.78994584083557,3.119410275515893,1739141217.4285936,56.78994584083557,2.0788661832916047 +1739141217.4481106,56.809945821762085,17.026857986127983,1739141217.448117,56.809945821762085,0.28306506341614224,1739141217.4481235,56.809945821762085,95.77276741409902,1739141217.4481287,56.809945821762085,9.318369677855985,1739141217.4481313,56.809945821762085,-0.01,1739141217.4481351,56.809945821762085,-3.1035924679816462,1739141217.4481378,56.809945821762085,0.46397154321721706,1739141217.4481406,56.809945821762085,0.05987274702133887,1739141217.4481437,56.809945821762085,2.076538063629198,1739141217.4481473,56.809945821762085,0.0,1739141217.4481502,56.809945821762085,-0.002328119662406536,1739141217.4481547,56.809945821762085,3.119410275515893,1739141217.448158,56.809945821762085,2.0788661832916047 +1739141217.4682274,56.8299458026886,16.798257906718483,1739141217.468233,56.8299458026886,0.2880188625281299,1739141217.468239,56.8299458026886,95.7935749751244,1739141217.4682448,56.8299458026886,9.298617249262794,1739141217.468247,56.8299458026886,-0.01,1739141217.4682505,56.8299458026886,-3.101875798010877,1739141217.4682534,56.8299458026886,0.4557935790064929,1739141217.4682555,56.8299458026886,0.062129973449082075,1739141217.468258,56.8299458026886,2.083341927499721,1739141217.4682605,56.8299458026886,0.0,1739141217.4682631,56.8299458026886,0.011332529114616414,1739141217.4682653,56.8299458026886,3.120544660746557,1739141217.468268,56.8299458026886,2.0785144724808746 +1739141217.4867177,56.84994578361511,16.798257906718483,1739141217.4867232,56.84994578361511,0.2880188625281299,1739141217.4867282,56.84994578361511,95.7935749751244,1739141217.486733,56.84994578361511,9.298617249262794,1739141217.4867356,56.84994578361511,-0.01,1739141217.4867387,56.84994578361511,-3.101875798010877,1739141217.4867415,56.84994578361511,0.4557935790064929,1739141217.4867446,56.84994578361511,0.062129973449082075,1739141217.4867468,56.84994578361511,2.083341927499721,1739141217.4867496,56.84994578361511,0.0,1739141217.4867525,56.84994578361511,0.004827455018846294,1739141217.486755,56.84994578361511,3.120544660746557,1739141217.486757,56.84994578361511,2.0785144724808746 +1739141217.5060358,56.869945764541626,16.798257906718483,1739141217.5060391,56.869945764541626,0.2880188625281299,1739141217.506042,56.869945764541626,95.7935749751244,1739141217.5060446,56.869945764541626,9.298617249262794,1739141217.5060463,56.869945764541626,-0.01,1739141217.506048,56.869945764541626,-3.101875798010877,1739141217.5060494,56.869945764541626,0.4557935790064929,1739141217.5060506,56.869945764541626,0.062129973449082075,1739141217.5060518,56.869945764541626,2.083341927499721,1739141217.5060537,56.869945764541626,0.0,1739141217.5060549,56.869945764541626,0.004827455018846294,1739141217.5060565,56.869945764541626,3.120544660746557,1739141217.5060577,56.869945764541626,2.0785144724808746 +1739141217.5255985,56.88994574546814,16.798257906718483,1739141217.5256014,56.88994574546814,0.2880188625281299,1739141217.5256047,56.88994574546814,95.7935749751244,1739141217.525607,56.88994574546814,9.298617249262794,1739141217.5256088,56.88994574546814,-0.01,1739141217.5256102,56.88994574546814,-3.101875798010877,1739141217.5256116,56.88994574546814,0.4557935790064929,1739141217.5256128,56.88994574546814,0.062129973449082075,1739141217.525614,56.88994574546814,2.083341927499721,1739141217.5256157,56.88994574546814,0.0,1739141217.525617,56.88994574546814,0.004827455018846294,1739141217.525618,56.88994574546814,3.120544660746557,1739141217.5256195,56.88994574546814,2.0785144724808746 +1739141217.5460196,56.90994572639465,16.798257906718483,1739141217.5460272,56.90994572639465,0.2880188625281299,1739141217.546036,56.90994572639465,95.7935749751244,1739141217.546044,56.90994572639465,9.298617249262794,1739141217.546048,56.90994572639465,-0.01,1739141217.546053,56.90994572639465,-3.101875798010877,1739141217.5460567,56.90994572639465,0.4557935790064929,1739141217.5460603,56.90994572639465,0.062129973449082075,1739141217.5460641,56.90994572639465,2.083341927499721,1739141217.5460703,56.90994572639465,0.0,1739141217.5460742,56.90994572639465,0.004827455018846294,1739141217.546078,56.90994572639465,3.120544660746557,1739141217.546081,56.90994572639465,2.0785144724808746 +1739141217.5662286,56.92994570732117,16.798257906718483,1739141217.5662334,56.92994570732117,0.2880188625281299,1739141217.566238,56.92994570732117,95.7935749751244,1739141217.5662425,56.92994570732117,9.298617249262794,1739141217.566245,56.92994570732117,-0.01,1739141217.5662484,56.92994570732117,-3.101875798010877,1739141217.5662513,56.92994570732117,0.4557935790064929,1739141217.5662541,56.92994570732117,0.062129973449082075,1739141217.5662565,56.92994570732117,2.083341927499721,1739141217.5662594,56.92994570732117,0.0,1739141217.5662622,56.92994570732117,0.004827455018846294,1739141217.5662656,56.92994570732117,3.120544660746557,1739141217.5662687,56.92994570732117,2.0785144724808746 +1739141217.58537,56.94994568824768,16.56963073763078,1739141217.5853727,56.94994568824768,0.29271377199391146,1739141217.5853755,56.94994568824768,96.13497240810814,1739141217.5853784,56.94994568824768,8.95525138157209,1739141217.5853796,56.94994568824768,-0.011,1739141217.5853817,56.94994568824768,-3.101726914620012,1739141217.5853832,56.94994568824768,0.45527329626734653,1739141217.5853844,56.94994568824768,0.06020265955789268,1739141217.585386,56.94994568824768,2.0837755433565723,1739141217.5853875,56.94994568824768,0.0,1739141217.5853894,56.94994568824768,0.004399907193910809,1739141217.5853903,56.94994568824768,3.1216790459772206,1739141217.5853918,56.94994568824768,2.079172041858607 +1739141217.6055195,56.969945669174194,16.56963073763078,1739141217.6055224,56.969945669174194,0.29271377199391146,1739141217.6055257,56.969945669174194,96.13497240810814,1739141217.605529,56.969945669174194,8.95525138157209,1739141217.6055307,56.969945669174194,-0.011,1739141217.6055324,56.969945669174194,-3.101726914620012,1739141217.6055338,56.969945669174194,0.45527329626734653,1739141217.6055353,56.969945669174194,0.06020265955789268,1739141217.6055365,56.969945669174194,2.0837755433565723,1739141217.6055381,56.969945669174194,0.0,1739141217.6055396,56.969945669174194,0.00460350149796529,1739141217.6055412,56.969945669174194,3.1216790459772206,1739141217.6055424,56.969945669174194,2.079172041858607 +1739141217.6268048,56.98994565010071,16.56963073763078,1739141217.6268084,56.98994565010071,0.29271377199391146,1739141217.6268122,56.98994565010071,96.13497240810814,1739141217.6268156,56.98994565010071,8.95525138157209,1739141217.6268172,56.98994565010071,-0.011,1739141217.6268191,56.98994565010071,-3.101726914620012,1739141217.6268206,56.98994565010071,0.45527329626734653,1739141217.6268222,56.98994565010071,0.06020265955789268,1739141217.6268234,56.98994565010071,2.0837755433565723,1739141217.6268256,56.98994565010071,0.0,1739141217.626827,56.98994565010071,0.00460350149796529,1739141217.6268284,56.98994565010071,3.1216790459772206,1739141217.62683,56.98994565010071,2.079172041858607 +1739141217.6455128,57.00994563102722,16.56963073763078,1739141217.6455152,57.00994563102722,0.29271377199391146,1739141217.6455183,57.00994563102722,96.13497240810814,1739141217.645521,57.00994563102722,8.95525138157209,1739141217.6455224,57.00994563102722,-0.011,1739141217.6455243,57.00994563102722,-3.101726914620012,1739141217.6455257,57.00994563102722,0.45527329626734653,1739141217.6455271,57.00994563102722,0.06020265955789268,1739141217.645528,57.00994563102722,2.0837755433565723,1739141217.6455297,57.00994563102722,0.0,1739141217.6455312,57.00994563102722,0.00460350149796529,1739141217.6455324,57.00994563102722,3.1216790459772206,1739141217.6455338,57.00994563102722,2.079172041858607 +1739141217.66599,57.029945611953735,16.56963073763078,1739141217.665993,57.029945611953735,0.29271377199391146,1739141217.665996,57.029945611953735,96.13497240810814,1739141217.665999,57.029945611953735,8.95525138157209,1739141217.6660001,57.029945611953735,-0.011,1739141217.666002,57.029945611953735,-3.101726914620012,1739141217.6660035,57.029945611953735,0.45527329626734653,1739141217.6660047,57.029945611953735,0.06020265955789268,1739141217.6660063,57.029945611953735,2.0837755433565723,1739141217.6660078,57.029945611953735,0.0,1739141217.6660094,57.029945611953735,0.00460350149796529,1739141217.6660106,57.029945611953735,3.1216790459772206,1739141217.6660118,57.029945611953735,2.079172041858607 +1739141217.6858077,57.04994559288025,16.34093978996596,1739141217.6858115,57.04994559288025,0.29715046528725786,1739141217.6858146,57.04994559288025,96.68460048362147,1739141217.6858172,57.04994559288025,8.404124175299401,1739141217.685819,57.04994559288025,-0.010609150364393166,1739141217.6858208,57.04994559288025,-3.102835862320455,1739141217.685823,57.04994559288025,0.4567438152250142,1739141217.6858244,57.04994559288025,0.05559542834209834,1739141217.6858258,57.04994559288025,2.0825502111907253,1739141217.6858277,57.04994559288025,0.0,1739141217.6858292,57.04994559288025,0.0013065249941629263,1739141217.6858313,57.04994559288025,3.1228134312078843,1739141217.685833,57.04994559288025,2.0796736966009495 +1739141217.7054174,57.06994557380676,16.34093978996596,1739141217.7054198,57.06994557380676,0.29715046528725786,1739141217.7054226,57.06994557380676,96.68460048362147,1739141217.7054255,57.06994557380676,8.404124175299401,1739141217.7054267,57.06994557380676,-0.010609150364393166,1739141217.7054284,57.06994557380676,-3.102835862320455,1739141217.70543,57.06994557380676,0.4567438152250142,1739141217.7054312,57.06994557380676,0.05559542834209834,1739141217.7054327,57.06994557380676,2.0825502111907253,1739141217.705434,57.06994557380676,0.0,1739141217.7054353,57.06994557380676,0.0028765145897757805,1739141217.705437,57.06994557380676,3.1228134312078843,1739141217.7054381,57.06994557380676,2.0796736966009495 +1739141217.7252092,57.089945554733276,16.34093978996596,1739141217.7252116,57.089945554733276,0.29715046528725786,1739141217.7252145,57.089945554733276,96.68460048362147,1739141217.725217,57.089945554733276,8.404124175299401,1739141217.7252185,57.089945554733276,-0.010609150364393166,1739141217.7252202,57.089945554733276,-3.102835862320455,1739141217.7252219,57.089945554733276,0.4567438152250142,1739141217.725223,57.089945554733276,0.05559542834209834,1739141217.7252245,57.089945554733276,2.0825502111907253,1739141217.7252262,57.089945554733276,0.0,1739141217.7252276,57.089945554733276,0.0028765145897757805,1739141217.7252288,57.089945554733276,3.1228134312078843,1739141217.72523,57.089945554733276,2.0796736966009495 +1739141217.7452931,57.10994553565979,16.34093978996596,1739141217.745298,57.10994553565979,0.29715046528725786,1739141217.7453039,57.10994553565979,96.68460048362147,1739141217.7453086,57.10994553565979,8.404124175299401,1739141217.7453103,57.10994553565979,-0.010609150364393166,1739141217.745312,57.10994553565979,-3.102835862320455,1739141217.7453132,57.10994553565979,0.4567438152250142,1739141217.7453146,57.10994553565979,0.05559542834209834,1739141217.7453158,57.10994553565979,2.0825502111907253,1739141217.7453175,57.10994553565979,0.0,1739141217.7453191,57.10994553565979,0.0028765145897757805,1739141217.74532,57.10994553565979,3.1228134312078843,1739141217.7453215,57.10994553565979,2.0796736966009495 +1739141217.765365,57.129945516586304,16.34093978996596,1739141217.7653677,57.129945516586304,0.29715046528725786,1739141217.765371,57.129945516586304,96.68460048362147,1739141217.765374,57.129945516586304,8.404124175299401,1739141217.7653751,57.129945516586304,-0.010609150364393166,1739141217.765377,57.129945516586304,-3.102835862320455,1739141217.7653785,57.129945516586304,0.4567438152250142,1739141217.76538,57.129945516586304,0.05559542834209834,1739141217.765381,57.129945516586304,2.0825502111907253,1739141217.7653828,57.129945516586304,0.0,1739141217.7653842,57.129945516586304,0.0028765145897757805,1739141217.7653859,57.129945516586304,3.1228134312078843,1739141217.7653873,57.129945516586304,2.0796736966009495 +1739141217.785379,57.14994549751282,16.34093978996596,1739141217.7853818,57.14994549751282,0.29715046528725786,1739141217.785385,57.14994549751282,96.68460048362147,1739141217.7853882,57.14994549751282,8.404124175299401,1739141217.78539,57.14994549751282,-0.010609150364393166,1739141217.7853916,57.14994549751282,-3.102835862320455,1739141217.7853935,57.14994549751282,0.4567438152250142,1739141217.785395,57.14994549751282,0.05559542834209834,1739141217.7853963,57.14994549751282,2.0825502111907253,1739141217.785398,57.14994549751282,0.0,1739141217.7853992,57.14994549751282,0.0028765145897757805,1739141217.7854006,57.14994549751282,3.1228134312078843,1739141217.7854018,57.14994549751282,2.0796736966009495 +1739141217.805378,57.16994547843933,16.112201043588037,1739141217.8053803,57.16994547843933,0.30132851811937034,1739141217.8053834,57.16994547843933,97.11776704916474,1739141217.8053863,57.16994547843933,7.970107031531143,1739141217.8053875,57.16994547843933,-0.011,1739141217.8053894,57.16994547843933,-3.103251723249526,1739141217.8053906,57.16994547843933,0.4559383673544808,1739141217.805392,57.16994547843933,0.05273656220885518,1739141217.8053937,57.16994547843933,2.0832212735392215,1739141217.8053951,57.16994547843933,0.0,1739141217.8053968,57.16994547843933,0.0036157502655505052,1739141217.805398,57.16994547843933,3.123947816438548,1739141217.8053992,57.16994547843933,2.079957540437983 +1739141217.8252852,57.189945459365845,16.112201043588037,1739141217.8252873,57.189945459365845,0.30132851811937034,1739141217.8252904,57.189945459365845,97.11776704916474,1739141217.8252933,57.189945459365845,7.970107031531143,1739141217.8252945,57.189945459365845,-0.011,1739141217.8252964,57.189945459365845,-3.103251723249526,1739141217.8252978,57.189945459365845,0.4559383673544808,1739141217.8252995,57.189945459365845,0.05273656220885518,1739141217.8253007,57.189945459365845,2.0832212735392215,1739141217.8253024,57.189945459365845,0.0,1739141217.8253038,57.189945459365845,0.0032637331012383974,1739141217.825305,57.189945459365845,3.123947816438548,1739141217.8253067,57.189945459365845,2.079957540437983 +1739141217.845323,57.20994544029236,16.112201043588037,1739141217.8453252,57.20994544029236,0.30132851811937034,1739141217.845328,57.20994544029236,97.11776704916474,1739141217.8453312,57.20994544029236,7.970107031531143,1739141217.8453324,57.20994544029236,-0.011,1739141217.8453343,57.20994544029236,-3.103251723249526,1739141217.8453355,57.20994544029236,0.4559383673544808,1739141217.845337,57.20994544029236,0.05273656220885518,1739141217.845338,57.20994544029236,2.0832212735392215,1739141217.8453395,57.20994544029236,0.0,1739141217.8453412,57.20994544029236,0.0032637331012383974,1739141217.8453424,57.20994544029236,3.123947816438548,1739141217.8453436,57.20994544029236,2.079957540437983 +1739141217.8652997,57.22994542121887,16.112201043588037,1739141217.8653026,57.22994542121887,0.30132851811937034,1739141217.8653054,57.22994542121887,97.11776704916474,1739141217.8653078,57.22994542121887,7.970107031531143,1739141217.8653095,57.22994542121887,-0.011,1739141217.8653111,57.22994542121887,-3.103251723249526,1739141217.8653128,57.22994542121887,0.4559383673544808,1739141217.865314,57.22994542121887,0.05273656220885518,1739141217.8653154,57.22994542121887,2.0832212735392215,1739141217.8653169,57.22994542121887,0.0,1739141217.8653183,57.22994542121887,0.0032637331012383974,1739141217.8653197,57.22994542121887,3.123947816438548,1739141217.865321,57.22994542121887,2.079957540437983 +1739141217.8852305,57.249945402145386,16.112201043588037,1739141217.885233,57.249945402145386,0.30132851811937034,1739141217.8852355,57.249945402145386,97.11776704916474,1739141217.885238,57.249945402145386,7.970107031531143,1739141217.8852394,57.249945402145386,-0.011,1739141217.885241,57.249945402145386,-3.103251723249526,1739141217.8852425,57.249945402145386,0.4559383673544808,1739141217.885244,57.249945402145386,0.05273656220885518,1739141217.8852448,57.249945402145386,2.0832212735392215,1739141217.8852465,57.249945402145386,0.0,1739141217.8852482,57.249945402145386,0.0032637331012383974,1739141217.8852496,57.249945402145386,3.123947816438548,1739141217.885251,57.249945402145386,2.079957540437983 +1739141217.9053366,57.2699453830719,15.883421207318793,1739141217.9053395,57.2699453830719,0.3052477149825208,1739141217.905342,57.2699453830719,97.12852362066627,1739141217.9053447,57.2699453830719,7.958269673754856,1739141217.9053462,57.2699453830719,-0.011,1739141217.905348,57.2699453830719,-3.1017095025369446,1739141217.9053495,57.2699453830719,0.4470465008797256,1739141217.9053507,57.2699453830719,0.054570742797497115,1739141217.9053519,57.2699453830719,2.0906439561754517,1739141217.9053535,57.2699453830719,0.0,1739141217.905355,57.2699453830719,0.016746542082154484,1739141217.9053566,57.2699453830719,3.125082201669212,1739141217.9053578,57.2699453830719,2.0803178025295694 +1739141217.925264,57.28994536399841,15.883421207318793,1739141217.9252663,57.28994536399841,0.3052477149825208,1739141217.9252687,57.28994536399841,97.12852362066627,1739141217.9252715,57.28994536399841,7.958269673754856,1739141217.9252732,57.28994536399841,-0.011,1739141217.925275,57.28994536399841,-3.1017095025369446,1739141217.9252765,57.28994536399841,0.4470465008797256,1739141217.9252777,57.28994536399841,0.054570742797497115,1739141217.925279,57.28994536399841,2.0906439561754517,1739141217.9252806,57.28994536399841,0.0,1739141217.9252818,57.28994536399841,0.010326153645882297,1739141217.925283,57.28994536399841,3.125082201669212,1739141217.9252844,57.28994536399841,2.0803178025295694 +1739141217.9453416,57.30994534492493,15.883421207318793,1739141217.945344,57.30994534492493,0.3052477149825208,1739141217.945347,57.30994534492493,97.12852362066627,1739141217.9453497,57.30994534492493,7.958269673754856,1739141217.945351,57.30994534492493,-0.011,1739141217.9453528,57.30994534492493,-3.1017095025369446,1739141217.945354,57.30994534492493,0.4470465008797256,1739141217.9453552,57.30994534492493,0.054570742797497115,1739141217.9453566,57.30994534492493,2.0906439561754517,1739141217.945358,57.30994534492493,0.0,1739141217.9453597,57.30994534492493,0.010326153645882297,1739141217.9453614,57.30994534492493,3.125082201669212,1739141217.9453623,57.30994534492493,2.0803178025295694 +1739141217.9656043,57.32994532585144,15.883421207318793,1739141217.9656074,57.32994532585144,0.3052477149825208,1739141217.9656105,57.32994532585144,97.12852362066627,1739141217.9656136,57.32994532585144,7.958269673754856,1739141217.9656148,57.32994532585144,-0.011,1739141217.9656167,57.32994532585144,-3.1017095025369446,1739141217.9656181,57.32994532585144,0.4470465008797256,1739141217.9656198,57.32994532585144,0.054570742797497115,1739141217.965621,57.32994532585144,2.0906439561754517,1739141217.965623,57.32994532585144,0.0,1739141217.9656243,57.32994532585144,0.010326153645882297,1739141217.965626,57.32994532585144,3.125082201669212,1739141217.9656277,57.32994532585144,2.0803178025295694 +1739141217.9854562,57.349945306777954,15.883421207318793,1739141217.9854586,57.349945306777954,0.3052477149825208,1739141217.985462,57.349945306777954,97.12852362066627,1739141217.9854648,57.349945306777954,7.958269673754856,1739141217.9854665,57.349945306777954,-0.011,1739141217.9854684,57.349945306777954,-3.1017095025369446,1739141217.98547,57.349945306777954,0.4470465008797256,1739141217.9854715,57.349945306777954,0.054570742797497115,1739141217.9854727,57.349945306777954,2.0906439561754517,1739141217.9854746,57.349945306777954,0.0,1739141217.985476,57.349945306777954,0.010326153645882297,1739141217.9854777,57.349945306777954,3.125082201669212,1739141217.9854789,57.349945306777954,2.0803178025295694 +1739141218.0055573,57.36994528770447,15.883421207318793,1739141218.0055614,57.36994528770447,0.3052477149825208,1739141218.0055664,57.36994528770447,97.12852362066627,1739141218.0055718,57.36994528770447,7.958269673754856,1739141218.0055754,57.36994528770447,-0.011,1739141218.0055797,57.36994528770447,-3.1017095025369446,1739141218.005583,57.36994528770447,0.4470465008797256,1739141218.005588,57.36994528770447,0.054570742797497115,1739141218.0055919,57.36994528770447,2.0906439561754517,1739141218.0055957,57.36994528770447,0.0,1739141218.0055995,57.36994528770447,0.010326153645882297,1739141218.0056033,57.36994528770447,3.125082201669212,1739141218.005607,57.36994528770447,2.0803178025295694 +1739141218.0255418,57.38994526863098,15.654546751860345,1739141218.0255463,57.38994526863098,0.30890882085632754,1739141218.0255523,57.38994526863098,97.13928438117868,1739141218.0255575,57.38994526863098,7.943734965528633,1739141218.0255616,57.38994526863098,-0.011,1739141218.0255654,57.38994526863098,-3.100128088266792,1739141218.025568,57.38994526863098,0.43842828914279997,1739141218.0255704,57.38994526863098,0.056527695528064956,1739141218.025574,57.38994526863098,2.09786343774239,1739141218.0255766,57.38994526863098,0.0,1739141218.02558,57.38994526863098,0.021707202351557115,1739141218.025584,57.38994526863098,3.1262165868998757,1739141218.0255861,57.38994526863098,2.081575785100837 +1739141218.0454593,57.409945249557495,15.654546751860345,1739141218.0454617,57.409945249557495,0.30890882085632754,1739141218.045465,57.409945249557495,97.13928438117868,1739141218.045468,57.409945249557495,7.943734965528633,1739141218.0454698,57.409945249557495,-0.011,1739141218.0454714,57.409945249557495,-3.100128088266792,1739141218.045473,57.409945249557495,0.43842828914279997,1739141218.0454745,57.409945249557495,0.056527695528064956,1739141218.0454757,57.409945249557495,2.09786343774239,1739141218.0454776,57.409945249557495,0.0,1739141218.045479,57.409945249557495,0.016287652641552963,1739141218.0454807,57.409945249557495,3.1262165868998757,1739141218.045482,57.409945249557495,2.081575785100837 +1739141218.065618,57.42994523048401,15.654546751860345,1739141218.0656207,57.42994523048401,0.30890882085632754,1739141218.0656238,57.42994523048401,97.13928438117868,1739141218.065627,57.42994523048401,7.943734965528633,1739141218.0656288,57.42994523048401,-0.011,1739141218.0656304,57.42994523048401,-3.100128088266792,1739141218.065632,57.42994523048401,0.43842828914279997,1739141218.0656333,57.42994523048401,0.056527695528064956,1739141218.0656347,57.42994523048401,2.09786343774239,1739141218.0656366,57.42994523048401,0.0,1739141218.065638,57.42994523048401,0.016287652641552963,1739141218.0656397,57.42994523048401,3.1262165868998757,1739141218.065641,57.42994523048401,2.081575785100837 +1739141218.0861573,57.44994521141052,15.654546751860345,1739141218.0861616,57.44994521141052,0.30890882085632754,1739141218.0861666,57.44994521141052,97.13928438117868,1739141218.0861723,57.44994521141052,7.943734965528633,1739141218.0861757,57.44994521141052,-0.011,1739141218.0861797,57.44994521141052,-3.100128088266792,1739141218.0861838,57.44994521141052,0.43842828914279997,1739141218.0861874,57.44994521141052,0.056527695528064956,1739141218.086191,57.44994521141052,2.09786343774239,1739141218.0861948,57.44994521141052,0.0,1739141218.0861986,57.44994521141052,0.016287652641552963,1739141218.0862021,57.44994521141052,3.1262165868998757,1739141218.086206,57.44994521141052,2.081575785100837 +1739141218.1054845,57.469945192337036,15.654546751860345,1739141218.105487,57.469945192337036,0.30890882085632754,1739141218.1054904,57.469945192337036,97.13928438117868,1739141218.1054935,57.469945192337036,7.943734965528633,1739141218.105495,57.469945192337036,-0.011,1739141218.1054971,57.469945192337036,-3.100128088266792,1739141218.1054983,57.469945192337036,0.43842828914279997,1739141218.1055007,57.469945192337036,0.056527695528064956,1739141218.1055052,57.469945192337036,2.09786343774239,1739141218.1055083,57.469945192337036,0.0,1739141218.10551,57.469945192337036,0.016287652641552963,1739141218.1055112,57.469945192337036,3.1262165868998757,1739141218.1055124,57.469945192337036,2.081575785100837 +1739141218.1255634,57.48994517326355,15.425506253506192,1739141218.125566,57.48994517326355,0.3123126940690595,1739141218.125569,57.48994517326355,97.15005268847455,1739141218.1255758,57.48994517326355,7.927474284188007,1739141218.1255786,57.48994517326355,-0.011,1739141218.1255827,57.48994517326355,-3.098499674055104,1739141218.1255875,57.48994517326355,0.4300608797376839,1739141218.12559,57.48994517326355,0.0586319780797878,1739141218.1255922,57.48994517326355,2.1048966740741797,1739141218.1255958,57.48994517326355,0.0,1739141218.1255987,57.48994517326355,0.026219597575062894,1739141218.1256022,57.48994517326355,3.1273509721305395,1739141218.1256058,57.48994517326355,2.0834065764490943 +1739141218.145593,57.50994515419006,15.425506253506192,1739141218.1455967,57.50994515419006,0.3123126940690595,1739141218.1456025,57.50994515419006,97.15005268847455,1739141218.1456077,57.50994515419006,7.927474284188007,1739141218.1456115,57.50994515419006,-0.011,1739141218.1456141,57.50994515419006,-3.098499674055104,1739141218.1456184,57.50994515419006,0.4300608797376839,1739141218.1456225,57.50994515419006,0.0586319780797878,1739141218.145624,57.50994515419006,2.1048966740741797,1739141218.1456256,57.50994515419006,0.0,1739141218.145627,57.50994515419006,0.021490097625085358,1739141218.1456285,57.50994515419006,3.1273509721305395,1739141218.14563,57.50994515419006,2.0834065764490943 +1739141218.1654482,57.52994513511658,15.425506253506192,1739141218.165451,57.52994513511658,0.3123126940690595,1739141218.1654541,57.52994513511658,97.15005268847455,1739141218.165457,57.52994513511658,7.927474284188007,1739141218.1654587,57.52994513511658,-0.011,1739141218.1654608,57.52994513511658,-3.098499674055104,1739141218.1654623,57.52994513511658,0.4300608797376839,1739141218.165464,57.52994513511658,0.0586319780797878,1739141218.165465,57.52994513511658,2.1048966740741797,1739141218.1654668,57.52994513511658,0.0,1739141218.1654685,57.52994513511658,0.021490097625085358,1739141218.1654696,57.52994513511658,3.1273509721305395,1739141218.165471,57.52994513511658,2.0834065764490943 +1739141218.1855004,57.54994511604309,15.425506253506192,1739141218.185503,57.54994511604309,0.3123126940690595,1739141218.1855063,57.54994511604309,97.15005268847455,1739141218.1855092,57.54994511604309,7.927474284188007,1739141218.1855106,57.54994511604309,-0.011,1739141218.1855125,57.54994511604309,-3.098499674055104,1739141218.185514,57.54994511604309,0.4300608797376839,1739141218.1855154,57.54994511604309,0.0586319780797878,1739141218.1855168,57.54994511604309,2.1048966740741797,1739141218.1855187,57.54994511604309,0.0,1739141218.1855235,57.54994511604309,0.021490097625085358,1739141218.1855266,57.54994511604309,3.1273509721305395,1739141218.185528,57.54994511604309,2.0834065764490943 +1739141218.2054589,57.569945096969604,15.425506253506192,1739141218.205462,57.569945096969604,0.3123126940690595,1739141218.205465,57.569945096969604,97.15005268847455,1739141218.205468,57.569945096969604,7.927474284188007,1739141218.2054694,57.569945096969604,-0.011,1739141218.2054713,57.569945096969604,-3.098499674055104,1739141218.2054727,57.569945096969604,0.4300608797376839,1739141218.2054744,57.569945096969604,0.0586319780797878,1739141218.2054756,57.569945096969604,2.1048966740741797,1739141218.2054775,57.569945096969604,0.0,1739141218.2054791,57.569945096969604,0.021490097625085358,1739141218.2054808,57.569945096969604,3.1273509721305395,1739141218.205482,57.569945096969604,2.0834065764490943 +1739141218.2378864,57.58994507789612,15.425506253506192,1739141218.237896,57.58994507789612,0.3123126940690595,1739141218.237906,57.58994507789612,97.15005268847455,1739141218.2379153,57.58994507789612,7.927474284188007,1739141218.2379205,57.58994507789612,-0.011,1739141218.2379267,57.58994507789612,-3.098499674055104,1739141218.2379317,57.58994507789612,0.4300608797376839,1739141218.2379365,57.58994507789612,0.0586319780797878,1739141218.2379408,57.58994507789612,2.1048966740741797,1739141218.2379463,57.58994507789612,0.0,1739141218.2379515,57.58994507789612,0.021490097625085358,1739141218.237956,57.58994507789612,3.1273509721305395,1739141218.2379603,57.58994507789612,2.0834065764490943 +1739141218.2506726,57.60994505882263,15.196226320270068,1739141218.2506814,57.60994505882263,0.3154599750155107,1739141218.2506905,57.60994505882263,97.43966078729287,1739141218.2507002,57.60994505882263,7.6305344151488095,1739141218.2507052,57.60994505882263,-0.013,1739141218.2507107,57.60994505882263,-3.0982054987033916,1739141218.2507157,57.60994505882263,0.4275946860407398,1739141218.2507203,57.60994505882263,0.0572566174449793,1739141218.2507248,57.60994505882263,2.106974131752443,1739141218.2507308,57.60994505882263,0.0,1739141218.2507353,57.60994505882263,0.020784849487313396,1739141218.25074,57.60994505882263,3.1284853573612033,1739141218.2507443,57.60994505882263,2.0858534496508083 +1739141218.2773156,57.629945039749146,15.196226320270068,1739141218.2773218,57.629945039749146,0.3154599750155107,1739141218.2773292,57.629945039749146,97.43966078729287,1739141218.277336,57.629945039749146,7.6305344151488095,1739141218.2773392,57.629945039749146,-0.013,1739141218.2773433,57.629945039749146,-3.0982054987033916,1739141218.2773466,57.629945039749146,0.4275946860407398,1739141218.2773502,57.629945039749146,0.0572566174449793,1739141218.2773533,57.629945039749146,2.106974131752443,1739141218.2773573,57.629945039749146,0.0,1739141218.2773607,57.629945039749146,0.021120682101634536,1739141218.277364,57.629945039749146,3.1284853573612033,1739141218.2773676,57.629945039749146,2.0858534496508083 +1739141218.2956324,57.64994502067566,15.196226320270068,1739141218.2956371,57.64994502067566,0.3154599750155107,1739141218.2956429,57.64994502067566,97.43966078729287,1739141218.295648,57.64994502067566,7.6305344151488095,1739141218.2956505,57.64994502067566,-0.013,1739141218.2956538,57.64994502067566,-3.0982054987033916,1739141218.2956564,57.64994502067566,0.4275946860407398,1739141218.2956593,57.64994502067566,0.0572566174449793,1739141218.2956614,57.64994502067566,2.106974131752443,1739141218.2956645,57.64994502067566,0.0,1739141218.2956674,57.64994502067566,0.021120682101634536,1739141218.2956698,57.64994502067566,3.1284853573612033,1739141218.2956722,57.64994502067566,2.0858534496508083 +1739141218.316089,57.67994499206543,15.196226320270068,1739141218.3160937,57.67994499206543,0.3154599750155107,1739141218.3160992,57.67994499206543,97.43966078729287,1739141218.3161042,57.67994499206543,7.6305344151488095,1739141218.3161068,57.67994499206543,-0.013,1739141218.3161101,57.67994499206543,-3.0982054987033916,1739141218.3161128,57.67994499206543,0.4275946860407398,1739141218.316115,57.67994499206543,0.0572566174449793,1739141218.3161175,57.67994499206543,2.106974131752443,1739141218.3161204,57.67994499206543,0.0,1739141218.3161232,57.67994499206543,0.021120682101634536,1739141218.3161256,57.67994499206543,3.1284853573612033,1739141218.3161283,57.67994499206543,2.0858534496508083 +1739141218.3374434,57.68994498252869,15.196226320270068,1739141218.3374481,57.68994498252869,0.3154599750155107,1739141218.3374538,57.68994498252869,97.43966078729287,1739141218.3374596,57.68994498252869,7.6305344151488095,1739141218.3374624,57.68994498252869,-0.013,1739141218.337466,57.68994498252869,-3.0982054987033916,1739141218.3374686,57.68994498252869,0.4275946860407398,1739141218.3374712,57.68994498252869,0.0572566174449793,1739141218.3374739,57.68994498252869,2.106974131752443,1739141218.3374772,57.68994498252869,0.0,1739141218.3374798,57.68994498252869,0.021120682101634536,1739141218.3374825,57.68994498252869,3.1284853573612033,1739141218.337485,57.68994498252869,2.0858534496508083 +1739141218.3559737,57.71994495391846,14.966685230610494,1739141218.355977,57.71994495391846,0.31835040884751464,1739141218.355981,57.71994495391846,97.57042122300363,1739141218.355985,57.71994495391846,7.49285431723417,1739141218.3559866,57.71994495391846,-0.01346828536406478,1739141218.355989,57.71994495391846,-3.0972243856519173,1739141218.3559911,57.71994495391846,0.42127628572716874,1739141218.3559928,57.71994495391846,0.05780065301831626,1739141218.3559947,57.71994495391846,2.112305949031433,1739141218.3559968,57.71994495391846,0.0,1739141218.355999,57.71994495391846,0.0268945317142919,1739141218.3560007,57.71994495391846,3.129619742591867,1739141218.3560023,57.71994495391846,2.088160870887117 +1739141218.3745153,57.729944944381714,14.966685230610494,1739141218.3745177,57.729944944381714,0.31835040884751464,1739141218.3745205,57.729944944381714,97.57042122300363,1739141218.3745234,57.729944944381714,7.49285431723417,1739141218.3745246,57.729944944381714,-0.01346828536406478,1739141218.3745265,57.729944944381714,-3.0972243856519173,1739141218.3745277,57.729944944381714,0.42127628572716874,1739141218.3745291,57.729944944381714,0.05780065301831626,1739141218.3745303,57.729944944381714,2.112305949031433,1739141218.3745317,57.729944944381714,0.0,1739141218.3745332,57.729944944381714,0.024145078144316212,1739141218.3745344,57.729944944381714,3.129619742591867,1739141218.3745358,57.729944944381714,2.088160870887117 +1739141218.3936837,57.74994492530823,14.966685230610494,1739141218.3936868,57.74994492530823,0.31835040884751464,1739141218.3936899,57.74994492530823,97.57042122300363,1739141218.3936927,57.74994492530823,7.49285431723417,1739141218.393694,57.74994492530823,-0.01346828536406478,1739141218.3936958,57.74994492530823,-3.0972243856519173,1739141218.393697,57.74994492530823,0.42127628572716874,1739141218.3936982,57.74994492530823,0.05780065301831626,1739141218.3936996,57.74994492530823,2.112305949031433,1739141218.3937013,57.74994492530823,0.0,1739141218.3937027,57.74994492530823,0.024145078144316212,1739141218.3937042,57.74994492530823,3.129619742591867,1739141218.3937054,57.74994492530823,2.088160870887117 +1739141218.41546,57.76994490623474,14.966685230610494,1739141218.4154644,57.76994490623474,0.31835040884751464,1739141218.4154696,57.76994490623474,97.57042122300363,1739141218.4154754,57.76994490623474,7.49285431723417,1739141218.4154787,57.76994490623474,-0.01346828536406478,1739141218.415483,57.76994490623474,-3.0972243856519173,1739141218.4154868,57.76994490623474,0.42127628572716874,1739141218.4154904,57.76994490623474,0.05780065301831626,1739141218.415494,57.76994490623474,2.112305949031433,1739141218.4154978,57.76994490623474,0.0,1739141218.4155016,57.76994490623474,0.024145078144316212,1739141218.4155052,57.76994490623474,3.129619742591867,1739141218.415509,57.76994490623474,2.088160870887117 +1739141218.4361613,57.789944887161255,14.966685230610494,1739141218.4361649,57.789944887161255,0.31835040884751464,1739141218.4361691,57.789944887161255,97.57042122300363,1739141218.4361746,57.789944887161255,7.49285431723417,1739141218.4361775,57.789944887161255,-0.01346828536406478,1739141218.436181,57.789944887161255,-3.0972243856519173,1739141218.4361844,57.789944887161255,0.42127628572716874,1739141218.4361877,57.789944887161255,0.05780065301831626,1739141218.4361906,57.789944887161255,2.112305949031433,1739141218.4361944,57.789944887161255,0.0,1739141218.4361975,57.789944887161255,0.024145078144316212,1739141218.4362009,57.789944887161255,3.129619742591867,1739141218.436204,57.789944887161255,2.088160870887117 +1739141218.4564621,57.80994486808777,14.966685230610494,1739141218.456466,57.80994486808777,0.31835040884751464,1739141218.4564707,57.80994486808777,97.57042122300363,1739141218.4564764,57.80994486808777,7.49285431723417,1739141218.4564795,57.80994486808777,-0.01346828536406478,1739141218.4564836,57.80994486808777,-3.0972243856519173,1739141218.4564874,57.80994486808777,0.42127628572716874,1739141218.456491,57.80994486808777,0.05780065301831626,1739141218.4564946,57.80994486808777,2.112305949031433,1739141218.4564984,57.80994486808777,0.0,1739141218.456502,57.80994486808777,0.024145078144316212,1739141218.4565058,57.80994486808777,3.129619742591867,1739141218.4565094,57.80994486808777,2.088160870887117 +1739141218.4737241,57.82994484901428,14.73687095565505,1739141218.4737265,57.82994484901428,0.3209835435043802,1739141218.4737294,57.82994484901428,97.80744737253258,1739141218.4737318,57.82994484901428,7.247917831455443,1739141218.4737332,57.82994484901428,-0.015,1739141218.4737349,57.82994484901428,-3.096758830922673,1739141218.4737363,57.82994484901428,0.41713143130118113,1739141218.4737375,57.82994484901428,0.056998889327344884,1739141218.4737387,57.82994484901428,2.1158109340238314,1739141218.4737403,57.82994484901428,0.0,1739141218.4737415,57.82994484901428,0.02579830934049557,1739141218.473743,57.82994484901428,3.130754127822531,1739141218.4737442,57.82994484901428,2.090799878027165 +1739141218.4964135,57.849944829940796,14.73687095565505,1739141218.4964175,57.849944829940796,0.3209835435043802,1739141218.496422,57.849944829940796,97.80744737253258,1739141218.4964275,57.849944829940796,7.247917831455443,1739141218.4964309,57.849944829940796,-0.015,1739141218.4964345,57.849944829940796,-3.096758830922673,1739141218.4964378,57.849944829940796,0.41713143130118113,1739141218.4964414,57.849944829940796,0.056998889327344884,1739141218.4964447,57.849944829940796,2.1158109340238314,1739141218.4964483,57.849944829940796,0.0,1739141218.4964516,57.849944829940796,0.02501105599666653,1739141218.496455,57.849944829940796,3.130754127822531,1739141218.4964583,57.849944829940796,2.090799878027165 +1739141218.5157788,57.86994481086731,14.73687095565505,1739141218.515783,57.86994481086731,0.3209835435043802,1739141218.5157878,57.86994481086731,97.80744737253258,1739141218.5157921,57.86994481086731,7.247917831455443,1739141218.5157945,57.86994481086731,-0.015,1739141218.5157976,57.86994481086731,-3.096758830922673,1739141218.5158,57.86994481086731,0.41713143130118113,1739141218.5158024,57.86994481086731,0.056998889327344884,1739141218.5158048,57.86994481086731,2.1158109340238314,1739141218.5158072,57.86994481086731,0.0,1739141218.5158098,57.86994481086731,0.02501105599666653,1739141218.5158124,57.86994481086731,3.130754127822531,1739141218.515815,57.86994481086731,2.090799878027165 +1739141218.5362434,57.88994479179382,14.73687095565505,1739141218.5362473,57.88994479179382,0.3209835435043802,1739141218.536252,57.88994479179382,97.80744737253258,1739141218.5362563,57.88994479179382,7.247917831455443,1739141218.5362585,57.88994479179382,-0.015,1739141218.5362613,57.88994479179382,-3.096758830922673,1739141218.536264,57.88994479179382,0.41713143130118113,1739141218.5362663,57.88994479179382,0.056998889327344884,1739141218.5362685,57.88994479179382,2.1158109340238314,1739141218.536271,57.88994479179382,0.0,1739141218.5362737,57.88994479179382,0.02501105599666653,1739141218.5362759,57.88994479179382,3.130754127822531,1739141218.5362782,57.88994479179382,2.090799878027165 +1739141218.5551052,57.90994477272034,14.73687095565505,1739141218.5551097,57.90994477272034,0.3209835435043802,1739141218.5551143,57.90994477272034,97.80744737253258,1739141218.5551188,57.90994477272034,7.247917831455443,1739141218.5551214,57.90994477272034,-0.015,1739141218.5551245,57.90994477272034,-3.096758830922673,1739141218.5551276,57.90994477272034,0.41713143130118113,1739141218.55513,57.90994477272034,0.056998889327344884,1739141218.5551324,57.90994477272034,2.1158109340238314,1739141218.555135,57.90994477272034,0.0,1739141218.5551376,57.90994477272034,0.02501105599666653,1739141218.55514,57.90994477272034,3.130754127822531,1739141218.5551424,57.90994477272034,2.090799878027165 +1739141218.5764802,57.93994474411011,14.50675782962606,1739141218.5764844,57.93994474411011,0.32335903341046013,1739141218.576489,57.93994474411011,98.03922941414942,1739141218.5764935,57.93994474411011,7.007910514152594,1739141218.5764961,57.93994474411011,-0.016,1739141218.5764995,57.93994474411011,-3.0963686832407222,1739141218.576502,57.93994474411011,0.41211178084744643,1739141218.5765045,57.93994474411011,0.05616269794685726,1739141218.576507,57.93994474411011,2.1200634543542782,1739141218.57651,57.93994474411011,0.0,1739141218.5765128,57.93994474411011,0.027892372418394776,1739141218.5765154,57.93994474411011,3.1318885130531946,1739141218.5765178,57.93994474411011,2.0935431380602036 +1739141218.5958662,57.949944734573364,14.50675782962606,1739141218.5958703,57.949944734573364,0.32335903341046013,1739141218.595875,57.949944734573364,98.03922941414942,1739141218.5958805,57.949944734573364,7.007910514152594,1739141218.5958836,57.949944734573364,-0.016,1739141218.5958874,57.949944734573364,-3.0963686832407222,1739141218.5958908,57.949944734573364,0.41211178084744643,1739141218.595894,57.949944734573364,0.05616269794685726,1739141218.5958977,57.949944734573364,2.1200634543542782,1739141218.5959013,57.949944734573364,0.0,1739141218.5959046,57.949944734573364,0.026520316294074586,1739141218.5959084,57.949944734573364,3.1318885130531946,1739141218.5959117,57.949944734573364,2.0935431380602036 +1739141218.615626,57.96994471549988,14.50675782962606,1739141218.6156316,57.96994471549988,0.32335903341046013,1739141218.615637,57.96994471549988,98.03922941414942,1739141218.6156428,57.96994471549988,7.007910514152594,1739141218.615646,57.96994471549988,-0.016,1739141218.6156507,57.96994471549988,-3.0963686832407222,1739141218.6156547,57.96994471549988,0.41211178084744643,1739141218.6156569,57.96994471549988,0.05616269794685726,1739141218.6156604,57.96994471549988,2.1200634543542782,1739141218.6156635,57.96994471549988,0.0,1739141218.6156666,57.96994471549988,0.026520316294074586,1739141218.6156702,57.96994471549988,3.1318885130531946,1739141218.615674,57.96994471549988,2.0935431380602036 +1739141218.6352777,57.98994469642639,14.50675782962606,1739141218.6352823,57.98994469642639,0.32335903341046013,1739141218.6352868,57.98994469642639,98.03922941414942,1739141218.635292,57.98994469642639,7.007910514152594,1739141218.6352952,57.98994469642639,-0.016,1739141218.6352987,57.98994469642639,-3.0963686832407222,1739141218.6353023,57.98994469642639,0.41211178084744643,1739141218.6353056,57.98994469642639,0.05616269794685726,1739141218.635309,57.98994469642639,2.1200634543542782,1739141218.6353126,57.98994469642639,0.0,1739141218.6353161,57.98994469642639,0.026520316294074586,1739141218.6353197,57.98994469642639,3.1318885130531946,1739141218.635323,57.98994469642639,2.0935431380602036 +1739141218.6540878,58.009944677352905,14.50675782962606,1739141218.65409,58.009944677352905,0.32335903341046013,1739141218.6540926,58.009944677352905,98.03922941414942,1739141218.6540952,58.009944677352905,7.007910514152594,1739141218.6540966,58.009944677352905,-0.016,1739141218.6540985,58.009944677352905,-3.0963686832407222,1739141218.6540997,58.009944677352905,0.41211178084744643,1739141218.654101,58.009944677352905,0.05616269794685726,1739141218.654102,58.009944677352905,2.1200634543542782,1739141218.6541035,58.009944677352905,0.0,1739141218.6541052,58.009944677352905,0.026520316294074586,1739141218.6541064,58.009944677352905,3.1318885130531946,1739141218.6541076,58.009944677352905,2.0935431380602036 +1739141218.673638,58.02994465827942,14.50675782962606,1739141218.6736405,58.02994465827942,0.32335903341046013,1739141218.6736434,58.02994465827942,98.03922941414942,1739141218.673646,58.02994465827942,7.007910514152594,1739141218.6736474,58.02994465827942,-0.016,1739141218.6736488,58.02994465827942,-3.0963686832407222,1739141218.6736505,58.02994465827942,0.41211178084744643,1739141218.6736517,58.02994465827942,0.05616269794685726,1739141218.6736526,58.02994465827942,2.1200634543542782,1739141218.6736543,58.02994465827942,0.0,1739141218.6736555,58.02994465827942,0.026520316294074586,1739141218.673657,58.02994465827942,3.1318885130531946,1739141218.6736581,58.02994465827942,2.0935431380602036 +1739141218.695066,58.04994463920593,14.276332887220452,1739141218.6950686,58.04994463920593,0.3254763250917252,1739141218.6950715,58.04994463920593,98.17049879952366,1739141218.6950743,58.04994463920593,6.867945559765835,1739141218.6950755,58.04994463920593,-0.016991404002128774,1739141218.6950772,58.04994463920593,-3.0953985114437255,1739141218.6950786,58.04994463920593,0.40594244314423156,1739141218.69508,58.04994463920593,0.05667605049212911,1739141218.695081,58.04994463920593,2.1253016699210288,1739141218.6950827,58.04994463920593,0.0,1739141218.6950843,58.04994463920593,0.030984136484238974,1739141218.6950855,58.04994463920593,3.1330228982838584,1739141218.6950872,58.04994463920593,2.0964431631606177 +1739141218.7138278,58.069944620132446,14.276332887220452,1739141218.71383,58.069944620132446,0.3254763250917252,1739141218.7138324,58.069944620132446,98.17049879952366,1739141218.7138352,58.069944620132446,6.867945559765835,1739141218.7138364,58.069944620132446,-0.016991404002128774,1739141218.7138379,58.069944620132446,-3.0953985114437255,1739141218.7138393,58.069944620132446,0.40594244314423156,1739141218.7138405,58.069944620132446,0.05667605049212911,1739141218.7138417,58.069944620132446,2.1253016699210288,1739141218.713843,58.069944620132446,0.0,1739141218.7138448,58.069944620132446,0.028858506760411018,1739141218.713846,58.069944620132446,3.1330228982838584,1739141218.7138474,58.069944620132446,2.0964431631606177 +1739141218.7336488,58.08994460105896,14.276332887220452,1739141218.7336514,58.08994460105896,0.3254763250917252,1739141218.7336545,58.08994460105896,98.17049879952366,1739141218.7336571,58.08994460105896,6.867945559765835,1739141218.7336583,58.08994460105896,-0.016991404002128774,1739141218.73366,58.08994460105896,-3.0953985114437255,1739141218.7336612,58.08994460105896,0.40594244314423156,1739141218.7336624,58.08994460105896,0.05667605049212911,1739141218.7336636,58.08994460105896,2.1253016699210288,1739141218.7336652,58.08994460105896,0.0,1739141218.7336667,58.08994460105896,0.028858506760411018,1739141218.7336676,58.08994460105896,3.1330228982838584,1739141218.7336688,58.08994460105896,2.0964431631606177 +1739141218.7603693,58.109944581985474,14.276332887220452,1739141218.7603784,58.109944581985474,0.3254763250917252,1739141218.7603884,58.109944581985474,98.17049879952366,1739141218.760398,58.109944581985474,6.867945559765835,1739141218.7604027,58.109944581985474,-0.016991404002128774,1739141218.7604084,58.109944581985474,-3.0953985114437255,1739141218.7604132,58.109944581985474,0.40594244314423156,1739141218.7604177,58.109944581985474,0.05667605049212911,1739141218.7604222,58.109944581985474,2.1253016699210288,1739141218.7604282,58.109944581985474,0.0,1739141218.7604334,58.109944581985474,0.028858506760411018,1739141218.7604375,58.109944581985474,3.1330228982838584,1739141218.760442,58.109944581985474,2.0964431631606177 +1739141218.8111308,58.15994453430176,14.045572344152724,1739141218.8111403,58.15994453430176,0.32733490676333954,1739141218.8111508,58.15994453430176,98.33634060769633,1739141218.811161,58.15994453430176,6.692579572359909,1739141218.811166,58.15994453430176,-0.018,1739141218.8111722,58.15994453430176,-3.094661921085124,1739141218.8111775,58.15994453430176,0.3999970795980668,1739141218.8111823,58.15994453430176,0.05668670174898034,1739141218.8111868,58.15994453430176,2.1303619610193505,1739141218.8111928,58.15994453430176,0.0,1739141218.811198,58.15994453430176,0.032455305430568404,1739141218.8112025,58.15994453430176,3.134157283514522,1739141218.811207,58.15994453430176,2.099619417715885 +1739141218.8431444,58.18994450569153,14.045572344152724,1739141218.8431468,58.18994450569153,0.32733490676333954,1739141218.84315,58.18994450569153,98.33634060769633,1739141218.8431525,58.18994450569153,6.692579572359909,1739141218.843154,58.18994450569153,-0.018,1739141218.8431556,58.18994450569153,-3.094661921085124,1739141218.843157,58.18994450569153,0.3999970795980668,1739141218.8431582,58.18994450569153,0.05668670174898034,1739141218.8431594,58.18994450569153,2.1303619610193505,1739141218.843161,58.18994450569153,0.0,1739141218.8431623,58.18994450569153,0.030742543303465375,1739141218.8431637,58.18994450569153,3.134157283514522,1739141218.843165,58.18994450569153,2.099619417715885 +1739141218.8618484,58.20994448661804,14.045572344152724,1739141218.8618517,58.20994448661804,0.32733490676333954,1739141218.8618548,58.20994448661804,98.33634060769633,1739141218.8618577,58.20994448661804,6.692579572359909,1739141218.861859,58.20994448661804,-0.018,1739141218.8618605,58.20994448661804,-3.094661921085124,1739141218.861862,58.20994448661804,0.3999970795980668,1739141218.8618631,58.20994448661804,0.05668670174898034,1739141218.8618646,58.20994448661804,2.1303619610193505,1739141218.861866,58.20994448661804,0.0,1739141218.8618677,58.20994448661804,0.030742543303465375,1739141218.8618717,58.20994448661804,3.134157283514522,1739141218.861876,58.20994448661804,2.099619417715885 +1739141218.882387,58.229944467544556,14.045572344152724,1739141218.8823893,58.229944467544556,0.32733490676333954,1739141218.8823922,58.229944467544556,98.33634060769633,1739141218.8823943,58.229944467544556,6.692579572359909,1739141218.8823957,58.229944467544556,-0.018,1739141218.8823972,58.229944467544556,-3.094661921085124,1739141218.8823986,58.229944467544556,0.3999970795980668,1739141218.8824,58.229944467544556,0.05668670174898034,1739141218.882401,58.229944467544556,2.1303619610193505,1739141218.8824027,58.229944467544556,0.0,1739141218.882404,58.229944467544556,0.030742543303465375,1739141218.8824053,58.229944467544556,3.134157283514522,1739141218.8824065,58.229944467544556,2.099619417715885 +1739141218.9019146,58.24994444847107,14.045572344152724,1739141218.9019172,58.24994444847107,0.32733490676333954,1739141218.90192,58.24994444847107,98.33634060769633,1739141218.9019232,58.24994444847107,6.692579572359909,1739141218.9019244,58.24994444847107,-0.018,1739141218.901926,58.24994444847107,-3.094661921085124,1739141218.9019275,58.24994444847107,0.3999970795980668,1739141218.9019287,58.24994444847107,0.05668670174898034,1739141218.90193,58.24994444847107,2.1303619610193505,1739141218.9019315,58.24994444847107,0.0,1739141218.9019327,58.24994444847107,0.030742543303465375,1739141218.9019341,58.24994444847107,3.134157283514522,1739141218.901935,58.24994444847107,2.099619417715885 +1739141218.923079,58.26994442939758,13.814448180246224,1739141218.923084,58.26994442939758,0.32893421601181405,1739141218.9230905,58.26994442939758,98.64218719494662,1739141218.9230955,58.26994442939758,6.376508714941417,1739141218.9230971,58.26994442939758,-0.01949528967646836,1739141218.9230988,58.26994442939758,-3.094781978046334,1739141218.9231002,58.26994442939758,0.39528862269442566,1739141218.9231017,58.26994442939758,0.05474822562375779,1739141218.923103,58.26994442939758,2.1343780287216103,1739141218.9231045,58.26994442939758,0.0,1739141218.923106,58.26994442939758,0.03189453879701898,1739141218.9231074,58.26994442939758,3.135291668745186,1739141218.9231086,58.26994442939758,2.1030320594812704 +1739141218.9433186,58.2899444103241,13.814448180246224,1739141218.9433222,58.2899444103241,0.32893421601181405,1739141218.9433265,58.2899444103241,98.64218719494662,1739141218.9433312,58.2899444103241,6.376508714941417,1739141218.943334,58.2899444103241,-0.01949528967646836,1739141218.9433377,58.2899444103241,-3.094781978046334,1739141218.9433408,58.2899444103241,0.39528862269442566,1739141218.943344,58.2899444103241,0.05474822562375779,1739141218.9433472,58.2899444103241,2.1343780287216103,1739141218.9433506,58.2899444103241,0.0,1739141218.9433544,58.2899444103241,0.031345969240339944,1739141218.9433575,58.2899444103241,3.135291668745186,1739141218.9433606,58.2899444103241,2.1030320594812704 +1739141218.9634886,58.30994439125061,13.814448180246224,1739141218.9634922,58.30994439125061,0.32893421601181405,1739141218.9634967,58.30994439125061,98.64218719494662,1739141218.9635022,58.30994439125061,6.376508714941417,1739141218.9635048,58.30994439125061,-0.01949528967646836,1739141218.9635088,58.30994439125061,-3.094781978046334,1739141218.9635122,58.30994439125061,0.39528862269442566,1739141218.9635153,58.30994439125061,0.05474822562375779,1739141218.9635186,58.30994439125061,2.1343780287216103,1739141218.9635222,58.30994439125061,0.0,1739141218.9635258,58.30994439125061,0.031345969240339944,1739141218.963529,58.30994439125061,3.135291668745186,1739141218.9635324,58.30994439125061,2.1030320594812704 +1739141218.983906,58.329944372177124,13.814448180246224,1739141218.9839098,58.329944372177124,0.32893421601181405,1739141218.9839149,58.329944372177124,98.64218719494662,1739141218.9839199,58.329944372177124,6.376508714941417,1739141218.983923,58.329944372177124,-0.01949528967646836,1739141218.9839268,58.329944372177124,-3.094781978046334,1739141218.98393,58.329944372177124,0.39528862269442566,1739141218.9839334,58.329944372177124,0.05474822562375779,1739141218.9839368,58.329944372177124,2.1343780287216103,1739141218.9839404,58.329944372177124,0.0,1739141218.9839437,58.329944372177124,0.031345969240339944,1739141218.983947,58.329944372177124,3.135291668745186,1739141218.9839506,58.329944372177124,2.1030320594812704 +1739141219.0035398,58.34994435310364,13.814448180246224,1739141219.0035434,58.34994435310364,0.32893421601181405,1739141219.003548,58.34994435310364,98.64218719494662,1739141219.003553,58.34994435310364,6.376508714941417,1739141219.003556,58.34994435310364,-0.01949528967646836,1739141219.0035596,58.34994435310364,-3.094781978046334,1739141219.0035632,58.34994435310364,0.39528862269442566,1739141219.0035665,58.34994435310364,0.05474822562375779,1739141219.0035698,58.34994435310364,2.1343780287216103,1739141219.0035734,58.34994435310364,0.0,1739141219.0035768,58.34994435310364,0.031345969240339944,1739141219.00358,58.34994435310364,3.135291668745186,1739141219.0035834,58.34994435310364,2.1030320594812704 +1739141219.0236402,58.36994433403015,13.582947911518108,1739141219.0236437,58.36994433403015,0.33027350688786683,1739141219.0236483,58.36994433403015,98.87765622665653,1739141219.0236537,58.36994433403015,6.130788164357663,1739141219.0236566,58.36994433403015,-0.021,1739141219.0236607,58.36994433403015,-3.094490377331982,1739141219.0236638,58.36994433403015,0.3897709728721319,1739141219.023667,58.36994433403015,0.05377692776343914,1739141219.0236704,58.36994433403015,2.139093931167314,1739141219.023674,58.36994433403015,0.0,1739141219.0236776,58.36994433403015,0.03382095707560498,1739141219.023681,58.36994433403015,3.1364260539758497,1739141219.0236843,58.36994433403015,2.1064515403162947 +1739141219.0417588,58.389944314956665,13.582947911518108,1739141219.0417614,58.389944314956665,0.33027350688786683,1739141219.0417643,58.389944314956665,98.87765622665653,1739141219.041767,58.389944314956665,6.130788164357663,1739141219.0417686,58.389944314956665,-0.021,1739141219.0417702,58.389944314956665,-3.094490377331982,1739141219.0417714,58.389944314956665,0.3897709728721319,1739141219.0417728,58.389944314956665,0.05377692776343914,1739141219.041774,58.389944314956665,2.139093931167314,1739141219.041776,58.389944314956665,0.0,1739141219.0417774,58.389944314956665,0.032642390851019165,1739141219.0417788,58.389944314956665,3.1364260539758497,1739141219.04178,58.389944314956665,2.1064515403162947 +1739141219.0617476,58.40994429588318,13.582947911518108,1739141219.0617497,58.40994429588318,0.33027350688786683,1739141219.0617528,58.40994429588318,98.87765622665653,1739141219.0617554,58.40994429588318,6.130788164357663,1739141219.0617568,58.40994429588318,-0.021,1739141219.0617585,58.40994429588318,-3.094490377331982,1739141219.06176,58.40994429588318,0.3897709728721319,1739141219.0617614,58.40994429588318,0.05377692776343914,1739141219.0617623,58.40994429588318,2.139093931167314,1739141219.0617638,58.40994429588318,0.0,1739141219.0617652,58.40994429588318,0.032642390851019165,1739141219.0617664,58.40994429588318,3.1364260539758497,1739141219.0617676,58.40994429588318,2.1064515403162947 +1739141219.0817678,58.42994427680969,13.582947911518108,1739141219.08177,58.42994427680969,0.33027350688786683,1739141219.081773,58.42994427680969,98.87765622665653,1739141219.081776,58.42994427680969,6.130788164357663,1739141219.081777,58.42994427680969,-0.021,1739141219.081779,58.42994427680969,-3.094490377331982,1739141219.0817802,58.42994427680969,0.3897709728721319,1739141219.0817814,58.42994427680969,0.05377692776343914,1739141219.0817828,58.42994427680969,2.139093931167314,1739141219.0817845,58.42994427680969,0.0,1739141219.081786,58.42994427680969,0.032642390851019165,1739141219.081787,58.42994427680969,3.1364260539758497,1739141219.081788,58.42994427680969,2.1064515403162947 +1739141219.101751,58.449944257736206,13.582947911518108,1739141219.1017537,58.449944257736206,0.33027350688786683,1739141219.1017563,58.449944257736206,98.87765622665653,1739141219.1017592,58.449944257736206,6.130788164357663,1739141219.1017609,58.449944257736206,-0.021,1739141219.1017628,58.449944257736206,-3.094490377331982,1739141219.1017642,58.449944257736206,0.3897709728721319,1739141219.1017656,58.449944257736206,0.05377692776343914,1739141219.1017666,58.449944257736206,2.139093931167314,1739141219.1017685,58.449944257736206,0.0,1739141219.1017697,58.449944257736206,0.032642390851019165,1739141219.101771,58.449944257736206,3.1364260539758497,1739141219.1017723,58.449944257736206,2.1064515403162947 +1739141219.1217425,58.46994423866272,13.582947911518108,1739141219.121745,58.46994423866272,0.33027350688786683,1739141219.1217482,58.46994423866272,98.87765622665653,1739141219.121751,58.46994423866272,6.130788164357663,1739141219.1217523,58.46994423866272,-0.021,1739141219.1217542,58.46994423866272,-3.094490377331982,1739141219.1217554,58.46994423866272,0.3897709728721319,1739141219.1217566,58.46994423866272,0.05377692776343914,1739141219.121758,58.46994423866272,2.139093931167314,1739141219.1217594,58.46994423866272,0.0,1739141219.121761,58.46994423866272,0.032642390851019165,1739141219.1217623,58.46994423866272,3.1364260539758497,1739141219.121764,58.46994423866272,2.1064515403162947 +1739141219.1415665,58.48994421958923,13.35105949404631,1739141219.1415687,58.48994421958923,0.3313519836849368,1739141219.1415715,58.48994421958923,99.11415000042413,1739141219.1415744,58.48994421958923,5.883506429856102,1739141219.141576,58.48994421958923,-0.022,1739141219.1415777,58.48994421958923,-3.094309612763461,1739141219.1415792,58.48994421958923,0.3834598044370044,1739141219.1415806,58.48994421958923,0.05268760637495981,1739141219.1415818,58.48994421958923,2.144500825899768,1739141219.1415834,58.48994421958923,0.0,1739141219.1415849,58.48994421958923,0.03609663401342698,1739141219.1415858,58.48994421958923,3.1375604392065135,1739141219.1415873,58.48994421958923,2.1100490704044144 +1739141219.1618352,58.50994420051575,13.35105949404631,1739141219.1618376,58.50994420051575,0.3313519836849368,1739141219.1618404,58.50994420051575,99.11415000042413,1739141219.1618433,58.50994420051575,5.883506429856102,1739141219.1618445,58.50994420051575,-0.022,1739141219.1618462,58.50994420051575,-3.094309612763461,1739141219.1618478,58.50994420051575,0.3834598044370044,1739141219.161849,58.50994420051575,0.05268760637495981,1739141219.1618505,58.50994420051575,2.144500825899768,1739141219.161852,58.50994420051575,0.0,1739141219.1618536,58.50994420051575,0.03445175549535362,1739141219.1618547,58.50994420051575,3.1375604392065135,1739141219.161856,58.50994420051575,2.1100490704044144 +1739141219.1817534,58.52994418144226,13.35105949404631,1739141219.1817555,58.52994418144226,0.3313519836849368,1739141219.1817584,58.52994418144226,99.11415000042413,1739141219.1817613,58.52994418144226,5.883506429856102,1739141219.1817625,58.52994418144226,-0.022,1739141219.1817644,58.52994418144226,-3.094309612763461,1739141219.1817656,58.52994418144226,0.3834598044370044,1739141219.181767,58.52994418144226,0.05268760637495981,1739141219.1817682,58.52994418144226,2.144500825899768,1739141219.18177,58.52994418144226,0.0,1739141219.1817713,58.52994418144226,0.03445175549535362,1739141219.1817725,58.52994418144226,3.1375604392065135,1739141219.181774,58.52994418144226,2.1100490704044144 +1739141219.2017617,58.549944162368774,13.35105949404631,1739141219.201764,58.549944162368774,0.3313519836849368,1739141219.2017672,58.549944162368774,99.11415000042413,1739141219.2017698,58.549944162368774,5.883506429856102,1739141219.201771,58.549944162368774,-0.022,1739141219.2017727,58.549944162368774,-3.094309612763461,1739141219.2017741,58.549944162368774,0.3834598044370044,1739141219.2017753,58.549944162368774,0.05268760637495981,1739141219.2017767,58.549944162368774,2.144500825899768,1739141219.2017782,58.549944162368774,0.0,1739141219.2017796,58.549944162368774,0.03445175549535362,1739141219.2017808,58.549944162368774,3.1375604392065135,1739141219.201782,58.549944162368774,2.1100490704044144 +1739141219.2234805,58.56994414329529,13.35105949404631,1739141219.2234843,58.56994414329529,0.3313519836849368,1739141219.2234888,58.56994414329529,99.11415000042413,1739141219.2234938,58.56994414329529,5.883506429856102,1739141219.223497,58.56994414329529,-0.022,1739141219.2235007,58.56994414329529,-3.094309612763461,1739141219.223504,58.56994414329529,0.3834598044370044,1739141219.2235074,58.56994414329529,0.05268760637495981,1739141219.2235107,58.56994414329529,2.144500825899768,1739141219.2235143,58.56994414329529,0.0,1739141219.2235177,58.56994414329529,0.03445175549535362,1739141219.2235212,58.56994414329529,3.1375604392065135,1739141219.2235246,58.56994414329529,2.1100490704044144 +1739141219.2435272,58.5899441242218,13.11876478067137,1739141219.2435308,58.5899441242218,0.33216883169333933,1739141219.2435353,58.5899441242218,99.45369607330848,1739141219.2435405,58.5899441242218,5.532564963236836,1739141219.2435436,58.5899441242218,-0.023,1739141219.2435474,58.5899441242218,-3.094809061995738,1739141219.2435508,58.5899441242218,0.3771508206656603,1739141219.243554,58.5899441242218,0.05021532413554798,1739141219.2435575,58.5899441242218,2.149919508663635,1739141219.243561,58.5899441242218,0.0,1739141219.2435644,58.5899441242218,0.03754189905899651,1739141219.2435677,58.5899441242218,3.1386948244371773,1739141219.243571,58.5899441242218,2.113849107274784 +1739141219.263499,58.609944105148315,13.11876478067137,1739141219.2635026,58.609944105148315,0.33216883169333933,1739141219.2635071,58.609944105148315,99.45369607330848,1739141219.2635126,58.609944105148315,5.532564963236836,1739141219.2635157,58.609944105148315,-0.023,1739141219.2635195,58.609944105148315,-3.094809061995738,1739141219.2635229,58.609944105148315,0.3771508206656603,1739141219.2635262,58.609944105148315,0.05021532413554798,1739141219.2635295,58.609944105148315,2.149919508663635,1739141219.263533,58.609944105148315,0.0,1739141219.2635367,58.609944105148315,0.03607040138885109,1739141219.26354,58.609944105148315,3.1386948244371773,1739141219.2635434,58.609944105148315,2.113849107274784 +1739141219.2835197,58.62994408607483,13.11876478067137,1739141219.2835233,58.62994408607483,0.33216883169333933,1739141219.283528,58.62994408607483,99.45369607330848,1739141219.2835333,58.62994408607483,5.532564963236836,1739141219.2835364,58.62994408607483,-0.023,1739141219.2835402,58.62994408607483,-3.094809061995738,1739141219.2835436,58.62994408607483,0.3771508206656603,1739141219.283547,58.62994408607483,0.05021532413554798,1739141219.2835505,58.62994408607483,2.149919508663635,1739141219.283554,58.62994408607483,0.0,1739141219.2835574,58.62994408607483,0.03607040138885109,1739141219.2835608,58.62994408607483,3.1386948244371773,1739141219.283564,58.62994408607483,2.113849107274784 +1739141219.303507,58.64994406700134,13.11876478067137,1739141219.3035107,58.64994406700134,0.33216883169333933,1739141219.3035154,58.64994406700134,99.45369607330848,1739141219.3035204,58.64994406700134,5.532564963236836,1739141219.3035235,58.64994406700134,-0.023,1739141219.3035274,58.64994406700134,-3.094809061995738,1739141219.3035307,58.64994406700134,0.3771508206656603,1739141219.303534,58.64994406700134,0.05021532413554798,1739141219.3035374,58.64994406700134,2.149919508663635,1739141219.303541,58.64994406700134,0.0,1739141219.3035445,58.64994406700134,0.03607040138885109,1739141219.3035479,58.64994406700134,3.1386948244371773,1739141219.3035512,58.64994406700134,2.113849107274784 +1739141219.323465,58.669944047927856,13.11876478067137,1739141219.323468,58.669944047927856,0.33216883169333933,1739141219.323471,58.669944047927856,99.45369607330848,1739141219.3234737,58.669944047927856,5.532564963236836,1739141219.3234751,58.669944047927856,-0.023,1739141219.323477,58.669944047927856,-3.094809061995738,1739141219.3234782,58.669944047927856,0.3771508206656603,1739141219.32348,58.669944047927856,0.05021532413554798,1739141219.323481,58.669944047927856,2.149919508663635,1739141219.3234825,58.669944047927856,0.0,1739141219.3234842,58.669944047927856,0.03607040138885109,1739141219.3234854,58.669944047927856,3.1386948244371773,1739141219.3234868,58.669944047927856,2.113849107274784 +1739141219.353536,58.68994402885437,13.11876478067137,1739141219.3535557,58.68994402885437,0.33216883169333933,1739141219.3535755,58.68994402885437,99.45369607330848,1739141219.3535988,58.68994402885437,5.532564963236836,1739141219.3536112,58.68994402885437,-0.023,1739141219.3536181,58.68994402885437,-3.094809061995738,1739141219.3536234,58.68994402885437,0.3771508206656603,1739141219.353628,58.68994402885437,0.05021532413554798,1739141219.3536327,58.68994402885437,2.149919508663635,1739141219.353639,58.68994402885437,0.0,1739141219.3536441,58.68994402885437,0.03607040138885109,1739141219.3536491,58.68994402885437,3.1386948244371773,1739141219.353654,58.68994402885437,2.113849107274784 +1739141219.3688917,58.709944009780884,12.886041427702981,1739141219.3689075,58.709944009780884,0.33272318523974675,1739141219.3689272,58.709944009780884,99.51726632889796,1739141219.3689454,58.709944009780884,5.457058739480545,1739141219.3689563,58.709944009780884,-0.023,1739141219.3689682,58.709944009780884,-3.0937460362936693,1739141219.368977,58.709944009780884,0.36882321971550075,1739141219.368985,58.709944009780884,0.05120165528220843,1739141219.3689935,58.709944009780884,2.157092918186362,1739141219.3690038,58.709944009780884,0.0,1739141219.3690128,58.709944009780884,0.04216947895950423,1739141219.369021,58.709944009780884,3.139829209667841,1739141219.36903,58.709944009780884,2.1178277633303866 +1739141219.4020224,58.739943981170654,12.886041427702981,1739141219.4020286,58.739943981170654,0.33272318523974675,1739141219.402035,58.739943981170654,99.51726632889796,1739141219.4020412,58.739943981170654,5.457058739480545,1739141219.4020438,58.739943981170654,-0.023,1739141219.4020472,58.739943981170654,-3.0937460362936693,1739141219.4020505,58.739943981170654,0.36882321971550075,1739141219.402053,58.739943981170654,0.05120165528220843,1739141219.4020557,58.739943981170654,2.157092918186362,1739141219.4020593,58.739943981170654,0.0,1739141219.4020622,58.739943981170654,0.03926515485597548,1739141219.402065,58.739943981170654,3.139829209667841,1739141219.402068,58.739943981170654,2.1178277633303866 +1739141219.4243507,58.769943952560425,12.886041427702981,1739141219.4243555,58.769943952560425,0.33272318523974675,1739141219.4243612,58.769943952560425,99.51726632889796,1739141219.4243665,58.769943952560425,5.457058739480545,1739141219.424369,58.769943952560425,-0.023,1739141219.4243724,58.769943952560425,-3.0937460362936693,1739141219.424375,58.769943952560425,0.36882321971550075,1739141219.4243777,58.769943952560425,0.05120165528220843,1739141219.4243798,58.769943952560425,2.157092918186362,1739141219.424383,58.769943952560425,0.0,1739141219.4243858,58.769943952560425,0.03926515485597548,1739141219.4243884,58.769943952560425,3.139829209667841,1739141219.4243906,58.769943952560425,2.1178277633303866 +1739141219.4467275,58.78994393348694,12.886041427702981,1739141219.4467328,58.78994393348694,0.33272318523974675,1739141219.4467387,58.78994393348694,99.51726632889796,1739141219.446744,58.78994393348694,5.457058739480545,1739141219.4467466,58.78994393348694,-0.023,1739141219.4467504,58.78994393348694,-3.0937460362936693,1739141219.446753,58.78994393348694,0.36882321971550075,1739141219.446756,58.78994393348694,0.05120165528220843,1739141219.446758,58.78994393348694,2.157092918186362,1739141219.4467618,58.78994393348694,0.0,1739141219.4467645,58.78994393348694,0.03926515485597548,1739141219.4467673,58.78994393348694,3.139829209667841,1739141219.4467697,58.78994393348694,2.1178277633303866 +1739141219.4667308,58.80994391441345,12.652860067733865,1739141219.4667382,58.80994391441345,0.33301410675350684,1739141219.466744,58.80994391441345,99.90367174448694,1739141219.4667501,58.80994391441345,5.057521301716508,1739141219.4667528,58.80994391441345,-0.024,1739141219.466756,58.80994391441345,-3.09462285599644,1739141219.4667602,58.80994391441345,0.36179194966454487,1739141219.4667642,58.80994391441345,0.04805407248433548,1739141219.4667685,58.80994391441345,2.163168298843093,1739141219.4667735,58.80994391441345,0.0,1739141219.4667773,58.80994391441345,0.04250303554653803,1739141219.4667811,58.80994391441345,3.140963594898505,1739141219.466785,58.80994391441345,2.122207112014663 +1739141219.4871392,58.829943895339966,12.652860067733865,1739141219.487145,58.829943895339966,0.33301410675350684,1739141219.487149,58.829943895339966,99.90367174448694,1739141219.4871526,58.829943895339966,5.057521301716508,1739141219.4871547,58.829943895339966,-0.024,1739141219.4871573,58.829943895339966,-3.09462285599644,1739141219.4871593,58.829943895339966,0.36179194966454487,1739141219.4871635,58.829943895339966,0.04805407248433548,1739141219.4871683,58.829943895339966,2.163168298843093,1739141219.487172,58.829943895339966,0.0,1739141219.4871757,58.829943895339966,0.04096118682843031,1739141219.4871793,58.829943895339966,3.140963594898505,1739141219.4871829,58.829943895339966,2.122207112014663 +1739141219.5066404,58.84994387626648,12.652860067733865,1739141219.5066442,58.84994387626648,0.33301410675350684,1739141219.5066488,58.84994387626648,99.90367174448694,1739141219.5066543,58.84994387626648,5.057521301716508,1739141219.5066574,58.84994387626648,-0.024,1739141219.5066612,58.84994387626648,-3.09462285599644,1739141219.5066648,58.84994387626648,0.36179194966454487,1739141219.5066683,58.84994387626648,0.04805407248433548,1739141219.5066717,58.84994387626648,2.163168298843093,1739141219.5066755,58.84994387626648,0.0,1739141219.506679,58.84994387626648,0.04096118682843031,1739141219.5066824,58.84994387626648,3.140963594898505,1739141219.506686,58.84994387626648,2.122207112014663 +1739141219.5270853,58.86994385719299,12.652860067733865,1739141219.527088,58.86994385719299,0.33301410675350684,1739141219.527091,58.86994385719299,99.90367174448694,1739141219.5270936,58.86994385719299,5.057521301716508,1739141219.527095,58.86994385719299,-0.024,1739141219.5270967,58.86994385719299,-3.09462285599644,1739141219.5270984,58.86994385719299,0.36179194966454487,1739141219.5270996,58.86994385719299,0.04805407248433548,1739141219.527101,58.86994385719299,2.163168298843093,1739141219.5271027,58.86994385719299,0.0,1739141219.5271041,58.86994385719299,0.04096118682843031,1739141219.5271056,58.86994385719299,3.140963594898505,1739141219.5271068,58.86994385719299,2.122207112014663 +1739141219.5472355,58.88994383811951,12.652860067733865,1739141219.5472403,58.88994383811951,0.33301410675350684,1739141219.547245,58.88994383811951,99.90367174448694,1739141219.5472505,58.88994383811951,5.057521301716508,1739141219.5472536,58.88994383811951,-0.024,1739141219.5472574,58.88994383811951,-3.09462285599644,1739141219.547261,58.88994383811951,0.36179194966454487,1739141219.5472643,58.88994383811951,0.04805407248433548,1739141219.547268,58.88994383811951,2.163168298843093,1739141219.5472715,58.88994383811951,0.0,1739141219.547275,58.88994383811951,0.04096118682843031,1739141219.5472786,58.88994383811951,3.140963594898505,1739141219.547282,58.88994383811951,2.122207112014663 +1739141219.5672593,58.90994381904602,12.652860067733865,1739141219.567263,58.90994381904602,0.33301410675350684,1739141219.5672662,58.90994381904602,99.90367174448694,1739141219.5672693,58.90994381904602,5.057521301716508,1739141219.567271,58.90994381904602,-0.024,1739141219.567273,58.90994381904602,-3.09462285599644,1739141219.5672748,58.90994381904602,0.36179194966454487,1739141219.5672762,58.90994381904602,0.04805407248433548,1739141219.567278,58.90994381904602,2.163168298843093,1739141219.5672796,58.90994381904602,0.0,1739141219.5672812,58.90994381904602,0.04096118682843031,1739141219.567283,58.90994381904602,3.140963594898505,1739141219.567284,58.90994381904602,2.122207112014663 +1739141219.586799,58.929943799972534,12.41918971859447,1739141219.5868032,58.929943799972534,0.3330405652647235,1739141219.5868082,58.929943799972534,100.05835965081353,1739141219.5868146,58.929943799972534,4.88928968919854,1739141219.586818,58.929943799972534,-0.024589420493218064,1739141219.5868225,58.929943799972534,-3.0941336646613142,1739141219.5868263,58.929943799972534,0.35382488193489925,1739141219.5868304,58.929943799972534,0.04781408412255276,1739141219.586834,58.929943799972534,2.1700729382845623,1739141219.586838,58.929943799972534,0.0,1739141219.5868418,58.929943799972534,0.0455222304044132,1739141219.5868454,58.929943799972534,3.1420979801291686,1739141219.5868492,58.929943799972534,2.126722634477494 +1739141219.6070938,58.94994378089905,12.41918971859447,1739141219.6070983,58.94994378089905,0.3330405652647235,1739141219.6071038,58.94994378089905,100.05835965081353,1739141219.6071103,58.94994378089905,4.88928968919854,1739141219.6071134,58.94994378089905,-0.024589420493218064,1739141219.607118,58.94994378089905,-3.0941336646613142,1739141219.6071217,58.94994378089905,0.35382488193489925,1739141219.6071255,58.94994378089905,0.04781408412255276,1739141219.6071293,58.94994378089905,2.1700729382845623,1739141219.6071334,58.94994378089905,0.0,1739141219.6071372,58.94994378089905,0.04335030380706817,1739141219.607141,58.94994378089905,3.1420979801291686,1739141219.6071453,58.94994378089905,2.126722634477494 +1739141219.6269903,58.96994376182556,12.41918971859447,1739141219.6269956,58.96994376182556,0.3330405652647235,1739141219.6270013,58.96994376182556,100.05835965081353,1739141219.6270075,58.96994376182556,4.88928968919854,1739141219.6270108,58.96994376182556,-0.024589420493218064,1739141219.627015,58.96994376182556,-3.0941336646613142,1739141219.6270194,58.96994376182556,0.35382488193489925,1739141219.6270235,58.96994376182556,0.04781408412255276,1739141219.6270278,58.96994376182556,2.1700729382845623,1739141219.6270318,58.96994376182556,0.0,1739141219.6270356,58.96994376182556,0.04335030380706817,1739141219.6270394,58.96994376182556,3.1420979801291686,1739141219.6270432,58.96994376182556,2.126722634477494 +1739141219.6465244,58.989943742752075,12.41918971859447,1739141219.6465285,58.989943742752075,0.3330405652647235,1739141219.646534,58.989943742752075,100.05835965081353,1739141219.64654,58.989943742752075,4.88928968919854,1739141219.6465433,58.989943742752075,-0.024589420493218064,1739141219.6465478,58.989943742752075,-3.0941336646613142,1739141219.6465516,58.989943742752075,0.35382488193489925,1739141219.6465554,58.989943742752075,0.04781408412255276,1739141219.646559,58.989943742752075,2.1700729382845623,1739141219.646563,58.989943742752075,0.0,1739141219.646567,58.989943742752075,0.04335030380706817,1739141219.646571,58.989943742752075,3.1420979801291686,1739141219.6465745,58.989943742752075,2.126722634477494 +1739141219.6669433,59.00994372367859,12.41918971859447,1739141219.666946,59.00994372367859,0.3330405652647235,1739141219.6669493,59.00994372367859,100.05835965081353,1739141219.6669524,59.00994372367859,4.88928968919854,1739141219.6669543,59.00994372367859,-0.024589420493218064,1739141219.666956,59.00994372367859,-3.0941336646613142,1739141219.6669576,59.00994372367859,0.35382488193489925,1739141219.6669593,59.00994372367859,0.04781408412255276,1739141219.6669607,59.00994372367859,2.1700729382845623,1739141219.6669624,59.00994372367859,0.0,1739141219.666964,59.00994372367859,0.04335030380706817,1739141219.6669655,59.00994372367859,3.1420979801291686,1739141219.6669672,59.00994372367859,2.126722634477494 +1739141219.6871684,59.0299437046051,12.185011713151582,1739141219.6871731,59.0299437046051,0.3328014304011946,1739141219.6871786,59.0299437046051,100.29065548212827,1739141219.6871846,59.0299437046051,4.642710409585816,1739141219.6871881,59.0299437046051,-0.025,1739141219.6871927,59.0299437046051,-3.094188901236512,1739141219.6871965,59.0299437046051,0.345433754720271,1739141219.6872003,59.0299437046051,0.04652722377679799,1739141219.687204,59.0299437046051,2.1773689189714855,1739141219.6872082,59.0299437046051,0.0,1739141219.687212,59.0299437046051,0.048188260998451644,1739141219.6872158,59.0299437046051,3.1432323653598324,1739141219.6872199,59.0299437046051,2.131484448262632 +1739141219.7067363,59.049943685531616,12.185011713151582,1739141219.7067406,59.049943685531616,0.3328014304011946,1739141219.7067459,59.049943685531616,100.29065548212827,1739141219.7067518,59.049943685531616,4.642710409585816,1739141219.7067552,59.049943685531616,-0.025,1739141219.7067595,59.049943685531616,-3.094188901236512,1739141219.7067633,59.049943685531616,0.345433754720271,1739141219.706767,59.049943685531616,0.04652722377679799,1739141219.7067707,59.049943685531616,2.1773689189714855,1739141219.7067747,59.049943685531616,0.0,1739141219.7067785,59.049943685531616,0.04588447070885371,1739141219.7067826,59.049943685531616,3.1432323653598324,1739141219.7067864,59.049943685531616,2.131484448262632 +1739141219.727042,59.06994366645813,12.185011713151582,1739141219.7270467,59.06994366645813,0.3328014304011946,1739141219.727052,59.06994366645813,100.29065548212827,1739141219.7270584,59.06994366645813,4.642710409585816,1739141219.7270617,59.06994366645813,-0.025,1739141219.7270658,59.06994366645813,-3.094188901236512,1739141219.7270699,59.06994366645813,0.345433754720271,1739141219.727074,59.06994366645813,0.04652722377679799,1739141219.7270782,59.06994366645813,2.1773689189714855,1739141219.7270823,59.06994366645813,0.0,1739141219.727086,59.06994366645813,0.04588447070885371,1739141219.72709,59.06994366645813,3.1432323653598324,1739141219.7270937,59.06994366645813,2.131484448262632 +1739141219.7471402,59.089943647384644,12.185011713151582,1739141219.7471445,59.089943647384644,0.3328014304011946,1739141219.7471495,59.089943647384644,100.29065548212827,1739141219.7471554,59.089943647384644,4.642710409585816,1739141219.7471588,59.089943647384644,-0.025,1739141219.747163,59.089943647384644,-3.094188901236512,1739141219.7471676,59.089943647384644,0.345433754720271,1739141219.7471714,59.089943647384644,0.04652722377679799,1739141219.7471752,59.089943647384644,2.1773689189714855,1739141219.7471793,59.089943647384644,0.0,1739141219.747183,59.089943647384644,0.04588447070885371,1739141219.747187,59.089943647384644,3.1432323653598324,1739141219.7471907,59.089943647384644,2.131484448262632 +1739141219.7722456,59.10994362831116,12.185011713151582,1739141219.7722545,59.10994362831116,0.3328014304011946,1739141219.7722745,59.10994362831116,100.29065548212827,1739141219.7722995,59.10994362831116,4.642710409585816,1739141219.772314,59.10994362831116,-0.025,1739141219.7723262,59.10994362831116,-3.094188901236512,1739141219.7723315,59.10994362831116,0.345433754720271,1739141219.7723365,59.10994362831116,0.04652722377679799,1739141219.772341,59.10994362831116,2.1773689189714855,1739141219.772347,59.10994362831116,0.0,1739141219.772352,59.10994362831116,0.04588447070885371,1739141219.7723563,59.10994362831116,3.1432323653598324,1739141219.772361,59.10994362831116,2.131484448262632 +1739141219.7904663,59.12994360923767,12.185011713151582,1739141219.7904966,59.12994360923767,0.3328014304011946,1739141219.7905045,59.12994360923767,100.29065548212827,1739141219.7905116,59.12994360923767,4.642710409585816,1739141219.7905152,59.12994360923767,-0.025,1739141219.7905192,59.12994360923767,-3.094188901236512,1739141219.7905228,59.12994360923767,0.345433754720271,1739141219.7905262,59.12994360923767,0.04652722377679799,1739141219.7905295,59.12994360923767,2.1773689189714855,1739141219.7905335,59.12994360923767,0.0,1739141219.790537,59.12994360923767,0.04588447070885371,1739141219.7905402,59.12994360923767,3.1432323653598324,1739141219.7905433,59.12994360923767,2.131484448262632 +1739141219.8086953,59.149943590164185,11.950292957260052,1739141219.8087,59.149943590164185,0.33229547839866314,1739141219.8087058,59.149943590164185,100.52650429532346,1739141219.8087108,59.149943590164185,4.3916574266643185,1739141219.8087134,59.149943590164185,-0.026,1739141219.8087168,59.149943590164185,-3.094225972220204,1739141219.8087194,59.149943590164185,0.3373257384869224,1739141219.8087218,59.149943590164185,0.04523933585967312,1739141219.8087242,59.149943590164185,2.1844420395834194,1739141219.808727,59.149943590164185,0.0,1739141219.80873,59.149943590164185,0.049709291735723506,1739141219.8087325,59.149943590164185,3.144366750590496,1739141219.8087347,59.149943590164185,2.1365540921036654 +1739141219.8290215,59.1699435710907,11.950292957260052,1739141219.8290265,59.1699435710907,0.33229547839866314,1739141219.8290324,59.1699435710907,100.52650429532346,1739141219.829038,59.1699435710907,4.3916574266643185,1739141219.82904,59.1699435710907,-0.026,1739141219.8290434,59.1699435710907,-3.094225972220204,1739141219.8290462,59.1699435710907,0.3373257384869224,1739141219.8290486,59.1699435710907,0.04523933585967312,1739141219.829051,59.1699435710907,2.1844420395834194,1739141219.829054,59.1699435710907,0.0,1739141219.8290567,59.1699435710907,0.047887947479754,1739141219.8290594,59.1699435710907,3.144366750590496,1739141219.829062,59.1699435710907,2.1365540921036654 +1739141219.8506758,59.18994355201721,11.950292957260052,1739141219.8506806,59.18994355201721,0.33229547839866314,1739141219.8506863,59.18994355201721,100.52650429532346,1739141219.8506916,59.18994355201721,4.3916574266643185,1739141219.8506942,59.18994355201721,-0.026,1739141219.8506973,59.18994355201721,-3.094225972220204,1739141219.8506997,59.18994355201721,0.3373257384869224,1739141219.8507023,59.18994355201721,0.04523933585967312,1739141219.8507047,59.18994355201721,2.1844420395834194,1739141219.8507078,59.18994355201721,0.0,1739141219.8507102,59.18994355201721,0.047887947479754,1739141219.8507125,59.18994355201721,3.144366750590496,1739141219.850715,59.18994355201721,2.1365540921036654 +1739141219.8677466,59.209943532943726,11.950292957260052,1739141219.8677495,59.209943532943726,0.33229547839866314,1739141219.8677528,59.209943532943726,100.52650429532346,1739141219.867756,59.209943532943726,4.3916574266643185,1739141219.8677576,59.209943532943726,-0.026,1739141219.8677597,59.209943532943726,-3.094225972220204,1739141219.8677611,59.209943532943726,0.3373257384869224,1739141219.8677628,59.209943532943726,0.04523933585967312,1739141219.8677642,59.209943532943726,2.1844420395834194,1739141219.867766,59.209943532943726,0.0,1739141219.8677676,59.209943532943726,0.047887947479754,1739141219.867769,59.209943532943726,3.144366750590496,1739141219.8677707,59.209943532943726,2.1365540921036654 +1739141219.8871994,59.22994351387024,11.950292957260052,1739141219.8872018,59.22994351387024,0.33229547839866314,1739141219.8872044,59.22994351387024,100.52650429532346,1739141219.8872066,59.22994351387024,4.3916574266643185,1739141219.887208,59.22994351387024,-0.026,1739141219.8872094,59.22994351387024,-3.094225972220204,1739141219.8872108,59.22994351387024,0.3373257384869224,1739141219.8872118,59.22994351387024,0.04523933585967312,1739141219.887213,59.22994351387024,2.1844420395834194,1739141219.8872147,59.22994351387024,0.0,1739141219.8872159,59.22994351387024,0.047887947479754,1739141219.887217,59.22994351387024,3.144366750590496,1739141219.8872185,59.22994351387024,2.1365540921036654 +1739141219.9075258,59.24994349479675,11.715010018352551,1739141219.9075284,59.24994349479675,0.3315214046881101,1739141219.907531,59.24994349479675,100.6708448710701,1739141219.9075336,59.24994349479675,4.231552015298292,1739141219.907535,59.24994349479675,-0.026,1739141219.907537,59.24994349479675,-3.0938540587661625,1739141219.9075382,59.24994349479675,0.3282697857362063,1739141219.9075394,59.24994349479675,0.04491226021897153,1739141219.9075408,59.24994349479675,2.1923692701992676,1739141219.9075422,59.24994349479675,0.0,1739141219.9075437,59.24994349479675,0.05298958557811171,1739141219.9075449,59.24994349479675,3.14550113582116,1739141219.907546,59.24994349479675,2.141809037310132 +1739141219.9271295,59.26994347572327,11.715010018352551,1739141219.9271324,59.26994347572327,0.3315214046881101,1739141219.9271352,59.26994347572327,100.6708448710701,1739141219.927138,59.26994347572327,4.231552015298292,1739141219.9271393,59.26994347572327,-0.026,1739141219.9271412,59.26994347572327,-3.0938540587661625,1739141219.9271424,59.26994347572327,0.3282697857362063,1739141219.9271436,59.26994347572327,0.04491226021897153,1739141219.9271448,59.26994347572327,2.1923692701992676,1739141219.9271462,59.26994347572327,0.0,1739141219.9271479,59.26994347572327,0.05056023288913547,1739141219.927149,59.26994347572327,3.14550113582116,1739141219.9271502,59.26994347572327,2.141809037310132 +1739141219.9471405,59.28994345664978,11.715010018352551,1739141219.9471455,59.28994345664978,0.3315214046881101,1739141219.94715,59.28994345664978,100.6708448710701,1739141219.9471548,59.28994345664978,4.231552015298292,1739141219.9471576,59.28994345664978,-0.026,1739141219.9471612,59.28994345664978,-3.0938540587661625,1739141219.9471636,59.28994345664978,0.3282697857362063,1739141219.9471667,59.28994345664978,0.04491226021897153,1739141219.9471693,59.28994345664978,2.1923692701992676,1739141219.9471724,59.28994345664978,0.0,1739141219.9471757,59.28994345664978,0.05056023288913547,1739141219.9471786,59.28994345664978,3.14550113582116,1739141219.9471812,59.28994345664978,2.141809037310132 +1739141219.9691367,59.309943437576294,11.715010018352551,1739141219.9691412,59.309943437576294,0.3315214046881101,1739141219.9691448,59.309943437576294,100.6708448710701,1739141219.9691484,59.309943437576294,4.231552015298292,1739141219.96915,59.309943437576294,-0.026,1739141219.9691517,59.309943437576294,-3.0938540587661625,1739141219.9691532,59.309943437576294,0.3282697857362063,1739141219.9691548,59.309943437576294,0.04491226021897153,1739141219.9691563,59.309943437576294,2.1923692701992676,1739141219.9691582,59.309943437576294,0.0,1739141219.9691596,59.309943437576294,0.05056023288913547,1739141219.9691613,59.309943437576294,3.14550113582116,1739141219.9691627,59.309943437576294,2.141809037310132 +1739141219.9874375,59.32994341850281,11.715010018352551,1739141219.987442,59.32994341850281,0.3315214046881101,1739141219.9874465,59.32994341850281,100.6708448710701,1739141219.9874504,59.32994341850281,4.231552015298292,1739141219.9874527,59.32994341850281,-0.026,1739141219.9874558,59.32994341850281,-3.0938540587661625,1739141219.9874585,59.32994341850281,0.3282697857362063,1739141219.9874606,59.32994341850281,0.04491226021897153,1739141219.9874623,59.32994341850281,2.1923692701992676,1739141219.9874647,59.32994341850281,0.0,1739141219.987467,59.32994341850281,0.05056023288913547,1739141219.987469,59.32994341850281,3.14550113582116,1739141219.987473,59.32994341850281,2.141809037310132 +1739141220.0078425,59.34994339942932,11.715010018352551,1739141220.007847,59.34994339942932,0.3315214046881101,1739141220.0078518,59.34994339942932,100.6708448710701,1739141220.0078566,59.34994339942932,4.231552015298292,1739141220.007859,59.34994339942932,-0.026,1739141220.007862,59.34994339942932,-3.0938540587661625,1739141220.0078642,59.34994339942932,0.3282697857362063,1739141220.0078666,59.34994339942932,0.04491226021897153,1739141220.007869,59.34994339942932,2.1923692701992676,1739141220.0078712,59.34994339942932,0.0,1739141220.0078738,59.34994339942932,0.05056023288913547,1739141220.0078762,59.34994339942932,3.14550113582116,1739141220.0078783,59.34994339942932,2.141809037310132 +1739141220.0285828,59.369943380355835,11.479131439898419,1739141220.0285878,59.369943380355835,0.3304777871958082,1739141220.0285938,59.369943380355835,100.99929159158417,1739141220.028599,59.369943380355835,3.886358961768094,1739141220.0286021,59.369943380355835,-0.027198471521460633,1739141220.028606,59.369943380355835,-3.094519988530994,1739141220.0286093,59.369943380355835,0.31938252779117526,1739141220.028613,59.369943380355835,0.04245021887424828,1739141220.028617,59.369943380355835,2.2001767999692747,1739141220.0286207,59.369943380355835,0.0,1739141220.0286243,59.369943380355835,0.05480509498170106,1739141220.0286276,59.369943380355835,3.1466355210518238,1739141220.0286312,59.369943380355835,2.147393068898555 +1739141220.0480568,59.38994336128235,11.479131439898419,1739141220.0480616,59.38994336128235,0.3304777871958082,1739141220.0480676,59.38994336128235,100.99929159158417,1739141220.0480728,59.38994336128235,3.886358961768094,1739141220.0480747,59.38994336128235,-0.027198471521460633,1739141220.0480797,59.38994336128235,-3.094519988530994,1739141220.0480843,59.38994336128235,0.31938252779117526,1739141220.048088,59.38994336128235,0.04245021887424828,1739141220.048092,59.38994336128235,2.2001767999692747,1739141220.048096,59.38994336128235,0.0,1739141220.0481,59.38994336128235,0.052783731070719764,1739141220.048104,59.38994336128235,3.1466355210518238,1739141220.0481076,59.38994336128235,2.147393068898555 +1739141220.0684648,59.40994334220886,11.479131439898419,1739141220.0684707,59.40994334220886,0.3304777871958082,1739141220.0684774,59.40994334220886,100.99929159158417,1739141220.0684824,59.40994334220886,3.886358961768094,1739141220.0684848,59.40994334220886,-0.027198471521460633,1739141220.0684884,59.40994334220886,-3.094519988530994,1739141220.0684912,59.40994334220886,0.31938252779117526,1739141220.068494,59.40994334220886,0.04245021887424828,1739141220.0684962,59.40994334220886,2.2001767999692747,1739141220.0684998,59.40994334220886,0.0,1739141220.068503,59.40994334220886,0.052783731070719764,1739141220.0685048,59.40994334220886,3.1466355210518238,1739141220.0685074,59.40994334220886,2.147393068898555 +1739141220.0880566,59.429943323135376,11.479131439898419,1739141220.0880625,59.429943323135376,0.3304777871958082,1739141220.0880668,59.429943323135376,100.99929159158417,1739141220.0880706,59.429943323135376,3.886358961768094,1739141220.0880742,59.429943323135376,-0.027198471521460633,1739141220.0880775,59.429943323135376,-3.094519988530994,1739141220.08808,59.429943323135376,0.31938252779117526,1739141220.0880818,59.429943323135376,0.04245021887424828,1739141220.0880837,59.429943323135376,2.2001767999692747,1739141220.0880861,59.429943323135376,0.0,1739141220.0880885,59.429943323135376,0.052783731070719764,1739141220.0880907,59.429943323135376,3.1466355210518238,1739141220.0880926,59.429943323135376,2.147393068898555 +1739141220.108915,59.44994330406189,11.479131439898419,1739141220.1089206,59.44994330406189,0.3304777871958082,1739141220.1089272,59.44994330406189,100.99929159158417,1739141220.1089323,59.44994330406189,3.886358961768094,1739141220.1089344,59.44994330406189,-0.027198471521460633,1739141220.1089377,59.44994330406189,-3.094519988530994,1739141220.10894,59.44994330406189,0.31938252779117526,1739141220.1089425,59.44994330406189,0.04245021887424828,1739141220.108945,59.44994330406189,2.2001767999692747,1739141220.1089482,59.44994330406189,0.0,1739141220.1089506,59.44994330406189,0.052783731070719764,1739141220.1089528,59.44994330406189,3.1466355210518238,1739141220.1089551,59.44994330406189,2.147393068898555 +1739141220.1292958,59.4699432849884,11.242631672998021,1739141220.1293015,59.4699432849884,0.32916313046174306,1739141220.1293075,59.4699432849884,101.2387426669386,1739141220.1293116,59.4699432849884,3.6295382709766644,1739141220.129314,59.4699432849884,-0.027335323019190914,1739141220.129317,59.4699432849884,-3.0947998186698706,1739141220.1293192,59.4699432849884,0.3094639491562164,1739141220.1293209,59.4699432849884,0.04091389023618819,1739141220.1293235,59.4699432849884,2.2089231894875216,1739141220.1293259,59.4699432849884,0.0,1739141220.129329,59.4699432849884,0.05842348930033786,1739141220.1293333,59.4699432849884,3.1477699062824875,1739141220.129336,59.4699432849884,2.1531853006857196 +1739141220.1483283,59.48994326591492,11.242631672998021,1739141220.148333,59.48994326591492,0.32916313046174306,1739141220.148338,59.48994326591492,101.2387426669386,1739141220.1483426,59.48994326591492,3.6295382709766644,1739141220.148345,59.48994326591492,-0.027335323019190914,1739141220.1483483,59.48994326591492,-3.0947998186698706,1739141220.148351,59.48994326591492,0.3094639491562164,1739141220.1483533,59.48994326591492,0.04091389023618819,1739141220.1483562,59.48994326591492,2.2089231894875216,1739141220.148359,59.48994326591492,0.0,1739141220.1483622,59.48994326591492,0.05573788880180208,1739141220.1483648,59.48994326591492,3.1477699062824875,1739141220.148367,59.48994326591492,2.1531853006857196 +1739141220.168068,59.50994324684143,11.242631672998021,1739141220.1680734,59.50994324684143,0.32916313046174306,1739141220.1680796,59.50994324684143,101.2387426669386,1739141220.1680863,59.50994324684143,3.6295382709766644,1739141220.1680903,59.50994324684143,-0.027335323019190914,1739141220.1680956,59.50994324684143,-3.0947998186698706,1739141220.168099,59.50994324684143,0.3094639491562164,1739141220.1681004,59.50994324684143,0.04091389023618819,1739141220.1681015,59.50994324684143,2.2089231894875216,1739141220.1681035,59.50994324684143,0.0,1739141220.1681054,59.50994324684143,0.05573788880180208,1739141220.1681073,59.50994324684143,3.1477699062824875,1739141220.1681085,59.50994324684143,2.1531853006857196 +1739141220.1884947,59.529943227767944,11.242631672998021,1739141220.1885014,59.529943227767944,0.32916313046174306,1739141220.1885087,59.529943227767944,101.2387426669386,1739141220.188514,59.529943227767944,3.6295382709766644,1739141220.1885173,59.529943227767944,-0.027335323019190914,1739141220.1885211,59.529943227767944,-3.0947998186698706,1739141220.1885247,59.529943227767944,0.3094639491562164,1739141220.1885283,59.529943227767944,0.04091389023618819,1739141220.1885316,59.529943227767944,2.2089231894875216,1739141220.1885362,59.529943227767944,0.0,1739141220.1885407,59.529943227767944,0.05573788880180208,1739141220.1885433,59.529943227767944,3.1477699062824875,1739141220.1885493,59.529943227767944,2.1531853006857196 +1739141220.2077107,59.54994320869446,11.242631672998021,1739141220.2077153,59.54994320869446,0.32916313046174306,1739141220.2077196,59.54994320869446,101.2387426669386,1739141220.2077239,59.54994320869446,3.6295382709766644,1739141220.2077258,59.54994320869446,-0.027335323019190914,1739141220.2077286,59.54994320869446,-3.0947998186698706,1739141220.2077308,59.54994320869446,0.3094639491562164,1739141220.2077327,59.54994320869446,0.04091389023618819,1739141220.2077348,59.54994320869446,2.2089231894875216,1739141220.207737,59.54994320869446,0.0,1739141220.2077398,59.54994320869446,0.05573788880180208,1739141220.207742,59.54994320869446,3.1477699062824875,1739141220.207744,59.54994320869446,2.1531853006857196 +1739141220.2277093,59.56994318962097,11.242631672998021,1739141220.2277145,59.56994318962097,0.32916313046174306,1739141220.227719,59.56994318962097,101.2387426669386,1739141220.2277236,59.56994318962097,3.6295382709766644,1739141220.2277257,59.56994318962097,-0.027335323019190914,1739141220.2277288,59.56994318962097,-3.0947998186698706,1739141220.2277317,59.56994318962097,0.3094639491562164,1739141220.227734,59.56994318962097,0.04091389023618819,1739141220.2277362,59.56994318962097,2.2089231894875216,1739141220.2277389,59.56994318962097,0.0,1739141220.2277412,59.56994318962097,0.05573788880180208,1739141220.2277434,59.56994318962097,3.1477699062824875,1739141220.2277458,59.56994318962097,2.1531853006857196 +1739141220.247781,59.589943170547485,11.005475828441018,1739141220.2477858,59.589943170547485,0.32757578724860537,1739141220.24779,59.589943170547485,101.47334197813187,1739141220.2477944,59.589943170547485,3.376842160382245,1739141220.2477965,59.589943170547485,-0.014584216038224497,1739141220.2477992,59.589943170547485,-3.0967706248105227,1739141220.2478013,59.589943170547485,0.28637354713088725,1739141220.2478034,59.589943170547485,0.037714201988689425,1739141220.2478054,59.589943170547485,2.22941966796149,1739141220.2478077,59.589943170547485,0.0,1739141220.2478101,59.589943170547485,0.08311528400008686,1739141220.2478118,59.589943170547485,3.1489042915131513,1739141220.247814,59.589943170547485,2.159341245330211 +1739141220.2675579,59.609943151474,11.005475828441018,1739141220.2675617,59.609943151474,0.32757578724860537,1739141220.2675648,59.609943151474,101.47334197813187,1739141220.2675679,59.609943151474,3.376842160382245,1739141220.2675705,59.609943151474,-0.014584216038224497,1739141220.2675724,59.609943151474,-3.0967706248105227,1739141220.267574,59.609943151474,0.28637354713088725,1739141220.2675755,59.609943151474,0.037714201988689425,1739141220.267578,59.609943151474,2.22941966796149,1739141220.2675796,59.609943151474,0.0,1739141220.2675812,59.609943151474,0.07007842263127895,1739141220.2675827,59.609943151474,3.1489042915131513,1739141220.2675843,59.609943151474,2.159341245330211 +1739141220.288044,59.62994313240051,11.005475828441018,1739141220.2880492,59.62994313240051,0.32757578724860537,1739141220.2880538,59.62994313240051,101.47334197813187,1739141220.288058,59.62994313240051,3.376842160382245,1739141220.2880611,59.62994313240051,-0.014584216038224497,1739141220.2880642,59.62994313240051,-3.0967706248105227,1739141220.2880669,59.62994313240051,0.28637354713088725,1739141220.288069,59.62994313240051,0.037714201988689425,1739141220.2880714,59.62994313240051,2.22941966796149,1739141220.2880743,59.62994313240051,0.0,1739141220.2880769,59.62994313240051,0.07007842263127895,1739141220.2880793,59.62994313240051,3.1489042915131513,1739141220.2880816,59.62994313240051,2.159341245330211 +1739141220.3072476,59.649943113327026,11.005475828441018,1739141220.3072536,59.649943113327026,0.32757578724860537,1739141220.307259,59.649943113327026,101.47334197813187,1739141220.3072631,59.649943113327026,3.376842160382245,1739141220.3072658,59.649943113327026,-0.014584216038224497,1739141220.3072693,59.649943113327026,-3.0967706248105227,1739141220.3072715,59.649943113327026,0.28637354713088725,1739141220.3072748,59.649943113327026,0.037714201988689425,1739141220.3072789,59.649943113327026,2.22941966796149,1739141220.3072836,59.649943113327026,0.0,1739141220.3072884,59.649943113327026,0.07007842263127895,1739141220.3072906,59.649943113327026,3.1489042915131513,1739141220.307292,59.649943113327026,2.159341245330211 +1739141220.327318,59.66994309425354,11.005475828441018,1739141220.3273215,59.66994309425354,0.32757578724860537,1739141220.3273263,59.66994309425354,101.47334197813187,1739141220.3273296,59.66994309425354,3.376842160382245,1739141220.327331,59.66994309425354,-0.014584216038224497,1739141220.3273332,59.66994309425354,-3.0967706248105227,1739141220.327335,59.66994309425354,0.28637354713088725,1739141220.3273368,59.66994309425354,0.037714201988689425,1739141220.3273377,59.66994309425354,2.22941966796149,1739141220.3273394,59.66994309425354,0.0,1739141220.327341,59.66994309425354,0.07007842263127895,1739141220.3273423,59.66994309425354,3.1489042915131513,1739141220.3273442,59.66994309425354,2.159341245330211 +1739141220.3474097,59.689943075180054,10.767564003852765,1739141220.3474143,59.689943075180054,0.3257134684952998,1739141220.3474176,59.689943075180054,101.81617888847089,1739141220.3474207,59.689943075180054,3.0110985395999155,1739141220.347422,59.689943075180054,0.00307605841600338,1739141220.347424,59.689943075180054,-3.10002068676636,1739141220.3474257,59.689943075180054,0.25711539439906983,1739141220.3474276,59.689943075180054,0.03276374449374894,1739141220.3474293,59.689943075180054,2.2556644234807,1739141220.3474343,59.689943075180054,0.0,1739141220.3474386,59.689943075180054,0.10532224303989178,1739141220.3474414,59.689943075180054,3.150038676743815,1739141220.3474433,59.689943075180054,2.167124960447689 +1739141220.368416,59.70994305610657,10.767564003852765,1739141220.368423,59.70994305610657,0.3257134684952998,1739141220.3684304,59.70994305610657,101.81617888847089,1739141220.3684378,59.70994305610657,3.0110985395999155,1739141220.3684416,59.70994305610657,0.00307605841600338,1739141220.3684468,59.70994305610657,-3.10002068676636,1739141220.3684509,59.70994305610657,0.25711539439906983,1739141220.3684556,59.70994305610657,0.03276374449374894,1739141220.36846,59.70994305610657,2.2556644234807,1739141220.3684657,59.70994305610657,0.0,1739141220.3684716,59.70994305610657,0.08853946303301097,1739141220.3684764,59.70994305610657,3.150038676743815,1739141220.3684804,59.70994305610657,2.167124960447689 +1739141220.3879492,59.72994303703308,10.767564003852765,1739141220.3879538,59.72994303703308,0.3257134684952998,1739141220.3879576,59.72994303703308,101.81617888847089,1739141220.3879611,59.72994303703308,3.0110985395999155,1739141220.3879626,59.72994303703308,0.00307605841600338,1739141220.3879647,59.72994303703308,-3.10002068676636,1739141220.3879664,59.72994303703308,0.25711539439906983,1739141220.387968,59.72994303703308,0.03276374449374894,1739141220.3879693,59.72994303703308,2.2556644234807,1739141220.387971,59.72994303703308,0.0,1739141220.3879724,59.72994303703308,0.08853946303301097,1739141220.3879743,59.72994303703308,3.150038676743815,1739141220.3879755,59.72994303703308,2.167124960447689 +1739141220.4070807,59.749943017959595,10.767564003852765,1739141220.407086,59.749943017959595,0.3257134684952998,1739141220.4070919,59.749943017959595,101.81617888847089,1739141220.4070976,59.749943017959595,3.0110985395999155,1739141220.407101,59.749943017959595,0.00307605841600338,1739141220.407105,59.749943017959595,-3.10002068676636,1739141220.407109,59.749943017959595,0.25711539439906983,1739141220.4071136,59.749943017959595,0.03276374449374894,1739141220.4071171,59.749943017959595,2.2556644234807,1739141220.407121,59.749943017959595,0.0,1739141220.4071245,59.749943017959595,0.08853946303301097,1739141220.4071295,59.749943017959595,3.150038676743815,1739141220.407134,59.749943017959595,2.167124960447689 +1739141220.4287913,59.76994299888611,10.767564003852765,1739141220.4287972,59.76994299888611,0.3257134684952998,1739141220.4288023,59.76994299888611,101.81617888847089,1739141220.4288077,59.76994299888611,3.0110985395999155,1739141220.4288108,59.76994299888611,0.00307605841600338,1739141220.4288146,59.76994299888611,-3.10002068676636,1739141220.4288182,59.76994299888611,0.25711539439906983,1739141220.4288216,59.76994299888611,0.03276374449374894,1739141220.428825,59.76994299888611,2.2556644234807,1739141220.4288301,59.76994299888611,0.0,1739141220.428834,59.76994299888611,0.08853946303301097,1739141220.4288378,59.76994299888611,3.150038676743815,1739141220.428842,59.76994299888611,2.167124960447689 +1739141220.4475265,59.78994297981262,10.767564003852765,1739141220.4475317,59.78994297981262,0.3257134684952998,1739141220.447537,59.78994297981262,101.81617888847089,1739141220.4475424,59.78994297981262,3.0110985395999155,1739141220.4475455,59.78994297981262,0.00307605841600338,1739141220.4475496,59.78994297981262,-3.10002068676636,1739141220.4475536,59.78994297981262,0.25711539439906983,1739141220.447557,59.78994297981262,0.03276374449374894,1739141220.4475608,59.78994297981262,2.2556644234807,1739141220.4475644,59.78994297981262,0.0,1739141220.4475684,59.78994297981262,0.08853946303301097,1739141220.447573,59.78994297981262,3.150038676743815,1739141220.4475765,59.78994297981262,2.167124960447689 +1739141220.4685652,59.809942960739136,10.528672499084507,1739141220.4685752,59.809942960739136,0.3235724460466196,1739141220.4685838,59.809942960739136,101.85783486495134,1739141220.468592,59.809942960739136,2.939468300136852,1739141220.4685962,59.809942960739136,0.006911901991788879,1739141220.4686012,59.809942960739136,-3.099891711010518,1739141220.468606,59.809942960739136,0.24393944863518052,1739141220.4686105,59.809942960739136,0.03246970771423249,1739141220.468615,59.809942960739136,2.267584011100086,1739141220.4686203,59.809942960739136,0.0,1739141220.468625,59.809942960739136,0.09215321457860662,1739141220.4686296,59.809942960739136,3.151173061974479,1739141220.4686337,59.809942960739136,2.177151631450443 +1739141220.4885707,59.82994294166565,10.528672499084507,1739141220.4885762,59.82994294166565,0.3235724460466196,1739141220.4885807,59.82994294166565,101.85783486495134,1739141220.4885848,59.82994294166565,2.939468300136852,1739141220.4885867,59.82994294166565,0.006911901991788879,1739141220.4885898,59.82994294166565,-3.099891711010518,1739141220.4886231,59.82994294166565,0.24393944863518052,1739141220.4886258,59.82994294166565,0.03246970771423249,1739141220.488647,59.82994294166565,2.267584011100086,1739141220.4886584,59.82994294166565,0.0,1739141220.4886687,59.82994294166565,0.09043237964964312,1739141220.4886732,59.82994294166565,3.151173061974479,1739141220.4886813,59.82994294166565,2.177151631450443 +1739141220.5078034,59.84994292259216,10.528672499084507,1739141220.507807,59.84994292259216,0.3235724460466196,1739141220.5078115,59.84994292259216,101.85783486495134,1739141220.5078154,59.84994292259216,2.939468300136852,1739141220.5078173,59.84994292259216,0.006911901991788879,1739141220.5078194,59.84994292259216,-3.099891711010518,1739141220.507821,59.84994292259216,0.24393944863518052,1739141220.507823,59.84994292259216,0.03246970771423249,1739141220.5078244,59.84994292259216,2.267584011100086,1739141220.5078263,59.84994292259216,0.0,1739141220.5078282,59.84994292259216,0.09043237964964312,1739141220.5078297,59.84994292259216,3.151173061974479,1739141220.5078313,59.84994292259216,2.177151631450443 +1739141220.527827,59.86994290351868,10.528672499084507,1739141220.527835,59.86994290351868,0.3235724460466196,1739141220.5278418,59.86994290351868,101.85783486495134,1739141220.5278463,59.86994290351868,2.939468300136852,1739141220.5278482,59.86994290351868,0.006911901991788879,1739141220.5278504,59.86994290351868,-3.099891711010518,1739141220.5278525,59.86994290351868,0.24393944863518052,1739141220.5278544,59.86994290351868,0.03246970771423249,1739141220.5278563,59.86994290351868,2.267584011100086,1739141220.527859,59.86994290351868,0.0,1739141220.5278609,59.86994290351868,0.09043237964964312,1739141220.5278628,59.86994290351868,3.151173061974479,1739141220.5278642,59.86994290351868,2.177151631450443 +1739141220.5477724,59.88994288444519,10.528672499084507,1739141220.547778,59.88994288444519,0.3235724460466196,1739141220.5477817,59.88994288444519,101.85783486495134,1739141220.5477853,59.88994288444519,2.939468300136852,1739141220.5477865,59.88994288444519,0.006911901991788879,1739141220.5477893,59.88994288444519,-3.099891711010518,1739141220.5477912,59.88994288444519,0.24393944863518052,1739141220.547793,59.88994288444519,0.03246970771423249,1739141220.547794,59.88994288444519,2.267584011100086,1739141220.547796,59.88994288444519,0.0,1739141220.547798,59.88994288444519,0.09043237964964312,1739141220.5477998,59.88994288444519,3.151173061974479,1739141220.547801,59.88994288444519,2.177151631450443 +1739141220.568379,59.909942865371704,10.288701982613498,1739141220.568384,59.909942865371704,0.32114950987878554,1739141220.5683887,59.909942865371704,102.1644986621714,1739141220.5683932,59.909942865371704,2.6034955369302635,1739141220.568395,59.909942865371704,0.023449161757948426,1739141220.5683973,59.909942865371704,-3.1028752059361637,1739141220.5683997,59.909942865371704,0.21533943394130647,1739141220.5684013,59.909942865371704,0.027958247768491852,1739141220.5684032,59.909942865371704,2.2936741365671947,1739141220.568406,59.909942865371704,0.0,1739141220.568408,59.909942865371704,0.12132698594947203,1739141220.56841,59.909942865371704,3.1523074472051427,1739141220.568412,59.909942865371704,2.1870588752525046 +1739141220.5877037,59.92994284629822,10.288701982613498,1739141220.5877082,59.92994284629822,0.32114950987878554,1739141220.5877125,59.92994284629822,102.1644986621714,1739141220.5877168,59.92994284629822,2.6034955369302635,1739141220.587719,59.92994284629822,0.023449161757948426,1739141220.5877218,59.92994284629822,-3.1028752059361637,1739141220.5877237,59.92994284629822,0.21533943394130647,1739141220.5877256,59.92994284629822,0.027958247768491852,1739141220.5877275,59.92994284629822,2.2936741365671947,1739141220.5877302,59.92994284629822,0.0,1739141220.587732,59.92994284629822,0.10661526131469001,1739141220.5877337,59.92994284629822,3.1523074472051427,1739141220.587736,59.92994284629822,2.1870588752525046 +1739141220.6100078,59.94994282722473,10.288701982613498,1739141220.610012,59.94994282722473,0.32114950987878554,1739141220.6100168,59.94994282722473,102.1644986621714,1739141220.6100209,59.94994282722473,2.6034955369302635,1739141220.610023,59.94994282722473,0.023449161757948426,1739141220.6100254,59.94994282722473,-3.1028752059361637,1739141220.6100273,59.94994282722473,0.21533943394130647,1739141220.610029,59.94994282722473,0.027958247768491852,1739141220.610031,59.94994282722473,2.2936741365671947,1739141220.6100328,59.94994282722473,0.0,1739141220.6100352,59.94994282722473,0.10661526131469001,1739141220.6100368,59.94994282722473,3.1523074472051427,1739141220.6100385,59.94994282722473,2.1870588752525046 +1739141220.635562,59.969942808151245,10.288701982613498,1739141220.6355715,59.969942808151245,0.32114950987878554,1739141220.6355824,59.969942808151245,102.1644986621714,1739141220.6355925,59.969942808151245,2.6034955369302635,1739141220.635597,59.969942808151245,0.023449161757948426,1739141220.6356032,59.969942808151245,-3.1028752059361637,1739141220.635608,59.969942808151245,0.21533943394130647,1739141220.6356127,59.969942808151245,0.027958247768491852,1739141220.6356173,59.969942808151245,2.2936741365671947,1739141220.6356232,59.969942808151245,0.0,1739141220.6356285,59.969942808151245,0.10661526131469001,1739141220.6356332,59.969942808151245,3.1523074472051427,1739141220.635638,59.969942808151245,2.1870588752525046 +1739141220.6559184,59.98994278907776,10.288701982613498,1739141220.6559281,59.98994278907776,0.32114950987878554,1739141220.6559381,59.98994278907776,102.1644986621714,1739141220.655948,59.98994278907776,2.6034955369302635,1739141220.655953,59.98994278907776,0.023449161757948426,1739141220.655959,59.98994278907776,-3.1028752059361637,1739141220.6559637,59.98994278907776,0.21533943394130647,1739141220.6559682,59.98994278907776,0.027958247768491852,1739141220.655973,59.98994278907776,2.2936741365671947,1739141220.6559792,59.98994278907776,0.0,1739141220.6559846,59.98994278907776,0.10661526131469001,1739141220.6559894,59.98994278907776,3.1523074472051427,1739141220.6559942,59.98994278907776,2.1870588752525046 +1739141220.6742702,60.00994277000427,10.288701982613498,1739141220.6742814,60.00994277000427,0.32114950987878554,1739141220.6742973,60.00994277000427,102.1644986621714,1739141220.674312,60.00994277000427,2.6034955369302635,1739141220.6743202,60.00994277000427,0.023449161757948426,1739141220.6743307,60.00994277000427,-3.1028752059361637,1739141220.674343,60.00994277000427,0.21533943394130647,1739141220.674357,60.00994277000427,0.027958247768491852,1739141220.6743681,60.00994277000427,2.2936741365671947,1739141220.6743774,60.00994277000427,0.0,1739141220.6743903,60.00994277000427,0.10661526131469001,1739141220.6744037,60.00994277000427,3.1523074472051427,1739141220.674414,60.00994277000427,2.1870588752525046 +1739141220.6960237,60.029942750930786,10.047528152274575,1739141220.69603,60.029942750930786,0.31844078927425734,1739141220.6960373,60.029942750930786,103.03086038155824,1739141220.6960456,60.029942750930786,1.7013897438232872,1739141220.6960504,60.029942750930786,0.03905783769254343,1739141220.6960566,60.029942750930786,-3.1081306314600137,1739141220.6960618,60.029942750930786,0.180470766202297,1739141220.6960673,60.029942750930786,0.019874865116694736,1739141220.6960728,60.029942750930786,2.325889218274488,1739141220.6960783,60.029942750930786,0.0,1739141220.696084,60.029942750930786,0.14527559004272864,1739141220.6960893,60.029942750930786,3.1534418324358064,1739141220.6960948,60.029942750930786,2.1990233177748886 +1739141220.7141442,60.0499427318573,10.047528152274575,1739141220.7141488,60.0499427318573,0.31844078927425734,1739141220.7141545,60.0499427318573,103.03086038155824,1739141220.7141612,60.0499427318573,1.7013897438232872,1739141220.7141645,60.0499427318573,0.03905783769254343,1739141220.714169,60.0499427318573,-3.1081306314600137,1739141220.7141728,60.0499427318573,0.180470766202297,1739141220.7141771,60.0499427318573,0.019874865116694736,1739141220.714181,60.0499427318573,2.325889218274488,1739141220.714185,60.0499427318573,0.0,1739141220.7141888,60.0499427318573,0.12686590049959934,1739141220.7141929,60.0499427318573,3.1534418324358064,1739141220.7141967,60.0499427318573,2.1990233177748886 +1739141220.732821,60.06994271278381,10.047528152274575,1739141220.732824,60.06994271278381,0.31844078927425734,1739141220.7328277,60.06994271278381,103.03086038155824,1739141220.7328308,60.06994271278381,1.7013897438232872,1739141220.7328322,60.06994271278381,0.03905783769254343,1739141220.7328339,60.06994271278381,-3.1081306314600137,1739141220.7328355,60.06994271278381,0.180470766202297,1739141220.7328374,60.06994271278381,0.019874865116694736,1739141220.7328403,60.06994271278381,2.325889218274488,1739141220.7328453,60.06994271278381,0.0,1739141220.7328494,60.06994271278381,0.12686590049959934,1739141220.7328525,60.06994271278381,3.1534418324358064,1739141220.7328553,60.06994271278381,2.1990233177748886 +1739141220.7531438,60.08994269371033,10.047528152274575,1739141220.753149,60.08994269371033,0.31844078927425734,1739141220.753154,60.08994269371033,103.03086038155824,1739141220.7531598,60.08994269371033,1.7013897438232872,1739141220.7531636,60.08994269371033,0.03905783769254343,1739141220.7531688,60.08994269371033,-3.1081306314600137,1739141220.7531729,60.08994269371033,0.180470766202297,1739141220.7531803,60.08994269371033,0.019874865116694736,1739141220.7531836,60.08994269371033,2.325889218274488,1739141220.7531874,60.08994269371033,0.0,1739141220.7531908,60.08994269371033,0.12686590049959934,1739141220.7531948,60.08994269371033,3.1534418324358064,1739141220.7531993,60.08994269371033,2.1990233177748886 +1739141220.7726946,60.10994267463684,10.047528152274575,1739141220.772698,60.10994267463684,0.31844078927425734,1739141220.7727025,60.10994267463684,103.03086038155824,1739141220.7727072,60.10994267463684,1.7013897438232872,1739141220.7727103,60.10994267463684,0.03905783769254343,1739141220.772714,60.10994267463684,-3.1081306314600137,1739141220.7727175,60.10994267463684,0.180470766202297,1739141220.7727206,60.10994267463684,0.019874865116694736,1739141220.772724,60.10994267463684,2.325889218274488,1739141220.7727273,60.10994267463684,0.0,1739141220.7727306,60.10994267463684,0.12686590049959934,1739141220.7727337,60.10994267463684,3.1534418324358064,1739141220.772737,60.10994267463684,2.1990233177748886 +1739141220.7927728,60.129942655563354,9.804948447031702,1739141220.792776,60.129942655563354,0.3154410386112865,1739141220.7927806,60.129942655563354,103.03668229448408,1739141220.7927856,60.129942655563354,1.6534404159875717,1739141220.7927885,60.129942655563354,0.03955216065992194,1739141220.7927918,60.129942655563354,-3.1077604342861376,1739141220.7927952,60.129942655563354,0.17003297121497812,1739141220.7927985,60.129942655563354,0.019629762619310247,1739141220.7928016,60.129942655563354,2.33562038044324,1739141220.792805,60.129942655563354,0.0,1739141220.7928083,60.129942655563354,0.11863359360221717,1739141220.7928116,60.129942655563354,3.1545762176664702,1739141220.7928145,60.129942655563354,2.213066638741127 +1739141220.8127222,60.14994263648987,9.804948447031702,1739141220.812726,60.14994263648987,0.3154410386112865,1739141220.8127303,60.14994263648987,103.03668229448408,1739141220.8127356,60.14994263648987,1.6534404159875717,1739141220.8127387,60.14994263648987,0.03955216065992194,1739141220.8127422,60.14994263648987,-3.1077604342861376,1739141220.8127456,60.14994263648987,0.17003297121497812,1739141220.812749,60.14994263648987,0.019629762619310247,1739141220.8127518,60.14994263648987,2.33562038044324,1739141220.812755,60.14994263648987,0.0,1739141220.8127587,60.14994263648987,0.12255374170211297,1739141220.812762,60.14994263648987,3.1545762176664702,1739141220.8127654,60.14994263648987,2.213066638741127 +1739141220.8408794,60.16994261741638,9.804948447031702,1739141220.840888,60.16994261741638,0.3154410386112865,1739141220.8408985,60.16994261741638,103.03668229448408,1739141220.8409083,60.16994261741638,1.6534404159875717,1739141220.840913,60.16994261741638,0.03955216065992194,1739141220.8409193,60.16994261741638,-3.1077604342861376,1739141220.8409245,60.16994261741638,0.17003297121497812,1739141220.840929,60.16994261741638,0.019629762619310247,1739141220.8409333,60.16994261741638,2.33562038044324,1739141220.8409393,60.16994261741638,0.0,1739141220.8409443,60.16994261741638,0.12255374170211297,1739141220.840949,60.16994261741638,3.1545762176664702,1739141220.8409534,60.16994261741638,2.213066638741127 +1739141220.8565545,60.189942598342896,9.804948447031702,1739141220.856564,60.189942598342896,0.3154410386112865,1739141220.8565743,60.189942598342896,103.03668229448408,1739141220.8565834,60.189942598342896,1.6534404159875717,1739141220.8565884,60.189942598342896,0.03955216065992194,1739141220.8565943,60.189942598342896,-3.1077604342861376,1739141220.8565998,60.189942598342896,0.17003297121497812,1739141220.8566043,60.189942598342896,0.019629762619310247,1739141220.8566089,60.189942598342896,2.33562038044324,1739141220.8566146,60.189942598342896,0.0,1739141220.85662,60.189942598342896,0.12255374170211297,1739141220.8566246,60.189942598342896,3.1545762176664702,1739141220.8566291,60.189942598342896,2.213066638741127 +1739141220.8742592,60.20994257926941,9.804948447031702,1739141220.8742661,60.20994257926941,0.3154410386112865,1739141220.8742733,60.20994257926941,103.03668229448408,1739141220.8742805,60.20994257926941,1.6534404159875717,1739141220.874284,60.20994257926941,0.03955216065992194,1739141220.8742883,60.20994257926941,-3.1077604342861376,1739141220.874292,60.20994257926941,0.17003297121497812,1739141220.8742952,60.20994257926941,0.019629762619310247,1739141220.8742986,60.20994257926941,2.33562038044324,1739141220.8743026,60.20994257926941,0.0,1739141220.8743062,60.20994257926941,0.12255374170211297,1739141220.8743093,60.20994257926941,3.1545762176664702,1739141220.8743126,60.20994257926941,2.213066638741127 +1739141220.89264,60.22994256019592,9.804948447031702,1739141220.8926437,60.22994256019592,0.3154410386112865,1739141220.8926485,60.22994256019592,103.03668229448408,1739141220.8926528,60.22994256019592,1.6534404159875717,1739141220.892655,60.22994256019592,0.03955216065992194,1739141220.8926575,60.22994256019592,-3.1077604342861376,1739141220.8926594,60.22994256019592,0.17003297121497812,1739141220.8926618,60.22994256019592,0.019629762619310247,1739141220.8926635,60.22994256019592,2.33562038044324,1739141220.892666,60.22994256019592,0.0,1739141220.8926685,60.22994256019592,0.12255374170211297,1739141220.8926704,60.22994256019592,3.1545762176664702,1739141220.8926725,60.22994256019592,2.213066638741127 +1739141220.9135501,60.24994254112244,9.560868648962792,1739141220.9135556,60.24994254112244,0.3121458200890732,1739141220.9135618,60.24994254112244,103.04254020963774,1739141220.9135687,60.24994254112244,1.6075654257595038,1739141220.9135728,60.24994254112244,0.04,1739141220.913578,60.24994254112244,-3.1073880380580796,1739141220.9135828,60.24994254112244,0.15983809721597375,1739141220.913587,60.24994254112244,0.019383499710476967,1739141220.9135916,60.24994254112244,2.3451643693652775,1739141220.9135964,60.24994254112244,0.0,1739141220.913601,60.24994254112244,0.11530720051303275,1739141220.9136057,60.24994254112244,3.155710602897134,1739141220.91361,60.24994254112244,2.2264064332288895 +1739141220.933604,60.26994252204895,9.560868648962792,1739141220.9336083,60.26994252204895,0.3121458200890732,1739141220.9336135,60.26994252204895,103.04254020963774,1739141220.9336197,60.26994252204895,1.6075654257595038,1739141220.933623,60.26994252204895,0.04,1739141220.9336276,60.26994252204895,-3.1073880380580796,1739141220.9336314,60.26994252204895,0.15983809721597375,1739141220.9336352,60.26994252204895,0.019383499710476967,1739141220.9336395,60.26994252204895,2.3451643693652775,1739141220.9336436,60.26994252204895,0.0,1739141220.9336479,60.26994252204895,0.11875793613638796,1739141220.9336517,60.26994252204895,3.155710602897134,1739141220.9336555,60.26994252204895,2.2264064332288895 +1739141220.9507408,60.289942502975464,9.560868648962792,1739141220.9507432,60.289942502975464,0.3121458200890732,1739141220.9507463,60.289942502975464,103.04254020963774,1739141220.950749,60.289942502975464,1.6075654257595038,1739141220.9507504,60.289942502975464,0.04,1739141220.9507525,60.289942502975464,-3.1073880380580796,1739141220.9507542,60.289942502975464,0.15983809721597375,1739141220.9507554,60.289942502975464,0.019383499710476967,1739141220.9507565,60.289942502975464,2.3451643693652775,1739141220.9507582,60.289942502975464,0.0,1739141220.95076,60.289942502975464,0.11875793613638796,1739141220.9507613,60.289942502975464,3.155710602897134,1739141220.9507625,60.289942502975464,2.2264064332288895 +1739141220.9705882,60.30994248390198,9.560868648962792,1739141220.9705908,60.30994248390198,0.3121458200890732,1739141220.9705935,60.30994248390198,103.04254020963774,1739141220.970596,60.30994248390198,1.6075654257595038,1739141220.9705973,60.30994248390198,0.04,1739141220.970599,60.30994248390198,-3.1073880380580796,1739141220.9706001,60.30994248390198,0.15983809721597375,1739141220.9706016,60.30994248390198,0.019383499710476967,1739141220.9706025,60.30994248390198,2.3451643693652775,1739141220.970604,60.30994248390198,0.0,1739141220.9706054,60.30994248390198,0.11875793613638796,1739141220.9706066,60.30994248390198,3.155710602897134,1739141220.9706078,60.30994248390198,2.2264064332288895 +1739141220.9926615,60.32994246482849,9.560868648962792,1739141220.992665,60.32994246482849,0.3121458200890732,1739141220.99267,60.32994246482849,103.04254020963774,1739141220.992675,60.32994246482849,1.6075654257595038,1739141220.992678,60.32994246482849,0.04,1739141220.9926982,60.32994246482849,-3.1073880380580796,1739141220.9927018,60.32994246482849,0.15983809721597375,1739141220.992705,60.32994246482849,0.019383499710476967,1739141220.9927266,60.32994246482849,2.3451643693652775,1739141220.99273,60.32994246482849,0.0,1739141220.9927332,60.32994246482849,0.11875793613638796,1739141220.9927366,60.32994246482849,3.155710602897134,1739141220.99274,60.32994246482849,2.2264064332288895 +1739141221.0112798,60.349942445755005,9.315342248238764,1739141221.0112824,60.349942445755005,0.3085525000843097,1739141221.0112855,60.349942445755005,103.0484328432551,1739141221.0112886,60.349942445755005,1.5627994568479542,1739141221.01129,60.349942445755005,0.04024127846273089,1739141221.0112917,60.349942445755005,-3.106997014868459,1739141221.0112932,60.349942445755005,0.15004022148610638,1739141221.0112944,60.349942445755005,0.019149382824304582,1739141221.0112958,60.349942445755005,2.3543734550962285,1739141221.0112972,60.349942445755005,0.0,1739141221.011299,60.349942445755005,0.11160011922906414,1739141221.0113,60.349942445755005,3.156844988127798,1739141221.0113013,60.349942445755005,2.239364849922894 +1739141221.031228,60.36994242668152,9.315342248238764,1739141221.0312312,60.36994242668152,0.3085525000843097,1739141221.0312343,60.36994242668152,103.0484328432551,1739141221.0312374,60.36994242668152,1.5627994568479542,1739141221.0312388,60.36994242668152,0.04024127846273089,1739141221.0312405,60.36994242668152,-3.106997014868459,1739141221.031242,60.36994242668152,0.15004022148610638,1739141221.0312436,60.36994242668152,0.019149382824304582,1739141221.0312448,60.36994242668152,2.3543734550962285,1739141221.0312464,60.36994242668152,0.0,1739141221.0312479,60.36994242668152,0.11500860517333455,1739141221.0312495,60.36994242668152,3.156844988127798,1739141221.0312507,60.36994242668152,2.239364849922894 +1739141221.051254,60.38994240760803,9.315342248238764,1739141221.051257,60.38994240760803,0.3085525000843097,1739141221.0512598,60.38994240760803,103.0484328432551,1739141221.0512624,60.38994240760803,1.5627994568479542,1739141221.0512638,60.38994240760803,0.04024127846273089,1739141221.0512655,60.38994240760803,-3.106997014868459,1739141221.0512671,60.38994240760803,0.15004022148610638,1739141221.0512683,60.38994240760803,0.019149382824304582,1739141221.0512698,60.38994240760803,2.3543734550962285,1739141221.0512717,60.38994240760803,0.0,1739141221.051273,60.38994240760803,0.11500860517333455,1739141221.0512745,60.38994240760803,3.156844988127798,1739141221.0512757,60.38994240760803,2.239364849922894 +1739141221.071291,60.409942388534546,9.315342248238764,1739141221.071294,60.409942388534546,0.3085525000843097,1739141221.071297,60.409942388534546,103.0484328432551,1739141221.0712996,60.409942388534546,1.5627994568479542,1739141221.0713015,60.409942388534546,0.04024127846273089,1739141221.071303,60.409942388534546,-3.106997014868459,1739141221.0713046,60.409942388534546,0.15004022148610638,1739141221.0713058,60.409942388534546,0.019149382824304582,1739141221.0713067,60.409942388534546,2.3543734550962285,1739141221.0713086,60.409942388534546,0.0,1739141221.07131,60.409942388534546,0.11500860517333455,1739141221.0713115,60.409942388534546,3.156844988127798,1739141221.0713127,60.409942388534546,2.239364849922894 +1739141221.0923045,60.42994236946106,9.315342248238764,1739141221.0923069,60.42994236946106,0.3085525000843097,1739141221.0923097,60.42994236946106,103.0484328432551,1739141221.0923126,60.42994236946106,1.5627994568479542,1739141221.092314,60.42994236946106,0.04024127846273089,1739141221.0923162,60.42994236946106,-3.106997014868459,1739141221.0923173,60.42994236946106,0.15004022148610638,1739141221.0923188,60.42994236946106,0.019149382824304582,1739141221.09232,60.42994236946106,2.3543734550962285,1739141221.0923216,60.42994236946106,0.0,1739141221.092323,60.42994236946106,0.11500860517333455,1739141221.0923243,60.42994236946106,3.156844988127798,1739141221.0923257,60.42994236946106,2.239364849922894 +1739141221.1123316,60.44994235038757,9.315342248238764,1739141221.1123343,60.44994235038757,0.3085525000843097,1739141221.112337,60.44994235038757,103.0484328432551,1739141221.1123397,60.44994235038757,1.5627994568479542,1739141221.1123412,60.44994235038757,0.04024127846273089,1739141221.1123428,60.44994235038757,-3.106997014868459,1739141221.1123443,60.44994235038757,0.15004022148610638,1739141221.1123457,60.44994235038757,0.019149382824304582,1739141221.1123466,60.44994235038757,2.3543734550962285,1739141221.1123486,60.44994235038757,0.0,1739141221.11235,60.44994235038757,0.11500860517333455,1739141221.1123512,60.44994235038757,3.156844988127798,1739141221.1123526,60.44994235038757,2.239364849922894 +1739141221.131604,60.46994233131409,9.068418528326836,1739141221.1316066,60.46994233131409,0.3046585635629713,1739141221.1316097,60.46994233131409,103.33255968910653,1739141221.1316123,60.46994233131409,1.2411279310383592,1739141221.1316137,60.46994233131409,0.04380646669810467,1739141221.1316154,60.46994233131409,-3.1082790071011264,1739141221.1316168,60.46994233131409,0.13255919772773384,1739141221.131618,60.46994233131409,0.016598225906744975,1739141221.1316192,60.46994233131409,2.3708938899286682,1739141221.1316211,60.46994233131409,0.0,1739141221.1316226,60.46994233131409,0.12263902265207446,1739141221.131624,60.46994233131409,3.1579793733584616,1739141221.1316252,60.46994233131409,2.251888401224436 +1739141221.152181,60.4899423122406,9.068418528326836,1739141221.152184,60.4899423122406,0.3046585635629713,1739141221.1521876,60.4899423122406,103.33255968910653,1739141221.1521912,60.4899423122406,1.2411279310383592,1739141221.1521928,60.4899423122406,0.04380646669810467,1739141221.152195,60.4899423122406,-3.1082790071011264,1739141221.152197,60.4899423122406,0.13255919772773384,1739141221.1521983,60.4899423122406,0.016598225906744975,1739141221.1522,60.4899423122406,2.3708938899286682,1739141221.1522021,60.4899423122406,0.0,1739141221.152204,60.4899423122406,0.11900548870423222,1739141221.1522057,60.4899423122406,3.1579793733584616,1739141221.1522074,60.4899423122406,2.251888401224436 +1739141221.172307,60.509942293167114,9.068418528326836,1739141221.172311,60.509942293167114,0.3046585635629713,1739141221.1723151,60.509942293167114,103.33255968910653,1739141221.1723192,60.509942293167114,1.2411279310383592,1739141221.1723216,60.509942293167114,0.04380646669810467,1739141221.172324,60.509942293167114,-3.1082790071011264,1739141221.172326,60.509942293167114,0.13255919772773384,1739141221.1723282,60.509942293167114,0.016598225906744975,1739141221.17233,60.509942293167114,2.3708938899286682,1739141221.1723323,60.509942293167114,0.0,1739141221.1723347,60.509942293167114,0.11900548870423222,1739141221.1723366,60.509942293167114,3.1579793733584616,1739141221.1723387,60.509942293167114,2.251888401224436 +1739141221.1920888,60.52994227409363,9.068418528326836,1739141221.1920948,60.52994227409363,0.3046585635629713,1739141221.1921003,60.52994227409363,103.33255968910653,1739141221.192106,60.52994227409363,1.2411279310383592,1739141221.1921093,60.52994227409363,0.04380646669810467,1739141221.1921127,60.52994227409363,-3.1082790071011264,1739141221.192116,60.52994227409363,0.13255919772773384,1739141221.192119,60.52994227409363,0.016598225906744975,1739141221.1921217,60.52994227409363,2.3708938899286682,1739141221.1921256,60.52994227409363,0.0,1739141221.1921284,60.52994227409363,0.11900548870423222,1739141221.1921315,60.52994227409363,3.1579793733584616,1739141221.1921344,60.52994227409363,2.251888401224436 +1739141221.2114859,60.54994225502014,9.068418528326836,1739141221.2114897,60.54994225502014,0.3046585635629713,1739141221.2114942,60.54994225502014,103.33255968910653,1739141221.2114983,60.54994225502014,1.2411279310383592,1739141221.2115004,60.54994225502014,0.04380646669810467,1739141221.2115028,60.54994225502014,-3.1082790071011264,1739141221.211505,60.54994225502014,0.13255919772773384,1739141221.2115068,60.54994225502014,0.016598225906744975,1739141221.2115088,60.54994225502014,2.3708938899286682,1739141221.2115114,60.54994225502014,0.0,1739141221.2115133,60.54994225502014,0.11900548870423222,1739141221.2115154,60.54994225502014,3.1579793733584616,1739141221.211517,60.54994225502014,2.251888401224436 +1739141221.2321038,60.569942235946655,8.820092637982544,1739141221.232112,60.569942235946655,0.30046073788238203,1739141221.2321193,60.569942235946655,103.72098071054788,1739141221.2321272,60.569942235946655,0.8137782606338967,1739141221.232133,60.569942235946655,0.05363885871038146,1739141221.232141,60.569942235946655,-3.110774012237393,1739141221.2321482,60.569942235946655,0.10651169673082278,1739141221.2321546,60.569942235946655,0.012749057415699592,1739141221.2321603,60.569942235946655,2.395725369277339,1739141221.2321656,60.569942235946655,0.0,1739141221.2321732,60.569942235946655,0.14149886002354467,1739141221.2321796,60.569942235946655,3.1591137585891254,1739141221.2321823,60.569942235946655,2.2649376438041466 +1739141221.2513285,60.58994221687317,8.820092637982544,1739141221.2513318,60.58994221687317,0.30046073788238203,1739141221.2513354,60.58994221687317,103.72098071054788,1739141221.2513392,60.58994221687317,0.8137782606338967,1739141221.251341,60.58994221687317,0.05363885871038146,1739141221.2513433,60.58994221687317,-3.110774012237393,1739141221.2513452,60.58994221687317,0.10651169673082278,1739141221.2513468,60.58994221687317,0.012749057415699592,1739141221.2513485,60.58994221687317,2.395725369277339,1739141221.2513506,60.58994221687317,0.0,1739141221.2513523,60.58994221687317,0.1307877254731924,1739141221.2513537,60.58994221687317,3.1591137585891254,1739141221.2513556,60.58994221687317,2.2649376438041466 +1739141221.271388,60.60994219779968,8.820092637982544,1739141221.2713914,60.60994219779968,0.30046073788238203,1739141221.271395,60.60994219779968,103.72098071054788,1739141221.2713985,60.60994219779968,0.8137782606338967,1739141221.2714005,60.60994219779968,0.05363885871038146,1739141221.2714028,60.60994219779968,-3.110774012237393,1739141221.2714045,60.60994219779968,0.10651169673082278,1739141221.2714062,60.60994219779968,0.012749057415699592,1739141221.2714076,60.60994219779968,2.395725369277339,1739141221.2714097,60.60994219779968,0.0,1739141221.2714114,60.60994219779968,0.1307877254731924,1739141221.2714133,60.60994219779968,3.1591137585891254,1739141221.2714148,60.60994219779968,2.2649376438041466 +1739141221.2929065,60.629942178726196,8.820092637982544,1739141221.2929103,60.629942178726196,0.30046073788238203,1739141221.2929142,60.629942178726196,103.72098071054788,1739141221.2929177,60.629942178726196,0.8137782606338967,1739141221.2929194,60.629942178726196,0.05363885871038146,1739141221.2929215,60.629942178726196,-3.110774012237393,1739141221.2929235,60.629942178726196,0.10651169673082278,1739141221.292925,60.629942178726196,0.012749057415699592,1739141221.2929265,60.629942178726196,2.395725369277339,1739141221.2929285,60.629942178726196,0.0,1739141221.2929304,60.629942178726196,0.1307877254731924,1739141221.2929318,60.629942178726196,3.1591137585891254,1739141221.2929337,60.629942178726196,2.2649376438041466 +1739141221.3123665,60.64994215965271,8.820092637982544,1739141221.3123698,60.64994215965271,0.30046073788238203,1739141221.3123734,60.64994215965271,103.72098071054788,1739141221.312377,60.64994215965271,0.8137782606338967,1739141221.3123786,60.64994215965271,0.05363885871038146,1739141221.312381,60.64994215965271,-3.110774012237393,1739141221.3123827,60.64994215965271,0.10651169673082278,1739141221.3123844,60.64994215965271,0.012749057415699592,1739141221.3123858,60.64994215965271,2.395725369277339,1739141221.312388,60.64994215965271,0.0,1739141221.3123896,60.64994215965271,0.1307877254731924,1739141221.3123913,60.64994215965271,3.1591137585891254,1739141221.3123927,60.64994215965271,2.2649376438041466 +1739141221.331797,60.669942140579224,8.820092637982544,1739141221.3318002,60.669942140579224,0.30046073788238203,1739141221.3318038,60.669942140579224,103.72098071054788,1739141221.3318079,60.669942140579224,0.8137782606338967,1739141221.3318095,60.669942140579224,0.05363885871038146,1739141221.3318117,60.669942140579224,-3.110774012237393,1739141221.3318133,60.669942140579224,0.10651169673082278,1739141221.331815,60.669942140579224,0.012749057415699592,1739141221.3318167,60.669942140579224,2.395725369277339,1739141221.3318188,60.669942140579224,0.0,1739141221.3318205,60.669942140579224,0.1307877254731924,1739141221.3318222,60.669942140579224,3.1591137585891254,1739141221.3318238,60.669942140579224,2.2649376438041466 +1739141221.3513987,60.68994212150574,8.570252611067307,1739141221.351402,60.68994212150574,0.2959538016018115,1739141221.3514056,60.68994212150574,104.4703928187849,1739141221.3514092,60.68994212150574,0.02121785785939112,1739141221.3514109,60.68994212150574,0.065,1739141221.3514132,60.68994212150574,-3.1145840323925644,1739141221.3514147,60.68994212150574,0.07143643011548895,1739141221.3514166,60.68994212150574,0.007501170757454201,1739141221.3514183,60.68994212150574,2.4295745502641557,1739141221.3514204,60.68994212150574,0.0,1739141221.3514225,60.68994212150574,0.167668828622009,1739141221.3514242,60.68994212150574,3.160248143819789,1739141221.351426,60.68994212150574,2.2794681604862173 +1739141221.3726633,60.70994210243225,8.570252611067307,1739141221.3726668,60.70994210243225,0.2959538016018115,1739141221.3726704,60.70994210243225,104.4703928187849,1739141221.372674,60.70994210243225,0.02121785785939112,1739141221.372676,60.70994210243225,0.065,1739141221.3726778,60.70994210243225,-3.1145840323925644,1739141221.37268,60.70994210243225,0.07143643011548895,1739141221.3726814,60.70994210243225,0.007501170757454201,1739141221.372683,60.70994210243225,2.4295745502641557,1739141221.3726852,60.70994210243225,0.0,1739141221.372687,60.70994210243225,0.15010638977793844,1739141221.3726892,60.70994210243225,3.160248143819789,1739141221.3726907,60.70994210243225,2.2794681604862173 +1739141221.3911164,60.729942083358765,8.570252611067307,1739141221.391119,60.729942083358765,0.2959538016018115,1739141221.391122,60.729942083358765,104.4703928187849,1739141221.3911252,60.729942083358765,0.02121785785939112,1739141221.3911269,60.729942083358765,0.065,1739141221.3911285,60.729942083358765,-3.1145840323925644,1739141221.3911307,60.729942083358765,0.07143643011548895,1739141221.391132,60.729942083358765,0.007501170757454201,1739141221.3911335,60.729942083358765,2.4295745502641557,1739141221.3911352,60.729942083358765,0.0,1739141221.391137,60.729942083358765,0.15010638977793844,1739141221.3911383,60.729942083358765,3.160248143819789,1739141221.3911395,60.729942083358765,2.2794681604862173 +1739141221.4106066,60.74994206428528,8.570252611067307,1739141221.4106112,60.74994206428528,0.2959538016018115,1739141221.4106174,60.74994206428528,104.4703928187849,1739141221.4106214,60.74994206428528,0.02121785785939112,1739141221.4106236,60.74994206428528,0.065,1739141221.4106257,60.74994206428528,-3.1145840323925644,1739141221.4106276,60.74994206428528,0.07143643011548895,1739141221.4106297,60.74994206428528,0.007501170757454201,1739141221.4106314,60.74994206428528,2.4295745502641557,1739141221.4106338,60.74994206428528,0.0,1739141221.4106357,60.74994206428528,0.15010638977793844,1739141221.4106376,60.74994206428528,3.160248143819789,1739141221.4106393,60.74994206428528,2.2794681604862173 +1739141221.4318824,60.76994204521179,8.570252611067307,1739141221.4318852,60.76994204521179,0.2959538016018115,1739141221.431888,60.76994204521179,104.4703928187849,1739141221.431891,60.76994204521179,0.02121785785939112,1739141221.4318924,60.76994204521179,0.065,1739141221.4318943,60.76994204521179,-3.1145840323925644,1739141221.4318955,60.76994204521179,0.07143643011548895,1739141221.4318972,60.76994204521179,0.007501170757454201,1739141221.4318984,60.76994204521179,2.4295745502641557,1739141221.4318998,60.76994204521179,0.0,1739141221.4319012,60.76994204521179,0.15010638977793844,1739141221.4319024,60.76994204521179,3.160248143819789,1739141221.4319036,60.76994204521179,2.2794681604862173 +1739141221.4562352,60.789942026138306,8.318725006876091,1739141221.4562445,60.789942026138306,0.2911309726028497,1739141221.456255,60.789942026138306,104.49931367043791,1739141221.4562647,60.789942026138306,-0.05743172606272351,1739141221.4562693,60.789942026138306,0.065,1739141221.4562752,60.789942026138306,-3.1146022251307364,1739141221.45628,60.789942026138306,0.060334414266086524,1739141221.4562848,60.789942026138306,0.006599630414635802,1739141221.4562893,60.789942026138306,2.440387812360853,1739141221.4562955,60.789942026138306,0.0,1739141221.4563003,60.789942026138306,0.13910432824946078,1739141221.4563048,60.789942026138306,3.161382529050453,1739141221.4563093,60.789942026138306,2.2960444045759205 +1739141221.4960008,60.819941997528076,8.318725006876091,1739141221.49601,60.819941997528076,0.2911309726028497,1739141221.4960203,60.819941997528076,104.49931367043791,1739141221.4960308,60.819941997528076,-0.05743172606272351,1739141221.4960356,60.819941997528076,0.065,1739141221.4960418,60.819941997528076,-3.1146022251307364,1739141221.4960475,60.819941997528076,0.060334414266086524,1739141221.4960635,60.819941997528076,0.006599630414635802,1739141221.4960802,60.819941997528076,2.440387812360853,1739141221.4960938,60.819941997528076,0.0,1739141221.4961104,60.819941997528076,0.1443434077849326,1739141221.4961228,60.819941997528076,3.161382529050453,1739141221.496137,60.819941997528076,2.2960444045759205 +1739141221.5147047,60.83994197845459,8.318725006876091,1739141221.5147095,60.83994197845459,0.2911309726028497,1739141221.5147152,60.83994197845459,104.49931367043791,1739141221.5147204,60.83994197845459,-0.05743172606272351,1739141221.5147233,60.83994197845459,0.065,1739141221.514727,60.83994197845459,-3.1146022251307364,1739141221.51473,60.83994197845459,0.060334414266086524,1739141221.5147328,60.83994197845459,0.006599630414635802,1739141221.5147355,60.83994197845459,2.440387812360853,1739141221.5147383,60.83994197845459,0.0,1739141221.5147414,60.83994197845459,0.1443434077849326,1739141221.514744,60.83994197845459,3.161382529050453,1739141221.5147467,60.83994197845459,2.2960444045759205 +1739141221.5317483,60.8599419593811,8.318725006876091,1739141221.5317514,60.8599419593811,0.2911309726028497,1739141221.531755,60.8599419593811,104.49931367043791,1739141221.531758,60.8599419593811,-0.05743172606272351,1739141221.5317595,60.8599419593811,0.065,1739141221.5317616,60.8599419593811,-3.1146022251307364,1739141221.5317633,60.8599419593811,0.060334414266086524,1739141221.5317647,60.8599419593811,0.006599630414635802,1739141221.5317662,60.8599419593811,2.440387812360853,1739141221.531768,60.8599419593811,0.0,1739141221.5317698,60.8599419593811,0.1443434077849326,1739141221.5317714,60.8599419593811,3.161382529050453,1739141221.5317726,60.8599419593811,2.2960444045759205 +1739141221.5507035,60.87994194030762,8.318725006876091,1739141221.550706,60.87994194030762,0.2911309726028497,1739141221.550733,60.87994194030762,104.49931367043791,1739141221.5507362,60.87994194030762,-0.05743172606272351,1739141221.5507374,60.87994194030762,0.065,1739141221.5507393,60.87994194030762,-3.1146022251307364,1739141221.5507405,60.87994194030762,0.060334414266086524,1739141221.55076,60.87994194030762,0.006599630414635802,1739141221.550761,60.87994194030762,2.440387812360853,1739141221.5507624,60.87994194030762,0.0,1739141221.550764,60.87994194030762,0.1443434077849326,1739141221.5507653,60.87994194030762,3.161382529050453,1739141221.5507662,60.87994194030762,2.2960444045759205 +1739141221.570512,60.89994192123413,8.065434849478747,1739141221.5705147,60.89994192123413,0.28598691935385556,1739141221.5705175,60.89994192123413,104.52843689448535,1739141221.5705204,60.89994192123413,-0.13349278553459198,1739141221.5705218,60.89994192123413,0.065,1739141221.5705237,60.89994192123413,-3.114646028508904,1739141221.5705254,60.89994192123413,0.04939456346800275,1739141221.5705268,60.89994192123413,0.005639107389911373,1739141221.570528,60.89994192123413,2.451090203217155,1739141221.5705295,60.89994192123413,0.0,1739141221.5705311,60.89994192123413,0.1349057089545599,1739141221.5705323,60.89994192123413,3.1625169142811167,1739141221.5705335,60.89994192123413,2.311690349717396 +1739141221.5909455,60.919941902160645,8.065434849478747,1739141221.5909479,60.919941902160645,0.28598691935385556,1739141221.5909507,60.919941902160645,104.52843689448535,1739141221.590953,60.919941902160645,-0.13349278553459198,1739141221.5909545,60.919941902160645,0.065,1739141221.590956,60.919941902160645,-3.114646028508904,1739141221.5909574,60.919941902160645,0.04939456346800275,1739141221.5909586,60.919941902160645,0.005639107389911373,1739141221.5909595,60.919941902160645,2.451090203217155,1739141221.5909612,60.919941902160645,0.0,1739141221.5909624,60.919941902160645,0.13939985349975892,1739141221.5909636,60.919941902160645,3.1625169142811167,1739141221.590965,60.919941902160645,2.311690349717396 +1739141221.610727,60.93994188308716,8.065434849478747,1739141221.6107292,60.93994188308716,0.28598691935385556,1739141221.610732,60.93994188308716,104.52843689448535,1739141221.610735,60.93994188308716,-0.13349278553459198,1739141221.6107361,60.93994188308716,0.065,1739141221.6107376,60.93994188308716,-3.114646028508904,1739141221.610739,60.93994188308716,0.04939456346800275,1739141221.6107402,60.93994188308716,0.005639107389911373,1739141221.6107411,60.93994188308716,2.451090203217155,1739141221.6107428,60.93994188308716,0.0,1739141221.6107442,60.93994188308716,0.13939985349975892,1739141221.6107457,60.93994188308716,3.1625169142811167,1739141221.6107469,60.93994188308716,2.311690349717396 +1739141221.6306531,60.95994186401367,8.065434849478747,1739141221.6306562,60.95994186401367,0.28598691935385556,1739141221.6306593,60.95994186401367,104.52843689448535,1739141221.630662,60.95994186401367,-0.13349278553459198,1739141221.6306634,60.95994186401367,0.065,1739141221.6306653,60.95994186401367,-3.114646028508904,1739141221.6306667,60.95994186401367,0.04939456346800275,1739141221.630668,60.95994186401367,0.005639107389911373,1739141221.6306696,60.95994186401367,2.451090203217155,1739141221.630671,60.95994186401367,0.0,1739141221.630673,60.95994186401367,0.13939985349975892,1739141221.6306741,60.95994186401367,3.1625169142811167,1739141221.6306756,60.95994186401367,2.311690349717396 +1739141221.6505203,60.979941844940186,8.065434849478747,1739141221.6505227,60.979941844940186,0.28598691935385556,1739141221.6505253,60.979941844940186,104.52843689448535,1739141221.6505282,60.979941844940186,-0.13349278553459198,1739141221.6505299,60.979941844940186,0.065,1739141221.6505313,60.979941844940186,-3.114646028508904,1739141221.650533,60.979941844940186,0.04939456346800275,1739141221.6505518,60.979941844940186,0.005639107389911373,1739141221.6505532,60.979941844940186,2.451090203217155,1739141221.6505551,60.979941844940186,0.0,1739141221.6505566,60.979941844940186,0.13939985349975892,1739141221.650558,60.979941844940186,3.1625169142811167,1739141221.6505592,60.979941844940186,2.311690349717396 +1739141221.675869,60.9999418258667,8.065434849478747,1739141221.6758778,60.9999418258667,0.28598691935385556,1739141221.6758876,60.9999418258667,104.52843689448535,1739141221.6758974,60.9999418258667,-0.13349278553459198,1739141221.6759021,60.9999418258667,0.065,1739141221.675908,60.9999418258667,-3.114646028508904,1739141221.6759126,60.9999418258667,0.04939456346800275,1739141221.6759174,60.9999418258667,0.005639107389911373,1739141221.6759217,60.9999418258667,2.451090203217155,1739141221.6759279,60.9999418258667,0.0,1739141221.675933,60.9999418258667,0.13939985349975892,1739141221.6759377,60.9999418258667,3.1625169142811167,1739141221.6759424,60.9999418258667,2.311690349717396 +1739141221.7028556,61.01994180679321,7.810451558608905,1739141221.702865,61.01994180679321,0.2805191109177052,1739141221.7028756,61.01994180679321,104.65924233375992,1739141221.7028854,61.01994180679321,-0.30981205506761667,1739141221.7028902,61.01994180679321,0.065,1739141221.7028964,61.01994180679321,-3.1150579821475413,1739141221.7029014,61.01994180679321,0.03635918509663268,1739141221.7029057,61.01994180679321,0.004231837655569576,1739141221.70291,61.01994180679321,2.4639039358453383,1739141221.7029157,61.01994180679321,0.0,1739141221.7029204,61.01994180679321,0.13489908539969722,1739141221.7029252,61.01994180679321,3.1636512995117805,1739141221.70293,61.01994180679321,2.3268616264702158 +1739141221.72192,61.03994178771973,7.810451558608905,1739141221.7219284,61.03994178771973,0.2805191109177052,1739141221.7219381,61.03994178771973,104.65924233375992,1739141221.7219477,61.03994178771973,-0.30981205506761667,1739141221.7219527,61.03994178771973,0.065,1739141221.7219586,61.03994178771973,-3.1150579821475413,1739141221.7219632,61.03994178771973,0.03635918509663268,1739141221.721968,61.03994178771973,0.004231837655569576,1739141221.7219722,61.03994178771973,2.4639039358453383,1739141221.7219784,61.03994178771973,0.0,1739141221.721983,61.03994178771973,0.13704230937512252,1739141221.7219875,61.03994178771973,3.1636512995117805,1739141221.7219923,61.03994178771973,2.3268616264702158 +1739141221.745381,61.05994176864624,7.810451558608905,1739141221.74539,61.05994176864624,0.2805191109177052,1739141221.7453992,61.05994176864624,104.65924233375992,1739141221.745409,61.05994176864624,-0.30981205506761667,1739141221.7454138,61.05994176864624,0.065,1739141221.7454193,61.05994176864624,-3.1150579821475413,1739141221.745424,61.05994176864624,0.03635918509663268,1739141221.7454286,61.05994176864624,0.004231837655569576,1739141221.7454329,61.05994176864624,2.4639039358453383,1739141221.7454388,61.05994176864624,0.0,1739141221.7454436,61.05994176864624,0.13704230937512252,1739141221.745448,61.05994176864624,3.1636512995117805,1739141221.745453,61.05994176864624,2.3268616264702158 +1739141221.7734697,61.08994174003601,7.810451558608905,1739141221.7734742,61.08994174003601,0.2805191109177052,1739141221.7734797,61.08994174003601,104.65924233375992,1739141221.773485,61.08994174003601,-0.30981205506761667,1739141221.7734876,61.08994174003601,0.065,1739141221.7734907,61.08994174003601,-3.1150579821475413,1739141221.7734935,61.08994174003601,0.03635918509663268,1739141221.773496,61.08994174003601,0.004231837655569576,1739141221.773498,61.08994174003601,2.4639039358453383,1739141221.7735014,61.08994174003601,0.0,1739141221.773504,61.08994174003601,0.13704230937512252,1739141221.7735066,61.08994174003601,3.1636512995117805,1739141221.7735088,61.08994174003601,2.3268616264702158 +1739141221.7918494,61.11994171142578,7.553810664886683,1739141221.791853,61.11994171142578,0.2747244896556804,1739141221.7918575,61.11994171142578,104.79868242837246,1739141221.7918615,61.11994171142578,-0.49424766074674364,1739141221.791864,61.11994171142578,0.065,1739141221.7918663,61.11994171142578,-3.115539532724774,1739141221.7918687,61.11994171142578,0.023025951604055257,1739141221.7918708,61.11994171142578,0.002728359789413711,1739141221.791873,61.11994171142578,2.477079762480792,1739141221.7918756,61.11994171142578,0.0,1739141221.791878,61.11994171142578,0.13356265160203062,1739141221.79188,61.11994171142578,3.1647856847424443,1739141221.791882,61.11994171142578,2.3418601301590787 +1739141221.812673,61.139941692352295,7.553810664886683,1739141221.8126774,61.139941692352295,0.2747244896556804,1739141221.8126814,61.139941692352295,104.79868242837246,1739141221.8126853,61.139941692352295,-0.49424766074674364,1739141221.8126872,61.139941692352295,0.065,1739141221.8126893,61.139941692352295,-3.115539532724774,1739141221.8126915,61.139941692352295,0.023025951604055257,1739141221.8126934,61.139941692352295,0.002728359789413711,1739141221.812695,61.139941692352295,2.477079762480792,1739141221.8126976,61.139941692352295,0.0,1739141221.8126996,61.139941692352295,0.1352196323217134,1739141221.8127017,61.139941692352295,3.1647856847424443,1739141221.8127038,61.139941692352295,2.3418601301590787 +1739141221.8325162,61.15994167327881,7.553810664886683,1739141221.8325222,61.15994167327881,0.2747244896556804,1739141221.8325279,61.15994167327881,104.79868242837246,1739141221.8325334,61.15994167327881,-0.49424766074674364,1739141221.8325362,61.15994167327881,0.065,1739141221.8325398,61.15994167327881,-3.115539532724774,1739141221.8325438,61.15994167327881,0.023025951604055257,1739141221.8325472,61.15994167327881,0.002728359789413711,1739141221.8325503,61.15994167327881,2.477079762480792,1739141221.8325548,61.15994167327881,0.0,1739141221.8325586,61.15994167327881,0.1352196323217134,1739141221.832562,61.15994167327881,3.1647856847424443,1739141221.8325653,61.15994167327881,2.3418601301590787 +1739141221.851302,61.17994165420532,7.553810664886683,1739141221.8513057,61.17994165420532,0.2747244896556804,1739141221.8513095,61.17994165420532,104.79868242837246,1739141221.8513126,61.17994165420532,-0.49424766074674364,1739141221.8513148,61.17994165420532,0.065,1739141221.8513165,61.17994165420532,-3.115539532724774,1739141221.8513181,61.17994165420532,0.023025951604055257,1739141221.8513196,61.17994165420532,0.002728359789413711,1739141221.8513207,61.17994165420532,2.477079762480792,1739141221.851323,61.17994165420532,0.0,1739141221.8513246,61.17994165420532,0.1352196323217134,1739141221.8513265,61.17994165420532,3.1647856847424443,1739141221.8513284,61.17994165420532,2.3418601301590787 +1739141221.8714175,61.199941635131836,7.553810664886683,1739141221.8714213,61.199941635131836,0.2747244896556804,1739141221.8714247,61.199941635131836,104.79868242837246,1739141221.8714275,61.199941635131836,-0.49424766074674364,1739141221.8714294,61.199941635131836,0.065,1739141221.8714316,61.199941635131836,-3.115539532724774,1739141221.8714333,61.199941635131836,0.023025951604055257,1739141221.8714345,61.199941635131836,0.002728359789413711,1739141221.871436,61.199941635131836,2.477079762480792,1739141221.871438,61.199941635131836,0.0,1739141221.8714402,61.199941635131836,0.1352196323217134,1739141221.8714414,61.199941635131836,3.1647856847424443,1739141221.871443,61.199941635131836,2.3418601301590787 +1739141221.8911204,61.21994161605835,7.553810664886683,1739141221.8911235,61.21994161605835,0.2747244896556804,1739141221.8911266,61.21994161605835,104.79868242837246,1739141221.8911293,61.21994161605835,-0.49424766074674364,1739141221.8911312,61.21994161605835,0.065,1739141221.8911328,61.21994161605835,-3.115539532724774,1739141221.891135,61.21994161605835,0.023025951604055257,1739141221.8911364,61.21994161605835,0.002728359789413711,1739141221.8911376,61.21994161605835,2.477079762480792,1739141221.8911393,61.21994161605835,0.0,1739141221.8911412,61.21994161605835,0.1352196323217134,1739141221.8911428,61.21994161605835,3.1647856847424443,1739141221.8911445,61.21994161605835,2.3418601301590787 +1739141221.9217753,61.23994159698486,7.295540257086282,1739141221.9217849,61.23994159698486,0.2685999440796767,1739141221.9217951,61.23994159698486,105.22019365295908,1739141221.9218044,61.23994159698486,-0.960067218744832,1739141221.9218094,61.23994159698486,0.065,1739141221.9218154,61.23994159698486,-3.116935633230168,1739141221.92182,61.23994159698486,0.0027219083771818802,1739141221.9218245,61.23994159698486,0.00030652971771061635,1739141221.9218297,61.23994159698486,2.4972795728422463,1739141221.9218352,61.23994159698486,0.0,1739141221.9218404,61.23994159698486,0.14558669918519807,1739141221.921845,61.23994159698486,3.165920069973108,1739141221.9218495,61.23994159698486,2.3566295746295673 +1739141221.9351656,61.25994157791138,7.295540257086282,1739141221.9351714,61.25994157791138,0.2685999440796767,1739141221.9351776,61.25994157791138,105.22019365295908,1739141221.9351828,61.25994157791138,-0.960067218744832,1739141221.9351857,61.25994157791138,0.065,1739141221.9351892,61.25994157791138,-3.116935633230168,1739141221.9351923,61.25994157791138,0.0027219083771818802,1739141221.935195,61.25994157791138,0.00030652971771061635,1739141221.9351974,61.25994157791138,2.4972795728422463,1739141221.935201,61.25994157791138,0.0,1739141221.9352038,61.25994157791138,0.14064999821267898,1739141221.9352064,61.25994157791138,3.165920069973108,1739141221.935209,61.25994157791138,2.3566295746295673 +1739141221.9725099,61.299941539764404,7.295540257086282,1739141221.9725137,61.299941539764404,0.2685999440796767,1739141221.972518,61.299941539764404,105.22019365295908,1739141221.9725218,61.299941539764404,-0.960067218744832,1739141221.9725235,61.299941539764404,0.065,1739141221.9725263,61.299941539764404,-3.116935633230168,1739141221.9725282,61.299941539764404,0.0027219083771818802,1739141221.97253,61.299941539764404,0.00030652971771061635,1739141221.9725318,61.299941539764404,2.4972795728422463,1739141221.972534,61.299941539764404,0.0,1739141221.972536,61.299941539764404,0.14064999821267898,1739141221.9725378,61.299941539764404,3.165920069973108,1739141221.97254,61.299941539764404,2.3566295746295673 +1739141221.9927933,61.31994152069092,7.295540257086282,1739141221.992797,61.31994152069092,0.2685999440796767,1739141221.992801,61.31994152069092,105.22019365295908,1739141221.9928048,61.31994152069092,-0.960067218744832,1739141221.992807,61.31994152069092,0.065,1739141221.9928093,61.31994152069092,-3.116935633230168,1739141221.9928112,61.31994152069092,0.0027219083771818802,1739141221.9928133,61.31994152069092,0.00030652971771061635,1739141221.9928148,61.31994152069092,2.4972795728422463,1739141221.992817,61.31994152069092,0.0,1739141221.9928188,61.31994152069092,0.14064999821267898,1739141221.9928207,61.31994152069092,3.165920069973108,1739141221.9928226,61.31994152069092,2.3566295746295673 +1739141222.0126436,61.33994150161743,7.035618398726836,1739141222.0126472,61.33994150161743,0.2621412050194749,1739141222.0126517,61.33994150161743,105.44907744135243,1739141222.0126557,61.33994150161743,-1.2352303895529313,1739141222.0126576,61.33994150161743,0.065,1739141222.01266,61.33994150161743,-3.1177614981368715,1739141222.012662,61.33994150161743,-0.013490652499534642,1739141222.0126638,61.33994150161743,-0.0015137261284729256,1739141222.0126653,61.33994150161743,2.4865456816558633,1739141222.0126677,61.33994150161743,0.0,1739141222.0126693,61.33994150161743,0.09070748536703377,1739141222.0126717,61.33994150161743,3.167054455203772,1739141222.0126739,61.33994150161743,2.3720560354344844 +1739141222.0325916,61.359941482543945,7.035618398726836,1739141222.0325956,61.359941482543945,0.2621412050194749,1739141222.0326002,61.359941482543945,105.44907744135243,1739141222.0326042,61.359941482543945,-1.2352303895529313,1739141222.0326056,61.359941482543945,0.065,1739141222.0326083,61.359941482543945,-3.1177614981368715,1739141222.03261,61.359941482543945,-0.013490652499534642,1739141222.0326118,61.359941482543945,-0.0015137261284729256,1739141222.0326135,61.359941482543945,2.4865456816558633,1739141222.032616,61.359941482543945,0.0,1739141222.0326178,61.359941482543945,0.11448964622137892,1739141222.0326197,61.359941482543945,3.167054455203772,1739141222.0326214,61.359941482543945,2.3720560354344844 +1739141222.0577857,61.37994146347046,7.035618398726836,1739141222.0577948,61.37994146347046,0.2621412050194749,1739141222.0578043,61.37994146347046,105.44907744135243,1739141222.0578144,61.37994146347046,-1.2352303895529313,1739141222.057819,61.37994146347046,0.065,1739141222.057825,61.37994146347046,-3.1177614981368715,1739141222.0578296,61.37994146347046,-0.013490652499534642,1739141222.0578341,61.37994146347046,-0.0015137261284729256,1739141222.057839,61.37994146347046,2.4865456816558633,1739141222.0578444,61.37994146347046,0.0,1739141222.0578496,61.37994146347046,0.11448964622137892,1739141222.057854,61.37994146347046,3.167054455203772,1739141222.0578585,61.37994146347046,2.3720560354344844 +1739141222.0772736,61.39994144439697,7.035618398726836,1739141222.077282,61.39994144439697,0.2621412050194749,1739141222.0772924,61.39994144439697,105.44907744135243,1739141222.0773017,61.39994144439697,-1.2352303895529313,1739141222.077307,61.39994144439697,0.065,1739141222.077313,61.39994144439697,-3.1177614981368715,1739141222.0773177,61.39994144439697,-0.013490652499534642,1739141222.0773222,61.39994144439697,-0.0015137261284729256,1739141222.0773265,61.39994144439697,2.4865456816558633,1739141222.0773323,61.39994144439697,0.0,1739141222.0773373,61.39994144439697,0.11448964622137892,1739141222.077342,61.39994144439697,3.167054455203772,1739141222.0773466,61.39994144439697,2.3720560354344844 +1739141222.1049588,61.419941425323486,7.035618398726836,1739141222.104965,61.419941425323486,0.2621412050194749,1739141222.1049721,61.419941425323486,105.44907744135243,1739141222.1049795,61.419941425323486,-1.2352303895529313,1739141222.104983,61.419941425323486,0.065,1739141222.1049871,61.419941425323486,-3.1177614981368715,1739141222.1049905,61.419941425323486,-0.013490652499534642,1739141222.1049936,61.419941425323486,-0.0015137261284729256,1739141222.1049967,61.419941425323486,2.4865456816558633,1739141222.1050007,61.419941425323486,0.0,1739141222.105004,61.419941425323486,0.11448964622137892,1739141222.1050074,61.419941425323486,3.167054455203772,1739141222.1050105,61.419941425323486,2.3720560354344844 +1739141222.1272864,61.44994139671326,6.774197627576832,1739141222.1272933,61.44994139671326,0.2553485109374849,1739141222.1273005,61.44994139671326,105.7785094171055,1739141222.127308,61.44994139671326,-1.6008465030934569,1739141222.1273115,61.44994139671326,0.065,1739141222.127316,61.44994139671326,-3.1188685052335043,1739141222.1273198,61.44994139671326,-0.032436786789793,1739141222.1273232,61.44994139671326,-0.0035497711211840317,1739141222.1273263,61.44994139671326,2.4677727350965046,1739141222.1273303,61.44994139671326,0.0,1739141222.1273344,61.44994139671326,0.05562408837428473,1739141222.1273377,61.44994139671326,3.1681888404344356,1739141222.1273408,61.44994139671326,2.384117414696969 +1739141222.1473103,61.46994137763977,6.774197627576832,1739141222.147314,61.46994137763977,0.2553485109374849,1739141222.1473188,61.46994137763977,105.7785094171055,1739141222.1473227,61.46994137763977,-1.6008465030934569,1739141222.1473243,61.46994137763977,0.065,1739141222.1473272,61.46994137763977,-3.1188685052335043,1739141222.1473293,61.46994137763977,-0.032436786789793,1739141222.147331,61.46994137763977,-0.0035497711211840317,1739141222.1473327,61.46994137763977,2.4677727350965046,1739141222.1473358,61.46994137763977,0.0,1739141222.1473377,61.46994137763977,0.0836553203995356,1739141222.1473396,61.46994137763977,3.1681888404344356,1739141222.147341,61.46994137763977,2.384117414696969 +1739141222.1667185,61.489941358566284,6.774197627576832,1739141222.1667213,61.489941358566284,0.2553485109374849,1739141222.1667247,61.489941358566284,105.7785094171055,1739141222.166727,61.489941358566284,-1.6008465030934569,1739141222.1667287,61.489941358566284,0.065,1739141222.1667304,61.489941358566284,-3.1188685052335043,1739141222.166732,61.489941358566284,-0.032436786789793,1739141222.1667335,61.489941358566284,-0.0035497711211840317,1739141222.166735,61.489941358566284,2.4677727350965046,1739141222.1667364,61.489941358566284,0.0,1739141222.166738,61.489941358566284,0.0836553203995356,1739141222.1667392,61.489941358566284,3.1681888404344356,1739141222.1667404,61.489941358566284,2.384117414696969 +1739141222.186797,61.5099413394928,6.774197627576832,1739141222.1867998,61.5099413394928,0.2553485109374849,1739141222.1868029,61.5099413394928,105.7785094171055,1739141222.1868057,61.5099413394928,-1.6008465030934569,1739141222.1868074,61.5099413394928,0.065,1739141222.186809,61.5099413394928,-3.1188685052335043,1739141222.186811,61.5099413394928,-0.032436786789793,1739141222.1868122,61.5099413394928,-0.0035497711211840317,1739141222.1868134,61.5099413394928,2.4677727350965046,1739141222.1868153,61.5099413394928,0.0,1739141222.186817,61.5099413394928,0.0836553203995356,1739141222.1868184,61.5099413394928,3.1681888404344356,1739141222.1868198,61.5099413394928,2.384117414696969 +1739141222.2067335,61.52994132041931,6.774197627576832,1739141222.2067378,61.52994132041931,0.2553485109374849,1739141222.2067423,61.52994132041931,105.7785094171055,1739141222.2067487,61.52994132041931,-1.6008465030934569,1739141222.2067544,61.52994132041931,0.065,1739141222.2067597,61.52994132041931,-3.1188685052335043,1739141222.2067626,61.52994132041931,-0.032436786789793,1739141222.2067652,61.52994132041931,-0.0035497711211840317,1739141222.2067673,61.52994132041931,2.4677727350965046,1739141222.2067702,61.52994132041931,0.0,1739141222.206773,61.52994132041931,0.0836553203995356,1739141222.2067757,61.52994132041931,3.1681888404344356,1739141222.2067778,61.52994132041931,2.384117414696969 +1739141222.227448,61.549941301345825,6.774197627576832,1739141222.2274504,61.549941301345825,0.2553485109374849,1739141222.2274535,61.549941301345825,105.7785094171055,1739141222.2274563,61.549941301345825,-1.6008465030934569,1739141222.2274575,61.549941301345825,0.065,1739141222.227459,61.549941301345825,-3.1188685052335043,1739141222.2274606,61.549941301345825,-0.032436786789793,1739141222.2274616,61.549941301345825,-0.0035497711211840317,1739141222.227463,61.549941301345825,2.4677727350965046,1739141222.2274644,61.549941301345825,0.0,1739141222.2274659,61.549941301345825,0.0836553203995356,1739141222.2274673,61.549941301345825,3.1681888404344356,1739141222.2274685,61.549941301345825,2.384117414696969 +1739141222.2471924,61.56994128227234,6.511635536115852,1739141222.2471955,61.56994128227234,0.2482281404972877,1739141222.2471988,61.56994128227234,106.10629365802454,1739141222.2472014,61.56994128227234,-1.9544361648175292,1739141222.2472034,61.56994128227234,0.065,1739141222.247205,61.56994128227234,-3.1199533919876803,1739141222.2472064,61.56994128227234,-0.05158122849412922,1739141222.2472079,61.56994128227234,-0.005524400404116838,1739141222.2472093,61.56994128227234,2.4489472552463485,1739141222.247211,61.56994128227234,0.0,1739141222.2472126,61.56994128227234,0.03129411275811084,1739141222.2472138,61.56994128227234,3.1693232256650994,1739141222.247215,61.56994128227234,2.3927192216319764 +1739141222.2665985,61.58994126319885,6.511635536115852,1739141222.2666028,61.58994126319885,0.2482281404972877,1739141222.2666073,61.58994126319885,106.10629365802454,1739141222.2666101,61.58994126319885,-1.9544361648175292,1739141222.2666118,61.58994126319885,0.065,1739141222.2666135,61.58994126319885,-3.1199533919876803,1739141222.2666152,61.58994126319885,-0.05158122849412922,1739141222.2666166,61.58994126319885,-0.005524400404116838,1739141222.2666175,61.58994126319885,2.4489472552463485,1739141222.2666194,61.58994126319885,0.0,1739141222.2666209,61.58994126319885,0.05622803361437212,1739141222.266622,61.58994126319885,3.1693232256650994,1739141222.2666235,61.58994126319885,2.3927192216319764 +1739141222.2865732,61.609941244125366,6.511635536115852,1739141222.2865753,61.609941244125366,0.2482281404972877,1739141222.286578,61.609941244125366,106.10629365802454,1739141222.2865806,61.609941244125366,-1.9544361648175292,1739141222.286582,61.609941244125366,0.065,1739141222.2865837,61.609941244125366,-3.1199533919876803,1739141222.2865849,61.609941244125366,-0.05158122849412922,1739141222.286586,61.609941244125366,-0.005524400404116838,1739141222.2865875,61.609941244125366,2.4489472552463485,1739141222.286589,61.609941244125366,0.0,1739141222.2865906,61.609941244125366,0.05622803361437212,1739141222.2865915,61.609941244125366,3.1693232256650994,1739141222.286593,61.609941244125366,2.3927192216319764 +1739141222.3066936,61.62994122505188,6.511635536115852,1739141222.3066964,61.62994122505188,0.2482281404972877,1739141222.306699,61.62994122505188,106.10629365802454,1739141222.306702,61.62994122505188,-1.9544361648175292,1739141222.306703,61.62994122505188,0.065,1739141222.306705,61.62994122505188,-3.1199533919876803,1739141222.3067064,61.62994122505188,-0.05158122849412922,1739141222.3067076,61.62994122505188,-0.005524400404116838,1739141222.306709,61.62994122505188,2.4489472552463485,1739141222.3067105,61.62994122505188,0.0,1739141222.3067122,61.62994122505188,0.05622803361437212,1739141222.3067133,61.62994122505188,3.1693232256650994,1739141222.3067145,61.62994122505188,2.3927192216319764 +1739141222.326994,61.649941205978394,6.511635536115852,1739141222.3269966,61.649941205978394,0.2482281404972877,1739141222.3269997,61.649941205978394,106.10629365802454,1739141222.327002,61.649941205978394,-1.9544361648175292,1739141222.3270035,61.649941205978394,0.065,1739141222.327005,61.649941205978394,-3.1199533919876803,1739141222.327006,61.649941205978394,-0.05158122849412922,1739141222.3270078,61.649941205978394,-0.005524400404116838,1739141222.3270087,61.649941205978394,2.4489472552463485,1739141222.3270104,61.649941205978394,0.0,1739141222.3270118,61.649941205978394,0.05622803361437212,1739141222.327013,61.649941205978394,3.1693232256650994,1739141222.3270144,61.649941205978394,2.3927192216319764 +1739141222.346374,61.66994118690491,6.2482489580204685,1739141222.3463774,61.66994118690491,0.2407864313579111,1739141222.3463814,61.66994118690491,106.33298170814234,1739141222.3463852,61.66994118690491,-2.1988950950366255,1739141222.3463874,61.66994118690491,0.065,1739141222.34639,61.66994118690491,-3.1207854954162215,1739141222.3463922,61.66994118690491,-0.06807939000469884,1739141222.3463964,61.66994118690491,-0.007324334596716419,1739141222.3464003,61.66994118690491,2.432839213381561,1739141222.3464043,61.66994118690491,0.0,1739141222.3464081,61.66994118690491,0.014167556343446661,1739141222.346412,61.66994118690491,3.170457610895763,1739141222.3464162,61.66994118690491,2.3986428483324085 +1739141222.3663433,61.68994116783142,6.2482489580204685,1739141222.3663461,61.68994116783142,0.2407864313579111,1739141222.3663502,61.68994116783142,106.33298170814234,1739141222.366354,61.68994116783142,-2.1988950950366255,1739141222.3663561,61.68994116783142,0.065,1739141222.366359,61.68994116783142,-3.1207854954162215,1739141222.3663633,61.68994116783142,-0.06807939000469884,1739141222.3663676,61.68994116783142,-0.007324334596716419,1739141222.3663697,61.68994116783142,2.432839213381561,1739141222.3663719,61.68994116783142,0.0,1739141222.3663735,61.68994116783142,0.034196365049152355,1739141222.3663754,61.68994116783142,3.170457610895763,1739141222.3663774,61.68994116783142,2.3986428483324085 +1739141222.3863435,61.709941148757935,6.2482489580204685,1739141222.3863468,61.709941148757935,0.2407864313579111,1739141222.3863506,61.709941148757935,106.33298170814234,1739141222.3863544,61.709941148757935,-2.1988950950366255,1739141222.386356,61.709941148757935,0.065,1739141222.3863592,61.709941148757935,-3.1207854954162215,1739141222.3863618,61.709941148757935,-0.06807939000469884,1739141222.3863652,61.709941148757935,-0.007324334596716419,1739141222.3863692,61.709941148757935,2.432839213381561,1739141222.386372,61.709941148757935,0.0,1739141222.3863742,61.709941148757935,0.034196365049152355,1739141222.386376,61.709941148757935,3.170457610895763,1739141222.386378,61.709941148757935,2.3986428483324085 +1739141222.406438,61.72994112968445,6.2482489580204685,1739141222.406443,61.72994112968445,0.2407864313579111,1739141222.4064486,61.72994112968445,106.33298170814234,1739141222.4064553,61.72994112968445,-2.1988950950366255,1739141222.4064581,61.72994112968445,0.065,1739141222.406461,61.72994112968445,-3.1207854954162215,1739141222.406465,61.72994112968445,-0.06807939000469884,1739141222.4064775,61.72994112968445,-0.007324334596716419,1739141222.4064822,61.72994112968445,2.432839213381561,1739141222.4064867,61.72994112968445,0.0,1739141222.4064908,61.72994112968445,0.034196365049152355,1739141222.406493,61.72994112968445,3.170457610895763,1739141222.4064946,61.72994112968445,2.3986428483324085 +1739141222.4263895,61.74994111061096,6.2482489580204685,1739141222.4263945,61.74994111061096,0.2407864313579111,1739141222.426399,61.74994111061096,106.33298170814234,1739141222.4264028,61.74994111061096,-2.1988950950366255,1739141222.4264047,61.74994111061096,0.065,1739141222.426407,61.74994111061096,-3.1207854954162215,1739141222.4264092,61.74994111061096,-0.06807939000469884,1739141222.4264112,61.74994111061096,-0.007324334596716419,1739141222.4264133,61.74994111061096,2.432839213381561,1739141222.426416,61.74994111061096,0.0,1739141222.4264188,61.74994111061096,0.034196365049152355,1739141222.4264224,61.74994111061096,3.170457610895763,1739141222.4264262,61.74994111061096,2.3986428483324085 +1739141222.4465108,61.769941091537476,6.2482489580204685,1739141222.4465148,61.769941091537476,0.2407864313579111,1739141222.4465199,61.769941091537476,106.33298170814234,1739141222.446525,61.769941091537476,-2.1988950950366255,1739141222.446527,61.769941091537476,0.065,1739141222.446532,61.769941091537476,-3.1207854954162215,1739141222.4465349,61.769941091537476,-0.06807939000469884,1739141222.4465365,61.769941091537476,-0.007324334596716419,1739141222.4465375,61.769941091537476,2.432839213381561,1739141222.4465392,61.769941091537476,0.0,1739141222.4465408,61.769941091537476,0.034196365049152355,1739141222.446542,61.769941091537476,3.170457610895763,1739141222.4465437,61.769941091537476,2.3986428483324085 +1739141222.4663742,61.78994107246399,5.98436256458767,1739141222.4663777,61.78994107246399,0.23303102678820498,1739141222.4663815,61.78994107246399,106.65499591366385,1739141222.4663858,61.78994107246399,-2.530948383449249,1739141222.466389,61.78994107246399,0.065,1739141222.4663937,61.78994107246399,-3.121862402588456,1739141222.466397,61.78994107246399,-0.08745999346951976,1739141222.466399,61.78994107246399,-0.009259748352073056,1739141222.4664006,61.78994107246399,2.4140521714755296,1739141222.4664025,61.78994107246399,0.0,1739141222.4664047,61.78994107246399,-0.008058332345874122,1739141222.4664068,61.78994107246399,3.171591996126427,1739141222.466409,61.78994107246399,2.401989209296116 +1739141222.4866388,61.8099410533905,5.98436256458767,1739141222.4866414,61.8099410533905,0.23303102678820498,1739141222.4866447,61.8099410533905,106.65499591366385,1739141222.4866478,61.8099410533905,-2.530948383449249,1739141222.4866495,61.8099410533905,0.065,1739141222.4866552,61.8099410533905,-3.121862402588456,1739141222.4866579,61.8099410533905,-0.08745999346951976,1739141222.486659,61.8099410533905,-0.009259748352073056,1739141222.4866602,61.8099410533905,2.4140521714755296,1739141222.4866621,61.8099410533905,0.0,1739141222.4866636,61.8099410533905,0.012062962179413717,1739141222.4866652,61.8099410533905,3.171591996126427,1739141222.4866664,61.8099410533905,2.401989209296116 +1739141222.506854,61.82994103431702,5.98436256458767,1739141222.5068572,61.82994103431702,0.23303102678820498,1739141222.5068607,61.82994103431702,106.65499591366385,1739141222.506864,61.82994103431702,-2.530948383449249,1739141222.506866,61.82994103431702,0.065,1739141222.506868,61.82994103431702,-3.121862402588456,1739141222.5068696,61.82994103431702,-0.08745999346951976,1739141222.5068712,61.82994103431702,-0.009259748352073056,1739141222.506873,61.82994103431702,2.4140521714755296,1739141222.5068748,61.82994103431702,0.0,1739141222.5068772,61.82994103431702,0.012062962179413717,1739141222.506879,61.82994103431702,3.171591996126427,1739141222.5068805,61.82994103431702,2.401989209296116 +1739141222.5269046,61.84994101524353,5.98436256458767,1739141222.526908,61.84994101524353,0.23303102678820498,1739141222.5269113,61.84994101524353,106.65499591366385,1739141222.5269146,61.84994101524353,-2.530948383449249,1739141222.5269163,61.84994101524353,0.065,1739141222.5269184,61.84994101524353,-3.121862402588456,1739141222.52692,61.84994101524353,-0.08745999346951976,1739141222.526922,61.84994101524353,-0.009259748352073056,1739141222.5269234,61.84994101524353,2.4140521714755296,1739141222.5269258,61.84994101524353,0.0,1739141222.5269277,61.84994101524353,0.012062962179413717,1739141222.526929,61.84994101524353,3.171591996126427,1739141222.5269303,61.84994101524353,2.401989209296116 +1739141222.5469942,61.869940996170044,5.98436256458767,1739141222.5469978,61.869940996170044,0.23303102678820498,1739141222.5470018,61.869940996170044,106.65499591366385,1739141222.5470052,61.869940996170044,-2.530948383449249,1739141222.5470073,61.869940996170044,0.065,1739141222.5470095,61.869940996170044,-3.121862402588456,1739141222.5470114,61.869940996170044,-0.08745999346951976,1739141222.547013,61.869940996170044,-0.009259748352073056,1739141222.5470147,61.869940996170044,2.4140521714755296,1739141222.547017,61.869940996170044,0.0,1739141222.547019,61.869940996170044,0.012062962179413717,1739141222.5470204,61.869940996170044,3.171591996126427,1739141222.547022,61.869940996170044,2.401989209296116 +1739141222.5670936,61.88994097709656,5.720213016083505,1739141222.5670962,61.88994097709656,0.2249679974350718,1739141222.5670998,61.88994097709656,106.8775687305747,1739141222.5671034,61.88994097709656,-2.7569330442909954,1739141222.5671053,61.88994097709656,0.065,1739141222.5671077,61.88994097709656,-3.1227243915151477,1739141222.5671093,61.88994097709656,-0.10399204776123407,1739141222.567111,61.88994097709656,-0.011109778743350328,1739141222.5671124,61.88994097709656,2.39814114123556,1739141222.5671146,61.88994097709656,0.0,1739141222.5671165,61.88994097709656,-0.020483829197060092,1739141222.5671184,61.88994097709656,3.1727263813570907,1739141222.5671198,61.88994097709656,2.403126490606417 +1739141222.5868657,61.90994095802307,5.720213016083505,1739141222.586869,61.90994095802307,0.2249679974350718,1739141222.586873,61.90994095802307,106.8775687305747,1739141222.5868764,61.90994095802307,-2.7569330442909954,1739141222.5868783,61.90994095802307,0.065,1739141222.5868804,61.90994095802307,-3.1227243915151477,1739141222.586882,61.90994095802307,-0.10399204776123407,1739141222.5868838,61.90994095802307,-0.011109778743350328,1739141222.5868852,61.90994095802307,2.39814114123556,1739141222.5868871,61.90994095802307,0.0,1739141222.586889,61.90994095802307,-0.004985349370857151,1739141222.5868905,61.90994095802307,3.1727263813570907,1739141222.5868921,61.90994095802307,2.403126490606417 +1739141222.6070411,61.929940938949585,5.720213016083505,1739141222.6070447,61.929940938949585,0.2249679974350718,1739141222.6070483,61.929940938949585,106.8775687305747,1739141222.6070518,61.929940938949585,-2.7569330442909954,1739141222.6070535,61.929940938949585,0.065,1739141222.6070557,61.929940938949585,-3.1227243915151477,1739141222.6070573,61.929940938949585,-0.10399204776123407,1739141222.6070595,61.929940938949585,-0.011109778743350328,1739141222.607061,61.929940938949585,2.39814114123556,1739141222.6070628,61.929940938949585,0.0,1739141222.6070645,61.929940938949585,-0.004985349370857151,1739141222.6070662,61.929940938949585,3.1727263813570907,1739141222.6070676,61.929940938949585,2.403126490606417 +1739141222.6268275,61.9499409198761,5.720213016083505,1739141222.6268308,61.9499409198761,0.2249679974350718,1739141222.6268342,61.9499409198761,106.8775687305747,1739141222.6268394,61.9499409198761,-2.7569330442909954,1739141222.6268444,61.9499409198761,0.065,1739141222.6268475,61.9499409198761,-3.1227243915151477,1739141222.6268492,61.9499409198761,-0.10399204776123407,1739141222.626851,61.9499409198761,-0.011109778743350328,1739141222.6268535,61.9499409198761,2.39814114123556,1739141222.6268554,61.9499409198761,0.0,1739141222.6268575,61.9499409198761,-0.004985349370857151,1739141222.6268592,61.9499409198761,3.1727263813570907,1739141222.6268613,61.9499409198761,2.403126490606417 +1739141222.646894,61.96994090080261,5.720213016083505,1739141222.6468973,61.96994090080261,0.2249679974350718,1739141222.646901,61.96994090080261,106.8775687305747,1739141222.646904,61.96994090080261,-2.7569330442909954,1739141222.646906,61.96994090080261,0.065,1739141222.646908,61.96994090080261,-3.1227243915151477,1739141222.64691,61.96994090080261,-0.10399204776123407,1739141222.6469114,61.96994090080261,-0.011109778743350328,1739141222.646913,61.96994090080261,2.39814114123556,1739141222.6469147,61.96994090080261,0.0,1739141222.6469166,61.96994090080261,-0.004985349370857151,1739141222.646918,61.96994090080261,3.1727263813570907,1739141222.6469197,61.96994090080261,2.403126490606417 +1739141222.6673944,61.989940881729126,5.720213016083505,1739141222.6673982,61.989940881729126,0.2249679974350718,1739141222.6674025,61.989940881729126,106.8775687305747,1739141222.6674058,61.989940881729126,-2.7569330442909954,1739141222.667408,61.989940881729126,0.065,1739141222.66741,61.989940881729126,-3.1227243915151477,1739141222.6674116,61.989940881729126,-0.10399204776123407,1739141222.6674132,61.989940881729126,-0.011109778743350328,1739141222.6674147,61.989940881729126,2.39814114123556,1739141222.6674166,61.989940881729126,0.0,1739141222.6674185,61.989940881729126,-0.004985349370857151,1739141222.6674201,61.989940881729126,3.1727263813570907,1739141222.6674216,61.989940881729126,2.403126490606417 +1739141222.6871908,62.00994086265564,5.45605813397002,1739141222.6871943,62.00994086265564,0.2166048804147973,1739141222.6871984,62.00994086265564,107.19654873349432,1739141222.6872022,62.00994086265564,-3.0733546416987347,1739141222.6872044,62.00994086265564,0.065,1739141222.687207,62.00994086265564,-3.123820161858043,1739141222.6872087,62.00994086265564,-0.12365433566523898,1739141222.6872108,62.00994086265564,-0.013049455198428716,1739141222.6872125,62.00994086265564,2.3793539413239566,1739141222.6872144,62.00994086265564,0.0,1739141222.687216,62.00994086265564,-0.03922376124325118,1739141222.687218,62.00994086265564,3.1738607665877545,1739141222.6872194,62.00994086265564,2.4022736887691196 +1739141222.7074075,62.02994084358215,5.45605813397002,1739141222.7074118,62.02994084358215,0.2166048804147973,1739141222.7074172,62.02994084358215,107.19654873349432,1739141222.7074213,62.02994084358215,-3.0733546416987347,1739141222.707424,62.02994084358215,0.065,1739141222.7074268,62.02994084358215,-3.123820161858043,1739141222.7074287,62.02994084358215,-0.12365433566523898,1739141222.7074308,62.02994084358215,-0.013049455198428716,1739141222.7074327,62.02994084358215,2.3793539413239566,1739141222.7074354,62.02994084358215,0.0,1739141222.7074378,62.02994084358215,-0.022919747445163008,1739141222.7074397,62.02994084358215,3.1738607665877545,1739141222.7074416,62.02994084358215,2.4022736887691196 +1739141222.7263143,62.04994082450867,5.45605813397002,1739141222.7263167,62.04994082450867,0.2166048804147973,1739141222.7263193,62.04994082450867,107.19654873349432,1739141222.7263222,62.04994082450867,-3.0733546416987347,1739141222.7263234,62.04994082450867,0.065,1739141222.726325,62.04994082450867,-3.123820161858043,1739141222.7263265,62.04994082450867,-0.12365433566523898,1739141222.726328,62.04994082450867,-0.013049455198428716,1739141222.726329,62.04994082450867,2.3793539413239566,1739141222.7263305,62.04994082450867,0.0,1739141222.726332,62.04994082450867,-0.022919747445163008,1739141222.7263331,62.04994082450867,3.1738607665877545,1739141222.7263346,62.04994082450867,2.4022736887691196 +1739141222.746749,62.06994080543518,5.45605813397002,1739141222.7467527,62.06994080543518,0.2166048804147973,1739141222.7467558,62.06994080543518,107.19654873349432,1739141222.7467594,62.06994080543518,-3.0733546416987347,1739141222.7467613,62.06994080543518,0.065,1739141222.7467632,62.06994080543518,-3.123820161858043,1739141222.746765,62.06994080543518,-0.12365433566523898,1739141222.7467668,62.06994080543518,-0.013049455198428716,1739141222.7467685,62.06994080543518,2.3793539413239566,1739141222.7467701,62.06994080543518,0.0,1739141222.746772,62.06994080543518,-0.022919747445163008,1739141222.7467735,62.06994080543518,3.1738607665877545,1739141222.7467747,62.06994080543518,2.4022736887691196 +1739141222.7663639,62.089940786361694,5.45605813397002,1739141222.7663665,62.089940786361694,0.2166048804147973,1739141222.7663693,62.089940786361694,107.19654873349432,1739141222.7663727,62.089940786361694,-3.0733546416987347,1739141222.766376,62.089940786361694,0.065,1739141222.7663805,62.089940786361694,-3.123820161858043,1739141222.7663846,62.089940786361694,-0.12365433566523898,1739141222.7663898,62.089940786361694,-0.013049455198428716,1739141222.7663946,62.089940786361694,2.3793539413239566,1739141222.7663999,62.089940786361694,0.0,1739141222.766406,62.089940786361694,-0.022919747445163008,1739141222.7664094,62.089940786361694,3.1738607665877545,1739141222.7664127,62.089940786361694,2.4022736887691196 +1739141222.7865117,62.10994076728821,5.1920853250085806,1739141222.7865138,62.10994076728821,0.20794779056812818,1739141222.7865167,62.10994076728821,107.41773442639254,1739141222.7865195,62.10994076728821,-3.2865789262407,1739141222.7865207,62.10994076728821,0.065,1739141222.7865226,62.10994076728821,-3.1247345442988634,1739141222.786524,62.10994076728821,-0.1402878540334133,1739141222.7865255,62.10994076728821,-0.014983020534477103,1739141222.7865267,62.10994076728821,2.3635756781408372,1739141222.7865286,62.10994076728821,0.0,1739141222.78653,62.10994076728821,-0.04797554685575132,1739141222.7865312,62.10994076728821,3.1749951518184183,1739141222.7865324,62.10994076728821,2.3996198859837023 +1739141222.8064437,62.12994074821472,5.1920853250085806,1739141222.8064475,62.12994074821472,0.20794779056812818,1739141222.806452,62.12994074821472,107.41773442639254,1739141222.8064575,62.12994074821472,-3.2865789262407,1739141222.8064606,62.12994074821472,0.065,1739141222.8064644,62.12994074821472,-3.1247345442988634,1739141222.8064766,62.12994074821472,-0.1402878540334133,1739141222.806478,62.12994074821472,-0.014983020534477103,1739141222.8064795,62.12994074821472,2.3635756781408372,1739141222.8064811,62.12994074821472,0.0,1739141222.8064828,62.12994074821472,-0.036044207842865106,1739141222.8064837,62.12994074821472,3.1749951518184183,1739141222.8064854,62.12994074821472,2.3996198859837023 +1739141222.8263605,62.149940729141235,5.1920853250085806,1739141222.826363,62.149940729141235,0.20794779056812818,1739141222.826366,62.149940729141235,107.41773442639254,1739141222.8263688,62.149940729141235,-3.2865789262407,1739141222.8263702,62.149940729141235,0.065,1739141222.8263721,62.149940729141235,-3.1247345442988634,1739141222.8263733,62.149940729141235,-0.1402878540334133,1739141222.8263748,62.149940729141235,-0.014983020534477103,1739141222.826376,62.149940729141235,2.3635756781408372,1739141222.8263776,62.149940729141235,0.0,1739141222.826379,62.149940729141235,-0.036044207842865106,1739141222.8263803,62.149940729141235,3.1749951518184183,1739141222.8263817,62.149940729141235,2.3996198859837023 +1739141222.846369,62.16994071006775,5.1920853250085806,1739141222.8463714,62.16994071006775,0.20794779056812818,1739141222.846374,62.16994071006775,107.41773442639254,1739141222.846377,62.16994071006775,-3.2865789262407,1739141222.8463783,62.16994071006775,0.065,1739141222.84638,62.16994071006775,-3.1247345442988634,1739141222.8463817,62.16994071006775,-0.1402878540334133,1739141222.846383,62.16994071006775,-0.014983020534477103,1739141222.846384,62.16994071006775,2.3635756781408372,1739141222.846386,62.16994071006775,0.0,1739141222.8463874,62.16994071006775,-0.036044207842865106,1739141222.8463886,62.16994071006775,3.1749951518184183,1739141222.84639,62.16994071006775,2.3996198859837023 +1739141222.8663237,62.18994069099426,5.1920853250085806,1739141222.8663266,62.18994069099426,0.20794779056812818,1739141222.8663292,62.18994069099426,107.41773442639254,1739141222.8663318,62.18994069099426,-3.2865789262407,1739141222.8663332,62.18994069099426,0.065,1739141222.866335,62.18994069099426,-3.1247345442988634,1739141222.8663363,62.18994069099426,-0.1402878540334133,1739141222.8663375,62.18994069099426,-0.014983020534477103,1739141222.8663387,62.18994069099426,2.3635756781408372,1739141222.8663406,62.18994069099426,0.0,1739141222.866342,62.18994069099426,-0.036044207842865106,1739141222.8663433,62.18994069099426,3.1749951518184183,1739141222.8663445,62.18994069099426,2.3996198859837023 +1739141222.8863502,62.209940671920776,5.1920853250085806,1739141222.8863523,62.209940671920776,0.20794779056812818,1739141222.8863552,62.209940671920776,107.41773442639254,1739141222.8863578,62.209940671920776,-3.2865789262407,1739141222.8863592,62.209940671920776,0.065,1739141222.886361,62.209940671920776,-3.1247345442988634,1739141222.8863623,62.209940671920776,-0.1402878540334133,1739141222.8863637,62.209940671920776,-0.014983020534477103,1739141222.8863647,62.209940671920776,2.3635756781408372,1739141222.8863664,62.209940671920776,0.0,1739141222.886368,62.209940671920776,-0.036044207842865106,1739141222.8863692,62.209940671920776,3.1749951518184183,1739141222.8863707,62.209940671920776,2.3996198859837023 +1739141222.9064546,62.22994065284729,4.928498813113169,1739141222.9064581,62.22994065284729,0.1990118532884324,1739141222.9064627,62.22994065284729,107.54157726849037,1739141222.9064772,62.22994065284729,-3.3978760261268444,1739141222.9064815,62.22994065284729,0.065,1739141222.9064867,62.22994065284729,-3.125499181221276,1739141222.906491,62.22994065284729,-0.15297526673565157,1739141222.906495,62.22994065284729,-0.016941560811912455,1739141222.9064987,62.22994065284729,2.3516109999496804,1739141222.9065025,62.22994065284729,0.0,1739141222.9065065,62.22994065284729,-0.050902218820571395,1739141222.90651,62.22994065284729,3.176057153419552,1739141222.906514,62.22994065284729,2.3954379719131396 +1739141222.9262984,62.249940633773804,4.928498813113169,1739141222.9263008,62.249940633773804,0.1990118532884324,1739141222.9263034,62.249940633773804,107.54157726849037,1739141222.9263062,62.249940633773804,-3.3978760261268444,1739141222.9263077,62.249940633773804,0.065,1739141222.9263096,62.249940633773804,-3.125499181221276,1739141222.926311,62.249940633773804,-0.15297526673565157,1739141222.9263124,62.249940633773804,-0.016941560811912455,1739141222.9263134,62.249940633773804,2.3516109999496804,1739141222.9263153,62.249940633773804,0.0,1739141222.9263165,62.249940633773804,-0.043826971963459194,1739141222.926318,62.249940633773804,3.176057153419552,1739141222.9263191,62.249940633773804,2.3954379719131396 +1739141222.946834,62.26994061470032,4.928498813113169,1739141222.946838,62.26994061470032,0.1990118532884324,1739141222.946843,62.26994061470032,107.54157726849037,1739141222.9468496,62.26994061470032,-3.3978760261268444,1739141222.9468532,62.26994061470032,0.065,1739141222.946857,62.26994061470032,-3.125499181221276,1739141222.9468606,62.26994061470032,-0.15297526673565157,1739141222.946864,62.26994061470032,-0.016941560811912455,1739141222.946868,62.26994061470032,2.3516109999496804,1739141222.9468715,62.26994061470032,0.0,1739141222.9468756,62.26994061470032,-0.043826971963459194,1739141222.946879,62.26994061470032,3.176057153419552,1739141222.9468825,62.26994061470032,2.3954379719131396 +1739141222.966365,62.28994059562683,4.928498813113169,1739141222.9663675,62.28994059562683,0.1990118532884324,1739141222.9663703,62.28994059562683,107.54157726849037,1739141222.9663732,62.28994059562683,-3.3978760261268444,1739141222.9663744,62.28994059562683,0.065,1739141222.9663763,62.28994059562683,-3.125499181221276,1739141222.9663775,62.28994059562683,-0.15297526673565157,1739141222.966379,62.28994059562683,-0.016941560811912455,1739141222.9663804,62.28994059562683,2.3516109999496804,1739141222.966382,62.28994059562683,0.0,1739141222.9663837,62.28994059562683,-0.043826971963459194,1739141222.966385,62.28994059562683,3.176057153419552,1739141222.9663858,62.28994059562683,2.3954379719131396 +1739141222.9863667,62.309940576553345,4.928498813113169,1739141222.9863694,62.309940576553345,0.1990118532884324,1739141222.986372,62.309940576553345,107.54157726849037,1739141222.9863749,62.309940576553345,-3.3978760261268444,1739141222.9863763,62.309940576553345,0.065,1739141222.986378,62.309940576553345,-3.125499181221276,1739141222.9863791,62.309940576553345,-0.15297526673565157,1739141222.9863806,62.309940576553345,-0.016941560811912455,1739141222.9863815,62.309940576553345,2.3516109999496804,1739141222.9863834,62.309940576553345,0.0,1739141222.9863849,62.309940576553345,-0.043826971963459194,1739141222.986386,62.309940576553345,3.176057153419552,1739141222.9863873,62.309940576553345,2.3954379719131396 +1739141223.0064373,62.32994055747986,4.665405306949323,1739141223.0064418,62.32994055747986,0.18982087690187743,1739141223.0064473,62.32994055747986,107.85100080113999,1739141223.0064545,62.32994055747986,-3.6927296108385472,1739141223.0064585,62.32994055747986,0.065,1739141223.0064628,62.32994055747986,-3.12665970503931,1739141223.0064785,62.32994055747986,-0.17152522342206794,1739141223.006484,62.32994055747986,-0.01885245418518272,1739141223.006486,62.32994055747986,2.334226662573278,1739141223.0064876,62.32994055747986,0.0,1739141223.006489,62.32994055747986,-0.06774347821913802,1739141223.0064907,62.32994055747986,3.177046703906893,1739141223.0064921,62.32994055747986,2.3905813226004997 +1739141223.0264323,62.34994053840637,4.665405306949323,1739141223.0264347,62.34994053840637,0.18982087690187743,1739141223.0264373,62.34994053840637,107.85100080113999,1739141223.0264404,62.34994053840637,-3.6927296108385472,1739141223.0264437,62.34994053840637,0.065,1739141223.026448,62.34994053840637,-3.12665970503931,1739141223.0264525,62.34994053840637,-0.17152522342206794,1739141223.0264578,62.34994053840637,-0.01885245418518272,1739141223.0264618,62.34994053840637,2.334226662573278,1739141223.0264845,62.34994053840637,0.0,1739141223.026487,62.34994053840637,-0.05635466002722156,1739141223.0264883,62.34994053840637,3.177046703906893,1739141223.0264895,62.34994053840637,2.3905813226004997 +1739141223.0464196,62.369940519332886,4.665405306949323,1739141223.046422,62.369940519332886,0.18982087690187743,1739141223.046425,62.369940519332886,107.85100080113999,1739141223.0464277,62.369940519332886,-3.6927296108385472,1739141223.046429,62.369940519332886,0.065,1739141223.0464308,62.369940519332886,-3.12665970503931,1739141223.046432,62.369940519332886,-0.17152522342206794,1739141223.0464332,62.369940519332886,-0.01885245418518272,1739141223.0464346,62.369940519332886,2.334226662573278,1739141223.0464363,62.369940519332886,0.0,1739141223.0464377,62.369940519332886,-0.05635466002722156,1739141223.046439,62.369940519332886,3.177046703906893,1739141223.0464401,62.369940519332886,2.3905813226004997 +1739141223.0664086,62.3899405002594,4.665405306949323,1739141223.0664113,62.3899405002594,0.18982087690187743,1739141223.066414,62.3899405002594,107.85100080113999,1739141223.0664167,62.3899405002594,-3.6927296108385472,1739141223.066418,62.3899405002594,0.065,1739141223.0664196,62.3899405002594,-3.12665970503931,1739141223.066421,62.3899405002594,-0.17152522342206794,1739141223.0664225,62.3899405002594,-0.01885245418518272,1739141223.0664237,62.3899405002594,2.334226662573278,1739141223.066425,62.3899405002594,0.0,1739141223.0664265,62.3899405002594,-0.05635466002722156,1739141223.066428,62.3899405002594,3.177046703906893,1739141223.0664291,62.3899405002594,2.3905813226004997 +1739141223.0864573,62.40994048118591,4.665405306949323,1739141223.0864623,62.40994048118591,0.18982087690187743,1739141223.08648,62.40994048118591,107.85100080113999,1739141223.0864873,62.40994048118591,-3.6927296108385472,1739141223.0864909,62.40994048118591,0.065,1739141223.0864968,62.40994048118591,-3.12665970503931,1739141223.086501,62.40994048118591,-0.17152522342206794,1739141223.086505,62.40994048118591,-0.01885245418518272,1739141223.0865085,62.40994048118591,2.334226662573278,1739141223.0865126,62.40994048118591,0.0,1739141223.0865161,62.40994048118591,-0.05635466002722156,1739141223.08652,62.40994048118591,3.177046703906893,1739141223.086524,62.40994048118591,2.3905813226004997 +1739141223.1063979,62.42994046211243,4.665405306949323,1739141223.1064005,62.42994046211243,0.18982087690187743,1739141223.1064034,62.42994046211243,107.85100080113999,1739141223.1064062,62.42994046211243,-3.6927296108385472,1739141223.1064076,62.42994046211243,0.065,1739141223.1064095,62.42994046211243,-3.12665970503931,1739141223.1064107,62.42994046211243,-0.17152522342206794,1739141223.106412,62.42994046211243,-0.01885245418518272,1739141223.1064134,62.42994046211243,2.334226662573278,1739141223.1064153,62.42994046211243,0.0,1739141223.106417,62.42994046211243,-0.05635466002722156,1739141223.1064181,62.42994046211243,3.177046703906893,1739141223.1064196,62.42994046211243,2.3905813226004997 +1739141223.126409,62.44994044303894,4.40294087898746,1739141223.1264112,62.44994044303894,0.18040292402637625,1739141223.1264138,62.44994044303894,108.15656971325299,1739141223.1264167,62.44994044303894,-3.9791151225196226,1739141223.1264179,62.44994044303894,0.065,1739141223.1264195,62.44994044303894,-3.127825669314458,1739141223.1264207,62.44994044303894,-0.18934906985569305,1739141223.126422,62.44994044303894,-0.02069350601239987,1739141223.1264234,62.44994044303894,2.3176438875526233,1739141223.1264248,62.44994044303894,0.0,1739141223.1264262,62.44994044303894,-0.07580507544300898,1739141223.1264274,62.44994044303894,3.177949230406596,1739141223.1264286,62.44994044303894,2.3841868557898587 +1739141223.1464062,62.469940423965454,4.40294087898746,1739141223.1464086,62.469940423965454,0.18040292402637625,1739141223.146411,62.469940423965454,108.15656971325299,1739141223.1464138,62.469940423965454,-3.9791151225196226,1739141223.1464155,62.469940423965454,0.065,1739141223.146417,62.469940423965454,-3.127825669314458,1739141223.1464183,62.469940423965454,-0.18934906985569305,1739141223.1464195,62.469940423965454,-0.02069350601239987,1739141223.146421,62.469940423965454,2.3176438875526233,1739141223.1464229,62.469940423965454,0.0,1739141223.146424,62.469940423965454,-0.06654296823723538,1739141223.1464255,62.469940423965454,3.177949230406596,1739141223.146427,62.469940423965454,2.3841868557898587 +1739141223.166454,62.48994040489197,4.40294087898746,1739141223.1664565,62.48994040489197,0.18040292402637625,1739141223.1664593,62.48994040489197,108.15656971325299,1739141223.166462,62.48994040489197,-3.9791151225196226,1739141223.1664634,62.48994040489197,0.065,1739141223.166465,62.48994040489197,-3.127825669314458,1739141223.1664665,62.48994040489197,-0.18934906985569305,1739141223.1664772,62.48994040489197,-0.02069350601239987,1739141223.1664815,62.48994040489197,2.3176438875526233,1739141223.1664858,62.48994040489197,0.0,1739141223.1664906,62.48994040489197,-0.06654296823723538,1739141223.1664944,62.48994040489197,3.177949230406596,1739141223.1664968,62.48994040489197,2.3841868557898587 +1739141223.1866336,62.50994038581848,4.40294087898746,1739141223.1866362,62.50994038581848,0.18040292402637625,1739141223.1866388,62.50994038581848,108.15656971325299,1739141223.1866415,62.50994038581848,-3.9791151225196226,1739141223.1866426,62.50994038581848,0.065,1739141223.1866446,62.50994038581848,-3.127825669314458,1739141223.1866457,62.50994038581848,-0.18934906985569305,1739141223.1866474,62.50994038581848,-0.02069350601239987,1739141223.1866486,62.50994038581848,2.3176438875526233,1739141223.18665,62.50994038581848,0.0,1739141223.1866517,62.50994038581848,-0.06654296823723538,1739141223.1866531,62.50994038581848,3.177949230406596,1739141223.1866546,62.50994038581848,2.3841868557898587 +1739141223.206986,62.529940366744995,4.40294087898746,1739141223.206989,62.529940366744995,0.18040292402637625,1739141223.206993,62.529940366744995,108.15656971325299,1739141223.2069962,62.529940366744995,-3.9791151225196226,1739141223.2069974,62.529940366744995,0.065,1739141223.2069998,62.529940366744995,-3.127825669314458,1739141223.2070017,62.529940366744995,-0.18934906985569305,1739141223.207003,62.529940366744995,-0.02069350601239987,1739141223.2070043,62.529940366744995,2.3176438875526233,1739141223.207006,62.529940366744995,0.0,1739141223.2070074,62.529940366744995,-0.06654296823723538,1739141223.207009,62.529940366744995,3.177949230406596,1739141223.2070105,62.529940366744995,2.3841868557898587 +1739141223.2264817,62.54994034767151,4.1412268997492365,1739141223.2264843,62.54994034767151,0.17078334293127995,1739141223.2264874,62.54994034767151,108.36872701157326,1739141223.22649,62.54994034767151,-4.169190244619195,1739141223.2264915,62.54994034767151,0.065,1739141223.2264946,62.54994034767151,-3.128864335819903,1739141223.2264988,62.54994034767151,-0.20325395354730702,1739141223.226503,62.54994034767151,-0.022598311863083385,1739141223.226507,62.54994034767151,2.3047890422394666,1739141223.2265115,62.54994034767151,0.0,1739141223.2265134,62.54994034767151,-0.07703174736701193,1739141223.2265158,62.54994034767151,3.178779160393826,1739141223.2265174,62.54994034767151,2.376826130382963 +1739141223.262716,62.57994031906128,4.1412268997492365,1739141223.2627213,62.57994031906128,0.17078334293127995,1739141223.262727,62.57994031906128,108.36872701157326,1739141223.2627323,62.57994031906128,-4.169190244619195,1739141223.2627354,62.57994031906128,0.065,1739141223.262739,62.57994031906128,-3.128864335819903,1739141223.262742,62.57994031906128,-0.20325395354730702,1739141223.2627459,62.57994031906128,-0.022598311863083385,1739141223.262749,62.57994031906128,2.3047890422394666,1739141223.2627525,62.57994031906128,0.0,1739141223.2627566,62.57994031906128,-0.07203708814349641,1739141223.26276,62.57994031906128,3.178779160393826,1739141223.262763,62.57994031906128,2.376826130382963 +1739141223.2737124,62.589940309524536,4.1412268997492365,1739141223.2737174,62.589940309524536,0.17078334293127995,1739141223.2737234,62.589940309524536,108.36872701157326,1739141223.2737288,62.589940309524536,-4.169190244619195,1739141223.2737322,62.589940309524536,0.065,1739141223.273736,62.589940309524536,-3.128864335819903,1739141223.2737396,62.589940309524536,-0.20325395354730702,1739141223.2737432,62.589940309524536,-0.022598311863083385,1739141223.2737467,62.589940309524536,2.3047890422394666,1739141223.273752,62.589940309524536,0.0,1739141223.2737565,62.589940309524536,-0.07203708814349641,1739141223.2737598,62.589940309524536,3.178779160393826,1739141223.2737634,62.589940309524536,2.376826130382963 +1739141223.2898057,62.60994029045105,4.1412268997492365,1739141223.2898102,62.60994029045105,0.17078334293127995,1739141223.289815,62.60994029045105,108.36872701157326,1739141223.2898207,62.60994029045105,-4.169190244619195,1739141223.289824,62.60994029045105,0.065,1739141223.289828,62.60994029045105,-3.128864335819903,1739141223.2898316,62.60994029045105,-0.20325395354730702,1739141223.289835,62.60994029045105,-0.022598311863083385,1739141223.2898383,62.60994029045105,2.3047890422394666,1739141223.2898421,62.60994029045105,0.0,1739141223.2898457,62.60994029045105,-0.07203708814349641,1739141223.2898495,62.60994029045105,3.178779160393826,1739141223.289853,62.60994029045105,2.376826130382963 +1739141223.3109424,62.62994027137756,4.1412268997492365,1739141223.3109467,62.62994027137756,0.17078334293127995,1739141223.3109517,62.62994027137756,108.36872701157326,1739141223.3109567,62.62994027137756,-4.169190244619195,1739141223.3109598,62.62994027137756,0.065,1739141223.3109634,62.62994027137756,-3.128864335819903,1739141223.3109667,62.62994027137756,-0.20325395354730702,1739141223.3109698,62.62994027137756,-0.022598311863083385,1739141223.3109732,62.62994027137756,2.3047890422394666,1739141223.3109765,62.62994027137756,0.0,1739141223.31098,62.62994027137756,-0.07203708814349641,1739141223.3109837,62.62994027137756,3.178779160393826,1739141223.310987,62.62994027137756,2.376826130382963 +1739141223.333612,62.64994025230408,4.1412268997492365,1739141223.3336177,62.64994025230408,0.17078334293127995,1739141223.3336244,62.64994025230408,108.36872701157326,1739141223.3336322,62.64994025230408,-4.169190244619195,1739141223.3336363,62.64994025230408,0.065,1739141223.3336418,62.64994025230408,-3.128864335819903,1739141223.3336465,62.64994025230408,-0.20325395354730702,1739141223.333652,62.64994025230408,-0.022598311863083385,1739141223.3336568,62.64994025230408,2.3047890422394666,1739141223.3336618,62.64994025230408,0.0,1739141223.3336666,62.64994025230408,-0.07203708814349641,1739141223.3336713,62.64994025230408,3.178779160393826,1739141223.3336763,62.64994025230408,2.376826130382963 +1739141223.3498178,62.66994023323059,3.880368301580261,1739141223.3498225,62.66994023323059,0.16098944983437136,1739141223.3498273,62.66994023323059,108.5803823014392,1739141223.3498328,62.66994023323059,-4.356743238173543,1739141223.3498359,62.66994023323059,0.065,1739141223.3498397,62.66994023323059,-3.129939891012851,1739141223.349843,62.66994023323059,-0.21643204427283155,1739141223.3498464,62.66994023323059,-0.024494256668095175,1739141223.34985,62.66994023323059,2.292671918766346,1739141223.3498538,62.66994023323059,0.0,1739141223.349857,62.66994023323059,-0.0798319570246913,1739141223.3498607,62.66994023323059,3.179521891290963,1739141223.349864,62.66994023323059,2.3687920316124305 +1739141223.3701944,62.689940214157104,3.880368301580261,1739141223.3702016,62.689940214157104,0.16098944983437136,1739141223.370208,62.689940214157104,108.5803823014392,1739141223.370214,62.689940214157104,-4.356743238173543,1739141223.3702176,62.689940214157104,0.065,1739141223.3702228,62.689940214157104,-3.129939891012851,1739141223.3702264,62.689940214157104,-0.21643204427283155,1739141223.3702304,62.689940214157104,-0.024494256668095175,1739141223.3702343,62.689940214157104,2.292671918766346,1739141223.3702388,62.689940214157104,0.0,1739141223.3702428,62.689940214157104,-0.07612011284608444,1739141223.3702466,62.689940214157104,3.179521891290963,1739141223.3702505,62.689940214157104,2.3687920316124305 +1739141223.3890176,62.70994019508362,3.880368301580261,1739141223.389022,62.70994019508362,0.16098944983437136,1739141223.3890285,62.70994019508362,108.5803823014392,1739141223.389034,62.70994019508362,-4.356743238173543,1739141223.3890371,62.70994019508362,0.065,1739141223.3890407,62.70994019508362,-3.129939891012851,1739141223.3890443,62.70994019508362,-0.21643204427283155,1739141223.3890476,62.70994019508362,-0.024494256668095175,1739141223.389051,62.70994019508362,2.292671918766346,1739141223.3890545,62.70994019508362,0.0,1739141223.3890584,62.70994019508362,-0.07612011284608444,1739141223.3890617,62.70994019508362,3.179521891290963,1739141223.389065,62.70994019508362,2.3687920316124305 +1739141223.4079645,62.72994017601013,3.880368301580261,1739141223.4079678,62.72994017601013,0.16098944983437136,1739141223.4079714,62.72994017601013,108.5803823014392,1739141223.4079745,62.72994017601013,-4.356743238173543,1739141223.4079762,62.72994017601013,0.065,1739141223.407978,62.72994017601013,-3.129939891012851,1739141223.4079795,62.72994017601013,-0.21643204427283155,1739141223.4079812,62.72994017601013,-0.024494256668095175,1739141223.4079823,62.72994017601013,2.292671918766346,1739141223.407984,62.72994017601013,0.0,1739141223.4079857,62.72994017601013,-0.07612011284608444,1739141223.4079869,62.72994017601013,3.179521891290963,1739141223.4079883,62.72994017601013,2.3687920316124305 +1739141223.4291584,62.749940156936646,3.880368301580261,1739141223.4291646,62.749940156936646,0.16098944983437136,1739141223.4291716,62.749940156936646,108.5803823014392,1739141223.4291773,62.749940156936646,-4.356743238173543,1739141223.4291804,62.749940156936646,0.065,1739141223.4291847,62.749940156936646,-3.129939891012851,1739141223.4291894,62.749940156936646,-0.21643204427283155,1739141223.4291935,62.749940156936646,-0.024494256668095175,1739141223.429197,62.749940156936646,2.292671918766346,1739141223.4292011,62.749940156936646,0.0,1739141223.4292054,62.749940156936646,-0.07612011284608444,1739141223.4292097,62.749940156936646,3.179521891290963,1739141223.4292138,62.749940156936646,2.3687920316124305 +1739141223.4465623,62.76994013786316,3.6204102449010467,1739141223.4465659,62.76994013786316,0.1510439268295567,1739141223.4465687,62.76994013786316,108.96582953772707,1739141223.446572,62.76994013786316,-4.7171164066251166,1739141223.4465744,62.76994013786316,0.065,1739141223.4465766,62.76994013786316,-3.1312729417680054,1739141223.446579,62.76994013786316,-0.23576230412642699,1739141223.4465806,62.76994013786316,-0.02604377621810417,1739141223.4465823,62.76994013786316,2.2750130990797364,1739141223.4465842,62.76994013786316,0.0,1739141223.4465861,62.76994013786316,-0.09387618805190738,1739141223.4465873,62.76994013786316,3.1801918763289527,1739141223.4465888,62.76994013786316,2.360434009000328 +1739141223.4665375,62.78994011878967,3.6204102449010467,1739141223.4665403,62.78994011878967,0.1510439268295567,1739141223.4665434,62.78994011878967,108.96582953772707,1739141223.466546,62.78994011878967,-4.7171164066251166,1739141223.4665475,62.78994011878967,0.065,1739141223.4665492,62.78994011878967,-3.1312729417680054,1739141223.4665506,62.78994011878967,-0.23576230412642699,1739141223.4665518,62.78994011878967,-0.02604377621810417,1739141223.466553,62.78994011878967,2.2750130990797364,1739141223.4665546,62.78994011878967,0.0,1739141223.4665577,62.78994011878967,-0.08542090992059181,1739141223.4665618,62.78994011878967,3.1801918763289527,1739141223.4665658,62.78994011878967,2.360434009000328 +1739141223.4868274,62.80994009971619,3.6204102449010467,1739141223.4868298,62.80994009971619,0.1510439268295567,1739141223.4868329,62.80994009971619,108.96582953772707,1739141223.4868357,62.80994009971619,-4.7171164066251166,1739141223.486837,62.80994009971619,0.065,1739141223.4868386,62.80994009971619,-3.1312729417680054,1739141223.4868398,62.80994009971619,-0.23576230412642699,1739141223.4868414,62.80994009971619,-0.02604377621810417,1739141223.4868426,62.80994009971619,2.2750130990797364,1739141223.486844,62.80994009971619,0.0,1739141223.4868455,62.80994009971619,-0.08542090992059181,1739141223.4868472,62.80994009971619,3.1801918763289527,1739141223.4868486,62.80994009971619,2.360434009000328 +1739141223.5071297,62.8299400806427,3.6204102449010467,1739141223.5071328,62.8299400806427,0.1510439268295567,1739141223.507136,62.8299400806427,108.96582953772707,1739141223.5071397,62.8299400806427,-4.7171164066251166,1739141223.5071409,62.8299400806427,0.065,1739141223.5071425,62.8299400806427,-3.1312729417680054,1739141223.5071442,62.8299400806427,-0.23576230412642699,1739141223.5071456,62.8299400806427,-0.02604377621810417,1739141223.507147,62.8299400806427,2.2750130990797364,1739141223.5071485,62.8299400806427,0.0,1739141223.5071502,62.8299400806427,-0.08542090992059181,1739141223.5071514,62.8299400806427,3.1801918763289527,1739141223.5071526,62.8299400806427,2.360434009000328 +1739141223.527313,62.849940061569214,3.6204102449010467,1739141223.5273166,62.849940061569214,0.1510439268295567,1739141223.5273197,62.849940061569214,108.96582953772707,1739141223.527322,62.849940061569214,-4.7171164066251166,1739141223.5273235,62.849940061569214,0.065,1739141223.527325,62.849940061569214,-3.1312729417680054,1739141223.527327,62.849940061569214,-0.23576230412642699,1739141223.5273283,62.849940061569214,-0.02604377621810417,1739141223.5273292,62.849940061569214,2.2750130990797364,1739141223.527331,62.849940061569214,0.0,1739141223.5273325,62.849940061569214,-0.08542090992059181,1739141223.5273337,62.849940061569214,3.1801918763289527,1739141223.5273347,62.849940061569214,2.360434009000328 +1739141223.5462568,62.86994004249573,3.6204102449010467,1739141223.5462592,62.86994004249573,0.1510439268295567,1739141223.546262,62.86994004249573,108.96582953772707,1739141223.5462644,62.86994004249573,-4.7171164066251166,1739141223.5462656,62.86994004249573,0.065,1739141223.5462677,62.86994004249573,-3.1312729417680054,1739141223.5462692,62.86994004249573,-0.23576230412642699,1739141223.5462704,62.86994004249573,-0.02604377621810417,1739141223.5462716,62.86994004249573,2.2750130990797364,1739141223.546273,62.86994004249573,0.0,1739141223.5462742,62.86994004249573,-0.08542090992059181,1739141223.5462756,62.86994004249573,3.1801918763289527,1739141223.5462768,62.86994004249573,2.360434009000328 +1739141223.5669065,62.88994002342224,3.3614426830620676,1739141223.5669086,62.88994002342224,0.14097351978361417,1739141223.5669117,62.88994002342224,109.9380423547786,1739141223.5669143,62.88994002342224,-5.660774195542622,1739141223.5669155,62.88994002342224,0.065,1739141223.5669172,62.88994002342224,-3.1331721373064,1739141223.5669184,62.88994002342224,-0.27750142826385804,1739141223.5669196,62.88994002342224,-0.02617930418917795,1739141223.566921,62.88994002342224,2.2373455941142724,1739141223.5669224,62.88994002342224,0.0,1739141223.5669239,62.88994002342224,-0.13916024408315864,1739141223.566925,62.88994002342224,3.1807744962652835,1739141223.5669284,62.88994002342224,2.3509156662889903 +1739141223.5861635,62.909940004348755,3.3614426830620676,1739141223.5861657,62.909940004348755,0.14097351978361417,1739141223.5861683,62.909940004348755,109.9380423547786,1739141223.586171,62.909940004348755,-5.660774195542622,1739141223.586172,62.909940004348755,0.065,1739141223.5861738,62.909940004348755,-3.1331721373064,1739141223.586175,62.909940004348755,-0.27750142826385804,1739141223.5861762,62.909940004348755,-0.02617930418917795,1739141223.5861773,62.909940004348755,2.2373455941142724,1739141223.5861788,62.909940004348755,0.0,1739141223.5861802,62.909940004348755,-0.11357007217471793,1739141223.5861814,62.909940004348755,3.1807744962652835,1739141223.5861824,62.909940004348755,2.3509156662889903 +1739141223.6068962,62.92993998527527,3.3614426830620676,1739141223.6068985,62.92993998527527,0.14097351978361417,1739141223.6069174,62.92993998527527,109.9380423547786,1739141223.6069202,62.92993998527527,-5.660774195542622,1739141223.6069214,62.92993998527527,0.065,1739141223.606923,62.92993998527527,-3.1331721373064,1739141223.6069245,62.92993998527527,-0.27750142826385804,1739141223.6069257,62.92993998527527,-0.02617930418917795,1739141223.6069272,62.92993998527527,2.2373455941142724,1739141223.6069286,62.92993998527527,0.0,1739141223.6069303,62.92993998527527,-0.11357007217471793,1739141223.6069312,62.92993998527527,3.1807744962652835,1739141223.6069324,62.92993998527527,2.3509156662889903 +1739141223.6262116,62.94993996620178,3.3614426830620676,1739141223.6262138,62.94993996620178,0.14097351978361417,1739141223.6262164,62.94993996620178,109.9380423547786,1739141223.626219,62.94993996620178,-5.660774195542622,1739141223.6262202,62.94993996620178,0.065,1739141223.626222,62.94993996620178,-3.1331721373064,1739141223.6262233,62.94993996620178,-0.27750142826385804,1739141223.6262248,62.94993996620178,-0.02617930418917795,1739141223.6262257,62.94993996620178,2.2373455941142724,1739141223.6262271,62.94993996620178,0.0,1739141223.6262288,62.94993996620178,-0.11357007217471793,1739141223.62623,62.94993996620178,3.1807744962652835,1739141223.6262312,62.94993996620178,2.3509156662889903 +1739141223.6463382,62.969939947128296,3.3614426830620676,1739141223.6463406,62.969939947128296,0.14097351978361417,1739141223.6463432,62.969939947128296,109.9380423547786,1739141223.646346,62.969939947128296,-5.660774195542622,1739141223.6463475,62.969939947128296,0.065,1739141223.646349,62.969939947128296,-3.1331721373064,1739141223.6463504,62.969939947128296,-0.27750142826385804,1739141223.6463518,62.969939947128296,-0.02617930418917795,1739141223.6463532,62.969939947128296,2.2373455941142724,1739141223.6463547,62.969939947128296,0.0,1739141223.646356,62.969939947128296,-0.11357007217471793,1739141223.6463575,62.969939947128296,3.1807744962652835,1739141223.646359,62.969939947128296,2.3509156662889903 +1739141223.6663105,62.98993992805481,3.1036798215179617,1739141223.666313,62.98993992805481,0.13080127771382877,1739141223.6663158,62.98993992805481,109.94317726752534,1739141223.6663184,62.98993992805481,-5.627953090116712,1739141223.6663196,62.98993992805481,0.065,1739141223.666321,62.98993992805481,-3.1340568315062014,1739141223.6663227,62.98993992805481,-0.2813043865525147,1739141223.666324,62.98993992805481,-0.02833408610264617,1739141223.666325,62.98993992805481,2.2339447686208738,1739141223.6663265,62.98993992805481,0.0,1739141223.666328,62.98993992805481,-0.09590871944076576,1739141223.6663294,62.98993992805481,3.1813498347586298,1739141223.6663303,62.98993992805481,2.3382636602314366 +1739141223.6865253,63.00993990898132,3.1036798215179617,1739141223.6865294,63.00993990898132,0.13080127771382877,1739141223.6865344,63.00993990898132,109.94317726752534,1739141223.6865401,63.00993990898132,-5.627953090116712,1739141223.6865435,63.00993990898132,0.065,1739141223.6865475,63.00993990898132,-3.1340568315062014,1739141223.6865513,63.00993990898132,-0.2813043865525147,1739141223.6865551,63.00993990898132,-0.02833408610264617,1739141223.6865587,63.00993990898132,2.2339447686208738,1739141223.6865625,63.00993990898132,0.0,1739141223.6865664,63.00993990898132,-0.10431889161056285,1739141223.68657,63.00993990898132,3.1813498347586298,1739141223.6865735,63.00993990898132,2.3382636602314366 +1739141223.7063446,63.02993988990784,3.1036798215179617,1739141223.706347,63.02993988990784,0.13080127771382877,1739141223.70635,63.02993988990784,109.94317726752534,1739141223.706353,63.02993988990784,-5.627953090116712,1739141223.7063541,63.02993988990784,0.065,1739141223.7063558,63.02993988990784,-3.1340568315062014,1739141223.7063572,63.02993988990784,-0.2813043865525147,1739141223.7063587,63.02993988990784,-0.02833408610264617,1739141223.7063599,63.02993988990784,2.2339447686208738,1739141223.7063613,63.02993988990784,0.0,1739141223.706363,63.02993988990784,-0.10431889161056285,1739141223.7063642,63.02993988990784,3.1813498347586298,1739141223.7063656,63.02993988990784,2.3382636602314366 +1739141223.7266202,63.04993987083435,3.1036798215179617,1739141223.7266226,63.04993987083435,0.13080127771382877,1739141223.7266269,63.04993987083435,109.94317726752534,1739141223.7266335,63.04993987083435,-5.627953090116712,1739141223.7266374,63.04993987083435,0.065,1739141223.7266417,63.04993987083435,-3.1340568315062014,1739141223.726644,63.04993987083435,-0.2813043865525147,1739141223.7266486,63.04993987083435,-0.02833408610264617,1739141223.726652,63.04993987083435,2.2339447686208738,1739141223.7266548,63.04993987083435,0.0,1739141223.7266588,63.04993987083435,-0.10431889161056285,1739141223.726661,63.04993987083435,3.1813498347586298,1739141223.7266626,63.04993987083435,2.3382636602314366 +1739141223.7488644,63.069939851760864,3.1036798215179617,1739141223.74887,63.069939851760864,0.13080127771382877,1739141223.7488759,63.069939851760864,109.94317726752534,1739141223.7488813,63.069939851760864,-5.627953090116712,1739141223.7488842,63.069939851760864,0.065,1739141223.748888,63.069939851760864,-3.1340568315062014,1739141223.748891,63.069939851760864,-0.2813043865525147,1739141223.748894,63.069939851760864,-0.02833408610264617,1739141223.7488966,63.069939851760864,2.2339447686208738,1739141223.7489,63.069939851760864,0.0,1739141223.7489033,63.069939851760864,-0.10431889161056285,1739141223.748906,63.069939851760864,3.1813498347586298,1739141223.7489085,63.069939851760864,2.3382636602314366 +1739141223.76806,63.08993983268738,3.1036798215179617,1739141223.7680647,63.08993983268738,0.13080127771382877,1739141223.7680693,63.08993983268738,109.94317726752534,1739141223.7680748,63.08993983268738,-5.627953090116712,1739141223.7680774,63.08993983268738,0.065,1739141223.768081,63.08993983268738,-3.1340568315062014,1739141223.7680836,63.08993983268738,-0.2813043865525147,1739141223.7680857,63.08993983268738,-0.02833408610264617,1739141223.768088,63.08993983268738,2.2339447686208738,1739141223.7680912,63.08993983268738,0.0,1739141223.768094,63.08993983268738,-0.10431889161056285,1739141223.7680962,63.08993983268738,3.1813498347586298,1739141223.7680986,63.08993983268738,2.3382636602314366 +1739141223.7875464,63.10993981361389,2.8472321789861477,1739141223.7875507,63.10993981361389,0.12054080702405301,1739141223.7875552,63.10993981361389,109.9482856994346,1739141223.7875845,63.10993981361389,-5.599302235258342,1739141223.7875872,63.10993981361389,0.065,1739141223.7875907,63.10993981361389,-3.13501717495835,1739141223.7875926,63.10993981361389,-0.2844665442189117,1739141223.787595,63.10993981361389,-0.03061973630906853,1739141223.7875967,63.10993981361389,2.2311209206572946,1739141223.7875993,63.10993981361389,0.0,1739141223.7876017,63.10993981361389,-0.08822668429002986,1739141223.7876039,63.10993981361389,3.1818522658706305,1739141223.7876062,63.10993981361389,2.327010564642228 +1739141223.8076396,63.129939794540405,2.8472321789861477,1739141223.8076437,63.129939794540405,0.12054080702405301,1739141223.8076477,63.129939794540405,109.9482856994346,1739141223.807652,63.129939794540405,-5.599302235258342,1739141223.8076546,63.129939794540405,0.065,1739141223.8076575,63.129939794540405,-3.13501717495835,1739141223.80766,63.129939794540405,-0.2844665442189117,1739141223.8076625,63.129939794540405,-0.03061973630906853,1739141223.8076649,63.129939794540405,2.2311209206572946,1739141223.8076677,63.129939794540405,0.0,1739141223.8076706,63.129939794540405,-0.09588964398493349,1739141223.8076727,63.129939794540405,3.1818522658706305,1739141223.8076751,63.129939794540405,2.327010564642228 +1739141223.8277225,63.14993977546692,2.8472321789861477,1739141223.8277273,63.14993977546692,0.12054080702405301,1739141223.827732,63.14993977546692,109.9482856994346,1739141223.8277364,63.14993977546692,-5.599302235258342,1739141223.8277385,63.14993977546692,0.065,1739141223.8277416,63.14993977546692,-3.13501717495835,1739141223.827744,63.14993977546692,-0.2844665442189117,1739141223.8277464,63.14993977546692,-0.03061973630906853,1739141223.8277485,63.14993977546692,2.2311209206572946,1739141223.8277514,63.14993977546692,0.0,1739141223.827754,63.14993977546692,-0.09588964398493349,1739141223.8277566,63.14993977546692,3.1818522658706305,1739141223.8277588,63.14993977546692,2.327010564642228 +1739141223.8483112,63.16993975639343,2.8472321789861477,1739141223.8483155,63.16993975639343,0.12054080702405301,1739141223.8483198,63.16993975639343,109.9482856994346,1739141223.848324,63.16993975639343,-5.599302235258342,1739141223.8483264,63.16993975639343,0.065,1739141223.8483295,63.16993975639343,-3.13501717495835,1739141223.8483317,63.16993975639343,-0.2844665442189117,1739141223.848334,63.16993975639343,-0.03061973630906853,1739141223.8483365,63.16993975639343,2.2311209206572946,1739141223.848339,63.16993975639343,0.0,1739141223.8483422,63.16993975639343,-0.09588964398493349,1739141223.8483446,63.16993975639343,3.1818522658706305,1739141223.8483472,63.16993975639343,2.327010564642228 +1739141223.8676398,63.189939737319946,2.8472321789861477,1739141223.8676443,63.189939737319946,0.12054080702405301,1739141223.867649,63.189939737319946,109.9482856994346,1739141223.8676538,63.189939737319946,-5.599302235258342,1739141223.8676565,63.189939737319946,0.065,1739141223.8676593,63.189939737319946,-3.13501717495835,1739141223.8676622,63.189939737319946,-0.2844665442189117,1739141223.8676643,63.189939737319946,-0.03061973630906853,1739141223.867667,63.189939737319946,2.2311209206572946,1739141223.8676698,63.189939737319946,0.0,1739141223.8676727,63.189939737319946,-0.09588964398493349,1739141223.8676975,63.189939737319946,3.1818522658706305,1739141223.8677003,63.189939737319946,2.327010564642228 +1739141223.8863397,63.20993971824646,2.591990091909052,1739141223.886342,63.20993971824646,0.11021265748347098,1739141223.886345,63.20993971824646,109.95336988487706,1739141223.8863478,63.20993971824646,-5.573132924881158,1739141223.886349,63.20993971824646,0.065,1739141223.8863509,63.20993971824646,-3.1360554197597885,1739141223.8863523,63.20993971824646,-0.28648766722579905,1739141223.8863537,63.20993971824646,-0.03299976551097614,1739141223.886355,63.20993971824646,2.2293179016505817,1739141223.886356,63.20993971824646,0.0,1739141223.8863578,63.20993971824646,-0.07944317546185825,1739141223.886359,63.20993971824646,3.1822233068444366,1739141223.8863604,63.20993971824646,2.316592732702349 +1739141223.9059808,63.229939699172974,2.591990091909052,1739141223.905983,63.229939699172974,0.11021265748347098,1739141223.9059856,63.229939699172974,109.95336988487706,1739141223.9059877,63.229939699172974,-5.573132924881158,1739141223.9059892,63.229939699172974,0.065,1739141223.9059906,63.229939699172974,-3.1360554197597885,1739141223.905992,63.229939699172974,-0.28648766722579905,1739141223.905993,63.229939699172974,-0.03299976551097614,1739141223.905994,63.229939699172974,2.2293179016505817,1739141223.9059956,63.229939699172974,0.0,1739141223.9059966,63.229939699172974,-0.08727483105176725,1739141223.9059975,63.229939699172974,3.1822233068444366,1739141223.905999,63.229939699172974,2.316592732702349 +1739141223.9261868,63.24993968009949,2.591990091909052,1739141223.926189,63.24993968009949,0.11021265748347098,1739141223.9261918,63.24993968009949,109.95336988487706,1739141223.9261947,63.24993968009949,-5.573132924881158,1739141223.9261959,63.24993968009949,0.065,1739141223.9261978,63.24993968009949,-3.1360554197597885,1739141223.9261992,63.24993968009949,-0.28648766722579905,1739141223.9262006,63.24993968009949,-0.03299976551097614,1739141223.9262016,63.24993968009949,2.2293179016505817,1739141223.9262037,63.24993968009949,0.0,1739141223.9262052,63.24993968009949,-0.08727483105176725,1739141223.926206,63.24993968009949,3.1822233068444366,1739141223.9262075,63.24993968009949,2.316592732702349 +1739141223.9462502,63.269939661026,2.591990091909052,1739141223.9462528,63.269939661026,0.11021265748347098,1739141223.9462557,63.269939661026,109.95336988487706,1739141223.946258,63.269939661026,-5.573132924881158,1739141223.9462597,63.269939661026,0.065,1739141223.9462614,63.269939661026,-3.1360554197597885,1739141223.9462628,63.269939661026,-0.28648766722579905,1739141223.946264,63.269939661026,-0.03299976551097614,1739141223.9462655,63.269939661026,2.2293179016505817,1739141223.946267,63.269939661026,0.0,1739141223.9462683,63.269939661026,-0.08727483105176725,1739141223.9462698,63.269939661026,3.1822233068444366,1739141223.946271,63.269939661026,2.316592732702349 +1739141223.9661844,63.289939641952515,2.591990091909052,1739141223.9661868,63.289939641952515,0.11021265748347098,1739141223.9661896,63.289939641952515,109.95336988487706,1739141223.9661925,63.289939641952515,-5.573132924881158,1739141223.9661937,63.289939641952515,0.065,1739141223.9661953,63.289939641952515,-3.1360554197597885,1739141223.9661968,63.289939641952515,-0.28648766722579905,1739141223.966198,63.289939641952515,-0.03299976551097614,1739141223.9661994,63.289939641952515,2.2293179016505817,1739141223.9662008,63.289939641952515,0.0,1739141223.966202,63.289939641952515,-0.08727483105176725,1739141223.9662035,63.289939641952515,3.1822233068444366,1739141223.9662046,63.289939641952515,2.316592732702349 +1739141223.9862525,63.30993962287903,2.591990091909052,1739141223.986255,63.30993962287903,0.11021265748347098,1739141223.986258,63.30993962287903,109.95336988487706,1739141223.9862604,63.30993962287903,-5.573132924881158,1739141223.986262,63.30993962287903,0.065,1739141223.9862638,63.30993962287903,-3.1360554197597885,1739141223.9862657,63.30993962287903,-0.28648766722579905,1739141223.986267,63.30993962287903,-0.03299976551097614,1739141223.9862685,63.30993962287903,2.2293179016505817,1739141223.9862702,63.30993962287903,0.0,1739141223.9862719,63.30993962287903,-0.08727483105176725,1739141223.986273,63.30993962287903,3.1822233068444366,1739141223.9862745,63.30993962287903,2.316592732702349 +1739141224.0063694,63.32993960380554,2.3378398909673237,1739141224.0063722,63.32993960380554,0.09984960613097726,1739141224.006375,63.32993960380554,110.22601502062042,1739141224.006378,63.32993960380554,-5.817581221259594,1739141224.0063796,63.32993960380554,0.065,1739141224.0063815,63.32993960380554,-3.1373194966878097,1739141224.0063832,63.32993960380554,-0.29857886809744355,1739141224.0063844,63.32993960380554,-0.03447469695323638,1739141224.0063856,63.32993960380554,2.2185618810361545,1739141224.0063875,63.32993960380554,0.0,1739141224.0063896,63.32993960380554,-0.08986561016909192,1739141224.0063908,63.32993960380554,3.182484751138523,1739141224.006392,63.32993960380554,2.3071937862473737 +1739141224.026301,63.349939584732056,2.3378398909673237,1739141224.0263035,63.349939584732056,0.09984960613097726,1739141224.0263066,63.349939584732056,110.22601502062042,1739141224.0263097,63.349939584732056,-5.817581221259594,1739141224.0263112,63.349939584732056,0.065,1739141224.026313,63.349939584732056,-3.1373194966878097,1739141224.0263145,63.349939584732056,-0.29857886809744355,1739141224.026316,63.349939584732056,-0.03447469695323638,1739141224.0263176,63.349939584732056,2.2185618810361545,1739141224.0263193,63.349939584732056,0.0,1739141224.026321,63.349939584732056,-0.08863190521121922,1739141224.0263221,63.349939584732056,3.182484751138523,1739141224.0263238,63.349939584732056,2.3071937862473737 +1739141224.0463548,63.36993956565857,2.3378398909673237,1739141224.0463574,63.36993956565857,0.09984960613097726,1739141224.0463605,63.36993956565857,110.22601502062042,1739141224.0463636,63.36993956565857,-5.817581221259594,1739141224.0463653,63.36993956565857,0.065,1739141224.046367,63.36993956565857,-3.1373194966878097,1739141224.0463686,63.36993956565857,-0.29857886809744355,1739141224.04637,63.36993956565857,-0.03447469695323638,1739141224.0463712,63.36993956565857,2.2185618810361545,1739141224.0463731,63.36993956565857,0.0,1739141224.0463748,63.36993956565857,-0.08863190521121922,1739141224.0463762,63.36993956565857,3.182484751138523,1739141224.0463774,63.36993956565857,2.3071937862473737 +1739141224.071338,63.38993954658508,2.3378398909673237,1739141224.0713472,63.38993954658508,0.09984960613097726,1739141224.0713575,63.38993954658508,110.22601502062042,1739141224.0713673,63.38993954658508,-5.817581221259594,1739141224.0713725,63.38993954658508,0.065,1739141224.0713787,63.38993954658508,-3.1373194966878097,1739141224.0713837,63.38993954658508,-0.29857886809744355,1739141224.0713887,63.38993954658508,-0.03447469695323638,1739141224.0713933,63.38993954658508,2.2185618810361545,1739141224.071399,63.38993954658508,0.0,1739141224.071404,63.38993954658508,-0.08863190521121922,1739141224.0714087,63.38993954658508,3.182484751138523,1739141224.071413,63.38993954658508,2.3071937862473737 +1739141224.0916438,63.4099395275116,2.3378398909673237,1739141224.0916529,63.4099395275116,0.09984960613097726,1739141224.0916634,63.4099395275116,110.22601502062042,1739141224.0916739,63.4099395275116,-5.817581221259594,1739141224.0916786,63.4099395275116,0.065,1739141224.0916848,63.4099395275116,-3.1373194966878097,1739141224.0916896,63.4099395275116,-0.29857886809744355,1739141224.091694,63.4099395275116,-0.03447469695323638,1739141224.0916984,63.4099395275116,2.2185618810361545,1739141224.0917041,63.4099395275116,0.0,1739141224.0917094,63.4099395275116,-0.08863190521121922,1739141224.0917141,63.4099395275116,3.182484751138523,1739141224.0917187,63.4099395275116,2.3071937862473737 +1739141224.114218,63.42993950843811,2.0847471886959488,1739141224.1142232,63.42993950843811,0.08947114302356418,1739141224.1142297,63.42993950843811,110.43150888884847,1739141224.1142352,63.42993950843811,-5.993960448563392,1739141224.1142378,63.42993950843811,0.065,1739141224.1142414,63.42993950843811,-3.138563571553579,1739141224.1142437,63.42993950843811,-0.3073326243862025,1739141224.1142464,63.42993950843811,-0.03616271933951785,1739141224.114249,63.42993950843811,2.2108071655299004,1739141224.1142523,63.42993950843811,0.0,1739141224.1142552,63.42993950843811,-0.08490886162606441,1739141224.1142576,63.42993950843811,3.1826730434623194,1739141224.1142602,63.42993950843811,2.297488905939288 +1739141224.1345072,63.45993947982788,2.0847471886959488,1739141224.134513,63.45993947982788,0.08947114302356418,1739141224.134519,63.45993947982788,110.43150888884847,1739141224.1345246,63.45993947982788,-5.993960448563392,1739141224.1345272,63.45993947982788,0.065,1739141224.1345305,63.45993947982788,-3.138563571553579,1739141224.1345334,63.45993947982788,-0.3073326243862025,1739141224.134536,63.45993947982788,-0.03616271933951785,1739141224.1345382,63.45993947982788,2.2108071655299004,1739141224.1345415,63.45993947982788,0.0,1739141224.1345441,63.45993947982788,-0.08668174040938759,1739141224.1345468,63.45993947982788,3.1826730434623194,1739141224.1345491,63.45993947982788,2.297488905939288 +1739141224.1540272,63.479939460754395,2.0847471886959488,1739141224.1540322,63.479939460754395,0.08947114302356418,1739141224.1540377,63.479939460754395,110.43150888884847,1739141224.154043,63.479939460754395,-5.993960448563392,1739141224.154046,63.479939460754395,0.065,1739141224.1540496,63.479939460754395,-3.138563571553579,1739141224.154052,63.479939460754395,-0.3073326243862025,1739141224.1540546,63.479939460754395,-0.03616271933951785,1739141224.1540573,63.479939460754395,2.2108071655299004,1739141224.1540601,63.479939460754395,0.0,1739141224.1540627,63.479939460754395,-0.08668174040938759,1739141224.1540654,63.479939460754395,3.1826730434623194,1739141224.154068,63.479939460754395,2.297488905939288 +1739141224.1750638,63.48993945121765,2.0847471886959488,1739141224.1750674,63.48993945121765,0.08947114302356418,1739141224.1750715,63.48993945121765,110.43150888884847,1739141224.1750753,63.48993945121765,-5.993960448563392,1739141224.1750772,63.48993945121765,0.065,1739141224.175079,63.48993945121765,-3.138563571553579,1739141224.175081,63.48993945121765,-0.3073326243862025,1739141224.1750827,63.48993945121765,-0.03616271933951785,1739141224.1750846,63.48993945121765,2.2108071655299004,1739141224.1750865,63.48993945121765,0.0,1739141224.1750886,63.48993945121765,-0.08668174040938759,1739141224.1750903,63.48993945121765,3.1826730434623194,1739141224.1750922,63.48993945121765,2.297488905939288 +1739141224.193108,63.509939432144165,2.0847471886959488,1739141224.1931112,63.509939432144165,0.08947114302356418,1739141224.193115,63.509939432144165,110.43150888884847,1739141224.193118,63.509939432144165,-5.993960448563392,1739141224.19312,63.509939432144165,0.065,1739141224.1931224,63.509939432144165,-3.138563571553579,1739141224.1931238,63.509939432144165,-0.3073326243862025,1739141224.1931257,63.509939432144165,-0.03616271933951785,1739141224.1931272,63.509939432144165,2.2108071655299004,1739141224.193129,63.509939432144165,0.0,1739141224.193131,63.509939432144165,-0.08668174040938759,1739141224.1931326,63.509939432144165,3.1826730434623194,1739141224.193134,63.509939432144165,2.297488905939288 +1739141224.2126312,63.52993941307068,2.0847471886959488,1739141224.212634,63.52993941307068,0.08947114302356418,1739141224.2126374,63.52993941307068,110.43150888884847,1739141224.2126405,63.52993941307068,-5.993960448563392,1739141224.212642,63.52993941307068,0.065,1739141224.2126439,63.52993941307068,-3.138563571553579,1739141224.2126453,63.52993941307068,-0.3073326243862025,1739141224.212647,63.52993941307068,-0.03616271933951785,1739141224.2126484,63.52993941307068,2.2108071655299004,1739141224.2126503,63.52993941307068,0.0,1739141224.2126524,63.52993941307068,-0.08668174040938759,1739141224.212654,63.52993941307068,3.1826730434623194,1739141224.2126555,63.52993941307068,2.297488905939288 +1739141224.233037,63.55993938446045,1.8327101885160424,1739141224.2330399,63.55993938446045,0.07909766728015288,1739141224.2330432,63.55993938446045,110.63682501060818,1739141224.2330463,63.55993938446045,-6.170883607243077,1739141224.2330477,63.55993938446045,0.065,1739141224.2330496,63.55993938446045,-3.139831238273103,1739141224.2330513,63.55993938446045,-0.31547426853815747,1739141224.2330527,63.55993938446045,-0.0378208014707609,1739141224.2330542,63.55993938446045,2.20361903443187,1739141224.233056,63.55993938446045,0.0,1739141224.2330577,63.55993938446045,-0.08233628493584685,1739141224.2330592,63.55993938446045,3.182780798234019,1739141224.2330606,63.55993938446045,2.2880245849126153 +1739141224.2587826,63.569939374923706,1.8327101885160424,1739141224.2587917,63.569939374923706,0.07909766728015288,1739141224.258802,63.569939374923706,110.63682501060818,1739141224.258812,63.569939374923706,-6.170883607243077,1739141224.2588167,63.569939374923706,0.065,1739141224.258823,63.569939374923706,-3.139831238273103,1739141224.2588277,63.569939374923706,-0.31547426853815747,1739141224.2588327,63.569939374923706,-0.0378208014707609,1739141224.258837,63.569939374923706,2.20361903443187,1739141224.258843,63.569939374923706,0.0,1739141224.258848,63.569939374923706,-0.08440555048074527,1739141224.2588522,63.569939374923706,3.182780798234019,1739141224.2588568,63.569939374923706,2.2880245849126153 +1739141224.2761815,63.58993935585022,1.8327101885160424,1739141224.2761865,63.58993935585022,0.07909766728015288,1739141224.2761915,63.58993935585022,110.63682501060818,1739141224.2761967,63.58993935585022,-6.170883607243077,1739141224.2761989,63.58993935585022,0.065,1739141224.2762022,63.58993935585022,-3.139831238273103,1739141224.276205,63.58993935585022,-0.31547426853815747,1739141224.2762074,63.58993935585022,-0.0378208014707609,1739141224.2762098,63.58993935585022,2.20361903443187,1739141224.276213,63.58993935585022,0.0,1739141224.2762158,63.58993935585022,-0.08440555048074527,1739141224.2762182,63.58993935585022,3.182780798234019,1739141224.2762206,63.58993935585022,2.2880245849126153 +1739141224.2927623,63.61993932723999,1.8327101885160424,1739141224.292765,63.61993932723999,0.07909766728015288,1739141224.2927682,63.61993932723999,110.63682501060818,1739141224.2927713,63.61993932723999,-6.170883607243077,1739141224.292773,63.61993932723999,0.065,1739141224.292775,63.61993932723999,-3.139831238273103,1739141224.2927768,63.61993932723999,-0.31547426853815747,1739141224.2927783,63.61993932723999,-0.0378208014707609,1739141224.2927794,63.61993932723999,2.20361903443187,1739141224.2927814,63.61993932723999,0.0,1739141224.2927828,63.61993932723999,-0.08440555048074527,1739141224.2927845,63.61993932723999,3.182780798234019,1739141224.2927861,63.61993932723999,2.2880245849126153 +1739141224.3131108,63.639939308166504,1.8327101885160424,1739141224.313115,63.639939308166504,0.07909766728015288,1739141224.313119,63.639939308166504,110.63682501060818,1739141224.313124,63.639939308166504,-6.170883607243077,1739141224.3131266,63.639939308166504,0.065,1739141224.31313,63.639939308166504,-3.139831238273103,1739141224.313133,63.639939308166504,-0.31547426853815747,1739141224.313136,63.639939308166504,-0.0378208014707609,1739141224.3131392,63.639939308166504,2.20361903443187,1739141224.313143,63.639939308166504,0.0,1739141224.3131464,63.639939308166504,-0.08440555048074527,1739141224.3131492,63.639939308166504,3.182780798234019,1739141224.3131526,63.639939308166504,2.2880245849126153 +1739141224.332779,63.65993928909302,1.5817033811412786,1739141224.3327816,63.65993928909302,0.0687426788858243,1739141224.3327844,63.65993928909302,111.17494648478261,1739141224.332787,63.65993928909302,-6.681326022962772,1739141224.3327882,63.65993928909302,0.065,1739141224.3327897,63.65993928909302,-3.141139710916248,1739141224.332791,63.65993928909302,-0.3372718479100939,1739141224.3327923,63.65993928909302,-0.03793494672963478,1739141224.3327932,63.65993928909302,2.184489128427571,1739141224.332795,63.65993928909302,0.0,1739141224.332796,63.65993928909302,-0.10331234242209994,1739141224.3327975,63.65993928909302,3.182873907241926,1739141224.3327987,63.65993928909302,2.278798232094372 +1739141224.3527195,63.67993927001953,1.5817033811412786,1739141224.352722,63.67993927001953,0.0687426788858243,1739141224.3527246,63.67993927001953,111.17494648478261,1739141224.352727,63.67993927001953,-6.681326022962772,1739141224.3527284,63.67993927001953,0.065,1739141224.3527298,63.67993927001953,-3.141139710916248,1739141224.3527312,63.67993927001953,-0.3372718479100939,1739141224.3527324,63.67993927001953,-0.03793494672963478,1739141224.3527336,63.67993927001953,2.184489128427571,1739141224.352735,63.67993927001953,0.0,1739141224.3527365,63.67993927001953,-0.0943091036668009,1739141224.352738,63.67993927001953,3.182873907241926,1739141224.352739,63.67993927001953,2.278798232094372 +1739141224.3735194,63.699939250946045,1.5817033811412786,1739141224.3735216,63.699939250946045,0.0687426788858243,1739141224.3735242,63.699939250946045,111.17494648478261,1739141224.3735268,63.699939250946045,-6.681326022962772,1739141224.373528,63.699939250946045,0.065,1739141224.3735297,63.699939250946045,-3.141139710916248,1739141224.3735309,63.699939250946045,-0.3372718479100939,1739141224.373532,63.699939250946045,-0.03793494672963478,1739141224.3735332,63.699939250946045,2.184489128427571,1739141224.3735347,63.699939250946045,0.0,1739141224.3735363,63.699939250946045,-0.0943091036668009,1739141224.3735373,63.699939250946045,3.182873907241926,1739141224.3735385,63.699939250946045,2.278798232094372 +1739141224.3946826,63.7099392414093,1.5817033811412786,1739141224.394688,63.7099392414093,0.0687426788858243,1739141224.3946939,63.7099392414093,111.17494648478261,1739141224.3947,63.7099392414093,-6.681326022962772,1739141224.3947036,63.7099392414093,0.065,1739141224.3947082,63.7099392414093,-3.141139710916248,1739141224.3947117,63.7099392414093,-0.3372718479100939,1739141224.3947155,63.7099392414093,-0.03793494672963478,1739141224.3947191,63.7099392414093,2.184489128427571,1739141224.3947234,63.7099392414093,0.0,1739141224.3947272,63.7099392414093,-0.0943091036668009,1739141224.394731,63.7099392414093,3.182873907241926,1739141224.394735,63.7099392414093,2.278798232094372 +1739141224.415155,63.729939222335815,1.5817033811412786,1739141224.4151595,63.729939222335815,0.0687426788858243,1739141224.4151652,63.729939222335815,111.17494648478261,1739141224.4151714,63.729939222335815,-6.681326022962772,1739141224.4151747,63.729939222335815,0.065,1739141224.4151788,63.729939222335815,-3.141139710916248,1739141224.4151833,63.729939222335815,-0.3372718479100939,1739141224.4151876,63.729939222335815,-0.03793494672963478,1739141224.415191,63.729939222335815,2.184489128427571,1739141224.415195,63.729939222335815,0.0,1739141224.4151993,63.729939222335815,-0.0943091036668009,1739141224.4152033,63.729939222335815,3.182873907241926,1739141224.4152076,63.729939222335815,2.278798232094372 +1739141224.4331224,63.759939193725586,1.331770603756003,1739141224.4331248,63.759939193725586,0.05841468825677776,1739141224.4331276,63.759939193725586,111.19741977876603,1739141224.43313,63.759939193725586,-6.6726101946487475,1739141224.4331312,63.759939193725586,0.065,1739141224.4331331,63.759939193725586,3.1407699403252316,1739141224.4331343,63.759939193725586,-0.3371337442209448,1739141224.4331353,63.759939193725586,-0.04040930681149733,1739141224.4331367,63.759939193725586,2.184609806163765,1739141224.4331381,63.759939193725586,0.0,1739141224.4331396,63.759939193725586,-0.07423108649945964,1739141224.4331408,63.759939193725586,3.1829010428198097,1739141224.433142,63.759939193725586,2.2684018579952214 +1739141224.4527078,63.7799391746521,1.331770603756003,1739141224.4527104,63.7799391746521,0.05841468825677776,1739141224.4527133,63.7799391746521,111.19741977876603,1739141224.4527159,63.7799391746521,-6.6726101946487475,1739141224.452717,63.7799391746521,0.065,1739141224.4527185,63.7799391746521,3.1407699403252316,1739141224.4527202,63.7799391746521,-0.3371337442209448,1739141224.4527214,63.7799391746521,-0.04040930681149733,1739141224.4527228,63.7799391746521,2.184609806163765,1739141224.4527242,63.7799391746521,0.0,1739141224.4527256,63.7799391746521,-0.08379205183145633,1739141224.452727,63.7799391746521,3.1829010428198097,1739141224.4527283,63.7799391746521,2.2684018579952214 +1739141224.4726255,63.79993915557861,1.331770603756003,1739141224.4726276,63.79993915557861,0.05841468825677776,1739141224.4726305,63.79993915557861,111.19741977876603,1739141224.4726331,63.79993915557861,-6.6726101946487475,1739141224.4726343,63.79993915557861,0.065,1739141224.472636,63.79993915557861,3.1407699403252316,1739141224.4726374,63.79993915557861,-0.3371337442209448,1739141224.4726386,63.79993915557861,-0.04040930681149733,1739141224.4726398,63.79993915557861,2.184609806163765,1739141224.4726412,63.79993915557861,0.0,1739141224.472643,63.79993915557861,-0.08379205183145633,1739141224.472644,63.79993915557861,3.1829010428198097,1739141224.4726453,63.79993915557861,2.2684018579952214 +1739141224.4928339,63.81993913650513,1.331770603756003,1739141224.4928362,63.81993913650513,0.05841468825677776,1739141224.4928389,63.81993913650513,111.19741977876603,1739141224.4928417,63.81993913650513,-6.6726101946487475,1739141224.492843,63.81993913650513,0.065,1739141224.4928446,63.81993913650513,3.1407699403252316,1739141224.492846,63.81993913650513,-0.3371337442209448,1739141224.4928472,63.81993913650513,-0.04040930681149733,1739141224.4928484,63.81993913650513,2.184609806163765,1739141224.4928498,63.81993913650513,0.0,1739141224.4928515,63.81993913650513,-0.08379205183145633,1739141224.4928524,63.81993913650513,3.1829010428198097,1739141224.4928536,63.81993913650513,2.2684018579952214 +1739141224.5122373,63.829939126968384,1.331770603756003,1739141224.5122402,63.829939126968384,0.05841468825677776,1739141224.512243,63.829939126968384,111.19741977876603,1739141224.5122454,63.829939126968384,-6.6726101946487475,1739141224.512247,63.829939126968384,0.065,1739141224.5122488,63.829939126968384,3.1407699403252316,1739141224.5122502,63.829939126968384,-0.3371337442209448,1739141224.5122514,63.829939126968384,-0.04040930681149733,1739141224.5122526,63.829939126968384,2.184609806163765,1739141224.5122545,63.829939126968384,0.0,1739141224.512256,63.829939126968384,-0.08379205183145633,1739141224.5122573,63.829939126968384,3.1829010428198097,1739141224.5122585,63.829939126968384,2.2684018579952214 +1739141224.5325608,63.859939098358154,1.331770603756003,1739141224.5325634,63.859939098358154,0.05841468825677776,1739141224.5325663,63.859939098358154,111.19741977876603,1739141224.532569,63.859939098358154,-6.6726101946487475,1739141224.5325701,63.859939098358154,0.065,1739141224.5325718,63.859939098358154,3.1407699403252316,1739141224.5325732,63.859939098358154,-0.3371337442209448,1739141224.5325744,63.859939098358154,-0.04040930681149733,1739141224.5325758,63.859939098358154,2.184609806163765,1739141224.5325775,63.859939098358154,0.0,1739141224.5325792,63.859939098358154,-0.08379205183145633,1739141224.5325804,63.859939098358154,3.1829010428198097,1739141224.5325818,63.859939098358154,2.2684018579952214 +1739141224.5521142,63.87993907928467,1.082900082845418,1739141224.5521164,63.87993907928467,0.04813446417213285,1739141224.5521197,63.87993907928467,111.81372379357373,1739141224.5521224,63.87993907928467,-7.261962715073032,1739141224.5521238,63.87993907928467,0.065,1739141224.5521257,63.87993907928467,3.1395715882622137,1739141224.5521271,63.87993907928467,-0.3609579456244791,1739141224.5521283,63.87993907928467,-0.039806332161145784,1739141224.5521297,63.87993907928467,2.1638900556662524,1739141224.5521314,63.87993907928467,0.0,1739141224.5521328,63.87993907928467,-0.10619699834840565,1739141224.552134,63.87993907928467,3.1828401081089908,1739141224.5521355,63.87993907928467,2.2594180265340844 +1739141224.573542,63.889939069747925,1.082900082845418,1739141224.5735445,63.889939069747925,0.04813446417213285,1739141224.5735474,63.889939069747925,111.81372379357373,1739141224.5735497,63.889939069747925,-7.261962715073032,1739141224.5735512,63.889939069747925,0.065,1739141224.5735528,63.889939069747925,3.1395715882622137,1739141224.5735543,63.889939069747925,-0.3609579456244791,1739141224.5735555,63.889939069747925,-0.039806332161145784,1739141224.5735567,63.889939069747925,2.1638900556662524,1739141224.5735583,63.889939069747925,0.0,1739141224.5735598,63.889939069747925,-0.09552797086783205,1739141224.5735612,63.889939069747925,3.1828401081089908,1739141224.5735621,63.889939069747925,2.2594180265340844 +1739141224.6009567,63.919939041137695,1.082900082845418,1739141224.600965,63.919939041137695,0.04813446417213285,1739141224.600975,63.919939041137695,111.81372379357373,1739141224.600985,63.919939041137695,-7.261962715073032,1739141224.6009903,63.919939041137695,0.065,1739141224.6009965,63.919939041137695,3.1395715882622137,1739141224.6010015,63.919939041137695,-0.3609579456244791,1739141224.601006,63.919939041137695,-0.039806332161145784,1739141224.6010103,63.919939041137695,2.1638900556662524,1739141224.601016,63.919939041137695,0.0,1739141224.6010206,63.919939041137695,-0.09552797086783205,1739141224.6010253,63.919939041137695,3.1828401081089908,1739141224.6010296,63.919939041137695,2.2594180265340844 +1739141224.644238,63.95993900299072,1.082900082845418,1739141224.6442478,63.95993900299072,0.04813446417213285,1739141224.6442585,63.95993900299072,111.81372379357373,1739141224.6442688,63.95993900299072,-7.261962715073032,1739141224.6442738,63.95993900299072,0.065,1739141224.64428,63.95993900299072,3.1395715882622137,1739141224.6442852,63.95993900299072,-0.3609579456244791,1739141224.6442897,63.95993900299072,-0.039806332161145784,1739141224.6442945,63.95993900299072,2.1638900556662524,1739141224.6443005,63.95993900299072,0.0,1739141224.644306,63.95993900299072,-0.09552797086783205,1739141224.6443105,63.95993900299072,3.1828401081089908,1739141224.6443152,63.95993900299072,2.2594180265340844 +1739141224.6627576,63.979938983917236,0.8350956681978943,1739141224.6627645,63.979938983917236,0.037915059250862804,1739141224.662772,63.979938983917236,111.74412187370157,1739141224.6627796,63.979938983917236,-7.16104290713637,1739141224.6627839,63.979938983917236,0.065,1739141224.662789,63.979938983917236,3.13820541399802,1739141224.6627936,63.979938983917236,-0.35624334833176363,1739141224.6627984,63.979938983917236,-0.042787107534810145,1739141224.662803,63.979938983917236,2.167974653982221,1739141224.6628075,63.979938983917236,0.0,1739141224.662812,63.979938983917236,-0.06780052363167437,1739141224.6628163,63.979938983917236,3.1827718324455243,1739141224.6628208,63.979938983917236,2.248978730512579 +1739141224.6792681,63.99993896484375,0.8350956681978943,1739141224.6792715,63.99993896484375,0.037915059250862804,1739141224.6792753,63.99993896484375,111.74412187370157,1739141224.6792789,63.99993896484375,-7.16104290713637,1739141224.6792808,63.99993896484375,0.065,1739141224.679283,63.99993896484375,3.13820541399802,1739141224.6792848,63.99993896484375,-0.35624334833176363,1739141224.6792865,63.99993896484375,-0.042787107534810145,1739141224.6792884,63.99993896484375,2.167974653982221,1739141224.6792903,63.99993896484375,0.0,1739141224.6792924,63.99993896484375,-0.08100407653035813,1739141224.679294,63.99993896484375,3.1827718324455243,1739141224.6792958,63.99993896484375,2.248978730512579 +1739141224.7010658,64.01993894577026,0.8350956681978943,1739141224.70107,64.01993894577026,0.037915059250862804,1739141224.701076,64.01993894577026,111.74412187370157,1739141224.7010827,64.01993894577026,-7.16104290713637,1739141224.7010865,64.01993894577026,0.065,1739141224.7010913,64.01993894577026,3.13820541399802,1739141224.7010958,64.01993894577026,-0.35624334833176363,1739141224.7011003,64.01993894577026,-0.042787107534810145,1739141224.7011046,64.01993894577026,2.167974653982221,1739141224.7011092,64.01993894577026,0.0,1739141224.701114,64.01993894577026,-0.08100407653035813,1739141224.7011182,64.01993894577026,3.1827718324455243,1739141224.7011228,64.01993894577026,2.248978730512579 +1739141224.718342,64.03993892669678,0.8350956681978943,1739141224.7183464,64.03993892669678,0.037915059250862804,1739141224.7183511,64.03993892669678,111.74412187370157,1739141224.718356,64.03993892669678,-7.16104290713637,1739141224.718359,64.03993892669678,0.065,1739141224.7183626,64.03993892669678,3.13820541399802,1739141224.718366,64.03993892669678,-0.35624334833176363,1739141224.7183695,64.03993892669678,-0.042787107534810145,1739141224.7183728,64.03993892669678,2.167974653982221,1739141224.7183764,64.03993892669678,0.0,1739141224.7183797,64.03993892669678,-0.08100407653035813,1739141224.718383,64.03993892669678,3.1827718324455243,1739141224.7183864,64.03993892669678,2.248978730512579 +1739141224.7407532,64.05993890762329,0.8350956681978943,1739141224.740757,64.05993890762329,0.037915059250862804,1739141224.7407613,64.05993890762329,111.74412187370157,1739141224.7407665,64.05993890762329,-7.16104290713637,1739141224.7407696,64.05993890762329,0.065,1739141224.7407732,64.05993890762329,3.13820541399802,1739141224.7407765,64.05993890762329,-0.35624334833176363,1739141224.7407796,64.05993890762329,-0.042787107534810145,1739141224.7407827,64.05993890762329,2.167974653982221,1739141224.740786,64.05993890762329,0.0,1739141224.7407897,64.05993890762329,-0.08100407653035813,1739141224.7407928,64.05993890762329,3.1827718324455243,1739141224.7407959,64.05993890762329,2.248978730512579 +1739141224.7605984,64.0799388885498,0.8350956681978943,1739141224.7606025,64.0799388885498,0.037915059250862804,1739141224.760607,64.0799388885498,111.74412187370157,1739141224.7606118,64.0799388885498,-7.16104290713637,1739141224.7606146,64.0799388885498,0.065,1739141224.7606182,64.0799388885498,3.13820541399802,1739141224.7606215,64.0799388885498,-0.35624334833176363,1739141224.7606246,64.0799388885498,-0.042787107534810145,1739141224.7606485,64.0799388885498,2.167974653982221,1739141224.7606523,64.0799388885498,0.0,1739141224.7606559,64.0799388885498,-0.08100407653035813,1739141224.76068,64.0799388885498,3.1827718324455243,1739141224.7606833,64.0799388885498,2.248978730512579 +1739141224.779703,64.09993886947632,0.5883360237491218,1739141224.7797055,64.09993886947632,0.02776304509787142,1739141224.7797086,64.09993886947632,112.0133470985516,1739141224.7797294,64.09993886947632,-7.4044483977347895,1739141224.779731,64.09993886947632,0.065,1739141224.7797327,64.09993886947632,3.1369338659211383,1739141224.7797344,64.09993886947632,-0.36511657073291975,1739141224.7797356,64.09993886947632,-0.04388904727748532,1739141224.7797368,64.09993886947632,2.160293524813314,1739141224.7797384,64.09993886947632,0.0,1739141224.7797399,64.09993886947632,-0.07923730961762822,1739141224.7797413,64.09993886947632,3.182630044861556,1739141224.7797425,64.09993886947632,2.2403721524287077 +1739141224.79827,64.11993885040283,0.5883360237491218,1739141224.7982726,64.11993885040283,0.02776304509787142,1739141224.798275,64.11993885040283,112.0133470985516,1739141224.7982779,64.11993885040283,-7.4044483977347895,1739141224.7982793,64.11993885040283,0.065,1739141224.7982807,64.11993885040283,3.1369338659211383,1739141224.7982821,64.11993885040283,-0.36511657073291975,1739141224.7982836,64.11993885040283,-0.04388904727748532,1739141224.7982845,64.11993885040283,2.160293524813314,1739141224.798286,64.11993885040283,0.0,1739141224.7982876,64.11993885040283,-0.08007862761539375,1739141224.7982888,64.11993885040283,3.182630044861556,1739141224.7982903,64.11993885040283,2.2403721524287077 +1739141224.8183289,64.13993883132935,0.5883360237491218,1739141224.8183312,64.13993883132935,0.02776304509787142,1739141224.8183339,64.13993883132935,112.0133470985516,1739141224.8183365,64.13993883132935,-7.4044483977347895,1739141224.8183377,64.13993883132935,0.065,1739141224.8183396,64.13993883132935,3.1369338659211383,1739141224.8183408,64.13993883132935,-0.36511657073291975,1739141224.8183422,64.13993883132935,-0.04388904727748532,1739141224.8183434,64.13993883132935,2.160293524813314,1739141224.818345,64.13993883132935,0.0,1739141224.8183463,64.13993883132935,-0.08007862761539375,1739141224.8183475,64.13993883132935,3.182630044861556,1739141224.818349,64.13993883132935,2.2403721524287077 +1739141224.8383234,64.15993881225586,0.5883360237491218,1739141224.8383265,64.15993881225586,0.02776304509787142,1739141224.8383296,64.15993881225586,112.0133470985516,1739141224.8383322,64.15993881225586,-7.4044483977347895,1739141224.8383336,64.15993881225586,0.065,1739141224.8383355,64.15993881225586,3.1369338659211383,1739141224.838337,64.15993881225586,-0.36511657073291975,1739141224.8383384,64.15993881225586,-0.04388904727748532,1739141224.8383396,64.15993881225586,2.160293524813314,1739141224.8383412,64.15993881225586,0.0,1739141224.8383427,64.15993881225586,-0.08007862761539375,1739141224.8383443,64.15993881225586,3.182630044861556,1739141224.8383458,64.15993881225586,2.2403721524287077 +1739141224.8579545,64.17993879318237,0.5883360237491218,1739141224.8579566,64.17993879318237,0.02776304509787142,1739141224.85796,64.17993879318237,112.0133470985516,1739141224.8579626,64.17993879318237,-7.4044483977347895,1739141224.8579638,64.17993879318237,0.065,1739141224.8579655,64.17993879318237,3.1369338659211383,1739141224.8579667,64.17993879318237,-0.36511657073291975,1739141224.8579679,64.17993879318237,-0.04388904727748532,1739141224.857969,64.17993879318237,2.160293524813314,1739141224.8579707,64.17993879318237,0.0,1739141224.857972,64.17993879318237,-0.08007862761539375,1739141224.8579733,64.17993879318237,3.182630044861556,1739141224.8579745,64.17993879318237,2.2403721524287077 +1739141224.8781626,64.19993877410889,0.3425391416911694,1739141224.8781657,64.19993877410889,0.017693116653759056,1739141224.8781686,64.19993877410889,112.1651508702665,1739141224.8781714,64.19993877410889,-7.529997904818792,1739141224.8781726,64.19993877410889,0.065,1739141224.8781745,64.19993877410889,3.135583623251452,1739141224.8781757,64.19993877410889,-0.3685513085732995,1739141224.878177,64.19993877410889,-0.04566469134285933,1739141224.8781784,64.19993877410889,2.157327545985401,1739141224.8781798,64.19993877410889,0.0,1739141224.8781815,64.19993877410889,-0.0690336865059064,1739141224.8781826,64.19993877410889,3.1824147018814504,1739141224.878184,64.19993877410889,2.231620730885079 +1739141224.899639,64.2199387550354,0.3425391416911694,1739141224.8996427,64.2199387550354,0.017693116653759056,1739141224.899647,64.2199387550354,112.1651508702665,1739141224.899652,64.2199387550354,-7.529997904818792,1739141224.8996549,64.2199387550354,0.065,1739141224.8996587,64.2199387550354,3.135583623251452,1739141224.899662,64.2199387550354,-0.3685513085732995,1739141224.8996654,64.2199387550354,-0.04566469134285933,1739141224.899669,64.2199387550354,2.157327545985401,1739141224.8996723,64.2199387550354,0.0,1739141224.8996756,64.2199387550354,-0.07429318489967818,1739141224.899679,64.2199387550354,3.1824147018814504,1739141224.899682,64.2199387550354,2.231620730885079 +1739141224.9180775,64.23993873596191,0.3425391416911694,1739141224.918081,64.23993873596191,0.017693116653759056,1739141224.9180841,64.23993873596191,112.1651508702665,1739141224.918087,64.23993873596191,-7.529997904818792,1739141224.9180882,64.23993873596191,0.065,1739141224.9180899,64.23993873596191,3.135583623251452,1739141224.9180913,64.23993873596191,-0.3685513085732995,1739141224.9180927,64.23993873596191,-0.04566469134285933,1739141224.9180942,64.23993873596191,2.157327545985401,1739141224.9180958,64.23993873596191,0.0,1739141224.9180973,64.23993873596191,-0.07429318489967818,1739141224.9180987,64.23993873596191,3.1824147018814504,1739141224.9180999,64.23993873596191,2.231620730885079 +1739141224.938366,64.25993871688843,0.3425391416911694,1739141224.9383688,64.25993871688843,0.017693116653759056,1739141224.938372,64.25993871688843,112.1651508702665,1739141224.9383748,64.25993871688843,-7.529997904818792,1739141224.938376,64.25993871688843,0.065,1739141224.9383776,64.25993871688843,3.135583623251452,1739141224.9383793,64.25993871688843,-0.3685513085732995,1739141224.9383807,64.25993871688843,-0.04566469134285933,1739141224.938382,64.25993871688843,2.157327545985401,1739141224.9383838,64.25993871688843,0.0,1739141224.9383855,64.25993871688843,-0.07429318489967818,1739141224.9383872,64.25993871688843,3.1824147018814504,1739141224.9383886,64.25993871688843,2.231620730885079 +1739141224.9596672,64.27993869781494,0.3425391416911694,1739141224.959671,64.27993869781494,0.017693116653759056,1739141224.9596765,64.27993869781494,112.1651508702665,1739141224.9596822,64.27993869781494,-7.529997904818792,1739141224.9596853,64.27993869781494,0.065,1739141224.9596896,64.27993869781494,3.135583623251452,1739141224.9596937,64.27993869781494,-0.3685513085732995,1739141224.9596972,64.27993869781494,-0.04566469134285933,1739141224.959701,64.27993869781494,2.157327545985401,1739141224.9597049,64.27993869781494,0.0,1739141224.9597087,64.27993869781494,-0.07429318489967818,1739141224.9597125,64.27993869781494,3.1824147018814504,1739141224.959716,64.27993869781494,2.231620730885079 +1739141224.9780493,64.29993867874146,0.3425391416911694,1739141224.9780521,64.29993867874146,0.017693116653759056,1739141224.9780555,64.29993867874146,112.1651508702665,1739141224.9780588,64.29993867874146,-7.529997904818792,1739141224.9780605,64.29993867874146,0.065,1739141224.9780622,64.29993867874146,3.135583623251452,1739141224.9780638,64.29993867874146,-0.3685513085732995,1739141224.9780655,64.29993867874146,-0.04566469134285933,1739141224.9780667,64.29993867874146,2.157327545985401,1739141224.9780686,64.29993867874146,0.0,1739141224.9780707,64.29993867874146,-0.07429318489967818,1739141224.9780722,64.29993867874146,3.1824147018814504,1739141224.9780736,64.29993867874146,2.231620730885079 +1739141224.9984477,64.31993865966797,0.09766119825217512,1739141224.9984505,64.31993865966797,0.007724157067269921,1739141224.9984539,64.31993865966797,112.75878390498805,1739141224.9984567,64.31993865966797,-8.099542547392396,1739141224.9984586,64.31993865966797,0.065,1739141224.9984605,64.31993865966797,3.1346055257058385,1739141224.998462,64.31993865966797,-0.3892751730243042,1739141224.9984632,64.31993865966797,-0.04448703166440521,1739141224.9984646,64.31993865966797,2.1395181982144558,1739141224.9984663,64.31993865966797,0.0,1739141224.9984825,64.31993865966797,-0.09296388048354556,1739141224.9984841,64.31993865966797,3.182111008723436,1739141224.9984856,64.31993865966797,2.223591266835763 +1739141225.0181255,64.33993864059448,0.09766119825217512,1739141225.0181289,64.33993864059448,0.007724157067269921,1739141225.018132,64.33993864059448,112.75878390498805,1739141225.0181348,64.33993864059448,-8.099542547392396,1739141225.0181363,64.33993864059448,0.065,1739141225.0181382,64.33993864059448,3.1346055257058385,1739141225.0181394,64.33993864059448,-0.3892751730243042,1739141225.0181406,64.33993864059448,-0.04448703166440521,1739141225.018142,64.33993864059448,2.1395181982144558,1739141225.0181437,64.33993864059448,0.0,1739141225.0181453,64.33993864059448,-0.08407306862130737,1739141225.0181465,64.33993864059448,3.182111008723436,1739141225.018148,64.33993864059448,2.223591266835763 +1739141225.038249,64.359938621521,0.09766119825217512,1739141225.038252,64.359938621521,0.007724157067269921,1739141225.0382555,64.359938621521,112.75878390498805,1739141225.0382583,64.359938621521,-8.099542547392396,1739141225.03826,64.359938621521,0.065,1739141225.0382617,64.359938621521,3.1346055257058385,1739141225.0382636,64.359938621521,-0.3892751730243042,1739141225.0382648,64.359938621521,-0.04448703166440521,1739141225.0382664,64.359938621521,2.1395181982144558,1739141225.0382683,64.359938621521,0.0,1739141225.03827,64.359938621521,-0.08407306862130737,1739141225.0382714,64.359938621521,3.182111008723436,1739141225.0382729,64.359938621521,2.223591266835763 +1739141225.0582333,64.37993860244751,0.09766119825217512,1739141225.0582361,64.37993860244751,0.007724157067269921,1739141225.058239,64.37993860244751,112.75878390498805,1739141225.058242,64.37993860244751,-8.099542547392396,1739141225.0582433,64.37993860244751,0.065,1739141225.0582454,64.37993860244751,3.1346055257058385,1739141225.0582469,64.37993860244751,-0.3892751730243042,1739141225.0582483,64.37993860244751,-0.04448703166440521,1739141225.0582495,64.37993860244751,2.1395181982144558,1739141225.0582514,64.37993860244751,0.0,1739141225.058253,64.37993860244751,-0.08407306862130737,1739141225.0582542,64.37993860244751,3.182111008723436,1739141225.0582557,64.37993860244751,2.223591266835763 +1739141225.0782704,64.39993858337402,0.09766119825217512,1739141225.078274,64.39993858337402,0.007724157067269921,1739141225.0782773,64.39993858337402,112.75878390498805,1739141225.0782807,64.39993858337402,-8.099542547392396,1739141225.0782824,64.39993858337402,0.065,1739141225.078284,64.39993858337402,3.1346055257058385,1739141225.0782855,64.39993858337402,-0.3892751730243042,1739141225.0782874,64.39993858337402,-0.04448703166440521,1739141225.0782888,64.39993858337402,2.1395181982144558,1739141225.0782907,64.39993858337402,0.0,1739141225.0782924,64.39993858337402,-0.08407306862130737,1739141225.078294,64.39993858337402,3.182111008723436,1739141225.0782955,64.39993858337402,2.223591266835763 +1739141225.0989885,64.41993856430054,-0.14626920334198124,1739141225.0989912,64.41993856430054,-0.002130394664366264,1739141225.0989945,64.41993856430054,112.76172092435891,1739141225.0989976,64.41993856430054,-8.074650070523752,1739141225.098999,64.41993856430054,0.065,1739141225.099001,64.41993856430054,3.1331257557924586,1739141225.0990024,64.41993856430054,-0.3857690289370154,1739141225.0990038,64.41993856430054,-0.04712514622037757,1739141225.0990055,64.41993856430054,2.1425208869262744,1739141225.0990071,64.41993856430054,0.0,1739141225.0990088,64.41993856430054,-0.060630972827829296,1739141225.0990102,64.41993856430054,3.1817999517521662,1739141225.0990117,64.41993856430054,2.214314768089263 +1739141225.1192405,64.43993854522705,-0.14626920334198124,1739141225.1192458,64.43993854522705,-0.002130394664366264,1739141225.1192505,64.43993854522705,112.76172092435891,1739141225.1192563,64.43993854522705,-8.074650070523752,1739141225.1192608,64.43993854522705,0.065,1739141225.119266,64.43993854522705,3.1331257557924586,1739141225.1192682,64.43993854522705,-0.3857690289370154,1739141225.11927,64.43993854522705,-0.04712514622037757,1739141225.1192718,64.43993854522705,2.1425208869262744,1739141225.1192734,64.43993854522705,0.0,1739141225.1192753,64.43993854522705,-0.07179388116298879,1739141225.1192765,64.43993854522705,3.1817999517521662,1739141225.1192782,64.43993854522705,2.214314768089263 +1739141225.1393604,64.45993852615356,-0.14626920334198124,1739141225.1393638,64.45993852615356,-0.002130394664366264,1739141225.1393673,64.45993852615356,112.76172092435891,1739141225.1393707,64.45993852615356,-8.074650070523752,1739141225.139372,64.45993852615356,0.065,1739141225.139374,64.45993852615356,3.1331257557924586,1739141225.1393757,64.45993852615356,-0.3857690289370154,1739141225.1393774,64.45993852615356,-0.04712514622037757,1739141225.1393788,64.45993852615356,2.1425208869262744,1739141225.1393807,64.45993852615356,0.0,1739141225.1393824,64.45993852615356,-0.07179388116298879,1739141225.1393838,64.45993852615356,3.1817999517521662,1739141225.139385,64.45993852615356,2.214314768089263 +1739141225.1587873,64.47993850708008,-0.14626920334198124,1739141225.1587906,64.47993850708008,-0.002130394664366264,1739141225.1587944,64.47993850708008,112.76172092435891,1739141225.1587975,64.47993850708008,-8.074650070523752,1739141225.1587994,64.47993850708008,0.065,1739141225.1588013,64.47993850708008,3.1331257557924586,1739141225.1588027,64.47993850708008,-0.3857690289370154,1739141225.1588042,64.47993850708008,-0.04712514622037757,1739141225.1588058,64.47993850708008,2.1425208869262744,1739141225.1588075,64.47993850708008,0.0,1739141225.1588092,64.47993850708008,-0.07179388116298879,1739141225.1588109,64.47993850708008,3.1817999517521662,1739141225.158812,64.47993850708008,2.214314768089263 +1739141225.1794078,64.49993848800659,-0.14626920334198124,1739141225.1794114,64.49993848800659,-0.002130394664366264,1739141225.1794145,64.49993848800659,112.76172092435891,1739141225.1794174,64.49993848800659,-8.074650070523752,1739141225.1794188,64.49993848800659,0.065,1739141225.1794212,64.49993848800659,3.1331257557924586,1739141225.1794226,64.49993848800659,-0.3857690289370154,1739141225.1794245,64.49993848800659,-0.04712514622037757,1739141225.179426,64.49993848800659,2.1425208869262744,1739141225.1794279,64.49993848800659,0.0,1739141225.1794293,64.49993848800659,-0.07179388116298879,1739141225.1794307,64.49993848800659,3.1817999517521662,1739141225.179432,64.49993848800659,2.214314768089263 +1739141225.199316,64.5199384689331,-0.14626920334198124,1739141225.1993194,64.5199384689331,-0.002130394664366264,1739141225.1993227,64.5199384689331,112.76172092435891,1739141225.1993258,64.5199384689331,-8.074650070523752,1739141225.1993272,64.5199384689331,0.065,1739141225.1993291,64.5199384689331,3.1331257557924586,1739141225.1993308,64.5199384689331,-0.3857690289370154,1739141225.199332,64.5199384689331,-0.04712514622037757,1739141225.1993334,64.5199384689331,2.1425208869262744,1739141225.199335,64.5199384689331,0.0,1739141225.199337,64.5199384689331,-0.07179388116298879,1739141225.1993384,64.5199384689331,3.1817999517521662,1739141225.19934,64.5199384689331,2.214314768089263 +1739141225.2186265,64.53993844985962,-0.3892760213742159,1739141225.2186298,64.53993844985962,-0.011871918612284205,1739141225.2186334,64.53993844985962,112.76464674769925,1739141225.2186365,64.53993844985962,-8.05465903447368,1739141225.2186382,64.53993844985962,0.065,1739141225.21864,64.53993844985962,3.1315645386687536,1739141225.218642,64.53993844985962,-0.38254959433919455,1739141225.2186434,64.53993844985962,-0.04999163831229991,1739141225.2186446,64.53993844985962,2.145281746574116,1739141225.2186465,64.53993844985962,0.0,1739141225.218648,64.53993844985962,-0.05193968411589864,1739141225.2186494,64.53993844985962,3.1814888947808964,1739141225.2186508,64.53993844985962,2.206675814959126 +1739141225.2389417,64.55993843078613,-0.3892760213742159,1739141225.238945,64.55993843078613,-0.011871918612284205,1739141225.2389483,64.55993843078613,112.76464674769925,1739141225.2389514,64.55993843078613,-8.05465903447368,1739141225.2389529,64.55993843078613,0.065,1739141225.2389548,64.55993843078613,3.1315645386687536,1739141225.2389562,64.55993843078613,-0.38254959433919455,1739141225.238958,64.55993843078613,-0.04999163831229991,1739141225.238959,64.55993843078613,2.145281746574116,1739141225.238961,64.55993843078613,0.0,1739141225.2389627,64.55993843078613,-0.06139406838501005,1739141225.2389643,64.55993843078613,3.1814888947808964,1739141225.2389655,64.55993843078613,2.206675814959126 +1739141225.2585607,64.57993841171265,-0.3892760213742159,1739141225.2585635,64.57993841171265,-0.011871918612284205,1739141225.2585669,64.57993841171265,112.76464674769925,1739141225.2585697,64.57993841171265,-8.05465903447368,1739141225.2585711,64.57993841171265,0.065,1739141225.258573,64.57993841171265,3.1315645386687536,1739141225.2585742,64.57993841171265,-0.38254959433919455,1739141225.258576,64.57993841171265,-0.04999163831229991,1739141225.2585773,64.57993841171265,2.145281746574116,1739141225.2585793,64.57993841171265,0.0,1739141225.2585807,64.57993841171265,-0.06139406838501005,1739141225.2585824,64.57993841171265,3.1814888947808964,1739141225.2585835,64.57993841171265,2.206675814959126 +1739141225.2789903,64.59993839263916,-0.3892760213742159,1739141225.2789931,64.59993839263916,-0.011871918612284205,1739141225.2789965,64.59993839263916,112.76464674769925,1739141225.2789993,64.59993839263916,-8.05465903447368,1739141225.279001,64.59993839263916,0.065,1739141225.279003,64.59993839263916,3.1315645386687536,1739141225.2790043,64.59993839263916,-0.38254959433919455,1739141225.279006,64.59993839263916,-0.04999163831229991,1739141225.2790072,64.59993839263916,2.145281746574116,1739141225.279009,64.59993839263916,0.0,1739141225.2790105,64.59993839263916,-0.06139406838501005,1739141225.2790122,64.59993839263916,3.1814888947808964,1739141225.2790134,64.59993839263916,2.206675814959126 +1739141225.2987175,64.61993837356567,-0.3892760213742159,1739141225.2987206,64.61993837356567,-0.011871918612284205,1739141225.2987237,64.61993837356567,112.76464674769925,1739141225.2987266,64.61993837356567,-8.05465903447368,1739141225.298728,64.61993837356567,0.065,1739141225.29873,64.61993837356567,3.1315645386687536,1739141225.2987318,64.61993837356567,-0.38254959433919455,1739141225.2987332,64.61993837356567,-0.04999163831229991,1739141225.2987347,64.61993837356567,2.145281746574116,1739141225.2987363,64.61993837356567,0.0,1739141225.2987382,64.61993837356567,-0.06139406838501005,1739141225.2987397,64.61993837356567,3.1814888947808964,1739141225.2987413,64.61993837356567,2.206675814959126 +1739141225.3193145,64.63993835449219,-0.631488903812429,1739141225.319318,64.63993835449219,-0.021495737801306092,1739141225.3193219,64.63993835449219,112.77801515810295,1739141225.3193252,64.63993835449219,-8.048137507439229,1739141225.3193266,64.63993835449219,0.065,1739141225.3193288,64.63993835449219,3.1299308072105605,1739141225.3193302,64.63993835449219,-0.37901101699847856,1739141225.319332,64.63993835449219,-0.052904615220357956,1739141225.3193333,64.63993835449219,2.1483203947162464,1739141225.319335,64.63993835449219,0.0,1739141225.3193367,64.63993835449219,-0.04293577154327168,1739141225.3193383,64.63993835449219,3.1810523297983075,1739141225.3193398,64.63993835449219,2.2000458358130746 +1739141225.3385444,64.6599383354187,-0.631488903812429,1739141225.3385477,64.6599383354187,-0.021495737801306092,1739141225.338551,64.6599383354187,112.77801515810295,1739141225.338554,64.6599383354187,-8.048137507439229,1739141225.3385553,64.6599383354187,0.065,1739141225.3385575,64.6599383354187,3.1299308072105605,1739141225.338559,64.6599383354187,-0.37901101699847856,1739141225.3385606,64.6599383354187,-0.052904615220357956,1739141225.338562,64.6599383354187,2.1483203947162464,1739141225.338564,64.6599383354187,0.0,1739141225.3385653,64.6599383354187,-0.051725441096828195,1739141225.338567,64.6599383354187,3.1810523297983075,1739141225.3385682,64.6599383354187,2.2000458358130746 +1739141225.358453,64.67993831634521,-0.631488903812429,1739141225.3584561,64.67993831634521,-0.021495737801306092,1739141225.3584595,64.67993831634521,112.77801515810295,1739141225.3584626,64.67993831634521,-8.048137507439229,1739141225.358464,64.67993831634521,0.065,1739141225.358466,64.67993831634521,3.1299308072105605,1739141225.3585002,64.67993831634521,-0.37901101699847856,1739141225.3585033,64.67993831634521,-0.052904615220357956,1739141225.3585048,64.67993831634521,2.1483203947162464,1739141225.3585064,64.67993831634521,0.0,1739141225.358508,64.67993831634521,-0.051725441096828195,1739141225.3585095,64.67993831634521,3.1810523297983075,1739141225.3585107,64.67993831634521,2.2000458358130746 +1739141225.3784442,64.69993829727173,-0.631488903812429,1739141225.378447,64.69993829727173,-0.021495737801306092,1739141225.37845,64.69993829727173,112.77801515810295,1739141225.3784528,64.69993829727173,-8.048137507439229,1739141225.3784542,64.69993829727173,0.065,1739141225.378456,64.69993829727173,3.1299308072105605,1739141225.3784573,64.69993829727173,-0.37901101699847856,1739141225.3784587,64.69993829727173,-0.052904615220357956,1739141225.37846,64.69993829727173,2.1483203947162464,1739141225.3784611,64.69993829727173,0.0,1739141225.3784628,64.69993829727173,-0.051725441096828195,1739141225.378464,64.69993829727173,3.1810523297983075,1739141225.3784652,64.69993829727173,2.2000458358130746 +1739141225.399946,64.71993827819824,-0.631488903812429,1739141225.3999488,64.71993827819824,-0.021495737801306092,1739141225.399952,64.71993827819824,112.77801515810295,1739141225.3999548,64.71993827819824,-8.048137507439229,1739141225.3999557,64.71993827819824,0.065,1739141225.3999574,64.71993827819824,3.1299308072105605,1739141225.399959,64.71993827819824,-0.37901101699847856,1739141225.39996,64.71993827819824,-0.052904615220357956,1739141225.3999612,64.71993827819824,2.1483203947162464,1739141225.3999627,64.71993827819824,0.0,1739141225.399964,64.71993827819824,-0.051725441096828195,1739141225.3999655,64.71993827819824,3.1810523297983075,1739141225.3999667,64.71993827819824,2.2000458358130746 +1739141225.4186742,64.73993825912476,-0.631488903812429,1739141225.418677,64.73993825912476,-0.021495737801306092,1739141225.4186797,64.73993825912476,112.77801515810295,1739141225.418682,64.73993825912476,-8.048137507439229,1739141225.4186833,64.73993825912476,0.065,1739141225.4186852,64.73993825912476,3.1299308072105605,1739141225.4186864,64.73993825912476,-0.37901101699847856,1739141225.4186878,64.73993825912476,-0.052904615220357956,1739141225.418689,64.73993825912476,2.1483203947162464,1739141225.4186902,64.73993825912476,0.0,1739141225.418692,64.73993825912476,-0.051725441096828195,1739141225.418693,64.73993825912476,3.1810523297983075,1739141225.4186945,64.73993825912476,2.2000458358130746 +1739141225.4419546,64.75993824005127,-0.8730410429602271,1739141225.4419584,64.75993824005127,-0.030972898411016914,1739141225.441963,64.75993824005127,112.77801515810295,1739141225.441967,64.75993824005127,-8.031670774666829,1739141225.4419696,64.75993824005127,0.065,1739141225.441972,64.75993824005127,3.128186854900894,1739141225.441974,64.75993824005127,-0.3743882597396885,1739141225.441976,64.75993824005127,-0.056091231984508216,1739141225.4419777,64.75993824005127,2.1522965352093353,1739141225.4419801,64.75993824005127,0.0,1739141225.4419827,64.75993824005127,-0.033655789276145064,1739141225.4419866,64.75993824005127,3.1805048914939134,1739141225.4419887,64.75993824005127,2.1945569248889414 +1739141225.4591777,64.77993822097778,-0.8730410429602271,1739141225.4591846,64.77993822097778,-0.030972898411016914,1739141225.459192,64.77993822097778,112.77801515810295,1739141225.4592009,64.77993822097778,-8.031670774666829,1739141225.4592052,64.77993822097778,0.065,1739141225.4592116,64.77993822097778,3.128186854900894,1739141225.4592392,64.77993822097778,-0.3743882597396885,1739141225.4592657,64.77993822097778,-0.056091231984508216,1739141225.4592714,64.77993822097778,2.1522965352093353,1739141225.4592772,64.77993822097778,0.0,1739141225.459283,64.77993822097778,-0.0422603896796061,1739141225.4592893,64.77993822097778,3.1805048914939134,1739141225.4592946,64.77993822097778,2.1945569248889414 +1739141225.4796686,64.7999382019043,-0.8730410429602271,1739141225.4796712,64.7999382019043,-0.030972898411016914,1739141225.479674,64.7999382019043,112.77801515810295,1739141225.4796767,64.7999382019043,-8.031670774666829,1739141225.479678,64.7999382019043,0.065,1739141225.4796798,64.7999382019043,3.128186854900894,1739141225.479681,64.7999382019043,-0.3743882597396885,1739141225.4796824,64.7999382019043,-0.056091231984508216,1739141225.4796839,64.7999382019043,2.1522965352093353,1739141225.479685,64.7999382019043,0.0,1739141225.4796865,64.7999382019043,-0.0422603896796061,1739141225.4796877,64.7999382019043,3.1805048914939134,1739141225.479689,64.7999382019043,2.1945569248889414 +1739141225.499031,64.81993818283081,-0.8730410429602271,1739141225.499034,64.81993818283081,-0.030972898411016914,1739141225.499037,64.81993818283081,112.77801515810295,1739141225.4990394,64.81993818283081,-8.031670774666829,1739141225.499041,64.81993818283081,0.065,1739141225.4990425,64.81993818283081,3.128186854900894,1739141225.499044,64.81993818283081,-0.3743882597396885,1739141225.4990451,64.81993818283081,-0.056091231984508216,1739141225.499046,64.81993818283081,2.1522965352093353,1739141225.4990478,64.81993818283081,0.0,1739141225.4990492,64.81993818283081,-0.0422603896796061,1739141225.4990501,64.81993818283081,3.1805048914939134,1739141225.4990516,64.81993818283081,2.1945569248889414 +1739141225.5202007,64.83993816375732,-0.8730410429602271,1739141225.520205,64.83993816375732,-0.030972898411016914,1739141225.5202103,64.83993816375732,112.77801515810295,1739141225.5202155,64.83993816375732,-8.031670774666829,1739141225.5202184,64.83993816375732,0.065,1739141225.5202222,64.83993816375732,3.128186854900894,1739141225.5202258,64.83993816375732,-0.3743882597396885,1739141225.5202293,64.83993816375732,-0.056091231984508216,1739141225.5202327,64.83993816375732,2.1522965352093353,1739141225.5202363,64.83993816375732,0.0,1739141225.5202398,64.83993816375732,-0.0422603896796061,1739141225.5202434,64.83993816375732,3.1805048914939134,1739141225.5202472,64.83993816375732,2.1945569248889414 +1739141225.5403118,64.85993814468384,-1.114036378708187,1739141225.5403159,64.85993814468384,-0.040284054514796885,1739141225.5403209,64.85993814468384,112.77801515810295,1739141225.5403264,64.85993814468384,-8.018036311315718,1739141225.5403295,64.85993814468384,0.065,1739141225.5403335,64.85993814468384,3.1263441171942477,1739141225.540337,64.85993814468384,-0.36909260104310626,1739141225.5403407,64.85993814468384,-0.05944798882704594,1739141225.5403442,64.85993814468384,2.1568604984868647,1739141225.5403478,64.85993814468384,0.0,1739141225.5403514,64.85993814468384,-0.02487088430196078,1739141225.540355,64.85993814468384,3.1798240815813528,1739141225.5403585,64.85993814468384,2.190012103771905 +1739141225.5588467,64.87993812561035,-1.114036378708187,1739141225.5588536,64.87993812561035,-0.040284054514796885,1739141225.558862,64.87993812561035,112.77801515810295,1739141225.5588672,64.87993812561035,-8.018036311315718,1739141225.5588715,64.87993812561035,0.065,1739141225.5588765,64.87993812561035,3.1263441171942477,1739141225.5588803,64.87993812561035,-0.36909260104310626,1739141225.5588822,64.87993812561035,-0.05944798882704594,1739141225.5588853,64.87993812561035,2.1568604984868647,1739141225.558888,64.87993812561035,0.0,1739141225.5588925,64.87993812561035,-0.033151605285040464,1739141225.5588973,64.87993812561035,3.1798240815813528,1739141225.5589023,64.87993812561035,2.190012103771905 +1739141225.5791302,64.89993810653687,-1.114036378708187,1739141225.5791337,64.89993810653687,-0.040284054514796885,1739141225.5791373,64.89993810653687,112.77801515810295,1739141225.5791402,64.89993810653687,-8.018036311315718,1739141225.5791419,64.89993810653687,0.065,1739141225.5791438,64.89993810653687,3.1263441171942477,1739141225.5791452,64.89993810653687,-0.36909260104310626,1739141225.5791469,64.89993810653687,-0.05944798882704594,1739141225.579148,64.89993810653687,2.1568604984868647,1739141225.5791497,64.89993810653687,0.0,1739141225.5791514,64.89993810653687,-0.033151605285040464,1739141225.5791523,64.89993810653687,3.1798240815813528,1739141225.5791538,64.89993810653687,2.190012103771905 +1739141225.5983465,64.91993808746338,-1.114036378708187,1739141225.5983498,64.91993808746338,-0.040284054514796885,1739141225.5983531,64.91993808746338,112.77801515810295,1739141225.598356,64.91993808746338,-8.018036311315718,1739141225.5983574,64.91993808746338,0.065,1739141225.5983593,64.91993808746338,3.1263441171942477,1739141225.5983608,64.91993808746338,-0.36909260104310626,1739141225.5983622,64.91993808746338,-0.05944798882704594,1739141225.5983634,64.91993808746338,2.1568604984868647,1739141225.5983646,64.91993808746338,0.0,1739141225.5983663,64.91993808746338,-0.033151605285040464,1739141225.5983675,64.91993808746338,3.1798240815813528,1739141225.598369,64.91993808746338,2.190012103771905 +1739141225.6187823,64.93993806838989,-1.114036378708187,1739141225.618786,64.93993806838989,-0.040284054514796885,1739141225.6187894,64.93993806838989,112.77801515810295,1739141225.6187918,64.93993806838989,-8.018036311315718,1739141225.6187935,64.93993806838989,0.065,1739141225.6187952,64.93993806838989,3.1263441171942477,1739141225.618797,64.93993806838989,-0.36909260104310626,1739141225.6187985,64.93993806838989,-0.05944798882704594,1739141225.6187997,64.93993806838989,2.1568604984868647,1739141225.618801,64.93993806838989,0.0,1739141225.6188028,64.93993806838989,-0.033151605285040464,1739141225.618804,64.93993806838989,3.1798240815813528,1739141225.6188054,64.93993806838989,2.190012103771905 +1739141225.6384454,64.9599380493164,-1.114036378708187,1739141225.6384485,64.9599380493164,-0.040284054514796885,1739141225.638452,64.9599380493164,112.77801515810295,1739141225.6384547,64.9599380493164,-8.018036311315718,1739141225.638456,64.9599380493164,0.065,1739141225.6384578,64.9599380493164,3.1263441171942477,1739141225.6384594,64.9599380493164,-0.36909260104310626,1739141225.6384606,64.9599380493164,-0.05944798882704594,1739141225.638462,64.9599380493164,2.1568604984868647,1739141225.6384635,64.9599380493164,0.0,1739141225.638465,64.9599380493164,-0.033151605285040464,1739141225.6384661,64.9599380493164,3.1798240815813528,1739141225.6385293,64.9599380493164,2.190012103771905 +1739141225.6602259,64.97993803024292,-1.3545991256350751,1739141225.6602306,64.97993803024292,-0.0493938401676548,1739141225.6602354,64.97993803024292,112.77801515810295,1739141225.6602411,64.97993803024292,-8.00763986898425,1739141225.660244,64.97993803024292,0.065,1739141225.6602478,64.97993803024292,3.124400128637198,1739141225.6602511,64.97993803024292,-0.3628966733750297,1739141225.6602545,64.97993803024292,-0.06293782676820255,1739141225.6602578,64.97993803024292,2.1622126286851406,1739141225.6602614,64.97993803024292,0.0,1739141225.6602647,64.97993803024292,-0.01631797668727015,1739141225.660268,64.97993803024292,3.1789651267121632,1739141225.6602714,64.97993803024292,2.1865466229947477 +1739141225.6801076,64.99993801116943,-1.3545991256350751,1739141225.680112,64.99993801116943,-0.0493938401676548,1739141225.6801171,64.99993801116943,112.77801515810295,1739141225.680123,64.99993801116943,-8.00763986898425,1739141225.6801264,64.99993801116943,0.065,1739141225.6801305,64.99993801116943,3.124400128637198,1739141225.6801343,64.99993801116943,-0.3628966733750297,1739141225.6801383,64.99993801116943,-0.06293782676820255,1739141225.6801422,64.99993801116943,2.1622126286851406,1739141225.680146,64.99993801116943,0.0,1739141225.6801498,64.99993801116943,-0.024333994309607032,1739141225.6801536,64.99993801116943,3.1789651267121632,1739141225.6801574,64.99993801116943,2.1865466229947477 +1739141225.6999173,65.01993799209595,-1.3545991256350751,1739141225.699921,65.01993799209595,-0.0493938401676548,1739141225.6999252,65.01993799209595,112.77801515810295,1739141225.6999304,65.01993799209595,-8.00763986898425,1739141225.6999333,65.01993799209595,0.065,1739141225.6999369,65.01993799209595,3.124400128637198,1739141225.6999397,65.01993799209595,-0.3628966733750297,1739141225.699943,65.01993799209595,-0.06293782676820255,1739141225.6999462,65.01993799209595,2.1622126286851406,1739141225.6999493,65.01993799209595,0.0,1739141225.6999526,65.01993799209595,-0.024333994309607032,1739141225.699956,65.01993799209595,3.1789651267121632,1739141225.699959,65.01993799209595,2.1865466229947477 diff --git a/tuning logs/2025-02-09_16-46-00 (after tuning cte = 0.5 (-50%), decay speed = 1.0 (+250%))/behavior.json b/tuning logs/2025-02-09_16-46-00 (after tuning cte = 0.5 (-50%), decay speed = 1.0 (+250%))/behavior.json new file mode 100644 index 000000000..ba95218a0 --- /dev/null +++ b/tuning logs/2025-02-09_16-46-00 (after tuning cte = 0.5 (-50%), decay speed = 1.0 (+250%))/behavior.json @@ -0,0 +1,6549 @@ +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141159.3618891, "x": 4.0, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.0, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": 0.0, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": -1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141159.401889} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": -2, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 0, "brake_pedal_position": 0, "brake_pedal_speed": 0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": -1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141159.401889} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.0, "x": 0.0, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.0, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": 0.0, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": -1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141159.421889} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.36000000000000004, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.683742855172885, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": -1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141159.421889} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.0, "x": 0.0, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.0, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": 0.0, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": -1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141159.441889} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.36000000000000004, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.683742855172885, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.015995993600000008, "gear": 1, "accelerator_pedal_position": 0.36000000000000004, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.08614717687913853, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141159.441889} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.0, "x": 0.0, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.0, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": 0.0, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": -1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141159.461889} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.36000000000000004, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.683742855172885, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.03197591848874033, "gear": 1, "accelerator_pedal_position": 0.36000000000000004, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.17209949070995442, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141159.461889} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141159.471889, "x": 4.000799598820634, "y": 4.999999978353969, "z": null, "yaw": -7.735876137242363e-05, "pitch": null, "roll": null}, "v": 0.039959828283559644, "accelerator_pedal_position": 0.36000000000000004, "brake_pedal_position": 0.0, "acceleration": 0.7979860407070577, "steering_wheel_angle": -0.21500257398224137, "front_wheel_angle": -0.009901792009563716, "heading_rate": -0.0001545651719748452, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141159.481889} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3923222334868708, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.4452216790081174, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.04793968869063022, "gear": 1, "accelerator_pedal_position": 0.36000000000000004, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2578569414924477, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141159.481889} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.1099998950958252, "x": 0.0007995988206337401, "y": -2.1646030745614553e-08, "z": null, "yaw": 6.2831079484182135, "pitch": null, "roll": null}, "v": 0.039959828283559644, "accelerator_pedal_position": 0.36000000000000004, "brake_pedal_position": 0.0, "acceleration": 0.7979860407070577, "steering_wheel_angle": -0.21500257398224137, "front_wheel_angle": -0.009901792009563716, "heading_rate": -0.0001545651719748452, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141159.501889} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3923222334868708, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.4452216790081174, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.06792646474275332, "gear": 1, "accelerator_pedal_position": 0.3923222334868708, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3428055276563607, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141159.501889} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.1099998950958252, "x": 0.0007995988206337401, "y": -2.1646030745614553e-08, "z": null, "yaw": 6.2831079484182135, "pitch": null, "roll": null}, "v": 0.039959828283559644, "accelerator_pedal_position": 0.36000000000000004, "brake_pedal_position": 0.0, "acceleration": 0.7979860407070577, "steering_wheel_angle": -0.21500257398224137, "front_wheel_angle": -0.009901792009563716, "heading_rate": -0.0001545651719748452, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141159.521889} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3923222334868708, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.4452216790081174, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.08789275617515352, "gear": 1, "accelerator_pedal_position": 0.3923222334868708, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.42756204057464825, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141159.521889} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.1099998950958252, "x": 0.0007995988206337401, "y": -2.1646030745614553e-08, "z": null, "yaw": 6.2831079484182135, "pitch": null, "roll": null}, "v": 0.039959828283559644, "accelerator_pedal_position": 0.36000000000000004, "brake_pedal_position": 0.0, "acceleration": 0.7979860407070577, "steering_wheel_angle": -0.21500257398224137, "front_wheel_angle": -0.009901792009563716, "heading_rate": -0.0001545651719748452, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141159.561889} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3923222334868708, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.4452216790081174, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.12776333211676622, "gear": 1, "accelerator_pedal_position": 0.3923222334868708, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5964988466743473, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141159.561889} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.1099998950958252, "x": 0.0007995988206337401, "y": -2.1646030745614553e-08, "z": null, "yaw": 6.2831079484182135, "pitch": null, "roll": null}, "v": 0.039959828283559644, "accelerator_pedal_position": 0.36000000000000004, "brake_pedal_position": 0.0, "acceleration": 0.7979860407070577, "steering_wheel_angle": -0.21500257398224137, "front_wheel_angle": -0.009901792009563716, "heading_rate": -0.0001545651719748452, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141159.561889} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141159.581889, "x": 4.010485176694682, "y": 4.999995439392224, "z": null, "yaw": -0.0009259362447010282, "pitch": null, "roll": null}, "v": 0.14766734168722773, "accelerator_pedal_position": 0.3923222334868708, "brake_pedal_position": 0.0, "acceleration": 0.9944125357705711, "steering_wheel_angle": -0.6806791398557588, "front_wheel_angle": -0.031543462039866035, "heading_rate": -0.0018201111991293548, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141159.591889} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3932162277635794, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.9434646338160393, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.15761146704493345, "gear": 1, "accelerator_pedal_position": 0.3923222334868708, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.722697258979355, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141159.591889} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.2199997901916504, "x": 0.010485176694682075, "y": -4.560607775871972e-06, "z": null, "yaw": 6.282259370934885, "pitch": null, "roll": null}, "v": 0.14766734168722773, "accelerator_pedal_position": 0.3923222334868708, "brake_pedal_position": 0.0, "acceleration": 0.9944125357705711, "steering_wheel_angle": -0.6806791398557588, "front_wheel_angle": -0.031543462039866035, "heading_rate": -0.0018201111991293548, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141159.611889} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3932162277635794, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.9434646338160393, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.2473709460108092, "gear": 1, "accelerator_pedal_position": 0.3932162277635794, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.093190474788047, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141159.611889} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.2199997901916504, "x": 0.010485176694682075, "y": -4.560607775871972e-06, "z": null, "yaw": 6.282259370934885, "pitch": null, "roll": null}, "v": 0.14766734168722773, "accelerator_pedal_position": 0.3923222334868708, "brake_pedal_position": 0.0, "acceleration": 0.9944125357705711, "steering_wheel_angle": -0.6806791398557588, "front_wheel_angle": -0.031543462039866035, "heading_rate": -0.0018201111991293548, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141159.6818888} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3932162277635794, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.9434646338160393, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.2573171555345345, "gear": 1, "accelerator_pedal_position": 0.3932162277635794, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.13412331551327, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141159.6818888} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141159.6918888, "x": 4.0322141645988605, "y": 4.999957721181195, "z": null, "yaw": -0.0026997138909716414, "pitch": null, "roll": null}, "v": 0.2573171555345345, "accelerator_pedal_position": 0.3932162277635794, "brake_pedal_position": 0.0, "acceleration": 0.9940734445603205, "steering_wheel_angle": -1.13412331551327, "front_wheel_angle": -0.052881359757611233, "heading_rate": -0.005320304395023072, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141159.7018888} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3941644766339281, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4697840567974108, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.28724136484811175, "gear": 1, "accelerator_pedal_position": 0.3941644766339281, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.13412331551327, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141159.7018888} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.3299996852874756, "x": 0.032214164598860506, "y": -4.227881880503048e-05, "z": null, "yaw": 6.280485593288614, "pitch": null, "roll": null}, "v": 0.2573171555345345, "accelerator_pedal_position": 0.3932162277635794, "brake_pedal_position": 0.0, "acceleration": 0.9940734445603205, "steering_wheel_angle": -1.13412331551327, "front_wheel_angle": -0.052881359757611233, "heading_rate": -0.005320304395023072, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141159.7218888} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3941644766339281, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4697840567974108, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.28724136484811175, "gear": 1, "accelerator_pedal_position": 0.3941644766339281, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.13412331551327, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141159.7218888} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.3299996852874756, "x": 0.032214164598860506, "y": -4.227881880503048e-05, "z": null, "yaw": 6.280485593288614, "pitch": null, "roll": null}, "v": 0.2573171555345345, "accelerator_pedal_position": 0.3932162277635794, "brake_pedal_position": 0.0, "acceleration": 0.9940734445603205, "steering_wheel_angle": -1.13412331551327, "front_wheel_angle": -0.052881359757611233, "heading_rate": -0.005320304395023072, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141159.7418888} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3941644766339281, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4697840567974108, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.3072026063415831, "gear": 1, "accelerator_pedal_position": 0.3941644766339281, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.13412331551327, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141159.7418888} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.3299996852874756, "x": 0.032214164598860506, "y": -4.227881880503048e-05, "z": null, "yaw": 6.280485593288614, "pitch": null, "roll": null}, "v": 0.2573171555345345, "accelerator_pedal_position": 0.3932162277635794, "brake_pedal_position": 0.0, "acceleration": 0.9940734445603205, "steering_wheel_angle": -1.13412331551327, "front_wheel_angle": -0.052881359757611233, "heading_rate": -0.005320304395023072, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141159.7618887} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3941644766339281, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4697840567974108, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.3371024867562946, "gear": 1, "accelerator_pedal_position": 0.3941644766339281, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.13412331551327, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141159.7618887} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.3299996852874756, "x": 0.032214164598860506, "y": -4.227881880503048e-05, "z": null, "yaw": 6.280485593288614, "pitch": null, "roll": null}, "v": 0.2573171555345345, "accelerator_pedal_position": 0.3932162277635794, "brake_pedal_position": 0.0, "acceleration": 0.9940734445603205, "steering_wheel_angle": -1.13412331551327, "front_wheel_angle": -0.052881359757611233, "heading_rate": -0.005320304395023072, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141159.7818887} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3941644766339281, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4697840567974108, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.34705785149387924, "gear": 1, "accelerator_pedal_position": 0.3941644766339281, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.13412331551327, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141159.7818887} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141159.8018887, "x": 4.066003717519418, "y": 4.999829298651387, "z": null, "yaw": -0.004974080255067382, "pitch": null, "roll": null}, "v": 0.36695158801381655, "accelerator_pedal_position": 0.3941644766339281, "brake_pedal_position": 0.0, "acceleration": 0.9938338648819012, "steering_wheel_angle": -1.13412331551327, "front_wheel_angle": -0.052881359757611233, "heading_rate": -0.007587112263910388, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141159.8018887} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.39515105825282393, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1252522143484467, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.37688992666263554, "gear": 1, "accelerator_pedal_position": 0.3941644766339281, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.13412331551327, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141159.8018887} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.4399995803833008, "x": 0.06600371751941836, "y": -0.0001707013486127451, "z": null, "yaw": 6.278211226924519, "pitch": null, "roll": null}, "v": 0.36695158801381655, "accelerator_pedal_position": 0.3941644766339281, "brake_pedal_position": 0.0, "acceleration": 0.9938338648819012, "steering_wheel_angle": -1.13412331551327, "front_wheel_angle": -0.052881359757611233, "heading_rate": -0.007587112263910388, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141159.8218887} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.39515105825282393, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1252522143484467, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.3868842182384237, "gear": 1, "accelerator_pedal_position": 0.39515105825282393, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.13412331551327, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141159.8218887} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.4399995803833008, "x": 0.06600371751941836, "y": -0.0001707013486127451, "z": null, "yaw": 6.278211226924519, "pitch": null, "roll": null}, "v": 0.36695158801381655, "accelerator_pedal_position": 0.3941644766339281, "brake_pedal_position": 0.0, "acceleration": 0.9938338648819012, "steering_wheel_angle": -1.13412331551327, "front_wheel_angle": -0.052881359757611233, "heading_rate": -0.007587112263910388, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141159.8418887} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.39515105825282393, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1252522143484467, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.40685550329849407, "gear": 1, "accelerator_pedal_position": 0.39515105825282393, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.13412331551327, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141159.8418887} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.4399995803833008, "x": 0.06600371751941836, "y": -0.0001707013486127451, "z": null, "yaw": 6.278211226924519, "pitch": null, "roll": null}, "v": 0.36695158801381655, "accelerator_pedal_position": 0.3941644766339281, "brake_pedal_position": 0.0, "acceleration": 0.9938338648819012, "steering_wheel_angle": -1.13412331551327, "front_wheel_angle": -0.052881359757611233, "heading_rate": -0.007587112263910388, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141159.8618886} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.39515105825282393, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1252522143484467, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.4268036135263509, "gear": 1, "accelerator_pedal_position": 0.39515105825282393, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.13412331551327, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141159.8618886} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.4399995803833008, "x": 0.06600371751941836, "y": -0.0001707013486127451, "z": null, "yaw": 6.278211226924519, "pitch": null, "roll": null}, "v": 0.36695158801381655, "accelerator_pedal_position": 0.3941644766339281, "brake_pedal_position": 0.0, "acceleration": 0.9938338648819012, "steering_wheel_angle": -1.13412331551327, "front_wheel_angle": -0.052881359757611233, "heading_rate": -0.007587112263910388, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141159.8818886} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.39515105825282393, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1252522143484467, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.44672841668996577, "gear": 1, "accelerator_pedal_position": 0.39515105825282393, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.13412331551327, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141159.8818886} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.4399995803833008, "x": 0.06600371751941836, "y": -0.0001707013486127451, "z": null, "yaw": 6.278211226924519, "pitch": null, "roll": null}, "v": 0.36695158801381655, "accelerator_pedal_position": 0.3941644766339281, "brake_pedal_position": 0.0, "acceleration": 0.9938338648819012, "steering_wheel_angle": -1.13412331551327, "front_wheel_angle": -0.052881359757611233, "heading_rate": -0.007587112263910388, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141159.9018886} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.39515105825282393, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1252522143484467, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5063616721607517, "gear": 1, "accelerator_pedal_position": 0.39515105825282393, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.13412331551327, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141159.9018886} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141159.9118886, "x": 4.11185185898861, "y": 4.999551577202913, "z": null, "yaw": -0.00724844661916312, "pitch": null, "roll": null}, "v": 0.47657163318349777, "accelerator_pedal_position": 0.39515105825282393, "brake_pedal_position": 0.0, "acceleration": 0.9935943272054226, "steering_wheel_angle": -1.13412331551327, "front_wheel_angle": -0.052881359757611233, "heading_rate": -0.009853622659952016, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141159.9418886} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3961759658999563, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9006736540747364, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5063616721607517, "gear": 1, "accelerator_pedal_position": 0.39515105825282393, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.13412331551327, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141159.9418886} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.549999475479126, "x": 0.11185185898860972, "y": -0.0004484227970866783, "z": null, "yaw": 6.2759368605604235, "pitch": null, "roll": null}, "v": 0.47657163318349777, "accelerator_pedal_position": 0.39515105825282393, "brake_pedal_position": 0.0, "acceleration": 0.9935943272054226, "steering_wheel_angle": -1.13412331551327, "front_wheel_angle": -0.052881359757611233, "heading_rate": -0.009853622659952016, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141159.9618886} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3961759658999563, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9006736540747364, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5263200138263351, "gear": 1, "accelerator_pedal_position": 0.3961759658999563, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.13412331551327, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141159.9618886} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.549999475479126, "x": 0.11185185898860972, "y": -0.0004484227970866783, "z": null, "yaw": 6.2759368605604235, "pitch": null, "roll": null}, "v": 0.47657163318349777, "accelerator_pedal_position": 0.39515105825282393, "brake_pedal_position": 0.0, "acceleration": 0.9935943272054226, "steering_wheel_angle": -1.13412331551327, "front_wheel_angle": -0.052881359757611233, "heading_rate": -0.009853622659952016, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141159.9818885} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3961759658999563, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9006736540747364, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5462542424934719, "gear": 1, "accelerator_pedal_position": 0.3961759658999563, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.13412331551327, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141159.9818885} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.549999475479126, "x": 0.11185185898860972, "y": -0.0004484227970866783, "z": null, "yaw": 6.2759368605604235, "pitch": null, "roll": null}, "v": 0.47657163318349777, "accelerator_pedal_position": 0.39515105825282393, "brake_pedal_position": 0.0, "acceleration": 0.9935943272054226, "steering_wheel_angle": -1.13412331551327, "front_wheel_angle": -0.052881359757611233, "heading_rate": -0.009853622659952016, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141160.0018885} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3961759658999563, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9006736540747364, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5661642283936793, "gear": 1, "accelerator_pedal_position": 0.3961759658999563, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.13412331551327, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141160.0018885} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141160.0218885, "x": 4.169745575415375, "y": 4.999069811154565, "z": null, "yaw": -0.009522812983258858, "pitch": null, "roll": null}, "v": 0.5860498424950735, "accelerator_pedal_position": 0.3961759658999563, "brake_pedal_position": 0.0, "acceleration": 0.993362750571088, "steering_wheel_angle": -1.13412331551327, "front_wheel_angle": -0.052881359757611233, "heading_rate": -0.012117200449585482, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141160.0218885} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3972379258085822, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7175784026895959, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5860498424950735, "gear": 1, "accelerator_pedal_position": 0.3961759658999563, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.13412331551327, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141160.0218885} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.6599993705749512, "x": 0.16974557541537472, "y": -0.0009301888454347207, "z": null, "yaw": 6.273662494196327, "pitch": null, "roll": null}, "v": 0.5860498424950735, "accelerator_pedal_position": 0.3961759658999563, "brake_pedal_position": 0.0, "acceleration": 0.993362750571088, "steering_wheel_angle": -1.13412331551327, "front_wheel_angle": -0.052881359757611233, "heading_rate": -0.012117200449585482, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141160.0418885} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3972379258085822, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7175784026895959, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6060436603953886, "gear": 1, "accelerator_pedal_position": 0.3972379258085822, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.13412331551327, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141160.0418885} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.6599993705749512, "x": 0.16974557541537472, "y": -0.0009301888454347207, "z": null, "yaw": 6.273662494196327, "pitch": null, "roll": null}, "v": 0.5860498424950735, "accelerator_pedal_position": 0.3961759658999563, "brake_pedal_position": 0.0, "acceleration": 0.993362750571088, "steering_wheel_angle": -1.13412331551327, "front_wheel_angle": -0.052881359757611233, "heading_rate": -0.012117200449585482, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141160.0618885} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3972379258085822, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7175784026895959, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6459567885149271, "gear": 1, "accelerator_pedal_position": 0.3972379258085822, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.13412331551327, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141160.0618885} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.6599993705749512, "x": 0.16974557541537472, "y": -0.0009301888454347207, "z": null, "yaw": 6.273662494196327, "pitch": null, "roll": null}, "v": 0.5860498424950735, "accelerator_pedal_position": 0.3961759658999563, "brake_pedal_position": 0.0, "acceleration": 0.993362750571088, "steering_wheel_angle": -1.13412331551327, "front_wheel_angle": -0.052881359757611233, "heading_rate": -0.012117200449585482, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141160.0818884} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3972379258085822, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7175784026895959, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6559194544664432, "gear": 1, "accelerator_pedal_position": 0.3972379258085822, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.13412331551327, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141160.0818884} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.6599993705749512, "x": 0.16974557541537472, "y": -0.0009301888454347207, "z": null, "yaw": 6.273662494196327, "pitch": null, "roll": null}, "v": 0.5860498424950735, "accelerator_pedal_position": 0.3961759658999563, "brake_pedal_position": 0.0, "acceleration": 0.993362750571088, "steering_wheel_angle": -1.13412331551327, "front_wheel_angle": -0.052881359757611233, "heading_rate": -0.012117200449585482, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141160.1118884} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3972379258085822, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7175784026895959, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7056382921936021, "gear": 1, "accelerator_pedal_position": 0.3972379258085822, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.13412331551327, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141160.1118884} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141160.1318884, "x": 4.239696867679311, "y": 4.998329066673654, "z": null, "yaw": -0.011797179347354596, "pitch": null, "roll": null}, "v": 0.6957071762662096, "accelerator_pedal_position": 0.3972379258085822, "brake_pedal_position": 0.0, "acceleration": 0.993111592739245, "steering_wheel_angle": -1.13412331551327, "front_wheel_angle": -0.052881359757611233, "heading_rate": -0.014384481826908135, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141160.1418884} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.398340070970303, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5519999618234283, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7056382921936021, "gear": 1, "accelerator_pedal_position": 0.3972379258085822, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.13412331551327, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141160.1418884} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.7699992656707764, "x": 0.23969686767931098, "y": -0.0016709333263458248, "z": null, "yaw": 6.271388127832232, "pitch": null, "roll": null}, "v": 0.6957071762662096, "accelerator_pedal_position": 0.3972379258085822, "brake_pedal_position": 0.0, "acceleration": 0.993111592739245, "steering_wheel_angle": -1.13412331551327, "front_wheel_angle": -0.052881359757611233, "heading_rate": -0.014384481826908135, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141160.1618884} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.398340070970303, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5519999618234283, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7256191605047495, "gear": 1, "accelerator_pedal_position": 0.398340070970303, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.13412331551327, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141160.1618884} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.7699992656707764, "x": 0.23969686767931098, "y": -0.0016709333263458248, "z": null, "yaw": 6.271388127832232, "pitch": null, "roll": null}, "v": 0.6957071762662096, "accelerator_pedal_position": 0.3972379258085822, "brake_pedal_position": 0.0, "acceleration": 0.993111592739245, "steering_wheel_angle": -1.13412331551327, "front_wheel_angle": -0.052881359757611233, "heading_rate": -0.014384481826908135, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141160.1818883} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.398340070970303, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5519999618234283, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7455742967735622, "gear": 1, "accelerator_pedal_position": 0.398340070970303, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.13412331551327, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141160.1818883} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.7699992656707764, "x": 0.23969686767931098, "y": -0.0016709333263458248, "z": null, "yaw": 6.271388127832232, "pitch": null, "roll": null}, "v": 0.6957071762662096, "accelerator_pedal_position": 0.3972379258085822, "brake_pedal_position": 0.0, "acceleration": 0.993111592739245, "steering_wheel_angle": -1.13412331551327, "front_wheel_angle": -0.052881359757611233, "heading_rate": -0.014384481826908135, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141160.2018883} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.398340070970303, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5519999618234283, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7655035749073185, "gear": 1, "accelerator_pedal_position": 0.398340070970303, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.13412331551327, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141160.2018883} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.7699992656707764, "x": 0.23969686767931098, "y": -0.0016709333263458248, "z": null, "yaw": 6.271388127832232, "pitch": null, "roll": null}, "v": 0.6957071762662096, "accelerator_pedal_position": 0.3972379258085822, "brake_pedal_position": 0.0, "acceleration": 0.993111592739245, "steering_wheel_angle": -1.13412331551327, "front_wheel_angle": -0.052881359757611233, "heading_rate": -0.014384481826908135, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141160.2218883} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.398340070970303, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5519999618234283, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7854068695947338, "gear": 1, "accelerator_pedal_position": 0.398340070970303, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.13412331551327, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141160.2218883} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141160.2418883, "x": 4.32170037677306, "y": 4.997274556099358, "z": null, "yaw": -0.014071545711450334, "pitch": null, "roll": null}, "v": 0.805284056308144, "accelerator_pedal_position": 0.398340070970303, "brake_pedal_position": 0.0, "acceleration": 0.9928764166355455, "steering_wheel_angle": -1.13412331551327, "front_wheel_angle": -0.052881359757611233, "heading_rate": -0.016650099738271133, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141160.2418883} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3994798443086157, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.40036774030185984, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.805284056308144, "gear": 1, "accelerator_pedal_position": 0.398340070970303, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.13412331551327, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141160.2418883} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.8799991607666016, "x": 0.32170037677305974, "y": -0.0027254439006423326, "z": null, "yaw": 6.269113761468136, "pitch": null, "roll": null}, "v": 0.805284056308144, "accelerator_pedal_position": 0.398340070970303, "brake_pedal_position": 0.0, "acceleration": 0.9928764166355455, "steering_wheel_angle": -1.13412331551327, "front_wheel_angle": -0.052881359757611233, "heading_rate": -0.016650099738271133, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141160.2618883} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3994798443086157, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.40036774030185984, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8252774357400314, "gear": 1, "accelerator_pedal_position": 0.3994798443086157, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.13412331551327, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141160.2618883} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.8799991607666016, "x": 0.32170037677305974, "y": -0.0027254439006423326, "z": null, "yaw": 6.269113761468136, "pitch": null, "roll": null}, "v": 0.805284056308144, "accelerator_pedal_position": 0.398340070970303, "brake_pedal_position": 0.0, "acceleration": 0.9928764166355455, "steering_wheel_angle": -1.13412331551327, "front_wheel_angle": -0.052881359757611233, "heading_rate": -0.016650099738271133, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141160.2818882} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3994798443086157, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.40036774030185984, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8452442705617675, "gear": 1, "accelerator_pedal_position": 0.3994798443086157, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.13412331551327, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141160.2818882} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.8799991607666016, "x": 0.32170037677305974, "y": -0.0027254439006423326, "z": null, "yaw": 6.269113761468136, "pitch": null, "roll": null}, "v": 0.805284056308144, "accelerator_pedal_position": 0.398340070970303, "brake_pedal_position": 0.0, "acceleration": 0.9928764166355455, "steering_wheel_angle": -1.13412331551327, "front_wheel_angle": -0.052881359757611233, "heading_rate": -0.016650099738271133, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141160.3018882} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3994798443086157, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.40036774030185984, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8651844365993495, "gear": 1, "accelerator_pedal_position": 0.3994798443086157, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.13412331551327, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141160.3018882} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.8799991607666016, "x": 0.32170037677305974, "y": -0.0027254439006423326, "z": null, "yaw": 6.269113761468136, "pitch": null, "roll": null}, "v": 0.805284056308144, "accelerator_pedal_position": 0.398340070970303, "brake_pedal_position": 0.0, "acceleration": 0.9928764166355455, "steering_wheel_angle": -1.13412331551327, "front_wheel_angle": -0.052881359757611233, "heading_rate": -0.016650099738271133, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141160.3218882} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3994798443086157, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.40036774030185984, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8850978104824444, "gear": 1, "accelerator_pedal_position": 0.3994798443086157, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.13412331551327, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141160.3218882} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.8799991607666016, "x": 0.32170037677305974, "y": -0.0027254439006423326, "z": null, "yaw": 6.269113761468136, "pitch": null, "roll": null}, "v": 0.805284056308144, "accelerator_pedal_position": 0.398340070970303, "brake_pedal_position": 0.0, "acceleration": 0.9928764166355455, "steering_wheel_angle": -1.13412331551327, "front_wheel_angle": -0.052881359757611233, "heading_rate": -0.016650099738271133, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141160.3418882} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3994798443086157, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.40036774030185984, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9049842696464003, "gear": 1, "accelerator_pedal_position": 0.3994798443086157, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.13412331551327, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141160.3418882} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141160.3518882, "x": 4.415759861559938, "y": 4.9958513789093475, "z": null, "yaw": -0.016345912075546077, "pitch": null, "roll": null}, "v": 0.9149173681280349, "accelerator_pedal_position": 0.3994798443086157, "brake_pedal_position": 0.0, "acceleration": 0.9926324206174231, "steering_wheel_angle": -1.13412331551327, "front_wheel_angle": -0.052881359757611233, "heading_rate": -0.018916884436340042, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141160.3618882} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.40065865700982806, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.26916338950335944, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9248436923342092, "gear": 1, "accelerator_pedal_position": 0.3994798443086157, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.13412331551327, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141160.3618882} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.9899990558624268, "x": 0.4157598615599376, "y": -0.0041486210906525045, "z": null, "yaw": 6.26683939510404, "pitch": null, "roll": null}, "v": 0.9149173681280349, "accelerator_pedal_position": 0.3994798443086157, "brake_pedal_position": 0.0, "acceleration": 0.9926324206174231, "steering_wheel_angle": -1.13412331551327, "front_wheel_angle": -0.052881359757611233, "heading_rate": -0.018916884436340042, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141160.3818882} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.40065865700982806, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.26916338950335944, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.944823258573748, "gear": 1, "accelerator_pedal_position": 0.40065865700982806, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.0950530065795974, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141160.3818882} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.9899990558624268, "x": 0.4157598615599376, "y": -0.0041486210906525045, "z": null, "yaw": 6.26683939510404, "pitch": null, "roll": null}, "v": 0.9149173681280349, "accelerator_pedal_position": 0.3994798443086157, "brake_pedal_position": 0.0, "acceleration": 0.9926324206174231, "steering_wheel_angle": -1.13412331551327, "front_wheel_angle": -0.052881359757611233, "heading_rate": -0.018916884436340042, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141160.4018881} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.40065865700982806, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.26916338950335944, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9647753437717637, "gear": 1, "accelerator_pedal_position": 0.40065865700982806, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.0950530065795974, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141160.4018881} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.9899990558624268, "x": 0.4157598615599376, "y": -0.0041486210906525045, "z": null, "yaw": 6.26683939510404, "pitch": null, "roll": null}, "v": 0.9149173681280349, "accelerator_pedal_position": 0.3994798443086157, "brake_pedal_position": 0.0, "acceleration": 0.9926324206174231, "steering_wheel_angle": -1.13412331551327, "front_wheel_angle": -0.052881359757611233, "heading_rate": -0.018916884436340042, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141160.421888} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.40065865700982806, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.26916338950335944, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9846998265481088, "gear": 1, "accelerator_pedal_position": 0.40065865700982806, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.0950530065795974, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141160.421888} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.9899990558624268, "x": 0.4157598615599376, "y": -0.0041486210906525045, "z": null, "yaw": 6.26683939510404, "pitch": null, "roll": null}, "v": 0.9149173681280349, "accelerator_pedal_position": 0.3994798443086157, "brake_pedal_position": 0.0, "acceleration": 0.9926324206174231, "steering_wheel_angle": -1.13412331551327, "front_wheel_angle": -0.052881359757611233, "heading_rate": -0.018916884436340042, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141160.441888} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.40065865700982806, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.26916338950335944, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0045965863502433, "gear": 1, "accelerator_pedal_position": 0.40065865700982806, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.0950530065795974, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141160.441888} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141160.461888, "x": 4.521866048632031, "y": 4.994007416069539, "z": null, "yaw": -0.018555095939810817, "pitch": null, "roll": null}, "v": 1.0244655034550187, "accelerator_pedal_position": 0.40065865700982806, "brake_pedal_position": 0.0, "acceleration": 0.9923980354609807, "steering_wheel_angle": -1.0950530065795974, "front_wheel_angle": -0.05103228090105111, "heading_rate": -0.020439938881359972, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141160.461888} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.40187497133607114, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.1542598356108028, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0244655034550187, "gear": 1, "accelerator_pedal_position": 0.40065865700982806, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.0950530065795974, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141160.461888} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.099998950958252, "x": 0.521866048632031, "y": -0.005992583930461315, "z": null, "yaw": 6.264630211239775, "pitch": null, "roll": null}, "v": 1.0244655034550187, "accelerator_pedal_position": 0.40065865700982806, "brake_pedal_position": 0.0, "acceleration": 0.9923980354609807, "steering_wheel_angle": -1.0950530065795974, "front_wheel_angle": -0.05103228090105111, "heading_rate": -0.020439938881359972, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141160.481888} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.40187497133607114, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.1542598356108028, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.044458444524012, "gear": 1, "accelerator_pedal_position": 0.40187497133607114, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.0170228671867927, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141160.481888} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.099998950958252, "x": 0.521866048632031, "y": -0.005992583930461315, "z": null, "yaw": 6.264630211239775, "pitch": null, "roll": null}, "v": 1.0244655034550187, "accelerator_pedal_position": 0.40065865700982806, "brake_pedal_position": 0.0, "acceleration": 0.9923980354609807, "steering_wheel_angle": -1.0950530065795974, "front_wheel_angle": -0.05103228090105111, "heading_rate": -0.020439938881359972, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141160.501888} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.40187497133607114, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.1542598356108028, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0644230899380516, "gear": 1, "accelerator_pedal_position": 0.40187497133607114, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.9779444772075659, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141160.501888} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.099998950958252, "x": 0.521866048632031, "y": -0.005992583930461315, "z": null, "yaw": 6.264630211239775, "pitch": null, "roll": null}, "v": 1.0244655034550187, "accelerator_pedal_position": 0.40065865700982806, "brake_pedal_position": 0.0, "acceleration": 0.9923980354609807, "steering_wheel_angle": -1.0950530065795974, "front_wheel_angle": -0.05103228090105111, "heading_rate": -0.020439938881359972, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141160.521888} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.40187497133607114, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.1542598356108028, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0843593203654394, "gear": 1, "accelerator_pedal_position": 0.40187497133607114, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.9779444772075659, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141160.521888} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.099998950958252, "x": 0.521866048632031, "y": -0.005992583930461315, "z": null, "yaw": 6.264630211239775, "pitch": null, "roll": null}, "v": 1.0244655034550187, "accelerator_pedal_position": 0.40065865700982806, "brake_pedal_position": 0.0, "acceleration": 0.9923980354609807, "steering_wheel_angle": -1.0950530065795974, "front_wheel_angle": -0.05103228090105111, "heading_rate": -0.020439938881359972, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141160.541888} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.40187497133607114, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.1542598356108028, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.10426701732387, "gear": 1, "accelerator_pedal_position": 0.40187497133607114, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.9779444772075659, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141160.541888} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.099998950958252, "x": 0.521866048632031, "y": -0.005992583930461315, "z": null, "yaw": 6.264630211239775, "pitch": null, "roll": null}, "v": 1.0244655034550187, "accelerator_pedal_position": 0.40065865700982806, "brake_pedal_position": 0.0, "acceleration": 0.9923980354609807, "steering_wheel_angle": -1.0950530065795974, "front_wheel_angle": -0.05103228090105111, "heading_rate": -0.020439938881359972, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141160.561888} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.40187497133607114, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.1542598356108028, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1241460631820348, "gear": 1, "accelerator_pedal_position": 0.40187497133607114, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.9779444772075659, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141160.561888} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141160.571888, "x": 4.640023074827214, "y": 4.991703305625816, "z": null, "yaw": -0.02055491014442012, "pitch": null, "roll": null}, "v": 1.1340748054218115, "accelerator_pedal_position": 0.40187497133607114, "brake_pedal_position": 0.0, "acceleration": 0.9921535739364286, "steering_wheel_angle": -0.9779444772075659, "front_wheel_angle": -0.045501886641880644, "heading_rate": -0.02017116631494419, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141160.581888} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4031303995062425, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.05250972383997811, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1439963411611758, "gear": 1, "accelerator_pedal_position": 0.40187497133607114, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.9779444772075659, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141160.581888} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.2099988460540771, "x": 0.640023074827214, "y": -0.008296694374183566, "z": null, "yaw": 6.262630397035166, "pitch": null, "roll": null}, "v": 1.1340748054218115, "accelerator_pedal_position": 0.40187497133607114, "brake_pedal_position": 0.0, "acceleration": 0.9921535739364286, "steering_wheel_angle": -0.9779444772075659, "front_wheel_angle": -0.045501886641880644, "heading_rate": -0.02017116631494419, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141160.601888} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4031303995062425, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.05250972383997811, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1739527854943848, "gear": 1, "accelerator_pedal_position": 0.4031303995062425, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.899870592740773, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141160.601888} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.2099988460540771, "x": 0.640023074827214, "y": -0.008296694374183566, "z": null, "yaw": 6.262630397035166, "pitch": null, "roll": null}, "v": 1.1340748054218115, "accelerator_pedal_position": 0.40187497133607114, "brake_pedal_position": 0.0, "acceleration": 0.9921535739364286, "steering_wheel_angle": -0.9779444772075659, "front_wheel_angle": -0.045501886641880644, "heading_rate": -0.02017116631494419, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141160.611888} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4031303995062425, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.05250972383997811, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1739527854943848, "gear": 1, "accelerator_pedal_position": 0.4031303995062425, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.899870592740773, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141160.611888} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.2099988460540771, "x": 0.640023074827214, "y": -0.008296694374183566, "z": null, "yaw": 6.262630397035166, "pitch": null, "roll": null}, "v": 1.1340748054218115, "accelerator_pedal_position": 0.40187497133607114, "brake_pedal_position": 0.0, "acceleration": 0.9921535739364286, "steering_wheel_angle": -0.9779444772075659, "front_wheel_angle": -0.045501886641880644, "heading_rate": -0.02017116631494419, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141160.641888} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4031303995062425, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.05250972383997811, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2038433329169478, "gear": 1, "accelerator_pedal_position": 0.4031303995062425, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.899870592740773, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141160.641888} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.2099988460540771, "x": 0.640023074827214, "y": -0.008296694374183566, "z": null, "yaw": 6.262630397035166, "pitch": null, "roll": null}, "v": 1.1340748054218115, "accelerator_pedal_position": 0.40187497133607114, "brake_pedal_position": 0.0, "acceleration": 0.9921535739364286, "steering_wheel_angle": -0.9779444772075659, "front_wheel_angle": -0.045501886641880644, "heading_rate": -0.02017116631494419, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141160.661888} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4031303995062425, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.05250972383997811, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.22373356210781, "gear": 1, "accelerator_pedal_position": 0.4031303995062425, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.899870592740773, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141160.661888} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141160.6818879, "x": 4.770221543669862, "y": 4.988914503825118, "z": null, "yaw": -0.02238909574644596, "pitch": null, "roll": null}, "v": 1.2435942155124968, "accelerator_pedal_position": 0.4031303995062425, "brake_pedal_position": 0.0, "acceleration": 0.9919200204098292, "steering_wheel_angle": -0.899870592740773, "front_wheel_angle": -0.04182481509309995, "heading_rate": -0.020329472051588273, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141160.6818879} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.40442319624066986, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.024488167616568114, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2435942155124968, "gear": 1, "accelerator_pedal_position": 0.4031303995062425, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.899870592740773, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141160.6818879} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.3199987411499023, "x": 0.7702215436698623, "y": -0.011085496174882081, "z": null, "yaw": 6.26079621143314, "pitch": null, "roll": null}, "v": 1.2435942155124968, "accelerator_pedal_position": 0.4031303995062425, "brake_pedal_position": 0.0, "acceleration": 0.9919200204098292, "steering_wheel_angle": -0.899870592740773, "front_wheel_angle": -0.04182481509309995, "heading_rate": -0.020329472051588273, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141160.7018878} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.40442319624066986, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.024488167616568114, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2635867183240659, "gear": 1, "accelerator_pedal_position": 0.40442319624066986, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.8216041229744567, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141160.7018878} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.3199987411499023, "x": 0.7702215436698623, "y": -0.011085496174882081, "z": null, "yaw": 6.26079621143314, "pitch": null, "roll": null}, "v": 1.2435942155124968, "accelerator_pedal_position": 0.4031303995062425, "brake_pedal_position": 0.0, "acceleration": 0.9919200204098292, "steering_wheel_angle": -0.899870592740773, "front_wheel_angle": -0.04182481509309995, "heading_rate": -0.020329472051588273, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141160.7218878} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.40442319624066986, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.024488167616568114, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.283549175010773, "gear": 1, "accelerator_pedal_position": 0.40442319624066986, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.8216041229744567, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141160.7218878} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.3199987411499023, "x": 0.7702215436698623, "y": -0.011085496174882081, "z": null, "yaw": 6.26079621143314, "pitch": null, "roll": null}, "v": 1.2435942155124968, "accelerator_pedal_position": 0.4031303995062425, "brake_pedal_position": 0.0, "acceleration": 0.9919200204098292, "steering_wheel_angle": -0.899870592740773, "front_wheel_angle": -0.04182481509309995, "heading_rate": -0.020329472051588273, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141160.7318878} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.40442319624066986, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.024488167616568114, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2935191003398425, "gear": 1, "accelerator_pedal_position": 0.40442319624066986, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.8216041229744567, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141160.7318878} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.3199987411499023, "x": 0.7702215436698623, "y": -0.011085496174882081, "z": null, "yaw": 6.26079621143314, "pitch": null, "roll": null}, "v": 1.2435942155124968, "accelerator_pedal_position": 0.4031303995062425, "brake_pedal_position": 0.0, "acceleration": 0.9919200204098292, "steering_wheel_angle": -0.899870592740773, "front_wheel_angle": -0.04182481509309995, "heading_rate": -0.020329472051588273, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141160.7518878} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.40442319624066986, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.024488167616568114, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3233834941665805, "gear": 1, "accelerator_pedal_position": 0.40442319624066986, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.8216041229744567, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141160.7518878} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.3199987411499023, "x": 0.7702215436698623, "y": -0.011085496174882081, "z": null, "yaw": 6.26079621143314, "pitch": null, "roll": null}, "v": 1.2435942155124968, "accelerator_pedal_position": 0.4031303995062425, "brake_pedal_position": 0.0, "acceleration": 0.9919200204098292, "steering_wheel_angle": -0.899870592740773, "front_wheel_angle": -0.04182481509309995, "heading_rate": -0.020329472051588273, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141160.7718878} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.40442319624066986, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.024488167616568114, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3333231177972757, "gear": 1, "accelerator_pedal_position": 0.40442319624066986, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.8216041229744567, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141160.7718878} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141160.7918878, "x": 4.912466299607237, "y": 4.985618805987714, "z": null, "yaw": -0.024050588540212182, "pitch": null, "roll": null}, "v": 1.3531795197146586, "accelerator_pedal_position": 0.40442319624066986, "brake_pedal_position": 0.0, "acceleration": 0.9916750523927016, "steering_wheel_angle": -0.8216041229744567, "front_wheel_angle": -0.03814658712980844, "heading_rate": -0.020173528564566702, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141160.7918878} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4057551878578376, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.10611291627059201, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3630962702385856, "gear": 1, "accelerator_pedal_position": 0.40442319624066986, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.8216041229744567, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141160.7918878} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.4299986362457275, "x": 0.912466299607237, "y": -0.014381194012286436, "z": null, "yaw": 6.259134718639374, "pitch": null, "roll": null}, "v": 1.3531795197146586, "accelerator_pedal_position": 0.40442319624066986, "brake_pedal_position": 0.0, "acceleration": 0.9916750523927016, "steering_wheel_angle": -0.8216041229744567, "front_wheel_angle": -0.03814658712980844, "heading_rate": -0.020173528564566702, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141160.8118877} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4057551878578376, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.10611291627059201, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3730886182003874, "gear": 1, "accelerator_pedal_position": 0.4057551878578376, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7823235371307881, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141160.8118877} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.4299986362457275, "x": 0.912466299607237, "y": -0.014381194012286436, "z": null, "yaw": 6.259134718639374, "pitch": null, "roll": null}, "v": 1.3531795197146586, "accelerator_pedal_position": 0.40442319624066986, "brake_pedal_position": 0.0, "acceleration": 0.9916750523927016, "steering_wheel_angle": -0.8216041229744567, "front_wheel_angle": -0.03814658712980844, "heading_rate": -0.020173528564566702, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141160.8318877} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4057551878578376, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.10611291627059201, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3930501093626397, "gear": 1, "accelerator_pedal_position": 0.4057551878578376, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7430007559045173, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141160.8318877} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.4299986362457275, "x": 0.912466299607237, "y": -0.014381194012286436, "z": null, "yaw": 6.259134718639374, "pitch": null, "roll": null}, "v": 1.3531795197146586, "accelerator_pedal_position": 0.40442319624066986, "brake_pedal_position": 0.0, "acceleration": 0.9916750523927016, "steering_wheel_angle": -0.8216041229744567, "front_wheel_angle": -0.03814658712980844, "heading_rate": -0.020173528564566702, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141160.8518877} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4057551878578376, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.10611291627059201, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.41298056802264, "gear": 1, "accelerator_pedal_position": 0.4057551878578376, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7430007559045173, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141160.8518877} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.4299986362457275, "x": 0.912466299607237, "y": -0.014381194012286436, "z": null, "yaw": 6.259134718639374, "pitch": null, "roll": null}, "v": 1.3531795197146586, "accelerator_pedal_position": 0.40442319624066986, "brake_pedal_position": 0.0, "acceleration": 0.9916750523927016, "steering_wheel_angle": -0.8216041229744567, "front_wheel_angle": -0.03814658712980844, "heading_rate": -0.020173528564566702, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141160.8718877} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4057551878578376, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.10611291627059201, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4328798835969403, "gear": 1, "accelerator_pedal_position": 0.4057551878578376, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7430007559045173, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141160.8718877} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.4299986362457275, "x": 0.912466299607237, "y": -0.014381194012286436, "z": null, "yaw": 6.259134718639374, "pitch": null, "roll": null}, "v": 1.3531795197146586, "accelerator_pedal_position": 0.40442319624066986, "brake_pedal_position": 0.0, "acceleration": 0.9916750523927016, "steering_wheel_angle": -0.8216041229744567, "front_wheel_angle": -0.03814658712980844, "heading_rate": -0.020173528564566702, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141160.8918877} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4057551878578376, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.10611291627059201, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.452747946418479, "gear": 1, "accelerator_pedal_position": 0.4057551878578376, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7430007559045173, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141160.8918877} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141160.9018877, "x": 5.066747640077267, "y": 4.981797431831849, "z": null, "yaw": -0.025567941880914637, "pitch": null, "roll": null}, "v": 1.4626702240268021, "accelerator_pedal_position": 0.4057551878578376, "brake_pedal_position": 0.0, "acceleration": 0.9914423710675986, "steering_wheel_angle": -0.7430007559045173, "front_wheel_angle": -0.03446044985131556, "heading_rate": -0.019696966975622062, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141160.9118876} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.38896074280190823, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.19034102382799678, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4814415512842536, "gear": 1, "accelerator_pedal_position": 0.38896074280190823, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.703547999349412, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141160.9118876} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.5399985313415527, "x": 1.066747640077267, "y": -0.018202568168151245, "z": null, "yaw": 6.257617365298672, "pitch": null, "roll": null}, "v": 1.4626702240268021, "accelerator_pedal_position": 0.4057551878578376, "brake_pedal_position": 0.0, "acceleration": 0.9914423710675986, "steering_wheel_angle": -0.7430007559045173, "front_wheel_angle": -0.03446044985131556, "heading_rate": -0.019696966975622062, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141160.9318876} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4071244084870218, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.19034102382799678, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4902914100267435, "gear": 1, "accelerator_pedal_position": 0.38896074280190823, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6640528591202076, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141160.9318876} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.5399985313415527, "x": 1.066747640077267, "y": -0.018202568168151245, "z": null, "yaw": 6.257617365298672, "pitch": null, "roll": null}, "v": 1.4626702240268021, "accelerator_pedal_position": 0.4057551878578376, "brake_pedal_position": 0.0, "acceleration": 0.9914423710675986, "steering_wheel_angle": -0.7430007559045173, "front_wheel_angle": -0.03446044985131556, "heading_rate": -0.019696966975622062, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141160.9518876} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4071244084870218, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.19034102382799678, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5102395029722653, "gear": 1, "accelerator_pedal_position": 0.4071244084870218, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6640528591202076, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141160.9518876} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.5399985313415527, "x": 1.066747640077267, "y": -0.018202568168151245, "z": null, "yaw": 6.257617365298672, "pitch": null, "roll": null}, "v": 1.4626702240268021, "accelerator_pedal_position": 0.4057551878578376, "brake_pedal_position": 0.0, "acceleration": 0.9914423710675986, "steering_wheel_angle": -0.7430007559045173, "front_wheel_angle": -0.03446044985131556, "heading_rate": -0.019696966975622062, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141160.9718876} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4071244084870218, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.19034102382799678, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5301556498745217, "gear": 1, "accelerator_pedal_position": 0.4071244084870218, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6640528591202076, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141160.9718876} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.5399985313415527, "x": 1.066747640077267, "y": -0.018202568168151245, "z": null, "yaw": 6.257617365298672, "pitch": null, "roll": null}, "v": 1.4626702240268021, "accelerator_pedal_position": 0.4057551878578376, "brake_pedal_position": 0.0, "acceleration": 0.9914423710675986, "steering_wheel_angle": -0.7430007559045173, "front_wheel_angle": -0.03446044985131556, "heading_rate": -0.019696966975622062, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141160.9918876} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4071244084870218, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.19034102382799678, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.550039743296505, "gear": 1, "accelerator_pedal_position": 0.4071244084870218, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6640528591202076, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141160.9918876} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141161.0118876, "x": 5.232870215409701, "y": 4.977442834032264, "z": null, "yaw": -0.026926455557307757, "pitch": null, "roll": null}, "v": 1.5698916767389155, "accelerator_pedal_position": 0.4071244084870218, "brake_pedal_position": 0.0, "acceleration": 0.9913873704399989, "steering_wheel_angle": -0.6640528591202076, "front_wheel_angle": -0.03076609726953152, "heading_rate": -0.018872923876472856, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141161.0118876} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.36862711095487505, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.261064729657947, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5698916767389155, "gear": 1, "accelerator_pedal_position": 0.4071244084870218, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6640528591202076, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141161.0118876} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.649998426437378, "x": 1.2328702154097009, "y": -0.02255716596773638, "z": null, "yaw": 6.256258851622278, "pitch": null, "roll": null}, "v": 1.5698916767389155, "accelerator_pedal_position": 0.4071244084870218, "brake_pedal_position": 0.0, "acceleration": 0.9913873704399989, "steering_wheel_angle": -0.6640528591202076, "front_wheel_angle": -0.03076609726953152, "heading_rate": -0.018872923876472856, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141161.0318875} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.38779679511487236, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.261064729657947, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5849011451389725, "gear": 1, "accelerator_pedal_position": 0.36862711095487505, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5847866271323764, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141161.0318875} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.649998426437378, "x": 1.2328702154097009, "y": -0.02255716596773638, "z": null, "yaw": 6.256258851622278, "pitch": null, "roll": null}, "v": 1.5698916767389155, "accelerator_pedal_position": 0.4071244084870218, "brake_pedal_position": 0.0, "acceleration": 0.9913873704399989, "steering_wheel_angle": -0.6640528591202076, "front_wheel_angle": -0.03076609726953152, "heading_rate": -0.018872923876472856, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141161.0518875} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.38779679511487236, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.261064729657947, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6022813509505816, "gear": 1, "accelerator_pedal_position": 0.38779679511487236, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5847866271323764, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141161.0518875} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.649998426437378, "x": 1.2328702154097009, "y": -0.02255716596773638, "z": null, "yaw": 6.256258851622278, "pitch": null, "roll": null}, "v": 1.5698916767389155, "accelerator_pedal_position": 0.4071244084870218, "brake_pedal_position": 0.0, "acceleration": 0.9913873704399989, "steering_wheel_angle": -0.6640528591202076, "front_wheel_angle": -0.03076609726953152, "heading_rate": -0.018872923876472856, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141161.0718875} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.38779679511487236, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.261064729657947, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6196330792587144, "gear": 1, "accelerator_pedal_position": 0.38779679511487236, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5847866271323764, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141161.0718875} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.649998426437378, "x": 1.2328702154097009, "y": -0.02255716596773638, "z": null, "yaw": 6.256258851622278, "pitch": null, "roll": null}, "v": 1.5698916767389155, "accelerator_pedal_position": 0.4071244084870218, "brake_pedal_position": 0.0, "acceleration": 0.9913873704399989, "steering_wheel_angle": -0.6640528591202076, "front_wheel_angle": -0.03076609726953152, "heading_rate": -0.018872923876472856, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141161.0918875} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.38779679511487236, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.261064729657947, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6369562563404034, "gear": 1, "accelerator_pedal_position": 0.38779679511487236, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5847866271323764, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141161.0918875} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.649998426437378, "x": 1.2328702154097009, "y": -0.02255716596773638, "z": null, "yaw": 6.256258851622278, "pitch": null, "roll": null}, "v": 1.5698916767389155, "accelerator_pedal_position": 0.4071244084870218, "brake_pedal_position": 0.0, "acceleration": 0.9913873704399989, "steering_wheel_angle": -0.6640528591202076, "front_wheel_angle": -0.03076609726953152, "heading_rate": -0.018872923876472856, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141161.1118875} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.38779679511487236, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.261064729657947, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.654250809187609, "gear": 1, "accelerator_pedal_position": 0.38779679511487236, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5847866271323764, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141161.1118875} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141161.1218874, "x": 5.410041036521422, "y": 4.972572966994861, "z": null, "yaw": -0.028111385434640108, "pitch": null, "roll": null}, "v": 1.662887328903725, "accelerator_pedal_position": 0.38779679511487236, "brake_pedal_position": 0.0, "acceleration": 0.8629336603364802, "steering_wheel_angle": -0.5847866271323764, "front_wheel_angle": -0.027064803965893197, "heading_rate": -0.017584653025633737, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141161.1318874} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3566231284758664, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.30862447274823657, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6715166655070897, "gear": 1, "accelerator_pedal_position": 0.38779679511487236, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5847866271323764, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141161.1318874} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.7599983215332031, "x": 1.410041036521422, "y": -0.02742703300513938, "z": null, "yaw": 6.2550739217449465, "pitch": null, "roll": null}, "v": 1.662887328903725, "accelerator_pedal_position": 0.38779679511487236, "brake_pedal_position": 0.0, "acceleration": 0.8629336603364802, "steering_wheel_angle": -0.5847866271323764, "front_wheel_angle": -0.027064803965893197, "heading_rate": -0.017584653025633737, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141161.1518874} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.37205106327013654, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.30862447274823657, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.69248556113127, "gear": 1, "accelerator_pedal_position": 0.37205106327013654, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5450393739045407, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141161.1518874} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.7599983215332031, "x": 1.410041036521422, "y": -0.02742703300513938, "z": null, "yaw": 6.2550739217449465, "pitch": null, "roll": null}, "v": 1.662887328903725, "accelerator_pedal_position": 0.38779679511487236, "brake_pedal_position": 0.0, "acceleration": 0.8629336603364802, "steering_wheel_angle": -0.5847866271323764, "front_wheel_angle": -0.027064803965893197, "heading_rate": -0.017584653025633737, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141161.1718874} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.37205106327013654, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.30862447274823657, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.700106059067624, "gear": 1, "accelerator_pedal_position": 0.37205106327013654, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5450393739045407, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141161.1718874} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.7599983215332031, "x": 1.410041036521422, "y": -0.02742703300513938, "z": null, "yaw": 6.2550739217449465, "pitch": null, "roll": null}, "v": 1.662887328903725, "accelerator_pedal_position": 0.38779679511487236, "brake_pedal_position": 0.0, "acceleration": 0.8629336603364802, "steering_wheel_angle": -0.5847866271323764, "front_wheel_angle": -0.027064803965893197, "heading_rate": -0.017584653025633737, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141161.1918874} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.37205106327013654, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.30862447274823657, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.715327861989958, "gear": 1, "accelerator_pedal_position": 0.37205106327013654, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5450393739045407, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141161.1918874} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.7599983215332031, "x": 1.410041036521422, "y": -0.02742703300513938, "z": null, "yaw": 6.2550739217449465, "pitch": null, "roll": null}, "v": 1.662887328903725, "accelerator_pedal_position": 0.38779679511487236, "brake_pedal_position": 0.0, "acceleration": 0.8629336603364802, "steering_wheel_angle": -0.5847866271323764, "front_wheel_angle": -0.027064803965893197, "heading_rate": -0.017584653025633737, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141161.2118874} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.37205106327013654, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.30862447274823657, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7456945227366658, "gear": 1, "accelerator_pedal_position": 0.37205106327013654, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5450393739045407, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141161.2118874} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141161.2318873, "x": 5.597011007399473, "y": 4.967220276899468, "z": null, "yaw": -0.02920942149079223, "pitch": null, "roll": null}, "v": 1.7456945227366658, "accelerator_pedal_position": 0.37205106327013654, "brake_pedal_position": 0.0, "acceleration": 0.757559925634392, "steering_wheel_angle": -0.5450393739045407, "front_wheel_angle": -0.02521181256253744, "heading_rate": -0.017195879176870665, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141161.2418873} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3441249609478605, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3542740874937962, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7532701219930098, "gear": 1, "accelerator_pedal_position": 0.37205106327013654, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5450393739045407, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141161.2418873} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.8699982166290283, "x": 1.5970110073994732, "y": -0.03277972310053201, "z": null, "yaw": 6.253975885688794, "pitch": null, "roll": null}, "v": 1.7456945227366658, "accelerator_pedal_position": 0.37205106327013654, "brake_pedal_position": 0.0, "acceleration": 0.757559925634392, "steering_wheel_angle": -0.5450393739045407, "front_wheel_angle": -0.02521181256253744, "heading_rate": -0.017195879176870665, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141161.2618873} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3579536192986768, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3542740874937962, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7715908765047381, "gear": 1, "accelerator_pedal_position": 0.3579536192986768, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5052009357954803, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141161.2618873} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.8699982166290283, "x": 1.5970110073994732, "y": -0.03277972310053201, "z": null, "yaw": 6.253975885688794, "pitch": null, "roll": null}, "v": 1.7456945227366658, "accelerator_pedal_position": 0.37205106327013654, "brake_pedal_position": 0.0, "acceleration": 0.757559925634392, "steering_wheel_angle": -0.5450393739045407, "front_wheel_angle": -0.02521181256253744, "heading_rate": -0.017195879176870665, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141161.2818873} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3579536192986768, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3542740874937962, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7782633288492815, "gear": 1, "accelerator_pedal_position": 0.3579536192986768, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5052009357954803, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141161.2818873} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.8699982166290283, "x": 1.5970110073994732, "y": -0.03277972310053201, "z": null, "yaw": 6.253975885688794, "pitch": null, "roll": null}, "v": 1.7456945227366658, "accelerator_pedal_position": 0.37205106327013654, "brake_pedal_position": 0.0, "acceleration": 0.757559925634392, "steering_wheel_angle": -0.5450393739045407, "front_wheel_angle": -0.02521181256253744, "heading_rate": -0.017195879176870665, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141161.3018873} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3579536192986768, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3542740874937962, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7915911149746024, "gear": 1, "accelerator_pedal_position": 0.3579536192986768, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5052009357954803, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141161.3018873} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.8699982166290283, "x": 1.5970110073994732, "y": -0.03277972310053201, "z": null, "yaw": 6.253975885688794, "pitch": null, "roll": null}, "v": 1.7456945227366658, "accelerator_pedal_position": 0.37205106327013654, "brake_pedal_position": 0.0, "acceleration": 0.757559925634392, "steering_wheel_angle": -0.5450393739045407, "front_wheel_angle": -0.02521181256253744, "heading_rate": -0.017195879176870665, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141161.3218873} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3579536192986768, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3542740874937962, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8048960497105813, "gear": 1, "accelerator_pedal_position": 0.3579536192986768, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5052009357954803, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141161.3218873} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141161.3418872, "x": 5.792565117050322, "y": 4.961414212136448, "z": null, "yaw": -0.030227709008359395, "pitch": null, "roll": null}, "v": 1.8181781014594094, "accelerator_pedal_position": 0.3579536192986768, "brake_pedal_position": 0.0, "acceleration": 0.6632434994574941, "steering_wheel_angle": -0.5052009357954803, "front_wheel_angle": -0.02335656217603749, "heading_rate": -0.016591450693352564, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141161.3418872} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.33103792121389664, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.39325077155758253, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8181781014594094, "gear": 1, "accelerator_pedal_position": 0.3579536192986768, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5052009357954803, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141161.3418872} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.9799981117248535, "x": 1.792565117050322, "y": -0.0385857878635516, "z": null, "yaw": 6.252957598171227, "pitch": null, "roll": null}, "v": 1.8181781014594094, "accelerator_pedal_position": 0.3579536192986768, "brake_pedal_position": 0.0, "acceleration": 0.6632434994574941, "steering_wheel_angle": -0.5052009357954803, "front_wheel_angle": -0.02335656217603749, "heading_rate": -0.016591450693352564, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141161.3618872} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3443278718059619, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.39325077155758253, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.828074231565125, "gear": 1, "accelerator_pedal_position": 0.33103792121389664, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.46527811787034806, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141161.3618872} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.9799981117248535, "x": 1.792565117050322, "y": -0.0385857878635516, "z": null, "yaw": 6.252957598171227, "pitch": null, "roll": null}, "v": 1.8181781014594094, "accelerator_pedal_position": 0.3579536192986768, "brake_pedal_position": 0.0, "acceleration": 0.6632434994574941, "steering_wheel_angle": -0.5052009357954803, "front_wheel_angle": -0.02335656217603749, "heading_rate": -0.016591450693352564, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141161.3818872} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3443278718059619, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.39325077155758253, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8396137703361424, "gear": 1, "accelerator_pedal_position": 0.3443278718059619, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.46527811787034806, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141161.3818872} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.9799981117248535, "x": 1.792565117050322, "y": -0.0385857878635516, "z": null, "yaw": 6.252957598171227, "pitch": null, "roll": null}, "v": 1.8181781014594094, "accelerator_pedal_position": 0.3579536192986768, "brake_pedal_position": 0.0, "acceleration": 0.6632434994574941, "steering_wheel_angle": -0.5052009357954803, "front_wheel_angle": -0.02335656217603749, "heading_rate": -0.016591450693352564, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141161.4018872} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3443278718059619, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.39325077155758253, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8511333002535415, "gear": 1, "accelerator_pedal_position": 0.3443278718059619, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.46527811787034806, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141161.4018872} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.9799981117248535, "x": 1.792565117050322, "y": -0.0385857878635516, "z": null, "yaw": 6.252957598171227, "pitch": null, "roll": null}, "v": 1.8181781014594094, "accelerator_pedal_position": 0.3579536192986768, "brake_pedal_position": 0.0, "acceleration": 0.6632434994574941, "steering_wheel_angle": -0.5052009357954803, "front_wheel_angle": -0.02335656217603749, "heading_rate": -0.016591450693352564, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141161.4218872} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3443278718059619, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.39325077155758253, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8626328029546975, "gear": 1, "accelerator_pedal_position": 0.3443278718059619, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.46527811787034806, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141161.4218872} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.9799981117248535, "x": 1.792565117050322, "y": -0.0385857878635516, "z": null, "yaw": 6.252957598171227, "pitch": null, "roll": null}, "v": 1.8181781014594094, "accelerator_pedal_position": 0.3579536192986768, "brake_pedal_position": 0.0, "acceleration": 0.6632434994574941, "steering_wheel_angle": -0.5052009357954803, "front_wheel_angle": -0.02335656217603749, "heading_rate": -0.016591450693352564, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141161.4418871} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3443278718059619, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.39325077155758253, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8741122603854499, "gear": 1, "accelerator_pedal_position": 0.3443278718059619, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.46527811787034806, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141161.4418871} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141161.4518871, "x": 5.995483275887654, "y": 4.955191427966496, "z": null, "yaw": -0.03115891098549216, "pitch": null, "roll": null}, "v": 1.8798444665666771, "accelerator_pedal_position": 0.3443278718059619, "brake_pedal_position": 0.0, "acceleration": 0.5727188232741145, "steering_wheel_angle": -0.46527811787034806, "front_wheel_angle": -0.021499376465556812, "heading_rate": -0.015789731260235952, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141161.4618871} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3229243716355796, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4385224472468356, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8855716547994184, "gear": 1, "accelerator_pedal_position": 0.3443278718059619, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.46527811787034806, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141161.4618871} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.0899980068206787, "x": 1.9954832758876542, "y": -0.04480857203350386, "z": null, "yaw": 6.252026396194094, "pitch": null, "roll": null}, "v": 1.8798444665666771, "accelerator_pedal_position": 0.3443278718059619, "brake_pedal_position": 0.0, "acceleration": 0.5727188232741145, "steering_wheel_angle": -0.46527811787034806, "front_wheel_angle": -0.021499376465556812, "heading_rate": -0.015789731260235952, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141161.481887} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3335251868678205, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4385224472468356, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.894336705920289, "gear": 1, "accelerator_pedal_position": 0.3229243716355796, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4252638921995004, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141161.481887} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.0899980068206787, "x": 1.9954832758876542, "y": -0.04480857203350386, "z": null, "yaw": 6.252026396194094, "pitch": null, "roll": null}, "v": 1.8798444665666771, "accelerator_pedal_position": 0.3443278718059619, "brake_pedal_position": 0.0, "acceleration": 0.5727188232741145, "steering_wheel_angle": -0.46527811787034806, "front_wheel_angle": -0.021499376465556812, "heading_rate": -0.015789731260235952, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141161.501887} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3335251868678205, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4385224472468356, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9044108838420102, "gear": 1, "accelerator_pedal_position": 0.3335251868678205, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4252638921995004, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141161.501887} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.0899980068206787, "x": 1.9954832758876542, "y": -0.04480857203350386, "z": null, "yaw": 6.252026396194094, "pitch": null, "roll": null}, "v": 1.8798444665666771, "accelerator_pedal_position": 0.3443278718059619, "brake_pedal_position": 0.0, "acceleration": 0.5727188232741145, "steering_wheel_angle": -0.46527811787034806, "front_wheel_angle": -0.021499376465556812, "heading_rate": -0.015789731260235952, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141161.521887} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3335251868678205, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4385224472468356, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.914467331397698, "gear": 1, "accelerator_pedal_position": 0.3335251868678205, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4252638921995004, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141161.521887} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.0899980068206787, "x": 1.9954832758876542, "y": -0.04480857203350386, "z": null, "yaw": 6.252026396194094, "pitch": null, "roll": null}, "v": 1.8798444665666771, "accelerator_pedal_position": 0.3443278718059619, "brake_pedal_position": 0.0, "acceleration": 0.5727188232741145, "steering_wheel_angle": -0.46527811787034806, "front_wheel_angle": -0.021499376465556812, "heading_rate": -0.015789731260235952, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141161.541887} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3335251868678205, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4385224472468356, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.924506039357455, "gear": 1, "accelerator_pedal_position": 0.3335251868678205, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4252638921995004, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141161.541887} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141161.561887, "x": 6.204888139829938, "y": 4.948581019782474, "z": null, "yaw": -0.03201745601212215, "pitch": null, "roll": null}, "v": 1.9345269987215237, "accelerator_pedal_position": 0.3335251868678205, "brake_pedal_position": 0.0, "acceleration": 0.5003821208999768, "steering_wheel_angle": -0.4252638921995004, "front_wheel_angle": -0.019639935242646532, "heading_rate": -0.014843308920526514, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141161.561887} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.31209515353250566, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4674583653026352, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9345269987215237, "gear": 1, "accelerator_pedal_position": 0.3335251868678205, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4252638921995004, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141161.561887} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.199997901916504, "x": 2.2048881398299383, "y": -0.05141898021752578, "z": null, "yaw": 6.251167851167464, "pitch": null, "roll": null}, "v": 1.9345269987215237, "accelerator_pedal_position": 0.3335251868678205, "brake_pedal_position": 0.0, "acceleration": 0.5003821208999768, "steering_wheel_angle": -0.4252638921995004, "front_wheel_angle": -0.019639935242646532, "heading_rate": -0.014843308920526514, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141161.581887} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.32266716870751555, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4674583653026352, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9418526356145118, "gear": 1, "accelerator_pedal_position": 0.31209515353250566, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3851755519475717, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141161.581887} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.199997901916504, "x": 2.2048881398299383, "y": -0.05141898021752578, "z": null, "yaw": 6.251167851167464, "pitch": null, "roll": null}, "v": 1.9345269987215237, "accelerator_pedal_position": 0.3335251868678205, "brake_pedal_position": 0.0, "acceleration": 0.5003821208999768, "steering_wheel_angle": -0.4252638921995004, "front_wheel_angle": -0.019639935242646532, "heading_rate": -0.014843308920526514, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141161.601887} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.32266716870751555, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4674583653026352, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9504861822713513, "gear": 1, "accelerator_pedal_position": 0.32266716870751555, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3851755519475717, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141161.601887} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.199997901916504, "x": 2.2048881398299383, "y": -0.05141898021752578, "z": null, "yaw": 6.251167851167464, "pitch": null, "roll": null}, "v": 1.9345269987215237, "accelerator_pedal_position": 0.3335251868678205, "brake_pedal_position": 0.0, "acceleration": 0.5003821208999768, "steering_wheel_angle": -0.4252638921995004, "front_wheel_angle": -0.019639935242646532, "heading_rate": -0.014843308920526514, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141161.621887} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.32266716870751555, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4674583653026352, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9591043738267666, "gear": 1, "accelerator_pedal_position": 0.32266716870751555, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3851755519475717, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141161.621887} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.199997901916504, "x": 2.2048881398299383, "y": -0.05141898021752578, "z": null, "yaw": 6.251167851167464, "pitch": null, "roll": null}, "v": 1.9345269987215237, "accelerator_pedal_position": 0.3335251868678205, "brake_pedal_position": 0.0, "acceleration": 0.5003821208999768, "steering_wheel_angle": -0.4252638921995004, "front_wheel_angle": -0.019639935242646532, "heading_rate": -0.014843308920526514, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141161.641887} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.32266716870751555, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4674583653026352, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9677072078943538, "gear": 1, "accelerator_pedal_position": 0.32266716870751555, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3851755519475717, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141161.641887} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.199997901916504, "x": 2.2048881398299383, "y": -0.05141898021752578, "z": null, "yaw": 6.251167851167464, "pitch": null, "roll": null}, "v": 1.9345269987215237, "accelerator_pedal_position": 0.3335251868678205, "brake_pedal_position": 0.0, "acceleration": 0.5003821208999768, "steering_wheel_angle": -0.4252638921995004, "front_wheel_angle": -0.019639935242646532, "heading_rate": -0.014843308920526514, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141161.661887} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.32266716870751555, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4674583653026352, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9762946822506382, "gear": 1, "accelerator_pedal_position": 0.32266716870751555, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3851755519475717, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141161.661887} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141161.671887, "x": 6.419820886674358, "y": 4.941620600772406, "z": null, "yaw": -0.03278875162459146, "pitch": null, "roll": null}, "v": 1.9805826588866233, "accelerator_pedal_position": 0.32266716870751555, "brake_pedal_position": 0.0, "acceleration": 0.4284135947908168, "steering_wheel_angle": -0.3851755519475717, "front_wheel_angle": -0.017779048070549086, "heading_rate": -0.013756478503294095, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141161.681887} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3044224070938263, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.49738555602453266, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9848667948345315, "gear": 1, "accelerator_pedal_position": 0.32266716870751555, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3851755519475717, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141161.681887} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.309997797012329, "x": 2.4198208866743576, "y": -0.05837939922759361, "z": null, "yaw": 6.250396555554995, "pitch": null, "roll": null}, "v": 1.9805826588866233, "accelerator_pedal_position": 0.32266716870751555, "brake_pedal_position": 0.0, "acceleration": 0.4284135947908168, "steering_wheel_angle": -0.3851755519475717, "front_wheel_angle": -0.017779048070549086, "heading_rate": -0.013756478503294095, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141161.701887} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.31342322474767553, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.49738555602453266, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9911439722077808, "gear": 1, "accelerator_pedal_position": 0.3044224070938263, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.34501185132993617, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141161.701887} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.309997797012329, "x": 2.4198208866743576, "y": -0.05837939922759361, "z": null, "yaw": 6.250396555554995, "pitch": null, "roll": null}, "v": 1.9805826588866233, "accelerator_pedal_position": 0.32266716870751555, "brake_pedal_position": 0.0, "acceleration": 0.4284135947908168, "steering_wheel_angle": -0.3851755519475717, "front_wheel_angle": -0.017779048070549086, "heading_rate": -0.013756478503294095, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141161.7218869} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.31342322474767553, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.49738555602453266, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.998534478423982, "gear": 1, "accelerator_pedal_position": 0.31342322474767553, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.34501185132993617, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141161.7218869} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.309997797012329, "x": 2.4198208866743576, "y": -0.05837939922759361, "z": null, "yaw": 6.250396555554995, "pitch": null, "roll": null}, "v": 1.9805826588866233, "accelerator_pedal_position": 0.32266716870751555, "brake_pedal_position": 0.0, "acceleration": 0.4284135947908168, "steering_wheel_angle": -0.3851755519475717, "front_wheel_angle": -0.017779048070549086, "heading_rate": -0.013756478503294095, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141161.7418869} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.31342322474767553, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.49738555602453266, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0059116975032807, "gear": 1, "accelerator_pedal_position": 0.31342322474767553, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.34501185132993617, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141161.7418869} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.309997797012329, "x": 2.4198208866743576, "y": -0.05837939922759361, "z": null, "yaw": 6.250396555554995, "pitch": null, "roll": null}, "v": 1.9805826588866233, "accelerator_pedal_position": 0.32266716870751555, "brake_pedal_position": 0.0, "acceleration": 0.4284135947908168, "steering_wheel_angle": -0.3851755519475717, "front_wheel_angle": -0.017779048070549086, "heading_rate": -0.013756478503294095, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141161.7618868} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.31342322474767553, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.49738555602453266, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0132756315746194, "gear": 1, "accelerator_pedal_position": 0.31342322474767553, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.34501185132993617, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141161.7618868} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141161.7818868, "x": 6.639559712048663, "y": 4.934341649430899, "z": null, "yaw": -0.03348728247672171, "pitch": null, "roll": null}, "v": 2.0206262828806127, "accelerator_pedal_position": 0.31342322474767553, "brake_pedal_position": 0.0, "acceleration": 0.36703453477826214, "steering_wheel_angle": -0.34501185132993617, "front_wheel_angle": -0.015916661860412046, "heading_rate": -0.012564195902152851, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141161.7818868} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2945215052761352, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5076388948773004, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0206262828806127, "gear": 1, "accelerator_pedal_position": 0.31342322474767553, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.34501185132993617, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141161.7818868} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.4199976921081543, "x": 2.639559712048663, "y": -0.06565835056910085, "z": null, "yaw": 6.249698024702864, "pitch": null, "roll": null}, "v": 2.0206262828806127, "accelerator_pedal_position": 0.31342322474767553, "brake_pedal_position": 0.0, "acceleration": 0.36703453477826214, "steering_wheel_angle": -0.34501185132993617, "front_wheel_angle": -0.015916661860412046, "heading_rate": -0.012564195902152851, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141161.8018868} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.30379695043996296, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5076388948773004, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.025602007665923, "gear": 1, "accelerator_pedal_position": 0.2945215052761352, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.34501185132993617, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141161.8018868} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.4199976921081543, "x": 2.639559712048663, "y": -0.06565835056910085, "z": null, "yaw": 6.249698024702864, "pitch": null, "roll": null}, "v": 2.0206262828806127, "accelerator_pedal_position": 0.31342322474767553, "brake_pedal_position": 0.0, "acceleration": 0.36703453477826214, "steering_wheel_angle": -0.34501185132993617, "front_wheel_angle": -0.015916661860412046, "heading_rate": -0.012564195902152851, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141161.8218868} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.30379695043996296, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5076388948773004, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0317276373538378, "gear": 1, "accelerator_pedal_position": 0.30379695043996296, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.34501185132993617, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141161.8218868} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.4199976921081543, "x": 2.639559712048663, "y": -0.06565835056910085, "z": null, "yaw": 6.249698024702864, "pitch": null, "roll": null}, "v": 2.0206262828806127, "accelerator_pedal_position": 0.31342322474767553, "brake_pedal_position": 0.0, "acceleration": 0.36703453477826214, "steering_wheel_angle": -0.34501185132993617, "front_wheel_angle": -0.015916661860412046, "heading_rate": -0.012564195902152851, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141161.8418868} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.30379695043996296, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5076388948773004, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.037842171950215, "gear": 1, "accelerator_pedal_position": 0.30379695043996296, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.34501185132993617, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141161.8418868} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.4199976921081543, "x": 2.639559712048663, "y": -0.06565835056910085, "z": null, "yaw": 6.249698024702864, "pitch": null, "roll": null}, "v": 2.0206262828806127, "accelerator_pedal_position": 0.31342322474767553, "brake_pedal_position": 0.0, "acceleration": 0.36703453477826214, "steering_wheel_angle": -0.34501185132993617, "front_wheel_angle": -0.015916661860412046, "heading_rate": -0.012564195902152851, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141161.8618867} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.30379695043996296, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5076388948773004, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0439456166028878, "gear": 1, "accelerator_pedal_position": 0.30379695043996296, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.34501185132993617, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141161.8618867} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.4199976921081543, "x": 2.639559712048663, "y": -0.06565835056910085, "z": null, "yaw": 6.249698024702864, "pitch": null, "roll": null}, "v": 2.0206262828806127, "accelerator_pedal_position": 0.31342322474767553, "brake_pedal_position": 0.0, "acceleration": 0.36703453477826214, "steering_wheel_angle": -0.34501185132993617, "front_wheel_angle": -0.015916661860412046, "heading_rate": -0.012564195902152851, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141161.8818867} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.30379695043996296, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5076388948773004, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.050037976531659, "gear": 1, "accelerator_pedal_position": 0.30379695043996296, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.34501185132993617, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141161.8818867} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141161.8918867, "x": 6.863274242782845, "y": 4.926777420656552, "z": null, "yaw": -0.03417125930160326, "pitch": null, "roll": null}, "v": 2.0530800013753687, "accelerator_pedal_position": 0.30379695043996296, "brake_pedal_position": 0.0, "acceleration": 0.3039255652605252, "steering_wheel_angle": -0.34501185132993617, "front_wheel_angle": -0.015916661860412046, "heading_rate": -0.012765992186985957, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141161.9018867} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28978969332022186, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5337612672123868, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.056119257027974, "gear": 1, "accelerator_pedal_position": 0.30379695043996296, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.34501185132993617, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141161.9018867} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.5299975872039795, "x": 2.863274242782845, "y": -0.07322257934344822, "z": null, "yaw": 6.249014047877983, "pitch": null, "roll": null}, "v": 2.0530800013753687, "accelerator_pedal_position": 0.30379695043996296, "brake_pedal_position": 0.0, "acceleration": 0.3039255652605252, "steering_wheel_angle": -0.34501185132993617, "front_wheel_angle": -0.015916661860412046, "heading_rate": -0.012765992186985957, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141161.9218867} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2966841814952087, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5337612672123868, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0604393545038153, "gear": 1, "accelerator_pedal_position": 0.28978969332022186, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3047656037392084, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141161.9218867} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.5299975872039795, "x": 2.863274242782845, "y": -0.07322257934344822, "z": null, "yaw": 6.249014047877983, "pitch": null, "roll": null}, "v": 2.0530800013753687, "accelerator_pedal_position": 0.30379695043996296, "brake_pedal_position": 0.0, "acceleration": 0.3039255652605252, "steering_wheel_angle": -0.34501185132993617, "front_wheel_angle": -0.015916661860412046, "heading_rate": -0.012765992186985957, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141161.9418867} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2966841814952087, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5337612672123868, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.065612994615733, "gear": 1, "accelerator_pedal_position": 0.2966841814952087, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3047656037392084, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141161.9418867} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.5299975872039795, "x": 2.863274242782845, "y": -0.07322257934344822, "z": null, "yaw": 6.249014047877983, "pitch": null, "roll": null}, "v": 2.0530800013753687, "accelerator_pedal_position": 0.30379695043996296, "brake_pedal_position": 0.0, "acceleration": 0.3039255652605252, "steering_wheel_angle": -0.34501185132993617, "front_wheel_angle": -0.015916661860412046, "heading_rate": -0.012765992186985957, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141161.9618866} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2966841814952087, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5337612672123868, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0733557543097136, "gear": 1, "accelerator_pedal_position": 0.2966841814952087, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3047656037392084, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141161.9618866} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.5299975872039795, "x": 2.863274242782845, "y": -0.07322257934344822, "z": null, "yaw": 6.249014047877983, "pitch": null, "roll": null}, "v": 2.0530800013753687, "accelerator_pedal_position": 0.30379695043996296, "brake_pedal_position": 0.0, "acceleration": 0.3039255652605252, "steering_wheel_angle": -0.34501185132993617, "front_wheel_angle": -0.015916661860412046, "heading_rate": -0.012765992186985957, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141161.9818866} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2966841814952087, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5337612672123868, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0759319573676165, "gear": 1, "accelerator_pedal_position": 0.2966841814952087, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3047656037392084, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141161.9818866} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141162.0018866, "x": 7.0903726039687625, "y": 4.918948738940112, "z": null, "yaw": -0.034789682646275966, "pitch": null, "roll": null}, "v": 2.0810772931875103, "accelerator_pedal_position": 0.2966841814952087, "brake_pedal_position": 0.0, "acceleration": 0.25691344268347227, "steering_wheel_angle": -0.3047656037392084, "front_wheel_angle": -0.014052448722147618, "heading_rate": -0.011424280104317527, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141162.0018866} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2869288710625535, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5768219075826718, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0810772931875103, "gear": 1, "accelerator_pedal_position": 0.2966841814952087, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3047656037392084, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141162.0018866} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.6399974822998047, "x": 3.0903726039687625, "y": -0.08105126105988791, "z": null, "yaw": 6.24839562453331, "pitch": null, "roll": null}, "v": 2.0810772931875103, "accelerator_pedal_position": 0.2966841814952087, "brake_pedal_position": 0.0, "acceleration": 0.25691344268347227, "steering_wheel_angle": -0.3047656037392084, "front_wheel_angle": -0.014052448722147618, "heading_rate": -0.011424280104317527, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141162.0218866} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2917691025758079, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5768219075826718, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.084994352595374, "gear": 1, "accelerator_pedal_position": 0.2869288710625535, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.264429271670414, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141162.0218866} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.6399974822998047, "x": 3.0903726039687625, "y": -0.08105126105988791, "z": null, "yaw": 6.24839562453331, "pitch": null, "roll": null}, "v": 2.0810772931875103, "accelerator_pedal_position": 0.2966841814952087, "brake_pedal_position": 0.0, "acceleration": 0.25691344268347227, "steering_wheel_angle": -0.3047656037392084, "front_wheel_angle": -0.014052448722147618, "heading_rate": -0.011424280104317527, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141162.0418866} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2917691025758079, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5768219075826718, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0895089843588117, "gear": 1, "accelerator_pedal_position": 0.2917691025758079, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.264429271670414, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141162.0418866} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.6399974822998047, "x": 3.0903726039687625, "y": -0.08105126105988791, "z": null, "yaw": 6.24839562453331, "pitch": null, "roll": null}, "v": 2.0810772931875103, "accelerator_pedal_position": 0.2966841814952087, "brake_pedal_position": 0.0, "acceleration": 0.25691344268347227, "steering_wheel_angle": -0.3047656037392084, "front_wheel_angle": -0.014052448722147618, "heading_rate": -0.011424280104317527, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141162.0618865} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2917691025758079, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5768219075826718, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.094015333986061, "gear": 1, "accelerator_pedal_position": 0.2917691025758079, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.264429271670414, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141162.0618865} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.6399974822998047, "x": 3.0903726039687625, "y": -0.08105126105988791, "z": null, "yaw": 6.24839562453331, "pitch": null, "roll": null}, "v": 2.0810772931875103, "accelerator_pedal_position": 0.2966841814952087, "brake_pedal_position": 0.0, "acceleration": 0.25691344268347227, "steering_wheel_angle": -0.3047656037392084, "front_wheel_angle": -0.014052448722147618, "heading_rate": -0.011424280104317527, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141162.0818865} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2917691025758079, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5768219075826718, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.098513408551636, "gear": 1, "accelerator_pedal_position": 0.2917691025758079, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.264429271670414, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141162.0818865} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.6399974822998047, "x": 3.0903726039687625, "y": -0.08105126105988791, "z": null, "yaw": 6.24839562453331, "pitch": null, "roll": null}, "v": 2.0810772931875103, "accelerator_pedal_position": 0.2966841814952087, "brake_pedal_position": 0.0, "acceleration": 0.25691344268347227, "steering_wheel_angle": -0.3047656037392084, "front_wheel_angle": -0.014052448722147618, "heading_rate": -0.011424280104317527, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141162.1018865} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2917691025758079, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5768219075826718, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1030032151617757, "gear": 1, "accelerator_pedal_position": 0.2917691025758079, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.264429271670414, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141162.1018865} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141162.1118865, "x": 7.320333297200856, "y": 4.910888804916718, "z": null, "yaw": -0.03532062040302587, "pitch": null, "roll": null}, "v": 2.1052450202128847, "accelerator_pedal_position": 0.2917691025758079, "brake_pedal_position": 0.0, "acceleration": 0.22397407413684361, "steering_wheel_angle": -0.264429271670414, "front_wheel_angle": -0.01218606594783578, "heading_rate": -0.010021845560643715, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141162.1218865} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28122776656642956, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6094313104875684, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1074847609542533, "gear": 1, "accelerator_pedal_position": 0.2917691025758079, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.264429271670414, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141162.1218865} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.74999737739563, "x": 3.3203332972008557, "y": -0.08911119508328191, "z": null, "yaw": 6.24786468677656, "pitch": null, "roll": null}, "v": 2.1052450202128847, "accelerator_pedal_position": 0.2917691025758079, "brake_pedal_position": 0.0, "acceleration": 0.22397407413684361, "steering_wheel_angle": -0.264429271670414, "front_wheel_angle": -0.01218606594783578, "heading_rate": -0.010021845560643715, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141162.1418865} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2864166053763089, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6094313104875684, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1106409934615216, "gear": 1, "accelerator_pedal_position": 0.28122776656642956, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.22401399395543317, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141162.1418865} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.74999737739563, "x": 3.3203332972008557, "y": -0.08911119508328191, "z": null, "yaw": 6.24786468677656, "pitch": null, "roll": null}, "v": 2.1052450202128847, "accelerator_pedal_position": 0.2917691025758079, "brake_pedal_position": 0.0, "acceleration": 0.22397407413684361, "steering_wheel_angle": -0.264429271670414, "front_wheel_angle": -0.01218606594783578, "heading_rate": -0.010021845560643715, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141162.1618865} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2864166053763089, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6094313104875684, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.114439714436416, "gear": 1, "accelerator_pedal_position": 0.2864166053763089, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.22401399395543317, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141162.1618865} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.74999737739563, "x": 3.3203332972008557, "y": -0.08911119508328191, "z": null, "yaw": 6.24786468677656, "pitch": null, "roll": null}, "v": 2.1052450202128847, "accelerator_pedal_position": 0.2917691025758079, "brake_pedal_position": 0.0, "acceleration": 0.22397407413684361, "steering_wheel_angle": -0.264429271670414, "front_wheel_angle": -0.01218606594783578, "heading_rate": -0.010021845560643715, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141162.1818864} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2864166053763089, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6094313104875684, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1182314285015544, "gear": 1, "accelerator_pedal_position": 0.2864166053763089, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.22401399395543317, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141162.1818864} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.74999737739563, "x": 3.3203332972008557, "y": -0.08911119508328191, "z": null, "yaw": 6.24786468677656, "pitch": null, "roll": null}, "v": 2.1052450202128847, "accelerator_pedal_position": 0.2917691025758079, "brake_pedal_position": 0.0, "acceleration": 0.22397407413684361, "steering_wheel_angle": -0.264429271670414, "front_wheel_angle": -0.01218606594783578, "heading_rate": -0.010021845560643715, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141162.2018864} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2864166053763089, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6094313104875684, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1257938646266292, "gear": 1, "accelerator_pedal_position": 0.2864166053763089, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.22401399395543317, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141162.2018864} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141162.2218864, "x": 7.552786752087844, "y": 4.902625065338767, "z": null, "yaw": -0.03577858505019693, "pitch": null, "roll": null}, "v": 2.1257938646266292, "accelerator_pedal_position": 0.2864166053763089, "brake_pedal_position": 0.0, "acceleration": 0.18862409482175702, "steering_wheel_angle": -0.22401399395543317, "front_wheel_angle": -0.010318035079410023, "heading_rate": -0.008568278936942928, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141162.2218864} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2735540555318939, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5999385081772602, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1257938646266292, "gear": 1, "accelerator_pedal_position": 0.2864166053763089, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.22401399395543317, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141162.2218864} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.859997272491455, "x": 3.552786752087844, "y": -0.09737493466123315, "z": null, "yaw": 6.247406722129389, "pitch": null, "roll": null}, "v": 2.1257938646266292, "accelerator_pedal_position": 0.2864166053763089, "brake_pedal_position": 0.0, "acceleration": 0.18862409482175702, "steering_wheel_angle": -0.22401399395543317, "front_wheel_angle": -0.010318035079410023, "heading_rate": -0.008568278936942928, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141162.2518864} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2798236059663463, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5999385081772602, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.133056177136706, "gear": 1, "accelerator_pedal_position": 0.2798236059663463, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.22401399395543317, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141162.2518864} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.859997272491455, "x": 3.552786752087844, "y": -0.09737493466123315, "z": null, "yaw": 6.247406722129389, "pitch": null, "roll": null}, "v": 2.1257938646266292, "accelerator_pedal_position": 0.2864166053763089, "brake_pedal_position": 0.0, "acceleration": 0.18862409482175702, "steering_wheel_angle": -0.22401399395543317, "front_wheel_angle": -0.010318035079410023, "heading_rate": -0.008568278936942928, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141162.2818863} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2798236059663463, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5999385081772602, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.134523631555552, "gear": 1, "accelerator_pedal_position": 0.2798236059663463, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.22401399395543317, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141162.2818863} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.859997272491455, "x": 3.552786752087844, "y": -0.09737493466123315, "z": null, "yaw": 6.247406722129389, "pitch": null, "roll": null}, "v": 2.1257938646266292, "accelerator_pedal_position": 0.2864166053763089, "brake_pedal_position": 0.0, "acceleration": 0.18862409482175702, "steering_wheel_angle": -0.22401399395543317, "front_wheel_angle": -0.010318035079410023, "heading_rate": -0.008568278936942928, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141162.3118863} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2798236059663463, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5999385081772602, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1389178382830787, "gear": 1, "accelerator_pedal_position": 0.2798236059663463, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.22401399395543317, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141162.3118863} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141162.3318863, "x": 7.787148086005088, "y": 4.8941890177846235, "z": null, "yaw": -0.036221953854081064, "pitch": null, "roll": null}, "v": 2.140379857784941, "accelerator_pedal_position": 0.2798236059663463, "brake_pedal_position": 0.0, "acceleration": 0.1460662850443024, "steering_wheel_angle": -0.22401399395543317, "front_wheel_angle": -0.010318035079410023, "heading_rate": -0.00862706961276168, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141162.3318863} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27405017217868044, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6401226528378362, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.140379857784941, "gear": 1, "accelerator_pedal_position": 0.2798236059663463, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.22401399395543317, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141162.3318863} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.9699971675872803, "x": 3.7871480860050877, "y": -0.10581098221537655, "z": null, "yaw": 6.246963353325505, "pitch": null, "roll": null}, "v": 2.140379857784941, "accelerator_pedal_position": 0.2798236059663463, "brake_pedal_position": 0.0, "acceleration": 0.1460662850443024, "steering_wheel_angle": -0.22401399395543317, "front_wheel_angle": -0.010318035079410023, "heading_rate": -0.00862706961276168, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141162.3518863} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.276902404052112, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6401226528378362, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1425784834218873, "gear": 1, "accelerator_pedal_position": 0.27405017217868044, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.22401399395543317, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141162.3518863} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.9699971675872803, "x": 3.7871480860050877, "y": -0.10581098221537655, "z": null, "yaw": 6.246963353325505, "pitch": null, "roll": null}, "v": 2.140379857784941, "accelerator_pedal_position": 0.2798236059663463, "brake_pedal_position": 0.0, "acceleration": 0.1460662850443024, "steering_wheel_angle": -0.22401399395543317, "front_wheel_angle": -0.010318035079410023, "heading_rate": -0.00862706961276168, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141162.3718863} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.276902404052112, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6401226528378362, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.145129391941183, "gear": 1, "accelerator_pedal_position": 0.276902404052112, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.22401399395543317, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141162.3718863} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.9699971675872803, "x": 3.7871480860050877, "y": -0.10581098221537655, "z": null, "yaw": 6.246963353325505, "pitch": null, "roll": null}, "v": 2.140379857784941, "accelerator_pedal_position": 0.2798236059663463, "brake_pedal_position": 0.0, "acceleration": 0.1460662850443024, "steering_wheel_angle": -0.22401399395543317, "front_wheel_angle": -0.010318035079410023, "heading_rate": -0.00862706961276168, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141162.3918862} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.276902404052112, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6401226528378362, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.147675563592495, "gear": 1, "accelerator_pedal_position": 0.276902404052112, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.22401399395543317, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141162.3918862} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.9699971675872803, "x": 3.7871480860050877, "y": -0.10581098221537655, "z": null, "yaw": 6.246963353325505, "pitch": null, "roll": null}, "v": 2.140379857784941, "accelerator_pedal_position": 0.2798236059663463, "brake_pedal_position": 0.0, "acceleration": 0.1460662850443024, "steering_wheel_angle": -0.22401399395543317, "front_wheel_angle": -0.010318035079410023, "heading_rate": -0.00862706961276168, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141162.4118862} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.276902404052112, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6401226528378362, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1502170045798814, "gear": 1, "accelerator_pedal_position": 0.276902404052112, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.22401399395543317, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141162.4118862} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.9699971675872803, "x": 3.7871480860050877, "y": -0.10581098221537655, "z": null, "yaw": 6.246963353325505, "pitch": null, "roll": null}, "v": 2.140379857784941, "accelerator_pedal_position": 0.2798236059663463, "brake_pedal_position": 0.0, "acceleration": 0.1460662850443024, "steering_wheel_angle": -0.22401399395543317, "front_wheel_angle": -0.010318035079410023, "heading_rate": -0.00862706961276168, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141162.4318862} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.276902404052112, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6401226528378362, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1527537211103183, "gear": 1, "accelerator_pedal_position": 0.276902404052112, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.22401399395543317, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141162.4318862} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141162.4418862, "x": 8.023100521273037, "y": 4.885590949714348, "z": null, "yaw": -0.036665322657965196, "pitch": null, "roll": null}, "v": 2.1540203096446446, "accelerator_pedal_position": 0.276902404052112, "brake_pedal_position": 0.0, "acceleration": 0.12654097489985144, "steering_wheel_angle": -0.22401399395543317, "front_wheel_angle": -0.010318035079410023, "heading_rate": -0.008682049165720549, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141162.4518862} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2715068521491142, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6830151051010864, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.155285719393643, "gear": 1, "accelerator_pedal_position": 0.276902404052112, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.22401399395543317, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141162.4518862} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.0799970626831055, "x": 4.023100521273037, "y": -0.11440905028565229, "z": null, "yaw": 6.246519984521621, "pitch": null, "roll": null}, "v": 2.1540203096446446, "accelerator_pedal_position": 0.276902404052112, "brake_pedal_position": 0.0, "acceleration": 0.12654097489985144, "steering_wheel_angle": -0.22401399395543317, "front_wheel_angle": -0.010318035079410023, "heading_rate": -0.008682049165720549, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141162.4718862} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2741727580579343, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6830151051010864, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1571388757014627, "gear": 1, "accelerator_pedal_position": 0.2715068521491142, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.14289134884433966, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141162.4718862} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.0799970626831055, "x": 4.023100521273037, "y": -0.11440905028565229, "z": null, "yaw": 6.246519984521621, "pitch": null, "roll": null}, "v": 2.1540203096446446, "accelerator_pedal_position": 0.276902404052112, "brake_pedal_position": 0.0, "acceleration": 0.12654097489985144, "steering_wheel_angle": -0.22401399395543317, "front_wheel_angle": -0.010318035079410023, "heading_rate": -0.008682049165720549, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141162.4918861} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2741727580579343, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6830151051010864, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.159321664809064, "gear": 1, "accelerator_pedal_position": 0.2741727580579343, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.14289134884433966, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141162.4918861} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.0799970626831055, "x": 4.023100521273037, "y": -0.11440905028565229, "z": null, "yaw": 6.246519984521621, "pitch": null, "roll": null}, "v": 2.1540203096446446, "accelerator_pedal_position": 0.276902404052112, "brake_pedal_position": 0.0, "acceleration": 0.12654097489985144, "steering_wheel_angle": -0.22401399395543317, "front_wheel_angle": -0.010318035079410023, "heading_rate": -0.008682049165720549, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141162.5118861} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2741727580579343, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6830151051010864, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1615003881617394, "gear": 1, "accelerator_pedal_position": 0.2741727580579343, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.14289134884433966, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141162.5118861} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.0799970626831055, "x": 4.023100521273037, "y": -0.11440905028565229, "z": null, "yaw": 6.246519984521621, "pitch": null, "roll": null}, "v": 2.1540203096446446, "accelerator_pedal_position": 0.276902404052112, "brake_pedal_position": 0.0, "acceleration": 0.12654097489985144, "steering_wheel_angle": -0.22401399395543317, "front_wheel_angle": -0.010318035079410023, "heading_rate": -0.008682049165720549, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141162.531886} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2741727580579343, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6830151051010864, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.163675051434686, "gear": 1, "accelerator_pedal_position": 0.2741727580579343, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.14289134884433966, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141162.531886} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141162.551886, "x": 8.2604709488189, "y": 4.876845960959644, "z": null, "yaw": -0.03698438537726733, "pitch": null, "roll": null}, "v": 2.1658456603031317, "accelerator_pedal_position": 0.2741727580579343, "brake_pedal_position": 0.0, "acceleration": 0.10837858060439354, "steering_wheel_angle": -0.14289134884433966, "front_wheel_angle": -0.006574503225742279, "heading_rate": -0.005562329861249382, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141162.551886} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2687817057307802, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7207028492197535, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1658456603031317, "gear": 1, "accelerator_pedal_position": 0.2741727580579343, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.14289134884433966, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141162.551886} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.1899969577789307, "x": 4.2604709488189005, "y": -0.12315403904035627, "z": null, "yaw": 6.246200921802319, "pitch": null, "roll": null}, "v": 2.1658456603031317, "accelerator_pedal_position": 0.2741727580579343, "brake_pedal_position": 0.0, "acceleration": 0.10837858060439354, "steering_wheel_angle": -0.14289134884433966, "front_wheel_angle": -0.006574503225742279, "heading_rate": -0.005562329861249382, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141162.571886} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2714328448743065, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7207028492197535, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1673386533858143, "gear": 1, "accelerator_pedal_position": 0.2687817057307802, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.14289134884433966, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141162.571886} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.1899969577789307, "x": 4.2604709488189005, "y": -0.12315403904035627, "z": null, "yaw": 6.246200921802319, "pitch": null, "roll": null}, "v": 2.1658456603031317, "accelerator_pedal_position": 0.2741727580579343, "brake_pedal_position": 0.0, "acceleration": 0.10837858060439354, "steering_wheel_angle": -0.14289134884433966, "front_wheel_angle": -0.006574503225742279, "heading_rate": -0.005562329861249382, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141162.591886} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2714328448743065, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7207028492197535, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.169160098363942, "gear": 1, "accelerator_pedal_position": 0.2714328448743065, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.14289134884433966, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141162.591886} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.1899969577789307, "x": 4.2604709488189005, "y": -0.12315403904035627, "z": null, "yaw": 6.246200921802319, "pitch": null, "roll": null}, "v": 2.1658456603031317, "accelerator_pedal_position": 0.2741727580579343, "brake_pedal_position": 0.0, "acceleration": 0.10837858060439354, "steering_wheel_angle": -0.14289134884433966, "front_wheel_angle": -0.006574503225742279, "heading_rate": -0.005562329861249382, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141162.611886} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2714328448743065, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7207028492197535, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1709781434147724, "gear": 1, "accelerator_pedal_position": 0.2714328448743065, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.14289134884433966, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141162.611886} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.1899969577789307, "x": 4.2604709488189005, "y": -0.12315403904035627, "z": null, "yaw": 6.246200921802319, "pitch": null, "roll": null}, "v": 2.1658456603031317, "accelerator_pedal_position": 0.2741727580579343, "brake_pedal_position": 0.0, "acceleration": 0.10837858060439354, "steering_wheel_angle": -0.14289134884433966, "front_wheel_angle": -0.006574503225742279, "heading_rate": -0.005562329861249382, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141162.631886} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2714328448743065, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7207028492197535, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1727927935631457, "gear": 1, "accelerator_pedal_position": 0.2714328448743065, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.14289134884433966, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141162.631886} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.1899969577789307, "x": 4.2604709488189005, "y": -0.12315403904035627, "z": null, "yaw": 6.246200921802319, "pitch": null, "roll": null}, "v": 2.1658456603031317, "accelerator_pedal_position": 0.2741727580579343, "brake_pedal_position": 0.0, "acceleration": 0.10837858060439354, "steering_wheel_angle": -0.14289134884433966, "front_wheel_angle": -0.006574503225742279, "heading_rate": -0.005562329861249382, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141162.651886} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2714328448743065, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7207028492197535, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1755084143305545, "gear": 1, "accelerator_pedal_position": 0.2714328448743065, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.14289134884433966, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141162.651886} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141162.661886, "x": 8.499018729674752, "y": 4.86798869394324, "z": null, "yaw": -0.03726688763306143, "pitch": null, "roll": null}, "v": 2.1755084143305545, "accelerator_pedal_position": 0.2714328448743065, "brake_pedal_position": 0.0, "acceleration": 0.09035149113965751, "steering_wheel_angle": -0.14289134884433966, "front_wheel_angle": -0.006574503225742279, "heading_rate": -0.005587145768612384, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141162.671886} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2654121478023233, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7425590298118205, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1764119292419513, "gear": 1, "accelerator_pedal_position": 0.2714328448743065, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.14289134884433966, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141162.671886} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.299996852874756, "x": 4.499018729674752, "y": -0.13201130605675981, "z": null, "yaw": 6.245918419546525, "pitch": null, "roll": null}, "v": 2.1755084143305545, "accelerator_pedal_position": 0.2714328448743065, "brake_pedal_position": 0.0, "acceleration": 0.09035149113965751, "steering_wheel_angle": -0.14289134884433966, "front_wheel_angle": -0.006574503225742279, "heading_rate": -0.005587145768612384, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141162.691886} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2683479198415903, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7425590298118205, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1774641896725826, "gear": 1, "accelerator_pedal_position": 0.2654121478023233, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.10219875315003235, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141162.691886} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.299996852874756, "x": 4.499018729674752, "y": -0.13201130605675981, "z": null, "yaw": 6.245918419546525, "pitch": null, "roll": null}, "v": 2.1755084143305545, "accelerator_pedal_position": 0.2714328448743065, "brake_pedal_position": 0.0, "acceleration": 0.09035149113965751, "steering_wheel_angle": -0.14289134884433966, "front_wheel_angle": -0.006574503225742279, "heading_rate": -0.005587145768612384, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141162.711886} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2683479198415903, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7425590298118205, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.181001952196107, "gear": 1, "accelerator_pedal_position": 0.2683479198415903, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.10219875315003235, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141162.711886} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.299996852874756, "x": 4.499018729674752, "y": -0.13201130605675981, "z": null, "yaw": 6.245918419546525, "pitch": null, "roll": null}, "v": 2.1755084143305545, "accelerator_pedal_position": 0.2714328448743065, "brake_pedal_position": 0.0, "acceleration": 0.09035149113965751, "steering_wheel_angle": -0.14289134884433966, "front_wheel_angle": -0.006574503225742279, "heading_rate": -0.005587145768612384, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141162.741886} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2683479198415903, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7425590298118205, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.18170751925856, "gear": 1, "accelerator_pedal_position": 0.2683479198415903, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.10219875315003235, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141162.741886} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.299996852874756, "x": 4.499018729674752, "y": -0.13201130605675981, "z": null, "yaw": 6.245918419546525, "pitch": null, "roll": null}, "v": 2.1755084143305545, "accelerator_pedal_position": 0.2714328448743065, "brake_pedal_position": 0.0, "acceleration": 0.09035149113965751, "steering_wheel_angle": -0.14289134884433966, "front_wheel_angle": -0.006574503225742279, "heading_rate": -0.005587145768612384, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141162.761886} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2683479198415903, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7425590298118205, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1824124257190713, "gear": 1, "accelerator_pedal_position": 0.2683479198415903, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.10219875315003235, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141162.761886} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141162.7718859, "x": 8.738535211435488, "y": 4.8590334607772325, "z": null, "yaw": -0.03748347666924879, "pitch": null, "roll": null}, "v": 2.183116672096718, "accelerator_pedal_position": 0.2683479198415903, "brake_pedal_position": 0.0, "acceleration": 0.07035868136523682, "steering_wheel_angle": -0.10219875315003235, "front_wheel_angle": -0.004699698438457282, "heading_rate": -0.004007838106844755, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141162.7818859} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.263718678233362, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7732258951204383, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1845231866786916, "gear": 1, "accelerator_pedal_position": 0.2683479198415903, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.10219875315003235, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141162.7818859} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.409996747970581, "x": 4.738535211435488, "y": -0.14096653922276747, "z": null, "yaw": 6.245701830510337, "pitch": null, "roll": null}, "v": 2.183116672096718, "accelerator_pedal_position": 0.2683479198415903, "brake_pedal_position": 0.0, "acceleration": 0.07035868136523682, "steering_wheel_angle": -0.10219875315003235, "front_wheel_angle": -0.004699698438457282, "heading_rate": -0.004007838106844755, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141162.8018858} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26597732990423784, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7732258951204383, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1853486830565654, "gear": 1, "accelerator_pedal_position": 0.263718678233362, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.06142834544617217, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141162.8018858} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.409996747970581, "x": 4.738535211435488, "y": -0.14096653922276747, "z": null, "yaw": 6.245701830510337, "pitch": null, "roll": null}, "v": 2.183116672096718, "accelerator_pedal_position": 0.2683479198415903, "brake_pedal_position": 0.0, "acceleration": 0.07035868136523682, "steering_wheel_angle": -0.10219875315003235, "front_wheel_angle": -0.004699698438457282, "heading_rate": -0.004007838106844755, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141162.8218858} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26597732990423784, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7732258951204383, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.185902016947398, "gear": 1, "accelerator_pedal_position": 0.26597732990423784, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.06142834544617217, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141162.8218858} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.409996747970581, "x": 4.738535211435488, "y": -0.14096653922276747, "z": null, "yaw": 6.245701830510337, "pitch": null, "roll": null}, "v": 2.183116672096718, "accelerator_pedal_position": 0.2683479198415903, "brake_pedal_position": 0.0, "acceleration": 0.07035868136523682, "steering_wheel_angle": -0.10219875315003235, "front_wheel_angle": -0.004699698438457282, "heading_rate": -0.004007838106844755, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141162.8418858} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26597732990423784, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7732258951204383, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.187558909060464, "gear": 1, "accelerator_pedal_position": 0.26597732990423784, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.06142834544617217, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141162.8418858} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.409996747970581, "x": 4.738535211435488, "y": -0.14096653922276747, "z": null, "yaw": 6.245701830510337, "pitch": null, "roll": null}, "v": 2.183116672096718, "accelerator_pedal_position": 0.2683479198415903, "brake_pedal_position": 0.0, "acceleration": 0.07035868136523682, "steering_wheel_angle": -0.10219875315003235, "front_wheel_angle": -0.004699698438457282, "heading_rate": -0.004007838106844755, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141162.8618858} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26597732990423784, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7732258951204383, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.188660916748052, "gear": 1, "accelerator_pedal_position": 0.26597732990423784, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.06142834544617217, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141162.8618858} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141162.8818858, "x": 8.978820039593836, "y": 4.850004924089649, "z": null, "yaw": -0.03762678073659206, "pitch": null, "roll": null}, "v": 2.189211145747843, "accelerator_pedal_position": 0.26597732990423784, "brake_pedal_position": 0.0, "acceleration": 0.054971300207428464, "steering_wheel_angle": -0.06142834544617217, "front_wheel_angle": -0.0028233227633359423, "heading_rate": -0.002414400814226773, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141162.8818858} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26151057208771267, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7915115260681181, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.189211145747843, "gear": 1, "accelerator_pedal_position": 0.26597732990423784, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.06142834544617217, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141162.8818858} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.5199966430664062, "x": 4.9788200395938365, "y": -0.14999507591035144, "z": null, "yaw": 6.245558526442994, "pitch": null, "roll": null}, "v": 2.189211145747843, "accelerator_pedal_position": 0.26597732990423784, "brake_pedal_position": 0.0, "acceleration": 0.054971300207428464, "steering_wheel_angle": -0.06142834544617217, "front_wheel_angle": -0.0028233227633359423, "heading_rate": -0.002414400814226773, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141162.9018857} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2636811202502925, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7915115260681181, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1905629780742086, "gear": 1, "accelerator_pedal_position": 0.2636811202502925, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.06142834544617217, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141162.9018857} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.5199966430664062, "x": 4.9788200395938365, "y": -0.14999507591035144, "z": null, "yaw": 6.245558526442994, "pitch": null, "roll": null}, "v": 2.189211145747843, "accelerator_pedal_position": 0.26597732990423784, "brake_pedal_position": 0.0, "acceleration": 0.054971300207428464, "steering_wheel_angle": -0.06142834544617217, "front_wheel_angle": -0.0028233227633359423, "heading_rate": -0.002414400814226773, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141162.9218857} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2636811202502925, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7915115260681181, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1905629780742086, "gear": 1, "accelerator_pedal_position": 0.2636811202502925, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.06142834544617217, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141162.9218857} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.5199966430664062, "x": 4.9788200395938365, "y": -0.14999507591035144, "z": null, "yaw": 6.245558526442994, "pitch": null, "roll": null}, "v": 2.189211145747843, "accelerator_pedal_position": 0.26597732990423784, "brake_pedal_position": 0.0, "acceleration": 0.054971300207428464, "steering_wheel_angle": -0.06142834544617217, "front_wheel_angle": -0.0028233227633359423, "heading_rate": -0.002414400814226773, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141162.9418857} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2636811202502925, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7915115260681181, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1913724620071164, "gear": 1, "accelerator_pedal_position": 0.2636811202502925, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.06142834544617217, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141162.9418857} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.5199966430664062, "x": 4.9788200395938365, "y": -0.14999507591035144, "z": null, "yaw": 6.245558526442994, "pitch": null, "roll": null}, "v": 2.189211145747843, "accelerator_pedal_position": 0.26597732990423784, "brake_pedal_position": 0.0, "acceleration": 0.054971300207428464, "steering_wheel_angle": -0.06142834544617217, "front_wheel_angle": -0.0028233227633359423, "heading_rate": -0.002414400814226773, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141162.9618857} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2636811202502925, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7915115260681181, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.192583841980955, "gear": 1, "accelerator_pedal_position": 0.2636811202502925, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.06142834544617217, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141162.9618857} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.5199966430664062, "x": 4.9788200395938365, "y": -0.14999507591035144, "z": null, "yaw": 6.245558526442994, "pitch": null, "roll": null}, "v": 2.189211145747843, "accelerator_pedal_position": 0.26597732990423784, "brake_pedal_position": 0.0, "acceleration": 0.054971300207428464, "steering_wheel_angle": -0.06142834544617217, "front_wheel_angle": -0.0028233227633359423, "heading_rate": -0.002414400814226773, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141162.9818857} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2636811202502925, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7915115260681181, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1929868776851964, "gear": 1, "accelerator_pedal_position": 0.2636811202502925, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.06142834544617217, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141162.9818857} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141162.9918857, "x": 9.21965928696011, "y": 4.840925335336219, "z": null, "yaw": -0.03774809570891935, "pitch": null, "roll": null}, "v": 2.193389535117427, "accelerator_pedal_position": 0.2636811202502925, "brake_pedal_position": 0.0, "acceleration": 0.04022794828083026, "steering_wheel_angle": -0.06142834544617217, "front_wheel_angle": -0.0028233227633359423, "heading_rate": -0.0024190090068698968, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141163.0018857} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25885814769171406, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.803010348466016, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1938922806710868, "gear": 1, "accelerator_pedal_position": 0.25885814769171406, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.02058091721173448, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141163.0018857} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.6299965381622314, "x": 5.219659286960111, "y": -0.15907466466378128, "z": null, "yaw": 6.245437211470667, "pitch": null, "roll": null}, "v": 2.193389535117427, "accelerator_pedal_position": 0.2636811202502925, "brake_pedal_position": 0.0, "acceleration": 0.04022794828083026, "steering_wheel_angle": -0.06142834544617217, "front_wheel_angle": -0.0028233227633359423, "heading_rate": -0.0024190090068698968, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141163.0218856} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26118467228862374, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.803010348466016, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1939926524275646, "gear": 1, "accelerator_pedal_position": 0.25885814769171406, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.02058091721173448, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141163.0218856} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.6299965381622314, "x": 5.219659286960111, "y": -0.15907466466378128, "z": null, "yaw": 6.245437211470667, "pitch": null, "roll": null}, "v": 2.193389535117427, "accelerator_pedal_position": 0.2636811202502925, "brake_pedal_position": 0.0, "acceleration": 0.04022794828083026, "steering_wheel_angle": -0.06142834544617217, "front_wheel_angle": -0.0028233227633359423, "heading_rate": -0.0024190090068698968, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141163.0418856} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26118467228862374, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.803010348466016, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1947290166147084, "gear": 1, "accelerator_pedal_position": 0.26118467228862374, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.02058091721173448, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141163.0418856} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.6299965381622314, "x": 5.219659286960111, "y": -0.15907466466378128, "z": null, "yaw": 6.245437211470667, "pitch": null, "roll": null}, "v": 2.193389535117427, "accelerator_pedal_position": 0.2636811202502925, "brake_pedal_position": 0.0, "acceleration": 0.04022794828083026, "steering_wheel_angle": -0.06142834544617217, "front_wheel_angle": -0.0028233227633359423, "heading_rate": -0.0024190090068698968, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141163.0618856} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26118467228862374, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.803010348466016, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1954633085848374, "gear": 1, "accelerator_pedal_position": 0.26118467228862374, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.02058091721173448, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141163.0618856} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.6299965381622314, "x": 5.219659286960111, "y": -0.15907466466378128, "z": null, "yaw": 6.245437211470667, "pitch": null, "roll": null}, "v": 2.193389535117427, "accelerator_pedal_position": 0.2636811202502925, "brake_pedal_position": 0.0, "acceleration": 0.04022794828083026, "steering_wheel_angle": -0.06142834544617217, "front_wheel_angle": -0.0028233227633359423, "heading_rate": -0.0024190090068698968, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141163.0918856} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26118467228862374, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.803010348466016, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.19570761303465, "gear": 1, "accelerator_pedal_position": 0.26118467228862374, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.02058091721173448, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141163.0918856} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141163.1018856, "x": 9.460885848060867, "y": 4.831807641893765, "z": null, "yaw": -0.037803390324551454, "pitch": null, "roll": null}, "v": 2.195951688053978, "accelerator_pedal_position": 0.26118467228862374, "brake_pedal_position": 0.0, "acceleration": 0.02438457923852827, "steering_wheel_angle": -0.02058091721173448, "front_wheel_angle": -0.0009454176151775053, "heading_rate": -0.0008109734478562793, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141163.1118855} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25523354947204774, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7869329202876548, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1960672054391543, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.02058091721173448, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141163.1118855} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.7399964332580566, "x": 5.460885848060867, "y": -0.16819235810623478, "z": null, "yaw": 6.245381916855035, "pitch": null, "roll": null}, "v": 2.195951688053978, "accelerator_pedal_position": 0.26118467228862374, "brake_pedal_position": 0.0, "acceleration": 0.02438457923852827, "steering_wheel_angle": -0.02058091721173448, "front_wheel_angle": -0.0009454176151775053, "heading_rate": -0.0008109734478562793, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141163.1318855} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2580857479928815, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7869329202876548, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.195938997561357, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.02058091721173448, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141163.1318855} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.7399964332580566, "x": 5.460885848060867, "y": -0.16819235810623478, "z": null, "yaw": 6.245381916855035, "pitch": null, "roll": null}, "v": 2.195951688053978, "accelerator_pedal_position": 0.26118467228862374, "brake_pedal_position": 0.0, "acceleration": 0.02438457923852827, "steering_wheel_angle": -0.02058091721173448, "front_wheel_angle": -0.0009454176151775053, "heading_rate": -0.0008109734478562793, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141163.1518855} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2580857479928815, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7869329202876548, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1960393003227576, "gear": 1, "accelerator_pedal_position": 0.2580857479928815, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.02058091721173448, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141163.1518855} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.7399964332580566, "x": 5.460885848060867, "y": -0.16819235810623478, "z": null, "yaw": 6.245381916855035, "pitch": null, "roll": null}, "v": 2.195951688053978, "accelerator_pedal_position": 0.26118467228862374, "brake_pedal_position": 0.0, "acceleration": 0.02438457923852827, "steering_wheel_angle": -0.02058091721173448, "front_wheel_angle": -0.0009454176151775053, "heading_rate": -0.0008109734478562793, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141163.1718855} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2580857479928815, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7869329202876548, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1961394147633584, "gear": 1, "accelerator_pedal_position": 0.2580857479928815, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.02058091721173448, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141163.1718855} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.7399964332580566, "x": 5.460885848060867, "y": -0.16819235810623478, "z": null, "yaw": 6.245381916855035, "pitch": null, "roll": null}, "v": 2.195951688053978, "accelerator_pedal_position": 0.26118467228862374, "brake_pedal_position": 0.0, "acceleration": 0.02438457923852827, "steering_wheel_angle": -0.02058091721173448, "front_wheel_angle": -0.0009454176151775053, "heading_rate": -0.0008109734478562793, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141163.1918855} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2580857479928815, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7869329202876548, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1962393412327286, "gear": 1, "accelerator_pedal_position": 0.2580857479928815, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.02058091721173448, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141163.1918855} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141163.2118855, "x": 9.702284372352429, "y": 4.82267314565926, "z": null, "yaw": -0.03784401374980685, "pitch": null, "roll": null}, "v": 2.196339080079804, "accelerator_pedal_position": 0.2580857479928815, "brake_pedal_position": 0.0, "acceleration": 0.004979917404660972, "steering_wheel_angle": -0.02058091721173448, "front_wheel_angle": -0.0009454176151775053, "heading_rate": -0.0008111165132290585, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141163.2118855} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25778012202734757, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8346553795122966, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.196339080079804, "gear": 1, "accelerator_pedal_position": 0.2580857479928815, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.02058091721173448, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141163.2118855} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.849996328353882, "x": 5.702284372352429, "y": -0.17732685434074025, "z": null, "yaw": 6.245341293429779, "pitch": null, "roll": null}, "v": 2.196339080079804, "accelerator_pedal_position": 0.2580857479928815, "brake_pedal_position": 0.0, "acceleration": 0.004979917404660972, "steering_wheel_angle": -0.02058091721173448, "front_wheel_angle": -0.0009454176151775053, "heading_rate": -0.0008111165132290585, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141163.2318854} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2579284304648677, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8346553795122966, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1964004463488895, "gear": 1, "accelerator_pedal_position": 0.25778012202734757, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.02058091721173448, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141163.2318854} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.849996328353882, "x": 5.702284372352429, "y": -0.17732685434074025, "z": null, "yaw": 6.245341293429779, "pitch": null, "roll": null}, "v": 2.196339080079804, "accelerator_pedal_position": 0.2580857479928815, "brake_pedal_position": 0.0, "acceleration": 0.004979917404660972, "steering_wheel_angle": -0.02058091721173448, "front_wheel_angle": -0.0009454176151775053, "heading_rate": -0.0008111165132290585, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141163.2518854} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2579284304648677, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8346553795122966, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.196480227240439, "gear": 1, "accelerator_pedal_position": 0.2579284304648677, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.02058091721173448, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141163.2518854} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.849996328353882, "x": 5.702284372352429, "y": -0.17732685434074025, "z": null, "yaw": 6.245341293429779, "pitch": null, "roll": null}, "v": 2.196339080079804, "accelerator_pedal_position": 0.2580857479928815, "brake_pedal_position": 0.0, "acceleration": 0.004979917404660972, "steering_wheel_angle": -0.02058091721173448, "front_wheel_angle": -0.0009454176151775053, "heading_rate": -0.0008111165132290585, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141163.2718854} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2579284304648677, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8346553795122966, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.196559858327262, "gear": 1, "accelerator_pedal_position": 0.2579284304648677, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.02058091721173448, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141163.2718854} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.849996328353882, "x": 5.702284372352429, "y": -0.17732685434074025, "z": null, "yaw": 6.245341293429779, "pitch": null, "roll": null}, "v": 2.196339080079804, "accelerator_pedal_position": 0.2580857479928815, "brake_pedal_position": 0.0, "acceleration": 0.004979917404660972, "steering_wheel_angle": -0.02058091721173448, "front_wheel_angle": -0.0009454176151775053, "heading_rate": -0.0008111165132290585, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141163.2918854} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2579284304648677, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8346553795122966, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.196639339888111, "gear": 1, "accelerator_pedal_position": 0.2579284304648677, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.02058091721173448, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141163.2918854} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.849996328353882, "x": 5.702284372352429, "y": -0.17732685434074025, "z": null, "yaw": 6.245341293429779, "pitch": null, "roll": null}, "v": 2.196339080079804, "accelerator_pedal_position": 0.2580857479928815, "brake_pedal_position": 0.0, "acceleration": 0.004979917404660972, "steering_wheel_angle": -0.02058091721173448, "front_wheel_angle": -0.0009454176151775053, "heading_rate": -0.0008111165132290585, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141163.3118854} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2579284304648677, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8346553795122966, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1967186722012313, "gear": 1, "accelerator_pedal_position": 0.2579284304648677, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.02058091721173448, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141163.3118854} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141163.3218853, "x": 9.94372867018119, "y": 4.8135270949489435, "z": null, "yaw": -0.03788463717506225, "pitch": null, "roll": null}, "v": 2.196758282476705, "accelerator_pedal_position": 0.2579284304648677, "brake_pedal_position": 0.0, "acceleration": 0.00395730676528766, "steering_wheel_angle": -0.02058091721173448, "front_wheel_angle": -0.0009454176151775053, "heading_rate": -0.000811271326294853, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141163.3318853} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2576150448315653, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.886680662051216, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.196797855544358, "gear": 1, "accelerator_pedal_position": 0.2579284304648677, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.02058091721173448, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141163.3318853} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.959996223449707, "x": 5.943728670181191, "y": -0.18647290505105651, "z": null, "yaw": 6.245300670004524, "pitch": null, "roll": null}, "v": 2.196758282476705, "accelerator_pedal_position": 0.2579284304648677, "brake_pedal_position": 0.0, "acceleration": 0.00395730676528766, "steering_wheel_angle": -0.02058091721173448, "front_wheel_angle": -0.0009454176151775053, "heading_rate": -0.000811271326294853, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141163.3518853} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2577672762445583, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.886680662051216, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.196837735389536, "gear": 1, "accelerator_pedal_position": 0.2576150448315653, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.06133493489449966, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141163.3518853} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.959996223449707, "x": 5.943728670181191, "y": -0.18647290505105651, "z": null, "yaw": 6.245300670004524, "pitch": null, "roll": null}, "v": 2.196758282476705, "accelerator_pedal_position": 0.2579284304648677, "brake_pedal_position": 0.0, "acceleration": 0.00395730676528766, "steering_wheel_angle": -0.02058091721173448, "front_wheel_angle": -0.0009454176151775053, "heading_rate": -0.000811271326294853, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141163.3718853} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2577672762445583, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.886680662051216, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1968965603353974, "gear": 1, "accelerator_pedal_position": 0.2577672762445583, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.06133493489449966, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141163.3718853} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.959996223449707, "x": 5.943728670181191, "y": -0.18647290505105651, "z": null, "yaw": 6.245300670004524, "pitch": null, "roll": null}, "v": 2.196758282476705, "accelerator_pedal_position": 0.2579284304648677, "brake_pedal_position": 0.0, "acceleration": 0.00395730676528766, "steering_wheel_angle": -0.02058091721173448, "front_wheel_angle": -0.0009454176151775053, "heading_rate": -0.000811271326294853, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141163.3918853} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2577672762445583, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.886680662051216, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1969552748156396, "gear": 1, "accelerator_pedal_position": 0.2577672762445583, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.06133493489449966, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141163.3918853} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.959996223449707, "x": 5.943728670181191, "y": -0.18647290505105651, "z": null, "yaw": 6.245300670004524, "pitch": null, "roll": null}, "v": 2.196758282476705, "accelerator_pedal_position": 0.2579284304648677, "brake_pedal_position": 0.0, "acceleration": 0.00395730676528766, "steering_wheel_angle": -0.02058091721173448, "front_wheel_angle": -0.0009454176151775053, "heading_rate": -0.000811271326294853, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141163.4118853} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2577672762445583, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.886680662051216, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1970138790363243, "gear": 1, "accelerator_pedal_position": 0.2577672762445583, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.06133493489449966, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141163.4118853} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141163.4318852, "x": 10.185214475450548, "y": 4.804379993337624, "z": null, "yaw": -0.03780026906270714, "pitch": null, "roll": null}, "v": 2.197072373203134, "accelerator_pedal_position": 0.2577672762445583, "brake_pedal_position": 0.0, "acceleration": 0.002920587737408109, "steering_wheel_angle": 0.06133493489449966, "front_wheel_angle": 0.002819026041160382, "heading_rate": 0.0024193830629270076, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141163.4318852} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2539697064518247, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8802596327541127, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.197072373203134, "gear": 1, "accelerator_pedal_position": 0.2577672762445583, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.06133493489449966, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141163.4318852} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.069996118545532, "x": 6.1852144754505485, "y": -0.19562000666237633, "z": null, "yaw": 6.245385038116879, "pitch": null, "roll": null}, "v": 2.197072373203134, "accelerator_pedal_position": 0.2577672762445583, "brake_pedal_position": 0.0, "acceleration": 0.002920587737408109, "steering_wheel_angle": 0.06133493489449966, "front_wheel_angle": 0.002819026041160382, "heading_rate": 0.0024193830629270076, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141163.4518852} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25578032193577527, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8802596327541127, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1966562842612865, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.06133493489449966, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141163.4518852} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.069996118545532, "x": 6.1852144754505485, "y": -0.19562000666237633, "z": null, "yaw": 6.245385038116879, "pitch": null, "roll": null}, "v": 2.197072373203134, "accelerator_pedal_position": 0.2577672762445583, "brake_pedal_position": 0.0, "acceleration": 0.002920587737408109, "steering_wheel_angle": 0.06133493489449966, "front_wheel_angle": 0.002819026041160382, "heading_rate": 0.0024193830629270076, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141163.4718852} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25578032193577527, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8802596327541127, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1964671973012404, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.06133493489449966, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141163.4718852} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.069996118545532, "x": 6.1852144754505485, "y": -0.19562000666237633, "z": null, "yaw": 6.245385038116879, "pitch": null, "roll": null}, "v": 2.197072373203134, "accelerator_pedal_position": 0.2577672762445583, "brake_pedal_position": 0.0, "acceleration": 0.002920587737408109, "steering_wheel_angle": 0.06133493489449966, "front_wheel_angle": 0.002819026041160382, "heading_rate": 0.0024193830629270076, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141163.4918852} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25578032193577527, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8802596327541127, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.196278465394224, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.06133493489449966, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141163.4918852} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.069996118545532, "x": 6.1852144754505485, "y": -0.19562000666237633, "z": null, "yaw": 6.245385038116879, "pitch": null, "roll": null}, "v": 2.197072373203134, "accelerator_pedal_position": 0.2577672762445583, "brake_pedal_position": 0.0, "acceleration": 0.002920587737408109, "steering_wheel_angle": 0.06133493489449966, "front_wheel_angle": 0.002819026041160382, "heading_rate": 0.0024193830629270076, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141163.5118852} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25578032193577527, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8802596327541127, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.196090087859305, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.06133493489449966, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141163.5118852} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.069996118545532, "x": 6.1852144754505485, "y": -0.19562000666237633, "z": null, "yaw": 6.245385038116879, "pitch": null, "roll": null}, "v": 2.197072373203134, "accelerator_pedal_position": 0.2577672762445583, "brake_pedal_position": 0.0, "acceleration": 0.002920587737408109, "steering_wheel_angle": 0.06133493489449966, "front_wheel_angle": 0.002819026041160382, "heading_rate": 0.0024193830629270076, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141163.5318851} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25578032193577527, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8802596327541127, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.195902064016909, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.06133493489449966, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141163.5318851} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141163.5418851, "x": 10.426646843154478, "y": 4.795262746450103, "z": null, "yaw": -0.037679138716630325, "pitch": null, "roll": null}, "v": 2.195808184518411, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35800614505790096, "steering_wheel_angle": 0.06133493489449966, "front_wheel_angle": 0.002819026041160382, "heading_rate": 0.0024179909573553084, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141163.5518851} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2562063362870468, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9305863801118298, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1956473158405183, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.10228185249761974, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141163.5518851} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.179996013641357, "x": 6.426646843154478, "y": -0.20473725354989725, "z": null, "yaw": 6.245506168462956, "pitch": null, "roll": null}, "v": 2.195808184518411, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35800614505790096, "steering_wheel_angle": 0.06133493489449966, "front_wheel_angle": 0.002819026041160382, "heading_rate": 0.0024179909573553084, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141163.571885} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2559944250628163, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9305863801118298, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1955803014869826, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.10228185249761974, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141163.571885} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.179996013641357, "x": 6.426646843154478, "y": -0.20473725354989725, "z": null, "yaw": 6.245506168462956, "pitch": null, "roll": null}, "v": 2.195808184518411, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35800614505790096, "steering_wheel_angle": 0.06133493489449966, "front_wheel_angle": 0.002819026041160382, "heading_rate": 0.0024179909573553084, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141163.591885} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2559944250628163, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9305863801118298, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1954199850588787, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.10228185249761974, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141163.591885} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.179996013641357, "x": 6.426646843154478, "y": -0.20473725354989725, "z": null, "yaw": 6.245506168462956, "pitch": null, "roll": null}, "v": 2.195808184518411, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35800614505790096, "steering_wheel_angle": 0.06133493489449966, "front_wheel_angle": 0.002819026041160382, "heading_rate": 0.0024179909573553084, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141163.611885} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2559944250628163, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9305863801118298, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1952599695931485, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.10228185249761974, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141163.611885} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.179996013641357, "x": 6.426646843154478, "y": -0.20473725354989725, "z": null, "yaw": 6.245506168462956, "pitch": null, "roll": null}, "v": 2.195808184518411, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35800614505790096, "steering_wheel_angle": 0.06133493489449966, "front_wheel_angle": 0.002819026041160382, "heading_rate": 0.0024179909573553084, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141163.631885} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2559944250628163, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9305863801118298, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1951002545145575, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.10228185249761974, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141163.631885} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141163.651885, "x": 10.667971864801656, "y": 4.786184648664712, "z": null, "yaw": -0.03749175549802773, "pitch": null, "roll": null}, "v": 2.1949408392490084, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35792469484048184, "steering_wheel_angle": 0.10228185249761974, "front_wheel_angle": 0.004703524974642843, "heading_rate": 0.004032826245612057, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141163.651885} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25261395010923926, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9233601753444083, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.194649964182431, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.10228185249761974, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141163.651885} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.289995908737183, "x": 6.667971864801656, "y": -0.21381535133528828, "z": null, "yaw": 6.245693551681558, "pitch": null, "roll": null}, "v": 2.1949408392490084, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35792469484048184, "steering_wheel_angle": 0.10228185249761974, "front_wheel_angle": 0.004703524974642843, "heading_rate": 0.004032826245612057, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141163.671885} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2542174951573229, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9233601753444083, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1943593622356383, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.10228185249761974, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141163.671885} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.289995908737183, "x": 6.667971864801656, "y": -0.21381535133528828, "z": null, "yaw": 6.245693551681558, "pitch": null, "roll": null}, "v": 2.1949408392490084, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35792469484048184, "steering_wheel_angle": 0.10228185249761974, "front_wheel_angle": 0.004703524974642843, "heading_rate": 0.004032826245612057, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141163.691885} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2542174951573229, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9233601753444083, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1939793256489453, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.10228185249761974, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141163.691885} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.289995908737183, "x": 6.667971864801656, "y": -0.21381535133528828, "z": null, "yaw": 6.245693551681558, "pitch": null, "roll": null}, "v": 2.1949408392490084, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35792469484048184, "steering_wheel_angle": 0.10228185249761974, "front_wheel_angle": 0.004703524974642843, "heading_rate": 0.004032826245612057, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141163.711885} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2542174951573229, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9233601753444083, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1936000022952995, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.10228185249761974, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141163.711885} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.289995908737183, "x": 6.667971864801656, "y": -0.21381535133528828, "z": null, "yaw": 6.245693551681558, "pitch": null, "roll": null}, "v": 2.1949408392490084, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35792469484048184, "steering_wheel_angle": 0.10228185249761974, "front_wheel_angle": 0.004703524974642843, "heading_rate": 0.004032826245612057, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141163.731885} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2542174951573229, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9233601753444083, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.193221390778615, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.10228185249761974, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141163.731885} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.289995908737183, "x": 6.667971864801656, "y": -0.21381535133528828, "z": null, "yaw": 6.245693551681558, "pitch": null, "roll": null}, "v": 2.1949408392490084, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35792469484048184, "steering_wheel_angle": 0.10228185249761974, "front_wheel_angle": 0.004703524974642843, "heading_rate": 0.004032826245612057, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141163.751885} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2542174951573229, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9233601753444083, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.192843489705749, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.10228185249761974, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141163.751885} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141163.761885, "x": 10.90912307218825, "y": 4.777161408677103, "z": null, "yaw": -0.037289649418863854, "pitch": null, "roll": null}, "v": 2.1926548051511943, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35771009120308594, "steering_wheel_angle": 0.10228185249761974, "front_wheel_angle": 0.004703524974642843, "heading_rate": 0.004028626051172565, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141163.771885} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25522671285449433, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9763450258650905, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.192466297686496, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.10228185249761974, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141163.771885} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.399995803833008, "x": 6.909123072188249, "y": -0.22283859132289674, "z": null, "yaw": 6.245895657760722, "pitch": null, "roll": null}, "v": 2.1926548051511943, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35771009120308594, "steering_wheel_angle": 0.10228185249761974, "front_wheel_angle": 0.004703524974642843, "heading_rate": 0.004028626051172565, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141163.791885} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2547297819971343, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9763450258650905, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1922159063512034, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.14323632993631794, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141163.791885} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.399995803833008, "x": 6.909123072188249, "y": -0.22283859132289674, "z": null, "yaw": 6.245895657760722, "pitch": null, "roll": null}, "v": 2.1926548051511943, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35771009120308594, "steering_wheel_angle": 0.10228185249761974, "front_wheel_angle": 0.004703524974642843, "heading_rate": 0.004028626051172565, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141163.8118849} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2547297819971343, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9763450258650905, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.19190389754604, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.14323632993631794, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141163.8118849} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.399995803833008, "x": 6.909123072188249, "y": -0.22283859132289674, "z": null, "yaw": 6.245895657760722, "pitch": null, "roll": null}, "v": 2.1926548051511943, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35771009120308594, "steering_wheel_angle": 0.10228185249761974, "front_wheel_angle": 0.004703524974642843, "heading_rate": 0.004028626051172565, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141163.8318849} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2547297819971343, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9763450258650905, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1915924740419963, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.14323632993631794, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141163.8318849} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.399995803833008, "x": 6.909123072188249, "y": -0.22283859132289674, "z": null, "yaw": 6.245895657760722, "pitch": null, "roll": null}, "v": 2.1926548051511943, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35771009120308594, "steering_wheel_angle": 0.10228185249761974, "front_wheel_angle": 0.004703524974642843, "heading_rate": 0.004028626051172565, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141163.8518848} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2547297819971343, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9763450258650905, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1912816347023236, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.14323632993631794, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141163.8518848} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141163.8718848, "x": 11.150064773155345, "y": 4.7682005916530965, "z": null, "yaw": -0.037021205546060997, "pitch": null, "roll": null}, "v": 2.190971378392623, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35755212472898784, "steering_wheel_angle": 0.14323632993631794, "front_wheel_angle": 0.006590405929925539, "heading_rate": 0.005640468679274089, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141163.8718848} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25223867588200505, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9652807484271456, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.190971378392623, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.14323632993631794, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141163.8718848} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.509995698928833, "x": 7.150064773155345, "y": -0.2317994083469035, "z": null, "yaw": 6.246164101633525, "pitch": null, "roll": null}, "v": 2.190971378392623, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35755212472898784, "steering_wheel_angle": 0.14323632993631794, "front_wheel_angle": 0.006590405929925539, "heading_rate": 0.005640468679274089, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141163.8918848} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25341288193489303, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9652807484271456, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1903504617805454, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.14323632993631794, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141163.8918848} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.509995698928833, "x": 7.150064773155345, "y": -0.2317994083469035, "z": null, "yaw": 6.246164101633525, "pitch": null, "roll": null}, "v": 2.190971378392623, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35755212472898784, "steering_wheel_angle": 0.14323632993631794, "front_wheel_angle": 0.006590405929925539, "heading_rate": 0.005640468679274089, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141163.9118848} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25341288193489303, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9652807484271456, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1898774165048684, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.14323632993631794, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141163.9118848} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.509995698928833, "x": 7.150064773155345, "y": -0.2317994083469035, "z": null, "yaw": 6.246164101633525, "pitch": null, "roll": null}, "v": 2.190971378392623, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35755212472898784, "steering_wheel_angle": 0.14323632993631794, "front_wheel_angle": 0.006590405929925539, "heading_rate": 0.005640468679274089, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141163.9318848} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25341288193489303, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9652807484271456, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.189405258245116, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.14323632993631794, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141163.9318848} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.509995698928833, "x": 7.150064773155345, "y": -0.2317994083469035, "z": null, "yaw": 6.246164101633525, "pitch": null, "roll": null}, "v": 2.190971378392623, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35755212472898784, "steering_wheel_angle": 0.14323632993631794, "front_wheel_angle": 0.006590405929925539, "heading_rate": 0.005640468679274089, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141163.9518847} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25341288193489303, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9652807484271456, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1889339852488967, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.14323632993631794, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141163.9518847} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.509995698928833, "x": 7.150064773155345, "y": -0.2317994083469035, "z": null, "yaw": 6.246164101633525, "pitch": null, "roll": null}, "v": 2.190971378392623, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35755212472898784, "steering_wheel_angle": 0.14323632993631794, "front_wheel_angle": 0.006590405929925539, "heading_rate": 0.005640468679274089, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141163.9718847} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25341288193489303, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9652807484271456, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.188463595767606, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.14323632993631794, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141163.9718847} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141163.9818847, "x": 11.390763738003251, "y": 4.759316570881186, "z": null, "yaw": -0.036738019941338365, "pitch": null, "roll": null}, "v": 2.188228731799653, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3572948864167178, "steering_wheel_angle": 0.14323632993631794, "front_wheel_angle": 0.006590405929925539, "heading_rate": 0.005633407969874355, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141163.9918847} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24969041354911875, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.940979543297891, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1879940880564166, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.14323632993631794, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141163.9918847} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.619995594024658, "x": 7.390763738003251, "y": -0.24068342911881402, "z": null, "yaw": 6.246447287238248, "pitch": null, "roll": null}, "v": 2.188228731799653, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3572948864167178, "steering_wheel_angle": 0.14323632993631794, "front_wheel_angle": 0.006590405929925539, "heading_rate": 0.005633407969874355, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141164.0118847} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25144341930854125, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.940979543297891, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1870603699460998, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.14323632993631794, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141164.0118847} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.619995594024658, "x": 7.390763738003251, "y": -0.24068342911881402, "z": null, "yaw": 6.246447287238248, "pitch": null, "roll": null}, "v": 2.188228731799653, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3572948864167178, "steering_wheel_angle": 0.14323632993631794, "front_wheel_angle": 0.006590405929925539, "heading_rate": 0.005633407969874355, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141164.0318847} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25144341930854125, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.940979543297891, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1863474246830843, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.14323632993631794, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141164.0318847} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.619995594024658, "x": 7.390763738003251, "y": -0.24068342911881402, "z": null, "yaw": 6.246447287238248, "pitch": null, "roll": null}, "v": 2.188228731799653, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3572948864167178, "steering_wheel_angle": 0.14323632993631794, "front_wheel_angle": 0.006590405929925539, "heading_rate": 0.005633407969874355, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141164.0518847} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25144341930854125, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.940979543297891, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.185280510695682, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.14323632993631794, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141164.0518847} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.619995594024658, "x": 7.390763738003251, "y": -0.24068342911881402, "z": null, "yaw": 6.246447287238248, "pitch": null, "roll": null}, "v": 2.188228731799653, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3572948864167178, "steering_wheel_angle": 0.14323632993631794, "front_wheel_angle": 0.006590405929925539, "heading_rate": 0.005633407969874355, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141164.0718846} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25144341930854125, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.940979543297891, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.184925539056075, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.14323632993631794, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141164.0718846} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141164.0918846, "x": 11.63110524481588, "y": 4.7505138933021405, "z": null, "yaw": -0.036454834336615734, "pitch": null, "roll": null}, "v": 2.18421659328725, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35691885092827613, "steering_wheel_angle": 0.14323632993631794, "front_wheel_angle": 0.006590405929925539, "heading_rate": 0.005623079061957394, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141164.0918846} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25318260332716375, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9922251508686155, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.18421659328725, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.14323632993631794, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141164.0918846} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.729995489120483, "x": 7.631105244815879, "y": -0.24948610669785953, "z": null, "yaw": 6.2467304728429704, "pitch": null, "roll": null}, "v": 2.18421659328725, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35691885092827613, "steering_wheel_angle": 0.14323632993631794, "front_wheel_angle": 0.006590405929925539, "heading_rate": 0.005623079061957394, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141164.1118846} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2523257697101983, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9922251508686155, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1837262714635597, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.14323632993631794, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141164.1118846} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.729995489120483, "x": 7.631105244815879, "y": -0.24948610669785953, "z": null, "yaw": 6.2467304728429704, "pitch": null, "roll": null}, "v": 2.18421659328725, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35691885092827613, "steering_wheel_angle": 0.14323632993631794, "front_wheel_angle": 0.006590405929925539, "heading_rate": 0.005623079061957394, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141164.1318846} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2523257697101983, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9922251508686155, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.183129813806576, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.14323632993631794, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141164.1318846} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.729995489120483, "x": 7.631105244815879, "y": -0.24948610669785953, "z": null, "yaw": 6.2467304728429704, "pitch": null, "roll": null}, "v": 2.18421659328725, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35691885092827613, "steering_wheel_angle": 0.14323632993631794, "front_wheel_angle": 0.006590405929925539, "heading_rate": 0.005623079061957394, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141164.1518846} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2523257697101983, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9922251508686155, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1819402467429976, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.14323632993631794, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141164.1518846} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.729995489120483, "x": 7.631105244815879, "y": -0.24948610669785953, "z": null, "yaw": 6.2467304728429704, "pitch": null, "roll": null}, "v": 2.18421659328725, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35691885092827613, "steering_wheel_angle": 0.14323632993631794, "front_wheel_angle": 0.006590405929925539, "heading_rate": 0.005623079061957394, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141164.1718845} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2523257697101983, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9922251508686155, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1816435509024776, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.14323632993631794, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141164.1718845} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.729995489120483, "x": 7.631105244815879, "y": -0.24948610669785953, "z": null, "yaw": 6.2467304728429704, "pitch": null, "roll": null}, "v": 2.18421659328725, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35691885092827613, "steering_wheel_angle": 0.14323632993631794, "front_wheel_angle": 0.006590405929925539, "heading_rate": 0.005623079061957394, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141164.1918845} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2523257697101983, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9922251508686155, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1810509923846335, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.14323632993631794, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141164.1918845} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141164.2018845, "x": 11.87105690340838, "y": 4.74179353776165, "z": null, "yaw": -0.0361716487318931, "pitch": null, "roll": null}, "v": 2.1810509923846335, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3566223839330516, "steering_wheel_angle": 0.14323632993631794, "front_wheel_angle": 0.006590405929925539, "heading_rate": 0.005614929492812683, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141164.2218845} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25378165517227613, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0476840743582745, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1804595429011693, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.14323632993631794, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141164.2218845} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.839995384216309, "x": 7.87105690340838, "y": -0.2582064622383502, "z": null, "yaw": 6.247013658447693, "pitch": null, "roll": null}, "v": 2.1810509923846335, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3566223839330516, "steering_wheel_angle": 0.14323632993631794, "front_wheel_angle": 0.006590405929925539, "heading_rate": 0.005614929492812683, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141164.2418845} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2530657880616627, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0476840743582745, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1800511007461965, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2251741643512392, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141164.2418845} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.839995384216309, "x": 7.87105690340838, "y": -0.2582064622383502, "z": null, "yaw": 6.247013658447693, "pitch": null, "roll": null}, "v": 2.1810509923846335, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3566223839330516, "steering_wheel_angle": 0.14323632993631794, "front_wheel_angle": 0.006590405929925539, "heading_rate": 0.005614929492812683, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141164.2618845} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2530657880616627, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0476840743582745, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1795539813499505, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2251741643512392, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141164.2618845} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.839995384216309, "x": 7.87105690340838, "y": -0.2582064622383502, "z": null, "yaw": 6.247013658447693, "pitch": null, "roll": null}, "v": 2.1810509923846335, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3566223839330516, "steering_wheel_angle": 0.14323632993631794, "front_wheel_angle": 0.006590405929925539, "heading_rate": 0.005614929492812683, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141164.2818844} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2530657880616627, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0476840743582745, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1790577920617844, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2251741643512392, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141164.2818844} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.839995384216309, "x": 7.87105690340838, "y": -0.2582064622383502, "z": null, "yaw": 6.247013658447693, "pitch": null, "roll": null}, "v": 2.1810509923846335, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3566223839330516, "steering_wheel_angle": 0.14323632993631794, "front_wheel_angle": 0.006590405929925539, "heading_rate": 0.005614929492812683, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141164.3018844} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2530657880616627, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0476840743582745, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1785625310430348, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2251741643512392, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141164.3018844} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141164.3118844, "x": 12.110678101814068, "y": 4.733161030392812, "z": null, "yaw": -0.03577767705837795, "pitch": null, "roll": null}, "v": 2.178315248061201, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35636633560241937, "steering_wheel_angle": 0.2251741643512392, "front_wheel_angle": 0.010371631292741235, "heading_rate": 0.008825583098021457, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141164.3218844} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.251801297027709, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0459233664167609, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1780681964590305, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2251741643512392, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141164.3218844} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.949995279312134, "x": 8.110678101814068, "y": -0.2668389696071882, "z": null, "yaw": 6.2474076301212085, "pitch": null, "roll": null}, "v": 2.178315248061201, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35636633560241937, "steering_wheel_angle": 0.2251741643512392, "front_wheel_angle": 0.010371631292741235, "heading_rate": 0.008825583098021457, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141164.3418844} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2523839274621167, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0459233664167609, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1774167990375037, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2251741643512392, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141164.3418844} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.949995279312134, "x": 8.110678101814068, "y": -0.2668389696071882, "z": null, "yaw": 6.2474076301212085, "pitch": null, "roll": null}, "v": 2.178315248061201, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35636633560241937, "steering_wheel_angle": 0.2251741643512392, "front_wheel_angle": 0.010371631292741235, "heading_rate": 0.008825583098021457, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141164.3618844} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2523839274621167, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0459233664167609, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.176839414572699, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2251741643512392, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141164.3618844} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.949995279312134, "x": 8.110678101814068, "y": -0.2668389696071882, "z": null, "yaw": 6.2474076301212085, "pitch": null, "roll": null}, "v": 2.178315248061201, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35636633560241937, "steering_wheel_angle": 0.2251741643512392, "front_wheel_angle": 0.010371631292741235, "heading_rate": 0.008825583098021457, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141164.3818843} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2523839274621167, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0459233664167609, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.176263109769823, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2251741643512392, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141164.3818843} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.949995279312134, "x": 8.110678101814068, "y": -0.2668389696071882, "z": null, "yaw": 6.2474076301212085, "pitch": null, "roll": null}, "v": 2.178315248061201, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35636633560241937, "steering_wheel_angle": 0.2251741643512392, "front_wheel_angle": 0.010371631292741235, "heading_rate": 0.008825583098021457, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141164.4018843} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2523839274621167, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0459233664167609, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.175687882477208, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2251741643512392, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141164.4018843} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141164.4218843, "x": 12.349980471711715, "y": 4.724644218615614, "z": null, "yaw": -0.0353320050457313, "pitch": null, "roll": null}, "v": 2.175113730547953, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35606688393557995, "steering_wheel_angle": 0.2251741643512392, "front_wheel_angle": 0.010371631292741235, "heading_rate": 0.008812611945715521, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141164.4218843} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2523733301161609, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0671483031941742, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.175113730547953, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2251741643512392, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141164.4218843} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.059995174407959, "x": 8.349980471711715, "y": -0.2753557813843859, "z": null, "yaw": 6.247853302133855, "pitch": null, "roll": null}, "v": 2.175113730547953, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35606688393557995, "steering_wheel_angle": 0.2251741643512392, "front_wheel_angle": 0.010371631292741235, "heading_rate": 0.008812611945715521, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141164.4418843} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25235556109740903, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0671483031941742, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.174539327790927, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2251741643512392, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141164.4418843} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.059995174407959, "x": 8.349980471711715, "y": -0.2753557813843859, "z": null, "yaw": 6.247853302133855, "pitch": null, "roll": null}, "v": 2.175113730547953, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35606688393557995, "steering_wheel_angle": 0.2251741643512392, "front_wheel_angle": 0.010371631292741235, "heading_rate": 0.008812611945715521, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141164.4618843} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25235556109740903, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0671483031941742, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1739637785029995, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2251741643512392, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141164.4618843} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.059995174407959, "x": 8.349980471711715, "y": -0.2753557813843859, "z": null, "yaw": 6.247853302133855, "pitch": null, "roll": null}, "v": 2.175113730547953, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35606688393557995, "steering_wheel_angle": 0.2251741643512392, "front_wheel_angle": 0.010371631292741235, "heading_rate": 0.008812611945715521, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141164.4818842} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25235556109740903, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0671483031941742, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1733893047838553, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2251741643512392, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141164.4818842} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.059995174407959, "x": 8.349980471711715, "y": -0.2753557813843859, "z": null, "yaw": 6.247853302133855, "pitch": null, "roll": null}, "v": 2.175113730547953, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35606688393557995, "steering_wheel_angle": 0.2251741643512392, "front_wheel_angle": 0.010371631292741235, "heading_rate": 0.008812611945715521, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141164.5018842} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25235556109740903, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0671483031941742, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1728159044915585, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2251741643512392, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141164.5018842} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.059995174407959, "x": 8.349980471711715, "y": -0.2753557813843859, "z": null, "yaw": 6.247853302133855, "pitch": null, "roll": null}, "v": 2.175113730547953, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35606688393557995, "steering_wheel_angle": 0.2251741643512392, "front_wheel_angle": 0.010371631292741235, "heading_rate": 0.008812611945715521, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141164.5218842} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25235556109740903, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0671483031941742, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1722435754889147, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2251741643512392, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141164.5218842} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141164.5318842, "x": 12.588937467014777, "y": 4.7162463286983565, "z": null, "yaw": -0.03488633303308465, "pitch": null, "roll": null}, "v": 2.171957812054633, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35577189797618314, "steering_wheel_angle": 0.2251741643512392, "front_wheel_angle": 0.010371631292741235, "heading_rate": 0.008799825540745824, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141164.5418842} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25233229758493214, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.088095853745085, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.171672315643459, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2251741643512392, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141164.5418842} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.169995069503784, "x": 8.588937467014777, "y": -0.28375367130164353, "z": null, "yaw": 6.248298974146501, "pitch": null, "roll": null}, "v": 2.171957812054633, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35577189797618314, "steering_wheel_angle": 0.2251741643512392, "front_wheel_angle": 0.010371631292741235, "heading_rate": 0.008799825540745824, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141164.5618842} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25232090032160703, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.088095853745085, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1710992162467964, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.26612240267350307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141164.5618842} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.169995069503784, "x": 8.588937467014777, "y": -0.28375367130164353, "z": null, "yaw": 6.248298974146501, "pitch": null, "roll": null}, "v": 2.171957812054633, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35577189797618314, "steering_wheel_angle": 0.2251741643512392, "front_wheel_angle": 0.010371631292741235, "heading_rate": 0.008799825540745824, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141164.5818841} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25232090032160703, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.088095853745085, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.170525763191953, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.26612240267350307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141164.5818841} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.169995069503784, "x": 8.588937467014777, "y": -0.28375367130164353, "z": null, "yaw": 6.248298974146501, "pitch": null, "roll": null}, "v": 2.171957812054633, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35577189797618314, "steering_wheel_angle": 0.2251741643512392, "front_wheel_angle": 0.010371631292741235, "heading_rate": 0.008799825540745824, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141164.6018841} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25232090032160703, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.088095853745085, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1699533810005174, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.26612240267350307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141164.6018841} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.169995069503784, "x": 8.588937467014777, "y": -0.28375367130164353, "z": null, "yaw": 6.248298974146501, "pitch": null, "roll": null}, "v": 2.171957812054633, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35577189797618314, "steering_wheel_angle": 0.2251741643512392, "front_wheel_angle": 0.010371631292741235, "heading_rate": 0.008799825540745824, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141164.621884} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25232090032160703, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.088095853745085, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.169382067541778, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.26612240267350307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141164.621884} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141164.641884, "x": 12.827551993934565, "y": 4.707972727380936, "z": null, "yaw": -0.034374110959921135, "pitch": null, "roll": null}, "v": 2.168811820689734, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3554780381701219, "steering_wheel_angle": 0.26612240267350307, "front_wheel_angle": 0.012264367751761826, "heading_rate": 0.010390796666354207, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141164.641884} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25077421722875753, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.07318364701602, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.168811820689734, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.26612240267350307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141164.641884} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.279994964599609, "x": 8.827551993934565, "y": -0.29202727261906425, "z": null, "yaw": 6.248811196219665, "pitch": null, "roll": null}, "v": 2.168811820689734, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3554780381701219, "steering_wheel_angle": 0.26612240267350307, "front_wheel_angle": 0.012264367751761826, "heading_rate": 0.010390796666354207, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141164.661884} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2514883440254378, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.07318364701602, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1680493931946936, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.26612240267350307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141164.661884} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.279994964599609, "x": 8.827551993934565, "y": -0.29202727261906425, "z": null, "yaw": 6.248811196219665, "pitch": null, "roll": null}, "v": 2.168811820689734, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3554780381701219, "steering_wheel_angle": 0.26612240267350307, "front_wheel_angle": 0.012264367751761826, "heading_rate": 0.010390796666354207, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141164.681884} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2514883440254378, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.07318364701602, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1673776128959297, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.26612240267350307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141164.681884} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.279994964599609, "x": 8.827551993934565, "y": -0.29202727261906425, "z": null, "yaw": 6.248811196219665, "pitch": null, "roll": null}, "v": 2.168811820689734, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3554780381701219, "steering_wheel_angle": 0.26612240267350307, "front_wheel_angle": 0.012264367751761826, "heading_rate": 0.010390796666354207, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141164.701884} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2514883440254378, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.07318364701602, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1667070862378313, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.26612240267350307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141164.701884} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.279994964599609, "x": 8.827551993934565, "y": -0.29202727261906425, "z": null, "yaw": 6.248811196219665, "pitch": null, "roll": null}, "v": 2.168811820689734, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3554780381701219, "steering_wheel_angle": 0.26612240267350307, "front_wheel_angle": 0.012264367751761826, "heading_rate": 0.010390796666354207, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141164.721884} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2514883440254378, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.07318364701602, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1660378107011615, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.26612240267350307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141164.721884} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.279994964599609, "x": 8.827551993934565, "y": -0.29202727261906425, "z": null, "yaw": 6.248811196219665, "pitch": null, "roll": null}, "v": 2.168811820689734, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3554780381701219, "steering_wheel_angle": 0.26612240267350307, "front_wheel_angle": 0.012264367751761826, "heading_rate": 0.010390796666354207, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141164.741884} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2514883440254378, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.07318364701602, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1653697837723915, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.26612240267350307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141164.741884} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141164.751884, "x": 13.065789284002436, "y": 4.699837424302789, "z": null, "yaw": -0.03384709998442054, "pitch": null, "roll": null}, "v": 2.1650362377520476, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35512563099539785, "steering_wheel_angle": 0.26612240267350307, "front_wheel_angle": 0.012264367751761826, "heading_rate": 0.010372707815017174, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141164.761884} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2510374927613733, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0737080125480953, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1647030029436833, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.26612240267350307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141164.761884} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.389994859695435, "x": 9.065789284002436, "y": -0.30016257569721105, "z": null, "yaw": 6.249338207195166, "pitch": null, "roll": null}, "v": 2.1650362377520476, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35512563099539785, "steering_wheel_angle": 0.26612240267350307, "front_wheel_angle": 0.012264367751761826, "heading_rate": 0.010372707815017174, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141164.781884} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25122533386287893, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0737080125480953, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.163981135591503, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.26612240267350307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141164.781884} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.389994859695435, "x": 9.065789284002436, "y": -0.30016257569721105, "z": null, "yaw": 6.249338207195166, "pitch": null, "roll": null}, "v": 2.1650362377520476, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35512563099539785, "steering_wheel_angle": 0.26612240267350307, "front_wheel_angle": 0.012264367751761826, "heading_rate": 0.010372707815017174, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141164.801884} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25122533386287893, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0737080125480953, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1632840835610185, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.26612240267350307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141164.801884} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.389994859695435, "x": 9.065789284002436, "y": -0.30016257569721105, "z": null, "yaw": 6.249338207195166, "pitch": null, "roll": null}, "v": 2.1650362377520476, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35512563099539785, "steering_wheel_angle": 0.26612240267350307, "front_wheel_angle": 0.012264367751761826, "heading_rate": 0.010372707815017174, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141164.821884} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25122533386287893, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0737080125480953, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1625883311934255, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.26612240267350307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141164.821884} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.389994859695435, "x": 9.065789284002436, "y": -0.30016257569721105, "z": null, "yaw": 6.249338207195166, "pitch": null, "roll": null}, "v": 2.1650362377520476, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35512563099539785, "steering_wheel_angle": 0.26612240267350307, "front_wheel_angle": 0.012264367751761826, "heading_rate": 0.010372707815017174, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141164.841884} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25122533386287893, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0737080125480953, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1618938758719466, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.26612240267350307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141164.841884} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141164.8618839, "x": 13.30361675957803, "y": 4.691841596633276, "z": null, "yaw": -0.03332008900891994, "pitch": null, "roll": null}, "v": 2.1612007149857653, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35476792105383814, "steering_wheel_angle": 0.26612240267350307, "front_wheel_angle": 0.012264367751761826, "heading_rate": 0.01035433179142978, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141164.8618839} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2532795992198489, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.126764902316098, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1612007149857653, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.26612240267350307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141164.8618839} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.49999475479126, "x": 9.30361675957803, "y": -0.30815840336672373, "z": null, "yaw": 6.249865218170666, "pitch": null, "roll": null}, "v": 2.1612007149857653, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35476792105383814, "steering_wheel_angle": 0.26612240267350307, "front_wheel_angle": 0.012264367751761826, "heading_rate": 0.01035433179142978, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141164.8818839} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.252274123028227, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.126764902316098, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.16076550941508, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.30707017938001563, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141164.8818839} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.49999475479126, "x": 9.30361675957803, "y": -0.30815840336672373, "z": null, "yaw": 6.249865218170666, "pitch": null, "roll": null}, "v": 2.1612007149857653, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35476792105383814, "steering_wheel_angle": 0.26612240267350307, "front_wheel_angle": 0.012264367751761826, "heading_rate": 0.01035433179142978, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141164.9018838} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.252274123028227, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.126764902316098, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.160205488893148, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.30707017938001563, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141164.9018838} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.49999475479126, "x": 9.30361675957803, "y": -0.30815840336672373, "z": null, "yaw": 6.249865218170666, "pitch": null, "roll": null}, "v": 2.1612007149857653, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35476792105383814, "steering_wheel_angle": 0.26612240267350307, "front_wheel_angle": 0.012264367751761826, "heading_rate": 0.01035433179142978, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141164.9218838} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.252274123028227, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.126764902316098, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1596465118403576, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.30707017938001563, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141164.9218838} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.49999475479126, "x": 9.30361675957803, "y": -0.30815840336672373, "z": null, "yaw": 6.249865218170666, "pitch": null, "roll": null}, "v": 2.1612007149857653, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35476792105383814, "steering_wheel_angle": 0.26612240267350307, "front_wheel_angle": 0.012264367751761826, "heading_rate": 0.01035433179142978, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141164.9418838} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.252274123028227, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.126764902316098, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.159088576187521, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.30707017938001563, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141164.9418838} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.49999475479126, "x": 9.30361675957803, "y": -0.30815840336672373, "z": null, "yaw": 6.249865218170666, "pitch": null, "roll": null}, "v": 2.1612007149857653, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35476792105383814, "steering_wheel_angle": 0.26612240267350307, "front_wheel_angle": 0.012264367751761826, "heading_rate": 0.01035433179142978, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141164.9618838} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.252274123028227, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.126764902316098, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1585316798700025, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.30707017938001563, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141164.9618838} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141164.9718838, "x": 13.541077106556024, "y": 4.683990596487919, "z": null, "yaw": -0.03271905042774731, "pitch": null, "roll": null}, "v": 2.1582536208180314, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.354493267958643, "steering_wheel_angle": 0.30707017938001563, "front_wheel_angle": 0.014159143117244418, "heading_rate": 0.01193791571695724, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141164.9818838} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2516820798304503, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1240808101964135, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1579758208277093, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.30707017938001563, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141164.9818838} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.609994649887085, "x": 9.541077106556024, "y": -0.31600940351208084, "z": null, "yaw": 6.250466256751839, "pitch": null, "roll": null}, "v": 2.1582536208180314, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.354493267958643, "steering_wheel_angle": 0.30707017938001563, "front_wheel_angle": 0.014159143117244418, "heading_rate": 0.01193791571695724, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141165.0018837} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2519430793429955, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1240808101964135, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.157347026074701, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.30707017938001563, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141165.0018837} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.609994649887085, "x": 9.541077106556024, "y": -0.31600940351208084, "z": null, "yaw": 6.250466256751839, "pitch": null, "roll": null}, "v": 2.1582536208180314, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.354493267958643, "steering_wheel_angle": 0.30707017938001563, "front_wheel_angle": 0.014159143117244418, "heading_rate": 0.01193791571695724, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141165.0218837} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2519430793429955, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1240808101964135, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.156752011967297, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.30707017938001563, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141165.0218837} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.609994649887085, "x": 9.541077106556024, "y": -0.31600940351208084, "z": null, "yaw": 6.250466256751839, "pitch": null, "roll": null}, "v": 2.1582536208180314, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.354493267958643, "steering_wheel_angle": 0.30707017938001563, "front_wheel_angle": 0.014159143117244418, "heading_rate": 0.01193791571695724, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141165.0418837} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2519430793429955, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1240808101964135, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.156158105712414, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.30707017938001563, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141165.0418837} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.609994649887085, "x": 9.541077106556024, "y": -0.31600940351208084, "z": null, "yaw": 6.250466256751839, "pitch": null, "roll": null}, "v": 2.1582536208180314, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.354493267958643, "steering_wheel_angle": 0.30707017938001563, "front_wheel_angle": 0.014159143117244418, "heading_rate": 0.01193791571695724, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141165.0618837} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2519430793429955, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1240808101964135, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.155565305106325, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.30707017938001563, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141165.0618837} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141165.0818837, "x": 13.77819574568042, "y": 4.676295160050941, "z": null, "yaw": -0.03211060908600748, "pitch": null, "roll": null}, "v": 2.1549736079501933, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35418779290712843, "steering_wheel_angle": 0.30707017938001563, "front_wheel_angle": 0.014159143117244418, "heading_rate": 0.011919773031227866, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141165.0818837} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25058403430548526, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.102897379194991, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1549736079501933, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.30707017938001563, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141165.0818837} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.71999454498291, "x": 9.77819574568042, "y": -0.32370483994905896, "z": null, "yaw": 6.2510746980935785, "pitch": null, "roll": null}, "v": 2.1549736079501933, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35418779290712843, "steering_wheel_angle": 0.30707017938001563, "front_wheel_angle": 0.014159143117244418, "heading_rate": 0.011919773031227866, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141165.1018836} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2512079246310828, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.102897379194991, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.154213210493616, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.30707017938001563, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141165.1018836} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.71999454498291, "x": 9.77819574568042, "y": -0.32370483994905896, "z": null, "yaw": 6.2510746980935785, "pitch": null, "roll": null}, "v": 2.1549736079501933, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35418779290712843, "steering_wheel_angle": 0.30707017938001563, "front_wheel_angle": 0.014159143117244418, "heading_rate": 0.011919773031227866, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141165.1218836} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2512079246310828, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.102897379194991, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.153532178053753, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.30707017938001563, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141165.1218836} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.71999454498291, "x": 9.77819574568042, "y": -0.32370483994905896, "z": null, "yaw": 6.2510746980935785, "pitch": null, "roll": null}, "v": 2.1549736079501933, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35418779290712843, "steering_wheel_angle": 0.30707017938001563, "front_wheel_angle": 0.014159143117244418, "heading_rate": 0.011919773031227866, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141165.1418836} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2512079246310828, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.102897379194991, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.152852412752878, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.30707017938001563, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141165.1418836} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.71999454498291, "x": 9.77819574568042, "y": -0.32370483994905896, "z": null, "yaw": 6.2510746980935785, "pitch": null, "roll": null}, "v": 2.1549736079501933, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35418779290712843, "steering_wheel_angle": 0.30707017938001563, "front_wheel_angle": 0.014159143117244418, "heading_rate": 0.011919773031227866, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141165.1618836} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2512079246310828, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.102897379194991, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.152173912048587, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.30707017938001563, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141165.1618836} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.71999454498291, "x": 9.77819574568042, "y": -0.32370483994905896, "z": null, "yaw": 6.2510746980935785, "pitch": null, "roll": null}, "v": 2.1549736079501933, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35418779290712843, "steering_wheel_angle": 0.30707017938001563, "front_wheel_angle": 0.014159143117244418, "heading_rate": 0.011919773031227866, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141165.1818836} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2512079246310828, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.102897379194991, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1514966734042376, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.30707017938001563, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141165.1818836} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141165.1918836, "x": 14.014928218008727, "y": 4.6687564401582575, "z": null, "yaw": -0.031502167744267645, "pitch": null, "roll": null}, "v": 2.151158526563411, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3538327563922352, "steering_wheel_angle": 0.30707017938001563, "front_wheel_angle": 0.014159143117244418, "heading_rate": 0.011898670729065865, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141165.2018836} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25341767301186885, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1554193771391752, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1508206942889316, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.30707017938001563, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141165.2018836} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.829994440078735, "x": 10.014928218008727, "y": -0.3312435598417425, "z": null, "yaw": 6.251683139435318, "pitch": null, "roll": null}, "v": 2.151158526563411, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3538327563922352, "steering_wheel_angle": 0.30707017938001563, "front_wheel_angle": 0.014159143117244418, "heading_rate": 0.011898670729065865, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141165.2218835} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.252338360937863, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1554193771391752, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1504220622682215, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.30707017938001563, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141165.2218835} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.829994440078735, "x": 10.014928218008727, "y": -0.3312435598417425, "z": null, "yaw": 6.251683139435318, "pitch": null, "roll": null}, "v": 2.151158526563411, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3538327563922352, "steering_wheel_angle": 0.30707017938001563, "front_wheel_angle": 0.014159143117244418, "heading_rate": 0.011898670729065865, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141165.2418835} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.252338360937863, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1554193771391752, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1498893201697302, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.30707017938001563, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141165.2418835} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.829994440078735, "x": 10.014928218008727, "y": -0.3312435598417425, "z": null, "yaw": 6.251683139435318, "pitch": null, "roll": null}, "v": 2.151158526563411, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3538327563922352, "steering_wheel_angle": 0.30707017938001563, "front_wheel_angle": 0.014159143117244418, "heading_rate": 0.011898670729065865, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141165.2618835} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.252338360937863, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1554193771391752, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1493575685155784, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.30707017938001563, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141165.2618835} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.829994440078735, "x": 10.014928218008727, "y": -0.3312435598417425, "z": null, "yaw": 6.251683139435318, "pitch": null, "roll": null}, "v": 2.151158526563411, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3538327563922352, "steering_wheel_angle": 0.30707017938001563, "front_wheel_angle": 0.014159143117244418, "heading_rate": 0.011898670729065865, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141165.2718835} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.252338360937863, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1554193771391752, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1488268053513355, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.30707017938001563, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141165.2718835} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141165.3018835, "x": 14.25129822224381, "y": 4.661373228727933, "z": null, "yaw": -0.030893726402527837, "pitch": null, "roll": null}, "v": 2.148297028726835, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35356665267270726, "steering_wheel_angle": 0.30707017938001563, "front_wheel_angle": 0.014159143117244418, "heading_rate": 0.011882842969219756, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141165.3018835} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2465015742801108, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1019574856539873, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.148297028726835, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.30707017938001563, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141165.3018835} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.9399943351745605, "x": 10.25129822224381, "y": -0.3386267712720672, "z": null, "yaw": 6.252291580777058, "pitch": null, "roll": null}, "v": 2.148297028726835, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35356665267270726, "steering_wheel_angle": 0.30707017938001563, "front_wheel_angle": 0.014159143117244418, "heading_rate": 0.011882842969219756, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141165.3218834} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24926072330729662, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1019574856539873, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1470389774703134, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.30707017938001563, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141165.3218834} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.9399943351745605, "x": 10.25129822224381, "y": -0.3386267712720672, "z": null, "yaw": 6.252291580777058, "pitch": null, "roll": null}, "v": 2.148297028726835, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35356665267270726, "steering_wheel_angle": 0.30707017938001563, "front_wheel_angle": 0.014159143117244418, "heading_rate": 0.011882842969219756, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141165.3418834} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24926072330729662, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1019574856539873, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1461279971442493, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.30707017938001563, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141165.3418834} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.9399943351745605, "x": 10.25129822224381, "y": -0.3386267712720672, "z": null, "yaw": 6.252291580777058, "pitch": null, "roll": null}, "v": 2.148297028726835, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35356665267270726, "steering_wheel_angle": 0.30707017938001563, "front_wheel_angle": 0.014159143117244418, "heading_rate": 0.011882842969219756, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141165.3618834} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24926072330729662, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1019574856539873, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1452187091270187, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.30707017938001563, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141165.3618834} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.9399943351745605, "x": 10.25129822224381, "y": -0.3386267712720672, "z": null, "yaw": 6.252291580777058, "pitch": null, "roll": null}, "v": 2.148297028726835, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35356665267270726, "steering_wheel_angle": 0.30707017938001563, "front_wheel_angle": 0.014159143117244418, "heading_rate": 0.011882842969219756, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141165.3818834} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24926072330729662, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1019574856539873, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1443111099442875, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.30707017938001563, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141165.3818834} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.9399943351745605, "x": 10.25129822224381, "y": -0.3386267712720672, "z": null, "yaw": 6.252291580777058, "pitch": null, "roll": null}, "v": 2.148297028726835, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35356665267270726, "steering_wheel_angle": 0.30707017938001563, "front_wheel_angle": 0.014159143117244418, "heading_rate": 0.011882842969219756, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141165.4018834} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24926072330729662, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1019574856539873, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.143405196130016, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.30707017938001563, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141165.4018834} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141165.4118834, "x": 14.48721705600599, "y": 4.6541477766552015, "z": null, "yaw": -0.030285285060788043, "pitch": null, "roll": null}, "v": 2.142952870155177, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.353070113544822, "steering_wheel_angle": 0.30707017938001563, "front_wheel_angle": 0.014159143117244418, "heading_rate": 0.01185328290547603, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141165.4218833} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25213030208231924, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1564426410604187, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1425009642264348, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.30707017938001563, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141165.4218833} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.049994230270386, "x": 10.48721705600599, "y": -0.3458522233447985, "z": null, "yaw": 6.252900022118798, "pitch": null, "roll": null}, "v": 2.142952870155177, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.353070113544822, "steering_wheel_angle": 0.30707017938001563, "front_wheel_angle": 0.014159143117244418, "heading_rate": 0.01185328290547603, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141165.4418833} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.250726003744866, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1564426410604187, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1419569416186013, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.30707017938001563, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141165.4418833} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.049994230270386, "x": 10.48721705600599, "y": -0.3458522233447985, "z": null, "yaw": 6.252900022118798, "pitch": null, "roll": null}, "v": 2.142952870155177, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.353070113544822, "steering_wheel_angle": 0.30707017938001563, "front_wheel_angle": 0.014159143117244418, "heading_rate": 0.01185328290547603, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141165.4618833} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.250726003744866, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1564426410604187, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.141238472889195, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.30707017938001563, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141165.4618833} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.049994230270386, "x": 10.48721705600599, "y": -0.3458522233447985, "z": null, "yaw": 6.252900022118798, "pitch": null, "roll": null}, "v": 2.142952870155177, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.353070113544822, "steering_wheel_angle": 0.30707017938001563, "front_wheel_angle": 0.014159143117244418, "heading_rate": 0.01185328290547603, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141165.4818833} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.250726003744866, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1564426410604187, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.140521337426203, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.30707017938001563, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141165.4818833} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.049994230270386, "x": 10.48721705600599, "y": -0.3458522233447985, "z": null, "yaw": 6.252900022118798, "pitch": null, "roll": null}, "v": 2.142952870155177, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.353070113544822, "steering_wheel_angle": 0.30707017938001563, "front_wheel_angle": 0.014159143117244418, "heading_rate": 0.01185328290547603, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141165.5018833} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.250726003744866, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1564426410604187, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.139805532549859, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.30707017938001563, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141165.5018833} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141165.5218832, "x": 14.722643944495465, "y": 4.647080774353003, "z": null, "yaw": -0.02967684371904825, "pitch": null, "roll": null}, "v": 2.1390910555865106, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35271165822022765, "steering_wheel_angle": 0.30707017938001563, "front_wheel_angle": 0.014159143117244418, "heading_rate": 0.011831922108769577, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141165.5218832} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2530667233860946, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2152352292701474, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1390910555865106, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.30707017938001563, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141165.5218832} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.159994125366211, "x": 10.722643944495465, "y": -0.35291922564699707, "z": null, "yaw": 6.253508463460538, "pitch": null, "roll": null}, "v": 2.1390910555865106, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35271165822022765, "steering_wheel_angle": 0.30707017938001563, "front_wheel_angle": 0.014159143117244418, "heading_rate": 0.011831922108769577, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141165.5418832} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2519247835331868, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2152352292701474, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.138670358096914, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3890340880600119, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141165.5418832} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.159994125366211, "x": 10.722643944495465, "y": -0.35291922564699707, "z": null, "yaw": 6.253508463460538, "pitch": null, "roll": null}, "v": 2.1390910555865106, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35271165822022765, "steering_wheel_angle": 0.30707017938001563, "front_wheel_angle": 0.014159143117244418, "heading_rate": 0.011831922108769577, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141165.5618832} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2519247835331868, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2152352292701474, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1381077645821183, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3890340880600119, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141165.5618832} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.159994125366211, "x": 10.722643944495465, "y": -0.35291922564699707, "z": null, "yaw": 6.253508463460538, "pitch": null, "roll": null}, "v": 2.1390910555865106, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35271165822022765, "steering_wheel_angle": 0.30707017938001563, "front_wheel_angle": 0.014159143117244418, "heading_rate": 0.011831922108769577, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141165.5818832} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2519247835331868, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2152352292701474, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.137546214362597, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3890340880600119, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141165.5818832} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.159994125366211, "x": 10.722643944495465, "y": -0.35291922564699707, "z": null, "yaw": 6.253508463460538, "pitch": null, "roll": null}, "v": 2.1390910555865106, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35271165822022765, "steering_wheel_angle": 0.30707017938001563, "front_wheel_angle": 0.014159143117244418, "heading_rate": 0.011831922108769577, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141165.6018832} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2519247835331868, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2152352292701474, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1369857053775463, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3890340880600119, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141165.6018832} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.159994125366211, "x": 10.722643944495465, "y": -0.35291922564699707, "z": null, "yaw": 6.253508463460538, "pitch": null, "roll": null}, "v": 2.1390910555865106, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35271165822022765, "steering_wheel_angle": 0.30707017938001563, "front_wheel_angle": 0.014159143117244418, "heading_rate": 0.011831922108769577, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141165.6218832} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2519247835331868, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2152352292701474, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.136426235570684, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3890340880600119, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141165.6218832} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141165.6318831, "x": 14.957701644172095, "y": 4.6401808569527185, "z": null, "yaw": -0.028927390151915, "pitch": null, "roll": null}, "v": 2.136146889717719, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35243857983039284, "steering_wheel_angle": 0.3890340880600119, "front_wheel_angle": 0.017958073201871236, "heading_rate": 0.014986408776010098, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141165.6418831} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2508261437183973, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.224878178067688, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1358678028902394, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3890340880600119, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141165.6418831} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.269994020462036, "x": 10.957701644172095, "y": -0.35981914304728146, "z": null, "yaw": 6.2542579170276715, "pitch": null, "roll": null}, "v": 2.136146889717719, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35243857983039284, "steering_wheel_angle": 0.3890340880600119, "front_wheel_angle": 0.017958073201871236, "heading_rate": 0.014986408776010098, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141165.661883} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2513284998133537, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.224878178067688, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1351731389721538, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3890340880600119, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141165.661883} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.269994020462036, "x": 10.957701644172095, "y": -0.35981914304728146, "z": null, "yaw": 6.2542579170276715, "pitch": null, "roll": null}, "v": 2.136146889717719, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35243857983039284, "steering_wheel_angle": 0.3890340880600119, "front_wheel_angle": 0.017958073201871236, "heading_rate": 0.014986408776010098, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141165.681883} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2513284998133537, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.224878178067688, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1345425278679313, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3890340880600119, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141165.681883} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.269994020462036, "x": 10.957701644172095, "y": -0.35981914304728146, "z": null, "yaw": 6.2542579170276715, "pitch": null, "roll": null}, "v": 2.136146889717719, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35243857983039284, "steering_wheel_angle": 0.3890340880600119, "front_wheel_angle": 0.017958073201871236, "heading_rate": 0.014986408776010098, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141165.701883} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2513284998133537, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.224878178067688, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1339130852992545, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3890340880600119, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141165.701883} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.269994020462036, "x": 10.957701644172095, "y": -0.35981914304728146, "z": null, "yaw": 6.2542579170276715, "pitch": null, "roll": null}, "v": 2.136146889717719, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35243857983039284, "steering_wheel_angle": 0.3890340880600119, "front_wheel_angle": 0.017958073201871236, "heading_rate": 0.014986408776010098, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141165.721883} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2513284998133537, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.224878178067688, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.133284808942397, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3890340880600119, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141165.721883} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141165.741883, "x": 15.192406810504824, "y": 4.633471928258614, "z": null, "yaw": -0.028155671234411643, "pitch": null, "roll": null}, "v": 2.1326576964788173, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35211517332744424, "steering_wheel_angle": 0.3890340880600119, "front_wheel_angle": 0.017958073201871236, "heading_rate": 0.014961929899380232, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141165.741883} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2445773480316368, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1414863460699503, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1326576964788173, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3890340880600119, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141165.741883} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.379993915557861, "x": 11.192406810504824, "y": -0.3665280717413859, "z": null, "yaw": 6.255029635945174, "pitch": null, "roll": null}, "v": 2.1326576964788173, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35211517332744424, "steering_wheel_angle": 0.3890340880600119, "front_wheel_angle": 0.017958073201871236, "heading_rate": 0.014961929899380232, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141165.761883} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24776754331158593, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1414863460699503, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1311882425253956, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3890340880600119, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141165.761883} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.379993915557861, "x": 11.192406810504824, "y": -0.3665280717413859, "z": null, "yaw": 6.255029635945174, "pitch": null, "roll": null}, "v": 2.1326576964788173, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35211517332744424, "steering_wheel_angle": 0.3890340880600119, "front_wheel_angle": 0.017958073201871236, "heading_rate": 0.014961929899380232, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141165.781883} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24776754331158593, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1414863460699503, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.130120099409624, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3890340880600119, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141165.781883} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.379993915557861, "x": 11.192406810504824, "y": -0.3665280717413859, "z": null, "yaw": 6.255029635945174, "pitch": null, "roll": null}, "v": 2.1326576964788173, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35211517332744424, "steering_wheel_angle": 0.3890340880600119, "front_wheel_angle": 0.017958073201871236, "heading_rate": 0.014961929899380232, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141165.801883} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24776754331158593, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1414863460699503, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1290539337443017, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3890340880600119, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141165.801883} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.379993915557861, "x": 11.192406810504824, "y": -0.3665280717413859, "z": null, "yaw": 6.255029635945174, "pitch": null, "roll": null}, "v": 2.1326576964788173, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35211517332744424, "steering_wheel_angle": 0.3890340880600119, "front_wheel_angle": 0.017958073201871236, "heading_rate": 0.014961929899380232, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141165.821883} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24776754331158593, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1414863460699503, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1279897414141065, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3890340880600119, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141165.821883} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.379993915557861, "x": 11.192406810504824, "y": -0.3665280717413859, "z": null, "yaw": 6.255029635945174, "pitch": null, "roll": null}, "v": 2.1326576964788173, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35211517332744424, "steering_wheel_angle": 0.3890340880600119, "front_wheel_angle": 0.017958073201871236, "heading_rate": 0.014961929899380232, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141165.841883} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24776754331158593, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1414863460699503, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1269275183138574, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3890340880600119, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141165.841883} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141165.851883, "x": 15.426577059761073, "y": 4.626959128691955, "z": null, "yaw": -0.027383952316908287, "pitch": null, "roll": null}, "v": 2.1263971439448586, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35153550533501143, "steering_wheel_angle": 0.3890340880600119, "front_wheel_angle": 0.017958073201871236, "heading_rate": 0.014918008200975875, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141165.861883} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2512791087525388, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1956435915685504, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1258672603484827, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3890340880600119, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141165.861883} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.4899938106536865, "x": 11.426577059761073, "y": -0.37304087130804486, "z": null, "yaw": 6.255801354862678, "pitch": null, "roll": null}, "v": 2.1263971439448586, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35153550533501143, "steering_wheel_angle": 0.3890340880600119, "front_wheel_angle": 0.017958073201871236, "heading_rate": 0.014918008200975875, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141165.881883} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24956276869527474, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1956435915685504, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1252477060810855, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3890340880600119, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141165.881883} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.4899938106536865, "x": 11.426577059761073, "y": -0.37304087130804486, "z": null, "yaw": 6.255801354862678, "pitch": null, "roll": null}, "v": 2.1263971439448586, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35153550533501143, "steering_wheel_angle": 0.3890340880600119, "front_wheel_angle": 0.017958073201871236, "heading_rate": 0.014918008200975875, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141165.901883} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24956276869527474, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1956435915685504, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1244148542749524, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3890340880600119, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141165.901883} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.4899938106536865, "x": 11.426577059761073, "y": -0.37304087130804486, "z": null, "yaw": 6.255801354862678, "pitch": null, "roll": null}, "v": 2.1263971439448586, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35153550533501143, "steering_wheel_angle": 0.3890340880600119, "front_wheel_angle": 0.017958073201871236, "heading_rate": 0.014918008200975875, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141165.9218829} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24956276869527474, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1956435915685504, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.123583542406628, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3890340880600119, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141165.9218829} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.4899938106536865, "x": 11.426577059761073, "y": -0.37304087130804486, "z": null, "yaw": 6.255801354862678, "pitch": null, "roll": null}, "v": 2.1263971439448586, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35153550533501143, "steering_wheel_angle": 0.3890340880600119, "front_wheel_angle": 0.017958073201871236, "heading_rate": 0.014918008200975875, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141165.9418828} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24956276869527474, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1956435915685504, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1227537673524735, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3890340880600119, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141165.9418828} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141165.9618828, "x": 15.660173268276314, "y": 4.620642712785377, "z": null, "yaw": -0.026612233399404932, "pitch": null, "roll": null}, "v": 2.121925525996156, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3511219556785484, "steering_wheel_angle": 0.3890340880600119, "front_wheel_angle": 0.017958073201871236, "heading_rate": 0.014886636999495315, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141165.9618828} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25246477865390154, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.253577604999428, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.121925525996156, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3890340880600119, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141165.9618828} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.599993705749512, "x": 11.660173268276314, "y": -0.37935728721462336, "z": null, "yaw": 6.2565730737801815, "pitch": null, "roll": null}, "v": 2.121925525996156, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3511219556785484, "steering_wheel_angle": 0.3890340880600119, "front_wheel_angle": 0.017958073201871236, "heading_rate": 0.014886636999495315, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141165.9818828} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2510513598984748, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.253577604999428, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.121461398824246, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.42999280577628485, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141165.9818828} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.599993705749512, "x": 11.660173268276314, "y": -0.37935728721462336, "z": null, "yaw": 6.2565730737801815, "pitch": null, "roll": null}, "v": 2.121925525996156, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3511219556785484, "steering_wheel_angle": 0.3890340880600119, "front_wheel_angle": 0.017958073201871236, "heading_rate": 0.014886636999495315, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141166.0018828} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2510513598984748, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.253577604999428, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.120821533557129, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.42999280577628485, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141166.0018828} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.599993705749512, "x": 11.660173268276314, "y": -0.37935728721462336, "z": null, "yaw": 6.2565730737801815, "pitch": null, "roll": null}, "v": 2.121925525996156, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3511219556785484, "steering_wheel_angle": 0.3890340880600119, "front_wheel_angle": 0.017958073201871236, "heading_rate": 0.014886636999495315, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141166.0218828} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2510513598984748, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.253577604999428, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.120182850465722, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.42999280577628485, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141166.0218828} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.599993705749512, "x": 11.660173268276314, "y": -0.37935728721462336, "z": null, "yaw": 6.2565730737801815, "pitch": null, "roll": null}, "v": 2.121925525996156, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3511219556785484, "steering_wheel_angle": 0.3890340880600119, "front_wheel_angle": 0.017958073201871236, "heading_rate": 0.014886636999495315, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141166.0418828} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2510513598984748, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.253577604999428, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1195453472028185, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.42999280577628485, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141166.0418828} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.599993705749512, "x": 11.660173268276314, "y": -0.37935728721462336, "z": null, "yaw": 6.2565730737801815, "pitch": null, "roll": null}, "v": 2.121925525996156, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3511219556785484, "steering_wheel_angle": 0.3890340880600119, "front_wheel_angle": 0.017958073201871236, "heading_rate": 0.014886636999495315, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141166.0618827} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2510513598984748, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.253577604999428, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1189090214264525, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.42999280577628485, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141166.0618827} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141166.0718827, "x": 15.893345752174335, "y": 4.6145249231585295, "z": null, "yaw": -0.025766210225430436, "pitch": null, "roll": null}, "v": 2.118591299365286, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3508138559057272, "steering_wheel_angle": 0.42999280577628485, "front_wheel_angle": 0.01985958155924378, "heading_rate": 0.0164374488233668, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141166.0818827} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2536905628896164, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3145118942073362, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.118273870799883, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.42999280577628485, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141166.0818827} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.709993600845337, "x": 11.893345752174335, "y": -0.38547507684147053, "z": null, "yaw": 6.257419096954155, "pitch": null, "roll": null}, "v": 2.118591299365286, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3508138559057272, "steering_wheel_angle": 0.42999280577628485, "front_wheel_angle": 0.01985958155924378, "heading_rate": 0.0164374488233668, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141166.1018827} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25241032465256097, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3145118942073362, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.117969641016189, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141166.1018827} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.709993600845337, "x": 11.893345752174335, "y": -0.38547507684147053, "z": null, "yaw": 6.257419096954155, "pitch": null, "roll": null}, "v": 2.118591299365286, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3508138559057272, "steering_wheel_angle": 0.42999280577628485, "front_wheel_angle": 0.01985958155924378, "heading_rate": 0.0164374488233668, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141166.1218827} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25241032465256097, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3145118942073362, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.117506017070356, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141166.1218827} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.709993600845337, "x": 11.893345752174335, "y": -0.38547507684147053, "z": null, "yaw": 6.257419096954155, "pitch": null, "roll": null}, "v": 2.118591299365286, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3508138559057272, "steering_wheel_angle": 0.42999280577628485, "front_wheel_angle": 0.01985958155924378, "heading_rate": 0.0164374488233668, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141166.1418827} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25241032465256097, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3145118942073362, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.117043249065148, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141166.1418827} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.709993600845337, "x": 11.893345752174335, "y": -0.38547507684147053, "z": null, "yaw": 6.257419096954155, "pitch": null, "roll": null}, "v": 2.118591299365286, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3508138559057272, "steering_wheel_angle": 0.42999280577628485, "front_wheel_angle": 0.01985958155924378, "heading_rate": 0.0164374488233668, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141166.1618826} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25241032465256097, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3145118942073362, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.116581335334708, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141166.1618826} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141166.1818826, "x": 16.12619350595814, "y": 4.608620035205706, "z": null, "yaw": -0.02484576304883087, "pitch": null, "roll": null}, "v": 2.1161202742167298, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3505856638603474, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017993459917880584, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141166.1818826} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2516820484147226, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2733980736726345, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1161202742167298, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141166.1818826} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.819993495941162, "x": 12.126193505958138, "y": -0.39137996479429393, "z": null, "yaw": 6.258339544130755, "pitch": null, "roll": null}, "v": 2.1161202742167298, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3505856638603474, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017993459917880584, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141166.2018826} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2520114607271725, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2733980736726345, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.115569071543048, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141166.2018826} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.819993495941162, "x": 12.126193505958138, "y": -0.39137996479429393, "z": null, "yaw": 6.258339544130755, "pitch": null, "roll": null}, "v": 2.1161202742167298, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3505856638603474, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017993459917880584, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141166.2218826} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2520114607271725, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2733980736726345, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.11506004361047, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141166.2218826} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.819993495941162, "x": 12.126193505958138, "y": -0.39137996479429393, "z": null, "yaw": 6.258339544130755, "pitch": null, "roll": null}, "v": 2.1161202742167298, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3505856638603474, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017993459917880584, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141166.2418826} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2520114607271725, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2733980736726345, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.114551954947913, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141166.2418826} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.819993495941162, "x": 12.126193505958138, "y": -0.39137996479429393, "z": null, "yaw": 6.258339544130755, "pitch": null, "roll": null}, "v": 2.1161202742167298, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3505856638603474, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017993459917880584, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141166.2618825} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2520114607271725, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2733980736726345, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.114044803719, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141166.2618825} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.819993495941162, "x": 12.126193505958138, "y": -0.39137996479429393, "z": null, "yaw": 6.258339544130755, "pitch": null, "roll": null}, "v": 2.1161202742167298, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3505856638603474, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017993459917880584, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141166.2818825} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2520114607271725, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2733980736726345, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1135385880913145, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141166.2818825} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141166.2918825, "x": 16.35875352870449, "y": 4.6029396241137, "z": null, "yaw": -0.023910428410680647, "pitch": null, "roll": null}, "v": 2.113285830556382, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3503240615441229, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017969358523922323, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141166.3018825} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25365397574703347, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3030017833499128, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1130333062363893, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141166.3018825} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.929993391036987, "x": 12.35875352870449, "y": -0.3970603758862996, "z": null, "yaw": 6.259274878768905, "pitch": null, "roll": null}, "v": 2.113285830556382, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3503240615441229, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017969358523922323, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141166.3218825} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25285189373185524, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3030017833499128, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1127341759990985, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141166.3218825} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.929993391036987, "x": 12.35875352870449, "y": -0.3970603758862996, "z": null, "yaw": 6.259274878768905, "pitch": null, "roll": null}, "v": 2.113285830556382, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3503240615441229, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017969358523922323, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141166.3418825} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25285189373185524, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3030017833499128, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1123353834332144, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141166.3418825} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.929993391036987, "x": 12.35875352870449, "y": -0.3970603758862996, "z": null, "yaw": 6.259274878768905, "pitch": null, "roll": null}, "v": 2.113285830556382, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3503240615441229, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017969358523922323, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141166.3618824} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25285189373185524, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3030017833499128, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1119373262899006, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141166.3618824} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.929993391036987, "x": 12.35875352870449, "y": -0.3970603758862996, "z": null, "yaw": 6.259274878768905, "pitch": null, "roll": null}, "v": 2.113285830556382, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3503240615441229, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017969358523922323, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141166.3818824} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25285189373185524, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3030017833499128, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.111540003149597, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141166.3818824} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141166.4018824, "x": 16.591044452554264, "y": 4.5974831864051335, "z": null, "yaw": -0.022975093772530424, "pitch": null, "roll": null}, "v": 2.1111434125957107, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35012643571524815, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017951141453667677, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141166.4018824} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2529514612015999, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.280475206790926, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1111434125957107, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141166.4018824} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.0399932861328125, "x": 12.591044452554264, "y": -0.40251681359486646, "z": null, "yaw": 6.260210213407055, "pitch": null, "roll": null}, "v": 2.1111434125957107, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35012643571524815, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017951141453667677, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141166.4218824} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25288899088355293, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.280475206790926, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1107599934095735, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141166.4218824} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.0399932861328125, "x": 12.591044452554264, "y": -0.40251681359486646, "z": null, "yaw": 6.260210213407055, "pitch": null, "roll": null}, "v": 2.1111434125957107, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35012643571524815, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017951141453667677, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141166.4418824} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25288899088355293, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.280475206790926, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1103694758641605, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141166.4418824} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.0399932861328125, "x": 12.591044452554264, "y": -0.40251681359486646, "z": null, "yaw": 6.260210213407055, "pitch": null, "roll": null}, "v": 2.1111434125957107, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35012643571524815, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017951141453667677, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141166.4618824} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25288899088355293, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.280475206790926, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1099796781740334, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141166.4618824} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.0399932861328125, "x": 12.591044452554264, "y": -0.40251681359486646, "z": null, "yaw": 6.260210213407055, "pitch": null, "roll": null}, "v": 2.1111434125957107, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35012643571524815, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017951141453667677, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141166.4818823} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25288899088355293, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.280475206790926, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.109590598951508, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141166.4818823} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.0399932861328125, "x": 12.591044452554264, "y": -0.40251681359486646, "z": null, "yaw": 6.260210213407055, "pitch": null, "roll": null}, "v": 2.1111434125957107, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35012643571524815, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017951141453667677, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141166.5018823} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25288899088355293, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.280475206790926, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1092022368117926, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141166.5018823} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141166.5118823, "x": 16.823104605163135, "y": 4.592249338149462, "z": null, "yaw": -0.0220397591343802, "pitch": null, "roll": null}, "v": 2.1090083242160316, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34992957732692676, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017932986707149257, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141166.5218823} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25272032523394794, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2344324602949779, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1088145903729845, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141166.5218823} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.149993181228638, "x": 12.823104605163135, "y": -0.407750661850538, "z": null, "yaw": 6.261145548045206, "pitch": null, "roll": null}, "v": 2.1090083242160316, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34992957732692676, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017932986707149257, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141166.5418823} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25278564350823135, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2344324602949779, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.108406584766298, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141166.5418823} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.149993181228638, "x": 12.823104605163135, "y": -0.407750661850538, "z": null, "yaw": 6.261145548045206, "pitch": null, "roll": null}, "v": 2.1090083242160316, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34992957732692676, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017932986707149257, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141166.5618823} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25278564350823135, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2344324602949779, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.108007491953727, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141166.5618823} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.149993181228638, "x": 12.823104605163135, "y": -0.407750661850538, "z": null, "yaw": 6.261145548045206, "pitch": null, "roll": null}, "v": 2.1090083242160316, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34992957732692676, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017932986707149257, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141166.5818822} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25278564350823135, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2344324602949779, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.107609134427175, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141166.5818822} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.149993181228638, "x": 12.823104605163135, "y": -0.407750661850538, "z": null, "yaw": 6.261145548045206, "pitch": null, "roll": null}, "v": 2.1090083242160316, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34992957732692676, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017932986707149257, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141166.6018822} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25278564350823135, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2344324602949779, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.107211510768509, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141166.6018822} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141166.6218822, "x": 17.05493149711031, "y": 4.587237691797768, "z": null, "yaw": -0.021104424496229977, "pitch": null, "roll": null}, "v": 2.1068146195625608, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34972740939015345, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017914333543983238, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141166.6218822} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2550255097742682, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2791377909139146, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1068146195625608, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141166.6218822} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.259993076324463, "x": 13.05493149711031, "y": -0.4127623082022316, "z": null, "yaw": 6.262080882683356, "pitch": null, "roll": null}, "v": 2.1068146195625608, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34972740939015345, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017914333543983238, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141166.6418822} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2539435029785583, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2791377909139146, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1066983137008517, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141166.6418822} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.259993076324463, "x": 13.05493149711031, "y": -0.4127623082022316, "z": null, "yaw": 6.262080882683356, "pitch": null, "roll": null}, "v": 2.1068146195625608, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34972740939015345, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017914333543983238, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141166.6618822} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2539435029785583, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2791377909139146, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1064470335114525, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141166.6618822} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.259993076324463, "x": 13.05493149711031, "y": -0.4127623082022316, "z": null, "yaw": 6.262080882683356, "pitch": null, "roll": null}, "v": 2.1068146195625608, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34972740939015345, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017914333543983238, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141166.6818821} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2539435029785583, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2791377909139146, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.106196216118638, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141166.6818821} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.259993076324463, "x": 13.05493149711031, "y": -0.4127623082022316, "z": null, "yaw": 6.262080882683356, "pitch": null, "roll": null}, "v": 2.1068146195625608, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34972740939015345, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017914333543983238, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141166.7018821} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2539435029785583, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2791377909139146, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1059458606448977, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141166.7018821} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.259993076324463, "x": 13.05493149711031, "y": -0.4127623082022316, "z": null, "yaw": 6.262080882683356, "pitch": null, "roll": null}, "v": 2.1068146195625608, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34972740939015345, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017914333543983238, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141166.721882} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2539435029785583, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2791377909139146, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1056959662144763, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141166.721882} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141166.731882, "x": 17.28657535517179, "y": 4.582446771498333, "z": null, "yaw": -0.020169089858079754, "pitch": null, "roll": null}, "v": 2.1055711916173157, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3496128600105534, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017903760623735675, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141166.741882} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2535099954216356, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.230810640191766, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.10544653195337, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141166.741882} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.369992971420288, "x": 13.286575355171792, "y": -0.4175532285016672, "z": null, "yaw": 6.263016217321506, "pitch": null, "roll": null}, "v": 2.1055711916173157, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3496128600105534, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017903760623735675, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141166.761882} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25370770011858185, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.230810640191766, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.105143393500157, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141166.761882} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.369992971420288, "x": 13.286575355171792, "y": -0.4175532285016672, "z": null, "yaw": 6.263016217321506, "pitch": null, "roll": null}, "v": 2.1055711916173157, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3496128600105534, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017903760623735675, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141166.781882} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25370770011858185, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.230810640191766, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.104865514904143, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141166.781882} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.369992971420288, "x": 13.286575355171792, "y": -0.4175532285016672, "z": null, "yaw": 6.263016217321506, "pitch": null, "roll": null}, "v": 2.1055711916173157, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3496128600105534, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017903760623735675, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141166.801882} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25370770011858185, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.230810640191766, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1045881479175783, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141166.801882} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.369992971420288, "x": 13.286575355171792, "y": -0.4175532285016672, "z": null, "yaw": 6.263016217321506, "pitch": null, "roll": null}, "v": 2.1055711916173157, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3496128600105534, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017903760623735675, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141166.821882} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25370770011858185, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.230810640191766, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1043112915677673, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141166.821882} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141166.841882, "x": 17.518065967346864, "y": 4.577875628124675, "z": null, "yaw": -0.01923375521992953, "pitch": null, "roll": null}, "v": 2.1040349448839737, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3494713777371278, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01789069785298622, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141166.841882} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25582048742829716, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2807502495764689, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1040349448839737, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141166.841882} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.479992866516113, "x": 13.518065967346864, "y": -0.42212437187532537, "z": null, "yaw": 6.263951551959657, "pitch": null, "roll": null}, "v": 2.1040349448839737, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3494713777371278, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01789069785298622, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141166.861882} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2548036181234392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2807502495764689, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.104023083721201, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141166.861882} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.479992866516113, "x": 13.518065967346864, "y": -0.42212437187532537, "z": null, "yaw": 6.263951551959657, "pitch": null, "roll": null}, "v": 2.1040349448839737, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3494713777371278, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01789069785298622, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141166.881882} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2548036181234392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2807502495764689, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.103884194249548, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141166.881882} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.479992866516113, "x": 13.518065967346864, "y": -0.42212437187532537, "z": null, "yaw": 6.263951551959657, "pitch": null, "roll": null}, "v": 2.1040349448839737, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3494713777371278, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01789069785298622, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141166.901882} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2548036181234392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2807502495764689, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1037455604344855, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141166.901882} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.479992866516113, "x": 13.518065967346864, "y": -0.42212437187532537, "z": null, "yaw": 6.263951551959657, "pitch": null, "roll": null}, "v": 2.1040349448839737, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3494713777371278, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01789069785298622, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141166.921882} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2548036181234392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2807502495764689, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1036071817977375, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141166.921882} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.479992866516113, "x": 13.518065967346864, "y": -0.42212437187532537, "z": null, "yaw": 6.263951551959657, "pitch": null, "roll": null}, "v": 2.1040349448839737, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3494713777371278, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01789069785298622, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141166.941882} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2548036181234392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2807502495764689, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1034690578619504, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141166.941882} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141166.951882, "x": 17.74944278563942, "y": 4.573523234402353, "z": null, "yaw": -0.018298420581779308, "pitch": null, "roll": null}, "v": 2.103400091257996, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3494129240019413, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01788529966583593, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141166.9618819} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25571807194998436, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2762474985851562, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1033311881506913, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141166.9618819} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.5899927616119385, "x": 13.74944278563942, "y": -0.4264767655976467, "z": null, "yaw": 6.264886886597807, "pitch": null, "roll": null}, "v": 2.103400091257996, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3494129240019413, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01788529966583593, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141166.9818819} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25527816390919533, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2762474985851562, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1033078262980527, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141166.9818819} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.5899927616119385, "x": 13.74944278563942, "y": -0.4264767655976467, "z": null, "yaw": 6.264886886597807, "pitch": null, "roll": null}, "v": 2.103400091257996, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3494129240019413, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01788529966583593, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141167.0018818} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25527816390919533, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2762474985851562, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1032295442500497, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141167.0018818} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.5899927616119385, "x": 13.74944278563942, "y": -0.4264767655976467, "z": null, "yaw": 6.264886886597807, "pitch": null, "roll": null}, "v": 2.103400091257996, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3494129240019413, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01788529966583593, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141167.0218818} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25527816390919533, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2762474985851562, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1031514062764023, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141167.0218818} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.5899927616119385, "x": 13.74944278563942, "y": -0.4264767655976467, "z": null, "yaw": 6.264886886597807, "pitch": null, "roll": null}, "v": 2.103400091257996, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3494129240019413, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01788529966583593, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141167.0418818} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25527816390919533, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2762474985851562, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1030734121095085, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141167.0418818} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141167.0618818, "x": 17.9807600142712, "y": 4.569388395874351, "z": null, "yaw": -0.017363085943629085, "pitch": null, "roll": null}, "v": 2.1029955614822704, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3493756813902548, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01788185993209593, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141167.0618818} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2559172319793216, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2735050417308638, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1029955614822704, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141167.0618818} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.699992656707764, "x": 13.980760014271201, "y": -0.4306116041256489, "z": null, "yaw": 6.265822221235958, "pitch": null, "roll": null}, "v": 2.1029955614822704, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3493756813902548, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01788185993209593, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141167.0818818} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2556100761649333, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2735050417308638, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1029977008666694, "gear": 1, "accelerator_pedal_position": 0.2559172319793216, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141167.0818818} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.699992656707764, "x": 13.980760014271201, "y": -0.4306116041256489, "z": null, "yaw": 6.265822221235958, "pitch": null, "roll": null}, "v": 2.1029955614822704, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3493756813902548, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01788185993209593, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141167.1018817} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2556100761649333, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2735050417308638, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1029614595099866, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141167.1018817} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.699992656707764, "x": 13.980760014271201, "y": -0.4306116041256489, "z": null, "yaw": 6.265822221235958, "pitch": null, "roll": null}, "v": 2.1029955614822704, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3493756813902548, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01788185993209593, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141167.1218817} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2556100761649333, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2735050417308638, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.102925284849748, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141167.1218817} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.699992656707764, "x": 13.980760014271201, "y": -0.4306116041256489, "z": null, "yaw": 6.265822221235958, "pitch": null, "roll": null}, "v": 2.1029955614822704, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3493756813902548, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01788185993209593, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141167.1418817} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2556100761649333, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2735050417308638, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.102889176762687, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141167.1418817} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.699992656707764, "x": 13.980760014271201, "y": -0.4306116041256489, "z": null, "yaw": 6.265822221235958, "pitch": null, "roll": null}, "v": 2.1029955614822704, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3493756813902548, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01788185993209593, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141167.1618817} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2556100761649333, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2735050417308638, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.102853135125765, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141167.1618817} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141167.1718817, "x": 18.212050026665914, "y": 4.565470444799063, "z": null, "yaw": -0.016427751305478862, "pitch": null, "roll": null}, "v": 2.1028351391877194, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34936091318541235, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01788049585456116, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141167.1818817} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25580298794887757, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.241773547249341, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1028171598161736, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141167.1818817} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.809992551803589, "x": 14.212050026665914, "y": -0.43452955520093717, "z": null, "yaw": 6.266757555874108, "pitch": null, "roll": null}, "v": 2.1028351391877194, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34936091318541235, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01788049585456116, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141167.2018816} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25570999995160737, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.241773547249341, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1028053535851345, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141167.2018816} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.809992551803589, "x": 14.212050026665914, "y": -0.43452955520093717, "z": null, "yaw": 6.266757555874108, "pitch": null, "roll": null}, "v": 2.1028351391877194, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34936091318541235, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01788049585456116, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141167.2218816} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25570999995160737, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.241773547249341, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.10278195093122, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141167.2218816} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.809992551803589, "x": 14.212050026665914, "y": -0.43452955520093717, "z": null, "yaw": 6.266757555874108, "pitch": null, "roll": null}, "v": 2.1028351391877194, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34936091318541235, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01788049585456116, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141167.2418816} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25570999995160737, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.241773547249341, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.102758591344453, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141167.2418816} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.809992551803589, "x": 14.212050026665914, "y": -0.43452955520093717, "z": null, "yaw": 6.266757555874108, "pitch": null, "roll": null}, "v": 2.1028351391877194, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34936091318541235, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01788049585456116, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141167.2618816} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25570999995160737, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.241773547249341, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.102735274745361, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141167.2618816} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.809992551803589, "x": 14.212050026665914, "y": -0.43452955520093717, "z": null, "yaw": 6.266757555874108, "pitch": null, "roll": null}, "v": 2.1028351391877194, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34936091318541235, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01788049585456116, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141167.2718816} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25570999995160737, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.241773547249341, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.102723632541398, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141167.2718816} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141167.2818816, "x": 18.443326194123742, "y": 4.561769108015815, "z": null, "yaw": -0.015492416667328639, "pitch": null, "roll": null}, "v": 2.102712001054618, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3493495776465221, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017879448805823282, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141167.3018816} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25598157330467125, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2094122153887852, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1026887701930455, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141167.3018816} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.919992446899414, "x": 14.443326194123742, "y": -0.4382308919841851, "z": null, "yaw": 6.267692890512258, "pitch": null, "roll": null}, "v": 2.102712001054618, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3493495776465221, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017879448805823282, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141167.3218815} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2558513889352164, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2094122153887852, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.102699513126159, "gear": 1, "accelerator_pedal_position": 0.25598157330467125, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141167.3218815} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.919992446899414, "x": 14.443326194123742, "y": -0.4382308919841851, "z": null, "yaw": 6.267692890512258, "pitch": null, "roll": null}, "v": 2.102712001054618, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3493495776465221, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017879448805823282, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141167.3418815} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2558513889352164, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2094122153887852, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1026939707336054, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141167.3418815} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.919992446899414, "x": 14.443326194123742, "y": -0.4382308919841851, "z": null, "yaw": 6.267692890512258, "pitch": null, "roll": null}, "v": 2.102712001054618, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3493495776465221, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017879448805823282, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141167.3618815} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2558513889352164, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2094122153887852, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.102688438540333, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141167.3618815} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.919992446899414, "x": 14.443326194123742, "y": -0.4382308919841851, "z": null, "yaw": 6.267692890512258, "pitch": null, "roll": null}, "v": 2.102712001054618, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3493495776465221, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017879448805823282, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141167.3818815} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2558513889352164, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2094122153887852, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1026829165275607, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141167.3818815} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141167.3918815, "x": 18.674596269073763, "y": 4.558284236709034, "z": null, "yaw": -0.014557082029178416, "pitch": null, "roll": null}, "v": 2.1026801593330022, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34934664649117675, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017879178054321775, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141167.4018815} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25757633580005856, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2561853447327636, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1026774046765415, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141167.4018815} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.02999234199524, "x": 14.674596269073763, "y": -0.44171576329096585, "z": null, "yaw": 6.268628225150408, "pitch": null, "roll": null}, "v": 2.1026801593330022, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34934664649117675, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017879178054321775, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141167.4218814} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.256754708794526, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2561853447327636, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1028874220833917, "gear": 1, "accelerator_pedal_position": 0.25757633580005856, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141167.4218814} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.02999234199524, "x": 14.674596269073763, "y": -0.44171576329096585, "z": null, "yaw": 6.268628225150408, "pitch": null, "roll": null}, "v": 2.1026801593330022, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34934664649117675, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017879178054321775, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141167.4418814} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.256754708794526, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2561853447327636, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1029943968963694, "gear": 1, "accelerator_pedal_position": 0.256754708794526, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141167.4418814} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.02999234199524, "x": 14.674596269073763, "y": -0.44171576329096585, "z": null, "yaw": 6.268628225150408, "pitch": null, "roll": null}, "v": 2.1026801593330022, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34934664649117675, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017879178054321775, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141167.4618814} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.256754708794526, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2561853447327636, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.103101174839366, "gear": 1, "accelerator_pedal_position": 0.256754708794526, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141167.4618814} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.02999234199524, "x": 14.674596269073763, "y": -0.44171576329096585, "z": null, "yaw": 6.268628225150408, "pitch": null, "roll": null}, "v": 2.1026801593330022, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34934664649117675, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017879178054321775, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141167.4718814} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.256754708794526, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2561853447327636, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1032077562701317, "gear": 1, "accelerator_pedal_position": 0.256754708794526, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141167.4718814} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141167.5018814, "x": 18.90590051165626, "y": 4.555015249418263, "z": null, "yaw": -0.013621747391028192, "pitch": null, "roll": null}, "v": 2.1033141415457814, "accelerator_pedal_position": 0.256754708794526, "brake_pedal_position": 0.0, "acceleration": 0.0053119191082336426, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017884568831808896, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141167.5018814} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2564005744954532, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1946107963228285, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1033141415457814, "gear": 1, "accelerator_pedal_position": 0.256754708794526, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141167.5018814} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.139992237091064, "x": 14.90590051165626, "y": -0.44498475058173703, "z": null, "yaw": 6.269563559788558, "pitch": null, "roll": null}, "v": 2.1033141415457814, "accelerator_pedal_position": 0.256754708794526, "brake_pedal_position": 0.0, "acceleration": 0.0053119191082336426, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017884568831808896, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141167.5218813} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25657365677129307, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1946107963228285, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.103376084612994, "gear": 1, "accelerator_pedal_position": 0.2564005744954532, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141167.5218813} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.139992237091064, "x": 14.90590051165626, "y": -0.44498475058173703, "z": null, "yaw": 6.269563559788558, "pitch": null, "roll": null}, "v": 2.1033141415457814, "accelerator_pedal_position": 0.256754708794526, "brake_pedal_position": 0.0, "acceleration": 0.0053119191082336426, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017884568831808896, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141167.5418813} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25657365677129307, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1946107963228285, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.103459538999068, "gear": 1, "accelerator_pedal_position": 0.25657365677129307, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141167.5418813} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.139992237091064, "x": 14.90590051165626, "y": -0.44498475058173703, "z": null, "yaw": 6.269563559788558, "pitch": null, "roll": null}, "v": 2.1033141415457814, "accelerator_pedal_position": 0.256754708794526, "brake_pedal_position": 0.0, "acceleration": 0.0053119191082336426, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017884568831808896, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141167.5618813} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25657365677129307, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1946107963228285, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1035428397850247, "gear": 1, "accelerator_pedal_position": 0.25657365677129307, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141167.5618813} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.139992237091064, "x": 14.90590051165626, "y": -0.44498475058173703, "z": null, "yaw": 6.269563559788558, "pitch": null, "roll": null}, "v": 2.1033141415457814, "accelerator_pedal_position": 0.256754708794526, "brake_pedal_position": 0.0, "acceleration": 0.0053119191082336426, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017884568831808896, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141167.5818813} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25657365677129307, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1946107963228285, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.103625987250795, "gear": 1, "accelerator_pedal_position": 0.25657365677129307, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141167.5818813} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.139992237091064, "x": 14.90590051165626, "y": -0.44498475058173703, "z": null, "yaw": 6.269563559788558, "pitch": null, "roll": null}, "v": 2.1033141415457814, "accelerator_pedal_position": 0.256754708794526, "brake_pedal_position": 0.0, "acceleration": 0.0053119191082336426, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017884568831808896, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141167.6018813} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25657365677129307, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1946107963228285, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1037089816758097, "gear": 1, "accelerator_pedal_position": 0.25657365677129307, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141167.6018813} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141167.6118813, "x": 19.13726579250321, "y": 4.551961841958836, "z": null, "yaw": -0.01268641275287797, "pitch": null, "roll": null}, "v": 2.1037504215852194, "accelerator_pedal_position": 0.25657365677129307, "brake_pedal_position": 0.0, "acceleration": 0.004140175378120725, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01788827853937999, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141167.6218812} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25811443492795894, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2406810881762267, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1037918233390007, "gear": 1, "accelerator_pedal_position": 0.25657365677129307, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141167.6218812} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.24999213218689, "x": 15.13726579250321, "y": -0.44803815804116365, "z": null, "yaw": 6.270498894426709, "pitch": null, "roll": null}, "v": 2.1037504215852194, "accelerator_pedal_position": 0.25657365677129307, "brake_pedal_position": 0.0, "acceleration": 0.004140175378120725, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01788827853937999, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141167.6418812} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2573837911424558, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2406810881762267, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.104067021118887, "gear": 1, "accelerator_pedal_position": 0.25811443492795894, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141167.6418812} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.24999213218689, "x": 15.13726579250321, "y": -0.44803815804116365, "z": null, "yaw": 6.270498894426709, "pitch": null, "roll": null}, "v": 2.1037504215852194, "accelerator_pedal_position": 0.25657365677129307, "brake_pedal_position": 0.0, "acceleration": 0.004140175378120725, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01788827853937999, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141167.6618812} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2573837911424558, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2406810881762267, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1042504239050945, "gear": 1, "accelerator_pedal_position": 0.2573837911424558, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141167.6618812} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.24999213218689, "x": 15.13726579250321, "y": -0.44803815804116365, "z": null, "yaw": 6.270498894426709, "pitch": null, "roll": null}, "v": 2.1037504215852194, "accelerator_pedal_position": 0.25657365677129307, "brake_pedal_position": 0.0, "acceleration": 0.004140175378120725, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01788827853937999, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141167.6818812} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2573837911424558, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2406810881762267, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1044334890772407, "gear": 1, "accelerator_pedal_position": 0.2573837911424558, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141167.6818812} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.24999213218689, "x": 15.13726579250321, "y": -0.44803815804116365, "z": null, "yaw": 6.270498894426709, "pitch": null, "roll": null}, "v": 2.1037504215852194, "accelerator_pedal_position": 0.25657365677129307, "brake_pedal_position": 0.0, "acceleration": 0.004140175378120725, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01788827853937999, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141167.7018812} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2573837911424558, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2406810881762267, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.104616217243418, "gear": 1, "accelerator_pedal_position": 0.2573837911424558, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141167.7018812} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.24999213218689, "x": 15.13726579250321, "y": -0.44803815804116365, "z": null, "yaw": 6.270498894426709, "pitch": null, "roll": null}, "v": 2.1037504215852194, "accelerator_pedal_position": 0.25657365677129307, "brake_pedal_position": 0.0, "acceleration": 0.004140175378120725, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01788827853937999, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141167.7118812} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2573837911424558, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2406810881762267, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1047986090106736, "gear": 1, "accelerator_pedal_position": 0.2573837911424558, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141167.7118812} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141167.7218812, "x": 19.368714105317284, "y": 4.549123860819831, "z": null, "yaw": -0.011751078114727746, "pitch": null, "roll": null}, "v": 2.1047986090106736, "accelerator_pedal_position": 0.2573837911424558, "brake_pedal_position": 0.0, "acceleration": 0.00910699234488227, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01789719132125545, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141167.7418811} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2571056695049306, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1775085472833322, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1049806649850105, "gear": 1, "accelerator_pedal_position": 0.2573837911424558, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141167.7418811} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.359992027282715, "x": 15.368714105317284, "y": -0.4508761391801688, "z": null, "yaw": 6.271434229064859, "pitch": null, "roll": null}, "v": 2.1047986090106736, "accelerator_pedal_position": 0.2573837911424558, "brake_pedal_position": 0.0, "acceleration": 0.00910699234488227, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01789719132125545, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141167.761881} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25724546257190906, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1775085472833322, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1051276365762943, "gear": 1, "accelerator_pedal_position": 0.2571056695049306, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141167.761881} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.359992027282715, "x": 15.368714105317284, "y": -0.4508761391801688, "z": null, "yaw": 6.271434229064859, "pitch": null, "roll": null}, "v": 2.1047986090106736, "accelerator_pedal_position": 0.2573837911424558, "brake_pedal_position": 0.0, "acceleration": 0.00910699234488227, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01789719132125545, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141167.781881} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25724546257190906, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1775085472833322, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.105291803651412, "gear": 1, "accelerator_pedal_position": 0.25724546257190906, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141167.781881} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.359992027282715, "x": 15.368714105317284, "y": -0.4508761391801688, "z": null, "yaw": 6.271434229064859, "pitch": null, "roll": null}, "v": 2.1047986090106736, "accelerator_pedal_position": 0.2573837911424558, "brake_pedal_position": 0.0, "acceleration": 0.00910699234488227, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01789719132125545, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141167.801881} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25724546257190906, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1775085472833322, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1054556684535797, "gear": 1, "accelerator_pedal_position": 0.25724546257190906, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141167.801881} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.359992027282715, "x": 15.368714105317284, "y": -0.4508761391801688, "z": null, "yaw": 6.271434229064859, "pitch": null, "roll": null}, "v": 2.1047986090106736, "accelerator_pedal_position": 0.2573837911424558, "brake_pedal_position": 0.0, "acceleration": 0.00910699234488227, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01789719132125545, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141167.811881} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25724546257190906, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1775085472833322, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.105537487672915, "gear": 1, "accelerator_pedal_position": 0.25724546257190906, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141167.811881} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141167.831881, "x": 19.600272629439562, "y": 4.546501141551166, "z": null, "yaw": -0.010815743476577523, "pitch": null, "roll": null}, "v": 2.105700900088785, "accelerator_pedal_position": 0.25724546257190906, "brake_pedal_position": 0.0, "acceleration": 0.008159333263645097, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017904863540337736, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141167.841881} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2579538270884469, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1658881805608252, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1057824934214215, "gear": 1, "accelerator_pedal_position": 0.25724546257190906, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141167.841881} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.46999192237854, "x": 15.600272629439562, "y": -0.4534988584488344, "z": null, "yaw": 6.272369563703009, "pitch": null, "roll": null}, "v": 2.105700900088785, "accelerator_pedal_position": 0.25724546257190906, "brake_pedal_position": 0.0, "acceleration": 0.008159333263645097, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017904863540337736, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141167.861881} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25762284233544525, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1658881805608252, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1060339594573976, "gear": 1, "accelerator_pedal_position": 0.2579538270884469, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141167.861881} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.46999192237854, "x": 15.600272629439562, "y": -0.4534988584488344, "z": null, "yaw": 6.272369563703009, "pitch": null, "roll": null}, "v": 2.105700900088785, "accelerator_pedal_position": 0.25724546257190906, "brake_pedal_position": 0.0, "acceleration": 0.008159333263645097, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017904863540337736, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141167.871881} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25762284233544525, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1658881805608252, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1062436083715923, "gear": 1, "accelerator_pedal_position": 0.25762284233544525, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141167.871881} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.46999192237854, "x": 15.600272629439562, "y": -0.4534988584488344, "z": null, "yaw": 6.272369563703009, "pitch": null, "roll": null}, "v": 2.105700900088785, "accelerator_pedal_position": 0.25724546257190906, "brake_pedal_position": 0.0, "acceleration": 0.008159333263645097, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017904863540337736, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141167.901881} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25762284233544525, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1658881805608252, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.106452871190521, "gear": 1, "accelerator_pedal_position": 0.25762284233544525, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141167.901881} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.46999192237854, "x": 15.600272629439562, "y": -0.4534988584488344, "z": null, "yaw": 6.272369563703009, "pitch": null, "roll": null}, "v": 2.105700900088785, "accelerator_pedal_position": 0.25724546257190906, "brake_pedal_position": 0.0, "acceleration": 0.008159333263645097, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017904863540337736, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141167.921881} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25762284233544525, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1658881805608252, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.106661748607719, "gear": 1, "accelerator_pedal_position": 0.25762284233544525, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141167.921881} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141167.941881, "x": 19.83194605823353, "y": 4.544093841052233, "z": null, "yaw": -0.0098804088384273, "pitch": null, "roll": null}, "v": 2.1068702413155407, "accelerator_pedal_position": 0.25762284233544525, "brake_pedal_position": 0.0, "acceleration": 0.010410230393345599, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017914806498094116, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141167.941881} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2589663760185309, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2096245115123576, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1068702413155407, "gear": 1, "accelerator_pedal_position": 0.25762284233544525, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141167.941881} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.579991817474365, "x": 15.83194605823353, "y": -0.45590615894776665, "z": null, "yaw": 6.273304898341159, "pitch": null, "roll": null}, "v": 2.1068702413155407, "accelerator_pedal_position": 0.25762284233544525, "brake_pedal_position": 0.0, "acceleration": 0.010410230393345599, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017914806498094116, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141167.961881} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25833480548384263, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2096245115123576, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1072462143445283, "gear": 1, "accelerator_pedal_position": 0.2589663760185309, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141167.961881} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.579991817474365, "x": 15.83194605823353, "y": -0.45590615894776665, "z": null, "yaw": 6.273304898341159, "pitch": null, "roll": null}, "v": 2.1068702413155407, "accelerator_pedal_position": 0.25762284233544525, "brake_pedal_position": 0.0, "acceleration": 0.010410230393345599, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017914806498094116, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141167.971881} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25833480548384263, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2096245115123576, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1073944679193093, "gear": 1, "accelerator_pedal_position": 0.25833480548384263, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141167.971881} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.579991817474365, "x": 15.83194605823353, "y": -0.45590615894776665, "z": null, "yaw": 6.273304898341159, "pitch": null, "roll": null}, "v": 2.1068702413155407, "accelerator_pedal_position": 0.25762284233544525, "brake_pedal_position": 0.0, "acceleration": 0.010410230393345599, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017914806498094116, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141168.001881} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25833480548384263, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2096245115123576, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1078384094674667, "gear": 1, "accelerator_pedal_position": 0.25833480548384263, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141168.001881} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.579991817474365, "x": 15.83194605823353, "y": -0.45590615894776665, "z": null, "yaw": 6.273304898341159, "pitch": null, "roll": null}, "v": 2.1068702413155407, "accelerator_pedal_position": 0.25762284233544525, "brake_pedal_position": 0.0, "acceleration": 0.010410230393345599, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017914806498094116, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141168.0118809} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25833480548384263, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2096245115123576, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1079861173294305, "gear": 1, "accelerator_pedal_position": 0.25833480548384263, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141168.0118809} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.579991817474365, "x": 15.83194605823353, "y": -0.45590615894776665, "z": null, "yaw": 6.273304898341159, "pitch": null, "roll": null}, "v": 2.1068702413155407, "accelerator_pedal_position": 0.25762284233544525, "brake_pedal_position": 0.0, "acceleration": 0.010410230393345599, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017914806498094116, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141168.0418808} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25833480548384263, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2096245115123576, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1084284246497513, "gear": 1, "accelerator_pedal_position": 0.25833480548384263, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141168.0418808} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141168.0518808, "x": 20.063780387925064, "y": 4.541901736925146, "z": null, "yaw": -0.008945074200277077, "pitch": null, "roll": null}, "v": 2.1085755887379793, "accelerator_pedal_position": 0.25833480548384263, "brake_pedal_position": 0.0, "acceleration": 0.01470284470290023, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01792930713913309, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141168.0618808} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25753419816883827, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0971483437545364, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.108722617185008, "gear": 1, "accelerator_pedal_position": 0.25833480548384263, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141168.0618808} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.68999171257019, "x": 16.063780387925064, "y": -0.458098263074854, "z": null, "yaw": 6.274240232979309, "pitch": null, "roll": null}, "v": 2.1085755887379793, "accelerator_pedal_position": 0.25833480548384263, "brake_pedal_position": 0.0, "acceleration": 0.01470284470290023, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01792930713913309, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141168.0818808} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2579274136861585, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0971483437545364, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.108916237847207, "gear": 1, "accelerator_pedal_position": 0.25753419816883827, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141168.0818808} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.68999171257019, "x": 16.063780387925064, "y": -0.458098263074854, "z": null, "yaw": 6.274240232979309, "pitch": null, "roll": null}, "v": 2.1085755887379793, "accelerator_pedal_position": 0.25833480548384263, "brake_pedal_position": 0.0, "acceleration": 0.01470284470290023, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01792930713913309, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141168.1018808} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2579274136861585, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0971483437545364, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1091586310105157, "gear": 1, "accelerator_pedal_position": 0.2579274136861585, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141168.1018808} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.68999171257019, "x": 16.063780387925064, "y": -0.458098263074854, "z": null, "yaw": 6.274240232979309, "pitch": null, "roll": null}, "v": 2.1085755887379793, "accelerator_pedal_position": 0.25833480548384263, "brake_pedal_position": 0.0, "acceleration": 0.01470284470290023, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01792930713913309, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141168.1118808} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2579274136861585, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0971483437545364, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1094005774942604, "gear": 1, "accelerator_pedal_position": 0.2579274136861585, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141168.1118808} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.68999171257019, "x": 16.063780387925064, "y": -0.458098263074854, "z": null, "yaw": 6.274240232979309, "pitch": null, "roll": null}, "v": 2.1085755887379793, "accelerator_pedal_position": 0.25833480548384263, "brake_pedal_position": 0.0, "acceleration": 0.01470284470290023, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01792930713913309, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141168.1418808} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2579274136861585, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0971483437545364, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.109642078098173, "gear": 1, "accelerator_pedal_position": 0.2579274136861585, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141168.1418808} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141168.1618807, "x": 20.295780323024722, "y": 4.53992507871897, "z": null, "yaw": -0.008009739562126854, "pitch": null, "roll": null}, "v": 2.1098831336206403, "accelerator_pedal_position": 0.2579274136861585, "brake_pedal_position": 0.0, "acceleration": 0.012036110482090079, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017940425248402985, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141168.1618807} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2593241596042632, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1309583489883346, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1098831336206403, "gear": 1, "accelerator_pedal_position": 0.2579274136861585, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141168.1618807} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.799991607666016, "x": 16.295780323024722, "y": -0.4600749212810298, "z": null, "yaw": 6.27517556761746, "pitch": null, "roll": null}, "v": 2.1098831336206403, "accelerator_pedal_position": 0.2579274136861585, "brake_pedal_position": 0.0, "acceleration": 0.012036110482090079, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017940425248402985, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141168.1818807} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2586682258287579, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1309583489883346, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1102982576101645, "gear": 1, "accelerator_pedal_position": 0.2593241596042632, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141168.1818807} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.799991607666016, "x": 16.295780323024722, "y": -0.4600749212810298, "z": null, "yaw": 6.27517556761746, "pitch": null, "roll": null}, "v": 2.1098831336206403, "accelerator_pedal_position": 0.2579274136861585, "brake_pedal_position": 0.0, "acceleration": 0.012036110482090079, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017940425248402985, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141168.2018807} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2586682258287579, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1309583489883346, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1107966351155976, "gear": 1, "accelerator_pedal_position": 0.2586682258287579, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141168.2018807} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.799991607666016, "x": 16.295780323024722, "y": -0.4600749212810298, "z": null, "yaw": 6.27517556761746, "pitch": null, "roll": null}, "v": 2.1098831336206403, "accelerator_pedal_position": 0.2579274136861585, "brake_pedal_position": 0.0, "acceleration": 0.012036110482090079, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017940425248402985, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141168.2218807} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2586682258287579, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1309583489883346, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1109624546688557, "gear": 1, "accelerator_pedal_position": 0.2586682258287579, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141168.2218807} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.799991607666016, "x": 16.295780323024722, "y": -0.4600749212810298, "z": null, "yaw": 6.27517556761746, "pitch": null, "roll": null}, "v": 2.1098831336206403, "accelerator_pedal_position": 0.2579274136861585, "brake_pedal_position": 0.0, "acceleration": 0.012036110482090079, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017940425248402985, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141168.2418807} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2586682258287579, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1309583489883346, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.111293635166503, "gear": 1, "accelerator_pedal_position": 0.2586682258287579, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141168.2418807} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.799991607666016, "x": 16.295780323024722, "y": -0.4600749212810298, "z": null, "yaw": 6.27517556761746, "pitch": null, "roll": null}, "v": 2.1098831336206403, "accelerator_pedal_position": 0.2579274136861585, "brake_pedal_position": 0.0, "acceleration": 0.012036110482090079, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017940425248402985, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141168.2618806} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2586682258287579, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1309583489883346, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.111789261421995, "gear": 1, "accelerator_pedal_position": 0.2586682258287579, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141168.2618806} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141168.2718806, "x": 20.52795995070897, "y": 4.5381640742654925, "z": null, "yaw": -0.007074404923976623, "pitch": null, "roll": null}, "v": 2.111789261421995, "accelerator_pedal_position": 0.2586682258287579, "brake_pedal_position": 0.0, "acceleration": 0.016490409512064597, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017956633133469787, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141168.2718806} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2596908792869887, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1411027447036406, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.111789261421995, "gear": 1, "accelerator_pedal_position": 0.2586682258287579, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141168.2718806} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.90999150276184, "x": 16.52795995070897, "y": -0.4618359257345075, "z": null, "yaw": 6.27611090225561, "pitch": null, "roll": null}, "v": 2.111789261421995, "accelerator_pedal_position": 0.2586682258287579, "brake_pedal_position": 0.0, "acceleration": 0.016490409512064597, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017956633133469787, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141168.3018806} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25921729373592284, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1411027447036406, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.112872081466178, "gear": 1, "accelerator_pedal_position": 0.25921729373592284, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141168.3018806} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.90999150276184, "x": 16.52795995070897, "y": -0.4618359257345075, "z": null, "yaw": 6.27611090225561, "pitch": null, "roll": null}, "v": 2.111789261421995, "accelerator_pedal_position": 0.2586682258287579, "brake_pedal_position": 0.0, "acceleration": 0.016490409512064597, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017956633133469787, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141168.3218806} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25921729373592284, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1411027447036406, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.113070303440676, "gear": 1, "accelerator_pedal_position": 0.25921729373592284, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141168.3218806} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.90999150276184, "x": 16.52795995070897, "y": -0.4618359257345075, "z": null, "yaw": 6.27611090225561, "pitch": null, "roll": null}, "v": 2.111789261421995, "accelerator_pedal_position": 0.2586682258287579, "brake_pedal_position": 0.0, "acceleration": 0.016490409512064597, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017956633133469787, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141168.3418806} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25921729373592284, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1411027447036406, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1134661989151926, "gear": 1, "accelerator_pedal_position": 0.25921729373592284, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141168.3418806} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.90999150276184, "x": 16.52795995070897, "y": -0.4618359257345075, "z": null, "yaw": 6.27611090225561, "pitch": null, "roll": null}, "v": 2.111789261421995, "accelerator_pedal_position": 0.2586682258287579, "brake_pedal_position": 0.0, "acceleration": 0.016490409512064597, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017956633133469787, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141168.3618805} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25921729373592284, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1411027447036406, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.11386136416227, "gear": 1, "accelerator_pedal_position": 0.25921729373592284, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141168.3618805} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141168.3818805, "x": 20.7603688542531, "y": 4.536618725139072, "z": null, "yaw": -0.00613907028582639, "pitch": null, "roll": null}, "v": 2.114058673351994, "accelerator_pedal_position": 0.25921729373592284, "brake_pedal_position": 0.0, "acceleration": 0.019712711438169994, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01797593003880033, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141168.3818805} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.260098591398655, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1526804241423168, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.114058673351994, "gear": 1, "accelerator_pedal_position": 0.25921729373592284, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141168.3818805} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.019991397857666, "x": 16.7603688542531, "y": -0.46338127486092784, "z": null, "yaw": 6.27704623689376, "pitch": null, "roll": null}, "v": 2.114058673351994, "accelerator_pedal_position": 0.25921729373592284, "brake_pedal_position": 0.0, "acceleration": 0.019712711438169994, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01797593003880033, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141168.4018805} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25969487783329476, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1526804241423168, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.114814599967792, "gear": 1, "accelerator_pedal_position": 0.260098591398655, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141168.4018805} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.019991397857666, "x": 16.7603688542531, "y": -0.46338127486092784, "z": null, "yaw": 6.27704623689376, "pitch": null, "roll": null}, "v": 2.114058673351994, "accelerator_pedal_position": 0.25921729373592284, "brake_pedal_position": 0.0, "acceleration": 0.019712711438169994, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01797593003880033, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141168.4218805} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25969487783329476, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1526804241423168, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1150408784531654, "gear": 1, "accelerator_pedal_position": 0.25969487783329476, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141168.4218805} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.019991397857666, "x": 16.7603688542531, "y": -0.46338127486092784, "z": null, "yaw": 6.27704623689376, "pitch": null, "roll": null}, "v": 2.114058673351994, "accelerator_pedal_position": 0.25921729373592284, "brake_pedal_position": 0.0, "acceleration": 0.019712711438169994, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01797593003880033, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141168.4518805} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25969487783329476, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1526804241423168, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1163941698622266, "gear": 1, "accelerator_pedal_position": 0.25969487783329476, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141168.4518805} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.019991397857666, "x": 16.7603688542531, "y": -0.46338127486092784, "z": null, "yaw": 6.27704623689376, "pitch": null, "roll": null}, "v": 2.114058673351994, "accelerator_pedal_position": 0.25921729373592284, "brake_pedal_position": 0.0, "acceleration": 0.019712711438169994, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01797593003880033, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141168.4818804} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25969487783329476, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1526804241423168, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1166189902136536, "gear": 1, "accelerator_pedal_position": 0.25969487783329476, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141168.4818804} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141168.4918804, "x": 20.99304278090828, "y": 4.535289252585694, "z": null, "yaw": -0.005203735647676158, "pitch": null, "roll": null}, "v": 2.1166189902136536, "accelerator_pedal_position": 0.25969487783329476, "brake_pedal_position": 0.0, "acceleration": 0.02246127745007881, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017997700521030786, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141168.5018804} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2599889809828317, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.145503105142974, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.117086389814136, "gear": 1, "accelerator_pedal_position": 0.2599889809828317, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141168.5018804} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.129991292953491, "x": 16.99304278090828, "y": -0.46471074741430574, "z": null, "yaw": 6.27798157153191, "pitch": null, "roll": null}, "v": 2.1166189902136536, "accelerator_pedal_position": 0.25969487783329476, "brake_pedal_position": 0.0, "acceleration": 0.02246127745007881, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017997700521030786, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141168.5218804} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25986693824849916, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.145503105142974, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1173289524524623, "gear": 1, "accelerator_pedal_position": 0.2599889809828317, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141168.5218804} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.129991292953491, "x": 16.99304278090828, "y": -0.46471074741430574, "z": null, "yaw": 6.27798157153191, "pitch": null, "roll": null}, "v": 2.1166189902136536, "accelerator_pedal_position": 0.25969487783329476, "brake_pedal_position": 0.0, "acceleration": 0.02246127745007881, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017997700521030786, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141168.5418804} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25986693824849916, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.145503105142974, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1180324353074806, "gear": 1, "accelerator_pedal_position": 0.25986693824849916, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141168.5418804} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.129991292953491, "x": 16.99304278090828, "y": -0.46471074741430574, "z": null, "yaw": 6.27798157153191, "pitch": null, "roll": null}, "v": 2.1166189902136536, "accelerator_pedal_position": 0.25969487783329476, "brake_pedal_position": 0.0, "acceleration": 0.02246127745007881, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017997700521030786, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141168.5618804} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25986693824849916, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.145503105142974, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.118500341687835, "gear": 1, "accelerator_pedal_position": 0.25986693824849916, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141168.5618804} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.129991292953491, "x": 16.99304278090828, "y": -0.46471074741430574, "z": null, "yaw": 6.27798157153191, "pitch": null, "roll": null}, "v": 2.1166189902136536, "accelerator_pedal_position": 0.25969487783329476, "brake_pedal_position": 0.0, "acceleration": 0.02246127745007881, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.017997700521030786, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141168.5818803} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25986693824849916, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.145503105142974, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.118733970787749, "gear": 1, "accelerator_pedal_position": 0.25986693824849916, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141168.5818803} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141168.6018803, "x": 21.225997516672084, "y": 4.534176072460567, "z": null, "yaw": -0.004268401009525925, "pitch": null, "roll": null}, "v": 2.119200581750002, "accelerator_pedal_position": 0.25986693824849916, "brake_pedal_position": 0.0, "acceleration": 0.023298223908724047, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01801965190271717, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141168.6018803} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26034997223579465, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1225833525355424, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.119696520608616, "gear": 1, "accelerator_pedal_position": 0.26034997223579465, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141168.6018803} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.239991188049316, "x": 17.225997516672084, "y": -0.46582392753943314, "z": null, "yaw": 6.2789169061700605, "pitch": null, "roll": null}, "v": 2.119200581750002, "accelerator_pedal_position": 0.25986693824849916, "brake_pedal_position": 0.0, "acceleration": 0.023298223908724047, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01801965190271717, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141168.6218803} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26013812212735943, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1225833525355424, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.119696520608616, "gear": 1, "accelerator_pedal_position": 0.26034997223579465, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141168.6218803} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.239991188049316, "x": 17.225997516672084, "y": -0.46582392753943314, "z": null, "yaw": 6.2789169061700605, "pitch": null, "roll": null}, "v": 2.119200581750002, "accelerator_pedal_position": 0.25986693824849916, "brake_pedal_position": 0.0, "acceleration": 0.023298223908724047, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01801965190271717, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141168.6418803} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26013812212735943, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1225833525355424, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1204442484127775, "gear": 1, "accelerator_pedal_position": 0.26013812212735943, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141168.6418803} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.239991188049316, "x": 17.225997516672084, "y": -0.46582392753943314, "z": null, "yaw": 6.2789169061700605, "pitch": null, "roll": null}, "v": 2.119200581750002, "accelerator_pedal_position": 0.25986693824849916, "brake_pedal_position": 0.0, "acceleration": 0.023298223908724047, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01801965190271717, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141168.6618803} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26013812212735943, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1225833525355424, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.12094158276518, "gear": 1, "accelerator_pedal_position": 0.26013812212735943, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141168.6618803} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.239991188049316, "x": 17.225997516672084, "y": -0.46582392753943314, "z": null, "yaw": 6.2789169061700605, "pitch": null, "roll": null}, "v": 2.119200581750002, "accelerator_pedal_position": 0.25986693824849916, "brake_pedal_position": 0.0, "acceleration": 0.023298223908724047, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01801965190271717, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141168.6818802} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26013812212735943, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1225833525355424, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.121189905287007, "gear": 1, "accelerator_pedal_position": 0.26013812212735943, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141168.6818802} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.239991188049316, "x": 17.225997516672084, "y": -0.46582392753943314, "z": null, "yaw": 6.2789169061700605, "pitch": null, "roll": null}, "v": 2.119200581750002, "accelerator_pedal_position": 0.25986693824849916, "brake_pedal_position": 0.0, "acceleration": 0.023298223908724047, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01801965190271717, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141168.7018802} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26013812212735943, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1225833525355424, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1216858620216357, "gear": 1, "accelerator_pedal_position": 0.26013812212735943, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141168.7018802} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141168.7118802, "x": 21.459244430960013, "y": 4.533279665409693, "z": null, "yaw": -0.0033330663713756954, "pitch": null, "roll": null}, "v": 2.1219334966338748, "accelerator_pedal_position": 0.26013812212735943, "brake_pedal_position": 0.0, "acceleration": 0.02474057082293396, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.0180428899932081, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141168.7218802} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2609200918382932, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.102949451833481, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.122180902342104, "gear": 1, "accelerator_pedal_position": 0.26013812212735943, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141168.7218802} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.349991083145142, "x": 17.459244430960013, "y": -0.46672033459030704, "z": null, "yaw": 6.279852240808211, "pitch": null, "roll": null}, "v": 2.1219334966338748, "accelerator_pedal_position": 0.26013812212735943, "brake_pedal_position": 0.0, "acceleration": 0.02474057082293396, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.0180428899932081, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141168.7418802} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26056696721506006, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.102949451833481, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1227727288748977, "gear": 1, "accelerator_pedal_position": 0.2609200918382932, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141168.7418802} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.349991083145142, "x": 17.459244430960013, "y": -0.46672033459030704, "z": null, "yaw": 6.279852240808211, "pitch": null, "roll": null}, "v": 2.1219334966338748, "accelerator_pedal_position": 0.26013812212735943, "brake_pedal_position": 0.0, "acceleration": 0.02474057082293396, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.0180428899932081, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141168.7618802} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26056696721506006, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.102949451833481, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1233193414253098, "gear": 1, "accelerator_pedal_position": 0.26056696721506006, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141168.7618802} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.349991083145142, "x": 17.459244430960013, "y": -0.46672033459030704, "z": null, "yaw": 6.279852240808211, "pitch": null, "roll": null}, "v": 2.1219334966338748, "accelerator_pedal_position": 0.26013812212735943, "brake_pedal_position": 0.0, "acceleration": 0.02474057082293396, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.0180428899932081, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141168.7818801} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26056696721506006, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.102949451833481, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1238649436071917, "gear": 1, "accelerator_pedal_position": 0.26056696721506006, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141168.7818801} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.349991083145142, "x": 17.459244430960013, "y": -0.46672033459030704, "z": null, "yaw": 6.279852240808211, "pitch": null, "roll": null}, "v": 2.1219334966338748, "accelerator_pedal_position": 0.26013812212735943, "brake_pedal_position": 0.0, "acceleration": 0.02474057082293396, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.0180428899932081, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141168.8018801} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26056696721506006, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.102949451833481, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.124681456263304, "gear": 1, "accelerator_pedal_position": 0.26056696721506006, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141168.8018801} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141168.82188, "x": 21.692807586640953, "y": 4.532600507684108, "z": null, "yaw": -0.0023977317332254675, "pitch": null, "roll": null}, "v": 2.1249531238570545, "accelerator_pedal_position": 0.26056696721506006, "brake_pedal_position": 0.0, "acceleration": 0.027141631115374043, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018068566010809386, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141168.82188} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26106693620951554, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.067244444878101, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1249531238570545, "gear": 1, "accelerator_pedal_position": 0.26056696721506006, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141168.82188} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.459990978240967, "x": 17.692807586640953, "y": -0.4673994923158924, "z": null, "yaw": 6.280787575446361, "pitch": null, "roll": null}, "v": 2.1249531238570545, "accelerator_pedal_position": 0.26056696721506006, "brake_pedal_position": 0.0, "acceleration": 0.027141631115374043, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018068566010809386, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141168.84188} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26085012964714205, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.067244444878101, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1258467268949057, "gear": 1, "accelerator_pedal_position": 0.26085012964714205, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141168.84188} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.459990978240967, "x": 17.692807586640953, "y": -0.4673994923158924, "z": null, "yaw": 6.280787575446361, "pitch": null, "roll": null}, "v": 2.1249531238570545, "accelerator_pedal_position": 0.26056696721506006, "brake_pedal_position": 0.0, "acceleration": 0.027141631115374043, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018068566010809386, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141168.86188} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26085012964714205, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.067244444878101, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1261350142037796, "gear": 1, "accelerator_pedal_position": 0.26085012964714205, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141168.86188} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.459990978240967, "x": 17.692807586640953, "y": -0.4673994923158924, "z": null, "yaw": 6.280787575446361, "pitch": null, "roll": null}, "v": 2.1249531238570545, "accelerator_pedal_position": 0.26056696721506006, "brake_pedal_position": 0.0, "acceleration": 0.027141631115374043, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018068566010809386, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141168.88188} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26085012964714205, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.067244444878101, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1269982767135747, "gear": 1, "accelerator_pedal_position": 0.26085012964714205, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141168.88188} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.459990978240967, "x": 17.692807586640953, "y": -0.4673994923158924, "z": null, "yaw": 6.280787575446361, "pitch": null, "roll": null}, "v": 2.1249531238570545, "accelerator_pedal_position": 0.26056696721506006, "brake_pedal_position": 0.0, "acceleration": 0.027141631115374043, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018068566010809386, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141168.90188} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26085012964714205, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.067244444878101, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.127572454505723, "gear": 1, "accelerator_pedal_position": 0.26085012964714205, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141168.90188} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.459990978240967, "x": 17.692807586640953, "y": -0.4673994923158924, "z": null, "yaw": 6.280787575446361, "pitch": null, "roll": null}, "v": 2.1249531238570545, "accelerator_pedal_position": 0.26056696721506006, "brake_pedal_position": 0.0, "acceleration": 0.027141631115374043, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018068566010809386, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141168.92188} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26085012964714205, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.067244444878101, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.128145570002918, "gear": 1, "accelerator_pedal_position": 0.26085012964714205, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141168.92188} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141168.93188, "x": 21.926713103407845, "y": 4.532139136917842, "z": null, "yaw": -0.0014623970950752383, "pitch": null, "roll": null}, "v": 2.128145570002918, "accelerator_pedal_position": 0.26085012964714205, "brake_pedal_position": 0.0, "acceleration": 0.028615996123261322, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018095711514997163, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141168.94188} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2614165622841404, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.037483452475959, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.128431729964151, "gear": 1, "accelerator_pedal_position": 0.26085012964714205, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141168.94188} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.569990873336792, "x": 17.926713103407845, "y": -0.4678608630821577, "z": null, "yaw": 6.281722910084511, "pitch": null, "roll": null}, "v": 2.128145570002918, "accelerator_pedal_position": 0.26085012964714205, "brake_pedal_position": 0.0, "acceleration": 0.028615996123261322, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018095711514997163, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141168.96188} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26116933901484235, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.037483452475959, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.129359392750226, "gear": 1, "accelerator_pedal_position": 0.2614165622841404, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141168.96188} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.569990873336792, "x": 17.926713103407845, "y": -0.4678608630821577, "z": null, "yaw": 6.281722910084511, "pitch": null, "roll": null}, "v": 2.128145570002918, "accelerator_pedal_position": 0.26085012964714205, "brake_pedal_position": 0.0, "acceleration": 0.028615996123261322, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018095711514997163, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141168.98188} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26116933901484235, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.037483452475959, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1296643795999293, "gear": 1, "accelerator_pedal_position": 0.26116933901484235, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141168.98188} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.569990873336792, "x": 17.926713103407845, "y": -0.4678608630821577, "z": null, "yaw": 6.281722910084511, "pitch": null, "roll": null}, "v": 2.128145570002918, "accelerator_pedal_position": 0.26085012964714205, "brake_pedal_position": 0.0, "acceleration": 0.028615996123261322, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018095711514997163, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141169.00188} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26116933901484235, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.037483452475959, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1305776467921156, "gear": 1, "accelerator_pedal_position": 0.26116933901484235, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141169.00188} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.569990873336792, "x": 17.926713103407845, "y": -0.4678608630821577, "z": null, "yaw": 6.281722910084511, "pitch": null, "roll": null}, "v": 2.128145570002918, "accelerator_pedal_position": 0.26085012964714205, "brake_pedal_position": 0.0, "acceleration": 0.028615996123261322, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018095711514997163, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141169.02188} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26116933901484235, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.037483452475959, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1308815055462462, "gear": 1, "accelerator_pedal_position": 0.26116933901484235, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141169.02188} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141169.04188, "x": 22.160975410755086, "y": 4.531896178044759, "z": null, "yaw": -0.0005270624569250087, "pitch": null, "roll": null}, "v": 2.131488379044069, "accelerator_pedal_position": 0.26116933901484235, "brake_pedal_position": 0.0, "acceleration": 0.030301522790562085, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01812413556122362, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141169.04188} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.262249019512164, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0125923581820393, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.131488379044069, "gear": 1, "accelerator_pedal_position": 0.26116933901484235, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141169.04188} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.679990768432617, "x": 18.160975410755086, "y": -0.4681038219552409, "z": null, "yaw": 6.282658244722661, "pitch": null, "roll": null}, "v": 2.131488379044069, "accelerator_pedal_position": 0.26116933901484235, "brake_pedal_position": 0.0, "acceleration": 0.030301522790562085, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01812413556122362, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141169.0618799} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26175846907835576, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0125923581820393, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.132598835503667, "gear": 1, "accelerator_pedal_position": 0.262249019512164, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141169.0618799} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.679990768432617, "x": 18.160975410755086, "y": -0.4681038219552409, "z": null, "yaw": 6.282658244722661, "pitch": null, "roll": null}, "v": 2.131488379044069, "accelerator_pedal_position": 0.26116933901484235, "brake_pedal_position": 0.0, "acceleration": 0.030301522790562085, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01812413556122362, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141169.0818799} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26175846907835576, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0125923581820393, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.133276135821346, "gear": 1, "accelerator_pedal_position": 0.26175846907835576, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141169.0818799} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.679990768432617, "x": 18.160975410755086, "y": -0.4681038219552409, "z": null, "yaw": 6.282658244722661, "pitch": null, "roll": null}, "v": 2.131488379044069, "accelerator_pedal_position": 0.26116933901484235, "brake_pedal_position": 0.0, "acceleration": 0.030301522790562085, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01812413556122362, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141169.1018798} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26175846907835576, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0125923581820393, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1339521815187092, "gear": 1, "accelerator_pedal_position": 0.26175846907835576, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141169.1018798} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.679990768432617, "x": 18.160975410755086, "y": -0.4681038219552409, "z": null, "yaw": 6.282658244722661, "pitch": null, "roll": null}, "v": 2.131488379044069, "accelerator_pedal_position": 0.26116933901484235, "brake_pedal_position": 0.0, "acceleration": 0.030301522790562085, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01812413556122362, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141169.1218798} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26175846907835576, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0125923581820393, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1342897345540464, "gear": 1, "accelerator_pedal_position": 0.26175846907835576, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141169.1218798} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.679990768432617, "x": 18.160975410755086, "y": -0.4681038219552409, "z": null, "yaw": 6.282658244722661, "pitch": null, "roll": null}, "v": 2.131488379044069, "accelerator_pedal_position": 0.26116933901484235, "brake_pedal_position": 0.0, "acceleration": 0.030301522790562085, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01812413556122362, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141169.1418798} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26175846907835576, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0125923581820393, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.135300517614768, "gear": 1, "accelerator_pedal_position": 0.26175846907835576, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141169.1418798} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141169.1518798, "x": 22.395633761078443, "y": 4.531872296255121, "z": null, "yaw": 0.0004082721812252206, "pitch": null, "roll": null}, "v": 2.135300517614768, "accelerator_pedal_position": 0.26175846907835576, "brake_pedal_position": 0.0, "acceleration": 0.033630322853726025, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.0181565503362291, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141169.1618798} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2625279157766525, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0166982843905952, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1359728122872266, "gear": 1, "accelerator_pedal_position": 0.26175846907835576, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141169.1618798} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.789990663528442, "x": 18.395633761078443, "y": -0.4681277037448792, "z": null, "yaw": 0.0004082721812252206, "pitch": null, "roll": null}, "v": 2.135300517614768, "accelerator_pedal_position": 0.26175846907835576, "brake_pedal_position": 0.0, "acceleration": 0.033630322853726025, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.0181565503362291, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141169.1818798} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2621884276809255, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0166982843905952, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1367399971315506, "gear": 1, "accelerator_pedal_position": 0.2625279157766525, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141169.1818798} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.789990663528442, "x": 18.395633761078443, "y": -0.4681277037448792, "z": null, "yaw": 0.0004082721812252206, "pitch": null, "roll": null}, "v": 2.135300517614768, "accelerator_pedal_position": 0.26175846907835576, "brake_pedal_position": 0.0, "acceleration": 0.033630322853726025, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.0181565503362291, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141169.2018797} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2621884276809255, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0166982843905952, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1371018380815086, "gear": 1, "accelerator_pedal_position": 0.2621884276809255, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141169.2018797} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.789990663528442, "x": 18.395633761078443, "y": -0.4681277037448792, "z": null, "yaw": 0.0004082721812252206, "pitch": null, "roll": null}, "v": 2.135300517614768, "accelerator_pedal_position": 0.26175846907835576, "brake_pedal_position": 0.0, "acceleration": 0.033630322853726025, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.0181565503362291, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141169.2218797} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2621884276809255, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0166982843905952, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1381853486779425, "gear": 1, "accelerator_pedal_position": 0.2621884276809255, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141169.2218797} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.789990663528442, "x": 18.395633761078443, "y": -0.4681277037448792, "z": null, "yaw": 0.0004082721812252206, "pitch": null, "roll": null}, "v": 2.135300517614768, "accelerator_pedal_position": 0.26175846907835576, "brake_pedal_position": 0.0, "acceleration": 0.033630322853726025, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.0181565503362291, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141169.2418797} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2621884276809255, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0166982843905952, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1385458490751312, "gear": 1, "accelerator_pedal_position": 0.2621884276809255, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141169.2418797} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141169.2618797, "x": 22.630714007293086, "y": 4.532068251866177, "z": null, "yaw": 0.00134360681937545, "pitch": null, "roll": null}, "v": 2.1392658468742067, "accelerator_pedal_position": 0.2621884276809255, "brake_pedal_position": 0.0, "acceleration": 0.03594979702604967, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018190267698120228, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141169.2618797} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26271225534533454, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9887189768498077, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1392658468742067, "gear": 1, "accelerator_pedal_position": 0.2621884276809255, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141169.2618797} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.899990558624268, "x": 18.630714007293086, "y": -0.46793174813382343, "z": null, "yaw": 0.00134360681937545, "pitch": null, "roll": null}, "v": 2.1392658468742067, "accelerator_pedal_position": 0.2621884276809255, "brake_pedal_position": 0.0, "acceleration": 0.03594979702604967, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018190267698120228, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141169.2818797} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2624908338397672, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9887189768498077, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1404414669173075, "gear": 1, "accelerator_pedal_position": 0.26271225534533454, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141169.2818797} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.899990558624268, "x": 18.630714007293086, "y": -0.46793174813382343, "z": null, "yaw": 0.00134360681937545, "pitch": null, "roll": null}, "v": 2.1392658468742067, "accelerator_pedal_position": 0.2621884276809255, "brake_pedal_position": 0.0, "acceleration": 0.03594979702604967, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018190267698120228, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141169.3018796} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2624908338397672, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9887189768498077, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1411957315568713, "gear": 1, "accelerator_pedal_position": 0.2624908338397672, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141169.3018796} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.899990558624268, "x": 18.630714007293086, "y": -0.46793174813382343, "z": null, "yaw": 0.00134360681937545, "pitch": null, "roll": null}, "v": 2.1392658468742067, "accelerator_pedal_position": 0.2621884276809255, "brake_pedal_position": 0.0, "acceleration": 0.03594979702604967, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018190267698120228, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141169.3218796} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2624908338397672, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9887189768498077, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1415723388899943, "gear": 1, "accelerator_pedal_position": 0.2624908338397672, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141169.3218796} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.899990558624268, "x": 18.630714007293086, "y": -0.46793174813382343, "z": null, "yaw": 0.00134360681937545, "pitch": null, "roll": null}, "v": 2.1392658468742067, "accelerator_pedal_position": 0.2621884276809255, "brake_pedal_position": 0.0, "acceleration": 0.03594979702604967, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018190267698120228, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141169.3418796} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2624908338397672, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9887189768498077, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1423245050648774, "gear": 1, "accelerator_pedal_position": 0.2624908338397672, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141169.3418796} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.899990558624268, "x": 18.630714007293086, "y": -0.46793174813382343, "z": null, "yaw": 0.00134360681937545, "pitch": null, "roll": null}, "v": 2.1392658468742067, "accelerator_pedal_position": 0.2621884276809255, "brake_pedal_position": 0.0, "acceleration": 0.03594979702604967, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018190267698120228, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141169.3618796} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2624908338397672, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9887189768498077, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.143075275224926, "gear": 1, "accelerator_pedal_position": 0.2624908338397672, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141169.3618796} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141169.3718796, "x": 22.86624413669995, "y": 4.5324848838680545, "z": null, "yaw": 0.0022789414575256797, "pitch": null, "roll": null}, "v": 2.143450137538771, "accelerator_pedal_position": 0.2624908338397672, "brake_pedal_position": 0.0, "acceleration": 0.037451419700456456, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018225846898071642, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141169.3818796} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2628071056584565, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9485401206730616, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1438246517357755, "gear": 1, "accelerator_pedal_position": 0.2624908338397672, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141169.3818796} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.009990453720093, "x": 18.86624413669995, "y": -0.4675151161319455, "z": null, "yaw": 0.0022789414575256797, "pitch": null, "roll": null}, "v": 2.143450137538771, "accelerator_pedal_position": 0.2624908338397672, "brake_pedal_position": 0.0, "acceleration": 0.037451419700456456, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018225846898071642, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141169.4018795} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26268609355621864, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9485401206730616, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1446121525768573, "gear": 1, "accelerator_pedal_position": 0.2628071056584565, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141169.4018795} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.009990453720093, "x": 18.86624413669995, "y": -0.4675151161319455, "z": null, "yaw": 0.0022789414575256797, "pitch": null, "roll": null}, "v": 2.143450137538771, "accelerator_pedal_position": 0.2624908338397672, "brake_pedal_position": 0.0, "acceleration": 0.037451419700456456, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018225846898071642, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141169.4218795} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26268609355621864, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9485401206730616, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1457679940776107, "gear": 1, "accelerator_pedal_position": 0.26268609355621864, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141169.4218795} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.009990453720093, "x": 18.86624413669995, "y": -0.4675151161319455, "z": null, "yaw": 0.0022789414575256797, "pitch": null, "roll": null}, "v": 2.143450137538771, "accelerator_pedal_position": 0.2624908338397672, "brake_pedal_position": 0.0, "acceleration": 0.037451419700456456, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018225846898071642, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141169.4418795} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26268609355621864, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9485401206730616, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1465367663866015, "gear": 1, "accelerator_pedal_position": 0.26268609355621864, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141169.4418795} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.009990453720093, "x": 18.86624413669995, "y": -0.4675151161319455, "z": null, "yaw": 0.0022789414575256797, "pitch": null, "roll": null}, "v": 2.143450137538771, "accelerator_pedal_position": 0.2624908338397672, "brake_pedal_position": 0.0, "acceleration": 0.037451419700456456, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018225846898071642, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141169.4618795} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26268609355621864, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9485401206730616, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1469206168417267, "gear": 1, "accelerator_pedal_position": 0.26268609355621864, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141169.4618795} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141169.4818795, "x": 23.102234949637214, "y": 4.533123062765733, "z": null, "yaw": 0.0032142760956759076, "pitch": null, "roll": null}, "v": 2.147687247864722, "accelerator_pedal_position": 0.26268609355621864, "brake_pedal_position": 0.0, "acceleration": 0.03827811718672286, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01826187522583097, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141169.4818795} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2626030074719165, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9078469871139957, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1480700290365893, "gear": 1, "accelerator_pedal_position": 0.26268609355621864, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141169.4818795} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.119990348815918, "x": 19.102234949637214, "y": -0.46687693723426715, "z": null, "yaw": 0.0032142760956759076, "pitch": null, "roll": null}, "v": 2.147687247864722, "accelerator_pedal_position": 0.26268609355621864, "brake_pedal_position": 0.0, "acceleration": 0.03827811718672286, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01826187522583097, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141169.5018795} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2626725666509267, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9078469871139957, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.148447261504101, "gear": 1, "accelerator_pedal_position": 0.2626030074719165, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141169.5018795} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.119990348815918, "x": 19.102234949637214, "y": -0.46687693723426715, "z": null, "yaw": 0.0032142760956759076, "pitch": null, "roll": null}, "v": 2.147687247864722, "accelerator_pedal_position": 0.26268609355621864, "brake_pedal_position": 0.0, "acceleration": 0.03827811718672286, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01826187522583097, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141169.5218794} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2626725666509267, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9078469871139957, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1492093655075504, "gear": 1, "accelerator_pedal_position": 0.2626725666509267, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141169.5218794} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.119990348815918, "x": 19.102234949637214, "y": -0.46687693723426715, "z": null, "yaw": 0.0032142760956759076, "pitch": null, "roll": null}, "v": 2.147687247864722, "accelerator_pedal_position": 0.26268609355621864, "brake_pedal_position": 0.0, "acceleration": 0.03827811718672286, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01826187522583097, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141169.5418794} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2626725666509267, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9078469871139957, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1503498662218887, "gear": 1, "accelerator_pedal_position": 0.2626725666509267, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141169.5418794} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.119990348815918, "x": 19.102234949637214, "y": -0.46687693723426715, "z": null, "yaw": 0.0032142760956759076, "pitch": null, "roll": null}, "v": 2.147687247864722, "accelerator_pedal_position": 0.26268609355621864, "brake_pedal_position": 0.0, "acceleration": 0.03827811718672286, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01826187522583097, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141169.5618794} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2626725666509267, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9078469871139957, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1507293262497447, "gear": 1, "accelerator_pedal_position": 0.2626725666509267, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141169.5618794} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.119990348815918, "x": 19.102234949637214, "y": -0.46687693723426715, "z": null, "yaw": 0.0032142760956759076, "pitch": null, "roll": null}, "v": 2.147687247864722, "accelerator_pedal_position": 0.26268609355621864, "brake_pedal_position": 0.0, "acceleration": 0.03827811718672286, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01826187522583097, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141169.5818794} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2626725666509267, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9078469871139957, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.151865589898506, "gear": 1, "accelerator_pedal_position": 0.2626725666509267, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141169.5818794} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141169.5918794, "x": 23.338688146461575, "y": 4.533983656544115, "z": null, "yaw": 0.004149610733826137, "pitch": null, "roll": null}, "v": 2.151865589898506, "accelerator_pedal_position": 0.2626725666509267, "brake_pedal_position": 0.0, "acceleration": 0.03780500690347399, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018297403844324035, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141169.6018794} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26312181998767614, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9369145693767699, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1522436399675406, "gear": 1, "accelerator_pedal_position": 0.2626725666509267, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141169.6018794} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.229990243911743, "x": 19.338688146461575, "y": -0.46601634345588483, "z": null, "yaw": 0.004149610733826137, "pitch": null, "roll": null}, "v": 2.151865589898506, "accelerator_pedal_position": 0.2626725666509267, "brake_pedal_position": 0.0, "acceleration": 0.03780500690347399, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018297403844324035, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141169.6218793} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26293749484953977, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9369145693767699, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.153054815718033, "gear": 1, "accelerator_pedal_position": 0.26312181998767614, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141169.6218793} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.229990243911743, "x": 19.338688146461575, "y": -0.46601634345588483, "z": null, "yaw": 0.004149610733826137, "pitch": null, "roll": null}, "v": 2.151865589898506, "accelerator_pedal_position": 0.2626725666509267, "brake_pedal_position": 0.0, "acceleration": 0.03780500690347399, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018297403844324035, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141169.6418793} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26293749484953977, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9369145693767699, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1542342219398605, "gear": 1, "accelerator_pedal_position": 0.26293749484953977, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141169.6418793} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.229990243911743, "x": 19.338688146461575, "y": -0.46601634345588483, "z": null, "yaw": 0.004149610733826137, "pitch": null, "roll": null}, "v": 2.151865589898506, "accelerator_pedal_position": 0.2626725666509267, "brake_pedal_position": 0.0, "acceleration": 0.03780500690347399, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018297403844324035, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141169.6618793} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26293749484953977, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9369145693767699, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1550186642742726, "gear": 1, "accelerator_pedal_position": 0.26293749484953977, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141169.6618793} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.229990243911743, "x": 19.338688146461575, "y": -0.46601634345588483, "z": null, "yaw": 0.004149610733826137, "pitch": null, "roll": null}, "v": 2.151865589898506, "accelerator_pedal_position": 0.2626725666509267, "brake_pedal_position": 0.0, "acceleration": 0.03780500690347399, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018297403844324035, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141169.6818793} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26293749484953977, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9369145693767699, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1554103378258946, "gear": 1, "accelerator_pedal_position": 0.26293749484953977, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141169.6818793} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141169.7018793, "x": 23.575607605812003, "y": 4.535067551334759, "z": null, "yaw": 0.005084945371976369, "pitch": null, "roll": null}, "v": 2.15619259124338, "accelerator_pedal_position": 0.26293749484953977, "brake_pedal_position": 0.0, "acceleration": 0.03905804834212606, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018334196519207518, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141169.7018793} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2623968417874205, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7906557684234065, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.156549380910419, "gear": 1, "accelerator_pedal_position": 0.2623968417874205, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141169.7018793} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.339990139007568, "x": 19.575607605812003, "y": -0.4649324486652411, "z": null, "yaw": 0.005084945371976369, "pitch": null, "roll": null}, "v": 2.15619259124338, "accelerator_pedal_position": 0.26293749484953977, "brake_pedal_position": 0.0, "acceleration": 0.03905804834212606, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018334196519207518, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141169.7218792} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2626849822316202, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7906557684234065, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1569058383084467, "gear": 1, "accelerator_pedal_position": 0.2623968417874205, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141169.7218792} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.339990139007568, "x": 19.575607605812003, "y": -0.4649324486652411, "z": null, "yaw": 0.005084945371976369, "pitch": null, "roll": null}, "v": 2.15619259124338, "accelerator_pedal_position": 0.26293749484953977, "brake_pedal_position": 0.0, "acceleration": 0.03905804834212606, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018334196519207518, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141169.7418792} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2626849822316202, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7906557684234065, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.157653758214488, "gear": 1, "accelerator_pedal_position": 0.2626849822316202, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141169.7418792} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.339990139007568, "x": 19.575607605812003, "y": -0.4649324486652411, "z": null, "yaw": 0.005084945371976369, "pitch": null, "roll": null}, "v": 2.15619259124338, "accelerator_pedal_position": 0.26293749484953977, "brake_pedal_position": 0.0, "acceleration": 0.03905804834212606, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018334196519207518, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141169.7618792} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2626849822316202, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7906557684234065, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.158400285404664, "gear": 1, "accelerator_pedal_position": 0.2626849822316202, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141169.7618792} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.339990139007568, "x": 19.575607605812003, "y": -0.4649324486652411, "z": null, "yaw": 0.005084945371976369, "pitch": null, "roll": null}, "v": 2.15619259124338, "accelerator_pedal_position": 0.26293749484953977, "brake_pedal_position": 0.0, "acceleration": 0.03905804834212606, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018334196519207518, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141169.7818792} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2626849822316202, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7906557684234065, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1591454222495607, "gear": 1, "accelerator_pedal_position": 0.2626849822316202, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141169.7818792} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.339990139007568, "x": 19.575607605812003, "y": -0.4649324486652411, "z": null, "yaw": 0.005084945371976369, "pitch": null, "roll": null}, "v": 2.15619259124338, "accelerator_pedal_position": 0.26293749484953977, "brake_pedal_position": 0.0, "acceleration": 0.03905804834212606, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018334196519207518, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141169.8018792} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2626849822316202, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7906557684234065, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.16026052579736, "gear": 1, "accelerator_pedal_position": 0.2626849822316202, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141169.8018792} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141169.8118792, "x": 23.81298733456196, "y": 4.536375584716073, "z": null, "yaw": 0.006020280010126602, "pitch": null, "roll": null}, "v": 2.16026052579736, "accelerator_pedal_position": 0.2626849822316202, "brake_pedal_position": 0.0, "acceleration": 0.03710085726457518, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01836878633824448, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141169.8218791} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2634340149722448, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.811173765580456, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1606315343700055, "gear": 1, "accelerator_pedal_position": 0.2626849822316202, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141169.8218791} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.449990034103394, "x": 19.81298733456196, "y": -0.4636244152839266, "z": null, "yaw": 0.006020280010126602, "pitch": null, "roll": null}, "v": 2.16026052579736, "accelerator_pedal_position": 0.2626849822316202, "brake_pedal_position": 0.0, "acceleration": 0.03710085726457518, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01836878633824448, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141169.8418791} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2631062077674736, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.811173765580456, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1614660998226953, "gear": 1, "accelerator_pedal_position": 0.2634340149722448, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141169.8418791} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.449990034103394, "x": 19.81298733456196, "y": -0.4636244152839266, "z": null, "yaw": 0.006020280010126602, "pitch": null, "roll": null}, "v": 2.16026052579736, "accelerator_pedal_position": 0.2626849822316202, "brake_pedal_position": 0.0, "acceleration": 0.03710085726457518, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01836878633824448, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141169.861879} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2631062077674736, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.811173765580456, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1622581531528025, "gear": 1, "accelerator_pedal_position": 0.2631062077674736, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141169.861879} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.449990034103394, "x": 19.81298733456196, "y": -0.4636244152839266, "z": null, "yaw": 0.006020280010126602, "pitch": null, "roll": null}, "v": 2.16026052579736, "accelerator_pedal_position": 0.2626849822316202, "brake_pedal_position": 0.0, "acceleration": 0.03710085726457518, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01836878633824448, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141169.881879} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2631062077674736, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.811173765580456, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.16304873013144, "gear": 1, "accelerator_pedal_position": 0.2631062077674736, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141169.881879} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.449990034103394, "x": 19.81298733456196, "y": -0.4636244152839266, "z": null, "yaw": 0.006020280010126602, "pitch": null, "roll": null}, "v": 2.16026052579736, "accelerator_pedal_position": 0.2626849822316202, "brake_pedal_position": 0.0, "acceleration": 0.03710085726457518, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01836878633824448, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141169.901879} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2631062077674736, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.811173765580456, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1638378332605717, "gear": 1, "accelerator_pedal_position": 0.2631062077674736, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141169.901879} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141169.921879, "x": 24.050829816463132, "y": 4.537908640779654, "z": null, "yaw": 0.006955614648276835, "pitch": null, "roll": null}, "v": 2.164625465038895, "accelerator_pedal_position": 0.2631062077674736, "brake_pedal_position": 0.0, "acceleration": 0.03932649125581672, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018405901600662924, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141169.921879} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26375934359125575, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8328278783842464, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.164625465038895, "gear": 1, "accelerator_pedal_position": 0.2631062077674736, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141169.921879} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.559989929199219, "x": 20.050829816463132, "y": -0.46209135922034594, "z": null, "yaw": 0.006955614648276835, "pitch": null, "roll": null}, "v": 2.164625465038895, "accelerator_pedal_position": 0.2631062077674736, "brake_pedal_position": 0.0, "acceleration": 0.03932649125581672, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018405901600662924, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141169.941879} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26347933786732003, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8328278783842464, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1654932318535107, "gear": 1, "accelerator_pedal_position": 0.26375934359125575, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141169.941879} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.559989929199219, "x": 20.050829816463132, "y": -0.46209135922034594, "z": null, "yaw": 0.006955614648276835, "pitch": null, "roll": null}, "v": 2.164625465038895, "accelerator_pedal_position": 0.2631062077674736, "brake_pedal_position": 0.0, "acceleration": 0.03932649125581672, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018405901600662924, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141169.961879} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26347933786732003, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8328278783842464, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1663243956904084, "gear": 1, "accelerator_pedal_position": 0.26347933786732003, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141169.961879} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.559989929199219, "x": 20.050829816463132, "y": -0.46209135922034594, "z": null, "yaw": 0.006955614648276835, "pitch": null, "roll": null}, "v": 2.164625465038895, "accelerator_pedal_position": 0.2631062077674736, "brake_pedal_position": 0.0, "acceleration": 0.03932649125581672, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018405901600662924, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141169.981879} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26347933786732003, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8328278783842464, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1671540089282515, "gear": 1, "accelerator_pedal_position": 0.26347933786732003, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141169.981879} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.559989929199219, "x": 20.050829816463132, "y": -0.46209135922034594, "z": null, "yaw": 0.006955614648276835, "pitch": null, "roll": null}, "v": 2.164625465038895, "accelerator_pedal_position": 0.2631062077674736, "brake_pedal_position": 0.0, "acceleration": 0.03932649125581672, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018405901600662924, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141170.001879} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26347933786732003, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8328278783842464, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.167982074184625, "gear": 1, "accelerator_pedal_position": 0.26347933786732003, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141170.001879} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.559989929199219, "x": 20.050829816463132, "y": -0.46209135922034594, "z": null, "yaw": 0.006955614648276835, "pitch": null, "roll": null}, "v": 2.164625465038895, "accelerator_pedal_position": 0.2631062077674736, "brake_pedal_position": 0.0, "acceleration": 0.03932649125581672, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018405901600662924, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141170.021879} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26347933786732003, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8328278783842464, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.16880859407377, "gear": 1, "accelerator_pedal_position": 0.26347933786732003, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141170.021879} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141170.031879, "x": 24.28916391056593, "y": 4.5396678000896244, "z": null, "yaw": 0.007890949286427067, "pitch": null, "roll": null}, "v": 2.169221275321668, "accelerator_pedal_position": 0.26347933786732003, "brake_pedal_position": 0.0, "acceleration": 0.041229588491585034, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01844497996927969, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141170.041879} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2640960154815545, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8553505378707748, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.169633571206584, "gear": 1, "accelerator_pedal_position": 0.26347933786732003, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141170.041879} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.669989824295044, "x": 20.28916391056593, "y": -0.46033219991037555, "z": null, "yaw": 0.007890949286427067, "pitch": null, "roll": null}, "v": 2.169221275321668, "accelerator_pedal_position": 0.26347933786732003, "brake_pedal_position": 0.0, "acceleration": 0.041229588491585034, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01844497996927969, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141170.061879} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2638350424597056, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8553505378707748, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1705340568933438, "gear": 1, "accelerator_pedal_position": 0.2640960154815545, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141170.061879} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.669989824295044, "x": 20.28916391056593, "y": -0.46033219991037555, "z": null, "yaw": 0.007890949286427067, "pitch": null, "roll": null}, "v": 2.169221275321668, "accelerator_pedal_position": 0.26347933786732003, "brake_pedal_position": 0.0, "acceleration": 0.041229588491585034, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01844497996927969, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141170.081879} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2638350424597056, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8553505378707748, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.171400254757001, "gear": 1, "accelerator_pedal_position": 0.2638350424597056, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141170.081879} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.669989824295044, "x": 20.28916391056593, "y": -0.46033219991037555, "z": null, "yaw": 0.007890949286427067, "pitch": null, "roll": null}, "v": 2.169221275321668, "accelerator_pedal_position": 0.26347933786732003, "brake_pedal_position": 0.0, "acceleration": 0.041229588491585034, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01844497996927969, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141170.101879} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2638350424597056, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8553505378707748, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.172264834908971, "gear": 1, "accelerator_pedal_position": 0.2638350424597056, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141170.101879} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.669989824295044, "x": 20.28916391056593, "y": -0.46033219991037555, "z": null, "yaw": 0.007890949286427067, "pitch": null, "roll": null}, "v": 2.169221275321668, "accelerator_pedal_position": 0.26347933786732003, "brake_pedal_position": 0.0, "acceleration": 0.041229588491585034, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01844497996927969, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141170.1218789} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2638350424597056, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8553505378707748, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1731278000716325, "gear": 1, "accelerator_pedal_position": 0.2638350424597056, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141170.1218789} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141170.1418788, "x": 24.528008853587618, "y": 4.541654145312984, "z": null, "yaw": 0.00882628392457729, "pitch": null, "roll": null}, "v": 2.173989152963955, "accelerator_pedal_position": 0.2638350424597056, "brake_pedal_position": 0.0, "acceleration": 0.04300726935291299, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018485521433909628, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141170.1418788} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2641921473676323, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7708791457789674, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.173989152963955, "gear": 1, "accelerator_pedal_position": 0.2638350424597056, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141170.1418788} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.77998971939087, "x": 20.528008853587618, "y": -0.45834585468701583, "z": null, "yaw": 0.00882628392457729, "pitch": null, "roll": null}, "v": 2.173989152963955, "accelerator_pedal_position": 0.2638350424597056, "brake_pedal_position": 0.0, "acceleration": 0.04300726935291299, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018485521433909628, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141170.1618788} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2640560381313762, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7708791457789674, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1753450598233863, "gear": 1, "accelerator_pedal_position": 0.2641921473676323, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141170.1618788} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.77998971939087, "x": 20.528008853587618, "y": -0.45834585468701583, "z": null, "yaw": 0.00882628392457729, "pitch": null, "roll": null}, "v": 2.173989152963955, "accelerator_pedal_position": 0.2638350424597056, "brake_pedal_position": 0.0, "acceleration": 0.04300726935291299, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018485521433909628, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141170.1818788} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2640560381313762, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7708791457789674, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.175787677063756, "gear": 1, "accelerator_pedal_position": 0.2640560381313762, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141170.1818788} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.77998971939087, "x": 20.528008853587618, "y": -0.45834585468701583, "z": null, "yaw": 0.00882628392457729, "pitch": null, "roll": null}, "v": 2.173989152963955, "accelerator_pedal_position": 0.2638350424597056, "brake_pedal_position": 0.0, "acceleration": 0.04300726935291299, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018485521433909628, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141170.2018788} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2640560381313762, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7708791457789674, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.177554010530727, "gear": 1, "accelerator_pedal_position": 0.2640560381313762, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141170.2018788} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.77998971939087, "x": 20.528008853587618, "y": -0.45834585468701583, "z": null, "yaw": 0.00882628392457729, "pitch": null, "roll": null}, "v": 2.173989152963955, "accelerator_pedal_position": 0.2638350424597056, "brake_pedal_position": 0.0, "acceleration": 0.04300726935291299, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018485521433909628, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141170.2218788} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2640560381313762, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7708791457789674, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.177554010530727, "gear": 1, "accelerator_pedal_position": 0.2640560381313762, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141170.2218788} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.77998971939087, "x": 20.528008853587618, "y": -0.45834585468701583, "z": null, "yaw": 0.00882628392457729, "pitch": null, "roll": null}, "v": 2.173989152963955, "accelerator_pedal_position": 0.2638350424597056, "brake_pedal_position": 0.0, "acceleration": 0.04300726935291299, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018485521433909628, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141170.2418787} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2640560381313762, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7708791457789674, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1784347008330185, "gear": 1, "accelerator_pedal_position": 0.2640560381313762, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141170.2418787} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141170.2518787, "x": 24.767383148459054, "y": 4.543868806004359, "z": null, "yaw": 0.009761618562727514, "pitch": null, "roll": null}, "v": 2.1788744280912336, "accelerator_pedal_position": 0.2640560381313762, "brake_pedal_position": 0.0, "acceleration": 0.043931579182640346, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018527061134304516, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141170.2618787} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26465510043121754, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7897009419089065, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.179790089948642, "gear": 1, "accelerator_pedal_position": 0.26465510043121754, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141170.2618787} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.889989614486694, "x": 20.767383148459054, "y": -0.45613119399564095, "z": null, "yaw": 0.009761618562727514, "pitch": null, "roll": null}, "v": 2.1788744280912336, "accelerator_pedal_position": 0.2640560381313762, "brake_pedal_position": 0.0, "acceleration": 0.043931579182640346, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018527061134304516, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141170.2818787} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26440464497232924, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7897009419089065, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.180265990196995, "gear": 1, "accelerator_pedal_position": 0.26465510043121754, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141170.2818787} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.889989614486694, "x": 20.767383148459054, "y": -0.45613119399564095, "z": null, "yaw": 0.009761618562727514, "pitch": null, "roll": null}, "v": 2.1788744280912336, "accelerator_pedal_position": 0.2640560381313762, "brake_pedal_position": 0.0, "acceleration": 0.043931579182640346, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018527061134304516, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141170.3018787} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26440464497232924, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7897009419089065, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.181185162451084, "gear": 1, "accelerator_pedal_position": 0.26440464497232924, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141170.3018787} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.889989614486694, "x": 20.767383148459054, "y": -0.45613119399564095, "z": null, "yaw": 0.009761618562727514, "pitch": null, "roll": null}, "v": 2.1788744280912336, "accelerator_pedal_position": 0.2640560381313762, "brake_pedal_position": 0.0, "acceleration": 0.043931579182640346, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018527061134304516, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141170.3218787} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26440464497232924, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7897009419089065, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1821026144691045, "gear": 1, "accelerator_pedal_position": 0.26440464497232924, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141170.3218787} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.889989614486694, "x": 20.767383148459054, "y": -0.45613119399564095, "z": null, "yaw": 0.009761618562727514, "pitch": null, "roll": null}, "v": 2.1788744280912336, "accelerator_pedal_position": 0.2640560381313762, "brake_pedal_position": 0.0, "acceleration": 0.043931579182640346, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018527061134304516, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141170.3418787} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26440464497232924, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7897009419089065, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.183018349133959, "gear": 1, "accelerator_pedal_position": 0.26440464497232924, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141170.3418787} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141170.3618786, "x": 25.00730025609969, "y": 4.546312914237043, "z": null, "yaw": 0.010696953200877737, "pitch": null, "roll": null}, "v": 2.183932369325043, "accelerator_pedal_position": 0.26440464497232924, "brake_pedal_position": 0.0, "acceleration": 0.04563680667294856, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018570069021883698, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141170.3618786} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26493587174653177, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.782742914642934, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.183932369325043, "gear": 1, "accelerator_pedal_position": 0.26440464497232924, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141170.3618786} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.99998950958252, "x": 21.00730025609969, "y": -0.45368708576295713, "z": null, "yaw": 0.010696953200877737, "pitch": null, "roll": null}, "v": 2.183932369325043, "accelerator_pedal_position": 0.26440464497232924, "brake_pedal_position": 0.0, "acceleration": 0.04563680667294856, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018570069021883698, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141170.3818786} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2647189876707131, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.782742914642934, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.184911050158999, "gear": 1, "accelerator_pedal_position": 0.26493587174653177, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141170.3818786} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.99998950958252, "x": 21.00730025609969, "y": -0.45368708576295713, "z": null, "yaw": 0.010696953200877737, "pitch": null, "roll": null}, "v": 2.183932369325043, "accelerator_pedal_position": 0.26440464497232924, "brake_pedal_position": 0.0, "acceleration": 0.04563680667294856, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018570069021883698, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141170.4018786} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2647189876707131, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.782742914642934, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1858608001277102, "gear": 1, "accelerator_pedal_position": 0.2647189876707131, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141170.4018786} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.99998950958252, "x": 21.00730025609969, "y": -0.45368708576295713, "z": null, "yaw": 0.010696953200877737, "pitch": null, "roll": null}, "v": 2.183932369325043, "accelerator_pedal_position": 0.26440464497232924, "brake_pedal_position": 0.0, "acceleration": 0.04563680667294856, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018570069021883698, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141170.4218786} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2647189876707131, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.782742914642934, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1872820899462364, "gear": 1, "accelerator_pedal_position": 0.2647189876707131, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141170.4218786} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.99998950958252, "x": 21.00730025609969, "y": -0.45368708576295713, "z": null, "yaw": 0.010696953200877737, "pitch": null, "roll": null}, "v": 2.183932369325043, "accelerator_pedal_position": 0.26440464497232924, "brake_pedal_position": 0.0, "acceleration": 0.04563680667294856, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018570069021883698, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141170.4418786} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2647189876707131, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.782742914642934, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.187754965336583, "gear": 1, "accelerator_pedal_position": 0.2647189876707131, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141170.4418786} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.99998950958252, "x": 21.00730025609969, "y": -0.45368708576295713, "z": null, "yaw": 0.010696953200877737, "pitch": null, "roll": null}, "v": 2.183932369325043, "accelerator_pedal_position": 0.26440464497232924, "brake_pedal_position": 0.0, "acceleration": 0.04563680667294856, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018570069021883698, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141170.4618785} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2647189876707131, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.782742914642934, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1891709330566447, "gear": 1, "accelerator_pedal_position": 0.2647189876707131, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141170.4618785} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141170.4718785, "x": 25.24778157146911, "y": 4.548987727541007, "z": null, "yaw": 0.01163228783902796, "pitch": null, "roll": null}, "v": 2.1891709330566447, "accelerator_pedal_position": 0.2647189876707131, "brake_pedal_position": 0.0, "acceleration": 0.047110432547723624, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018614612750177558, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141170.4818785} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2653898218186738, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7425459805588364, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.189642037382122, "gear": 1, "accelerator_pedal_position": 0.2647189876707131, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141170.4818785} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.109989404678345, "x": 21.24778157146911, "y": -0.45101227245899267, "z": null, "yaw": 0.01163228783902796, "pitch": null, "roll": null}, "v": 2.1891709330566447, "accelerator_pedal_position": 0.2647189876707131, "brake_pedal_position": 0.0, "acceleration": 0.047110432547723624, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018614612750177558, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141170.5018785} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26510778758752784, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7425459805588364, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.190666735823059, "gear": 1, "accelerator_pedal_position": 0.2653898218186738, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141170.5018785} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.109989404678345, "x": 21.24778157146911, "y": -0.45101227245899267, "z": null, "yaw": 0.01163228783902796, "pitch": null, "roll": null}, "v": 2.1891709330566447, "accelerator_pedal_position": 0.2647189876707131, "brake_pedal_position": 0.0, "acceleration": 0.047110432547723624, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018614612750177558, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141170.5218785} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26510778758752784, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7425459805588364, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1916542749227093, "gear": 1, "accelerator_pedal_position": 0.26510778758752784, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141170.5218785} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.109989404678345, "x": 21.24778157146911, "y": -0.45101227245899267, "z": null, "yaw": 0.01163228783902796, "pitch": null, "roll": null}, "v": 2.1891709330566447, "accelerator_pedal_position": 0.2647189876707131, "brake_pedal_position": 0.0, "acceleration": 0.047110432547723624, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018614612750177558, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141170.5418785} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26510778758752784, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7425459805588364, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1926399617125147, "gear": 1, "accelerator_pedal_position": 0.26510778758752784, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141170.5418785} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.109989404678345, "x": 21.24778157146911, "y": -0.45101227245899267, "z": null, "yaw": 0.01163228783902796, "pitch": null, "roll": null}, "v": 2.1891709330566447, "accelerator_pedal_position": 0.2647189876707131, "brake_pedal_position": 0.0, "acceleration": 0.047110432547723624, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018614612750177558, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141170.5618784} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26510778758752784, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7425459805588364, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1936237992783716, "gear": 1, "accelerator_pedal_position": 0.26510778758752784, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141170.5618784} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141170.5818784, "x": 25.488845113930182, "y": 4.551894523948009, "z": null, "yaw": 0.012567622477178183, "pitch": null, "roll": null}, "v": 2.194605790702573, "accelerator_pedal_position": 0.26510778758752784, "brake_pedal_position": 0.0, "acceleration": 0.049030437121067694, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01866082557390167, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141170.5818784} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2658130393878556, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7368517608958939, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.194605790702573, "gear": 1, "accelerator_pedal_position": 0.26510778758752784, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141170.5818784} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.21998929977417, "x": 21.488845113930182, "y": -0.4481054760519907, "z": null, "yaw": 0.012567622477178183, "pitch": null, "roll": null}, "v": 2.194605790702573, "accelerator_pedal_position": 0.26510778758752784, "brake_pedal_position": 0.0, "acceleration": 0.049030437121067694, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01866082557390167, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141170.6018784} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26551606180366993, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7368517608958939, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.195674054148341, "gear": 1, "accelerator_pedal_position": 0.2658130393878556, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141170.6018784} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.21998929977417, "x": 21.488845113930182, "y": -0.4481054760519907, "z": null, "yaw": 0.012567622477178183, "pitch": null, "roll": null}, "v": 2.194605790702573, "accelerator_pedal_position": 0.26510778758752784, "brake_pedal_position": 0.0, "acceleration": 0.049030437121067694, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01866082557390167, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141170.6218784} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26551606180366993, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7368517608958939, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.196703207398873, "gear": 1, "accelerator_pedal_position": 0.26551606180366993, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141170.6218784} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.21998929977417, "x": 21.488845113930182, "y": -0.4481054760519907, "z": null, "yaw": 0.012567622477178183, "pitch": null, "roll": null}, "v": 2.194605790702573, "accelerator_pedal_position": 0.26510778758752784, "brake_pedal_position": 0.0, "acceleration": 0.049030437121067694, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01866082557390167, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141170.6418784} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26551606180366993, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7368517608958939, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.198243314957521, "gear": 1, "accelerator_pedal_position": 0.26551606180366993, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141170.6418784} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.21998929977417, "x": 21.488845113930182, "y": -0.4481054760519907, "z": null, "yaw": 0.012567622477178183, "pitch": null, "roll": null}, "v": 2.194605790702573, "accelerator_pedal_position": 0.26510778758752784, "brake_pedal_position": 0.0, "acceleration": 0.049030437121067694, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01866082557390167, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141170.6618783} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26551606180366993, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7368517608958939, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1987557197955963, "gear": 1, "accelerator_pedal_position": 0.26551606180366993, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141170.6618783} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.21998929977417, "x": 21.488845113930182, "y": -0.4481054760519907, "z": null, "yaw": 0.012567622477178183, "pitch": null, "roll": null}, "v": 2.194605790702573, "accelerator_pedal_position": 0.26510778758752784, "brake_pedal_position": 0.0, "acceleration": 0.049030437121067694, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01866082557390167, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141170.6818783} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26551606180366993, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7368517608958939, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.19977908535145, "gear": 1, "accelerator_pedal_position": 0.26551606180366993, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141170.6818783} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141170.6918783, "x": 25.730517757973427, "y": 4.555034747102628, "z": null, "yaw": 0.013502957115328406, "pitch": null, "roll": null}, "v": 2.2002900468690685, "accelerator_pedal_position": 0.26551606180366993, "brake_pedal_position": 0.0, "acceleration": 0.05104812102597267, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018709159043762056, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141170.7018783} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2662093880618245, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7103055672457163, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2013105293815785, "gear": 1, "accelerator_pedal_position": 0.26551606180366993, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141170.7018783} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.329989194869995, "x": 21.730517757973427, "y": -0.4449652528973722, "z": null, "yaw": 0.013502957115328406, "pitch": null, "roll": null}, "v": 2.2002900468690685, "accelerator_pedal_position": 0.26551606180366993, "brake_pedal_position": 0.0, "acceleration": 0.05104812102597267, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018709159043762056, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141170.7218783} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26591992055208125, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7103055672457163, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.202415718891697, "gear": 1, "accelerator_pedal_position": 0.2662093880618245, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141170.7218783} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.329989194869995, "x": 21.730517757973427, "y": -0.4449652528973722, "z": null, "yaw": 0.013502957115328406, "pitch": null, "roll": null}, "v": 2.2002900468690685, "accelerator_pedal_position": 0.26551606180366993, "brake_pedal_position": 0.0, "acceleration": 0.05104812102597267, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018709159043762056, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141170.7418783} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26591992055208125, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7103055672457163, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.202949442566874, "gear": 1, "accelerator_pedal_position": 0.26591992055208125, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141170.7418783} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.329989194869995, "x": 21.730517757973427, "y": -0.4449652528973722, "z": null, "yaw": 0.013502957115328406, "pitch": null, "roll": null}, "v": 2.2002900468690685, "accelerator_pedal_position": 0.26551606180366993, "brake_pedal_position": 0.0, "acceleration": 0.05104812102597267, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018709159043762056, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141170.7618783} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26591992055208125, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7103055672457163, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2045476033335185, "gear": 1, "accelerator_pedal_position": 0.26591992055208125, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141170.7618783} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.329989194869995, "x": 21.730517757973427, "y": -0.4449652528973722, "z": null, "yaw": 0.013502957115328406, "pitch": null, "roll": null}, "v": 2.2002900468690685, "accelerator_pedal_position": 0.26551606180366993, "brake_pedal_position": 0.0, "acceleration": 0.05104812102597267, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018709159043762056, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141170.7818782} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26591992055208125, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7103055672457163, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2050793215528204, "gear": 1, "accelerator_pedal_position": 0.26591992055208125, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141170.7818782} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141170.8018782, "x": 25.972817896073458, "y": 4.5584097981376885, "z": null, "yaw": 0.014438291753478629, "pitch": null, "roll": null}, "v": 2.206141257424726, "accelerator_pedal_position": 0.26591992055208125, "brake_pedal_position": 0.0, "acceleration": 0.05302184810215588, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018758912133833117, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141170.8018782} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2666276919996762, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6834529687078255, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2066714759057477, "gear": 1, "accelerator_pedal_position": 0.26591992055208125, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141170.8018782} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.43998908996582, "x": 21.972817896073458, "y": -0.44159020186231146, "z": null, "yaw": 0.014438291753478629, "pitch": null, "roll": null}, "v": 2.206141257424726, "accelerator_pedal_position": 0.26591992055208125, "brake_pedal_position": 0.0, "acceleration": 0.05302184810215588, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018758912133833117, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141170.8218782} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.266332592313512, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6834529687078255, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.207245431017517, "gear": 1, "accelerator_pedal_position": 0.2666276919996762, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141170.8218782} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.43998908996582, "x": 21.972817896073458, "y": -0.44159020186231146, "z": null, "yaw": 0.014438291753478629, "pitch": null, "roll": null}, "v": 2.206141257424726, "accelerator_pedal_position": 0.26591992055208125, "brake_pedal_position": 0.0, "acceleration": 0.05302184810215588, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018758912133833117, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141170.8418782} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.266332592313512, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6834529687078255, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.208354850639338, "gear": 1, "accelerator_pedal_position": 0.266332592313512, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141170.8418782} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.43998908996582, "x": 21.972817896073458, "y": -0.44159020186231146, "z": null, "yaw": 0.014438291753478629, "pitch": null, "roll": null}, "v": 2.206141257424726, "accelerator_pedal_position": 0.26591992055208125, "brake_pedal_position": 0.0, "acceleration": 0.05302184810215588, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018758912133833117, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141170.8618782} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.266332592313512, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6834529687078255, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.20946218195145, "gear": 1, "accelerator_pedal_position": 0.266332592313512, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141170.8618782} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.43998908996582, "x": 21.972817896073458, "y": -0.44159020186231146, "z": null, "yaw": 0.014438291753478629, "pitch": null, "roll": null}, "v": 2.206141257424726, "accelerator_pedal_position": 0.26591992055208125, "brake_pedal_position": 0.0, "acceleration": 0.05302184810215588, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018758912133833117, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141170.8818781} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.266332592313512, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6834529687078255, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.21056742839453, "gear": 1, "accelerator_pedal_position": 0.266332592313512, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141170.8818781} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.43998908996582, "x": 21.972817896073458, "y": -0.44159020186231146, "z": null, "yaw": 0.014438291753478629, "pitch": null, "roll": null}, "v": 2.206141257424726, "accelerator_pedal_position": 0.26591992055208125, "brake_pedal_position": 0.0, "acceleration": 0.05302184810215588, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018758912133833117, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141170.901878} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.266332592313512, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6834529687078255, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2116705934055427, "gear": 1, "accelerator_pedal_position": 0.266332592313512, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141170.901878} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141170.911878, "x": 26.215770614596643, "y": 4.562021230002514, "z": null, "yaw": 0.015373626391628852, "pitch": null, "roll": null}, "v": 2.212221396447061, "accelerator_pedal_position": 0.266332592313512, "brake_pedal_position": 0.0, "acceleration": 0.05502839706811491, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018810611812309107, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141170.921878} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2672110719243953, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6502956136697569, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.212771680417742, "gear": 1, "accelerator_pedal_position": 0.266332592313512, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141170.921878} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.549988985061646, "x": 22.215770614596643, "y": -0.4379787699974864, "z": null, "yaw": 0.015373626391628852, "pitch": null, "roll": null}, "v": 2.212221396447061, "accelerator_pedal_position": 0.266332592313512, "brake_pedal_position": 0.0, "acceleration": 0.05502839706811491, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018810611812309107, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141170.941878} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26683637855435954, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6502956136697569, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2139804510547623, "gear": 1, "accelerator_pedal_position": 0.2672110719243953, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141170.941878} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.549988985061646, "x": 22.215770614596643, "y": -0.4379787699974864, "z": null, "yaw": 0.015373626391628852, "pitch": null, "roll": null}, "v": 2.212221396447061, "accelerator_pedal_position": 0.266332592313512, "brake_pedal_position": 0.0, "acceleration": 0.05502839706811491, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018810611812309107, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141170.961878} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26683637855435954, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6502956136697569, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.215140129074031, "gear": 1, "accelerator_pedal_position": 0.26683637855435954, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141170.961878} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.549988985061646, "x": 22.215770614596643, "y": -0.4379787699974864, "z": null, "yaw": 0.015373626391628852, "pitch": null, "roll": null}, "v": 2.212221396447061, "accelerator_pedal_position": 0.266332592313512, "brake_pedal_position": 0.0, "acceleration": 0.05502839706811491, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018810611812309107, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141170.981878} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26683637855435954, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6502956136697569, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2162976210412793, "gear": 1, "accelerator_pedal_position": 0.26683637855435954, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141170.981878} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.549988985061646, "x": 22.215770614596643, "y": -0.4379787699974864, "z": null, "yaw": 0.015373626391628852, "pitch": null, "roll": null}, "v": 2.212221396447061, "accelerator_pedal_position": 0.266332592313512, "brake_pedal_position": 0.0, "acceleration": 0.05502839706811491, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018810611812309107, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141171.001878} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26683637855435954, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6502956136697569, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2174529305416635, "gear": 1, "accelerator_pedal_position": 0.26683637855435954, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141171.001878} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141171.021878, "x": 26.459404451964115, "y": 4.5658707217895245, "z": null, "yaw": 0.016308961029779075, "pitch": null, "roll": null}, "v": 2.2186060611566103, "accelerator_pedal_position": 0.26683637855435954, "brake_pedal_position": 0.0, "acceleration": 0.05757493436090805, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018864900885543805, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141171.021878} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26846497301307415, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5880523408529432, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2191818105002192, "gear": 1, "accelerator_pedal_position": 0.26683637855435954, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141171.021878} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.65998888015747, "x": 22.459404451964115, "y": -0.43412927821047553, "z": null, "yaw": 0.016308961029779075, "pitch": null, "roll": null}, "v": 2.2186060611566103, "accelerator_pedal_position": 0.26683637855435954, "brake_pedal_position": 0.0, "acceleration": 0.05757493436090805, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018864900885543805, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141171.041878} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2677353277987207, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5880523408529432, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.219858803617481, "gear": 1, "accelerator_pedal_position": 0.26846497301307415, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141171.041878} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.65998888015747, "x": 22.459404451964115, "y": -0.43412927821047553, "z": null, "yaw": 0.016308961029779075, "pitch": null, "roll": null}, "v": 2.2186060611566103, "accelerator_pedal_position": 0.26683637855435954, "brake_pedal_position": 0.0, "acceleration": 0.05757493436090805, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018864900885543805, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141171.061878} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2677353277987207, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5880523408529432, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2223782379401187, "gear": 1, "accelerator_pedal_position": 0.2677353277987207, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141171.061878} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.65998888015747, "x": 22.459404451964115, "y": -0.43412927821047553, "z": null, "yaw": 0.016308961029779075, "pitch": null, "roll": null}, "v": 2.2186060611566103, "accelerator_pedal_position": 0.26683637855435954, "brake_pedal_position": 0.0, "acceleration": 0.05757493436090805, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018864900885543805, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141171.081878} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2677353277987207, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5880523408529432, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2230066103053217, "gear": 1, "accelerator_pedal_position": 0.2677353277987207, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141171.081878} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.65998888015747, "x": 22.459404451964115, "y": -0.43412927821047553, "z": null, "yaw": 0.016308961029779075, "pitch": null, "roll": null}, "v": 2.2186060611566103, "accelerator_pedal_position": 0.26683637855435954, "brake_pedal_position": 0.0, "acceleration": 0.05757493436090805, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018864900885543805, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141171.101878} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2677353277987207, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5880523408529432, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2248881681963915, "gear": 1, "accelerator_pedal_position": 0.2677353277987207, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141171.101878} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.65998888015747, "x": 22.459404451964115, "y": -0.43412927821047553, "z": null, "yaw": 0.016308961029779075, "pitch": null, "roll": null}, "v": 2.2186060611566103, "accelerator_pedal_position": 0.26683637855435954, "brake_pedal_position": 0.0, "acceleration": 0.05757493436090805, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018864900885543805, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141171.121878} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2677353277987207, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5880523408529432, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2248881681963915, "gear": 1, "accelerator_pedal_position": 0.2677353277987207, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141171.121878} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141171.131878, "x": 26.703761966296103, "y": 4.569960268790786, "z": null, "yaw": 0.0172442956679293, "pitch": null, "roll": null}, "v": 2.225514169363615, "accelerator_pedal_position": 0.2677353277987207, "brake_pedal_position": 0.0, "acceleration": 0.06254095709344148, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018923640820908364, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141171.1518779} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2679602138710421, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5967301095624539, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.228677437148637, "gear": 1, "accelerator_pedal_position": 0.2679602138710421, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141171.1518779} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.769988775253296, "x": 22.703761966296103, "y": -0.4300397312092139, "z": null, "yaw": 0.0172442956679293, "pitch": null, "roll": null}, "v": 2.225514169363615, "accelerator_pedal_position": 0.2677353277987207, "brake_pedal_position": 0.0, "acceleration": 0.06254095709344148, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018923640820908364, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141171.1818779} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2679028326684893, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5967301095624539, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2293139114851175, "gear": 1, "accelerator_pedal_position": 0.2679602138710421, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141171.1818779} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.769988775253296, "x": 22.703761966296103, "y": -0.4300397312092139, "z": null, "yaw": 0.0172442956679293, "pitch": null, "roll": null}, "v": 2.225514169363615, "accelerator_pedal_position": 0.2677353277987207, "brake_pedal_position": 0.0, "acceleration": 0.06254095709344148, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018923640820908364, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141171.2018778} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2679028326684893, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5967301095624539, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.230577885458199, "gear": 1, "accelerator_pedal_position": 0.2679028326684893, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141171.2018778} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.769988775253296, "x": 22.703761966296103, "y": -0.4300397312092139, "z": null, "yaw": 0.0172442956679293, "pitch": null, "roll": null}, "v": 2.225514169363615, "accelerator_pedal_position": 0.2677353277987207, "brake_pedal_position": 0.0, "acceleration": 0.06254095709344148, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018923640820908364, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141171.2218778} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2679028326684893, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5967301095624539, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.231208975786941, "gear": 1, "accelerator_pedal_position": 0.2679028326684893, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141171.2218778} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141171.2418778, "x": 26.948877938284667, "y": 4.574291842725991, "z": null, "yaw": 0.01817963030607952, "pitch": null, "roll": null}, "v": 2.232469365557215, "accelerator_pedal_position": 0.2679028326684893, "brake_pedal_position": 0.0, "acceleration": 0.06293004121868295, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018982781147408406, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141171.2418778} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2688558275624611, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5620114255350809, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.233098665969402, "gear": 1, "accelerator_pedal_position": 0.2679028326684893, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141171.2418778} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.879988670349121, "x": 22.948877938284667, "y": -0.4257081572740091, "z": null, "yaw": 0.01817963030607952, "pitch": null, "roll": null}, "v": 2.232469365557215, "accelerator_pedal_position": 0.2679028326684893, "brake_pedal_position": 0.0, "acceleration": 0.06293004121868295, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018982781147408406, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141171.2618778} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.268452139987353, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5620114255350809, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2344493177704816, "gear": 1, "accelerator_pedal_position": 0.268452139987353, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141171.2618778} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.879988670349121, "x": 22.948877938284667, "y": -0.4257081572740091, "z": null, "yaw": 0.01817963030607952, "pitch": null, "roll": null}, "v": 2.232469365557215, "accelerator_pedal_position": 0.2679028326684893, "brake_pedal_position": 0.0, "acceleration": 0.06293004121868295, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018982781147408406, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141171.2818778} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.268452139987353, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5620114255350809, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2351110754854373, "gear": 1, "accelerator_pedal_position": 0.268452139987353, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141171.2818778} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.879988670349121, "x": 22.948877938284667, "y": -0.4257081572740091, "z": null, "yaw": 0.01817963030607952, "pitch": null, "roll": null}, "v": 2.232469365557215, "accelerator_pedal_position": 0.2679028326684893, "brake_pedal_position": 0.0, "acceleration": 0.06293004121868295, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018982781147408406, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141171.3018777} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.268452139987353, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5620114255350809, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.23643271145491, "gear": 1, "accelerator_pedal_position": 0.268452139987353, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141171.3018777} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.879988670349121, "x": 22.948877938284667, "y": -0.4257081572740091, "z": null, "yaw": 0.01817963030607952, "pitch": null, "roll": null}, "v": 2.232469365557215, "accelerator_pedal_position": 0.2679028326684893, "brake_pedal_position": 0.0, "acceleration": 0.06293004121868295, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018982781147408406, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141171.3218777} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.268452139987353, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5620114255350809, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2377518448490084, "gear": 1, "accelerator_pedal_position": 0.268452139987353, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141171.3218777} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.879988670349121, "x": 22.948877938284667, "y": -0.4257081572740091, "z": null, "yaw": 0.01817963030607952, "pitch": null, "roll": null}, "v": 2.232469365557215, "accelerator_pedal_position": 0.2679028326684893, "brake_pedal_position": 0.0, "acceleration": 0.06293004121868295, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.018982781147408406, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141171.3418777} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.268452139987353, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5620114255350809, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2390684797107534, "gear": 1, "accelerator_pedal_position": 0.268452139987353, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141171.3418777} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141171.3518777, "x": 27.194769802507214, "y": 4.578867197130281, "z": null, "yaw": 0.019114964944229745, "pitch": null, "roll": null}, "v": 2.239725861454424, "accelerator_pedal_position": 0.268452139987353, "brake_pedal_position": 0.0, "acceleration": 0.06567586250355739, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.019044483437992536, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141171.3618777} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2695364151084807, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5290727079480558, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2411065232852647, "gear": 1, "accelerator_pedal_position": 0.2695364151084807, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141171.3618777} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.989988565444946, "x": 23.194769802507214, "y": -0.4211328028697192, "z": null, "yaw": 0.019114964944229745, "pitch": null, "roll": null}, "v": 2.239725861454424, "accelerator_pedal_position": 0.268452139987353, "brake_pedal_position": 0.0, "acceleration": 0.06567586250355739, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.019044483437992536, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141171.3818777} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2690724628729811, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5290727079480558, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.241829740123031, "gear": 1, "accelerator_pedal_position": 0.2695364151084807, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141171.3818777} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.989988565444946, "x": 23.194769802507214, "y": -0.4211328028697192, "z": null, "yaw": 0.019114964944229745, "pitch": null, "roll": null}, "v": 2.239725861454424, "accelerator_pedal_position": 0.268452139987353, "brake_pedal_position": 0.0, "acceleration": 0.06567586250355739, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.019044483437992536, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141171.4118776} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2690724628729811, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5290727079480558, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.244599931605719, "gear": 1, "accelerator_pedal_position": 0.2690724628729811, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141171.4118776} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2690724628729811, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5290727079480558, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.244599931605719, "gear": 1, "accelerator_pedal_position": 0.2690724628729811, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141171.4218776} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.989988565444946, "x": 23.194769802507214, "y": -0.4211328028697192, "z": null, "yaw": 0.019114964944229745, "pitch": null, "roll": null}, "v": 2.239725861454424, "accelerator_pedal_position": 0.268452139987353, "brake_pedal_position": 0.0, "acceleration": 0.06567586250355739, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.019044483437992536, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141171.4518776} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2690724628729811, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5290727079480558, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.246670683381022, "gear": 1, "accelerator_pedal_position": 0.2690724628729811, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141171.4518776} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141171.4618776, "x": 27.441475037590873, "y": 4.583688525071612, "z": null, "yaw": 0.020050299582379968, "pitch": null, "roll": null}, "v": 2.2473596240529363, "accelerator_pedal_position": 0.2690724628729811, "brake_pedal_position": 0.0, "acceleration": 0.06882865895525137, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.019109393643245303, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141171.4718776} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2708627876831274, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4857176017497183, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2480479106424887, "gear": 1, "accelerator_pedal_position": 0.2690724628729811, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141171.4718776} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.099988460540771, "x": 23.441475037590873, "y": -0.4163114749283876, "z": null, "yaw": 0.020050299582379968, "pitch": null, "roll": null}, "v": 2.2473596240529363, "accelerator_pedal_position": 0.2690724628729811, "brake_pedal_position": 0.0, "acceleration": 0.06882865895525137, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.019109393643245303, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141171.4918776} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27006543044824627, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4857176017497183, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2496462080068365, "gear": 1, "accelerator_pedal_position": 0.2708627876831274, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141171.4918776} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.099988460540771, "x": 23.441475037590873, "y": -0.4163114749283876, "z": null, "yaw": 0.020050299582379968, "pitch": null, "roll": null}, "v": 2.2473596240529363, "accelerator_pedal_position": 0.2690724628729811, "brake_pedal_position": 0.0, "acceleration": 0.06882865895525137, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.019109393643245303, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141171.5118775} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27006543044824627, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4857176017497183, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2511418482228653, "gear": 1, "accelerator_pedal_position": 0.27006543044824627, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141171.5118775} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.099988460540771, "x": 23.441475037590873, "y": -0.4163114749283876, "z": null, "yaw": 0.020050299582379968, "pitch": null, "roll": null}, "v": 2.2473596240529363, "accelerator_pedal_position": 0.2690724628729811, "brake_pedal_position": 0.0, "acceleration": 0.06882865895525137, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.019109393643245303, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141171.5318775} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27006543044824627, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4857176017497183, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.252634647613418, "gear": 1, "accelerator_pedal_position": 0.27006543044824627, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141171.5318775} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.099988460540771, "x": 23.441475037590873, "y": -0.4163114749283876, "z": null, "yaw": 0.020050299582379968, "pitch": null, "roll": null}, "v": 2.2473596240529363, "accelerator_pedal_position": 0.2690724628729811, "brake_pedal_position": 0.0, "acceleration": 0.06882865895525137, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.019109393643245303, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141171.5518775} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27006543044824627, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4857176017497183, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.254124610683414, "gear": 1, "accelerator_pedal_position": 0.27006543044824627, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141171.5518775} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141171.5718775, "x": 27.689046459574964, "y": 4.588758440805227, "z": null, "yaw": 0.02098563422053019, "pitch": null, "roll": null}, "v": 2.2556117419342914, "accelerator_pedal_position": 0.27006543044824627, "brake_pedal_position": 0.0, "acceleration": 0.07425050990130605, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01917956174954103, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141171.5718775} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27212998977314923, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.43756195218820043, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2556117419342914, "gear": 1, "accelerator_pedal_position": 0.27006543044824627, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141171.5718775} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.209988355636597, "x": 23.689046459574964, "y": -0.4112415591947727, "z": null, "yaw": 0.02098563422053019, "pitch": null, "roll": null}, "v": 2.2556117419342914, "accelerator_pedal_position": 0.27006543044824627, "brake_pedal_position": 0.0, "acceleration": 0.07425050990130605, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01917956174954103, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141171.5918775} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2712066141209273, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.43756195218820043, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2573539930307462, "gear": 1, "accelerator_pedal_position": 0.27212998977314923, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141171.5918775} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.209988355636597, "x": 23.689046459574964, "y": -0.4112415591947727, "z": null, "yaw": 0.02098563422053019, "pitch": null, "roll": null}, "v": 2.2556117419342914, "accelerator_pedal_position": 0.27006543044824627, "brake_pedal_position": 0.0, "acceleration": 0.07425050990130605, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01917956174954103, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141171.6118774} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2712066141209273, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.43756195218820043, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2589775635692604, "gear": 1, "accelerator_pedal_position": 0.2712066141209273, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141171.6118774} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.209988355636597, "x": 23.689046459574964, "y": -0.4112415591947727, "z": null, "yaw": 0.02098563422053019, "pitch": null, "roll": null}, "v": 2.2556117419342914, "accelerator_pedal_position": 0.27006543044824627, "brake_pedal_position": 0.0, "acceleration": 0.07425050990130605, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01917956174954103, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141171.6318774} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2712066141209273, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.43756195218820043, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2605980452277574, "gear": 1, "accelerator_pedal_position": 0.2712066141209273, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141171.6318774} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.209988355636597, "x": 23.689046459574964, "y": -0.4112415591947727, "z": null, "yaw": 0.02098563422053019, "pitch": null, "roll": null}, "v": 2.2556117419342914, "accelerator_pedal_position": 0.27006543044824627, "brake_pedal_position": 0.0, "acceleration": 0.07425050990130605, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01917956174954103, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141171.6518774} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2712066141209273, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.43756195218820043, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2622154428330172, "gear": 1, "accelerator_pedal_position": 0.2712066141209273, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141171.6518774} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.209988355636597, "x": 23.689046459574964, "y": -0.4112415591947727, "z": null, "yaw": 0.02098563422053019, "pitch": null, "roll": null}, "v": 2.2556117419342914, "accelerator_pedal_position": 0.27006543044824627, "brake_pedal_position": 0.0, "acceleration": 0.07425050990130605, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01917956174954103, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141171.6718774} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2712066141209273, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.43756195218820043, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2638297612086276, "gear": 1, "accelerator_pedal_position": 0.2712066141209273, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141171.6718774} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141171.6818774, "x": 27.937564018144847, "y": 4.594080286870797, "z": null, "yaw": 0.021920968858680414, "pitch": null, "roll": null}, "v": 2.2646357671918076, "accelerator_pedal_position": 0.2712066141209273, "brake_pedal_position": 0.0, "acceleration": 0.08052379831576079, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.019256293416803738, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141171.6918774} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2734707436350305, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.38716314453250744, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2654410051749654, "gear": 1, "accelerator_pedal_position": 0.2712066141209273, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141171.6918774} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.319988250732422, "x": 23.937564018144847, "y": -0.4059197131292027, "z": null, "yaw": 0.021920968858680414, "pitch": null, "roll": null}, "v": 2.2646357671918076, "accelerator_pedal_position": 0.2712066141209273, "brake_pedal_position": 0.0, "acceleration": 0.08052379831576079, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.019256293416803738, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141171.7118773} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2724580421826014, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.38716314453250744, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2673320608439775, "gear": 1, "accelerator_pedal_position": 0.2734707436350305, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141171.7118773} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.319988250732422, "x": 23.937564018144847, "y": -0.4059197131292027, "z": null, "yaw": 0.021920968858680414, "pitch": null, "roll": null}, "v": 2.2646357671918076, "accelerator_pedal_position": 0.2712066141209273, "brake_pedal_position": 0.0, "acceleration": 0.08052379831576079, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.019256293416803738, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141171.7318773} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2724580421826014, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.38716314453250744, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.269092985152005, "gear": 1, "accelerator_pedal_position": 0.2724580421826014, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141171.7318773} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.319988250732422, "x": 23.937564018144847, "y": -0.4059197131292027, "z": null, "yaw": 0.021920968858680414, "pitch": null, "roll": null}, "v": 2.2646357671918076, "accelerator_pedal_position": 0.2712066141209273, "brake_pedal_position": 0.0, "acceleration": 0.08052379831576079, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.019256293416803738, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141171.7518773} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2724580421826014, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.38716314453250744, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2708505521672997, "gear": 1, "accelerator_pedal_position": 0.2724580421826014, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141171.7518773} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.319988250732422, "x": 23.937564018144847, "y": -0.4059197131292027, "z": null, "yaw": 0.021920968858680414, "pitch": null, "roll": null}, "v": 2.2646357671918076, "accelerator_pedal_position": 0.2712066141209273, "brake_pedal_position": 0.0, "acceleration": 0.08052379831576079, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.019256293416803738, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141171.7718773} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2724580421826014, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.38716314453250744, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2726047670556855, "gear": 1, "accelerator_pedal_position": 0.2724580421826014, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141171.7718773} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141171.7918773, "x": 28.187099071242688, "y": 4.599657438779648, "z": null, "yaw": 0.022856303496830637, "pitch": null, "roll": null}, "v": 2.2743556349801985, "accelerator_pedal_position": 0.2724580421826014, "brake_pedal_position": 0.0, "acceleration": 0.08741804634858685, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.019338941862446668, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141171.7918773} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27429249179764703, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3438562265407816, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2743556349801985, "gear": 1, "accelerator_pedal_position": 0.2724580421826014, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141171.7918773} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.429988145828247, "x": 24.187099071242688, "y": -0.40034256122035217, "z": null, "yaw": 0.022856303496830637, "pitch": null, "roll": null}, "v": 2.2743556349801985, "accelerator_pedal_position": 0.2724580421826014, "brake_pedal_position": 0.0, "acceleration": 0.08741804634858685, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.019338941862446668, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141171.8118773} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.273489586044835, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3438562265407816, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.276332357802652, "gear": 1, "accelerator_pedal_position": 0.27429249179764703, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141171.8118773} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.429988145828247, "x": 24.187099071242688, "y": -0.40034256122035217, "z": null, "yaw": 0.022856303496830637, "pitch": null, "roll": null}, "v": 2.2743556349801985, "accelerator_pedal_position": 0.2724580421826014, "brake_pedal_position": 0.0, "acceleration": 0.08741804634858685, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.019338941862446668, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141171.8318772} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.273489586044835, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3438562265407816, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2782049909527777, "gear": 1, "accelerator_pedal_position": 0.273489586044835, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141171.8318772} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.429988145828247, "x": 24.187099071242688, "y": -0.40034256122035217, "z": null, "yaw": 0.022856303496830637, "pitch": null, "roll": null}, "v": 2.2743556349801985, "accelerator_pedal_position": 0.2724580421826014, "brake_pedal_position": 0.0, "acceleration": 0.08741804634858685, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.019338941862446668, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141171.8518772} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.273489586044835, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3438562265407816, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.280074047033567, "gear": 1, "accelerator_pedal_position": 0.273489586044835, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141171.8518772} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.429988145828247, "x": 24.187099071242688, "y": -0.40034256122035217, "z": null, "yaw": 0.022856303496830637, "pitch": null, "roll": null}, "v": 2.2743556349801985, "accelerator_pedal_position": 0.2724580421826014, "brake_pedal_position": 0.0, "acceleration": 0.08741804634858685, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.019338941862446668, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141171.8718772} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.273489586044835, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3438562265407816, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2819395314811914, "gear": 1, "accelerator_pedal_position": 0.273489586044835, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141171.8718772} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.429988145828247, "x": 24.187099071242688, "y": -0.40034256122035217, "z": null, "yaw": 0.022856303496830637, "pitch": null, "roll": null}, "v": 2.2743556349801985, "accelerator_pedal_position": 0.2724580421826014, "brake_pedal_position": 0.0, "acceleration": 0.08741804634858685, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.019338941862446668, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141171.8918772} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.273489586044835, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3438562265407816, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2838014497294394, "gear": 1, "accelerator_pedal_position": 0.273489586044835, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141171.8918772} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141171.9018772, "x": 28.43773451669617, "y": 4.605493739305943, "z": null, "yaw": 0.02379163813498086, "pitch": null, "roll": null}, "v": 2.2847310732261983, "accelerator_pedal_position": 0.273489586044835, "brake_pedal_position": 0.0, "acceleration": 0.09287339834925529, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01942716465133278, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141171.9118772} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27380976727937506, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3211710929825406, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.285659807209691, "gear": 1, "accelerator_pedal_position": 0.273489586044835, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141171.9118772} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.539988040924072, "x": 24.43773451669617, "y": -0.39450626069405725, "z": null, "yaw": 0.02379163813498086, "pitch": null, "roll": null}, "v": 2.2847310732261983, "accelerator_pedal_position": 0.273489586044835, "brake_pedal_position": 0.0, "acceleration": 0.09287339834925529, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01942716465133278, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141171.9318771} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2737328654826671, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3211710929825406, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2875546128479733, "gear": 1, "accelerator_pedal_position": 0.27380976727937506, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141171.9318771} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.539988040924072, "x": 24.43773451669617, "y": -0.39450626069405725, "z": null, "yaw": 0.02379163813498086, "pitch": null, "roll": null}, "v": 2.2847310732261983, "accelerator_pedal_position": 0.273489586044835, "brake_pedal_position": 0.0, "acceleration": 0.09287339834925529, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01942716465133278, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141171.951877} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2737328654826671, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3211710929825406, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.291314152299781, "gear": 1, "accelerator_pedal_position": 0.2737328654826671, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141171.951877} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.539988040924072, "x": 24.43773451669617, "y": -0.39450626069405725, "z": null, "yaw": 0.02379163813498086, "pitch": null, "roll": null}, "v": 2.2847310732261983, "accelerator_pedal_position": 0.273489586044835, "brake_pedal_position": 0.0, "acceleration": 0.09287339834925529, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01942716465133278, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141171.991877} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2737328654826671, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3211710929825406, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2931885236352603, "gear": 1, "accelerator_pedal_position": 0.2737328654826671, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141171.991877} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141172.011877, "x": 28.689498060017133, "y": 4.61159192431224, "z": null, "yaw": 0.024726972773131083, "pitch": null, "roll": null}, "v": 2.2950593033583493, "accelerator_pedal_position": 0.2737328654826671, "brake_pedal_position": 0.0, "acceleration": 0.0934044720394348, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.019514986027636308, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141172.011877} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2748932776310891, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.28073447868650236, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2950593033583493, "gear": 1, "accelerator_pedal_position": 0.2737328654826671, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141172.011877} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.649987936019897, "x": 24.689498060017133, "y": -0.38840807568776015, "z": null, "yaw": 0.024726972773131083, "pitch": null, "roll": null}, "v": 2.2950593033583493, "accelerator_pedal_position": 0.2737328654826671, "brake_pedal_position": 0.0, "acceleration": 0.0934044720394348, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.019514986027636308, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141172.031877} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27441608477317775, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.28073447868650236, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.297071478903344, "gear": 1, "accelerator_pedal_position": 0.2748932776310891, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141172.031877} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.649987936019897, "x": 24.689498060017133, "y": -0.38840807568776015, "z": null, "yaw": 0.024726972773131083, "pitch": null, "roll": null}, "v": 2.2950593033583493, "accelerator_pedal_position": 0.2737328654826671, "brake_pedal_position": 0.0, "acceleration": 0.0934044720394348, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.019514986027636308, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141172.051877} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27441608477317775, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.28073447868650236, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2999931210321165, "gear": 1, "accelerator_pedal_position": 0.27441608477317775, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141172.051877} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.649987936019897, "x": 24.689498060017133, "y": -0.38840807568776015, "z": null, "yaw": 0.024726972773131083, "pitch": null, "roll": null}, "v": 2.2950593033583493, "accelerator_pedal_position": 0.2737328654826671, "brake_pedal_position": 0.0, "acceleration": 0.0934044720394348, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.019514986027636308, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141172.071877} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27441608477317775, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.28073447868650236, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3009651329342447, "gear": 1, "accelerator_pedal_position": 0.27441608477317775, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141172.071877} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.649987936019897, "x": 24.689498060017133, "y": -0.38840807568776015, "z": null, "yaw": 0.024726972773131083, "pitch": null, "roll": null}, "v": 2.2950593033583493, "accelerator_pedal_position": 0.2737328654826671, "brake_pedal_position": 0.0, "acceleration": 0.0934044720394348, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.019514986027636308, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141172.091877} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27441608477317775, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.28073447868650236, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.302906357772088, "gear": 1, "accelerator_pedal_position": 0.27441608477317775, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141172.091877} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.649987936019897, "x": 24.689498060017133, "y": -0.38840807568776015, "z": null, "yaw": 0.024726972773131083, "pitch": null, "roll": null}, "v": 2.2950593033583493, "accelerator_pedal_position": 0.2737328654826671, "brake_pedal_position": 0.0, "acceleration": 0.0934044720394348, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.019514986027636308, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141172.111877} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27441608477317775, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.28073447868650236, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3048438553693393, "gear": 1, "accelerator_pedal_position": 0.27441608477317775, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141172.111877} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141172.121877, "x": 28.94241585963284, "y": 4.617954777550101, "z": null, "yaw": 0.025662307411281306, "pitch": null, "roll": null}, "v": 2.3058112082202147, "accelerator_pedal_position": 0.27441608477317775, "brake_pedal_position": 0.0, "acceleration": 0.0966423161418104, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.019606409928030838, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141172.131877} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2760895577954635, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.23268012814224173, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3067776313816326, "gear": 1, "accelerator_pedal_position": 0.27441608477317775, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141172.131877} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.759987831115723, "x": 24.94241585963284, "y": -0.38204522244989914, "z": null, "yaw": 0.025662307411281306, "pitch": null, "roll": null}, "v": 2.3058112082202147, "accelerator_pedal_position": 0.27441608477317775, "brake_pedal_position": 0.0, "acceleration": 0.0966423161418104, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.019606409928030838, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141172.151877} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.275371315156596, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.23268012814224173, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3089167750187243, "gear": 1, "accelerator_pedal_position": 0.2760895577954635, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141172.151877} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.759987831115723, "x": 24.94241585963284, "y": -0.38204522244989914, "z": null, "yaw": 0.025662307411281306, "pitch": null, "roll": null}, "v": 2.3058112082202147, "accelerator_pedal_position": 0.27441608477317775, "brake_pedal_position": 0.0, "acceleration": 0.0966423161418104, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.019606409928030838, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141172.171877} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.275371315156596, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.23268012814224173, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.310962069160609, "gear": 1, "accelerator_pedal_position": 0.275371315156596, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141172.171877} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.759987831115723, "x": 24.94241585963284, "y": -0.38204522244989914, "z": null, "yaw": 0.025662307411281306, "pitch": null, "roll": null}, "v": 2.3058112082202147, "accelerator_pedal_position": 0.27441608477317775, "brake_pedal_position": 0.0, "acceleration": 0.0966423161418104, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.019606409928030838, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141172.191877} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.275371315156596, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.23268012814224173, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3130034296811632, "gear": 1, "accelerator_pedal_position": 0.275371315156596, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141172.191877} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.759987831115723, "x": 24.94241585963284, "y": -0.38204522244989914, "z": null, "yaw": 0.025662307411281306, "pitch": null, "roll": null}, "v": 2.3058112082202147, "accelerator_pedal_position": 0.27441608477317775, "brake_pedal_position": 0.0, "acceleration": 0.0966423161418104, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.019606409928030838, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141172.2118769} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.275371315156596, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.23268012814224173, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3150408624796817, "gear": 1, "accelerator_pedal_position": 0.275371315156596, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141172.2118769} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141172.2318769, "x": 29.1965329889279, "y": 4.624585648287115, "z": null, "yaw": 0.02659764204943153, "pitch": null, "roll": null}, "v": 2.3170743734537256, "accelerator_pedal_position": 0.275371315156596, "brake_pedal_position": 0.0, "acceleration": 0.10152866453487902, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.019702181096922768, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141172.2318769} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2773672111107248, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.17765482952445338, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3170743734537256, "gear": 1, "accelerator_pedal_position": 0.275371315156596, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141172.2318769} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.869987726211548, "x": 25.1965329889279, "y": -0.37541435171288473, "z": null, "yaw": 0.02659764204943153, "pitch": null, "roll": null}, "v": 2.3170743734537256, "accelerator_pedal_position": 0.275371315156596, "brake_pedal_position": 0.0, "acceleration": 0.10152866453487902, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.019702181096922768, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141172.2518768} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27649936243262435, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.17765482952445338, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3193533352867255, "gear": 1, "accelerator_pedal_position": 0.2773672111107248, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141172.2518768} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.869987726211548, "x": 25.1965329889279, "y": -0.37541435171288473, "z": null, "yaw": 0.02659764204943153, "pitch": null, "roll": null}, "v": 2.3170743734537256, "accelerator_pedal_position": 0.275371315156596, "brake_pedal_position": 0.0, "acceleration": 0.10152866453487902, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.019702181096922768, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141172.2718768} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27649936243262435, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.17765482952445338, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3215194777153334, "gear": 1, "accelerator_pedal_position": 0.27649936243262435, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141172.2718768} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.869987726211548, "x": 25.1965329889279, "y": -0.37541435171288473, "z": null, "yaw": 0.02659764204943153, "pitch": null, "roll": null}, "v": 2.3170743734537256, "accelerator_pedal_position": 0.275371315156596, "brake_pedal_position": 0.0, "acceleration": 0.10152866453487902, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.019702181096922768, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141172.2918768} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27649936243262435, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.17765482952445338, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3236814449880243, "gear": 1, "accelerator_pedal_position": 0.27649936243262435, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141172.2918768} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.869987726211548, "x": 25.1965329889279, "y": -0.37541435171288473, "z": null, "yaw": 0.02659764204943153, "pitch": null, "roll": null}, "v": 2.3170743734537256, "accelerator_pedal_position": 0.275371315156596, "brake_pedal_position": 0.0, "acceleration": 0.10152866453487902, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.019702181096922768, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141172.3118768} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27649936243262435, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.17765482952445338, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3269165809953476, "gear": 1, "accelerator_pedal_position": 0.27649936243262435, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141172.3118768} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.869987726211548, "x": 25.1965329889279, "y": -0.37541435171288473, "z": null, "yaw": 0.02659764204943153, "pitch": null, "roll": null}, "v": 2.3170743734537256, "accelerator_pedal_position": 0.275371315156596, "brake_pedal_position": 0.0, "acceleration": 0.10152866453487902, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.019702181096922768, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141172.3318768} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27649936243262435, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.17765482952445338, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3279928787793978, "gear": 1, "accelerator_pedal_position": 0.27649936243262435, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141172.3318768} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141172.3418767, "x": 29.451923606583026, "y": 4.631488798525917, "z": null, "yaw": 0.027532976687581753, "pitch": null, "roll": null}, "v": 2.3290681374076825, "accelerator_pedal_position": 0.27649936243262435, "brake_pedal_position": 0.0, "acceleration": 0.10742202444664112, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01980416457754034, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141172.3518767} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27567758656740243, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.1638617009731126, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3301423576521487, "gear": 1, "accelerator_pedal_position": 0.27649936243262435, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141172.3518767} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.979987621307373, "x": 25.451923606583026, "y": -0.36851120147408256, "z": null, "yaw": 0.027532976687581753, "pitch": null, "roll": null}, "v": 2.3290681374076825, "accelerator_pedal_position": 0.27649936243262435, "brake_pedal_position": 0.0, "acceleration": 0.10742202444664112, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01980416457754034, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141172.3718767} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27615705611899855, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.1638617009731126, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3321850137208266, "gear": 1, "accelerator_pedal_position": 0.27567758656740243, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141172.3718767} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.979987621307373, "x": 25.451923606583026, "y": -0.36851120147408256, "z": null, "yaw": 0.027532976687581753, "pitch": null, "roll": null}, "v": 2.3290681374076825, "accelerator_pedal_position": 0.27649936243262435, "brake_pedal_position": 0.0, "acceleration": 0.10742202444664112, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01980416457754034, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141172.3918767} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27615705611899855, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.1638617009731126, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3342836286442497, "gear": 1, "accelerator_pedal_position": 0.27615705611899855, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141172.3918767} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.979987621307373, "x": 25.451923606583026, "y": -0.36851120147408256, "z": null, "yaw": 0.027532976687581753, "pitch": null, "roll": null}, "v": 2.3290681374076825, "accelerator_pedal_position": 0.27649936243262435, "brake_pedal_position": 0.0, "acceleration": 0.10742202444664112, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01980416457754034, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141172.4118767} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27615705611899855, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.1638617009731126, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.336378187849781, "gear": 1, "accelerator_pedal_position": 0.27615705611899855, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141172.4118767} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.979987621307373, "x": 25.451923606583026, "y": -0.36851120147408256, "z": null, "yaw": 0.027532976687581753, "pitch": null, "roll": null}, "v": 2.3290681374076825, "accelerator_pedal_position": 0.27649936243262435, "brake_pedal_position": 0.0, "acceleration": 0.10742202444664112, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.01980416457754034, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141172.4318767} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27615705611899855, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.1638617009731126, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.338468697421352, "gear": 1, "accelerator_pedal_position": 0.27615705611899855, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141172.4318767} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141172.4518766, "x": 29.708595175622126, "y": 4.638666823278186, "z": null, "yaw": 0.028468311325731976, "pitch": null, "roll": null}, "v": 2.340555163441303, "accelerator_pedal_position": 0.27615705611899855, "brake_pedal_position": 0.0, "acceleration": 0.10417185784055827, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.019901839244254694, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141172.4518766} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2770937390719248, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.1278806140031181, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.340555163441303, "gear": 1, "accelerator_pedal_position": 0.27615705611899855, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141172.4518766} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.089987516403198, "x": 25.708595175622126, "y": -0.3613331767218142, "z": null, "yaw": 0.028468311325731976, "pitch": null, "roll": null}, "v": 2.340555163441303, "accelerator_pedal_position": 0.27615705611899855, "brake_pedal_position": 0.0, "acceleration": 0.10417185784055827, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.019901839244254694, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141172.4718766} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27673232812491816, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.1278806140031181, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3427546206711045, "gear": 1, "accelerator_pedal_position": 0.2770937390719248, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141172.4718766} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.089987516403198, "x": 25.708595175622126, "y": -0.3613331767218142, "z": null, "yaw": 0.028468311325731976, "pitch": null, "roll": null}, "v": 2.340555163441303, "accelerator_pedal_position": 0.27615705611899855, "brake_pedal_position": 0.0, "acceleration": 0.10417185784055827, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.019901839244254694, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141172.4918766} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27673232812491816, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.1278806140031181, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3449046653893997, "gear": 1, "accelerator_pedal_position": 0.27673232812491816, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141172.4918766} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.089987516403198, "x": 25.708595175622126, "y": -0.3613331767218142, "z": null, "yaw": 0.028468311325731976, "pitch": null, "roll": null}, "v": 2.340555163441303, "accelerator_pedal_position": 0.27615705611899855, "brake_pedal_position": 0.0, "acceleration": 0.10417185784055827, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.019901839244254694, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141172.5118766} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27673232812491816, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.1278806140031181, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3470505458837936, "gear": 1, "accelerator_pedal_position": 0.27673232812491816, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141172.5118766} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.089987516403198, "x": 25.708595175622126, "y": -0.3613331767218142, "z": null, "yaw": 0.028468311325731976, "pitch": null, "roll": null}, "v": 2.340555163441303, "accelerator_pedal_position": 0.27615705611899855, "brake_pedal_position": 0.0, "acceleration": 0.10417185784055827, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.019901839244254694, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141172.5318766} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27673232812491816, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.1278806140031181, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3491922683785593, "gear": 1, "accelerator_pedal_position": 0.27673232812491816, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141172.5318766} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.089987516403198, "x": 25.708595175622126, "y": -0.3613331767218142, "z": null, "yaw": 0.028468311325731976, "pitch": null, "roll": null}, "v": 2.340555163441303, "accelerator_pedal_position": 0.27615705611899855, "brake_pedal_position": 0.0, "acceleration": 0.10417185784055827, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.019901839244254694, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141172.5518765} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27673232812491816, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.1278806140031181, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.351329839096611, "gear": 1, "accelerator_pedal_position": 0.27673232812491816, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141172.5518765} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141172.5618765, "x": 29.966543797168576, "y": 4.6461220277124085, "z": null, "yaw": 0.0294036459638822, "pitch": null, "roll": null}, "v": 2.3523970694836476, "accelerator_pedal_position": 0.27673232812491816, "brake_pedal_position": 0.0, "acceleration": 0.10661947758140355, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.020002531470646744, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141172.5718765} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2813269166748684, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.054890999411249135, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3534632642594615, "gear": 1, "accelerator_pedal_position": 0.27673232812491816, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141172.5718765} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.199987411499023, "x": 25.966543797168576, "y": -0.35387797228759155, "z": null, "yaw": 0.0294036459638822, "pitch": null, "roll": null}, "v": 2.3523970694836476, "accelerator_pedal_position": 0.27673232812491816, "brake_pedal_position": 0.0, "acceleration": 0.10661947758140355, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.020002531470646744, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141172.5918765} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27922647005295315, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.054890999411249135, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3561665948406754, "gear": 1, "accelerator_pedal_position": 0.2813269166748684, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141172.5918765} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.199987411499023, "x": 25.966543797168576, "y": -0.35387797228759155, "z": null, "yaw": 0.0294036459638822, "pitch": null, "roll": null}, "v": 2.3523970694836476, "accelerator_pedal_position": 0.27673232812491816, "brake_pedal_position": 0.0, "acceleration": 0.10661947758140355, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.020002531470646744, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141172.6118765} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27922647005295315, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.054890999411249135, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.358602249280362, "gear": 1, "accelerator_pedal_position": 0.27922647005295315, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141172.6118765} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.199987411499023, "x": 25.966543797168576, "y": -0.35387797228759155, "z": null, "yaw": 0.0294036459638822, "pitch": null, "roll": null}, "v": 2.3523970694836476, "accelerator_pedal_position": 0.27673232812491816, "brake_pedal_position": 0.0, "acceleration": 0.10661947758140355, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.020002531470646744, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141172.6318765} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27922647005295315, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.054890999411249135, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3610331730623897, "gear": 1, "accelerator_pedal_position": 0.27922647005295315, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141172.6318765} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.199987411499023, "x": 25.966543797168576, "y": -0.35387797228759155, "z": null, "yaw": 0.0294036459638822, "pitch": null, "roll": null}, "v": 2.3523970694836476, "accelerator_pedal_position": 0.27673232812491816, "brake_pedal_position": 0.0, "acceleration": 0.10661947758140355, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.020002531470646744, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141172.6518764} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27922647005295315, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.054890999411249135, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.363459373012285, "gear": 1, "accelerator_pedal_position": 0.27922647005295315, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141172.6518764} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141172.6718764, "x": 30.225868955271178, "y": 4.6538597960356825, "z": null, "yaw": 0.030338980602032422, "pitch": null, "roll": null}, "v": 2.3658808559560827, "accelerator_pedal_position": 0.27922647005295315, "brake_pedal_position": 0.0, "acceleration": 0.12089747278735813, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.020117184675565745, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141172.6718764} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27832177985695306, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.03509638013746842, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3658808559560827, "gear": 1, "accelerator_pedal_position": 0.27922647005295315, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141172.6718764} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.309987306594849, "x": 26.225868955271178, "y": -0.34614020396431755, "z": null, "yaw": 0.030338980602032422, "pitch": null, "roll": null}, "v": 2.3658808559560827, "accelerator_pedal_position": 0.27922647005295315, "brake_pedal_position": 0.0, "acceleration": 0.12089747278735813, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.020117184675565745, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141172.6918764} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2788524243558819, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.03509638013746842, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.368184597485557, "gear": 1, "accelerator_pedal_position": 0.27832177985695306, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141172.6918764} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.309987306594849, "x": 26.225868955271178, "y": -0.34614020396431755, "z": null, "yaw": 0.030338980602032422, "pitch": null, "roll": null}, "v": 2.3658808559560827, "accelerator_pedal_position": 0.27922647005295315, "brake_pedal_position": 0.0, "acceleration": 0.12089747278735813, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.020117184675565745, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141172.7118764} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2788524243558819, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.03509638013746842, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3705501539774425, "gear": 1, "accelerator_pedal_position": 0.2788524243558819, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141172.7118764} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.309987306594849, "x": 26.225868955271178, "y": -0.34614020396431755, "z": null, "yaw": 0.030338980602032422, "pitch": null, "roll": null}, "v": 2.3658808559560827, "accelerator_pedal_position": 0.27922647005295315, "brake_pedal_position": 0.0, "acceleration": 0.12089747278735813, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.020117184675565745, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141172.7318764} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2788524243558819, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.03509638013746842, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3729111046486806, "gear": 1, "accelerator_pedal_position": 0.2788524243558819, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141172.7318764} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.309987306594849, "x": 26.225868955271178, "y": -0.34614020396431755, "z": null, "yaw": 0.030338980602032422, "pitch": null, "roll": null}, "v": 2.3658808559560827, "accelerator_pedal_position": 0.27922647005295315, "brake_pedal_position": 0.0, "acceleration": 0.12089747278735813, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.020117184675565745, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141172.7518764} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2788524243558819, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.03509638013746842, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3764439094836707, "gear": 1, "accelerator_pedal_position": 0.2788524243558819, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141172.7518764} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2788524243558819, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.03509638013746842, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3764439094836707, "gear": 1, "accelerator_pedal_position": 0.2788524243558819, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141172.7618763} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141172.7818763, "x": 30.486636290438295, "y": 4.661884718818083, "z": null, "yaw": 0.03127431524018265, "pitch": null, "roll": null}, "v": 2.3787933750867944, "accelerator_pedal_position": 0.2788524243558819, "brake_pedal_position": 0.0, "acceleration": 0.11730140425635394, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.02022698037019058, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141172.7918763} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27807968083791995, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.013761248944755835, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.379966389129358, "gear": 1, "accelerator_pedal_position": 0.2788524243558819, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141172.7918763} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.419987201690674, "x": 26.486636290438295, "y": -0.338115281181917, "z": null, "yaw": 0.03127431524018265, "pitch": null, "roll": null}, "v": 2.3787933750867944, "accelerator_pedal_position": 0.2788524243558819, "brake_pedal_position": 0.0, "acceleration": 0.11730140425635394, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.02022698037019058, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141172.8118763} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27854352334860644, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.013761248944755835, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.382212438116495, "gear": 1, "accelerator_pedal_position": 0.27807968083791995, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141172.8118763} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.419987201690674, "x": 26.486636290438295, "y": -0.338115281181917, "z": null, "yaw": 0.03127431524018265, "pitch": null, "roll": null}, "v": 2.3787933750867944, "accelerator_pedal_position": 0.2788524243558819, "brake_pedal_position": 0.0, "acceleration": 0.11730140425635394, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.02022698037019058, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141172.8318763} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27854352334860644, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.013761248944755835, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.38451205547404, "gear": 1, "accelerator_pedal_position": 0.27854352334860644, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141172.8318763} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.419987201690674, "x": 26.486636290438295, "y": -0.338115281181917, "z": null, "yaw": 0.03127431524018265, "pitch": null, "roll": null}, "v": 2.3787933750867944, "accelerator_pedal_position": 0.2788524243558819, "brake_pedal_position": 0.0, "acceleration": 0.11730140425635394, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.02022698037019058, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141172.8518763} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27854352334860644, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.013761248944755835, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3879530643166254, "gear": 1, "accelerator_pedal_position": 0.27854352334860644, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141172.8518763} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.419987201690674, "x": 26.486636290438295, "y": -0.338115281181917, "z": null, "yaw": 0.03127431524018265, "pitch": null, "roll": null}, "v": 2.3787933750867944, "accelerator_pedal_position": 0.2788524243558819, "brake_pedal_position": 0.0, "acceleration": 0.11730140425635394, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.02022698037019058, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141172.8718762} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27854352334860644, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.013761248944755835, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.389097826010017, "gear": 1, "accelerator_pedal_position": 0.27854352334860644, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141172.8718762} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141172.8918762, "x": 30.74880147072861, "y": 4.670198107186077, "z": null, "yaw": 0.03220964987833287, "pitch": null, "roll": null}, "v": 2.3913839925113747, "accelerator_pedal_position": 0.27854352334860644, "brake_pedal_position": 0.0, "acceleration": 0.114140647306825, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.020334038921035198, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141172.8918762} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27439394392426075, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.017899944289270844, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3913839925113747, "gear": 1, "accelerator_pedal_position": 0.27854352334860644, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141172.8918762} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.529987096786499, "x": 26.74880147072861, "y": -0.329801892813923, "z": null, "yaw": 0.03220964987833287, "pitch": null, "roll": null}, "v": 2.3913839925113747, "accelerator_pedal_position": 0.27854352334860644, "brake_pedal_position": 0.0, "acceleration": 0.114140647306825, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.020334038921035198, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141172.9118762} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27646365901959996, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.017899944289270844, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.395165636226102, "gear": 1, "accelerator_pedal_position": 0.27646365901959996, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141172.9118762} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.529987096786499, "x": 26.74880147072861, "y": -0.329801892813923, "z": null, "yaw": 0.03220964987833287, "pitch": null, "roll": null}, "v": 2.3913839925113747, "accelerator_pedal_position": 0.27854352334860644, "brake_pedal_position": 0.0, "acceleration": 0.114140647306825, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.020334038921035198, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141172.9318762} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27646365901959996, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.017899944289270844, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.395165636226102, "gear": 1, "accelerator_pedal_position": 0.27646365901959996, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141172.9318762} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.529987096786499, "x": 26.74880147072861, "y": -0.329801892813923, "z": null, "yaw": 0.03220964987833287, "pitch": null, "roll": null}, "v": 2.3913839925113747, "accelerator_pedal_position": 0.27854352334860644, "brake_pedal_position": 0.0, "acceleration": 0.114140647306825, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.020334038921035198, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141172.9518762} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27646365901959996, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.017899944289270844, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3981858190128547, "gear": 1, "accelerator_pedal_position": 0.27646365901959996, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141172.9518762} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.529987096786499, "x": 26.74880147072861, "y": -0.329801892813923, "z": null, "yaw": 0.03220964987833287, "pitch": null, "roll": null}, "v": 2.3913839925113747, "accelerator_pedal_position": 0.27854352334860644, "brake_pedal_position": 0.0, "acceleration": 0.114140647306825, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.020334038921035198, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141172.9718761} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27646365901959996, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.017899944289270844, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.399190575269822, "gear": 1, "accelerator_pedal_position": 0.27646365901959996, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141172.9718761} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.529987096786499, "x": 26.74880147072861, "y": -0.329801892813923, "z": null, "yaw": 0.03220964987833287, "pitch": null, "roll": null}, "v": 2.3913839925113747, "accelerator_pedal_position": 0.27854352334860644, "brake_pedal_position": 0.0, "acceleration": 0.114140647306825, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.020334038921035198, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141172.9918761} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27646365901959996, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.017899944289270844, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.401197135354027, "gear": 1, "accelerator_pedal_position": 0.27646365901959996, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141172.9918761} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141173.001876, "x": 31.012243520644866, "y": 4.678798632493736, "z": null, "yaw": 0.033144984516483095, "pitch": null, "roll": null}, "v": 2.402198940706792, "accelerator_pedal_position": 0.27646365901959996, "brake_pedal_position": 0.0, "acceleration": 0.10008232432983172, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.02042599888155314, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141173.011876} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26752223656729346, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.06182000012799626, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.403640766943026, "gear": 1, "accelerator_pedal_position": 0.26752223656729346, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141173.011876} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.639986991882324, "x": 27.012243520644866, "y": -0.32120136750626394, "z": null, "yaw": 0.033144984516483095, "pitch": null, "roll": null}, "v": 2.402198940706792, "accelerator_pedal_position": 0.27646365901959996, "brake_pedal_position": 0.0, "acceleration": 0.10008232432983172, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.02042599888155314, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141173.031876} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2718607576867738, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.06182000012799626, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4040813374513594, "gear": 1, "accelerator_pedal_position": 0.26752223656729346, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141173.031876} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.639986991882324, "x": 27.012243520644866, "y": -0.32120136750626394, "z": null, "yaw": 0.033144984516483095, "pitch": null, "roll": null}, "v": 2.402198940706792, "accelerator_pedal_position": 0.27646365901959996, "brake_pedal_position": 0.0, "acceleration": 0.10008232432983172, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.02042599888155314, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141173.051876} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2718607576867738, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.06182000012799626, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.405503231708077, "gear": 1, "accelerator_pedal_position": 0.2718607576867738, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141173.051876} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.639986991882324, "x": 27.012243520644866, "y": -0.32120136750626394, "z": null, "yaw": 0.033144984516483095, "pitch": null, "roll": null}, "v": 2.402198940706792, "accelerator_pedal_position": 0.27646365901959996, "brake_pedal_position": 0.0, "acceleration": 0.10008232432983172, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.02042599888155314, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141173.071876} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2718607576867738, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.06182000012799626, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4069223374927815, "gear": 1, "accelerator_pedal_position": 0.2718607576867738, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141173.071876} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.639986991882324, "x": 27.012243520644866, "y": -0.32120136750626394, "z": null, "yaw": 0.033144984516483095, "pitch": null, "roll": null}, "v": 2.402198940706792, "accelerator_pedal_position": 0.27646365901959996, "brake_pedal_position": 0.0, "acceleration": 0.10008232432983172, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.02042599888155314, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141173.091876} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2718607576867738, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.06182000012799626, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.408338659468786, "gear": 1, "accelerator_pedal_position": 0.2718607576867738, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141173.091876} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141173.111876, "x": 31.276710092404013, "y": 4.687680210885432, "z": null, "yaw": 0.03408031915463332, "pitch": null, "roll": null}, "v": 2.409752202294994, "accelerator_pedal_position": 0.2718607576867738, "brake_pedal_position": 0.0, "acceleration": 0.07057306866293078, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.020490224583320917, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141173.111876} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2667795053967064, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.08809108402634028, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.409752202294994, "gear": 1, "accelerator_pedal_position": 0.2718607576867738, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141173.111876} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.74998688697815, "x": 27.276710092404013, "y": -0.3123197891145679, "z": null, "yaw": 0.03408031915463332, "pitch": null, "roll": null}, "v": 2.409752202294994, "accelerator_pedal_position": 0.2718607576867738, "brake_pedal_position": 0.0, "acceleration": 0.07057306866293078, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.020490224583320917, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141173.131876} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2692556170450349, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.08809108402634028, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.41052812597049, "gear": 1, "accelerator_pedal_position": 0.2667795053967064, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141173.131876} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.74998688697815, "x": 27.276710092404013, "y": -0.3123197891145679, "z": null, "yaw": 0.03408031915463332, "pitch": null, "roll": null}, "v": 2.409752202294994, "accelerator_pedal_position": 0.2718607576867738, "brake_pedal_position": 0.0, "acceleration": 0.07057306866293078, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.020490224583320917, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141173.141876} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2692556170450349, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.08809108402634028, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.41107027338821, "gear": 1, "accelerator_pedal_position": 0.2692556170450349, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141173.141876} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.74998688697815, "x": 27.276710092404013, "y": -0.3123197891145679, "z": null, "yaw": 0.03408031915463332, "pitch": null, "roll": null}, "v": 2.409752202294994, "accelerator_pedal_position": 0.2718607576867738, "brake_pedal_position": 0.0, "acceleration": 0.07057306866293078, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.020490224583320917, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141173.161876} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2692556170450349, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.08809108402634028, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.412693522645672, "gear": 1, "accelerator_pedal_position": 0.2692556170450349, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141173.161876} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.74998688697815, "x": 27.276710092404013, "y": -0.3123197891145679, "z": null, "yaw": 0.03408031915463332, "pitch": null, "roll": null}, "v": 2.409752202294994, "accelerator_pedal_position": 0.2718607576867738, "brake_pedal_position": 0.0, "acceleration": 0.07057306866293078, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.020490224583320917, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141173.181876} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2692556170450349, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.08809108402634028, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.413233542946242, "gear": 1, "accelerator_pedal_position": 0.2692556170450349, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141173.181876} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.74998688697815, "x": 27.276710092404013, "y": -0.3123197891145679, "z": null, "yaw": 0.03408031915463332, "pitch": null, "roll": null}, "v": 2.409752202294994, "accelerator_pedal_position": 0.2718607576867738, "brake_pedal_position": 0.0, "acceleration": 0.07057306866293078, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.020490224583320917, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141173.201876} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2692556170450349, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.08809108402634028, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.414311992150501, "gear": 1, "accelerator_pedal_position": 0.2692556170450349, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141173.201876} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141173.221876, "x": 31.541893318829885, "y": 4.696834165105594, "z": null, "yaw": 0.03501565379278354, "pitch": null, "roll": null}, "v": 2.4153883225784667, "accelerator_pedal_position": 0.2692556170450349, "brake_pedal_position": 0.0, "acceleration": 0.053737182914060655, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.020538148751738306, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141173.221876} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2619413871285473, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.1310761032972451, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4153883225784667, "gear": 1, "accelerator_pedal_position": 0.2692556170450349, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141173.221876} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.859986782073975, "x": 27.541893318829885, "y": -0.30316583489440596, "z": null, "yaw": 0.03501565379278354, "pitch": null, "roll": null}, "v": 2.4153883225784667, "accelerator_pedal_position": 0.2692556170450349, "brake_pedal_position": 0.0, "acceleration": 0.053737182914060655, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.020538148751738306, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141173.241876} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26546654650597934, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.1310761032972451, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4155487086218046, "gear": 1, "accelerator_pedal_position": 0.2619413871285473, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141173.241876} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.859986782073975, "x": 27.541893318829885, "y": -0.30316583489440596, "z": null, "yaw": 0.03501565379278354, "pitch": null, "roll": null}, "v": 2.4153883225784667, "accelerator_pedal_position": 0.2692556170450349, "brake_pedal_position": 0.0, "acceleration": 0.053737182914060655, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.020538148751738306, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141173.2618759} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26546654650597934, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.1310761032972451, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4164490146345092, "gear": 1, "accelerator_pedal_position": 0.26546654650597934, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141173.2618759} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.859986782073975, "x": 27.541893318829885, "y": -0.30316583489440596, "z": null, "yaw": 0.03501565379278354, "pitch": null, "roll": null}, "v": 2.4153883225784667, "accelerator_pedal_position": 0.2692556170450349, "brake_pedal_position": 0.0, "acceleration": 0.053737182914060655, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.020538148751738306, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141173.2718759} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26546654650597934, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.1310761032972451, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4164490146345092, "gear": 1, "accelerator_pedal_position": 0.26546654650597934, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141173.2718759} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.859986782073975, "x": 27.541893318829885, "y": -0.30316583489440596, "z": null, "yaw": 0.03501565379278354, "pitch": null, "roll": null}, "v": 2.4153883225784667, "accelerator_pedal_position": 0.2692556170450349, "brake_pedal_position": 0.0, "acceleration": 0.053737182914060655, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.020538148751738306, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141173.2918758} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26546654650597934, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.1310761032972451, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.417047744248926, "gear": 1, "accelerator_pedal_position": 0.26546654650597934, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141173.2918758} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.859986782073975, "x": 27.541893318829885, "y": -0.30316583489440596, "z": null, "yaw": 0.03501565379278354, "pitch": null, "roll": null}, "v": 2.4153883225784667, "accelerator_pedal_position": 0.2692556170450349, "brake_pedal_position": 0.0, "acceleration": 0.053737182914060655, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.020538148751738306, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141173.3218758} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26546654650597934, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.1310761032972451, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4179436325153874, "gear": 1, "accelerator_pedal_position": 0.26546654650597934, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141173.3218758} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141173.3318758, "x": 31.807542234529354, "y": 4.706252945991118, "z": null, "yaw": 0.035950988430933764, "pitch": null, "roll": null}, "v": 2.4182416747147513, "accelerator_pedal_position": 0.26546654650597934, "brake_pedal_position": 0.0, "acceleration": 0.029774903953361187, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.020562410925264736, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141173.3418758} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2536096853778206, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.19042923191061764, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.418539423754285, "gear": 1, "accelerator_pedal_position": 0.26546654650597934, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141173.3418758} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.9699866771698, "x": 27.807542234529354, "y": -0.29374705400888157, "z": null, "yaw": 0.035950988430933764, "pitch": null, "roll": null}, "v": 2.4182416747147513, "accelerator_pedal_position": 0.26546654650597934, "brake_pedal_position": 0.0, "acceleration": 0.029774903953361187, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.020562410925264736, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141173.3618758} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25927719069604194, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.19042923191061764, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4176526647647556, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141173.3618758} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.9699866771698, "x": 27.807542234529354, "y": -0.29374705400888157, "z": null, "yaw": 0.035950988430933764, "pitch": null, "roll": null}, "v": 2.4182416747147513, "accelerator_pedal_position": 0.26546654650597934, "brake_pedal_position": 0.0, "acceleration": 0.029774903953361187, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.020562410925264736, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141173.3818758} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25927719069604194, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.19042923191061764, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.417475739103426, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141173.3818758} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.9699866771698, "x": 27.807542234529354, "y": -0.29374705400888157, "z": null, "yaw": 0.035950988430933764, "pitch": null, "roll": null}, "v": 2.4182416747147513, "accelerator_pedal_position": 0.26546654650597934, "brake_pedal_position": 0.0, "acceleration": 0.029774903953361187, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.020562410925264736, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141173.3918757} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25927719069604194, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.19042923191061764, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4173874067574617, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141173.3918757} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.9699866771698, "x": 27.807542234529354, "y": -0.29374705400888157, "z": null, "yaw": 0.035950988430933764, "pitch": null, "roll": null}, "v": 2.4182416747147513, "accelerator_pedal_position": 0.26546654650597934, "brake_pedal_position": 0.0, "acceleration": 0.029774903953361187, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.020562410925264736, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141173.4118757} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25927719069604194, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.19042923191061764, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.416947046393846, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141173.4118757} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141173.4418757, "x": 32.073302547565916, "y": 4.715924533795651, "z": null, "yaw": 0.03688632306908399, "pitch": null, "roll": null}, "v": 2.416947046393846, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37926368257041165, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.02055140264606407, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141173.4418757} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2571983317952533, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.22027886252831808, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.416947046393846, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141173.4418757} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.079986572265625, "x": 28.073302547565916, "y": -0.2840754662043494, "z": null, "yaw": 0.03688632306908399, "pitch": null, "roll": null}, "v": 2.416947046393846, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37926368257041165, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.02055140264606407, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141173.4618757} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2581785638271187, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.22027886252831808, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4163557297689264, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141173.4618757} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.079986572265625, "x": 28.073302547565916, "y": -0.2840754662043494, "z": null, "yaw": 0.03688632306908399, "pitch": null, "roll": null}, "v": 2.416947046393846, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37926368257041165, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.02055140264606407, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141173.4818757} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2581785638271187, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.22027886252831808, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.416199834641958, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141173.4818757} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.079986572265625, "x": 28.073302547565916, "y": -0.2840754662043494, "z": null, "yaw": 0.03688632306908399, "pitch": null, "roll": null}, "v": 2.416947046393846, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37926368257041165, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.02055140264606407, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141173.5018756} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2581785638271187, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.22027886252831808, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.415577785426704, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141173.5018756} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.079986572265625, "x": 28.073302547565916, "y": -0.2840754662043494, "z": null, "yaw": 0.03688632306908399, "pitch": null, "roll": null}, "v": 2.416947046393846, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37926368257041165, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.02055140264606407, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141173.5218756} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2581785638271187, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.22027886252831808, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.415577785426704, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141173.5218756} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.079986572265625, "x": 28.073302547565916, "y": -0.2840754662043494, "z": null, "yaw": 0.03688632306908399, "pitch": null, "roll": null}, "v": 2.416947046393846, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37926368257041165, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.02055140264606407, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141173.5418756} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2581785638271187, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.22027886252831808, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4151128520258656, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141173.5418756} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141173.5518756, "x": 32.3388843416725, "y": 4.72583836794937, "z": null, "yaw": 0.03782165770723421, "pitch": null, "roll": null}, "v": 2.4151128520258656, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3790833434814984, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.020535806414014323, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141173.5618756} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2563500025373463, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.2529119925642419, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4148036576794754, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141173.5618756} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.18998646736145, "x": 28.338884341672497, "y": -0.27416163205062993, "z": null, "yaw": 0.03782165770723421, "pitch": null, "roll": null}, "v": 2.4151128520258656, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3790833434814984, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.020535806414014323, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141173.5818756} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25720700631571725, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.2529119925642419, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4142666130673858, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141173.5818756} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.18998646736145, "x": 28.338884341672497, "y": -0.27416163205062993, "z": null, "yaw": 0.03782165770723421, "pitch": null, "roll": null}, "v": 2.4151128520258656, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3790833434814984, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.020535806414014323, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141173.6018755} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25720700631571725, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.2529119925642419, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4138376964680694, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141173.6018755} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.18998646736145, "x": 28.338884341672497, "y": -0.27416163205062993, "z": null, "yaw": 0.03782165770723421, "pitch": null, "roll": null}, "v": 2.4151128520258656, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3790833434814984, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.020535806414014323, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141173.6218755} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25720700631571725, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.2529119925642419, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4136235542720788, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141173.6218755} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.18998646736145, "x": 28.338884341672497, "y": -0.27416163205062993, "z": null, "yaw": 0.03782165770723421, "pitch": null, "roll": null}, "v": 2.4151128520258656, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3790833434814984, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.020535806414014323, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141173.6418755} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25720700631571725, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.2529119925642419, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.413195901006363, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141173.6418755} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141173.6618755, "x": 32.604237907626064, "y": 4.735992226359615, "z": null, "yaw": 0.03875699234538443, "pitch": null, "roll": null}, "v": 2.4127690878037025, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3788530011007962, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.02051587728800845, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141173.6618755} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24927822102644578, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.29535035555246847, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.412555995687427, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141173.6618755} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.299986362457275, "x": 28.604237907626064, "y": -0.26400777364038497, "z": null, "yaw": 0.03875699234538443, "pitch": null, "roll": null}, "v": 2.4127690878037025, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3788530011007962, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.02051587728800845, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141173.6818755} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2530362850506006, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.29535035555246847, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.411139828025596, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141173.6818755} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.299986362457275, "x": 28.604237907626064, "y": -0.26400777364038497, "z": null, "yaw": 0.03875699234538443, "pitch": null, "roll": null}, "v": 2.4127690878037025, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3788530011007962, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.02051587728800845, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141173.7018754} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2530362850506006, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.29535035555246847, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.410195968522896, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141173.7018754} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.299986362457275, "x": 28.604237907626064, "y": -0.26400777364038497, "z": null, "yaw": 0.03875699234538443, "pitch": null, "roll": null}, "v": 2.4127690878037025, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3788530011007962, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.02051587728800845, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141173.7218754} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2530362850506006, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.29535035555246847, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4097247338936287, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141173.7218754} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.299986362457275, "x": 28.604237907626064, "y": -0.26400777364038497, "z": null, "yaw": 0.03875699234538443, "pitch": null, "roll": null}, "v": 2.4127690878037025, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3788530011007962, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.02051587728800845, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141173.7418754} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2530362850506006, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.29535035555246847, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.408783652382339, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141173.7418754} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.299986362457275, "x": 28.604237907626064, "y": -0.26400777364038497, "z": null, "yaw": 0.03875699234538443, "pitch": null, "roll": null}, "v": 2.4127690878037025, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3788530011007962, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.02051587728800845, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141173.7618754} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2530362850506006, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.29535035555246847, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.407375492011379, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141173.7618754} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141173.7718754, "x": 32.8691653728515, "y": 4.746377920759195, "z": null, "yaw": 0.039692326983534656, "pitch": null, "roll": null}, "v": 2.407375492011379, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3783233421959392, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.020470015315565342, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141173.7818754} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2519988028985296, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.3324217592204302, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.406907026405082, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141173.7818754} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.4099862575531, "x": 28.869165372851498, "y": -0.25362207924080504, "z": null, "yaw": 0.039692326983534656, "pitch": null, "roll": null}, "v": 2.407375492011379, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3783233421959392, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.020470015315565342, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141173.8018754} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25245248728101904, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.3324217592204302, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.405310049106562, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141173.8018754} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.4099862575531, "x": 28.869165372851498, "y": -0.25362207924080504, "z": null, "yaw": 0.039692326983534656, "pitch": null, "roll": null}, "v": 2.407375492011379, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3783233421959392, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.020470015315565342, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141173.8218753} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25245248728101904, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.3324217592204302, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4043046900576237, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141173.8218753} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.4099862575531, "x": 28.869165372851498, "y": -0.25362207924080504, "z": null, "yaw": 0.039692326983534656, "pitch": null, "roll": null}, "v": 2.407375492011379, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3783233421959392, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.020470015315565342, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141173.8418753} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25245248728101904, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.3324217592204302, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4033013023773058, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141173.8418753} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.4099862575531, "x": 28.869165372851498, "y": -0.25362207924080504, "z": null, "yaw": 0.039692326983534656, "pitch": null, "roll": null}, "v": 2.407375492011379, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3783233421959392, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.020470015315565342, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141173.8618753} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25245248728101904, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.3324217592204302, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4022998817975125, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141173.8618753} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141173.8818753, "x": 33.13348377077363, "y": 4.756987353101098, "z": null, "yaw": 0.04062766162168488, "pitch": null, "roll": null}, "v": 2.401799907839469, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37777642336495026, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.020422605888257075, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141173.8818753} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24810783376883205, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.37237116553342675, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.401799907839469, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141173.8818753} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.519986152648926, "x": 29.13348377077363, "y": -0.24301264689890179, "z": null, "yaw": 0.04062766162168488, "pitch": null, "roll": null}, "v": 2.401799907839469, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37777642336495026, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.020422605888257075, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141173.9018753} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2501350474001942, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.37237116553342675, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3988470416950927, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141173.9018753} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.519986152648926, "x": 29.13348377077363, "y": -0.24301264689890179, "z": null, "yaw": 0.04062766162168488, "pitch": null, "roll": null}, "v": 2.401799907839469, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37777642336495026, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.020422605888257075, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141173.9218752} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2501350474001942, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.37237116553342675, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3988470416950927, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141173.9218752} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.519986152648926, "x": 29.13348377077363, "y": -0.24301264689890179, "z": null, "yaw": 0.04062766162168488, "pitch": null, "roll": null}, "v": 2.401799907839469, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37777642336495026, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.020422605888257075, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141173.9518752} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2501350474001942, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.37237116553342675, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3969246369198003, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141173.9518752} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.519986152648926, "x": 29.13348377077363, "y": -0.24301264689890179, "z": null, "yaw": 0.04062766162168488, "pitch": null, "roll": null}, "v": 2.401799907839469, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37777642336495026, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.020422605888257075, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141173.9718752} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2501350474001942, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.37237116553342675, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3956461699863154, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141173.9718752} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141173.9918752, "x": 33.3970720680638, "y": 4.76781441466846, "z": null, "yaw": 0.0415629962598351, "pitch": null, "roll": null}, "v": 2.3943702055592384, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37704859709065985, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.020359430816494863, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141173.9918752} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24546359662248327, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4113245532998254, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3943702055592384, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4709767339446013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141173.9918752} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.629986047744751, "x": 29.3970720680638, "y": -0.23218558533154, "z": null, "yaw": 0.0415629962598351, "pitch": null, "roll": null}, "v": 2.3943702055592384, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37704859709065985, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.020359430816494863, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141174.0118752} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24763264464593393, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4113245532998254, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3925130924938594, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4310406380631588, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141174.0118752} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.629986047744751, "x": 29.3970720680638, "y": -0.23218558533154, "z": null, "yaw": 0.0415629962598351, "pitch": null, "roll": null}, "v": 2.3943702055592384, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37704859709065985, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.020359430816494863, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141174.0318751} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24763264464593393, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4113245532998254, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.390930610750102, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4310406380631588, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141174.0318751} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.629986047744751, "x": 29.3970720680638, "y": -0.23218558533154, "z": null, "yaw": 0.0415629962598351, "pitch": null, "roll": null}, "v": 2.3943702055592384, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37704859709065985, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.020359430816494863, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141174.051875} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24763264464593393, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4113245532998254, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.389351223665813, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4310406380631588, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141174.051875} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.629986047744751, "x": 29.3970720680638, "y": -0.23218558533154, "z": null, "yaw": 0.0415629962598351, "pitch": null, "roll": null}, "v": 2.3943702055592384, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37704859709065985, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.020359430816494863, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141174.071875} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24763264464593393, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4113245532998254, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3877749241918598, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4310406380631588, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141174.071875} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.629986047744751, "x": 29.3970720680638, "y": -0.23218558533154, "z": null, "yaw": 0.0415629962598351, "pitch": null, "roll": null}, "v": 2.3943702055592384, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37704859709065985, "steering_wheel_angle": 0.4709767339446013, "front_wheel_angle": 0.021764350794722866, "heading_rate": 0.020359430816494863, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141174.091875} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24763264464593393, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4113245532998254, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.38620170529874, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4310406380631588, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141174.091875} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141174.101875, "x": 33.65976061553092, "y": 4.778842828766993, "z": null, "yaw": 0.042425795630445254, "pitch": null, "roll": null}, "v": 2.3854162488786246, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37617291924807295, "steering_wheel_angle": 0.4310406380631588, "front_wheel_angle": 0.019908254539773313, "heading_rate": 0.0185530268872279, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141174.111875} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2482852054388762, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4538868826813048, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3846315599765147, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4310406380631588, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141174.111875} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.739985942840576, "x": 29.65976061553092, "y": -0.22115717123300715, "z": null, "yaw": 0.042425795630445254, "pitch": null, "roll": null}, "v": 2.3854162488786246, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37617291924807295, "steering_wheel_angle": 0.4310406380631588, "front_wheel_angle": 0.019908254539773313, "heading_rate": 0.0185530268872279, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141174.131875} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.247907743703767, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4538868826813048, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.383146011496097, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3910161345993913, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141174.131875} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.739985942840576, "x": 29.65976061553092, "y": -0.22115717123300715, "z": null, "yaw": 0.042425795630445254, "pitch": null, "roll": null}, "v": 2.3854162488786246, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37617291924807295, "steering_wheel_angle": 0.4310406380631588, "front_wheel_angle": 0.019908254539773313, "heading_rate": 0.0185530268872279, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141174.151875} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.247907743703767, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4538868826813048, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3816162037989543, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3910161345993913, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141174.151875} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.739985942840576, "x": 29.65976061553092, "y": -0.22115717123300715, "z": null, "yaw": 0.042425795630445254, "pitch": null, "roll": null}, "v": 2.3854162488786246, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37617291924807295, "steering_wheel_angle": 0.4310406380631588, "front_wheel_angle": 0.019908254539773313, "heading_rate": 0.0185530268872279, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141174.171875} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.247907743703767, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4538868826813048, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.380089382051122, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3910161345993913, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141174.171875} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.739985942840576, "x": 29.65976061553092, "y": -0.22115717123300715, "z": null, "yaw": 0.042425795630445254, "pitch": null, "roll": null}, "v": 2.3854162488786246, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37617291924807295, "steering_wheel_angle": 0.4310406380631588, "front_wheel_angle": 0.019908254539773313, "heading_rate": 0.0185530268872279, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141174.191875} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.247907743703767, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4538868826813048, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3785655394924676, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3910161345993913, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141174.191875} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141174.211875, "x": 33.92149798315181, "y": 4.790049591627915, "z": null, "yaw": 0.04321599012382982, "pitch": null, "roll": null}, "v": 2.377044669381504, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37535564707142544, "steering_wheel_angle": 0.3910161345993913, "front_wheel_angle": 0.01805004172138894, "heading_rate": 0.01676188112719099, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141174.211875} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2486180184826604, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.49906088107600616, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.377044669381504, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3910161345993913, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141174.211875} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.849985837936401, "x": 29.92149798315181, "y": -0.20995040837208467, "z": null, "yaw": 0.04321599012382982, "pitch": null, "roll": null}, "v": 2.377044669381504, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37535564707142544, "steering_wheel_angle": 0.3910161345993913, "front_wheel_angle": 0.01805004172138894, "heading_rate": 0.01676188112719099, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141174.231875} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2482175238410925, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.49906088107600616, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3756155060487125, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.35090010379455516, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141174.231875} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.849985837936401, "x": 29.92149798315181, "y": -0.20995040837208467, "z": null, "yaw": 0.04321599012382982, "pitch": null, "roll": null}, "v": 2.377044669381504, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37535564707142544, "steering_wheel_angle": 0.3910161345993913, "front_wheel_angle": 0.01805004172138894, "heading_rate": 0.01676188112719099, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141174.251875} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2482175238410925, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.49906088107600616, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3741390913558855, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.35090010379455516, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141174.251875} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.849985837936401, "x": 29.92149798315181, "y": -0.20995040837208467, "z": null, "yaw": 0.04321599012382982, "pitch": null, "roll": null}, "v": 2.377044669381504, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37535564707142544, "steering_wheel_angle": 0.3910161345993913, "front_wheel_angle": 0.01805004172138894, "heading_rate": 0.01676188112719099, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141174.271875} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2482175238410925, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.49906088107600616, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.372665553978139, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.35090010379455516, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141174.271875} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.849985837936401, "x": 29.92149798315181, "y": -0.20995040837208467, "z": null, "yaw": 0.04321599012382982, "pitch": null, "roll": null}, "v": 2.377044669381504, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37535564707142544, "steering_wheel_angle": 0.3910161345993913, "front_wheel_angle": 0.01805004172138894, "heading_rate": 0.01676188112719099, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141174.291875} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2482175238410925, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.49906088107600616, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.371194887439907, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.35090010379455516, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141174.291875} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.849985837936401, "x": 29.92149798315181, "y": -0.20995040837208467, "z": null, "yaw": 0.04321599012382982, "pitch": null, "roll": null}, "v": 2.377044669381504, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37535564707142544, "steering_wheel_angle": 0.3910161345993913, "front_wheel_angle": 0.01805004172138894, "heading_rate": 0.01676188112719099, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141174.3018749} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2482175238410925, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.49906088107600616, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3682621410681133, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.35090010379455516, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141174.3018749} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141174.3218749, "x": 34.18232442878285, "y": 4.8014127994018265, "z": null, "yaw": 0.04391896626987345, "pitch": null, "roll": null}, "v": 2.3689942563348674, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3745710506822193, "steering_wheel_angle": 0.35090010379455516, "front_wheel_angle": 0.016189574525158717, "heading_rate": 0.014982953210236464, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141174.3318748} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23660600029959628, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5349244274367551, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.367530738680766, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.35090010379455516, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141174.3318748} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.959985733032227, "x": 30.18232442878285, "y": -0.19858720059817347, "z": null, "yaw": 0.04391896626987345, "pitch": null, "roll": null}, "v": 2.3689942563348674, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3745710506822193, "steering_wheel_angle": 0.35090010379455516, "front_wheel_angle": 0.016189574525158717, "heading_rate": 0.014982953210236464, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141174.3518748} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.242075521183872, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5349244274367551, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3638491156329953, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3107022975811914, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141174.3518748} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.959985733032227, "x": 30.18232442878285, "y": -0.19858720059817347, "z": null, "yaw": 0.04391896626987345, "pitch": null, "roll": null}, "v": 2.3689942563348674, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3745710506822193, "steering_wheel_angle": 0.35090010379455516, "front_wheel_angle": 0.016189574525158717, "heading_rate": 0.014982953210236464, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141174.3718748} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.242075521183872, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5349244274367551, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3638491156329953, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3107022975811914, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141174.3718748} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.959985733032227, "x": 30.18232442878285, "y": -0.19858720059817347, "z": null, "yaw": 0.04391896626987345, "pitch": null, "roll": null}, "v": 2.3689942563348674, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3745710506822193, "steering_wheel_angle": 0.35090010379455516, "front_wheel_angle": 0.016189574525158717, "heading_rate": 0.014982953210236464, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141174.3918748} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.242075521183872, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5349244274367551, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.361628230744113, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3107022975811914, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141174.3918748} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.959985733032227, "x": 30.18232442878285, "y": -0.19858720059817347, "z": null, "yaw": 0.04391896626987345, "pitch": null, "roll": null}, "v": 2.3689942563348674, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3745710506822193, "steering_wheel_angle": 0.35090010379455516, "front_wheel_angle": 0.016189574525158717, "heading_rate": 0.014982953210236464, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141174.4118748} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.242075521183872, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5349244274367551, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.35719940232963, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3107022975811914, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141174.4118748} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141174.4318748, "x": 34.442093023748306, "y": 4.812906324623585, "z": null, "yaw": 0.044556463552950225, "pitch": null, "roll": null}, "v": 2.35719940232963, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3734238603399132, "steering_wheel_angle": 0.3107022975811914, "front_wheel_angle": 0.014327311728453841, "heading_rate": 0.013193219402128354, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141174.4318748} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24442499666203638, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5798134281711734, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.35719940232963, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3107022975811914, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141174.4318748} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.069985628128052, "x": 30.442093023748306, "y": -0.1870936753764152, "z": null, "yaw": 0.044556463552950225, "pitch": null, "roll": null}, "v": 2.35719940232963, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3734238603399132, "steering_wheel_angle": 0.3107022975811914, "front_wheel_angle": 0.014327311728453841, "heading_rate": 0.013193219402128354, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141174.4518747} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2432187932342787, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5798134281711734, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3542537752923343, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2704126627993296, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141174.4518747} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.069985628128052, "x": 30.442093023748306, "y": -0.1870936753764152, "z": null, "yaw": 0.044556463552950225, "pitch": null, "roll": null}, "v": 2.35719940232963, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3734238603399132, "steering_wheel_angle": 0.3107022975811914, "front_wheel_angle": 0.014327311728453841, "heading_rate": 0.013193219402128354, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141174.4718747} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2432187932342787, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5798134281711734, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3532235718979826, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2704126627993296, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141174.4718747} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.069985628128052, "x": 30.442093023748306, "y": -0.1870936753764152, "z": null, "yaw": 0.044556463552950225, "pitch": null, "roll": null}, "v": 2.35719940232963, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3734238603399132, "steering_wheel_angle": 0.3107022975811914, "front_wheel_angle": 0.014327311728453841, "heading_rate": 0.013193219402128354, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141174.4918747} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2432187932342787, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5798134281711734, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3511661641293453, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2704126627993296, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141174.4918747} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.069985628128052, "x": 30.442093023748306, "y": -0.1870936753764152, "z": null, "yaw": 0.044556463552950225, "pitch": null, "roll": null}, "v": 2.35719940232963, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3734238603399132, "steering_wheel_angle": 0.3107022975811914, "front_wheel_angle": 0.014327311728453841, "heading_rate": 0.013193219402128354, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141174.5118747} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2432187932342787, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5798134281711734, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3480875323114883, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2704126627993296, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141174.5118747} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.069985628128052, "x": 30.442093023748306, "y": -0.1870936753764152, "z": null, "yaw": 0.044556463552950225, "pitch": null, "roll": null}, "v": 2.35719940232963, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3734238603399132, "steering_wheel_angle": 0.3107022975811914, "front_wheel_angle": 0.014327311728453841, "heading_rate": 0.013193219402128354, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141174.5318747} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2432187932342787, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5798134281711734, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.347063311616535, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2704126627993296, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141174.5318747} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141174.5418746, "x": 34.7005730059964, "y": 4.824495612886367, "z": null, "yaw": 0.04509928654533487, "pitch": null, "roll": null}, "v": 2.3460400839189957, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37234104494949627, "steering_wheel_angle": 0.2704126627993296, "front_wheel_angle": 0.0124627941053964, "heading_rate": 0.011421768904228725, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141174.5518746} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24563172647004, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6271111365479624, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.345017848046643, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2704126627993296, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141174.5518746} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.179985523223877, "x": 30.700573005996397, "y": -0.1755043871136328, "z": null, "yaw": 0.04509928654533487, "pitch": null, "roll": null}, "v": 2.3460400839189957, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37234104494949627, "steering_wheel_angle": 0.2704126627993296, "front_wheel_angle": 0.0124627941053964, "heading_rate": 0.011421768904228725, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141174.5718746} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24440020980806837, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6271111365479624, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3432778176465074, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.23002823182223395, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141174.5718746} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.179985523223877, "x": 30.700573005996397, "y": -0.1755043871136328, "z": null, "yaw": 0.04509928654533487, "pitch": null, "roll": null}, "v": 2.3460400839189957, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37234104494949627, "steering_wheel_angle": 0.2704126627993296, "front_wheel_angle": 0.0124627941053964, "heading_rate": 0.011421768904228725, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141174.5918746} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24440020980806837, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6271111365479624, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3413872918570964, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.23002823182223395, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141174.5918746} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.179985523223877, "x": 30.700573005996397, "y": -0.1755043871136328, "z": null, "yaw": 0.04509928654533487, "pitch": null, "roll": null}, "v": 2.3460400839189957, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37234104494949627, "steering_wheel_angle": 0.2704126627993296, "front_wheel_angle": 0.0124627941053964, "heading_rate": 0.011421768904228725, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141174.6118746} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24440020980806837, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6271111365479624, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3385583624353616, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.23002823182223395, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141174.6118746} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.179985523223877, "x": 30.700573005996397, "y": -0.1755043871136328, "z": null, "yaw": 0.04509928654533487, "pitch": null, "roll": null}, "v": 2.3460400839189957, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37234104494949627, "steering_wheel_angle": 0.2704126627993296, "front_wheel_angle": 0.0124627941053964, "heading_rate": 0.011421768904228725, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141174.6318746} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24440020980806837, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6271111365479624, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3376172108456967, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.23002823182223395, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141174.6318746} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141174.6518745, "x": 34.95785856235377, "y": 4.836163442126726, "z": null, "yaw": 0.04556918292758674, "pitch": null, "roll": null}, "v": 2.3357376386326925, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37134358509688886, "steering_wheel_angle": 0.23002823182223395, "front_wheel_angle": 0.010595891779883121, "heading_rate": 0.009668027152067016, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141174.6518745} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24674332045968328, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6774691981370174, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3357376386326925, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.23002823182223395, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141174.6518745} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.289985418319702, "x": 30.95785856235377, "y": -0.16383655787327367, "z": null, "yaw": 0.04556918292758674, "pitch": null, "roll": null}, "v": 2.3357376386326925, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37134358509688886, "steering_wheel_angle": 0.23002823182223395, "front_wheel_angle": 0.010595891779883121, "heading_rate": 0.009668027152067016, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141174.6718745} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24555155594623432, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6774691981370174, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3341544478853686, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.14901891031904077, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141174.6718745} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.289985418319702, "x": 30.95785856235377, "y": -0.16383655787327367, "z": null, "yaw": 0.04556918292758674, "pitch": null, "roll": null}, "v": 2.3357376386326925, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37134358509688886, "steering_wheel_angle": 0.23002823182223395, "front_wheel_angle": 0.010595891779883121, "heading_rate": 0.009668027152067016, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141174.6918745} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24555155594623432, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6774691981370174, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3324254187022637, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.14901891031904077, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141174.6918745} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.289985418319702, "x": 30.95785856235377, "y": -0.16383655787327367, "z": null, "yaw": 0.04556918292758674, "pitch": null, "roll": null}, "v": 2.3357376386326925, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37134358509688886, "steering_wheel_angle": 0.23002823182223395, "front_wheel_angle": 0.010595891779883121, "heading_rate": 0.009668027152067016, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141174.7118745} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24555155594623432, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6774691981370174, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3306997303647234, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.14901891031904077, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141174.7118745} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.289985418319702, "x": 30.95785856235377, "y": -0.16383655787327367, "z": null, "yaw": 0.04556918292758674, "pitch": null, "roll": null}, "v": 2.3357376386326925, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37134358509688886, "steering_wheel_angle": 0.23002823182223395, "front_wheel_angle": 0.010595891779883121, "heading_rate": 0.009668027152067016, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141174.7318745} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24555155594623432, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6774691981370174, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3289773752269105, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.14901891031904077, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141174.7318745} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.289985418319702, "x": 30.95785856235377, "y": -0.16383655787327367, "z": null, "yaw": 0.04556918292758674, "pitch": null, "roll": null}, "v": 2.3357376386326925, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37134358509688886, "steering_wheel_angle": 0.23002823182223395, "front_wheel_angle": 0.010595891779883121, "heading_rate": 0.009668027152067016, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141174.7518744} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24555155594623432, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6774691981370174, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3272583456646565, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.14901891031904077, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141174.7518744} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141174.7618744, "x": 35.214060588193384, "y": 4.84788574789527, "z": null, "yaw": 0.0458857329980996, "pitch": null, "roll": null}, "v": 2.3264000755977174, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37044137689729656, "steering_wheel_angle": 0.14901891031904077, "front_wheel_angle": 0.006856988955221961, "heading_rate": 0.006231386578916164, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141174.7618744} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24087170635399677, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7184407139801895, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3264000755977174, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.14901891031904077, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141174.7618744} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.399985313415527, "x": 31.214060588193384, "y": -0.15211425210473006, "z": null, "yaw": 0.0458857329980996, "pitch": null, "roll": null}, "v": 2.3264000755977174, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37044137689729656, "steering_wheel_angle": 0.14901891031904077, "front_wheel_angle": 0.006856988955221961, "heading_rate": 0.006231386578916164, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141174.7918744} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24303146756636937, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7184407139801895, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.32295360751966, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.10840393210575795, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141174.7918744} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.399985313415527, "x": 31.214060588193384, "y": -0.15211425210473006, "z": null, "yaw": 0.0458857329980996, "pitch": null, "roll": null}, "v": 2.3264000755977174, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37044137689729656, "steering_wheel_angle": 0.14901891031904077, "front_wheel_angle": 0.006856988955221961, "heading_rate": 0.006231386578916164, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141174.8118744} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24303146756636937, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7184407139801895, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3209313403637033, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.10840393210575795, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141174.8118744} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.399985313415527, "x": 31.214060588193384, "y": -0.15211425210473006, "z": null, "yaw": 0.0458857329980996, "pitch": null, "roll": null}, "v": 2.3264000755977174, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37044137689729656, "steering_wheel_angle": 0.14901891031904077, "front_wheel_angle": 0.006856988955221961, "heading_rate": 0.006231386578916164, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141174.8318744} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24303146756636937, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7184407139801895, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.318912971420939, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.10840393210575795, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141174.8318744} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.399985313415527, "x": 31.214060588193384, "y": -0.15211425210473006, "z": null, "yaw": 0.0458857329980996, "pitch": null, "roll": null}, "v": 2.3264000755977174, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37044137689729656, "steering_wheel_angle": 0.14901891031904077, "front_wheel_angle": 0.006856988955221961, "heading_rate": 0.006231386578916164, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141174.8518744} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24303146756636937, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7184407139801895, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3168984915482547, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.10840393210575795, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141174.8518744} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141174.8718743, "x": 35.469101733117185, "y": 4.859623280600529, "z": null, "yaw": 0.04610726451456504, "pitch": null, "roll": null}, "v": 2.3148878916295716, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36933145408961066, "steering_wheel_angle": 0.10840393210575795, "front_wheel_angle": 0.004985455874461165, "heading_rate": 0.004508151192735118, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141174.8718743} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23170523872072096, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7300002826248885, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3148878916295716, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.10840393210575795, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141174.8718743} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.509985208511353, "x": 31.469101733117185, "y": -0.14037671939947138, "z": null, "yaw": 0.04610726451456504, "pitch": null, "roll": null}, "v": 2.3148878916295716, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36933145408961066, "steering_wheel_angle": 0.10840393210575795, "front_wheel_angle": 0.004985455874461165, "heading_rate": 0.004508151192735118, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141174.8918743} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23701411813293755, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7300002826248885, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3114660654593324, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.10840393210575795, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141174.8918743} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.509985208511353, "x": 31.469101733117185, "y": -0.14037671939947138, "z": null, "yaw": 0.04610726451456504, "pitch": null, "roll": null}, "v": 2.3148878916295716, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36933145408961066, "steering_wheel_angle": 0.10840393210575795, "front_wheel_angle": 0.004985455874461165, "heading_rate": 0.004508151192735118, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141174.9118743} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23701411813293755, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7300002826248885, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.308714113626207, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.10840393210575795, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141174.9118743} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.509985208511353, "x": 31.469101733117185, "y": -0.14037671939947138, "z": null, "yaw": 0.04610726451456504, "pitch": null, "roll": null}, "v": 2.3148878916295716, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36933145408961066, "steering_wheel_angle": 0.10840393210575795, "front_wheel_angle": 0.004985455874461165, "heading_rate": 0.004508151192735118, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141174.9318743} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23701411813293755, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7300002826248885, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3059674533444725, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.10840393210575795, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141174.9318743} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.509985208511353, "x": 31.469101733117185, "y": -0.14037671939947138, "z": null, "yaw": 0.04610726451456504, "pitch": null, "roll": null}, "v": 2.3148878916295716, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36933145408961066, "steering_wheel_angle": 0.10840393210575795, "front_wheel_angle": 0.004985455874461165, "heading_rate": 0.004508151192735118, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141174.9518743} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23701411813293755, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7300002826248885, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.303226071423137, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.10840393210575795, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141174.9518743} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.509985208511353, "x": 31.469101733117185, "y": -0.14037671939947138, "z": null, "yaw": 0.04610726451456504, "pitch": null, "roll": null}, "v": 2.3148878916295716, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36933145408961066, "steering_wheel_angle": 0.10840393210575795, "front_wheel_angle": 0.004985455874461165, "heading_rate": 0.004508151192735118, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141174.9718742} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23701411813293755, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7300002826248885, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.30048995471395, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.10840393210575795, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141174.9718742} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141174.9818742, "x": 35.722648955230014, "y": 4.871346651558874, "z": null, "yaw": 0.04632148509647488, "pitch": null, "roll": null}, "v": 2.2991238667167275, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36781589888090116, "steering_wheel_angle": 0.10840393210575795, "front_wheel_angle": 0.004985455874461165, "heading_rate": 0.004477451387370843, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141174.9918742} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24137574769742093, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7782958274478469, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.297759090111227, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.10840393210575795, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141174.9918742} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.619985103607178, "x": 31.722648955230014, "y": -0.12865334844112564, "z": null, "yaw": 0.04632148509647488, "pitch": null, "roll": null}, "v": 2.2991238667167275, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36781589888090116, "steering_wheel_angle": 0.10840393210575795, "front_wheel_angle": 0.004985455874461165, "heading_rate": 0.004477451387370843, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141175.0118742} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2391833092698798, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7782958274478469, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.295578406738549, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.06767907017233882, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141175.0118742} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.619985103607178, "x": 31.722648955230014, "y": -0.12865334844112564, "z": null, "yaw": 0.04632148509647488, "pitch": null, "roll": null}, "v": 2.2991238667167275, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36781589888090116, "steering_wheel_angle": 0.10840393210575795, "front_wheel_angle": 0.004985455874461165, "heading_rate": 0.004477451387370843, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141175.0318742} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2391833092698798, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7782958274478469, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2931279814803722, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.06767907017233882, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141175.0318742} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.619985103607178, "x": 31.722648955230014, "y": -0.12865334844112564, "z": null, "yaw": 0.04632148509647488, "pitch": null, "roll": null}, "v": 2.2991238667167275, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36781589888090116, "steering_wheel_angle": 0.10840393210575795, "front_wheel_angle": 0.004985455874461165, "heading_rate": 0.004477451387370843, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141175.0518742} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2391833092698798, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7782958274478469, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.290682252651264, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.06767907017233882, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141175.0518742} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.619985103607178, "x": 31.722648955230014, "y": -0.12865334844112564, "z": null, "yaw": 0.04632148509647488, "pitch": null, "roll": null}, "v": 2.2991238667167275, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36781589888090116, "steering_wheel_angle": 0.10840393210575795, "front_wheel_angle": 0.004985455874461165, "heading_rate": 0.004477451387370843, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141175.0718741} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2391833092698798, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7782958274478469, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2882412088586643, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.06767907017233882, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141175.0718741} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141175.0918741, "x": 35.974616751354084, "y": 4.883045047872106, "z": null, "yaw": 0.04646980113969472, "pitch": null, "roll": null}, "v": 2.285804838745584, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36653927954560644, "steering_wheel_angle": 0.06767907017233882, "front_wheel_angle": 0.003110869154397358, "heading_rate": 0.002777680743873027, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141175.0918741} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24289038529396245, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.829190877466107, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.285804838745584, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.06767907017233882, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141175.0918741} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.729984998703003, "x": 31.974616751354084, "y": -0.11695495212789364, "z": null, "yaw": 0.04646980113969472, "pitch": null, "roll": null}, "v": 2.285804838745584, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36653927954560644, "steering_wheel_angle": 0.06767907017233882, "front_wheel_angle": 0.003110869154397358, "heading_rate": 0.002777680743873027, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141175.111874} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24102784383128933, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.829190877466107, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2838362937776915, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.026853801333475497, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141175.111874} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.729984998703003, "x": 31.974616751354084, "y": -0.11695495212789364, "z": null, "yaw": 0.04646980113969472, "pitch": null, "roll": null}, "v": 2.285804838745584, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36653927954560644, "steering_wheel_angle": 0.06767907017233882, "front_wheel_angle": 0.003110869154397358, "heading_rate": 0.002777680743873027, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141175.131874} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24102784383128933, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.829190877466107, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2816388079429593, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.026853801333475497, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141175.131874} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.729984998703003, "x": 31.974616751354084, "y": -0.11695495212789364, "z": null, "yaw": 0.04646980113969472, "pitch": null, "roll": null}, "v": 2.285804838745584, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36653927954560644, "steering_wheel_angle": 0.06767907017233882, "front_wheel_angle": 0.003110869154397358, "heading_rate": 0.002777680743873027, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141175.151874} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24102784383128933, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.829190877466107, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.27944552361457, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.026853801333475497, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141175.151874} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.729984998703003, "x": 31.974616751354084, "y": -0.11695495212789364, "z": null, "yaw": 0.04646980113969472, "pitch": null, "roll": null}, "v": 2.285804838745584, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36653927954560644, "steering_wheel_angle": 0.06767907017233882, "front_wheel_angle": 0.003110869154397358, "heading_rate": 0.002777680743873027, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141175.171874} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24102784383128933, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.829190877466107, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.27725643083613, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.026853801333475497, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141175.171874} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.729984998703003, "x": 31.974616751354084, "y": -0.11695495212789364, "z": null, "yaw": 0.04646980113969472, "pitch": null, "roll": null}, "v": 2.285804838745584, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36653927954560644, "steering_wheel_angle": 0.06767907017233882, "front_wheel_angle": 0.003110869154397358, "heading_rate": 0.002777680743873027, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141175.191874} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24102784383128933, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.829190877466107, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2750715196813003, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.026853801333475497, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141175.191874} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141175.201874, "x": 36.225202247332085, "y": 4.894705814191877, "z": null, "yaw": 0.04653014343129663, "pitch": null, "roll": null}, "v": 2.273980629118949, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36540891047202956, "steering_wheel_angle": 0.026853801333475497, "front_wheel_angle": 0.001233674120186028, "heading_rate": 0.0010958408106063735, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141175.211874} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24443732943748117, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8826015752965864, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.272890780253684, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.026853801333475497, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141175.211874} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.839984893798828, "x": 32.225202247332085, "y": -0.10529418580812333, "z": null, "yaw": 0.04653014343129663, "pitch": null, "roll": null}, "v": 2.273980629118949, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36540891047202956, "steering_wheel_angle": 0.026853801333475497, "front_wheel_angle": 0.001233674120186028, "heading_rate": 0.0010958408106063735, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141175.231874} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24272764065105307, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8826015752965864, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2711401850155704, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.05496867166123902, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141175.231874} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.839984893798828, "x": 32.225202247332085, "y": -0.10529418580812333, "z": null, "yaw": 0.04653014343129663, "pitch": null, "roll": null}, "v": 2.273980629118949, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36540891047202956, "steering_wheel_angle": 0.026853801333475497, "front_wheel_angle": 0.001233674120186028, "heading_rate": 0.0010958408106063735, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141175.251874} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24272764065105307, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8826015752965864, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2691793202703137, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.05496867166123902, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141175.251874} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.839984893798828, "x": 32.225202247332085, "y": -0.10529418580812333, "z": null, "yaw": 0.04653014343129663, "pitch": null, "roll": null}, "v": 2.273980629118949, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36540891047202956, "steering_wheel_angle": 0.026853801333475497, "front_wheel_angle": 0.001233674120186028, "heading_rate": 0.0010958408106063735, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141175.271874} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24272764065105307, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8826015752965864, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2672221948116094, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.05496867166123902, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141175.271874} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.839984893798828, "x": 32.225202247332085, "y": -0.10529418580812333, "z": null, "yaw": 0.04653014343129663, "pitch": null, "roll": null}, "v": 2.273980629118949, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36540891047202956, "steering_wheel_angle": 0.026853801333475497, "front_wheel_angle": 0.001233674120186028, "heading_rate": 0.0010958408106063735, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141175.291874} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24272764065105307, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8826015752965864, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2652687999773886, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.05496867166123902, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141175.291874} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141175.311874, "x": 36.47453825749975, "y": 4.906311186741243, "z": null, "yaw": 0.04645831267052329, "pitch": null, "roll": null}, "v": 2.2633191271308535, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3643920910689064, "steering_wheel_angle": -0.05496867166123902, "front_wheel_angle": -0.002526213909286046, "heading_rate": -0.002233453290226437, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141175.311874} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2386176883995339, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.89672118120096, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2633191271308535, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.05496867166123902, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141175.311874} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.949984788894653, "x": 32.47453825749975, "y": -0.09368881325875744, "z": null, "yaw": 0.04645831267052329, "pitch": null, "roll": null}, "v": 2.2633191271308535, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3643920910689064, "steering_wheel_angle": -0.05496867166123902, "front_wheel_angle": -0.002526213909286046, "heading_rate": -0.002233453290226437, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141175.331874} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2404973375037481, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.89672118120096, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2608596682850113, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.05496867166123902, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141175.331874} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.949984788894653, "x": 32.47453825749975, "y": -0.09368881325875744, "z": null, "yaw": 0.04645831267052329, "pitch": null, "roll": null}, "v": 2.2633191271308535, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3643920910689064, "steering_wheel_angle": -0.05496867166123902, "front_wheel_angle": -0.002526213909286046, "heading_rate": -0.002233453290226437, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141175.3518739} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2404973375037481, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.89672118120096, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2586397357755006, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.05496867166123902, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141175.3518739} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.949984788894653, "x": 32.47453825749975, "y": -0.09368881325875744, "z": null, "yaw": 0.04645831267052329, "pitch": null, "roll": null}, "v": 2.2633191271308535, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3643920910689064, "steering_wheel_angle": -0.05496867166123902, "front_wheel_angle": -0.002526213909286046, "heading_rate": -0.002233453290226437, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141175.3718739} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2404973375037481, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.89672118120096, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.256424027291401, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.05496867166123902, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141175.3718739} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.949984788894653, "x": 32.47453825749975, "y": -0.09368881325875744, "z": null, "yaw": 0.04645831267052329, "pitch": null, "roll": null}, "v": 2.2633191271308535, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3643920910689064, "steering_wheel_angle": -0.05496867166123902, "front_wheel_angle": -0.002526213909286046, "heading_rate": -0.002233453290226437, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141175.3918738} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2404973375037481, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.89672118120096, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2542125328325433, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.05496867166123902, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141175.3918738} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.949984788894653, "x": 32.47453825749975, "y": -0.09368881325875744, "z": null, "yaw": 0.04645831267052329, "pitch": null, "roll": null}, "v": 2.2633191271308535, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3643920910689064, "steering_wheel_angle": -0.05496867166123902, "front_wheel_angle": -0.002526213909286046, "heading_rate": -0.002233453290226437, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141175.4118738} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2404973375037481, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.89672118120096, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2520052424289774, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.05496867166123902, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141175.4118738} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141175.4218738, "x": 36.722603434277964, "y": 4.917831921167882, "z": null, "yaw": 0.046349764185698555, "pitch": null, "roll": null}, "v": 2.2509031706405542, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36321080936802475, "steering_wheel_angle": -0.05496867166123902, "front_wheel_angle": -0.002526213909286046, "heading_rate": -0.0022212011696385106, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141175.4318738} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.246077471873122, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9584830569587658, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2498021461408584, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.05496867166123902, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141175.4318738} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.05998468399048, "x": 32.722603434277964, "y": -0.08216807883211796, "z": null, "yaw": 0.046349764185698555, "pitch": null, "roll": null}, "v": 2.2509031706405542, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36321080936802475, "steering_wheel_angle": -0.05496867166123902, "front_wheel_angle": -0.002526213909286046, "heading_rate": -0.0022212011696385106, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141175.4518738} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24333026124290602, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9584830569587658, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2483004196123906, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.13680482697816806, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141175.4518738} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.05998468399048, "x": 32.722603434277964, "y": -0.08216807883211796, "z": null, "yaw": 0.046349764185698555, "pitch": null, "roll": null}, "v": 2.2509031706405542, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36321080936802475, "steering_wheel_angle": -0.05496867166123902, "front_wheel_angle": -0.002526213909286046, "heading_rate": -0.0022212011696385106, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141175.4718738} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24333026124290602, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9584830569587658, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2464583059142713, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.13680482697816806, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141175.4718738} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.05998468399048, "x": 32.722603434277964, "y": -0.08216807883211796, "z": null, "yaw": 0.046349764185698555, "pitch": null, "roll": null}, "v": 2.2509031706405542, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36321080936802475, "steering_wheel_angle": -0.05496867166123902, "front_wheel_angle": -0.002526213909286046, "heading_rate": -0.0022212011696385106, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141175.4918737} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24333026124290602, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9584830569587658, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.244619688301645, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.13680482697816806, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141175.4918737} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.05998468399048, "x": 32.722603434277964, "y": -0.08216807883211796, "z": null, "yaw": 0.046349764185698555, "pitch": null, "roll": null}, "v": 2.2509031706405542, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36321080936802475, "steering_wheel_angle": -0.05496867166123902, "front_wheel_angle": -0.002526213909286046, "heading_rate": -0.0022212011696385106, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141175.5118737} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24333026124290602, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9584830569587658, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.242784558787844, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.13680482697816806, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141175.5118737} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141175.5318737, "x": 36.969443174229674, "y": 4.929258309787741, "z": null, "yaw": 0.04611611241299203, "pitch": null, "roll": null}, "v": 2.2409529094090446, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3622663448923409, "steering_wheel_angle": -0.13680482697816806, "front_wheel_angle": -0.006293954684283522, "heading_rate": -0.00550962590171633, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141175.5318737} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23514093841302947, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.94741318717884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2409529094090446, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.13680482697816806, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141175.5318737} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.169984579086304, "x": 32.969443174229674, "y": -0.07074169021225885, "z": null, "yaw": 0.04611611241299203, "pitch": null, "roll": null}, "v": 2.2409529094090446, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3622663448923409, "steering_wheel_angle": -0.13680482697816806, "front_wheel_angle": -0.006293954684283522, "heading_rate": -0.00550962590171633, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141175.5518737} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23896865866503206, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.94741318717884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.238101552065564, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.13680482697816806, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141175.5518737} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.169984579086304, "x": 32.969443174229674, "y": -0.07074169021225885, "z": null, "yaw": 0.04611611241299203, "pitch": null, "roll": null}, "v": 2.2409529094090446, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3622663448923409, "steering_wheel_angle": -0.13680482697816806, "front_wheel_angle": -0.006293954684283522, "heading_rate": -0.00550962590171633, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141175.5718737} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23896865866503206, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.94741318717884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2357338353748117, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.13680482697816806, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141175.5718737} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.169984579086304, "x": 32.969443174229674, "y": -0.07074169021225885, "z": null, "yaw": 0.04611611241299203, "pitch": null, "roll": null}, "v": 2.2409529094090446, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3622663448923409, "steering_wheel_angle": -0.13680482697816806, "front_wheel_angle": -0.006293954684283522, "heading_rate": -0.00550962590171633, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141175.5918736} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23896865866503206, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.94741318717884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2333706022707727, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.13680482697816806, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141175.5918736} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.169984579086304, "x": 32.969443174229674, "y": -0.07074169021225885, "z": null, "yaw": 0.04611611241299203, "pitch": null, "roll": null}, "v": 2.2409529094090446, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3622663448923409, "steering_wheel_angle": -0.13680482697816806, "front_wheel_angle": -0.006293954684283522, "heading_rate": -0.00550962590171633, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141175.6118736} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23896865866503206, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.94741318717884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2310118420302856, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.13680482697816806, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141175.6118736} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.169984579086304, "x": 32.969443174229674, "y": -0.07074169021225885, "z": null, "yaw": 0.04611611241299203, "pitch": null, "roll": null}, "v": 2.2409529094090446, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3622663448923409, "steering_wheel_angle": -0.13680482697816806, "front_wheel_angle": -0.006293954684283522, "heading_rate": -0.00550962590171633, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141175.6318736} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23896865866503206, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.94741318717884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2286575439631666, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.13680482697816806, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141175.6318736} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141175.6418736, "x": 37.214991713828304, "y": 4.940559871378192, "z": null, "yaw": 0.0458456654764928, "pitch": null, "roll": null}, "v": 2.227482064912923, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36099086674073355, "steering_wheel_angle": -0.13680482697816806, "front_wheel_angle": -0.006293954684283522, "heading_rate": -0.005476506368752384, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141175.6518736} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24330713201390458, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9979892635534082, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2263076974120803, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.13680482697816806, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141175.6518736} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.27998447418213, "x": 33.214991713828304, "y": -0.05944012862180781, "z": null, "yaw": 0.0458456654764928, "pitch": null, "roll": null}, "v": 2.227482064912923, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36099086674073355, "steering_wheel_angle": -0.13680482697816806, "front_wheel_angle": -0.006293954684283522, "heading_rate": -0.005476506368752384, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141175.6718736} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2411440119556508, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9979892635534082, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2245043446652977, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.1777012943154595, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141175.6718736} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.27998447418213, "x": 33.214991713828304, "y": -0.05944012862180781, "z": null, "yaw": 0.0458456654764928, "pitch": null, "roll": null}, "v": 2.227482064912923, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36099086674073355, "steering_wheel_angle": -0.13680482697816806, "front_wheel_angle": -0.006293954684283522, "heading_rate": -0.005476506368752384, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141175.6918736} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2411440119556508, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9979892635534082, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.222434136325044, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.1777012943154595, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141175.6918736} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.27998447418213, "x": 33.214991713828304, "y": -0.05944012862180781, "z": null, "yaw": 0.0458456654764928, "pitch": null, "roll": null}, "v": 2.227482064912923, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36099086674073355, "steering_wheel_angle": -0.13680482697816806, "front_wheel_angle": -0.006293954684283522, "heading_rate": -0.005476506368752384, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141175.7118735} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2411440119556508, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9979892635534082, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.220367837135438, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.1777012943154595, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141175.7118735} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.27998447418213, "x": 33.214991713828304, "y": -0.05944012862180781, "z": null, "yaw": 0.0458456654764928, "pitch": null, "roll": null}, "v": 2.227482064912923, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36099086674073355, "steering_wheel_angle": -0.13680482697816806, "front_wheel_angle": -0.006293954684283522, "heading_rate": -0.005476506368752384, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141175.7318735} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2411440119556508, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9979892635534082, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2183054380078424, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.1777012943154595, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141175.7318735} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141175.7518735, "x": 37.45919937384081, "y": 4.951727635231572, "z": null, "yaw": 0.04550891302022853, "pitch": null, "roll": null}, "v": 2.2162469298804446, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35992985103606717, "steering_wheel_angle": -0.1777012943154595, "front_wheel_angle": -0.008179879023608193, "heading_rate": -0.00708165473247945, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141175.7518735} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2448491461234288, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0507532278461884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2162469298804446, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.1777012943154595, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141175.7518735} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.389984369277954, "x": 33.45919937384081, "y": -0.04827236476842778, "z": null, "yaw": 0.04550891302022853, "pitch": null, "roll": null}, "v": 2.2162469298804446, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35992985103606717, "steering_wheel_angle": -0.1777012943154595, "front_wheel_angle": -0.008179879023608193, "heading_rate": -0.00708165473247945, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141175.7718735} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24300395630618796, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0507532278461884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2146552271022677, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.21861319946399407, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141175.7718735} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.389984369277954, "x": 33.45919937384081, "y": -0.04827236476842778, "z": null, "yaw": 0.04550891302022853, "pitch": null, "roll": null}, "v": 2.2162469298804446, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35992985103606717, "steering_wheel_angle": -0.1777012943154595, "front_wheel_angle": -0.008179879023608193, "heading_rate": -0.00708165473247945, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141175.7918735} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24300395630618796, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0507532278461884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.212835984890146, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.21861319946399407, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141175.7918735} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.389984369277954, "x": 33.45919937384081, "y": -0.04827236476842778, "z": null, "yaw": 0.04550891302022853, "pitch": null, "roll": null}, "v": 2.2162469298804446, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35992985103606717, "steering_wheel_angle": -0.1777012943154595, "front_wheel_angle": -0.008179879023608193, "heading_rate": -0.00708165473247945, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141175.8118734} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24300395630618796, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0507532278461884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2110201709086232, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.21861319946399407, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141175.8118734} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.389984369277954, "x": 33.45919937384081, "y": -0.04827236476842778, "z": null, "yaw": 0.04550891302022853, "pitch": null, "roll": null}, "v": 2.2162469298804446, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35992985103606717, "steering_wheel_angle": -0.1777012943154595, "front_wheel_angle": -0.008179879023608193, "heading_rate": -0.00708165473247945, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141175.8318734} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24300395630618796, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0507532278461884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.209207777379194, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.21861319946399407, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141175.8318734} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.389984369277954, "x": 33.45919937384081, "y": -0.04827236476842778, "z": null, "yaw": 0.04550891302022853, "pitch": null, "roll": null}, "v": 2.2162469298804446, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35992985103606717, "steering_wheel_angle": -0.1777012943154595, "front_wheel_angle": -0.008179879023608193, "heading_rate": -0.00708165473247945, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141175.8518734} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24300395630618796, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0507532278461884, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.207398796545457, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.21861319946399407, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141175.8518734} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141175.8618734, "x": 37.702258606183236, "y": 4.962750413033767, "z": null, "yaw": 0.04508364335233661, "pitch": null, "roll": null}, "v": 2.206495583471622, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35901100677237885, "steering_wheel_angle": -0.21861319946399407, "front_wheel_angle": -0.01006855710126428, "heading_rate": -0.0086785068499535, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141175.8718734} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23734389485200724, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.044532540680259, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.205593220673035, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.21861319946399407, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141175.8718734} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.49998426437378, "x": 33.702258606183236, "y": -0.03724958696623304, "z": null, "yaw": 0.04508364335233661, "pitch": null, "roll": null}, "v": 2.206495583471622, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35901100677237885, "steering_wheel_angle": -0.21861319946399407, "front_wheel_angle": -0.01006855710126428, "heading_rate": -0.0086785068499535, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141175.8918734} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23996915634057844, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.044532540680259, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2030838672157627, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.21861319946399407, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141175.8918734} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.49998426437378, "x": 33.702258606183236, "y": -0.03724958696623304, "z": null, "yaw": 0.04508364335233661, "pitch": null, "roll": null}, "v": 2.206495583471622, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35901100677237885, "steering_wheel_angle": -0.21861319946399407, "front_wheel_angle": -0.01006855710126428, "heading_rate": -0.0086785068499535, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141175.9118733} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23996915634057844, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.044532540680259, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2009072362367914, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.21861319946399407, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141175.9118733} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.49998426437378, "x": 33.702258606183236, "y": -0.03724958696623304, "z": null, "yaw": 0.04508364335233661, "pitch": null, "roll": null}, "v": 2.206495583471622, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35901100677237885, "steering_wheel_angle": -0.21861319946399407, "front_wheel_angle": -0.01006855710126428, "heading_rate": -0.0086785068499535, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141175.9318733} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23996915634057844, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.044532540680259, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1987346966634833, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.21861319946399407, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141175.9318733} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.49998426437378, "x": 33.702258606183236, "y": -0.03724958696623304, "z": null, "yaw": 0.04508364335233661, "pitch": null, "roll": null}, "v": 2.206495583471622, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35901100677237885, "steering_wheel_angle": -0.21861319946399407, "front_wheel_angle": -0.01006855710126428, "heading_rate": -0.0086785068499535, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141175.9518733} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23996915634057844, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.044532540680259, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1965662389181526, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.21861319946399407, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141175.9518733} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141175.9718733, "x": 37.9441214177006, "y": 4.973614250800811, "z": null, "yaw": 0.0446509954192767, "pitch": null, "roll": null}, "v": 2.194401853451746, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3578740876169119, "steering_wheel_angle": -0.21861319946399407, "front_wheel_angle": -0.01006855710126428, "heading_rate": -0.008630940238170919, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141175.9718733} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24481768370440524, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1008459305743383, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.194401853451746, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.21861319946399407, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141175.9718733} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.609984159469604, "x": 33.9441214177006, "y": -0.026385749199189235, "z": null, "yaw": 0.0446509954192767, "pitch": null, "roll": null}, "v": 2.194401853451746, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3578740876169119, "steering_wheel_angle": -0.21861319946399407, "front_wheel_angle": -0.01006855710126428, "heading_rate": -0.008630940238170919, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141175.9918733} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24242223754172687, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1008459305743383, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.192847312208829, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2595375756879506, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141175.9918733} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.609984159469604, "x": 33.9441214177006, "y": -0.026385749199189235, "z": null, "yaw": 0.0446509954192767, "pitch": null, "roll": null}, "v": 2.194401853451746, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3578740876169119, "steering_wheel_angle": -0.21861319946399407, "front_wheel_angle": -0.01006855710126428, "heading_rate": -0.008630940238170919, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141176.0118732} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24242223754172687, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1008459305743383, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.190996397650392, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2595375756879506, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141176.0118732} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.609984159469604, "x": 33.9441214177006, "y": -0.026385749199189235, "z": null, "yaw": 0.0446509954192767, "pitch": null, "roll": null}, "v": 2.194401853451746, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3578740876169119, "steering_wheel_angle": -0.21861319946399407, "front_wheel_angle": -0.01006855710126428, "heading_rate": -0.008630940238170919, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141176.0318732} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24242223754172687, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1008459305743383, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1891489548585845, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2595375756879506, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141176.0318732} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.609984159469604, "x": 33.9441214177006, "y": -0.026385749199189235, "z": null, "yaw": 0.0446509954192767, "pitch": null, "roll": null}, "v": 2.194401853451746, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3578740876169119, "steering_wheel_angle": -0.21861319946399407, "front_wheel_angle": -0.01006855710126428, "heading_rate": -0.008630940238170919, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141176.0518732} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24242223754172687, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1008459305743383, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1873049759568244, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2595375756879506, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141176.0518732} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.609984159469604, "x": 33.9441214177006, "y": -0.026385749199189235, "z": null, "yaw": 0.0446509954192767, "pitch": null, "roll": null}, "v": 2.194401853451746, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3578740876169119, "steering_wheel_angle": -0.21861319946399407, "front_wheel_angle": -0.01006855710126428, "heading_rate": -0.008630940238170919, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141176.0718732} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24242223754172687, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1008459305743383, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1854644530909737, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2595375756879506, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141176.0718732} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141176.0818732, "x": 38.184787666454284, "y": 4.984312719717692, "z": null, "yaw": 0.044144459454231885, "pitch": null, "roll": null}, "v": 2.1845454852232136, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35694966403125195, "steering_wheel_angle": -0.2595375756879506, "front_wheel_angle": -0.011959860698145744, "heading_rate": -0.010206291201912637, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141176.0918732} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24662964848717883, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1601274161858532, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.183627378429259, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2595375756879506, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141176.0918732} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.71998405456543, "x": 34.184787666454284, "y": -0.015687280282308258, "z": null, "yaw": 0.044144459454231885, "pitch": null, "roll": null}, "v": 2.1845454852232136, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35694966403125195, "steering_wheel_angle": -0.2595375756879506, "front_wheel_angle": -0.011959860698145744, "heading_rate": -0.010206291201912637, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141176.1118731} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24455568615630713, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1601274161858532, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.182319424247387, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.34138774222487145, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141176.1118731} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.71998405456543, "x": 34.184787666454284, "y": -0.015687280282308258, "z": null, "yaw": 0.044144459454231885, "pitch": null, "roll": null}, "v": 2.1845454852232136, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35694966403125195, "steering_wheel_angle": -0.2595375756879506, "front_wheel_angle": -0.011959860698145744, "heading_rate": -0.010206291201912637, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141176.1318731} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24455568615630713, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1601274161858532, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.180754794870145, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.34138774222487145, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141176.1318731} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.71998405456543, "x": 34.184787666454284, "y": -0.015687280282308258, "z": null, "yaw": 0.044144459454231885, "pitch": null, "roll": null}, "v": 2.1845454852232136, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35694966403125195, "steering_wheel_angle": -0.2595375756879506, "front_wheel_angle": -0.011959860698145744, "heading_rate": -0.010206291201912637, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141176.151873} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24455568615630713, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1601274161858532, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.179193093824971, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.34138774222487145, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141176.151873} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.71998405456543, "x": 34.184787666454284, "y": -0.015687280282308258, "z": null, "yaw": 0.044144459454231885, "pitch": null, "roll": null}, "v": 2.1845454852232136, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35694966403125195, "steering_wheel_angle": -0.2595375756879506, "front_wheel_angle": -0.011959860698145744, "heading_rate": -0.010206291201912637, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141176.171873} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24455568615630713, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1601274161858532, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1776343146561437, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.34138774222487145, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141176.171873} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141176.191873, "x": 38.42443516092936, "y": 4.994832324830776, "z": null, "yaw": 0.04350470892508082, "pitch": null, "roll": null}, "v": 2.176078450925494, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35615709679209767, "steering_wheel_angle": -0.34138774222487145, "front_wheel_angle": -0.01574871054151353, "heading_rate": -0.013387993434584399, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141176.191873} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24454756289097906, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1848083330455268, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.176078450925494, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.34138774222487145, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141176.191873} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.829983949661255, "x": 34.42443516092936, "y": -0.005167675169223784, "z": null, "yaw": 0.04350470892508082, "pitch": null, "roll": null}, "v": 2.176078450925494, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35615709679209767, "steering_wheel_angle": -0.34138774222487145, "front_wheel_angle": -0.01574871054151353, "heading_rate": -0.013387993434584399, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141176.211873} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24449104500896657, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1848083330455268, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.174524481278912, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.34138774222487145, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141176.211873} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.829983949661255, "x": 34.42443516092936, "y": -0.005167675169223784, "z": null, "yaw": 0.04350470892508082, "pitch": null, "roll": null}, "v": 2.176078450925494, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35615709679209767, "steering_wheel_angle": -0.34138774222487145, "front_wheel_angle": -0.01574871054151353, "heading_rate": -0.013387993434584399, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141176.231873} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24449104500896657, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1848083330455268, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.172966354709746, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.34138774222487145, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141176.231873} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.829983949661255, "x": 34.42443516092936, "y": -0.005167675169223784, "z": null, "yaw": 0.04350470892508082, "pitch": null, "roll": null}, "v": 2.176078450925494, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35615709679209767, "steering_wheel_angle": -0.34138774222487145, "front_wheel_angle": -0.01574871054151353, "heading_rate": -0.013387993434584399, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141176.251873} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24449104500896657, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1848083330455268, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1714111394514877, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.34138774222487145, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141176.251873} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.829983949661255, "x": 34.42443516092936, "y": -0.005167675169223784, "z": null, "yaw": 0.04350470892508082, "pitch": null, "roll": null}, "v": 2.176078450925494, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35615709679209767, "steering_wheel_angle": -0.34138774222487145, "front_wheel_angle": -0.01574871054151353, "heading_rate": -0.013387993434584399, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141176.271873} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24449104500896657, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1848083330455268, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1698588290974166, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.34138774222487145, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141176.271873} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.829983949661255, "x": 34.42443516092936, "y": -0.005167675169223784, "z": null, "yaw": 0.04350470892508082, "pitch": null, "roll": null}, "v": 2.176078450925494, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35615709679209767, "steering_wheel_angle": -0.34138774222487145, "front_wheel_angle": -0.01574871054151353, "heading_rate": -0.013387993434584399, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141176.291873} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24449104500896657, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1848083330455268, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1683094172581994, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.34138774222487145, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141176.291873} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141176.301873, "x": 38.66315327413841, "y": 5.005150724422931, "z": null, "yaw": 0.04282795056778081, "pitch": null, "roll": null}, "v": 2.1675357962897337, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35535890409646037, "steering_wheel_angle": -0.34138774222487145, "front_wheel_angle": -0.01574871054151353, "heading_rate": -0.01333543604441823, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141176.311873} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2449422620466238, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.209341018345029, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1667628975618296, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.34138774222487145, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141176.311873} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.93998384475708, "x": 34.66315327413841, "y": 0.0051507244229309634, "z": null, "yaw": 0.04282795056778081, "pitch": null, "roll": null}, "v": 2.1675357962897337, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35535890409646037, "steering_wheel_angle": -0.34138774222487145, "front_wheel_angle": -0.01574871054151353, "heading_rate": -0.01333543604441823, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141176.331873} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24466658197130994, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.209341018345029, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.165275639466016, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3823020657763717, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141176.331873} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.93998384475708, "x": 34.66315327413841, "y": 0.0051507244229309634, "z": null, "yaw": 0.04282795056778081, "pitch": null, "roll": null}, "v": 2.1675357962897337, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35535890409646037, "steering_wheel_angle": -0.34138774222487145, "front_wheel_angle": -0.01574871054151353, "heading_rate": -0.01333543604441823, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141176.351873} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24466658197130994, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.209341018345029, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.163756711748625, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3823020657763717, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141176.351873} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.93998384475708, "x": 34.66315327413841, "y": 0.0051507244229309634, "z": null, "yaw": 0.04282795056778081, "pitch": null, "roll": null}, "v": 2.1675357962897337, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35535890409646037, "steering_wheel_angle": -0.34138774222487145, "front_wheel_angle": -0.01574871054151353, "heading_rate": -0.01333543604441823, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141176.371873} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24466658197130994, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.209341018345029, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.16224061650407, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3823020657763717, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141176.371873} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.93998384475708, "x": 34.66315327413841, "y": 0.0051507244229309634, "z": null, "yaw": 0.04282795056778081, "pitch": null, "roll": null}, "v": 2.1675357962897337, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35535890409646037, "steering_wheel_angle": -0.34138774222487145, "front_wheel_angle": -0.01574871054151353, "heading_rate": -0.01333543604441823, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141176.391873} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24466658197130994, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.209341018345029, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.16072734753141, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3823020657763717, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141176.391873} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141176.4118729, "x": 38.90095125752977, "y": 5.015262349468032, "z": null, "yaw": 0.04208448120555008, "pitch": null, "roll": null}, "v": 2.1592168986464033, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3545830210863221, "steering_wheel_angle": -0.3823020657763717, "front_wheel_angle": -0.017645738460967897, "heading_rate": -0.014884738942761799, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141176.4118729} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2451783233764544, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.236944425906122, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1592168986464033, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3823020657763717, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141176.4118729} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.049983739852905, "x": 34.90095125752977, "y": 0.015262349468032177, "z": null, "yaw": 0.04208448120555008, "pitch": null, "roll": null}, "v": 2.1592168986464033, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3545830210863221, "steering_wheel_angle": -0.3823020657763717, "front_wheel_angle": -0.017645738460967897, "heading_rate": -0.014884738942761799, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141176.4318728} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24487552194577922, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.236944425906122, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1577732015578897, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.42320322534688376, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141176.4318728} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.049983739852905, "x": 34.90095125752977, "y": 0.015262349468032177, "z": null, "yaw": 0.04208448120555008, "pitch": null, "roll": null}, "v": 2.1592168986464033, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3545830210863221, "steering_wheel_angle": -0.3823020657763717, "front_wheel_angle": -0.017645738460967897, "heading_rate": -0.014884738942761799, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141176.4518728} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24487552194577922, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.236944425906122, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1562943606384737, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.42320322534688376, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141176.4518728} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.049983739852905, "x": 34.90095125752977, "y": 0.015262349468032177, "z": null, "yaw": 0.04208448120555008, "pitch": null, "roll": null}, "v": 2.1592168986464033, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3545830210863221, "steering_wheel_angle": -0.3823020657763717, "front_wheel_angle": -0.017645738460967897, "heading_rate": -0.014884738942761799, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141176.4718728} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24487552194577922, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.236944425906122, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1548182730225913, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.42320322534688376, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141176.4718728} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.049983739852905, "x": 34.90095125752977, "y": 0.015262349468032177, "z": null, "yaw": 0.04208448120555008, "pitch": null, "roll": null}, "v": 2.1592168986464033, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3545830210863221, "steering_wheel_angle": -0.3823020657763717, "front_wheel_angle": -0.017645738460967897, "heading_rate": -0.014884738942761799, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141176.4918728} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24487552194577922, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.236944425906122, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1533449327130185, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.42320322534688376, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141176.4918728} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.049983739852905, "x": 34.90095125752977, "y": 0.015262349468032177, "z": null, "yaw": 0.04208448120555008, "pitch": null, "roll": null}, "v": 2.1592168986464033, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3545830210863221, "steering_wheel_angle": -0.3823020657763717, "front_wheel_angle": -0.017645738460967897, "heading_rate": -0.014884738942761799, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141176.5118728} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24487552194577922, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.236944425906122, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.151874333728557, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.42320322534688376, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141176.5118728} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141176.5218728, "x": 39.137855996334935, "y": 5.025149312224259, "z": null, "yaw": 0.04125200163687805, "pitch": null, "roll": null}, "v": 2.151140060368488, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35383103861164583, "steering_wheel_angle": -0.42320322534688376, "front_wheel_angle": -0.019544231080425377, "heading_rate": -0.01642489543658163, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141176.5318727} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24724740396139838, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2770948457674425, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1504064701039827, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.42320322534688376, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141176.5318727} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.15998363494873, "x": 35.137855996334935, "y": 0.025149312224258757, "z": null, "yaw": 0.04125200163687805, "pitch": null, "roll": null}, "v": 2.151140060368488, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35383103861164583, "steering_wheel_angle": -0.42320322534688376, "front_wheel_angle": -0.019544231080425377, "heading_rate": -0.01642489543658163, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141176.5518727} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24606064183924103, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2770948457674425, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.149237683283783, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4641055677189161, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141176.5518727} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.15998363494873, "x": 35.137855996334935, "y": 0.025149312224258757, "z": null, "yaw": 0.04125200163687805, "pitch": null, "roll": null}, "v": 2.151140060368488, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35383103861164583, "steering_wheel_angle": -0.42320322534688376, "front_wheel_angle": -0.019544231080425377, "heading_rate": -0.01642489543658163, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141176.5718727} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24606064183924103, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2770948457674425, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.147922792871428, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4641055677189161, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141176.5718727} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.15998363494873, "x": 35.137855996334935, "y": 0.025149312224258757, "z": null, "yaw": 0.04125200163687805, "pitch": null, "roll": null}, "v": 2.151140060368488, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35383103861164583, "steering_wheel_angle": -0.42320322534688376, "front_wheel_angle": -0.019544231080425377, "heading_rate": -0.01642489543658163, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141176.5918727} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24606064183924103, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2770948457674425, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1466103460993002, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4641055677189161, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141176.5918727} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.15998363494873, "x": 35.137855996334935, "y": 0.025149312224258757, "z": null, "yaw": 0.04125200163687805, "pitch": null, "roll": null}, "v": 2.151140060368488, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35383103861164583, "steering_wheel_angle": -0.42320322534688376, "front_wheel_angle": -0.019544231080425377, "heading_rate": -0.01642489543658163, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141176.6118727} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24606064183924103, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2770948457674425, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.145300337737363, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4641055677189161, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141176.6118727} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141176.6318727, "x": 39.37392778875864, "y": 5.034797307200563, "z": null, "yaw": 0.04034525642661168, "pitch": null, "roll": null}, "v": 2.1439927625691357, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35316668778794513, "steering_wheel_angle": -0.4641055677189161, "front_wheel_angle": -0.02144486024239615, "heading_rate": -0.01796276349425968, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141176.6318727} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24650374293865068, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2998870669216533, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1439927625691357, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4641055677189161, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141176.6318727} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.269983530044556, "x": 35.37392778875864, "y": 0.034797307200562955, "z": null, "yaw": 0.04034525642661168, "pitch": null, "roll": null}, "v": 2.1439927625691357, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35316668778794513, "steering_wheel_angle": -0.4641055677189161, "front_wheel_angle": -0.02144486024239615, "heading_rate": -0.01796276349425968, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141176.6518726} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24624212507881746, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2998870669216533, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1427429773106366, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4641055677189161, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141176.6518726} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.269983530044556, "x": 35.37392778875864, "y": 0.034797307200562955, "z": null, "yaw": 0.04034525642661168, "pitch": null, "roll": null}, "v": 2.1439927625691357, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35316668778794513, "steering_wheel_angle": -0.4641055677189161, "front_wheel_angle": -0.02144486024239615, "heading_rate": -0.01796276349425968, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141176.6718726} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24624212507881746, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2998870669216533, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1414628250516454, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4641055677189161, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141176.6718726} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.269983530044556, "x": 35.37392778875864, "y": 0.034797307200562955, "z": null, "yaw": 0.04034525642661168, "pitch": null, "roll": null}, "v": 2.1439927625691357, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35316668778794513, "steering_wheel_angle": -0.4641055677189161, "front_wheel_angle": -0.02144486024239615, "heading_rate": -0.01796276349425968, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141176.6918726} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24624212507881746, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2998870669216533, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1401850485649634, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4641055677189161, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141176.6918726} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.269983530044556, "x": 35.37392778875864, "y": 0.034797307200562955, "z": null, "yaw": 0.04034525642661168, "pitch": null, "roll": null}, "v": 2.1439927625691357, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35316668778794513, "steering_wheel_angle": -0.4641055677189161, "front_wheel_angle": -0.02144486024239615, "heading_rate": -0.01796276349425968, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141176.7118726} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24624212507881746, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2998870669216533, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1389096427887275, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4641055677189161, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141176.7118726} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.269983530044556, "x": 35.37392778875864, "y": 0.034797307200562955, "z": null, "yaw": 0.04034525642661168, "pitch": null, "roll": null}, "v": 2.1439927625691357, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35316668778794513, "steering_wheel_angle": -0.4641055677189161, "front_wheel_angle": -0.02144486024239615, "heading_rate": -0.01796276349425968, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141176.7318726} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24624212507881746, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2998870669216533, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.137636602674101, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4641055677189161, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141176.7318726} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141176.7418725, "x": 39.60923053948027, "y": 5.044197140576314, "z": null, "yaw": 0.03942365630796166, "pitch": null, "roll": null}, "v": 2.137000968165681, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3525177797876946, "steering_wheel_angle": -0.4641055677189161, "front_wheel_angle": -0.02144486024239615, "heading_rate": -0.017904184961970583, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141176.7518725} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24113663177692696, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2418576977718943, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.13636592318523, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4641055677189161, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141176.7518725} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.37998342514038, "x": 35.60923053948027, "y": 0.04419714057631374, "z": null, "yaw": 0.03942365630796166, "pitch": null, "roll": null}, "v": 2.137000968165681, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3525177797876946, "steering_wheel_angle": -0.4641055677189161, "front_wheel_angle": -0.02144486024239615, "heading_rate": -0.017904184961970583, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141176.7718725} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2435183796437857, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2418576977718943, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1344597084724852, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4641055677189161, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141176.7718725} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.37998342514038, "x": 35.60923053948027, "y": 0.04419714057631374, "z": null, "yaw": 0.03942365630796166, "pitch": null, "roll": null}, "v": 2.137000968165681, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3525177797876946, "steering_wheel_angle": -0.4641055677189161, "front_wheel_angle": -0.02144486024239615, "heading_rate": -0.017904184961970583, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141176.7918725} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2435183796437857, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2418576977718943, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.132854606728412, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4641055677189161, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141176.7918725} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.37998342514038, "x": 35.60923053948027, "y": 0.04419714057631374, "z": null, "yaw": 0.03942365630796166, "pitch": null, "roll": null}, "v": 2.137000968165681, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3525177797876946, "steering_wheel_angle": -0.4641055677189161, "front_wheel_angle": -0.02144486024239615, "heading_rate": -0.017904184961970583, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141176.8118725} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2435183796437857, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2418576977718943, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1312524783450244, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4641055677189161, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141176.8118725} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.37998342514038, "x": 35.60923053948027, "y": 0.04419714057631374, "z": null, "yaw": 0.03942365630796166, "pitch": null, "roll": null}, "v": 2.137000968165681, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3525177797876946, "steering_wheel_angle": -0.4641055677189161, "front_wheel_angle": -0.02144486024239615, "heading_rate": -0.017904184961970583, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141176.8318725} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2435183796437857, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2418576977718943, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.129653316788088, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4641055677189161, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141176.8318725} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141176.8518724, "x": 39.84367224590362, "y": 5.0533461960548145, "z": null, "yaw": 0.038502056189311636, "pitch": null, "roll": null}, "v": 2.1280571155411696, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35168912664711255, "steering_wheel_angle": -0.4641055677189161, "front_wheel_angle": -0.02144486024239615, "heading_rate": -0.017829251728880235, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141176.8518724} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2478194815441806, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2953324693277586, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1280571155411696, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4641055677189161, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141176.8518724} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.489983320236206, "x": 35.84367224590362, "y": 0.0533461960548145, "z": null, "yaw": 0.038502056189311636, "pitch": null, "roll": null}, "v": 2.1280571155411696, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35168912664711255, "steering_wheel_angle": -0.4641055677189161, "front_wheel_angle": -0.02144486024239615, "heading_rate": -0.017829251728880235, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141176.8718724} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24570820125003334, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2953324693277586, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1270012570569357, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4641055677189161, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141176.8718724} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.489983320236206, "x": 35.84367224590362, "y": 0.0533461960548145, "z": null, "yaw": 0.038502056189311636, "pitch": null, "roll": null}, "v": 2.1280571155411696, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35168912664711255, "steering_wheel_angle": -0.4641055677189161, "front_wheel_angle": -0.02144486024239615, "heading_rate": -0.017829251728880235, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141176.8918724} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24570820125003334, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2953324693277586, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1256835640221308, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4641055677189161, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141176.8918724} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.489983320236206, "x": 35.84367224590362, "y": 0.0533461960548145, "z": null, "yaw": 0.038502056189311636, "pitch": null, "roll": null}, "v": 2.1280571155411696, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35168912664711255, "steering_wheel_angle": -0.4641055677189161, "front_wheel_angle": -0.02144486024239615, "heading_rate": -0.017829251728880235, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141176.9118724} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24570820125003334, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2953324693277586, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1243683081254976, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4641055677189161, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141176.9118724} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.489983320236206, "x": 35.84367224590362, "y": 0.0533461960548145, "z": null, "yaw": 0.038502056189311636, "pitch": null, "roll": null}, "v": 2.1280571155411696, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35168912664711255, "steering_wheel_angle": -0.4641055677189161, "front_wheel_angle": -0.02144486024239615, "heading_rate": -0.017829251728880235, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141176.9318724} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24570820125003334, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2953324693277586, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.12305548416779, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4641055677189161, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141176.9318724} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.489983320236206, "x": 35.84367224590362, "y": 0.0533461960548145, "z": null, "yaw": 0.038502056189311636, "pitch": null, "roll": null}, "v": 2.1280571155411696, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35168912664711255, "steering_wheel_angle": -0.4641055677189161, "front_wheel_angle": -0.02144486024239615, "heading_rate": -0.017829251728880235, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141176.9518723} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24570820125003334, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2953324693277586, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1217450869632115, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4641055677189161, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141176.9518723} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141176.9618723, "x": 40.07725194036916, "y": 5.0622460079366665, "z": null, "yaw": 0.037580456070661614, "pitch": null, "roll": null}, "v": 2.1210907967764516, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3510448015205202, "steering_wheel_angle": -0.4641055677189161, "front_wheel_angle": -0.02144486024239615, "heading_rate": -0.01777088663615189, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141176.9718723} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24930472564136885, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3521624998725907, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1204371113393736, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4641055677189161, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141176.9718723} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.59998321533203, "x": 36.07725194036916, "y": 0.06224600793666646, "z": null, "yaw": 0.037580456070661614, "pitch": null, "roll": null}, "v": 2.1210907967764516, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3510448015205202, "steering_wheel_angle": -0.4641055677189161, "front_wheel_angle": -0.02144486024239615, "heading_rate": -0.01777088663615189, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141176.9918723} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24754300266055398, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3521624998725907, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.119580909991542, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.505049279445718, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141176.9918723} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.59998321533203, "x": 36.07725194036916, "y": 0.06224600793666646, "z": null, "yaw": 0.037580456070661614, "pitch": null, "roll": null}, "v": 2.1210907967764516, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3510448015205202, "steering_wheel_angle": -0.4641055677189161, "front_wheel_angle": -0.02144486024239615, "heading_rate": -0.01777088663615189, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141177.0118723} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24754300266055398, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3521624998725907, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.118506176449719, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.505049279445718, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141177.0118723} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.59998321533203, "x": 36.07725194036916, "y": 0.06224600793666646, "z": null, "yaw": 0.037580456070661614, "pitch": null, "roll": null}, "v": 2.1210907967764516, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3510448015205202, "steering_wheel_angle": -0.4641055677189161, "front_wheel_angle": -0.02144486024239615, "heading_rate": -0.01777088663615189, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141177.0318723} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24754300266055398, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3521624998725907, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.117433427571759, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.505049279445718, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141177.0318723} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.59998321533203, "x": 36.07725194036916, "y": 0.06224600793666646, "z": null, "yaw": 0.037580456070661614, "pitch": null, "roll": null}, "v": 2.1210907967764516, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3510448015205202, "steering_wheel_angle": -0.4641055677189161, "front_wheel_angle": -0.02144486024239615, "heading_rate": -0.01777088663615189, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141177.0518723} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24754300266055398, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3521624998725907, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1163626592325664, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.505049279445718, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141177.0518723} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141177.0718722, "x": 40.31012283783255, "y": 5.070898207414177, "z": null, "yaw": 0.03659186221863315, "pitch": null, "roll": null}, "v": 2.115293867317209, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35050937481695843, "steering_wheel_angle": -0.505049279445718, "front_wheel_angle": -0.023349503439737226, "heading_rate": -0.019296890382725477, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141177.0718722} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24799668824800905, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3649947994014948, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.115293867317209, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.505049279445718, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141177.0718722} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.709983110427856, "x": 36.31012283783255, "y": 0.07089820741417707, "z": null, "yaw": 0.03659186221863315, "pitch": null, "roll": null}, "v": 2.115293867317209, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35050937481695843, "steering_wheel_angle": -0.505049279445718, "front_wheel_angle": -0.023349503439737226, "heading_rate": -0.019296890382725477, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141177.0918722} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24773985294826814, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3649947994014948, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1142837322486128, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5459627101391185, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141177.0918722} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.709983110427856, "x": 36.31012283783255, "y": 0.07089820741417707, "z": null, "yaw": 0.03659186221863315, "pitch": null, "roll": null}, "v": 2.115293867317209, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35050937481695843, "steering_wheel_angle": -0.505049279445718, "front_wheel_angle": -0.023349503439737226, "heading_rate": -0.019296890382725477, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141177.1118722} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24773985294826814, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3649947994014948, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1132433712414103, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5459627101391185, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141177.1118722} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.709983110427856, "x": 36.31012283783255, "y": 0.07089820741417707, "z": null, "yaw": 0.03659186221863315, "pitch": null, "roll": null}, "v": 2.115293867317209, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35050937481695843, "steering_wheel_angle": -0.505049279445718, "front_wheel_angle": -0.023349503439737226, "heading_rate": -0.019296890382725477, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141177.1318722} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24773985294826814, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3649947994014948, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.112204929232162, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5459627101391185, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141177.1318722} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.709983110427856, "x": 36.31012283783255, "y": 0.07089820741417707, "z": null, "yaw": 0.03659186221863315, "pitch": null, "roll": null}, "v": 2.115293867317209, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35050937481695843, "steering_wheel_angle": -0.505049279445718, "front_wheel_angle": -0.023349503439737226, "heading_rate": -0.019296890382725477, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141177.1518722} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24773985294826814, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3649947994014948, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.111168402250034, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5459627101391185, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141177.1518722} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.709983110427856, "x": 36.31012283783255, "y": 0.07089820741417707, "z": null, "yaw": 0.03659186221863315, "pitch": null, "roll": null}, "v": 2.115293867317209, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35050937481695843, "steering_wheel_angle": -0.505049279445718, "front_wheel_angle": -0.023349503439737226, "heading_rate": -0.019296890382725477, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141177.1718721} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24773985294826814, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3649947994014948, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1101337863339005, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5459627101391185, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141177.1718721} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141177.1818721, "x": 40.542370775809765, "y": 5.079287283247752, "z": null, "yaw": 0.03551390984611595, "pitch": null, "roll": null}, "v": 2.1096171937903776, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34998570673287877, "steering_wheel_angle": -0.5459627101391185, "front_wheel_angle": -0.02525483535749198, "heading_rate": -0.020816158131407757, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141177.1918721} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24994429910024532, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.397072776891601, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1091010775323156, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5459627101391185, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141177.1918721} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.81998300552368, "x": 36.542370775809765, "y": 0.07928728324775225, "z": null, "yaw": 0.03551390984611595, "pitch": null, "roll": null}, "v": 2.1096171937903776, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34998570673287877, "steering_wheel_angle": -0.5459627101391185, "front_wheel_angle": -0.02525483535749198, "heading_rate": -0.020816158131407757, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141177.211872} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24885466377238682, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.397072776891601, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1083457006783517, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141177.211872} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.81998300552368, "x": 36.542370775809765, "y": 0.07928728324775225, "z": null, "yaw": 0.03551390984611595, "pitch": null, "roll": null}, "v": 2.1096171937903776, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34998570673287877, "steering_wheel_angle": -0.5459627101391185, "front_wheel_angle": -0.02525483535749198, "heading_rate": -0.020816158131407757, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141177.231872} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24885466377238682, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.397072776891601, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.107455574000939, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141177.231872} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.81998300552368, "x": 36.542370775809765, "y": 0.07928728324775225, "z": null, "yaw": 0.03551390984611595, "pitch": null, "roll": null}, "v": 2.1096171937903776, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34998570673287877, "steering_wheel_angle": -0.5459627101391185, "front_wheel_angle": -0.02525483535749198, "heading_rate": -0.020816158131407757, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141177.251872} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24885466377238682, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.397072776891601, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1065670871345237, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141177.251872} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.81998300552368, "x": 36.542370775809765, "y": 0.07928728324775225, "z": null, "yaw": 0.03551390984611595, "pitch": null, "roll": null}, "v": 2.1096171937903776, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34998570673287877, "steering_wheel_angle": -0.5459627101391185, "front_wheel_angle": -0.02525483535749198, "heading_rate": -0.020816158131407757, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141177.271872} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24885466377238682, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.397072776891601, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1056802367425913, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141177.271872} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141177.291872, "x": 40.77404644390967, "y": 5.087398401510779, "z": null, "yaw": 0.03436141931081716, "pitch": null, "roll": null}, "v": 2.104795019496517, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3495413717157993, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022337608997813795, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141177.291872} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24556083875668092, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3241049225683688, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.104795019496517, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141177.291872} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.929982900619507, "x": 36.77404644390967, "y": 0.08739840151077871, "z": null, "yaw": 0.03436141931081716, "pitch": null, "roll": null}, "v": 2.104795019496517, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3495413717157993, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022337608997813795, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141177.311872} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24709547352947575, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3241049225683688, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1034998935185065, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141177.311872} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.929982900619507, "x": 36.77404644390967, "y": 0.08739840151077871, "z": null, "yaw": 0.03436141931081716, "pitch": null, "roll": null}, "v": 2.104795019496517, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3495413717157993, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022337608997813795, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141177.331872} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24709547352947575, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3241049225683688, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1023988925046577, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141177.331872} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.929982900619507, "x": 36.77404644390967, "y": 0.08739840151077871, "z": null, "yaw": 0.03436141931081716, "pitch": null, "roll": null}, "v": 2.104795019496517, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3495413717157993, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022337608997813795, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141177.351872} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24709547352947575, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3241049225683688, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.101299917577453, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141177.351872} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.929982900619507, "x": 36.77404644390967, "y": 0.08739840151077871, "z": null, "yaw": 0.03436141931081716, "pitch": null, "roll": null}, "v": 2.104795019496517, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3495413717157993, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022337608997813795, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141177.371872} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24709547352947575, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3241049225683688, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.100202964525566, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141177.371872} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.929982900619507, "x": 36.77404644390967, "y": 0.08739840151077871, "z": null, "yaw": 0.03436141931081716, "pitch": null, "roll": null}, "v": 2.104795019496517, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3495413717157993, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022337608997813795, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141177.391872} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24709547352947575, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3241049225683688, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0991080291480833, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141177.391872} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141177.401872, "x": 41.00512069680972, "y": 5.095218873822659, "z": null, "yaw": 0.03319401965099318, "pitch": null, "roll": null}, "v": 2.098561316777298, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34896766184160555, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022271452430233245, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141177.411872} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2510398490357205, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3761112849607926, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0977159235265526, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141177.411872} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.039982795715332, "x": 37.00512069680972, "y": 0.0952188738226587, "z": null, "yaw": 0.03319401965099318, "pitch": null, "roll": null}, "v": 2.098561316777298, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34896766184160555, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022271452430233245, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141177.431872} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24911786279650167, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3761112849607926, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.09741701491994, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141177.431872} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.039982795715332, "x": 37.00512069680972, "y": 0.0952188738226587, "z": null, "yaw": 0.03319401965099318, "pitch": null, "roll": null}, "v": 2.098561316777298, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34896766184160555, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022271452430233245, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141177.4518719} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24911786279650167, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3761112849607926, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.09616189591273, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141177.4518719} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.039982795715332, "x": 37.00512069680972, "y": 0.0952188738226587, "z": null, "yaw": 0.03319401965099318, "pitch": null, "roll": null}, "v": 2.098561316777298, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34896766184160555, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022271452430233245, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141177.4718719} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24911786279650167, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3761112849607926, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0957442919201674, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141177.4718719} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.039982795715332, "x": 37.00512069680972, "y": 0.0952188738226587, "z": null, "yaw": 0.03319401965099318, "pitch": null, "roll": null}, "v": 2.098561316777298, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34896766184160555, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022271452430233245, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141177.4918718} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24911786279650167, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3761112849607926, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.09491023512039, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141177.4918718} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141177.5118718, "x": 41.2356169175898, "y": 5.102750385718948, "z": null, "yaw": 0.0320266199911692, "pitch": null, "roll": null}, "v": 2.094077710652212, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3485555001151147, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022223869155094972, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141177.5118718} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24859163597832937, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.31057728264451, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.094077710652212, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141177.5118718} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.149982690811157, "x": 37.2356169175898, "y": 0.10275038571894779, "z": null, "yaw": 0.0320266199911692, "pitch": null, "roll": null}, "v": 2.094077710652212, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3485555001151147, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022223869155094972, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141177.5318718} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24881081748874095, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.31057728264451, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0931809672872896, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141177.5318718} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.149982690811157, "x": 37.2356169175898, "y": 0.10275038571894779, "z": null, "yaw": 0.0320266199911692, "pitch": null, "roll": null}, "v": 2.094077710652212, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3485555001151147, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022223869155094972, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141177.5518718} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24881081748874095, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.31057728264451, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.092313255913568, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141177.5518718} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.149982690811157, "x": 37.2356169175898, "y": 0.10275038571894779, "z": null, "yaw": 0.0320266199911692, "pitch": null, "roll": null}, "v": 2.094077710652212, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3485555001151147, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022223869155094972, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141177.5718718} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24881081748874095, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.31057728264451, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.091447137804103, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141177.5718718} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.149982690811157, "x": 37.2356169175898, "y": 0.10275038571894779, "z": null, "yaw": 0.0320266199911692, "pitch": null, "roll": null}, "v": 2.094077710652212, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3485555001151147, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022223869155094972, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141177.5918717} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24881081748874095, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.31057728264451, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0905826097334663, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141177.5918717} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.149982690811157, "x": 37.2356169175898, "y": 0.10275038571894779, "z": null, "yaw": 0.0320266199911692, "pitch": null, "roll": null}, "v": 2.094077710652212, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3485555001151147, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022223869155094972, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141177.6118717} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24881081748874095, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.31057728264451, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0897196684838035, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141177.6118717} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141177.6218717, "x": 41.465610209625275, "y": 5.109996697747575, "z": null, "yaw": 0.030859220331345208, "pitch": null, "roll": null}, "v": 2.089288791913323, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3481157161558125, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022173045681397666, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141177.6318717} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.252412332487605, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3589571595864414, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0888583108448113, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141177.6318717} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.259982585906982, "x": 37.465610209625275, "y": 0.10999669774757503, "z": null, "yaw": 0.030859220331345208, "pitch": null, "roll": null}, "v": 2.089288791913323, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3481157161558125, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022173045681397666, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141177.6518717} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25066381712254876, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3589571595864414, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.088448516417345, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141177.6518717} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.259982585906982, "x": 37.465610209625275, "y": 0.10999669774757503, "z": null, "yaw": 0.030859220331345208, "pitch": null, "roll": null}, "v": 2.089288791913323, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3481157161558125, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022173045681397666, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141177.6718717} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25066381712254876, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3589571595864414, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0878210096506677, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141177.6718717} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.259982585906982, "x": 37.465610209625275, "y": 0.10999669774757503, "z": null, "yaw": 0.030859220331345208, "pitch": null, "roll": null}, "v": 2.089288791913323, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3481157161558125, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022173045681397666, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141177.6918716} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25066381712254876, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3589571595864414, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.087194653950527, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141177.6918716} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.259982585906982, "x": 37.465610209625275, "y": 0.10999669774757503, "z": null, "yaw": 0.030859220331345208, "pitch": null, "roll": null}, "v": 2.089288791913323, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3481157161558125, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022173045681397666, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141177.7118716} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25066381712254876, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3589571595864414, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.086569447048608, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141177.7118716} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141177.7318716, "x": 41.69516073760308, "y": 5.116960810401662, "z": null, "yaw": 0.02969182067152119, "pitch": null, "roll": null}, "v": 2.0859453866816198, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34780895089626435, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022137563043850898, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141177.7318716} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2537750536045973, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.409909831244752, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0859453866816198, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141177.7318716} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.369982481002808, "x": 37.69516073760308, "y": 0.11696081040166195, "z": null, "yaw": 0.02969182067152119, "pitch": null, "roll": null}, "v": 2.0859453866816198, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34780895089626435, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022137563043850898, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141177.7518716} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2522701390796952, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.409909831244752, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0857111968103665, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141177.7518716} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.369982481002808, "x": 37.69516073760308, "y": 0.11696081040166195, "z": null, "yaw": 0.02969182067152119, "pitch": null, "roll": null}, "v": 2.0859453866816198, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34780895089626435, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022137563043850898, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141177.7718716} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2522701390796952, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.409909831244752, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0852894082635482, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141177.7718716} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.369982481002808, "x": 37.69516073760308, "y": 0.11696081040166195, "z": null, "yaw": 0.02969182067152119, "pitch": null, "roll": null}, "v": 2.0859453866816198, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34780895089626435, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022137563043850898, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141177.7918715} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2522701390796952, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.409909831244752, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0848683929888128, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141177.7918715} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.369982481002808, "x": 37.69516073760308, "y": 0.11696081040166195, "z": null, "yaw": 0.02969182067152119, "pitch": null, "roll": null}, "v": 2.0859453866816198, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34780895089626435, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022137563043850898, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141177.8118715} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2522701390796952, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.409909831244752, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0844481494976375, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141177.8118715} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.369982481002808, "x": 37.69516073760308, "y": 0.11696081040166195, "z": null, "yaw": 0.02969182067152119, "pitch": null, "roll": null}, "v": 2.0859453866816198, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34780895089626435, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022137563043850898, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141177.8318715} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2522701390796952, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.409909831244752, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0840286763046203, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141177.8318715} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141177.8418715, "x": 41.92441916118116, "y": 5.123648176456376, "z": null, "yaw": 0.028524421011697172, "pitch": null, "roll": null}, "v": 2.083819228106583, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34761398715959635, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.02211499870933063, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141177.8518715} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2558384369929123, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.21392394336573, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.083609971927468, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141177.8518715} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.479982376098633, "x": 37.92441916118116, "y": 0.12364817645637594, "z": null, "yaw": 0.028524421011697172, "pitch": null, "roll": null}, "v": 2.083819228106583, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34761398715959635, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.02211499870933063, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141177.8718715} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25412439227425115, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.21392394336573, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.083637867684421, "gear": 1, "accelerator_pedal_position": 0.2558384369929123, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141177.8718715} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.479982376098633, "x": 37.92441916118116, "y": 0.12364817645637594, "z": null, "yaw": 0.028524421011697172, "pitch": null, "roll": null}, "v": 2.083819228106583, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34761398715959635, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.02211499870933063, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141177.8918715} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25412439227425115, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.21392394336573, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0834515549355985, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141177.8918715} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.479982376098633, "x": 37.92441916118116, "y": 0.12364817645637594, "z": null, "yaw": 0.028524421011697172, "pitch": null, "roll": null}, "v": 2.083819228106583, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34761398715959635, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.02211499870933063, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141177.9118714} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25412439227425115, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.21392394336573, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.083265583615866, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141177.9118714} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.479982376098633, "x": 37.92441916118116, "y": 0.12364817645637594, "z": null, "yaw": 0.028524421011697172, "pitch": null, "roll": null}, "v": 2.083819228106583, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34761398715959635, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.02211499870933063, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141177.9318714} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25412439227425115, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.21392394336573, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.083079953085707, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141177.9318714} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141177.9518714, "x": 42.15350486968687, "y": 5.130062837279906, "z": null, "yaw": 0.027357021351873154, "pitch": null, "roll": null}, "v": 2.0828946627068534, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34752923489466964, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022105186551756726, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141177.9518714} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2568768701741816, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2502685857701639, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0828946627068534, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141177.9518714} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.589982271194458, "x": 38.15350486968687, "y": 0.13006283727990642, "z": null, "yaw": 0.027357021351873154, "pitch": null, "roll": null}, "v": 2.0828946627068534, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34752923489466964, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022105186551756726, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141177.9718714} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25555970843890713, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2502685857701639, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0830536139010425, "gear": 1, "accelerator_pedal_position": 0.2568768701741816, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141177.9718714} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.589982271194458, "x": 38.15350486968687, "y": 0.13006283727990642, "z": null, "yaw": 0.027357021351873154, "pitch": null, "roll": null}, "v": 2.0828946627068534, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34752923489466964, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022105186551756726, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141177.9918714} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25555970843890713, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2502685857701639, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0830477040800712, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141177.9918714} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.589982271194458, "x": 38.15350486968687, "y": 0.13006283727990642, "z": null, "yaw": 0.027357021351873154, "pitch": null, "roll": null}, "v": 2.0828946627068534, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34752923489466964, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022105186551756726, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141178.0118713} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25555970843890713, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2502685857701639, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0830418050881345, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141178.0118713} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.589982271194458, "x": 38.15350486968687, "y": 0.13006283727990642, "z": null, "yaw": 0.027357021351873154, "pitch": null, "roll": null}, "v": 2.0828946627068534, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34752923489466964, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022105186551756726, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141178.0318713} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25555970843890713, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2502685857701639, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.083035916905376, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141178.0318713} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.589982271194458, "x": 38.15350486968687, "y": 0.13006283727990642, "z": null, "yaw": 0.027357021351873154, "pitch": null, "roll": null}, "v": 2.0828946627068534, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34752923489466964, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022105186551756726, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141178.0518713} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25555970843890713, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2502685857701639, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.083030039511975, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141178.0518713} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141178.0618713, "x": 42.38255486524887, "y": 5.13620889421487, "z": null, "yaw": 0.026189621692049136, "pitch": null, "roll": null}, "v": 2.0830271048550997, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3475413744383652, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022106592123745897, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141178.0718713} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2579830790462231, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.288079190559632, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.083024172888148, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141178.0718713} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.699982166290283, "x": 38.38255486524887, "y": 0.13620889421487004, "z": null, "yaw": 0.026189621692049136, "pitch": null, "roll": null}, "v": 2.0830271048550997, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3475413744383652, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022106592123745897, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141178.0918713} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2568300173843495, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.288079190559632, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0833210995082796, "gear": 1, "accelerator_pedal_position": 0.2579830790462231, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141178.0918713} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.699982166290283, "x": 38.38255486524887, "y": 0.13620889421487004, "z": null, "yaw": 0.026189621692049136, "pitch": null, "roll": null}, "v": 2.0830271048550997, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3475413744383652, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022106592123745897, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141178.1118712} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2568300173843495, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.288079190559632, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0834734153772376, "gear": 1, "accelerator_pedal_position": 0.2568300173843495, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141178.1118712} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.699982166290283, "x": 38.38255486524887, "y": 0.13620889421487004, "z": null, "yaw": 0.026189621692049136, "pitch": null, "roll": null}, "v": 2.0830271048550997, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3475413744383652, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022106592123745897, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141178.1318712} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2568300173843495, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.288079190559632, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0836254521222157, "gear": 1, "accelerator_pedal_position": 0.2568300173843495, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141178.1318712} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.699982166290283, "x": 38.38255486524887, "y": 0.13620889421487004, "z": null, "yaw": 0.026189621692049136, "pitch": null, "roll": null}, "v": 2.0830271048550997, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3475413744383652, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022106592123745897, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141178.1518712} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2568300173843495, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.288079190559632, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0837772102454766, "gear": 1, "accelerator_pedal_position": 0.2568300173843495, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141178.1518712} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141178.1718712, "x": 42.61165863554302, "y": 5.142088744915665, "z": null, "yaw": 0.02502222203222512, "pitch": null, "roll": null}, "v": 2.083928690248412, "accelerator_pedal_position": 0.2568300173843495, "brake_pedal_position": 0.0, "acceleration": 0.007563586279359158, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022116160400850036, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141178.1718712} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2598382440257841, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.240513164602925, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.083928690248412, "gear": 1, "accelerator_pedal_position": 0.2568300173843495, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141178.1718712} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.80998206138611, "x": 38.61165863554302, "y": 0.14208874491566537, "z": null, "yaw": 0.02502222203222512, "pitch": null, "roll": null}, "v": 2.083928690248412, "accelerator_pedal_position": 0.2568300173843495, "brake_pedal_position": 0.0, "acceleration": 0.007563586279359158, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022116160400850036, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141178.1918712} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2584120514219476, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.240513164602925, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.084455748586642, "gear": 1, "accelerator_pedal_position": 0.2598382440257841, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141178.1918712} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.80998206138611, "x": 38.61165863554302, "y": 0.14208874491566537, "z": null, "yaw": 0.02502222203222512, "pitch": null, "roll": null}, "v": 2.083928690248412, "accelerator_pedal_position": 0.2568300173843495, "brake_pedal_position": 0.0, "acceleration": 0.007563586279359158, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022116160400850036, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141178.2118711} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2584120514219476, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.240513164602925, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.084803648542858, "gear": 1, "accelerator_pedal_position": 0.2584120514219476, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141178.2118711} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.80998206138611, "x": 38.61165863554302, "y": 0.14208874491566537, "z": null, "yaw": 0.02502222203222512, "pitch": null, "roll": null}, "v": 2.083928690248412, "accelerator_pedal_position": 0.2568300173843495, "brake_pedal_position": 0.0, "acceleration": 0.007563586279359158, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022116160400850036, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141178.2318711} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2584120514219476, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.240513164602925, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0851509107824966, "gear": 1, "accelerator_pedal_position": 0.2584120514219476, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141178.2318711} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.80998206138611, "x": 38.61165863554302, "y": 0.14208874491566537, "z": null, "yaw": 0.02502222203222512, "pitch": null, "roll": null}, "v": 2.083928690248412, "accelerator_pedal_position": 0.2568300173843495, "brake_pedal_position": 0.0, "acceleration": 0.007563586279359158, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022116160400850036, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141178.251871} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2584120514219476, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.240513164602925, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.085497536426307, "gear": 1, "accelerator_pedal_position": 0.2584120514219476, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141178.251871} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.80998206138611, "x": 38.61165863554302, "y": 0.14208874491566537, "z": null, "yaw": 0.02502222203222512, "pitch": null, "roll": null}, "v": 2.083928690248412, "accelerator_pedal_position": 0.2568300173843495, "brake_pedal_position": 0.0, "acceleration": 0.007563586279359158, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022116160400850036, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141178.271871} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2584120514219476, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.240513164602925, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0858435265932496, "gear": 1, "accelerator_pedal_position": 0.2584120514219476, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141178.271871} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141178.281871, "x": 42.84093458630885, "y": 5.147705177970934, "z": null, "yaw": 0.0238548223724011, "pitch": null, "roll": null}, "v": 2.0860162837220817, "accelerator_pedal_position": 0.2584120514219476, "brake_pedal_position": 0.0, "acceleration": 0.017259867841531662, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022138315454586516, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141178.291871} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26384363336571526, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0982917477973302, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.086188882400497, "gear": 1, "accelerator_pedal_position": 0.2584120514219476, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141178.291871} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.919981956481934, "x": 38.84093458630885, "y": 0.1477051779709342, "z": null, "yaw": 0.0238548223724011, "pitch": null, "roll": null}, "v": 2.0860162837220817, "accelerator_pedal_position": 0.2584120514219476, "brake_pedal_position": 0.0, "acceleration": 0.017259867841531662, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022138315454586516, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141178.311871} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2612717497208913, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0982917477973302, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0872122413049166, "gear": 1, "accelerator_pedal_position": 0.26384363336571526, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141178.311871} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.919981956481934, "x": 38.84093458630885, "y": 0.1477051779709342, "z": null, "yaw": 0.0238548223724011, "pitch": null, "roll": null}, "v": 2.0860162837220817, "accelerator_pedal_position": 0.2584120514219476, "brake_pedal_position": 0.0, "acceleration": 0.017259867841531662, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022138315454586516, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141178.331871} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2612717497208913, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0982917477973302, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.087912385460021, "gear": 1, "accelerator_pedal_position": 0.2612717497208913, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141178.331871} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.919981956481934, "x": 38.84093458630885, "y": 0.1477051779709342, "z": null, "yaw": 0.0238548223724011, "pitch": null, "roll": null}, "v": 2.0860162837220817, "accelerator_pedal_position": 0.2584120514219476, "brake_pedal_position": 0.0, "acceleration": 0.017259867841531662, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022138315454586516, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141178.351871} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2612717497208913, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0982917477973302, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0886112453735985, "gear": 1, "accelerator_pedal_position": 0.2612717497208913, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141178.351871} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.919981956481934, "x": 38.84093458630885, "y": 0.1477051779709342, "z": null, "yaw": 0.0238548223724011, "pitch": null, "roll": null}, "v": 2.0860162837220817, "accelerator_pedal_position": 0.2584120514219476, "brake_pedal_position": 0.0, "acceleration": 0.017259867841531662, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022138315454586516, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141178.371871} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2612717497208913, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0982917477973302, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0893088232060006, "gear": 1, "accelerator_pedal_position": 0.2612717497208913, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141178.371871} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141178.391871, "x": 43.07053603095351, "y": 5.153061372659257, "z": null, "yaw": 0.022687422712577083, "pitch": null, "roll": null}, "v": 2.0900051211146895, "accelerator_pedal_position": 0.2612717497208913, "brake_pedal_position": 0.0, "acceleration": 0.034766965636979674, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022180647885634, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141178.391871} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26290540098607595, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1221389658055887, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0900051211146895, "gear": 1, "accelerator_pedal_position": 0.2612717497208913, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141178.391871} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.02998185157776, "x": 39.07053603095351, "y": 0.15306137265925734, "z": null, "yaw": 0.022687422712577083, "pitch": null, "roll": null}, "v": 2.0900051211146895, "accelerator_pedal_position": 0.2612717497208913, "brake_pedal_position": 0.0, "acceleration": 0.034766965636979674, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022180647885634, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141178.411871} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2621553584144861, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1221389658055887, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.090904253923401, "gear": 1, "accelerator_pedal_position": 0.26290540098607595, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141178.411871} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.02998185157776, "x": 39.07053603095351, "y": 0.15306137265925734, "z": null, "yaw": 0.022687422712577083, "pitch": null, "roll": null}, "v": 2.0900051211146895, "accelerator_pedal_position": 0.2612717497208913, "brake_pedal_position": 0.0, "acceleration": 0.034766965636979674, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022180647885634, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141178.431871} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2621553584144861, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1221389658055887, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.091708024162595, "gear": 1, "accelerator_pedal_position": 0.2621553584144861, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141178.431871} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.02998185157776, "x": 39.07053603095351, "y": 0.15306137265925734, "z": null, "yaw": 0.022687422712577083, "pitch": null, "roll": null}, "v": 2.0900051211146895, "accelerator_pedal_position": 0.2612717497208913, "brake_pedal_position": 0.0, "acceleration": 0.034766965636979674, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022180647885634, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141178.451871} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2621553584144861, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1221389658055887, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0925103188729226, "gear": 1, "accelerator_pedal_position": 0.2621553584144861, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141178.451871} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.02998185157776, "x": 39.07053603095351, "y": 0.15306137265925734, "z": null, "yaw": 0.022687422712577083, "pitch": null, "roll": null}, "v": 2.0900051211146895, "accelerator_pedal_position": 0.2612717497208913, "brake_pedal_position": 0.0, "acceleration": 0.034766965636979674, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022180647885634, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141178.471871} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2621553584144861, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1221389658055887, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.093311140505746, "gear": 1, "accelerator_pedal_position": 0.2621553584144861, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141178.471871} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.02998185157776, "x": 39.07053603095351, "y": 0.15306137265925734, "z": null, "yaw": 0.022687422712577083, "pitch": null, "roll": null}, "v": 2.0900051211146895, "accelerator_pedal_position": 0.2612717497208913, "brake_pedal_position": 0.0, "acceleration": 0.034766965636979674, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022180647885634, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141178.4918709} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2621553584144861, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1221389658055887, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0941104915093463, "gear": 1, "accelerator_pedal_position": 0.2621553584144861, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141178.4918709} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141178.5018709, "x": 43.300609951550165, "y": 5.158159858215573, "z": null, "yaw": 0.021520023052753065, "pitch": null, "roll": null}, "v": 2.094509616289432, "accelerator_pedal_position": 0.2621553584144861, "brake_pedal_position": 0.0, "acceleration": 0.03987580394877749, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022228452850494667, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141178.5118709} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2637216227221697, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1459193027555212, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0949083743289196, "gear": 1, "accelerator_pedal_position": 0.2621553584144861, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141178.5118709} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.139981746673584, "x": 39.300609951550165, "y": 0.15815985821557277, "z": null, "yaw": 0.021520023052753065, "pitch": null, "roll": null}, "v": 2.094509616289432, "accelerator_pedal_position": 0.2621553584144861, "brake_pedal_position": 0.0, "acceleration": 0.03987580394877749, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022228452850494667, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141178.5318708} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26300730343963297, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1459193027555212, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.09590048447577, "gear": 1, "accelerator_pedal_position": 0.2637216227221697, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141178.5318708} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.139981746673584, "x": 39.300609951550165, "y": 0.15815985821557277, "z": null, "yaw": 0.021520023052753065, "pitch": null, "roll": null}, "v": 2.094509616289432, "accelerator_pedal_position": 0.2621553584144861, "brake_pedal_position": 0.0, "acceleration": 0.03987580394877749, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022228452850494667, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141178.5518708} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26300730343963297, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1459193027555212, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.096801522834088, "gear": 1, "accelerator_pedal_position": 0.26300730343963297, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141178.5518708} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.139981746673584, "x": 39.300609951550165, "y": 0.15815985821557277, "z": null, "yaw": 0.021520023052753065, "pitch": null, "roll": null}, "v": 2.094509616289432, "accelerator_pedal_position": 0.2621553584144861, "brake_pedal_position": 0.0, "acceleration": 0.03987580394877749, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022228452850494667, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141178.5718708} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26300730343963297, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1459193027555212, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0977009052773354, "gear": 1, "accelerator_pedal_position": 0.26300730343963297, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141178.5718708} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.139981746673584, "x": 39.300609951550165, "y": 0.15815985821557277, "z": null, "yaw": 0.021520023052753065, "pitch": null, "roll": null}, "v": 2.094509616289432, "accelerator_pedal_position": 0.2621553584144861, "brake_pedal_position": 0.0, "acceleration": 0.03987580394877749, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022228452850494667, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141178.5918708} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26300730343963297, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1459193027555212, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0985986345253216, "gear": 1, "accelerator_pedal_position": 0.26300730343963297, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141178.5918708} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141178.6118708, "x": 43.53120537227767, "y": 5.163000572329205, "z": null, "yaw": 0.020352623392929047, "pitch": null, "roll": null}, "v": 2.0994947132946398, "accelerator_pedal_position": 0.26300730343963297, "brake_pedal_position": 0.0, "acceleration": 0.04474213032145258, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.02228135831002257, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141178.6118708} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27901753154377096, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8504428123308396, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1023895021350207, "gear": 1, "accelerator_pedal_position": 0.27901753154377096, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141178.6118708} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.24998164176941, "x": 39.53120537227767, "y": 0.16300057232920473, "z": null, "yaw": 0.020352623392929047, "pitch": null, "roll": null}, "v": 2.0994947132946398, "accelerator_pedal_position": 0.26300730343963297, "brake_pedal_position": 0.0, "acceleration": 0.04474213032145258, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.02228135831002257, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141178.6318707} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2714285299914859, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8504428123308396, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1023895021350207, "gear": 1, "accelerator_pedal_position": 0.27901753154377096, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141178.6318707} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.24998164176941, "x": 39.53120537227767, "y": 0.16300057232920473, "z": null, "yaw": 0.020352623392929047, "pitch": null, "roll": null}, "v": 2.0994947132946398, "accelerator_pedal_position": 0.26300730343963297, "brake_pedal_position": 0.0, "acceleration": 0.04474213032145258, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.02228135831002257, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141178.6618707} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2714285299914859, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8504428123308396, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1053000735366587, "gear": 1, "accelerator_pedal_position": 0.2714285299914859, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141178.6618707} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2714285299914859, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8504428123308396, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1062684777843947, "gear": 1, "accelerator_pedal_position": 0.2714285299914859, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141178.6718707} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.24998164176941, "x": 39.53120537227767, "y": 0.16300057232920473, "z": null, "yaw": 0.020352623392929047, "pitch": null, "roll": null}, "v": 2.0994947132946398, "accelerator_pedal_position": 0.26300730343963297, "brake_pedal_position": 0.0, "acceleration": 0.04474213032145258, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.02228135831002257, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141178.6918707} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2714285299914859, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8504428123308396, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1091683407519395, "gear": 1, "accelerator_pedal_position": 0.2714285299914859, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141178.6918707} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141178.7218707, "x": 43.76272814048737, "y": 5.1675902946392025, "z": null, "yaw": 0.01918522373310503, "pitch": null, "roll": null}, "v": 2.1110971309272517, "accelerator_pedal_position": 0.2714285299914859, "brake_pedal_position": 0.0, "acceleration": 0.09630614493833156, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022404491568181185, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141178.7218707} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27293217908865475, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8358474644059379, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.112154170445208, "gear": 1, "accelerator_pedal_position": 0.27293217908865475, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141178.7218707} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.359981536865234, "x": 39.76272814048737, "y": 0.1675902946392025, "z": null, "yaw": 0.01918522373310503, "pitch": null, "roll": null}, "v": 2.1110971309272517, "accelerator_pedal_position": 0.2714285299914859, "brake_pedal_position": 0.0, "acceleration": 0.09630614493833156, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022404491568181185, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141178.7418706} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27229757644592084, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8358474644059379, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1132102350290536, "gear": 1, "accelerator_pedal_position": 0.27293217908865475, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141178.7418706} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.359981536865234, "x": 39.76272814048737, "y": 0.1675902946392025, "z": null, "yaw": 0.01918522373310503, "pitch": null, "roll": null}, "v": 2.1110971309272517, "accelerator_pedal_position": 0.2714285299914859, "brake_pedal_position": 0.0, "acceleration": 0.09630614493833156, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022404491568181185, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141178.7618706} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27229757644592084, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8358474644059379, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1152401533709138, "gear": 1, "accelerator_pedal_position": 0.27229757644592084, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141178.7618706} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.359981536865234, "x": 39.76272814048737, "y": 0.1675902946392025, "z": null, "yaw": 0.01918522373310503, "pitch": null, "roll": null}, "v": 2.1110971309272517, "accelerator_pedal_position": 0.2714285299914859, "brake_pedal_position": 0.0, "acceleration": 0.09630614493833156, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022404491568181185, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141178.7818706} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27229757644592084, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8358474644059379, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.117266326429911, "gear": 1, "accelerator_pedal_position": 0.27229757644592084, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141178.7818706} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.359981536865234, "x": 39.76272814048737, "y": 0.1675902946392025, "z": null, "yaw": 0.01918522373310503, "pitch": null, "roll": null}, "v": 2.1110971309272517, "accelerator_pedal_position": 0.2714285299914859, "brake_pedal_position": 0.0, "acceleration": 0.09630614493833156, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022404491568181185, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141178.8018706} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27229757644592084, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8358474644059379, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1192887594748524, "gear": 1, "accelerator_pedal_position": 0.27229757644592084, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141178.8018706} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.359981536865234, "x": 39.76272814048737, "y": 0.1675902946392025, "z": null, "yaw": 0.01918522373310503, "pitch": null, "roll": null}, "v": 2.1110971309272517, "accelerator_pedal_position": 0.2714285299914859, "brake_pedal_position": 0.0, "acceleration": 0.09630614493833156, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022404491568181185, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141178.8218706} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27229757644592084, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8358474644059379, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.121307457773909, "gear": 1, "accelerator_pedal_position": 0.27229757644592084, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141178.8218706} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141178.8318706, "x": 43.99547382860511, "y": 5.1719324542772105, "z": null, "yaw": 0.01801782407328101, "pitch": null, "roll": null}, "v": 2.122315408039851, "accelerator_pedal_position": 0.27229757644592084, "brake_pedal_position": 0.0, "acceleration": 0.100701855472979, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.02252354804895446, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141178.8418705} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2957538581293554, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5269792987173588, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.123322426594581, "gear": 1, "accelerator_pedal_position": 0.27229757644592084, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141178.8418705} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.46998143196106, "x": 39.99547382860511, "y": 0.1719324542772105, "z": null, "yaw": 0.01801782407328101, "pitch": null, "roll": null}, "v": 2.122315408039851, "accelerator_pedal_position": 0.27229757644592084, "brake_pedal_position": 0.0, "acceleration": 0.100701855472979, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.02252354804895446, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141178.8618705} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28466311501069075, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5269792987173588, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.128264350329773, "gear": 1, "accelerator_pedal_position": 0.2957538581293554, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141178.8618705} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.46998143196106, "x": 39.99547382860511, "y": 0.1719324542772105, "z": null, "yaw": 0.01801782407328101, "pitch": null, "roll": null}, "v": 2.122315408039851, "accelerator_pedal_position": 0.27229757644592084, "brake_pedal_position": 0.0, "acceleration": 0.100701855472979, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.02252354804895446, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141178.8818705} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28466311501069075, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5269792987173588, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1318114307690603, "gear": 1, "accelerator_pedal_position": 0.28466311501069075, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141178.8818705} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.46998143196106, "x": 39.99547382860511, "y": 0.1719324542772105, "z": null, "yaw": 0.01801782407328101, "pitch": null, "roll": null}, "v": 2.122315408039851, "accelerator_pedal_position": 0.27229757644592084, "brake_pedal_position": 0.0, "acceleration": 0.100701855472979, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.02252354804895446, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141178.9018705} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28466311501069075, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5269792987173588, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.135351943746769, "gear": 1, "accelerator_pedal_position": 0.28466311501069075, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141178.9018705} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.46998143196106, "x": 39.99547382860511, "y": 0.1719324542772105, "z": null, "yaw": 0.01801782407328101, "pitch": null, "roll": null}, "v": 2.122315408039851, "accelerator_pedal_position": 0.27229757644592084, "brake_pedal_position": 0.0, "acceleration": 0.100701855472979, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.02252354804895446, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141178.9218705} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28466311501069075, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5269792987173588, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1388858964108617, "gear": 1, "accelerator_pedal_position": 0.28466311501069075, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141178.9218705} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141178.9418705, "x": 44.22990934287443, "y": 5.176032271842575, "z": null, "yaw": 0.016850424413456994, "pitch": null, "roll": null}, "v": 2.1424132959239093, "accelerator_pedal_position": 0.28466311501069075, "brake_pedal_position": 0.0, "acceleration": 0.17612445671510613, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022736841389672916, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141178.9418705} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28497105506629933, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4925013678889609, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1424132959239093, "gear": 1, "accelerator_pedal_position": 0.28466311501069075, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141178.9418705} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.579981327056885, "x": 40.22990934287443, "y": 0.1760322718425753, "z": null, "yaw": 0.016850424413456994, "pitch": null, "roll": null}, "v": 2.1424132959239093, "accelerator_pedal_position": 0.28466311501069075, "brake_pedal_position": 0.0, "acceleration": 0.17612445671510613, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022736841389672916, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141178.9618704} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28496628473554536, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4925013678889609, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1459726240932957, "gear": 1, "accelerator_pedal_position": 0.28497105506629933, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141178.9618704} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.579981327056885, "x": 40.22990934287443, "y": 0.1760322718425753, "z": null, "yaw": 0.016850424413456994, "pitch": null, "roll": null}, "v": 2.1424132959239093, "accelerator_pedal_position": 0.28466311501069075, "brake_pedal_position": 0.0, "acceleration": 0.17612445671510613, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022736841389672916, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141178.9818704} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28496628473554536, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4925013678889609, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1495247459714104, "gear": 1, "accelerator_pedal_position": 0.28496628473554536, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141178.9818704} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.579981327056885, "x": 40.22990934287443, "y": 0.1760322718425753, "z": null, "yaw": 0.016850424413456994, "pitch": null, "roll": null}, "v": 2.1424132959239093, "accelerator_pedal_position": 0.28466311501069075, "brake_pedal_position": 0.0, "acceleration": 0.17612445671510613, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022736841389672916, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141179.0018704} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28496628473554536, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4925013678889609, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.153070265910867, "gear": 1, "accelerator_pedal_position": 0.28496628473554536, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141179.0018704} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.579981327056885, "x": 40.22990934287443, "y": 0.1760322718425753, "z": null, "yaw": 0.016850424413456994, "pitch": null, "roll": null}, "v": 2.1424132959239093, "accelerator_pedal_position": 0.28466311501069075, "brake_pedal_position": 0.0, "acceleration": 0.17612445671510613, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022736841389672916, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141179.0218704} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28496628473554536, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4925013678889609, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1566091911560172, "gear": 1, "accelerator_pedal_position": 0.28496628473554536, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141179.0218704} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.579981327056885, "x": 40.22990934287443, "y": 0.1760322718425753, "z": null, "yaw": 0.016850424413456994, "pitch": null, "roll": null}, "v": 2.1424132959239093, "accelerator_pedal_position": 0.28466311501069075, "brake_pedal_position": 0.0, "acceleration": 0.17612445671510613, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022736841389672916, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141179.0418704} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28496628473554536, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4925013678889609, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.160141528965777, "gear": 1, "accelerator_pedal_position": 0.28496628473554536, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141179.0418704} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141179.0518703, "x": 44.46651972071541, "y": 5.179893838960271, "z": null, "yaw": 0.015683024753632976, "pitch": null, "roll": null}, "v": 2.1619052298547494, "accelerator_pedal_position": 0.28496628473554536, "brake_pedal_position": 0.0, "acceleration": 0.1762056758756878, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022943703908219964, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141179.0618703} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28555768732427633, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4543961773623459, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1636672866135065, "gear": 1, "accelerator_pedal_position": 0.28496628473554536, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141179.0618703} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.68998122215271, "x": 40.46651972071541, "y": 0.1798938389602709, "z": null, "yaw": 0.015683024753632976, "pitch": null, "roll": null}, "v": 2.1619052298547494, "accelerator_pedal_position": 0.28496628473554536, "brake_pedal_position": 0.0, "acceleration": 0.1762056758756878, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022943703908219964, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141179.0818703} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2854142453813973, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4543961773623459, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.16726036222102, "gear": 1, "accelerator_pedal_position": 0.28555768732427633, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141179.0818703} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.68998122215271, "x": 40.46651972071541, "y": 0.1798938389602709, "z": null, "yaw": 0.015683024753632976, "pitch": null, "roll": null}, "v": 2.1619052298547494, "accelerator_pedal_position": 0.28496628473554536, "brake_pedal_position": 0.0, "acceleration": 0.1762056758756878, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022943703908219964, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141179.1018703} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2854142453813973, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4543961773623459, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1708288124508295, "gear": 1, "accelerator_pedal_position": 0.2854142453813973, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141179.1018703} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.68998122215271, "x": 40.46651972071541, "y": 0.1798938389602709, "z": null, "yaw": 0.015683024753632976, "pitch": null, "roll": null}, "v": 2.1619052298547494, "accelerator_pedal_position": 0.28496628473554536, "brake_pedal_position": 0.0, "acceleration": 0.1762056758756878, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022943703908219964, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141179.1218703} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2854142453813973, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4543961773623459, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1743906000194313, "gear": 1, "accelerator_pedal_position": 0.2854142453813973, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141179.1218703} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.68998122215271, "x": 40.46651972071541, "y": 0.1798938389602709, "z": null, "yaw": 0.015683024753632976, "pitch": null, "roll": null}, "v": 2.1619052298547494, "accelerator_pedal_position": 0.28496628473554536, "brake_pedal_position": 0.0, "acceleration": 0.1762056758756878, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.022943703908219964, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141179.1418703} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2854142453813973, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4543961773623459, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1779457322945324, "gear": 1, "accelerator_pedal_position": 0.2854142453813973, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141179.1418703} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141179.1618702, "x": 44.70528238293877, "y": 5.183511732320137, "z": null, "yaw": 0.014515625093808958, "pitch": null, "roll": null}, "v": 2.1814942166584994, "accelerator_pedal_position": 0.2854142453813973, "brake_pedal_position": 0.0, "acceleration": 0.1771751526276633, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.0231515964221381, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141179.1618702} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28592112327536834, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4135032075733135, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1814942166584994, "gear": 1, "accelerator_pedal_position": 0.2854142453813973, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141179.1618702} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.799981117248535, "x": 40.70528238293877, "y": 0.18351173232013718, "z": null, "yaw": 0.014515625093808958, "pitch": null, "roll": null}, "v": 2.1814942166584994, "accelerator_pedal_position": 0.2854142453813973, "brake_pedal_position": 0.0, "acceleration": 0.1771751526276633, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.0231515964221381, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141179.1818702} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2858192024966282, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4135032075733135, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.185099390571834, "gear": 1, "accelerator_pedal_position": 0.28592112327536834, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141179.1818702} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.799981117248535, "x": 40.70528238293877, "y": 0.18351173232013718, "z": null, "yaw": 0.014515625093808958, "pitch": null, "roll": null}, "v": 2.1814942166584994, "accelerator_pedal_position": 0.2854142453813973, "brake_pedal_position": 0.0, "acceleration": 0.1771751526276633, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.0231515964221381, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141179.2018702} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2858192024966282, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4135032075733135, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.188685078584219, "gear": 1, "accelerator_pedal_position": 0.2858192024966282, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141179.2018702} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.799981117248535, "x": 40.70528238293877, "y": 0.18351173232013718, "z": null, "yaw": 0.014515625093808958, "pitch": null, "roll": null}, "v": 2.1814942166584994, "accelerator_pedal_position": 0.2854142453813973, "brake_pedal_position": 0.0, "acceleration": 0.1771751526276633, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.0231515964221381, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141179.2218702} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2858192024966282, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4135032075733135, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1922640461700413, "gear": 1, "accelerator_pedal_position": 0.2858192024966282, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141179.2218702} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.799981117248535, "x": 40.70528238293877, "y": 0.18351173232013718, "z": null, "yaw": 0.014515625093808958, "pitch": null, "roll": null}, "v": 2.1814942166584994, "accelerator_pedal_position": 0.2854142453813973, "brake_pedal_position": 0.0, "acceleration": 0.1771751526276633, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.0231515964221381, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141179.2418702} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2858192024966282, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4135032075733135, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1958363008037662, "gear": 1, "accelerator_pedal_position": 0.2858192024966282, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141179.2418702} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.799981117248535, "x": 40.70528238293877, "y": 0.18351173232013718, "z": null, "yaw": 0.014515625093808958, "pitch": null, "roll": null}, "v": 2.1814942166584994, "accelerator_pedal_position": 0.2854142453813973, "brake_pedal_position": 0.0, "acceleration": 0.1771751526276633, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.0231515964221381, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141179.2618701} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2858192024966282, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4135032075733135, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1994018499746515, "gear": 1, "accelerator_pedal_position": 0.2858192024966282, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141179.2618701} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141179.2718701, "x": 44.94620998940349, "y": 5.186881112876351, "z": null, "yaw": 0.01334822543398494, "pitch": null, "roll": null}, "v": 2.2011821123559363, "accelerator_pedal_position": 0.2858192024966282, "brake_pedal_position": 0.0, "acceleration": 0.17785888306857178, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.023360538628863906, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141179.2818701} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3214724472930075, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.00911758711632836, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.202960701186622, "gear": 1, "accelerator_pedal_position": 0.2858192024966282, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141179.2818701} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.90998101234436, "x": 40.94620998940349, "y": 0.18688111287635056, "z": null, "yaw": 0.01334822543398494, "pitch": null, "roll": null}, "v": 2.2011821123559363, "accelerator_pedal_position": 0.2858192024966282, "brake_pedal_position": 0.0, "acceleration": 0.17785888306857178, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.023360538628863906, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141179.30187} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3046354462385261, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.00911758711632836, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2109674203216243, "gear": 1, "accelerator_pedal_position": 0.3214724472930075, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141179.30187} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.90998101234436, "x": 40.94620998940349, "y": 0.18688111287635056, "z": null, "yaw": 0.01334822543398494, "pitch": null, "roll": null}, "v": 2.2011821123559363, "accelerator_pedal_position": 0.2858192024966282, "brake_pedal_position": 0.0, "acceleration": 0.17785888306857178, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.023360538628863906, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141179.32187} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3046354462385261, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.00911758711632836, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.216855432295817, "gear": 1, "accelerator_pedal_position": 0.3046354462385261, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141179.32187} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.90998101234436, "x": 40.94620998940349, "y": 0.18688111287635056, "z": null, "yaw": 0.01334822543398494, "pitch": null, "roll": null}, "v": 2.2011821123559363, "accelerator_pedal_position": 0.2858192024966282, "brake_pedal_position": 0.0, "acceleration": 0.17785888306857178, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.023360538628863906, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141179.34187} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3046354462385261, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.00911758711632836, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2227323438147644, "gear": 1, "accelerator_pedal_position": 0.3046354462385261, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141179.34187} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.90998101234436, "x": 40.94620998940349, "y": 0.18688111287635056, "z": null, "yaw": 0.01334822543398494, "pitch": null, "roll": null}, "v": 2.2011821123559363, "accelerator_pedal_position": 0.2858192024966282, "brake_pedal_position": 0.0, "acceleration": 0.17785888306857178, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.023360538628863906, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141179.36187} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3046354462385261, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.00911758711632836, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2285981619970343, "gear": 1, "accelerator_pedal_position": 0.3046354462385261, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141179.36187} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141179.38187, "x": 45.19000159018385, "y": 5.19000574397161, "z": null, "yaw": 0.012180825774160922, "pitch": null, "roll": null}, "v": 2.2344528940259303, "accelerator_pedal_position": 0.3046354462385261, "brake_pedal_position": 0.0, "acceleration": 0.292321096933283, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.023713632257987814, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141179.38187} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28140353485344427, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.13546586691452597, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2344528940259303, "gear": 1, "accelerator_pedal_position": 0.3046354462385261, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141179.38187} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.019980907440186, "x": 41.19000159018385, "y": 0.19000574397160985, "z": null, "yaw": 0.012180825774160922, "pitch": null, "roll": null}, "v": 2.2344528940259303, "accelerator_pedal_position": 0.3046354462385261, "brake_pedal_position": 0.0, "acceleration": 0.292321096933283, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.023713632257987814, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141179.40187} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2927055409319691, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.13546586691452597, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.237393933743962, "gear": 1, "accelerator_pedal_position": 0.28140353485344427, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141179.40187} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.019980907440186, "x": 41.19000159018385, "y": 0.19000574397160985, "z": null, "yaw": 0.012180825774160922, "pitch": null, "roll": null}, "v": 2.2344528940259303, "accelerator_pedal_position": 0.3046354462385261, "brake_pedal_position": 0.0, "acceleration": 0.292321096933283, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.023713632257987814, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141179.42187} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2927055409319691, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.13546586691452597, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2417414850480646, "gear": 1, "accelerator_pedal_position": 0.2927055409319691, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141179.42187} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.019980907440186, "x": 41.19000159018385, "y": 0.19000574397160985, "z": null, "yaw": 0.012180825774160922, "pitch": null, "roll": null}, "v": 2.2344528940259303, "accelerator_pedal_position": 0.3046354462385261, "brake_pedal_position": 0.0, "acceleration": 0.292321096933283, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.023713632257987814, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141179.44187} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2927055409319691, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.13546586691452597, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.246080796165672, "gear": 1, "accelerator_pedal_position": 0.2927055409319691, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141179.44187} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.019980907440186, "x": 41.19000159018385, "y": 0.19000574397160985, "z": null, "yaw": 0.012180825774160922, "pitch": null, "roll": null}, "v": 2.2344528940259303, "accelerator_pedal_position": 0.3046354462385261, "brake_pedal_position": 0.0, "acceleration": 0.292321096933283, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.023713632257987814, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141179.46187} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2927055409319691, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.13546586691452597, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.250411875186649, "gear": 1, "accelerator_pedal_position": 0.2927055409319691, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141179.46187} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.019980907440186, "x": 41.19000159018385, "y": 0.19000574397160985, "z": null, "yaw": 0.012180825774160922, "pitch": null, "roll": null}, "v": 2.2344528940259303, "accelerator_pedal_position": 0.3046354462385261, "brake_pedal_position": 0.0, "acceleration": 0.292321096933283, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.023713632257987814, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141179.48187} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2927055409319691, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.13546586691452597, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2547347302283494, "gear": 1, "accelerator_pedal_position": 0.2927055409319691, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141179.48187} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141179.49187, "x": 45.43683525146994, "y": 5.19288129023154, "z": null, "yaw": 0.011013426114336904, "pitch": null, "roll": null}, "v": 2.2568930763011132, "accelerator_pedal_position": 0.2927055409319691, "brake_pedal_position": 0.0, "acceleration": 0.21562931343119213, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.023951783723028152, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141179.50187} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.015930997272302024, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0359945017123848, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.259049369435425, "gear": 1, "accelerator_pedal_position": 0.2927055409319691, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5868680246642785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141179.50187} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.12998080253601, "x": 41.43683525146994, "y": 0.19288129023154, "z": null, "yaw": 0.011013426114336904, "pitch": null, "roll": null}, "v": 2.2568930763011132, "accelerator_pedal_position": 0.2927055409319691, "brake_pedal_position": 0.0, "acceleration": 0.21562931343119213, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.023951783723028152, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141179.52187} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23362644452076645, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0359945017123848, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.249225374789098, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.015930997272302024, "steering_wheel_angle": -0.5057451576230444, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141179.52187} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.12998080253601, "x": 41.43683525146994, "y": 0.19288129023154, "z": null, "yaw": 0.011013426114336904, "pitch": null, "roll": null}, "v": 2.2568930763011132, "accelerator_pedal_position": 0.2927055409319691, "brake_pedal_position": 0.0, "acceleration": 0.21562931343119213, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.023951783723028152, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141179.5418699} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23362644452076645, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0359945017123848, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.246169103969799, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4244448040652949, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141179.5418699} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.12998080253601, "x": 41.43683525146994, "y": 0.19288129023154, "z": null, "yaw": 0.011013426114336904, "pitch": null, "roll": null}, "v": 2.2568930763011132, "accelerator_pedal_position": 0.2927055409319691, "brake_pedal_position": 0.0, "acceleration": 0.21562931343119213, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.023951783723028152, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141179.5618699} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23362644452076645, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0359945017123848, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.243118633561553, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.34296696399103005, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141179.5618699} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.12998080253601, "x": 41.43683525146994, "y": 0.19288129023154, "z": null, "yaw": 0.011013426114336904, "pitch": null, "roll": null}, "v": 2.2568930763011132, "accelerator_pedal_position": 0.2927055409319691, "brake_pedal_position": 0.0, "acceleration": 0.21562931343119213, "steering_wheel_angle": -0.5868680246642785, "front_wheel_angle": -0.02716189220105888, "heading_rate": -0.023951783723028152, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141179.5818698} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23362644452076645, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0359945017123848, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.240073948835537, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2613116374002497, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141179.5818698} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141179.6018698, "x": 45.68403298454367, "y": 5.195492808568848, "z": null, "yaw": 0.010178407907698594, "pitch": null, "roll": null}, "v": 2.237035035112037, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.361895009238789, "steering_wheel_angle": -0.17947882429295398, "front_wheel_angle": -0.00826189533988175, "heading_rate": -0.007219753854314111, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141179.6018698} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2437688959511315, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.068531504813877, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.237035035112037, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.17947882429295398, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141179.6018698} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.239980697631836, "x": 41.68403298454367, "y": 0.1954928085688481, "z": null, "yaw": 0.010178407907698594, "pitch": null, "roll": null}, "v": 2.237035035112037, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.361895009238789, "steering_wheel_angle": -0.17947882429295398, "front_wheel_angle": -0.00826189533988175, "heading_rate": -0.007219753854314111, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141179.6118698} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23879551216426273, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.068531504813877, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.23526908377687, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.09739434414603754, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141179.6118698} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.239980697631836, "x": 41.68403298454367, "y": 0.1954928085688481, "z": null, "yaw": 0.010178407907698594, "pitch": null, "roll": null}, "v": 2.237035035112037, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.361895009238789, "steering_wheel_angle": -0.17947882429295398, "front_wheel_angle": -0.00826189533988175, "heading_rate": -0.007219753854314111, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141179.6418698} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23879551216426273, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.068531504813877, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2328850974124634, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.015132056602425122, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141179.6418698} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.239980697631836, "x": 41.68403298454367, "y": 0.1954928085688481, "z": null, "yaw": 0.010178407907698594, "pitch": null, "roll": null}, "v": 2.237035035112037, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.361895009238789, "steering_wheel_angle": -0.17947882429295398, "front_wheel_angle": -0.00826189533988175, "heading_rate": -0.007219753854314111, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141179.6518698} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23879551216426273, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.068531504813877, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.229317573899065, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.10828669285466326, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141179.6518698} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.239980697631836, "x": 41.68403298454367, "y": 0.1954928085688481, "z": null, "yaw": 0.010178407907698594, "pitch": null, "roll": null}, "v": 2.237035035112037, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.361895009238789, "steering_wheel_angle": -0.17947882429295398, "front_wheel_angle": -0.00826189533988175, "heading_rate": -0.007219753854314111, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141179.6818697} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23879551216426273, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.068531504813877, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2281306489378525, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.14933937268847572, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141179.6818697} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.239980697631836, "x": 41.68403298454367, "y": 0.1954928085688481, "z": null, "yaw": 0.010178407907698594, "pitch": null, "roll": null}, "v": 2.237035035112037, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.361895009238789, "steering_wheel_angle": -0.17947882429295398, "front_wheel_angle": -0.00826189533988175, "heading_rate": -0.007219753854314111, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141179.7018697} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23879551216426273, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.068531504813877, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2257601652568533, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.23131137680857874, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141179.7018697} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141179.7118697, "x": 45.92949810509002, "y": 5.197978934245768, "z": null, "yaw": 0.01022982796699298, "pitch": null, "roll": null}, "v": 2.224576603853167, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36071624085676723, "steering_wheel_angle": 0.23131137680857874, "front_wheel_angle": 0.010655178581335627, "heading_rate": 0.009259436740401092, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141179.7118697} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24590934884111554, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1065618939155726, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2233941609548658, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.23131137680857874, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141179.7118697} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.34998059272766, "x": 41.92949810509002, "y": 0.19797893424576785, "z": null, "yaw": 0.01022982796699298, "pitch": null, "roll": null}, "v": 2.224576603853167, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36071624085676723, "steering_wheel_angle": 0.23131137680857874, "front_wheel_angle": 0.010655178581335627, "heading_rate": 0.009259436740401092, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141179.7418697} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.242431994904989, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1065618939155726, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2219214349810104, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.27227398056789676, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141179.7418697} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.34998059272766, "x": 41.92949810509002, "y": 0.19797893424576785, "z": null, "yaw": 0.01022982796699298, "pitch": null, "roll": null}, "v": 2.224576603853167, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36071624085676723, "steering_wheel_angle": 0.23131137680857874, "front_wheel_angle": 0.010655178581335627, "heading_rate": 0.009259436740401092, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141179.7618697} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.242431994904989, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1065618939155726, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.220017025517714, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.27227398056789676, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141179.7618697} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.34998059272766, "x": 41.92949810509002, "y": 0.19797893424576785, "z": null, "yaw": 0.01022982796699298, "pitch": null, "roll": null}, "v": 2.224576603853167, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36071624085676723, "steering_wheel_angle": 0.23131137680857874, "front_wheel_angle": 0.010655178581335627, "heading_rate": 0.009259436740401092, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141179.7818696} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.242431994904989, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1065618939155726, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.21811621025786, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.27227398056789676, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141179.7818696} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.34998059272766, "x": 41.92949810509002, "y": 0.19797893424576785, "z": null, "yaw": 0.01022982796699298, "pitch": null, "roll": null}, "v": 2.224576603853167, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36071624085676723, "steering_wheel_angle": 0.23131137680857874, "front_wheel_angle": 0.010655178581335627, "heading_rate": 0.009259436740401092, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141179.8018696} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.242431994904989, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1065618939155726, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.216218980973528, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.27227398056789676, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141179.8018696} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141179.8218696, "x": 46.17367849529681, "y": 5.200533632462366, "z": null, "yaw": 0.010754269698850917, "pitch": null, "roll": null}, "v": 2.2143253294604976, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35974863311992833, "steering_wheel_angle": 0.27227398056789676, "front_wheel_angle": 0.012548887879446283, "heading_rate": 0.010854991788605207, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141179.8218696} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21669660493556894, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.4230344794099006, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2143253294604976, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.27227398056789676, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141179.8218696} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.459980487823486, "x": 42.17367849529681, "y": 0.2005336324623661, "z": null, "yaw": 0.010754269698850917, "pitch": null, "roll": null}, "v": 2.2143253294604976, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35974863311992833, "steering_wheel_angle": 0.27227398056789676, "front_wheel_angle": 0.012548887879446283, "heading_rate": 0.010854991788605207, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141179.8418696} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22887783613087653, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.4230344794099006, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.209219839791622, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.35479507906412683, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141179.8418696} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.459980487823486, "x": 42.17367849529681, "y": 0.2005336324623661, "z": null, "yaw": 0.010754269698850917, "pitch": null, "roll": null}, "v": 2.2143253294604976, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35974863311992833, "steering_wheel_angle": 0.27227398056789676, "front_wheel_angle": 0.012548887879446283, "heading_rate": 0.010854991788605207, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141179.8618696} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22887783613087653, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.4230344794099006, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.200297600803701, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5603042869064014, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141179.8618696} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.459980487823486, "x": 42.17367849529681, "y": 0.2005336324623661, "z": null, "yaw": 0.010754269698850917, "pitch": null, "roll": null}, "v": 2.2143253294604976, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35974863311992833, "steering_wheel_angle": 0.27227398056789676, "front_wheel_angle": 0.012548887879446283, "heading_rate": 0.010854991788605207, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141179.8918695} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22887783613087653, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.4230344794099006, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1985181858082687, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.6012700933208619, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141179.8918695} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.459980487823486, "x": 42.17367849529681, "y": 0.2005336324623661, "z": null, "yaw": 0.010754269698850917, "pitch": null, "roll": null}, "v": 2.2143253294604976, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35974863311992833, "steering_wheel_angle": 0.27227398056789676, "front_wheel_angle": 0.012548887879446283, "heading_rate": 0.010854991788605207, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141179.9218695} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22887783613087653, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.4230344794099006, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.194964370931263, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.6012700933208619, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141179.9218695} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141179.9318695, "x": 46.4161120764978, "y": 5.20322717712699, "z": null, "yaw": 0.011681744061430518, "pitch": null, "roll": null}, "v": 2.1931899666450114, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35776032063017404, "steering_wheel_angle": 0.6012700933208619, "front_wheel_angle": 0.027833836414702193, "heading_rate": 0.023851820284026132, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141179.9418695} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.021006277887894165, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.031329876079509, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1914172281968893, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.6012700933208619, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141179.9418695} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.56998038291931, "x": 42.4161120764978, "y": 0.20322717712698957, "z": null, "yaw": 0.011681744061430518, "pitch": null, "roll": null}, "v": 2.1931899666450114, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35776032063017404, "steering_wheel_angle": 0.6012700933208619, "front_wheel_angle": 0.027833836414702193, "heading_rate": 0.023851820284026132, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141179.9618695} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.031329876079509, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.18090927388232, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.021006277887894165, "steering_wheel_angle": 0.6845116969607382, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141179.9618695} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.56998038291931, "x": 42.4161120764978, "y": 0.20322717712698957, "z": null, "yaw": 0.011681744061430518, "pitch": null, "roll": null}, "v": 2.1931899666450114, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35776032063017404, "steering_wheel_angle": 0.6012700933208619, "front_wheel_angle": 0.027833836414702193, "heading_rate": 0.023851820284026132, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141179.9818695} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.031329876079509, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.173780428794395, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.7675654432632903, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141179.9818695} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.56998038291931, "x": 42.4161120764978, "y": 0.20322717712698957, "z": null, "yaw": 0.011681744061430518, "pitch": null, "roll": null}, "v": 2.1931899666450114, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35776032063017404, "steering_wheel_angle": 0.6012700933208619, "front_wheel_angle": 0.027833836414702193, "heading_rate": 0.023851820284026132, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141180.0018694} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.031329876079509, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.166664910019833, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.8504313322285186, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141180.0018694} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.56998038291931, "x": 42.4161120764978, "y": 0.20322717712698957, "z": null, "yaw": 0.011681744061430518, "pitch": null, "roll": null}, "v": 2.1931899666450114, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35776032063017404, "steering_wheel_angle": 0.6012700933208619, "front_wheel_angle": 0.027833836414702193, "heading_rate": 0.023851820284026132, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141180.0218694} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.031329876079509, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1595626724042765, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.9331093638564226, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141180.0218694} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141180.0418694, "x": 46.65527772468831, "y": 5.2061705210020515, "z": null, "yaw": 0.01322023481888578, "pitch": null, "roll": null}, "v": 2.152473670991043, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3539551125926487, "steering_wheel_angle": 1.0155995381470029, "front_wheel_angle": 0.04727817300899309, "heading_rate": 0.0397816066656599, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141180.0418694} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22951251938036227, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.9912828062448373, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.152473670991043, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.0155995381470029, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141180.0418694} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.679980278015137, "x": 42.65527772468831, "y": 0.20617052100205147, "z": null, "yaw": 0.01322023481888578, "pitch": null, "roll": null}, "v": 2.152473670991043, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3539551125926487, "steering_wheel_angle": 1.0155995381470029, "front_wheel_angle": 0.04727817300899309, "heading_rate": 0.0397816066656599, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141180.0618694} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.9912828062448373, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1490852105803677, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.0978053898579845, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141180.0618694} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.679980278015137, "x": 42.65527772468831, "y": 0.20617052100205147, "z": null, "yaw": 0.01322023481888578, "pitch": null, "roll": null}, "v": 2.152473670991043, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3539551125926487, "steering_wheel_angle": 1.0155995381470029, "front_wheel_angle": 0.04727817300899309, "heading_rate": 0.0397816066656599, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141180.0818694} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.9912828062448373, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1420156988750727, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.179823824844759, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141180.0818694} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.679980278015137, "x": 42.65527772468831, "y": 0.20617052100205147, "z": null, "yaw": 0.01322023481888578, "pitch": null, "roll": null}, "v": 2.152473670991043, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3539551125926487, "steering_wheel_angle": 1.0155995381470029, "front_wheel_angle": 0.04727817300899309, "heading_rate": 0.0397816066656599, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141180.1018693} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.9912828062448373, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1349593127855413, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.179823824844759, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141180.1018693} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.679980278015137, "x": 42.65527772468831, "y": 0.20617052100205147, "z": null, "yaw": 0.01322023481888578, "pitch": null, "roll": null}, "v": 2.152473670991043, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3539551125926487, "steering_wheel_angle": 1.0155995381470029, "front_wheel_angle": 0.04727817300899309, "heading_rate": 0.0397816066656599, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141180.1218693} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.9912828062448373, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1279160080342754, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.179823824844759, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141180.1218693} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.679980278015137, "x": 42.65527772468831, "y": 0.20617052100205147, "z": null, "yaw": 0.01322023481888578, "pitch": null, "roll": null}, "v": 2.152473670991043, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3539551125926487, "steering_wheel_angle": 1.0155995381470029, "front_wheel_angle": 0.04727817300899309, "heading_rate": 0.0397816066656599, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141180.1418693} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.9912828062448373, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.12088574053662, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.179823824844759, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141180.1418693} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141180.1518693, "x": 46.890433701618065, "y": 5.209517247819447, "z": null, "yaw": 0.01551184595821379, "pitch": null, "roll": null}, "v": 2.1173754820339106, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3507015634208789, "steering_wheel_angle": 1.179823824844759, "front_wheel_angle": 0.05504678108352158, "heading_rate": 0.04557522402466654, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141180.1618693} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24233215338131592, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.9454659143674773, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.11301044776351, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.179823824844759, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141180.1618693} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.789980173110962, "x": 42.890433701618065, "y": 0.2095172478194467, "z": null, "yaw": 0.01551184595821379, "pitch": null, "roll": null}, "v": 2.1173754820339106, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3507015634208789, "steering_wheel_angle": 1.179823824844759, "front_wheel_angle": 0.05504678108352158, "heading_rate": 0.04557522402466654, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141180.1818693} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2290396007546142, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.9454659143674773, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1121532208107245, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.179823824844759, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141180.1818693} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.789980173110962, "x": 42.890433701618065, "y": 0.2095172478194467, "z": null, "yaw": 0.01551184595821379, "pitch": null, "roll": null}, "v": 2.1173754820339106, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3507015634208789, "steering_wheel_angle": 1.179823824844759, "front_wheel_angle": 0.05504678108352158, "heading_rate": 0.04557522402466654, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141180.2018692} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2290396007546142, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.9454659143674773, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.103732657954949, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.179823824844759, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141180.2018692} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.789980173110962, "x": 42.890433701618065, "y": 0.2095172478194467, "z": null, "yaw": 0.01551184595821379, "pitch": null, "roll": null}, "v": 2.1173754820339106, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3507015634208789, "steering_wheel_angle": 1.179823824844759, "front_wheel_angle": 0.05504678108352158, "heading_rate": 0.04557522402466654, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141180.2318692} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2290396007546142, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.9454659143674773, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.103732657954949, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.179823824844759, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141180.2318692} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.789980173110962, "x": 42.890433701618065, "y": 0.2095172478194467, "z": null, "yaw": 0.01551184595821379, "pitch": null, "roll": null}, "v": 2.1173754820339106, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3507015634208789, "steering_wheel_angle": 1.179823824844759, "front_wheel_angle": 0.05504678108352158, "heading_rate": 0.04557522402466654, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141180.2518692} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2290396007546142, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.9454659143674773, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1003752832473634, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.179823824844759, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141180.2518692} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141180.2618692, "x": 47.12234499356667, "y": 5.213364179529376, "z": null, "yaw": 0.01787952929319682, "pitch": null, "roll": null}, "v": 2.0986989130198554, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3489803169261, "steering_wheel_angle": 1.179823824844759, "front_wheel_angle": 0.05504678108352158, "heading_rate": 0.04517322219549164, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141180.2718692} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.013965630958031217, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.5468963524591643, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.097024084897758, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.179823824844759, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141180.2718692} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.899980068206787, "x": 43.12234499356667, "y": 0.2133641795293757, "z": null, "yaw": 0.01787952929319682, "pitch": null, "roll": null}, "v": 2.0986989130198554, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3489803169261, "steering_wheel_angle": 1.179823824844759, "front_wheel_angle": 0.05504678108352158, "heading_rate": 0.04517322219549164, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141180.2918692} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.5468963524591643, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.087817290067287, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.013965630958031217, "steering_wheel_angle": 1.2630180887415114, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141180.2918692} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.899980068206787, "x": 43.12234499356667, "y": 0.2133641795293757, "z": null, "yaw": 0.01787952929319682, "pitch": null, "roll": null}, "v": 2.0986989130198554, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3489803169261, "steering_wheel_angle": 1.179823824844759, "front_wheel_angle": 0.05504678108352158, "heading_rate": 0.04517322219549164, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141180.3118691} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.5468963524591643, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.080860868302487, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.3460186320457361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141180.3118691} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.899980068206787, "x": 43.12234499356667, "y": 0.2133641795293757, "z": null, "yaw": 0.01787952929319682, "pitch": null, "roll": null}, "v": 2.0986989130198554, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3489803169261, "steering_wheel_angle": 1.179823824844759, "front_wheel_angle": 0.05504678108352158, "heading_rate": 0.04517322219549164, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141180.3318691} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.5468963524591643, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.073917192095725, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.4288254547574333, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141180.3318691} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.899980068206787, "x": 43.12234499356667, "y": 0.2133641795293757, "z": null, "yaw": 0.01787952929319682, "pitch": null, "roll": null}, "v": 2.0986989130198554, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3489803169261, "steering_wheel_angle": 1.179823824844759, "front_wheel_angle": 0.05504678108352158, "heading_rate": 0.04517322219549164, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141180.351869} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.5468963524591643, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0669862188175427, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.5114385568766027, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141180.351869} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141180.371869, "x": 47.35123768463149, "y": 5.217721904767447, "z": null, "yaw": 0.020595614877894117, "pitch": null, "roll": null}, "v": 2.0600679060223084, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3454421930753468, "steering_wheel_angle": 1.5938579384032439, "front_wheel_angle": 0.07479222689095308, "heading_rate": 0.060298830702796895, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141180.371869} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.029845544675739723, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.1862394783001693, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.056613484091555, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.6349949839443667, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141180.371869} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.009979963302612, "x": 43.35123768463149, "y": 0.2177219047674468, "z": null, "yaw": 0.020595614877894117, "pitch": null, "roll": null}, "v": 2.0600679060223084, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3454421930753468, "steering_wheel_angle": 1.5938579384032439, "front_wheel_angle": 0.07479222689095308, "heading_rate": 0.060298830702796895, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141180.391869} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.014231763013319389, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.1862394783001693, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0507745678731553, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.029845544675739723, "steering_wheel_angle": 1.6769021140450386, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141180.391869} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.009979963302612, "x": 43.35123768463149, "y": 0.2177219047674468, "z": null, "yaw": 0.020595614877894117, "pitch": null, "roll": null}, "v": 2.0600679060223084, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3454421930753468, "steering_wheel_angle": 1.5938579384032439, "front_wheel_angle": 0.07479222689095308, "heading_rate": 0.060298830702796895, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141180.411869} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.014231763013319389, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.1862394783001693, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0370335835072884, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.014231763013319389, "steering_wheel_angle": 1.8023212238840993, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141180.411869} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.009979963302612, "x": 43.35123768463149, "y": 0.2177219047674468, "z": null, "yaw": 0.020595614877894117, "pitch": null, "roll": null}, "v": 2.0600679060223084, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3454421930753468, "steering_wheel_angle": 1.5938579384032439, "front_wheel_angle": 0.07479222689095308, "heading_rate": 0.060298830702796895, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141180.431869} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.014231763013319389, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.1862394783001693, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0324615750924355, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.014231763013319389, "steering_wheel_angle": 1.8440268336761347, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141180.431869} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.009979963302612, "x": 43.35123768463149, "y": 0.2177219047674468, "z": null, "yaw": 0.020595614877894117, "pitch": null, "roll": null}, "v": 2.0600679060223084, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3454421930753468, "steering_wheel_angle": 1.5938579384032439, "front_wheel_angle": 0.07479222689095308, "heading_rate": 0.060298830702796895, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141180.451869} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.014231763013319389, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.1862394783001693, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.023329990069479, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.014231763013319389, "steering_wheel_angle": 1.927286913028729, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141180.451869} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.009979963302612, "x": 43.35123768463149, "y": 0.2177219047674468, "z": null, "yaw": 0.020595614877894117, "pitch": null, "roll": null}, "v": 2.0600679060223084, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3454421930753468, "steering_wheel_angle": 1.5938579384032439, "front_wheel_angle": 0.07479222689095308, "heading_rate": 0.060298830702796895, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141180.471869} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.014231763013319389, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.1862394783001693, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.014214927976811, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.014231763013319389, "steering_wheel_angle": 2.0103454720726863, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141180.471869} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141180.481869, "x": 47.575272095727684, "y": 5.222689518529693, "z": null, "yaw": 0.024249396721983903, "pitch": null, "roll": null}, "v": 2.0096635732941484, "accelerator_pedal_position": 0, "brake_pedal_position": 0.014231763013319389, "acceleration": -0.4547247595495166, "steering_wheel_angle": 2.051799181478927, "front_wheel_angle": 0.0969057973058061, "heading_rate": 0.07631248379392018, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141180.491869} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22190612207962426, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.1045789843427403, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0005731773467796, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.014231763013319389, "steering_wheel_angle": 2.1345554600599304, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141180.491869} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.119979858398438, "x": 43.575272095727684, "y": 0.22268951852969288, "z": null, "yaw": 0.024249396721983903, "pitch": null, "roll": null}, "v": 2.0096635732941484, "accelerator_pedal_position": 0, "brake_pedal_position": 0.014231763013319389, "acceleration": -0.4547247595495166, "steering_wheel_angle": 2.051799181478927, "front_wheel_angle": 0.0969057973058061, "heading_rate": 0.07631248379392018, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141180.511869} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.1045789843427403, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9965122388869552, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.216899018782647, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141180.511869} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.119979858398438, "x": 43.575272095727684, "y": 0.22268951852969288, "z": null, "yaw": 0.024249396721983903, "pitch": null, "roll": null}, "v": 2.0096635732941484, "accelerator_pedal_position": 0, "brake_pedal_position": 0.014231763013319389, "acceleration": -0.4547247595495166, "steering_wheel_angle": 2.051799181478927, "front_wheel_angle": 0.0969057973058061, "heading_rate": 0.07631248379392018, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141180.531869} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.1045789843427403, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9931153766555092, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.257995614665283, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141180.531869} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.119979858398438, "x": 43.575272095727684, "y": 0.22268951852969288, "z": null, "yaw": 0.024249396721983903, "pitch": null, "roll": null}, "v": 2.0096635732941484, "accelerator_pedal_position": 0, "brake_pedal_position": 0.014231763013319389, "acceleration": -0.4547247595495166, "steering_wheel_angle": 2.051799181478927, "front_wheel_angle": 0.0969057973058061, "heading_rate": 0.07631248379392018, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141180.551869} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.1045789843427403, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.98633080810083, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.2990420882287728, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141180.551869} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.119979858398438, "x": 43.575272095727684, "y": 0.22268951852969288, "z": null, "yaw": 0.024249396721983903, "pitch": null, "roll": null}, "v": 2.0096635732941484, "accelerator_pedal_position": 0, "brake_pedal_position": 0.014231763013319389, "acceleration": -0.4547247595495166, "steering_wheel_angle": 2.051799181478927, "front_wheel_angle": 0.0969057973058061, "heading_rate": 0.07631248379392018, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141180.571869} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.1045789843427403, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9795584138125264, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.2990420882287728, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141180.571869} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141180.5918689, "x": 47.794378911368064, "y": 5.228443104931129, "z": null, "yaw": 0.0287836022497194, "pitch": null, "roll": null}, "v": 1.9727981536071102, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.33755923322911174, "steering_wheel_angle": 2.2990420882287728, "front_wheel_angle": 0.10896857904698651, "heading_rate": 0.08430779157853095, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141180.5918689} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23452459721575467, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.042809318169006, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9727981536071102, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.2990420882287728, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141180.5918689} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.229979753494263, "x": 43.794378911368064, "y": 0.22844310493112907, "z": null, "yaw": 0.0287836022497194, "pitch": null, "roll": null}, "v": 1.9727981536071102, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.33755923322911174, "steering_wheel_angle": 2.2990420882287728, "front_wheel_angle": 0.10896857904698651, "heading_rate": 0.08430779157853095, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141180.6118689} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2189994917695691, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.042809318169006, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.970363632845389, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.2990420882287728, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141180.6118689} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.229979753494263, "x": 43.794378911368064, "y": 0.22844310493112907, "z": null, "yaw": 0.0287836022497194, "pitch": null, "roll": null}, "v": 1.9727981536071102, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.33755923322911174, "steering_wheel_angle": 2.2990420882287728, "front_wheel_angle": 0.10896857904698651, "heading_rate": 0.08430779157853095, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141180.6318688} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2189994917695691, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.042809318169006, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9659936930322495, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.2990420882287728, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141180.6318688} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.229979753494263, "x": 43.794378911368064, "y": 0.22844310493112907, "z": null, "yaw": 0.0287836022497194, "pitch": null, "roll": null}, "v": 1.9727981536071102, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.33755923322911174, "steering_wheel_angle": 2.2990420882287728, "front_wheel_angle": 0.10896857904698651, "heading_rate": 0.08430779157853095, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141180.6518688} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2189994917695691, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.042809318169006, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.961631558090996, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.2990420882287728, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141180.6518688} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.229979753494263, "x": 43.794378911368064, "y": 0.22844310493112907, "z": null, "yaw": 0.0287836022497194, "pitch": null, "roll": null}, "v": 1.9727981536071102, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.33755923322911174, "steering_wheel_angle": 2.2990420882287728, "front_wheel_angle": 0.10896857904698651, "heading_rate": 0.08430779157853095, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141180.6718688} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2189994917695691, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.042809318169006, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.957277206473947, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.2990420882287728, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141180.6718688} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.229979753494263, "x": 43.794378911368064, "y": 0.22844310493112907, "z": null, "yaw": 0.0287836022497194, "pitch": null, "roll": null}, "v": 1.9727981536071102, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.33755923322911174, "steering_wheel_angle": 2.2990420882287728, "front_wheel_angle": 0.10896857904698651, "heading_rate": 0.08430779157853095, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141180.6918688} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2189994917695691, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.042809318169006, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9507602258404748, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.2990420882287728, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141180.6918688} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141180.7018688, "x": 48.010266710183274, "y": 5.235119593692338, "z": null, "yaw": 0.03348446688540545, "pitch": null, "roll": null}, "v": 1.9507602258404748, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.33559266587923553, "steering_wheel_angle": 2.2990420882287728, "front_wheel_angle": 0.10896857904698651, "heading_rate": 0.08336599780324022, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141180.7118688} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.426454999350982, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9452377705459674, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.3404579153876535, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141180.7118688} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.339979648590088, "x": 44.010266710183274, "y": 0.23511959369233804, "z": null, "yaw": 0.03348446688540545, "pitch": null, "roll": null}, "v": 1.9507602258404748, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.33559266587923553, "steering_wheel_angle": 2.2990420882287728, "front_wheel_angle": 0.10896857904698651, "heading_rate": 0.08336599780324022, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141180.7318687} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.426454999350982, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9418867566622986, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.381822588633351, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141180.7318687} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.339979648590088, "x": 44.010266710183274, "y": 0.23511959369233804, "z": null, "yaw": 0.03348446688540545, "pitch": null, "roll": null}, "v": 1.9507602258404748, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.33559266587923553, "steering_wheel_angle": 2.2990420882287728, "front_wheel_angle": 0.10896857904698651, "heading_rate": 0.08336599780324022, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141180.7518687} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.426454999350982, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9318515639900997, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.5056096848913465, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141180.7518687} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.339979648590088, "x": 44.010266710183274, "y": 0.23511959369233804, "z": null, "yaw": 0.03348446688540545, "pitch": null, "roll": null}, "v": 1.9507602258404748, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.33559266587923553, "steering_wheel_angle": 2.2990420882287728, "front_wheel_angle": 0.10896857904698651, "heading_rate": 0.08336599780324022, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141180.7718687} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.426454999350982, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9285124331615755, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.546769742484312, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141180.7718687} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.339979648590088, "x": 44.010266710183274, "y": 0.23511959369233804, "z": null, "yaw": 0.03348446688540545, "pitch": null, "roll": null}, "v": 1.9507602258404748, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.33559266587923553, "steering_wheel_angle": 2.2990420882287728, "front_wheel_angle": 0.10896857904698651, "heading_rate": 0.08336599780324022, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141180.7918687} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.426454999350982, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.918512772841295, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.628936395930694, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141180.7918687} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141180.8118687, "x": 48.222991900472415, "y": 5.242717339591516, "z": null, "yaw": 0.03853879178857235, "pitch": null, "roll": null}, "v": 1.9151854473289187, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3324386253430507, "steering_wheel_angle": 2.628936395930694, "front_wheel_angle": 0.125203062052967, "heading_rate": 0.09415935194282699, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141180.8118687} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2272897573706671, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.5281502818737787, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9151854473289187, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.628936395930694, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141180.8118687} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.449979543685913, "x": 44.222991900472415, "y": 0.24271733959151565, "z": null, "yaw": 0.03853879178857235, "pitch": null, "roll": null}, "v": 1.9151854473289187, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3324386253430507, "steering_wheel_angle": 2.628936395930694, "front_wheel_angle": 0.125203062052967, "heading_rate": 0.09415935194282699, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141180.8318686} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21913327386445736, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.5281502818737787, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.911949323670964, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.71116588999504, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141180.8318686} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.449979543685913, "x": 44.222991900472415, "y": 0.24271733959151565, "z": null, "yaw": 0.03853879178857235, "pitch": null, "roll": null}, "v": 1.9151854473289187, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3324386253430507, "steering_wheel_angle": 2.628936395930694, "front_wheel_angle": 0.125203062052967, "heading_rate": 0.09415935194282699, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141180.8518686} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21913327386445736, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.5281502818737787, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9076997987814275, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.7522034039382928, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141180.8518686} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.449979543685913, "x": 44.222991900472415, "y": 0.24271733959151565, "z": null, "yaw": 0.03853879178857235, "pitch": null, "roll": null}, "v": 1.9151854473289187, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3324386253430507, "steering_wheel_angle": 2.628936395930694, "front_wheel_angle": 0.125203062052967, "heading_rate": 0.09415935194282699, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141180.8718686} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21913327386445736, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.5281502818737787, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9034577646465807, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.7522034039382928, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141180.8718686} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.449979543685913, "x": 44.222991900472415, "y": 0.24271733959151565, "z": null, "yaw": 0.03853879178857235, "pitch": null, "roll": null}, "v": 1.9151854473289187, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3324386253430507, "steering_wheel_angle": 2.628936395930694, "front_wheel_angle": 0.125203062052967, "heading_rate": 0.09415935194282699, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141180.8918686} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21913327386445736, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.5281502818737787, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8992232008674894, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.7522034039382928, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141180.8918686} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.449979543685913, "x": 44.222991900472415, "y": 0.24271733959151565, "z": null, "yaw": 0.03853879178857235, "pitch": null, "roll": null}, "v": 1.9151854473289187, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3324386253430507, "steering_wheel_angle": 2.628936395930694, "front_wheel_angle": 0.125203062052967, "heading_rate": 0.09415935194282699, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141180.9118686} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21913327386445736, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.5281502818737787, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.894996087119162, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.7522034039382928, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141180.9118686} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141180.9218686, "x": 48.43241414645743, "y": 5.251323486109115, "z": null, "yaw": 0.04416519093785745, "pitch": null, "roll": null}, "v": 1.8928853176751113, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.33047441414245565, "steering_wheel_angle": 2.7522034039382928, "front_wheel_angle": 0.13131088405946167, "heading_rate": 0.09765427689802139, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141180.9318686} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.03511846889918068, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.476214680053516, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8907764031502152, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.7522034039382928, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141180.9318686} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.55997943878174, "x": 44.43241414645743, "y": 0.2513234861091149, "z": null, "yaw": 0.04416519093785745, "pitch": null, "roll": null}, "v": 1.8928853176751113, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.33047441414245565, "steering_wheel_angle": 2.7522034039382928, "front_wheel_angle": 0.13131088405946167, "heading_rate": 0.09765427689802139, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141180.9518685} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.476214680053516, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.878557028515086, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.03511846889918068, "steering_wheel_angle": 2.8367404173802258, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141180.9518685} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.55997943878174, "x": 44.43241414645743, "y": 0.2513234861091149, "z": null, "yaw": 0.04416519093785745, "pitch": null, "roll": null}, "v": 1.8928853176751113, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.33047441414245565, "steering_wheel_angle": 2.7522034039382928, "front_wheel_angle": 0.13131088405946167, "heading_rate": 0.09765427689802139, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141180.9718685} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.476214680053516, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8719755580970694, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.921058092248896, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141180.9718685} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.55997943878174, "x": 44.43241414645743, "y": 0.2513234861091149, "z": null, "yaw": 0.04416519093785745, "pitch": null, "roll": null}, "v": 1.8928853176751113, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.33047441414245565, "steering_wheel_angle": 2.7522034039382928, "front_wheel_angle": 0.13131088405946167, "heading_rate": 0.09765427689802139, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141180.9918685} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.476214680053516, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8654055965878802, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.005156428544304, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141180.9918685} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.55997943878174, "x": 44.43241414645743, "y": 0.2513234861091149, "z": null, "yaw": 0.04416519093785745, "pitch": null, "roll": null}, "v": 1.8928853176751113, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.33047441414245565, "steering_wheel_angle": 2.7522034039382928, "front_wheel_angle": 0.13131088405946167, "heading_rate": 0.09765427689802139, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141181.0118685} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.476214680053516, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.858847106603852, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.0890354262664497, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141181.0118685} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141181.0318685, "x": 48.638235614820324, "y": 5.260968115825434, "z": null, "yaw": 0.05021656377672019, "pitch": null, "roll": null}, "v": 1.8523000509170289, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.32692515733212374, "steering_wheel_angle": 3.172695085415333, "front_wheel_angle": 0.15232139221510668, "heading_rate": 0.11107322521830372, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141181.0318685} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22134749763279732, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.410604949625146, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8523000509170289, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.172695085415333, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141181.0318685} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.669979333877563, "x": 44.638235614820324, "y": 0.2609681158254338, "z": null, "yaw": 0.05021656377672019, "pitch": null, "roll": null}, "v": 1.8523000509170289, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.32692515733212374, "steering_wheel_angle": 3.172695085415333, "front_wheel_angle": 0.15232139221510668, "heading_rate": 0.11107322521830372, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141181.0518684} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.410604949625146, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8451657831709016, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.2974935658413114, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141181.0518684} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.669979333877563, "x": 44.638235614820324, "y": 0.2609681158254338, "z": null, "yaw": 0.05021656377672019, "pitch": null, "roll": null}, "v": 1.8523000509170289, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.32692515733212374, "steering_wheel_angle": 3.172695085415333, "front_wheel_angle": 0.15232139221510668, "heading_rate": 0.11107322521830372, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141181.0718684} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.410604949625146, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8419027366025778, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.338983881016809, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141181.0718684} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.669979333877563, "x": 44.638235614820324, "y": 0.2609681158254338, "z": null, "yaw": 0.05021656377672019, "pitch": null, "roll": null}, "v": 1.8523000509170289, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.32692515733212374, "steering_wheel_angle": 3.172695085415333, "front_wheel_angle": 0.15232139221510668, "heading_rate": 0.11107322521830372, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141181.0918684} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.410604949625146, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8353851427694827, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.4218007439180638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141181.0918684} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.669979333877563, "x": 44.638235614820324, "y": 0.2609681158254338, "z": null, "yaw": 0.05021656377672019, "pitch": null, "roll": null}, "v": 1.8523000509170289, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.32692515733212374, "steering_wheel_angle": 3.172695085415333, "front_wheel_angle": 0.15232139221510668, "heading_rate": 0.11107322521830372, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141181.1118684} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.410604949625146, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8256299315836761, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.5456166196455907, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141181.1118684} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.669979333877563, "x": 44.638235614820324, "y": 0.2609681158254338, "z": null, "yaw": 0.05021656377672019, "pitch": null, "roll": null}, "v": 1.8523000509170289, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.32692515733212374, "steering_wheel_angle": 3.172695085415333, "front_wheel_angle": 0.15232139221510668, "heading_rate": 0.11107322521830372, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141181.1318684} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.410604949625146, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8191405239608447, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.627887591047705, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141181.1318684} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141181.1418684, "x": 48.84015987893439, "y": 5.27174696352888, "z": null, "yaw": 0.05727479497807723, "pitch": null, "roll": null}, "v": 1.8191405239608447, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3240497486572076, "steering_wheel_angle": 3.627887591047705, "front_wheel_angle": 0.17538115820075842, "heading_rate": 0.12591985348501672, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141181.1518683} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23603559414424236, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.346264147032455, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8149145518044356, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.6689411930238913, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141181.1518683} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.77997922897339, "x": 44.84015987893439, "y": 0.27174696352888006, "z": null, "yaw": 0.05727479497807723, "pitch": null, "roll": null}, "v": 1.8191405239608447, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3240497486572076, "steering_wheel_angle": 3.627887591047705, "front_wheel_angle": 0.17538115820075842, "heading_rate": 0.12591985348501672, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141181.1718683} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22054552055321655, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.346264147032455, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8139299276795133, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.6689411930238913, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141181.1718683} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.77997922897339, "x": 44.84015987893439, "y": 0.27174696352888006, "z": null, "yaw": 0.05727479497807723, "pitch": null, "roll": null}, "v": 1.8191405239608447, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3240497486572076, "steering_wheel_angle": 3.627887591047705, "front_wheel_angle": 0.17538115820075842, "heading_rate": 0.12591985348501672, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141181.1918683} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22054552055321655, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.346264147032455, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8100278031589956, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.6689411930238913, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141181.1918683} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.77997922897339, "x": 44.84015987893439, "y": 0.27174696352888006, "z": null, "yaw": 0.05727479497807723, "pitch": null, "roll": null}, "v": 1.8191405239608447, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3240497486572076, "steering_wheel_angle": 3.627887591047705, "front_wheel_angle": 0.17538115820075842, "heading_rate": 0.12591985348501672, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141181.2118683} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22054552055321655, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.346264147032455, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8041872219730706, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.6689411930238913, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141181.2118683} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.77997922897339, "x": 44.84015987893439, "y": 0.27174696352888006, "z": null, "yaw": 0.05727479497807723, "pitch": null, "roll": null}, "v": 1.8191405239608447, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3240497486572076, "steering_wheel_angle": 3.627887591047705, "front_wheel_angle": 0.17538115820075842, "heading_rate": 0.12591985348501672, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141181.2318683} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22054552055321655, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.346264147032455, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.802243714243467, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.6689411930238913, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141181.2318683} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141181.2518682, "x": 49.03886036058447, "y": 5.283835537507509, "z": null, "yaw": 0.06497342248524306, "pitch": null, "roll": null}, "v": 1.7983617145897361, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.32225913429450814, "steering_wheel_angle": 3.6689411930238913, "front_wheel_angle": 0.17747750056309045, "heading_rate": 0.12600101400427316, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141181.2518682} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.07792746412016806, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.030112093083736, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7983617145897361, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.6689411930238913, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141181.2518682} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.889979124069214, "x": 45.03886036058447, "y": 0.28383553750750856, "z": null, "yaw": 0.06497342248524306, "pitch": null, "roll": null}, "v": 1.7983617145897361, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.32225913429450814, "steering_wheel_angle": 3.6689411930238913, "front_wheel_angle": 0.17747750056309045, "heading_rate": 0.12600101400427316, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141181.2718682} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.033282286933651026, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.030112093083736, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.779456258441037, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.07792746412016806, "steering_wheel_angle": 3.7558189523243986, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141181.2718682} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.889979124069214, "x": 45.03886036058447, "y": 0.28383553750750856, "z": null, "yaw": 0.06497342248524306, "pitch": null, "roll": null}, "v": 1.7983617145897361, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.32225913429450814, "steering_wheel_angle": 3.6689411930238913, "front_wheel_angle": 0.17747750056309045, "heading_rate": 0.12600101400427316, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141181.2918682} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.033282286933651026, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.030112093083736, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7677233631030207, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.033282286933651026, "steering_wheel_angle": 3.842451226609868, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141181.2918682} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.889979124069214, "x": 45.03886036058447, "y": 0.28383553750750856, "z": null, "yaw": 0.06497342248524306, "pitch": null, "roll": null}, "v": 1.7983617145897361, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.32225913429450814, "steering_wheel_angle": 3.6689411930238913, "front_wheel_angle": 0.17747750056309045, "heading_rate": 0.12600101400427316, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141181.3118682} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.033282286933651026, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.030112093083736, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7560105020779635, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.033282286933651026, "steering_wheel_angle": 3.9288380158802987, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141181.3118682} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.889979124069214, "x": 45.03886036058447, "y": 0.28383553750750856, "z": null, "yaw": 0.06497342248524306, "pitch": null, "roll": null}, "v": 1.7983617145897361, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.32225913429450814, "steering_wheel_angle": 3.6689411930238913, "front_wheel_angle": 0.17747750056309045, "heading_rate": 0.12600101400427316, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141181.3318682} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.033282286933651026, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.030112093083736, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7443175863034932, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.033282286933651026, "steering_wheel_angle": 4.0149793201356925, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141181.3318682} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.889979124069214, "x": 45.03886036058447, "y": 0.28383553750750856, "z": null, "yaw": 0.06497342248524306, "pitch": null, "roll": null}, "v": 1.7983617145897361, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.32225913429450814, "steering_wheel_angle": 3.6689411930238913, "front_wheel_angle": 0.17747750056309045, "heading_rate": 0.12600101400427316, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141181.3518682} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.033282286933651026, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.030112093083736, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7326445271493114, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.033282286933651026, "steering_wheel_angle": 4.100875139376048, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141181.3518682} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141181.3618681, "x": 49.23231903860168, "y": 5.29712471376856, "z": null, "yaw": 0.07317483238326329, "pitch": null, "roll": null}, "v": 1.7268154162252987, "accelerator_pedal_position": 0, "brake_pedal_position": 0.033282286933651026, "acceleration": -0.5824179810976067, "steering_wheel_angle": 4.143730992115586, "front_wheel_angle": 0.2019278025693984, "heading_rate": 0.13808981413333282, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141181.3718681} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.8939638204129485, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7151719767578417, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.033282286933651026, "steering_wheel_angle": 4.229258583833386, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141181.3718681} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.99997901916504, "x": 45.23231903860168, "y": 0.29712471376856, "z": null, "yaw": 0.07317483238326329, "pitch": null, "roll": null}, "v": 1.7268154162252987, "accelerator_pedal_position": 0, "brake_pedal_position": 0.033282286933651026, "acceleration": -0.5824179810976067, "steering_wheel_angle": 4.143730992115586, "front_wheel_angle": 0.2019278025693984, "heading_rate": 0.13808981413333282, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141181.391868} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.8939638204129485, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7120202092784773, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.271709369185096, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141181.391868} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.99997901916504, "x": 45.23231903860168, "y": 0.29712471376856, "z": null, "yaw": 0.07317483238326329, "pitch": null, "roll": null}, "v": 1.7268154162252987, "accelerator_pedal_position": 0, "brake_pedal_position": 0.033282286933651026, "acceleration": -0.5824179810976067, "steering_wheel_angle": 4.143730992115586, "front_wheel_angle": 0.2019278025693984, "heading_rate": 0.13808981413333282, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141181.411868} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.8939638204129485, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7025808262890165, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.398697303913963, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141181.411868} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.99997901916504, "x": 45.23231903860168, "y": 0.29712471376856, "z": null, "yaw": 0.07317483238326329, "pitch": null, "roll": null}, "v": 1.7268154162252987, "accelerator_pedal_position": 0, "brake_pedal_position": 0.033282286933651026, "acceleration": -0.5824179810976067, "steering_wheel_angle": 4.143730992115586, "front_wheel_angle": 0.2019278025693984, "heading_rate": 0.13808981413333282, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141181.431868} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.8939638204129485, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6963011283849767, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.483052242627987, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141181.431868} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.99997901916504, "x": 45.23231903860168, "y": 0.29712471376856, "z": null, "yaw": 0.07317483238326329, "pitch": null, "roll": null}, "v": 1.7268154162252987, "accelerator_pedal_position": 0, "brake_pedal_position": 0.033282286933651026, "acceleration": -0.5824179810976067, "steering_wheel_angle": 4.143730992115586, "front_wheel_angle": 0.2019278025693984, "heading_rate": 0.13808981413333282, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141181.451868} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.8939638204129485, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6900319706009477, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.567164233791165, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141181.451868} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141181.471868, "x": 49.41946909593622, "y": 5.311618742393967, "z": null, "yaw": 0.0824687967774469, "pitch": null, "roll": null}, "v": 1.6869013338094818, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3128014277905562, "steering_wheel_angle": 4.609129124041188, "front_wheel_angle": 0.22627444590330156, "heading_rate": 0.15170051230314086, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141181.471868} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.218513972078944, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6837733195315763, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.651033277403499, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141181.471868} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.109978914260864, "x": 45.41946909593622, "y": 0.3116187423939669, "z": null, "yaw": 0.0824687967774469, "pitch": null, "roll": null}, "v": 1.6869013338094818, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3128014277905562, "steering_wheel_angle": 4.609129124041188, "front_wheel_angle": 0.22627444590330156, "heading_rate": 0.15170051230314086, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141181.491868} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.218513972078944, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6775251419065333, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.735707551683857, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141181.491868} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.109978914260864, "x": 45.41946909593622, "y": 0.3116187423939669, "z": null, "yaw": 0.0824687967774469, "pitch": null, "roll": null}, "v": 1.6869013338094818, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3128014277905562, "steering_wheel_angle": 4.609129124041188, "front_wheel_angle": 0.22627444590330156, "heading_rate": 0.15170051230314086, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141181.511868} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.218513972078944, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6712874045898212, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.820132740902091, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141181.511868} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.109978914260864, "x": 45.41946909593622, "y": 0.3116187423939669, "z": null, "yaw": 0.0824687967774469, "pitch": null, "roll": null}, "v": 1.6869013338094818, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3128014277905562, "steering_wheel_angle": 4.609129124041188, "front_wheel_angle": 0.22627444590330156, "heading_rate": 0.15170051230314086, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141181.531868} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.218513972078944, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6681724407286522, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.862251928612912, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141181.531868} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.109978914260864, "x": 45.41946909593622, "y": 0.3116187423939669, "z": null, "yaw": 0.0824687967774469, "pitch": null, "roll": null}, "v": 1.6869013338094818, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3128014277905562, "steering_wheel_angle": 4.609129124041188, "front_wheel_angle": 0.22627444590330156, "heading_rate": 0.15170051230314086, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141181.551868} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.218513972078944, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.661950302036602, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.94630349023796, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141181.551868} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.109978914260864, "x": 45.41946909593622, "y": 0.3116187423939669, "z": null, "yaw": 0.0824687967774469, "pitch": null, "roll": null}, "v": 1.6869013338094818, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3128014277905562, "steering_wheel_angle": 4.609129124041188, "front_wheel_angle": 0.22627444590330156, "heading_rate": 0.15170051230314086, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141181.571868} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.218513972078944, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6557385213960902, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.030105966800885, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141181.571868} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141181.581868, "x": 49.60261464575829, "y": 5.327608546802779, "z": null, "yaw": 0.0928681943059611, "pitch": null, "roll": null}, "v": 1.6526365051302687, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3099438994374053, "steering_wheel_angle": 5.071913798184052, "front_wheel_angle": 0.25087562099303556, "heading_rate": 0.1654410772359855, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141181.591868} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.452702871598244, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.646440200349571, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.155342647153791, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141181.591868} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.21997880935669, "x": 45.60261464575829, "y": 0.32760854680277873, "z": null, "yaw": 0.0928681943059611, "pitch": null, "roll": null}, "v": 1.6526365051302687, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3099438994374053, "steering_wheel_angle": 5.071913798184052, "front_wheel_angle": 0.25087562099303556, "heading_rate": 0.1654410772359855, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141181.611868} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.452702871598244, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6402541721882795, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.239289919186872, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141181.611868} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.21997880935669, "x": 45.60261464575829, "y": 0.32760854680277873, "z": null, "yaw": 0.0928681943059611, "pitch": null, "roll": null}, "v": 1.6526365051302687, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3099438994374053, "steering_wheel_angle": 5.071913798184052, "front_wheel_angle": 0.25087562099303556, "heading_rate": 0.1654410772359855, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141181.631868} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.452702871598244, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6371650017272472, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.2811684139698425, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141181.631868} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.21997880935669, "x": 45.60261464575829, "y": 0.32760854680277873, "z": null, "yaw": 0.0928681943059611, "pitch": null, "roll": null}, "v": 1.6526365051302687, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3099438994374053, "steering_wheel_angle": 5.071913798184052, "front_wheel_angle": 0.25087562099303556, "heading_rate": 0.1654410772359855, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141181.6518679} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.452702871598244, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.630994327890033, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.364735121068647, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141181.6518679} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.21997880935669, "x": 45.60261464575829, "y": 0.32760854680277873, "z": null, "yaw": 0.0928681943059611, "pitch": null, "roll": null}, "v": 1.6526365051302687, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3099438994374053, "steering_wheel_angle": 5.071913798184052, "front_wheel_angle": 0.25087562099303556, "heading_rate": 0.1654410772359855, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141181.6718678} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.452702871598244, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.624833850054284, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.448048118211267, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141181.6718678} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141181.6918678, "x": 49.781839220889076, "y": 5.345228052405993, "z": null, "yaw": 0.10439787566598643, "pitch": null, "roll": null}, "v": 1.6186835361984833, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30713554071352445, "steering_wheel_angle": 5.531107405397704, "front_wheel_angle": 0.2756907689844812, "heading_rate": 0.17887371205399874, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141181.6918678} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22508330179688046, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.363558054635461, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6186835361984833, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.531107405397704, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141181.6918678} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.329978704452515, "x": 45.781839220889076, "y": 0.34522805240599297, "z": null, "yaw": 0.10439787566598643, "pitch": null, "roll": null}, "v": 1.6186835361984833, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30713554071352445, "steering_wheel_angle": 5.531107405397704, "front_wheel_angle": 0.2756907689844812, "heading_rate": 0.17887371205399874, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141181.7118678} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.363558054635461, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6126085963845882, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.654785337814317, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141181.7118678} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.329978704452515, "x": 45.781839220889076, "y": 0.34522805240599297, "z": null, "yaw": 0.10439787566598643, "pitch": null, "roll": null}, "v": 1.6186835361984833, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30713554071352445, "steering_wheel_angle": 5.531107405397704, "front_wheel_angle": 0.2756907689844812, "heading_rate": 0.17887371205399874, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141181.7318678} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.363558054635461, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6095422414378826, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.654785337814317, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141181.7318678} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.329978704452515, "x": 45.781839220889076, "y": 0.34522805240599297, "z": null, "yaw": 0.10439787566598643, "pitch": null, "roll": null}, "v": 1.6186835361984833, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30713554071352445, "steering_wheel_angle": 5.531107405397704, "front_wheel_angle": 0.2756907689844812, "heading_rate": 0.17887371205399874, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141181.7518678} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.363558054635461, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6003582880207425, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.654785337814317, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141181.7518678} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.329978704452515, "x": 45.781839220889076, "y": 0.34522805240599297, "z": null, "yaw": 0.10439787566598643, "pitch": null, "roll": null}, "v": 1.6186835361984833, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30713554071352445, "steering_wheel_angle": 5.531107405397704, "front_wheel_angle": 0.2756907689844812, "heading_rate": 0.17887371205399874, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141181.7718678} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.363558054635461, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5973019942117286, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.654785337814317, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141181.7718678} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.329978704452515, "x": 45.781839220889076, "y": 0.34522805240599297, "z": null, "yaw": 0.10439787566598643, "pitch": null, "roll": null}, "v": 1.6186835361984833, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30713554071352445, "steering_wheel_angle": 5.531107405397704, "front_wheel_angle": 0.2756907689844812, "heading_rate": 0.17887371205399874, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141181.7918677} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.363558054635461, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5911969190114421, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.654785337814317, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141181.7918677} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141181.8018677, "x": 49.95743732169153, "y": 5.364621651909588, "z": null, "yaw": 0.11681046439197855, "pitch": null, "roll": null}, "v": 1.5881481297884292, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30462955131092634, "steering_wheel_angle": 5.654785337814317, "front_wheel_angle": 0.2824459922173832, "heading_rate": 0.1800342339532375, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141181.8118677} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24208843812044004, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.253392756056128, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.58510183427532, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.654785337814317, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141181.8118677} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.43997859954834, "x": 45.95743732169153, "y": 0.3646216519095882, "z": null, "yaw": 0.11681046439197855, "pitch": null, "roll": null}, "v": 1.5881481297884292, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30462955131092634, "steering_wheel_angle": 5.654785337814317, "front_wheel_angle": 0.2824459922173832, "heading_rate": 0.1800342339532375, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141181.8318677} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22587060363870284, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.253392756056128, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5842756152808175, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.654785337814317, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141181.8318677} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.43997859954834, "x": 45.95743732169153, "y": 0.3646216519095882, "z": null, "yaw": 0.11681046439197855, "pitch": null, "roll": null}, "v": 1.5881481297884292, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30462955131092634, "steering_wheel_angle": 5.654785337814317, "front_wheel_angle": 0.2824459922173832, "heading_rate": 0.1800342339532375, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141181.8518677} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22587060363870284, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.253392756056128, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.581424344085412, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.654785337814317, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141181.8518677} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.43997859954834, "x": 45.95743732169153, "y": 0.3646216519095882, "z": null, "yaw": 0.11681046439197855, "pitch": null, "roll": null}, "v": 1.5881481297884292, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30462955131092634, "steering_wheel_angle": 5.654785337814317, "front_wheel_angle": 0.2824459922173832, "heading_rate": 0.1800342339532375, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141181.8718677} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22587060363870284, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.253392756056128, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.578577726701855, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.654785337814317, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141181.8718677} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.43997859954834, "x": 45.95743732169153, "y": 0.3646216519095882, "z": null, "yaw": 0.11681046439197855, "pitch": null, "roll": null}, "v": 1.5881481297884292, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30462955131092634, "steering_wheel_angle": 5.654785337814317, "front_wheel_angle": 0.2824459922173832, "heading_rate": 0.1800342339532375, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141181.8918676} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22587060363870284, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.253392756056128, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.575735752294277, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.654785337814317, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141181.8918676} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141181.9118676, "x": 50.130056279509745, "y": 5.385868483523003, "z": null, "yaw": 0.12928018643074976, "pitch": null, "roll": null}, "v": 1.5728984100603391, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3033850145867204, "steering_wheel_angle": 5.654785337814317, "front_wheel_angle": 0.2824459922173832, "heading_rate": 0.1783055088061607, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141181.9118676} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24895444562892924, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.21195471503651, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5714814726418909, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.654785337814317, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141181.9118676} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.549978494644165, "x": 46.130056279509745, "y": 0.3858684835230033, "z": null, "yaw": 0.12928018643074976, "pitch": null, "roll": null}, "v": 1.5728984100603391, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3033850145867204, "steering_wheel_angle": 5.654785337814317, "front_wheel_angle": 0.2824459922173832, "heading_rate": 0.1783055088061607, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141181.9318676} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23786731253513646, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.21195471503651, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5715353641182692, "gear": 1, "accelerator_pedal_position": 0.24895444562892924, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.654785337814317, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141181.9318676} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.549978494644165, "x": 46.130056279509745, "y": 0.3858684835230033, "z": null, "yaw": 0.12928018643074976, "pitch": null, "roll": null}, "v": 1.5728984100603391, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3033850145867204, "steering_wheel_angle": 5.654785337814317, "front_wheel_angle": 0.2824459922173832, "heading_rate": 0.1783055088061607, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141181.9518676} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23786731253513646, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.21195471503651, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5702038404519216, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.654785337814317, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141181.9518676} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.549978494644165, "x": 46.130056279509745, "y": 0.3858684835230033, "z": null, "yaw": 0.12928018643074976, "pitch": null, "roll": null}, "v": 1.5728984100603391, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3033850145867204, "steering_wheel_angle": 5.654785337814317, "front_wheel_angle": 0.2824459922173832, "heading_rate": 0.1783055088061607, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141181.9718676} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23786731253513646, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.21195471503651, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5695388915550847, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.654785337814317, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141181.9718676} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.549978494644165, "x": 46.130056279509745, "y": 0.3858684835230033, "z": null, "yaw": 0.12928018643074976, "pitch": null, "roll": null}, "v": 1.5728984100603391, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3033850145867204, "steering_wheel_angle": 5.654785337814317, "front_wheel_angle": 0.2824459922173832, "heading_rate": 0.1783055088061607, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141181.9918675} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23786731253513646, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.21195471503651, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5675472902574379, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.654785337814317, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141181.9918675} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.549978494644165, "x": 46.130056279509745, "y": 0.3858684835230033, "z": null, "yaw": 0.12928018643074976, "pitch": null, "roll": null}, "v": 1.5728984100603391, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3033850145867204, "steering_wheel_angle": 5.654785337814317, "front_wheel_angle": 0.2824459922173832, "heading_rate": 0.1783055088061607, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141182.0118675} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23786731253513646, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.21195471503651, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5668845031950358, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.654785337814317, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141182.0118675} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141182.0218675, "x": 50.30118070490294, "y": 5.409101921353684, "z": null, "yaw": 0.14174990846952096, "pitch": null, "roll": null}, "v": 1.5662222552722491, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3028416342927134, "steering_wheel_angle": 5.654785337814317, "front_wheel_angle": 0.2824459922173832, "heading_rate": 0.1775486924925671, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141182.0318675} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25477417926525947, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.217036122788282, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.565560545962768, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.654785337814317, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141182.0318675} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.65997838973999, "x": 46.30118070490294, "y": 0.40910192135368373, "z": null, "yaw": 0.14174990846952096, "pitch": null, "roll": null}, "v": 1.5662222552722491, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3028416342927134, "steering_wheel_angle": 5.654785337814317, "front_wheel_angle": 0.2824459922173832, "heading_rate": 0.1775486924925671, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141182.0518675} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24668188590034626, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.217036122788282, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.566240336880264, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.654785337814317, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141182.0518675} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.65997838973999, "x": 46.30118070490294, "y": 0.40910192135368373, "z": null, "yaw": 0.14174990846952096, "pitch": null, "roll": null}, "v": 1.5662222552722491, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3028416342927134, "steering_wheel_angle": 5.654785337814317, "front_wheel_angle": 0.2824459922173832, "heading_rate": 0.1775486924925671, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141182.0718675} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24668188590034626, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.217036122788282, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5661295237013084, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.654785337814317, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141182.0718675} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.65997838973999, "x": 46.30118070490294, "y": 0.40910192135368373, "z": null, "yaw": 0.14174990846952096, "pitch": null, "roll": null}, "v": 1.5662222552722491, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3028416342927134, "steering_wheel_angle": 5.654785337814317, "front_wheel_angle": 0.2824459922173832, "heading_rate": 0.1775486924925671, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141182.0918674} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24668188590034626, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.217036122788282, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5659081676197846, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.654785337814317, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141182.0918674} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.65997838973999, "x": 46.30118070490294, "y": 0.40910192135368373, "z": null, "yaw": 0.14174990846952096, "pitch": null, "roll": null}, "v": 1.5662222552722491, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3028416342927134, "steering_wheel_angle": 5.654785337814317, "front_wheel_angle": 0.2824459922173832, "heading_rate": 0.1775486924925671, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141182.1118674} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24668188590034626, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.217036122788282, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5655768080533847, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.654785337814317, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141182.1118674} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141182.1318674, "x": 50.471565767813445, "y": 5.434403240772973, "z": null, "yaw": 0.15421963050829215, "pitch": null, "roll": null}, "v": 1.5654665344439382, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30278018142683605, "steering_wheel_angle": 5.654785337814317, "front_wheel_angle": 0.2824459922173832, "heading_rate": 0.17746302314104034, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141182.1318674} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21946613998559725, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.8376824395286935, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5653563504984416, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.654785337814317, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141182.1318674} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.769978284835815, "x": 46.471565767813445, "y": 0.43440324077297277, "z": null, "yaw": 0.15421963050829215, "pitch": null, "roll": null}, "v": 1.5654665344439382, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30278018142683605, "steering_wheel_angle": 5.654785337814317, "front_wheel_angle": 0.2824459922173832, "heading_rate": 0.17746302314104034, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141182.1518674} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2324213433411962, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.8376824395286935, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5597396053238632, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.821947304257186, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141182.1518674} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.769978284835815, "x": 46.471565767813445, "y": 0.43440324077297277, "z": null, "yaw": 0.15421963050829215, "pitch": null, "roll": null}, "v": 1.5654665344439382, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30278018142683605, "steering_wheel_angle": 5.654785337814317, "front_wheel_angle": 0.2824459922173832, "heading_rate": 0.17746302314104034, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141182.1818674} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2324213433411962, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.8376824395286935, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.55774678537109, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.905135740892411, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141182.1818674} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.769978284835815, "x": 46.471565767813445, "y": 0.43440324077297277, "z": null, "yaw": 0.15421963050829215, "pitch": null, "roll": null}, "v": 1.5654665344439382, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30278018142683605, "steering_wheel_angle": 5.654785337814317, "front_wheel_angle": 0.2824459922173832, "heading_rate": 0.17746302314104034, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141182.2118673} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2324213433411962, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.8376824395286935, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.554763616359359, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.029427712612488, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141182.2118673} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.769978284835815, "x": 46.471565767813445, "y": 0.43440324077297277, "z": null, "yaw": 0.15421963050829215, "pitch": null, "roll": null}, "v": 1.5654665344439382, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30278018142683605, "steering_wheel_angle": 5.654785337814317, "front_wheel_angle": 0.2824459922173832, "heading_rate": 0.17746302314104034, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141182.2318673} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2324213433411962, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.8376824395286935, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.554763616359359, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.029427712612488, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141182.2318673} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141182.2418673, "x": 50.64097658631217, "y": 5.4617401861044845, "z": null, "yaw": 0.1671286307583094, "pitch": null, "roll": null}, "v": 1.5537708395197285, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30183058019340486, "steering_wheel_angle": 6.070727520990443, "front_wheel_angle": 0.3053957983972022, "heading_rate": 0.1913434242829515, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141182.2618673} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2242099164250224, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.245746820764632, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5517876999804154, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.153130864453249, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141182.2618673} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.87997817993164, "x": 46.64097658631217, "y": 0.46174018610448453, "z": null, "yaw": 0.1671286307583094, "pitch": null, "roll": null}, "v": 1.5537708395197285, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30183058019340486, "steering_wheel_angle": 6.070727520990443, "front_wheel_angle": 0.3053957983972022, "heading_rate": 0.1913434242829515, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141182.2818673} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22804777106544838, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.245746820764632, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5487817610305652, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.236676124816841, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141182.2818673} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.87997817993164, "x": 46.64097658631217, "y": 0.46174018610448453, "z": null, "yaw": 0.1671286307583094, "pitch": null, "roll": null}, "v": 1.5537708395197285, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30183058019340486, "steering_wheel_angle": 6.070727520990443, "front_wheel_angle": 0.3053957983972022, "heading_rate": 0.1913434242829515, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141182.3018672} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22804777106544838, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.245746820764632, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5462602268325893, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.319950652638101, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141182.3018672} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.87997817993164, "x": 46.64097658631217, "y": 0.46174018610448453, "z": null, "yaw": 0.1671286307583094, "pitch": null, "roll": null}, "v": 1.5537708395197285, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30183058019340486, "steering_wheel_angle": 6.070727520990443, "front_wheel_angle": 0.3053957983972022, "heading_rate": 0.1913434242829515, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141182.3218672} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22804777106544838, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.245746820764632, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.543742772732259, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.402954447917031, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141182.3218672} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.87997817993164, "x": 46.64097658631217, "y": 0.46174018610448453, "z": null, "yaw": 0.1671286307583094, "pitch": null, "roll": null}, "v": 1.5537708395197285, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30183058019340486, "steering_wheel_angle": 6.070727520990443, "front_wheel_angle": 0.3053957983972022, "heading_rate": 0.1913434242829515, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141182.3418672} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22804777106544838, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.245746820764632, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5412293895935574, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.485687510653629, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141182.3418672} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141182.3518672, "x": 50.80865801877323, "y": 5.491115450267034, "z": null, "yaw": 0.18122590999735436, "pitch": null, "roll": null}, "v": 1.5399742217872163, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30071391712705225, "steering_wheel_angle": 6.526952517318554, "front_wheel_angle": 0.3309941021470761, "heading_rate": 0.206715058763373, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141182.3618672} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.05807269037990887, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.952489269209698, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5234223608432051, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.05807269037990887, "steering_wheel_angle": 6.656994908185439, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141182.3618672} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.989978075027466, "x": 46.80865801877323, "y": 0.49111545026703407, "z": null, "yaw": 0.18122590999735436, "pitch": null, "roll": null}, "v": 1.5399742217872163, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30071391712705225, "steering_wheel_angle": 6.526952517318554, "front_wheel_angle": 0.3309941021470761, "heading_rate": 0.206715058763373, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141182.3818672} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.020051038700005887, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.952489269209698, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5234223608432051, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.05807269037990887, "steering_wheel_angle": 6.656994908185439, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141182.3818672} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.989978075027466, "x": 46.80865801877323, "y": 0.49111545026703407, "z": null, "yaw": 0.18122590999735436, "pitch": null, "roll": null}, "v": 1.5399742217872163, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30071391712705225, "steering_wheel_angle": 6.526952517318554, "front_wheel_angle": 0.3309941021470761, "heading_rate": 0.206715058763373, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141182.4018672} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.020051038700005887, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.952489269209698, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5142303068777092, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.020051038700005887, "steering_wheel_angle": 6.745523552354278, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141182.4018672} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.989978075027466, "x": 46.80865801877323, "y": 0.49111545026703407, "z": null, "yaw": 0.18122590999735436, "pitch": null, "roll": null}, "v": 1.5399742217872163, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30071391712705225, "steering_wheel_angle": 6.526952517318554, "front_wheel_angle": 0.3309941021470761, "heading_rate": 0.206715058763373, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141182.4218671} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.020051038700005887, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.952489269209698, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5050530150420023, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.020051038700005887, "steering_wheel_angle": 6.833735773354414, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141182.4218671} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.989978075027466, "x": 46.80865801877323, "y": 0.49111545026703407, "z": null, "yaw": 0.18122590999735436, "pitch": null, "roll": null}, "v": 1.5399742217872163, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30071391712705225, "steering_wheel_angle": 6.526952517318554, "front_wheel_angle": 0.3309941021470761, "heading_rate": 0.206715058763373, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141182.441867} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.020051038700005887, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.952489269209698, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4958904279530076, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.020051038700005887, "steering_wheel_angle": 6.921631571185845, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141182.441867} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141182.461867, "x": 50.972403810017134, "y": 5.522276723030158, "z": null, "yaw": 0.19659313978977616, "pitch": null, "roll": null}, "v": 1.4867424884815617, "accelerator_pedal_position": 0, "brake_pedal_position": 0.020051038700005887, "acceleration": -0.45684946629468864, "steering_wheel_angle": 7.009210945848574, "front_wheel_angle": 0.35856393638865236, "heading_rate": 0.217647608515599, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141182.461867} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.948457036105204, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4867424884815617, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.020051038700005887, "steering_wheel_angle": 7.009210945848574, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141182.461867} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.09997797012329, "x": 46.972403810017134, "y": 0.5222767230301582, "z": null, "yaw": 0.19659313978977616, "pitch": null, "roll": null}, "v": 1.4867424884815617, "accelerator_pedal_position": 0, "brake_pedal_position": 0.020051038700005887, "acceleration": -0.45684946629468864, "steering_wheel_angle": 7.009210945848574, "front_wheel_angle": 0.35856393638865236, "heading_rate": 0.217647608515599, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141182.481867} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.948457036105204, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4808160281380045, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.096456537473111, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141182.481867} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.09997797012329, "x": 46.972403810017134, "y": 0.5222767230301582, "z": null, "yaw": 0.19659313978977616, "pitch": null, "roll": null}, "v": 1.4867424884815617, "accelerator_pedal_position": 0, "brake_pedal_position": 0.020051038700005887, "acceleration": -0.45684946629468864, "steering_wheel_angle": 7.009210945848574, "front_wheel_angle": 0.35856393638865236, "heading_rate": 0.217647608515599, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141182.501867} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.948457036105204, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4719440221985072, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.226731867930278, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141182.501867} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.09997797012329, "x": 46.972403810017134, "y": 0.5222767230301582, "z": null, "yaw": 0.19659313978977616, "pitch": null, "roll": null}, "v": 1.4867424884815617, "accelerator_pedal_position": 0, "brake_pedal_position": 0.020051038700005887, "acceleration": -0.45684946629468864, "steering_wheel_angle": 7.009210945848574, "front_wheel_angle": 0.35856393638865236, "heading_rate": 0.217647608515599, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141182.521867} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.948457036105204, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4689913882669594, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.269998829554765, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141182.521867} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.09997797012329, "x": 46.972403810017134, "y": 0.5222767230301582, "z": null, "yaw": 0.19659313978977616, "pitch": null, "roll": null}, "v": 1.4867424884815617, "accelerator_pedal_position": 0, "brake_pedal_position": 0.020051038700005887, "acceleration": -0.45684946629468864, "steering_wheel_angle": 7.009210945848574, "front_wheel_angle": 0.35856393638865236, "heading_rate": 0.217647608515599, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141182.541867} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.948457036105204, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4630931508030478, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.356295530011883, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141182.541867} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.09997797012329, "x": 46.972403810017134, "y": 0.5222767230301582, "z": null, "yaw": 0.19659313978977616, "pitch": null, "roll": null}, "v": 1.4867424884815617, "accelerator_pedal_position": 0, "brake_pedal_position": 0.020051038700005887, "acceleration": -0.45684946629468864, "steering_wheel_angle": 7.009210945848574, "front_wheel_angle": 0.35856393638865236, "heading_rate": 0.217647608515599, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141182.561867} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.948457036105204, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4572042632169409, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.442275933413193, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141182.561867} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141182.571867, "x": 51.130957964595666, "y": 5.555086617230288, "z": null, "yaw": 0.2133186794276024, "pitch": null, "roll": null}, "v": 1.4542633166588586, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29386198377473915, "steering_wheel_angle": 7.485147523717921, "front_wheel_angle": 0.3863175353877717, "heading_rate": 0.23106694710097525, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141182.581867} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22682707168131958, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.845485272356902, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.451324696821111, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.527940039758697, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141182.581867} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.209977865219116, "x": 47.130957964595666, "y": 0.5550866172302884, "z": null, "yaw": 0.2133186794276024, "pitch": null, "roll": null}, "v": 1.4542633166588586, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29386198377473915, "steering_wheel_angle": 7.485147523717921, "front_wheel_angle": 0.3863175353877717, "heading_rate": 0.23106694710097525, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141182.601867} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.845485272356902, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4488064826721105, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.612857595087975, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141182.601867} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.209977865219116, "x": 47.130957964595666, "y": 0.5550866172302884, "z": null, "yaw": 0.2133186794276024, "pitch": null, "roll": null}, "v": 1.4542633166588586, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29386198377473915, "steering_wheel_angle": 7.485147523717921, "front_wheel_angle": 0.3863175353877717, "heading_rate": 0.23106694710097525, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141182.621867} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.845485272356902, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4429401846858851, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.697462040206681, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141182.621867} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.209977865219116, "x": 47.130957964595666, "y": 0.5550866172302884, "z": null, "yaw": 0.2133186794276024, "pitch": null, "roll": null}, "v": 1.4542633166588586, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29386198377473915, "steering_wheel_angle": 7.485147523717921, "front_wheel_angle": 0.3863175353877717, "heading_rate": 0.23106694710097525, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141182.641867} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.845485272356902, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4370831386763918, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.781753375114818, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141182.641867} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.209977865219116, "x": 47.130957964595666, "y": 0.5550866172302884, "z": null, "yaw": 0.2133186794276024, "pitch": null, "roll": null}, "v": 1.4542633166588586, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29386198377473915, "steering_wheel_angle": 7.485147523717921, "front_wheel_angle": 0.3863175353877717, "heading_rate": 0.23106694710097525, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141182.661867} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.845485272356902, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4283148552241252, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.907603295832193, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141182.661867} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141182.681867, "x": 51.28572414625838, "y": 5.589923892714019, "z": null, "yaw": 0.23143025388230684, "pitch": null, "roll": null}, "v": 1.4253966894639476, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29158739169654524, "steering_wheel_angle": 7.949396714299369, "front_wheel_angle": 0.4139437076564933, "heading_rate": 0.24461587289386655, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141182.681867} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.431657580216772, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4253966894639476, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.949396714299369, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141182.681867} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.31997776031494, "x": 47.28572414625838, "y": 0.5899238927140189, "z": null, "yaw": 0.23143025388230684, "pitch": null, "roll": null}, "v": 1.4253966894639476, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29158739169654524, "steering_wheel_angle": 7.949396714299369, "front_wheel_angle": 0.4139437076564933, "heading_rate": 0.24461587289386655, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141182.7018669} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.431657580216772, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4137469098783124, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.120755564915797, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141182.7018669} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.31997776031494, "x": 47.28572414625838, "y": 0.5899238927140189, "z": null, "yaw": 0.23143025388230684, "pitch": null, "roll": null}, "v": 1.4253966894639476, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29158739169654524, "steering_wheel_angle": 7.949396714299369, "front_wheel_angle": 0.4139437076564933, "heading_rate": 0.24461587289386655, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141182.7218668} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.431657580216772, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4137469098783124, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.120755564915797, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141182.7218668} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.31997776031494, "x": 47.28572414625838, "y": 0.5899238927140189, "z": null, "yaw": 0.23143025388230684, "pitch": null, "roll": null}, "v": 1.4253966894639476, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29158739169654524, "steering_wheel_angle": 7.949396714299369, "front_wheel_angle": 0.4139437076564933, "heading_rate": 0.24461587289386655, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141182.7518668} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.431657580216772, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4050335051640281, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.248402779196086, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141182.7518668} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.31997776031494, "x": 47.28572414625838, "y": 0.5899238927140189, "z": null, "yaw": 0.23143025388230684, "pitch": null, "roll": null}, "v": 1.4253966894639476, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29158739169654524, "steering_wheel_angle": 7.949396714299369, "front_wheel_angle": 0.4139437076564933, "heading_rate": 0.24461587289386655, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141182.7718668} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.431657580216772, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3992359118515008, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.333085720296262, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141182.7718668} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.431657580216772, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3963405077818736, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.375302630320347, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141182.7818668} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141182.7918668, "x": 51.436461524016835, "y": 5.626836801936563, "z": null, "yaw": 0.2509757320666865, "pitch": null, "roll": null}, "v": 1.3934473608466154, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.28908932351683475, "steering_wheel_angle": 8.41743649999376, "front_wheel_angle": 0.4423848029362968, "heading_rate": 0.2578406498593494, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141182.8118668} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23549566695973564, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.296828175291674, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3876678246486798, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.501455118288579, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141182.8118668} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.429977655410767, "x": 47.436461524016835, "y": 0.6268368019365633, "z": null, "yaw": 0.2509757320666865, "pitch": null, "roll": null}, "v": 1.3934473608466154, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.28908932351683475, "steering_wheel_angle": 8.41743649999376, "front_wheel_angle": 0.4423848029362968, "heading_rate": 0.2578406498593494, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141182.8318667} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21867293964410286, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.296828175291674, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3863325100789026, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.584563182093216, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141182.8318667} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.429977655410767, "x": 47.436461524016835, "y": 0.6268368019365633, "z": null, "yaw": 0.2509757320666865, "pitch": null, "roll": null}, "v": 1.3934473608466154, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.28908932351683475, "steering_wheel_angle": 8.41743649999376, "front_wheel_angle": 0.4423848029362968, "heading_rate": 0.2578406498593494, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141182.8518667} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21867293964410286, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.296828175291674, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.382897246739875, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.667343669053077, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141182.8518667} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.429977655410767, "x": 47.436461524016835, "y": 0.6268368019365633, "z": null, "yaw": 0.2509757320666865, "pitch": null, "roll": null}, "v": 1.3934473608466154, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.28908932351683475, "steering_wheel_angle": 8.41743649999376, "front_wheel_angle": 0.4423848029362968, "heading_rate": 0.2578406498593494, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141182.8718667} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21867293964410286, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.296828175291674, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.379467318018593, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.667343669053077, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141182.8718667} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.429977655410767, "x": 47.436461524016835, "y": 0.6268368019365633, "z": null, "yaw": 0.2509757320666865, "pitch": null, "roll": null}, "v": 1.3934473608466154, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.28908932351683475, "steering_wheel_angle": 8.41743649999376, "front_wheel_angle": 0.4423848029362968, "heading_rate": 0.2578406498593494, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141182.8918667} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21867293964410286, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.296828175291674, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3760427109269926, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.667343669053077, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141182.8918667} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141182.9018667, "x": 51.583595807536405, "y": 5.666037571719586, "z": null, "yaw": 0.27188774419346373, "pitch": null, "roll": null}, "v": 1.374332398945056, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2876045153751535, "steering_wheel_angle": 8.667343669053077, "front_wheel_angle": 0.4578265069782707, "heading_rate": 0.2645292762892166, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141182.9118667} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.84903238657296, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3726234125190608, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.667343669053077, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141182.9118667} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.539977550506592, "x": 47.583595807536405, "y": 0.6660375717195857, "z": null, "yaw": 0.27188774419346373, "pitch": null, "roll": null}, "v": 1.374332398945056, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2876045153751535, "steering_wheel_angle": 8.667343669053077, "front_wheel_angle": 0.4578265069782707, "heading_rate": 0.2645292762892166, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141182.9318666} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.84903238657296, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3668761958161526, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.75222574745778, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141182.9318666} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.539977550506592, "x": 47.583595807536405, "y": 0.6660375717195857, "z": null, "yaw": 0.27188774419346373, "pitch": null, "roll": null}, "v": 1.374332398945056, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2876045153751535, "steering_wheel_angle": 8.667343669053077, "front_wheel_angle": 0.4578265069782707, "heading_rate": 0.2645292762892166, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141182.9518666} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.84903238657296, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3611378684877367, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.836760622304292, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141182.9518666} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.539977550506592, "x": 47.583595807536405, "y": 0.6660375717195857, "z": null, "yaw": 0.27188774419346373, "pitch": null, "roll": null}, "v": 1.374332398945056, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2876045153751535, "steering_wheel_angle": 8.667343669053077, "front_wheel_angle": 0.4578265069782707, "heading_rate": 0.2645292762892166, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141182.9718666} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.84903238657296, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3554084036181004, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.920948293592605, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141182.9718666} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.539977550506592, "x": 47.583595807536405, "y": 0.6660375717195857, "z": null, "yaw": 0.27188774419346373, "pitch": null, "roll": null}, "v": 1.374332398945056, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2876045153751535, "steering_wheel_angle": 8.667343669053077, "front_wheel_angle": 0.4578265069782707, "heading_rate": 0.2645292762892166, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141182.9918666} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.84903238657296, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3496877743941265, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.004788761322722, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141182.9918666} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141183.0118666, "x": 51.72741027453565, "y": 5.707643119212896, "z": null, "yaw": 0.2936427258086655, "pitch": null, "roll": null}, "v": 1.3439759541047949, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.28526151135735867, "steering_wheel_angle": 9.088282025494644, "front_wheel_angle": 0.4842610089589816, "heading_rate": 0.2761654354386714, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141183.0118666} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24178135991402094, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.693047547032899, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3439759541047949, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.088282025494644, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141183.0118666} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.649977445602417, "x": 47.72741027453565, "y": 0.7076431192128956, "z": null, "yaw": 0.2936427258086655, "pitch": null, "roll": null}, "v": 1.3439759541047949, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.28526151135735867, "steering_wheel_angle": 9.088282025494644, "front_wheel_angle": 0.4842610089589816, "heading_rate": 0.2761654354386714, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141183.0318666} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22528880391664496, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.693047547032899, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3434935793560738, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.088282025494644, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141183.0318666} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.649977445602417, "x": 47.72741027453565, "y": 0.7076431192128956, "z": null, "yaw": 0.2936427258086655, "pitch": null, "roll": null}, "v": 1.3439759541047949, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.28526151135735867, "steering_wheel_angle": 9.088282025494644, "front_wheel_angle": 0.4842610089589816, "heading_rate": 0.2761654354386714, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141183.0518665} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22528880391664496, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.693047547032899, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3409511686546027, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.088282025494644, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141183.0518665} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.649977445602417, "x": 47.72741027453565, "y": 0.7076431192128956, "z": null, "yaw": 0.2936427258086655, "pitch": null, "roll": null}, "v": 1.3439759541047949, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.28526151135735867, "steering_wheel_angle": 9.088282025494644, "front_wheel_angle": 0.4842610089589816, "heading_rate": 0.2761654354386714, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141183.0718665} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22528880391664496, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.693047547032899, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3384126632090925, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.088282025494644, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141183.0718665} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.649977445602417, "x": 47.72741027453565, "y": 0.7076431192128956, "z": null, "yaw": 0.2936427258086655, "pitch": null, "roll": null}, "v": 1.3439759541047949, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.28526151135735867, "steering_wheel_angle": 9.088282025494644, "front_wheel_angle": 0.4842610089589816, "heading_rate": 0.2761654354386714, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141183.0918665} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22528880391664496, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.693047547032899, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.335878054444281, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.088282025494644, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141183.0918665} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.649977445602417, "x": 47.72741027453565, "y": 0.7076431192128956, "z": null, "yaw": 0.2936427258086655, "pitch": null, "roll": null}, "v": 1.3439759541047949, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.28526151135735867, "steering_wheel_angle": 9.088282025494644, "front_wheel_angle": 0.4842610089589816, "heading_rate": 0.2761654354386714, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141183.1118665} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22528880391664496, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.693047547032899, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3333473338099364, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.088282025494644, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141183.1118665} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141183.1218665, "x": 51.86799051415942, "y": 5.751731054779016, "z": null, "yaw": 0.3162459560267897, "pitch": null, "roll": null}, "v": 1.332083428876564, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.28434863405870364, "steering_wheel_angle": 9.088282025494644, "front_wheel_angle": 0.4842610089589816, "heading_rate": 0.27372171284223, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141183.1318665} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22530040295777576, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.917879917295364, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3308204927807672, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.088282025494644, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141183.1318665} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.759977340698242, "x": 47.86799051415942, "y": 0.7517310547790164, "z": null, "yaw": 0.3162459560267897, "pitch": null, "roll": null}, "v": 1.332083428876564, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.28434863405870364, "steering_wheel_angle": 9.088282025494644, "front_wheel_angle": 0.4842610089589816, "heading_rate": 0.27372171284223, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141183.1518664} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2252253270112646, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.917879917295364, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.328298972181231, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.171739734681767, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141183.1518664} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.759977340698242, "x": 47.86799051415942, "y": 0.7517310547790164, "z": null, "yaw": 0.3162459560267897, "pitch": null, "roll": null}, "v": 1.332083428876564, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.28434863405870364, "steering_wheel_angle": 9.088282025494644, "front_wheel_angle": 0.4842610089589816, "heading_rate": 0.27372171284223, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141183.1718664} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2252253270112646, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.917879917295364, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3257719310911091, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.254847627165047, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141183.1718664} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.759977340698242, "x": 47.86799051415942, "y": 0.7517310547790164, "z": null, "yaw": 0.3162459560267897, "pitch": null, "roll": null}, "v": 1.332083428876564, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.28434863405870364, "steering_wheel_angle": 9.088282025494644, "front_wheel_angle": 0.4842610089589816, "heading_rate": 0.27372171284223, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141183.1918664} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2252253270112646, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.917879917295364, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.323248756313, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.337605702944492, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141183.1918664} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.759977340698242, "x": 47.86799051415942, "y": 0.7517310547790164, "z": null, "yaw": 0.3162459560267897, "pitch": null, "roll": null}, "v": 1.332083428876564, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.28434863405870364, "steering_wheel_angle": 9.088282025494644, "front_wheel_angle": 0.4842610089589816, "heading_rate": 0.27372171284223, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141183.2118664} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2252253270112646, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.917879917295364, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3207294393859481, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.337605702944492, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141183.2118664} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141183.2318664, "x": 52.00611169306352, "y": 5.798523136110351, "z": null, "yaw": 0.33936900627488115, "pitch": null, "roll": null}, "v": 1.3182139718736126, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.28328757935010873, "steering_wheel_angle": 9.337605702944492, "front_wheel_angle": 0.5001812841773194, "heading_rate": 0.2814273035900647, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141183.2318664} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25108636040899207, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.784901285114946, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3182139718736126, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.337605702944492, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141183.2318664} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.869977235794067, "x": 48.00611169306352, "y": 0.7985231361103509, "z": null, "yaw": 0.33936900627488115, "pitch": null, "roll": null}, "v": 1.3182139718736126, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.28328757935010873, "steering_wheel_angle": 9.337605702944492, "front_wheel_angle": 0.5001812841773194, "heading_rate": 0.2814273035900647, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141183.2518663} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23869073414488157, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.784901285114946, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3189337403967714, "gear": 1, "accelerator_pedal_position": 0.25108636040899207, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.337605702944492, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141183.2518663} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.869977235794067, "x": 48.00611169306352, "y": 0.7985231361103509, "z": null, "yaw": 0.33936900627488115, "pitch": null, "roll": null}, "v": 1.3182139718736126, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.28328757935010873, "steering_wheel_angle": 9.337605702944492, "front_wheel_angle": 0.5001812841773194, "heading_rate": 0.2814273035900647, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141183.2718663} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23869073414488157, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.784901285114946, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3181035483308958, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.337605702944492, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141183.2718663} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.869977235794067, "x": 48.00611169306352, "y": 0.7985231361103509, "z": null, "yaw": 0.33936900627488115, "pitch": null, "roll": null}, "v": 1.3182139718736126, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.28328757935010873, "steering_wheel_angle": 9.337605702944492, "front_wheel_angle": 0.5001812841773194, "heading_rate": 0.2814273035900647, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141183.2918663} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23869073414488157, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.784901285114946, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3172746237535262, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.337605702944492, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141183.2918663} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.869977235794067, "x": 48.00611169306352, "y": 0.7985231361103509, "z": null, "yaw": 0.33936900627488115, "pitch": null, "roll": null}, "v": 1.3182139718736126, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.28328757935010873, "steering_wheel_angle": 9.337605702944492, "front_wheel_angle": 0.5001812841773194, "heading_rate": 0.2814273035900647, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141183.3118663} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23869073414488157, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.784901285114946, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3164469644547938, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.337605702944492, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141183.3118663} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.869977235794067, "x": 48.00611169306352, "y": 0.7985231361103509, "z": null, "yaw": 0.33936900627488115, "pitch": null, "roll": null}, "v": 1.3182139718736126, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.28328757935010873, "steering_wheel_angle": 9.337605702944492, "front_wheel_angle": 0.5001812841773194, "heading_rate": 0.2814273035900647, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141183.3318663} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23869073414488157, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.784901285114946, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3156205682294613, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.337605702944492, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141183.3318663} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141183.3418663, "x": 52.14224310116517, "y": 5.848220912100853, "z": null, "yaw": 0.36285305670631973, "pitch": null, "roll": null}, "v": 1.315207843081447, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2830581088591019, "steering_wheel_angle": 9.337605702944492, "front_wheel_angle": 0.5001812841773194, "heading_rate": 0.2807855210431681, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141183.3518662} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2575311492983465, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.69753208433666, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3155608632885878, "gear": 1, "accelerator_pedal_position": 0.2575311492983465, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.337605702944492, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141183.3518662} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.979977130889893, "x": 48.14224310116517, "y": 0.848220912100853, "z": null, "yaw": 0.36285305670631973, "pitch": null, "roll": null}, "v": 1.315207843081447, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2830581088591019, "steering_wheel_angle": 9.337605702944492, "front_wheel_angle": 0.5001812841773194, "heading_rate": 0.2807855210431681, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141183.3718662} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24854203507835498, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.69753208433666, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3163257096495884, "gear": 1, "accelerator_pedal_position": 0.2575311492983465, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.337605702944492, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141183.3718662} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.979977130889893, "x": 48.14224310116517, "y": 0.848220912100853, "z": null, "yaw": 0.36285305670631973, "pitch": null, "roll": null}, "v": 1.315207843081447, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2830581088591019, "steering_wheel_angle": 9.337605702944492, "front_wheel_angle": 0.5001812841773194, "heading_rate": 0.2807855210431681, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141183.3918662} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24854203507835498, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.69753208433666, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3167304411281726, "gear": 1, "accelerator_pedal_position": 0.24854203507835498, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.337605702944492, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141183.3918662} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.979977130889893, "x": 48.14224310116517, "y": 0.848220912100853, "z": null, "yaw": 0.36285305670631973, "pitch": null, "roll": null}, "v": 1.315207843081447, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2830581088591019, "steering_wheel_angle": 9.337605702944492, "front_wheel_angle": 0.5001812841773194, "heading_rate": 0.2807855210431681, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141183.4118662} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24854203507835498, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.69753208433666, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3173363805299168, "gear": 1, "accelerator_pedal_position": 0.24854203507835498, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.337605702944492, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141183.4118662} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.979977130889893, "x": 48.14224310116517, "y": 0.848220912100853, "z": null, "yaw": 0.36285305670631973, "pitch": null, "roll": null}, "v": 1.315207843081447, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2830581088591019, "steering_wheel_angle": 9.337605702944492, "front_wheel_angle": 0.5001812841773194, "heading_rate": 0.2807855210431681, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141183.4218662} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24854203507835498, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.69753208433666, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3173363805299168, "gear": 1, "accelerator_pedal_position": 0.24854203507835498, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.337605702944492, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141183.4218662} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141183.4518661, "x": 52.277072268442254, "y": 5.901064820505445, "z": null, "yaw": 0.3863371071377583, "pitch": null, "roll": null}, "v": 1.3179409331829586, "accelerator_pedal_position": 0.24854203507835498, "brake_pedal_position": 0.0, "acceleration": 0.02012098954697894, "steering_wheel_angle": 9.337605702944492, "front_wheel_angle": 0.5001812841773194, "heading_rate": 0.2813690121866006, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141183.4518661} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.01342168972523005, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.784335502350055, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3179409331829586, "gear": 1, "accelerator_pedal_position": 0.24854203507835498, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.337605702944492, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141183.4518661} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.089977025985718, "x": 48.277072268442254, "y": 0.9010648205054448, "z": null, "yaw": 0.3863371071377583, "pitch": null, "roll": null}, "v": 1.3179409331829586, "accelerator_pedal_position": 0.24854203507835498, "brake_pedal_position": 0.0, "acceleration": 0.02012098954697894, "steering_wheel_angle": 9.337605702944492, "front_wheel_angle": 0.5001812841773194, "heading_rate": 0.2813690121866006, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141183.4718661} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.784335502350055, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3101311095898511, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.01342168972523005, "steering_wheel_angle": 9.424208521965753, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141183.4718661} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.089977025985718, "x": 48.277072268442254, "y": 0.9010648205054448, "z": null, "yaw": 0.3863371071377583, "pitch": null, "roll": null}, "v": 1.3179409331829586, "accelerator_pedal_position": 0.24854203507835498, "brake_pedal_position": 0.0, "acceleration": 0.02012098954697894, "steering_wheel_angle": 9.337605702944492, "front_wheel_angle": 0.5001812841773194, "heading_rate": 0.2813690121866006, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141183.491866} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.784335502350055, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3044798430034406, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.51042492314278, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141183.491866} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.089977025985718, "x": 48.277072268442254, "y": 0.9010648205054448, "z": null, "yaw": 0.3863371071377583, "pitch": null, "roll": null}, "v": 1.3179409331829586, "accelerator_pedal_position": 0.24854203507835498, "brake_pedal_position": 0.0, "acceleration": 0.02012098954697894, "steering_wheel_angle": 9.337605702944492, "front_wheel_angle": 0.5001812841773194, "heading_rate": 0.2813690121866006, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141183.511866} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.784335502350055, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.298837176389549, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.596254906475572, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141183.511866} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.089977025985718, "x": 48.277072268442254, "y": 0.9010648205054448, "z": null, "yaw": 0.3863371071377583, "pitch": null, "roll": null}, "v": 1.3179409331829586, "accelerator_pedal_position": 0.24854203507835498, "brake_pedal_position": 0.0, "acceleration": 0.02012098954697894, "steering_wheel_angle": 9.337605702944492, "front_wheel_angle": 0.5001812841773194, "heading_rate": 0.2813690121866006, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141183.531866} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.784335502350055, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2932030839298885, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.681698471964124, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141183.531866} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.089977025985718, "x": 48.277072268442254, "y": 0.9010648205054448, "z": null, "yaw": 0.3863371071377583, "pitch": null, "roll": null}, "v": 1.3179409331829586, "accelerator_pedal_position": 0.24854203507835498, "brake_pedal_position": 0.0, "acceleration": 0.02012098954697894, "steering_wheel_angle": 9.337605702944492, "front_wheel_angle": 0.5001812841773194, "heading_rate": 0.2813690121866006, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141183.551866} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.784335502350055, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2847679655413813, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.809139286739015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141183.551866} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141183.561866, "x": 52.409136502916624, "y": 5.956461526700131, "z": null, "yaw": 0.4106077828026813, "pitch": null, "roll": null}, "v": 1.2847679655413813, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.28074468552988247, "steering_wheel_angle": 9.809139286739015, "front_wheel_angle": 0.530857396621236, "heading_rate": 0.29462807451255824, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141183.571866} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22759832235159214, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.904678768654096, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2819605186860825, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.851426349408527, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141183.571866} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.199976921081543, "x": 48.409136502916624, "y": 0.9564615267001306, "z": null, "yaw": 0.4106077828026813, "pitch": null, "roll": null}, "v": 1.2847679655413813, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.28074468552988247, "steering_wheel_angle": 9.809139286739015, "front_wheel_angle": 0.530857396621236, "heading_rate": 0.29462807451255824, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141183.591866} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22099374407479971, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.904678768654096, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2798004810170651, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.936328404032036, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141183.591866} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.199976921081543, "x": 48.409136502916624, "y": 0.9564615267001306, "z": null, "yaw": 0.4106077828026813, "pitch": null, "roll": null}, "v": 1.2847679655413813, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.28074468552988247, "steering_wheel_angle": 9.809139286739015, "front_wheel_angle": 0.530857396621236, "heading_rate": 0.29462807451255824, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141183.611866} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22099374407479971, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.904678768654096, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.276818448043758, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.02083834252401, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141183.611866} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.199976921081543, "x": 48.409136502916624, "y": 0.9564615267001306, "z": null, "yaw": 0.4106077828026813, "pitch": null, "roll": null}, "v": 1.2847679655413813, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.28074468552988247, "steering_wheel_angle": 9.809139286739015, "front_wheel_angle": 0.530857396621236, "heading_rate": 0.29462807451255824, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141183.631866} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22099374407479971, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.904678768654096, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.273840919296754, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.104956164884454, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141183.631866} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.199976921081543, "x": 48.409136502916624, "y": 0.9564615267001306, "z": null, "yaw": 0.4106077828026813, "pitch": null, "roll": null}, "v": 1.2847679655413813, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.28074468552988247, "steering_wheel_angle": 9.809139286739015, "front_wheel_angle": 0.530857396621236, "heading_rate": 0.29462807451255824, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141183.651866} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22099374407479971, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.904678768654096, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2708678844276886, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.188681871113367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141183.651866} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141183.671866, "x": 52.537239686862506, "y": 6.014017962356735, "z": null, "yaw": 0.43665349076458304, "pitch": null, "roll": null}, "v": 1.2678993331198698, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2794706538452516, "steering_wheel_angle": 10.272015461210742, "front_wheel_angle": 0.5617383763050101, "heading_rate": 0.3117119872668741, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141183.671866} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23589934359909442, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.92183275922554, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2678993331198698, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.272015461210742, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141183.671866} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.309976816177368, "x": 48.537239686862506, "y": 1.0140179623567347, "z": null, "yaw": 0.43665349076458304, "pitch": null, "roll": null}, "v": 1.2678993331198698, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2794706538452516, "steering_wheel_angle": 10.272015461210742, "front_wheel_angle": 0.5617383763050101, "heading_rate": 0.3117119872668741, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141183.691866} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22870436638877675, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.92183275922554, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.266797753183162, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.355044037299143, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141183.691866} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.309976816177368, "x": 48.537239686862506, "y": 1.0140179623567347, "z": null, "yaw": 0.43665349076458304, "pitch": null, "roll": null}, "v": 1.2678993331198698, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2794706538452516, "steering_wheel_angle": 10.272015461210742, "front_wheel_angle": 0.5617383763050101, "heading_rate": 0.3117119872668741, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141183.711866} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22870436638877675, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.92183275922554, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2638004509679461, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.355044037299143, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141183.711866} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.309976816177368, "x": 48.537239686862506, "y": 1.0140179623567347, "z": null, "yaw": 0.43665349076458304, "pitch": null, "roll": null}, "v": 1.2678993331198698, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2794706538452516, "steering_wheel_angle": 10.272015461210742, "front_wheel_angle": 0.5617383763050101, "heading_rate": 0.3117119872668741, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141183.721866} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22870436638877675, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.92183275922554, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2638004509679461, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.355044037299143, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141183.721866} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.309976816177368, "x": 48.537239686862506, "y": 1.0140179623567347, "z": null, "yaw": 0.43665349076458304, "pitch": null, "roll": null}, "v": 1.2678993331198698, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2794706538452516, "steering_wheel_angle": 10.272015461210742, "front_wheel_angle": 0.5617383763050101, "heading_rate": 0.3117119872668741, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141183.7518659} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22870436638877675, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.92183275922554, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2598145670842742, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.355044037299143, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141183.7518659} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.309976816177368, "x": 48.537239686862506, "y": 1.0140179623567347, "z": null, "yaw": 0.43665349076458304, "pitch": null, "roll": null}, "v": 1.2678993331198698, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2794706538452516, "steering_wheel_angle": 10.272015461210742, "front_wheel_angle": 0.5617383763050101, "heading_rate": 0.3117119872668741, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141183.7718658} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22870436638877675, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.92183275922554, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2588199694256867, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.355044037299143, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141183.7718658} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141183.7818658, "x": 52.66246036935824, "y": 6.074358369085092, "z": null, "yaw": 0.4639893009107135, "pitch": null, "roll": null}, "v": 1.25782611956873, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2787125714491298, "steering_wheel_angle": 10.355044037299143, "front_wheel_angle": 0.5673627390281828, "heading_rate": 0.31310734776102617, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141183.7918658} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23655780770935825, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.256833016753537, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.355044037299143, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141183.7918658} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.419976711273193, "x": 48.66246036935824, "y": 1.0743583690850924, "z": null, "yaw": 0.4639893009107135, "pitch": null, "roll": null}, "v": 1.25782611956873, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2787125714491298, "steering_wheel_angle": 10.355044037299143, "front_wheel_angle": 0.5673627390281828, "heading_rate": 0.31310734776102617, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141183.8118658} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23276031319141002, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2558303606516124, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141183.8118658} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.419976711273193, "x": 48.66246036935824, "y": 1.0743583690850924, "z": null, "yaw": 0.4639893009107135, "pitch": null, "roll": null}, "v": 1.25782611956873, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2787125714491298, "steering_wheel_angle": 10.355044037299143, "front_wheel_angle": 0.5673627390281828, "heading_rate": 0.31310734776102617, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141183.8318658} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23276031319141002, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2543547018470922, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141183.8318658} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.419976711273193, "x": 48.66246036935824, "y": 1.0743583690850924, "z": null, "yaw": 0.4639893009107135, "pitch": null, "roll": null}, "v": 1.25782611956873, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2787125714491298, "steering_wheel_angle": 10.355044037299143, "front_wheel_angle": 0.5673627390281828, "heading_rate": 0.31310734776102617, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141183.8518658} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23276031319141002, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2528812584868882, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141183.8518658} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.419976711273193, "x": 48.66246036935824, "y": 1.0743583690850924, "z": null, "yaw": 0.4639893009107135, "pitch": null, "roll": null}, "v": 1.25782611956873, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2787125714491298, "steering_wheel_angle": 10.355044037299143, "front_wheel_angle": 0.5673627390281828, "heading_rate": 0.31310734776102617, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141183.8718657} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23276031319141002, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.251410026376809, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141183.8718657} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141183.8918657, "x": 52.785056637175146, "y": 6.137640795830879, "z": null, "yaw": 0.49163581313802623, "pitch": null, "roll": null}, "v": 1.2499410013328662, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2781205751347734, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.31503448508179405, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141183.8918657} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22323471522450558, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2499410013328662, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141183.8918657} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.52997660636902, "x": 48.785056637175146, "y": 1.1376407958308787, "z": null, "yaw": 0.49163581313802623, "pitch": null, "roll": null}, "v": 1.2499410013328662, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2781205751347734, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.31503448508179405, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141183.9118657} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22772561201867017, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2472839258179553, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141183.9118657} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.52997660636902, "x": 48.785056637175146, "y": 1.1376407958308787, "z": null, "yaw": 0.49163581313802623, "pitch": null, "roll": null}, "v": 1.2499410013328662, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2781205751347734, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.31503448508179405, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141183.9318657} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22772561201867017, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.245191984050461, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141183.9318657} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.52997660636902, "x": 48.785056637175146, "y": 1.1376407958308787, "z": null, "yaw": 0.49163581313802623, "pitch": null, "roll": null}, "v": 1.2499410013328662, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2781205751347734, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.31503448508179405, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141183.9518657} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22772561201867017, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2431031754361386, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141183.9518657} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.52997660636902, "x": 48.785056637175146, "y": 1.1376407958308787, "z": null, "yaw": 0.49163581313802623, "pitch": null, "roll": null}, "v": 1.2499410013328662, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2781205751347734, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.31503448508179405, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141183.9718657} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22772561201867017, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2410174935377905, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141183.9718657} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.52997660636902, "x": 48.785056637175146, "y": 1.1376407958308787, "z": null, "yaw": 0.49163581313802623, "pitch": null, "roll": null}, "v": 1.2499410013328662, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2781205751347734, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.31503448508179405, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141183.9918656} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22772561201867017, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2389349319356913, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141183.9918656} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141184.0018656, "x": 52.9048855119647, "y": 6.203761085325608, "z": null, "yaw": 0.5193601563846635, "pitch": null, "roll": null}, "v": 1.2378948192443333, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2772185767973363, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.31199837156330334, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141184.0118656} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22941427899192582, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2368554842275268, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141184.0118656} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.639976501464844, "x": 48.9048855119647, "y": 1.203761085325608, "z": null, "yaw": 0.5193601563846635, "pitch": null, "roll": null}, "v": 1.2378948192443333, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2772185767973363, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.31199837156330334, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141184.0318656} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22854142774292438, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.234990148541996, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141184.0318656} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.639976501464844, "x": 48.9048855119647, "y": 1.203761085325608, "z": null, "yaw": 0.5193601563846635, "pitch": null, "roll": null}, "v": 1.2378948192443333, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2772185767973363, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.31199837156330334, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141184.0518656} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22854142774292438, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2330185333021257, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141184.0518656} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.639976501464844, "x": 48.9048855119647, "y": 1.203761085325608, "z": null, "yaw": 0.5193601563846635, "pitch": null, "roll": null}, "v": 1.2378948192443333, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2772185767973363, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.31199837156330334, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141184.0718656} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22854142774292438, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.231049861382317, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141184.0718656} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.639976501464844, "x": 48.9048855119647, "y": 1.203761085325608, "z": null, "yaw": 0.5193601563846635, "pitch": null, "roll": null}, "v": 1.2378948192443333, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2772185767973363, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.31199837156330334, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141184.0918655} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22854142774292438, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2290841268389538, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141184.0918655} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141184.1118655, "x": 53.02177112820831, "y": 6.272551647226214, "z": null, "yaw": 0.5470844996313009, "pitch": null, "roll": null}, "v": 1.2271213237442251, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27641433361908907, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.3092830253159297, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141184.1118655} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22937496649621206, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2261931158140476, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141184.1118655} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.74997639656067, "x": 49.02177112820831, "y": 1.272551647226214, "z": null, "yaw": 0.5470844996313009, "pitch": null, "roll": null}, "v": 1.2271213237442251, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27641433361908907, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.3092830253159297, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141184.1218655} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2289167673807467, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2243387747336045, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141184.1218655} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.74997639656067, "x": 49.02177112820831, "y": 1.272551647226214, "z": null, "yaw": 0.5470844996313009, "pitch": null, "roll": null}, "v": 1.2271213237442251, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27641433361908907, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.3092830253159297, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141184.1518655} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2289167673807467, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2224299418820956, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141184.1518655} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.74997639656067, "x": 49.02177112820831, "y": 1.272551647226214, "z": null, "yaw": 0.5470844996313009, "pitch": null, "roll": null}, "v": 1.2271213237442251, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27641433361908907, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.3092830253159297, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141184.1718655} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2289167673807467, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2214765913761703, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141184.1718655} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.74997639656067, "x": 49.02177112820831, "y": 1.272551647226214, "z": null, "yaw": 0.5470844996313009, "pitch": null, "roll": null}, "v": 1.2271213237442251, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27641433361908907, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.3092830253159297, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141184.1918654} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2289167673807467, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2195720186500967, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141184.1918654} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.74997639656067, "x": 49.02177112820831, "y": 1.272551647226214, "z": null, "yaw": 0.5470844996313009, "pitch": null, "roll": null}, "v": 1.2271213237442251, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27641433361908907, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.3092830253159297, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141184.2118654} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2289167673807467, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2176702789107885, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141184.2118654} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141184.2218654, "x": 53.135718266487345, "y": 6.343937896597713, "z": null, "yaw": 0.5748088428779383, "pitch": null, "roll": null}, "v": 1.2167204696418155, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2756401104945448, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.3066615994141716, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141184.2318654} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2402863259887329, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2157713664981666, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141184.2318654} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.859976291656494, "x": 49.135718266487345, "y": 1.343937896597713, "z": null, "yaw": 0.5748088428779383, "pitch": null, "roll": null}, "v": 1.2167204696418155, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2756401104945448, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.3066615994141716, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141184.2518654} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2348132592985478, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2152959425938028, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141184.2518654} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.859976291656494, "x": 49.135718266487345, "y": 1.343937896597713, "z": null, "yaw": 0.5748088428779383, "pitch": null, "roll": null}, "v": 1.2167204696418155, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2756401104945448, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.3066615994141716, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141184.2718654} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2348132592985478, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2141373457972977, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141184.2718654} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.859976291656494, "x": 49.135718266487345, "y": 1.343937896597713, "z": null, "yaw": 0.5748088428779383, "pitch": null, "roll": null}, "v": 1.2167204696418155, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2756401104945448, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.3066615994141716, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141184.2918653} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2348132592985478, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2129804697707243, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141184.2918653} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.859976291656494, "x": 49.135718266487345, "y": 1.343937896597713, "z": null, "yaw": 0.5748088428779383, "pitch": null, "roll": null}, "v": 1.2167204696418155, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2756401104945448, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.3066615994141716, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141184.3118653} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2348132592985478, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2118253114232163, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141184.3118653} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141184.3318653, "x": 53.24687295098099, "y": 6.417944275685628, "z": null, "yaw": 0.6025331861245757, "pitch": null, "roll": null}, "v": 1.2106718676708803, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.275190857095241, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.3051371128941308, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141184.3318653} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23040062088353236, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2106718676708803, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141184.3318653} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.96997618675232, "x": 49.24687295098099, "y": 1.4179442756856284, "z": null, "yaw": 0.6025331861245757, "pitch": null, "roll": null}, "v": 1.2106718676708803, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.275190857095241, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.3051371128941308, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141184.3518653} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2324676494737829, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2082473434343304, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141184.3518653} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.96997618675232, "x": 49.24687295098099, "y": 1.4179442756856284, "z": null, "yaw": 0.6025331861245757, "pitch": null, "roll": null}, "v": 1.2106718676708803, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.275190857095241, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.3051371128941308, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141184.3718653} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2324676494737829, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.207526461690433, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141184.3718653} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.96997618675232, "x": 49.24687295098099, "y": 1.4179442756856284, "z": null, "yaw": 0.6025331861245757, "pitch": null, "roll": null}, "v": 1.2106718676708803, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.275190857095241, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.3051371128941308, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141184.3918653} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2324676494737829, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2060863014711662, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141184.3918653} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.96997618675232, "x": 49.24687295098099, "y": 1.4179442756856284, "z": null, "yaw": 0.6025331861245757, "pitch": null, "roll": null}, "v": 1.2106718676708803, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.275190857095241, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.3051371128941308, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141184.4118652} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2324676494737829, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.203930061818737, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141184.4118652} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.96997618675232, "x": 49.24687295098099, "y": 1.4179442756856284, "z": null, "yaw": 0.6025331861245757, "pitch": null, "roll": null}, "v": 1.2106718676708803, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.275190857095241, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.3051371128941308, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141184.4318652} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2324676494737829, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2032123801205639, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141184.4318652} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141184.4418652, "x": 53.355289331850365, "y": 6.494547715124633, "z": null, "yaw": 0.6302575293712132, "pitch": null, "roll": null}, "v": 1.2024952300194476, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27458470928316764, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.30307627735911535, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141184.4518652} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23419809453486873, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.201170675438657, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141184.4518652} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.079976081848145, "x": 49.355289331850365, "y": 1.4945477151246331, "z": null, "yaw": 0.6302575293712132, "pitch": null, "roll": null}, "v": 1.2024952300194476, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27458470928316764, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.30307627735911535, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141184.4718652} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2333278899520599, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2005631899102136, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141184.4718652} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.079976081848145, "x": 49.355289331850365, "y": 1.4945477151246331, "z": null, "yaw": 0.6302575293712132, "pitch": null, "roll": null}, "v": 1.2024952300194476, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27458470928316764, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.30307627735911535, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141184.4918652} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2333278899520599, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1992408320539867, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141184.4918652} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.079976081848145, "x": 49.355289331850365, "y": 1.4945477151246331, "z": null, "yaw": 0.6302575293712132, "pitch": null, "roll": null}, "v": 1.2024952300194476, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27458470928316764, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.30307627735911535, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141184.5118651} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2333278899520599, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1979204303368025, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141184.5118651} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.079976081848145, "x": 49.355289331850365, "y": 1.4945477151246331, "z": null, "yaw": 0.6302575293712132, "pitch": null, "roll": null}, "v": 1.2024952300194476, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27458470928316764, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.30307627735911535, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141184.5318651} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2333278899520599, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.196601981167855, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141184.5318651} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141184.551865, "x": 53.46086948420948, "y": 6.573624774360018, "z": null, "yaw": 0.6579818726178506, "pitch": null, "roll": null}, "v": 1.1952854809647406, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27405134785828816, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.3012591359271625, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141184.551865} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23808733615594857, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1952854809647406, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141184.551865} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.18997597694397, "x": 49.46086948420948, "y": 1.5736247743600176, "z": null, "yaw": 0.6579818726178506, "pitch": null, "roll": null}, "v": 1.1952854809647406, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27405134785828816, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.3012591359271625, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141184.571865} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23578029498830483, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1945656371152842, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141184.571865} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.18997597694397, "x": 49.46086948420948, "y": 1.5736247743600176, "z": null, "yaw": 0.6579818726178506, "pitch": null, "roll": null}, "v": 1.1952854809647406, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27405134785828816, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.3012591359271625, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141184.591865} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23578029498830483, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.193558583114272, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141184.591865} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.18997597694397, "x": 49.46086948420948, "y": 1.5736247743600176, "z": null, "yaw": 0.6579818726178506, "pitch": null, "roll": null}, "v": 1.1952854809647406, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27405134785828816, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.3012591359271625, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141184.611865} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23578029498830483, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1925530165102736, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141184.611865} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.18997597694397, "x": 49.46086948420948, "y": 1.5736247743600176, "z": null, "yaw": 0.6579818726178506, "pitch": null, "roll": null}, "v": 1.1952854809647406, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27405134785828816, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.3012591359271625, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141184.631865} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23578029498830483, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1915489347021189, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141184.631865} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.18997597694397, "x": 49.46086948420948, "y": 1.5736247743600176, "z": null, "yaw": 0.6579818726178506, "pitch": null, "roll": null}, "v": 1.1952854809647406, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27405134785828816, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.3012591359271625, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141184.651865} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23578029498830483, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1905463350942704, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141184.651865} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141184.661865, "x": 53.563681934780504, "y": 6.655174402090081, "z": null, "yaw": 0.685706215864488, "pitch": null, "roll": null}, "v": 1.1900455903058917, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2736643645853596, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2999384765889737, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141184.671865} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22773263619579354, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.189545215096807, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141184.671865} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.299975872039795, "x": 49.563681934780504, "y": 1.655174402090081, "z": null, "yaw": 0.685706215864488, "pitch": null, "roll": null}, "v": 1.1900455903058917, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2736643645853596, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2999384765889737, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141184.691865} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23153537212820852, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1875399858532611, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141184.691865} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.299975872039795, "x": 49.563681934780504, "y": 1.655174402090081, "z": null, "yaw": 0.685706215864488, "pitch": null, "roll": null}, "v": 1.1900455903058917, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2736643645853596, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2999384765889737, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141184.711865} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23153537212820852, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1860128804154362, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141184.711865} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.299975872039795, "x": 49.563681934780504, "y": 1.655174402090081, "z": null, "yaw": 0.685706215864488, "pitch": null, "roll": null}, "v": 1.1900455903058917, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2736643645853596, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2999384765889737, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141184.731865} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23153537212820852, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1844880259529234, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141184.731865} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.299975872039795, "x": 49.563681934780504, "y": 1.655174402090081, "z": null, "yaw": 0.685706215864488, "pitch": null, "roll": null}, "v": 1.1900455903058917, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2736643645853596, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2999384765889737, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141184.751865} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23153537212820852, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1814450529734029, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141184.751865} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141184.771865, "x": 53.66361193930969, "y": 6.739052808237877, "z": null, "yaw": 0.7134305591111254, "pitch": null, "roll": null}, "v": 1.1814450529734029, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2730303767806234, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.29777080159705155, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141184.781865} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2319638843340241, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1806857099636097, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141184.781865} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.40997576713562, "x": 49.66361193930969, "y": 1.7390528082378767, "z": null, "yaw": 0.7134305591111254, "pitch": null, "roll": null}, "v": 1.1814450529734029, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2730303767806234, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.29777080159705155, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141184.8018649} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.231711526943878, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1784755476477988, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141184.8018649} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.40997576713562, "x": 49.66361193930969, "y": 1.7390528082378767, "z": null, "yaw": 0.7134305591111254, "pitch": null, "roll": null}, "v": 1.1814450529734029, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2730303767806234, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.29777080159705155, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141184.8218648} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.231711526943878, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.177729399846327, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141184.8218648} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.40997576713562, "x": 49.66361193930969, "y": 1.7390528082378767, "z": null, "yaw": 0.7134305591111254, "pitch": null, "roll": null}, "v": 1.1814450529734029, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2730303767806234, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.29777080159705155, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141184.8418648} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.231711526943878, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1762387503732348, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141184.8418648} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.40997576713562, "x": 49.66361193930969, "y": 1.7390528082378767, "z": null, "yaw": 0.7134305591111254, "pitch": null, "roll": null}, "v": 1.1814450529734029, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2730303767806234, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.29777080159705155, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141184.8618648} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.231711526943878, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.174006883772687, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141184.8618648} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141184.8818648, "x": 53.76048946744016, "y": 6.825057713524724, "z": null, "yaw": 0.7411549023577628, "pitch": null, "roll": null}, "v": 1.1732640215484784, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.272428685720025, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.29570885865763225, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141184.8818648} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2322227797171631, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1732640215484784, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141184.8818648} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.519975662231445, "x": 49.76048946744016, "y": 1.825057713524724, "z": null, "yaw": 0.7411549023577628, "pitch": null, "roll": null}, "v": 1.1732640215484784, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.272428685720025, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.29570885865763225, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141184.9018648} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23193348274265574, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1718438171185235, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141184.9018648} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.519975662231445, "x": 49.76048946744016, "y": 1.825057713524724, "z": null, "yaw": 0.7411549023577628, "pitch": null, "roll": null}, "v": 1.1732640215484784, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.272428685720025, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.29570885865763225, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141184.9218647} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23193348274265574, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1703895491855771, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141184.9218647} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.519975662231445, "x": 49.76048946744016, "y": 1.825057713524724, "z": null, "yaw": 0.7411549023577628, "pitch": null, "roll": null}, "v": 1.1732640215484784, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.272428685720025, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.29570885865763225, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141184.9418647} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23193348274265574, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1689374157723098, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141184.9418647} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.519975662231445, "x": 49.76048946744016, "y": 1.825057713524724, "z": null, "yaw": 0.7411549023577628, "pitch": null, "roll": null}, "v": 1.1732640215484784, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.272428685720025, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.29570885865763225, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141184.9618647} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23193348274265574, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1674874129025865, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141184.9618647} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.519975662231445, "x": 49.76048946744016, "y": 1.825057713524724, "z": null, "yaw": 0.7411549023577628, "pitch": null, "roll": null}, "v": 1.1732640215484784, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.272428685720025, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.29570885865763225, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141184.9818647} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23193348274265574, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.166039536609818, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141184.9818647} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141184.9918647, "x": 53.85429878223266, "y": 6.913107996403159, "z": null, "yaw": 0.7688792456044002, "pitch": null, "roll": null}, "v": 1.1653163946928353, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27184544273204087, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2937057428854319, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141185.0018647} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25266517182909665, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1645937829369308, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141185.0018647} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.62997555732727, "x": 49.85429878223266, "y": 1.9131079964031592, "z": null, "yaw": 0.7688792456044002, "pitch": null, "roll": null}, "v": 1.1653163946928353, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27184544273204087, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2937057428854319, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141185.0218647} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24274849641598956, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1657406594261421, "gear": 1, "accelerator_pedal_position": 0.25266517182909665, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141185.0218647} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.62997555732727, "x": 49.85429878223266, "y": 1.9131079964031592, "z": null, "yaw": 0.7688792456044002, "pitch": null, "roll": null}, "v": 1.1653163946928353, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27184544273204087, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2937057428854319, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141185.0418646} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24274849641598956, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1656467250080347, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141185.0418646} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.62997555732727, "x": 49.85429878223266, "y": 1.9131079964031592, "z": null, "yaw": 0.7688792456044002, "pitch": null, "roll": null}, "v": 1.1653163946928353, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27184544273204087, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2937057428854319, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141185.0618646} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24274849641598956, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1655529282724784, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141185.0618646} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.62997555732727, "x": 49.85429878223266, "y": 1.9131079964031592, "z": null, "yaw": 0.7688792456044002, "pitch": null, "roll": null}, "v": 1.1653163946928353, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27184544273204087, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2937057428854319, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141185.0818646} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24274849641598956, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1654592690141499, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141185.0818646} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141185.1018646, "x": 53.94529907477361, "y": 7.003398340121839, "z": null, "yaw": 0.7966035888510377, "pitch": null, "roll": null}, "v": 1.1653657470280423, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2718490605948644, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2937181816225346, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141185.1018646} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21776553959455913, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1653657470280423, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141185.1018646} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.739975452423096, "x": 49.94529907477361, "y": 2.003398340121839, "z": null, "yaw": 0.7966035888510377, "pitch": null, "roll": null}, "v": 1.1653657470280423, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2718490605948644, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2937181816225346, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141185.1218646} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22966246728972867, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1621506368943182, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141185.1218646} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.739975452423096, "x": 49.94529907477361, "y": 2.003398340121839, "z": null, "yaw": 0.7966035888510377, "pitch": null, "roll": null}, "v": 1.1653657470280423, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2718490605948644, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2937181816225346, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141185.1418645} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22966246728972867, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.160426807297341, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141185.1418645} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.739975452423096, "x": 49.94529907477361, "y": 2.003398340121839, "z": null, "yaw": 0.7966035888510377, "pitch": null, "roll": null}, "v": 1.1653657470280423, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2718490605948644, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2937181816225346, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141185.1618645} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22966246728972867, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.158705501054356, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141185.1618645} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.739975452423096, "x": 49.94529907477361, "y": 2.003398340121839, "z": null, "yaw": 0.7966035888510377, "pitch": null, "roll": null}, "v": 1.1653657470280423, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2718490605948644, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2937181816225346, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141185.1818645} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22966246728972867, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1569867132869356, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141185.1818645} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.739975452423096, "x": 49.94529907477361, "y": 2.003398340121839, "z": null, "yaw": 0.7966035888510377, "pitch": null, "roll": null}, "v": 1.1653657470280423, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2718490605948644, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2937181816225346, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141185.2018645} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22966246728972867, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1552704391289894, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141185.2018645} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141185.2118645, "x": 54.03333427955685, "y": 7.095724545652309, "z": null, "yaw": 0.8243279320976751, "pitch": null, "roll": null}, "v": 1.1544132431362804, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27104736151609826, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2909577181924861, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141185.2218645} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23303096398554335, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1535566737267273, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141185.2218645} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.84997534751892, "x": 50.03333427955685, "y": 2.095724545652309, "z": null, "yaw": 0.8243279320976751, "pitch": null, "roll": null}, "v": 1.1544132431362804, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27104736151609826, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2909577181924861, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141185.2418644} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2313658352735401, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1522663205197852, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141185.2418644} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.84997534751892, "x": 50.03333427955685, "y": 2.095724545652309, "z": null, "yaw": 0.8243279320976751, "pitch": null, "roll": null}, "v": 1.1544132431362804, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27104736151609826, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2909577181924861, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141185.2618644} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2313658352735401, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.150769786791395, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141185.2618644} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.84997534751892, "x": 50.03333427955685, "y": 2.095724545652309, "z": null, "yaw": 0.8243279320976751, "pitch": null, "roll": null}, "v": 1.1544132431362804, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27104736151609826, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2909577181924861, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141185.2818644} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2313658352735401, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1492754378890935, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141185.2818644} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.84997534751892, "x": 50.03333427955685, "y": 2.095724545652309, "z": null, "yaw": 0.8243279320976751, "pitch": null, "roll": null}, "v": 1.1544132431362804, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27104736151609826, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2909577181924861, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141185.3018644} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2313658352735401, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1477832697302937, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141185.3018644} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141185.3218644, "x": 54.11811007600361, "y": 7.189717915538396, "z": null, "yaw": 0.8520522753443125, "pitch": null, "roll": null}, "v": 1.1462932782422763, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27045454670954805, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2889111664300133, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141185.3218644} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23311598772630865, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1462932782422763, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141185.3218644} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.959975242614746, "x": 50.11811007600361, "y": 2.189717915538396, "z": null, "yaw": 0.8520522753443125, "pitch": null, "roll": null}, "v": 1.1462932782422763, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27045454670954805, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2889111664300133, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141185.3418643} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23223741451512933, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1450241486642256, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141185.3418643} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.959975242614746, "x": 50.11811007600361, "y": 2.189717915538396, "z": null, "yaw": 0.8520522753443125, "pitch": null, "roll": null}, "v": 1.1462932782422763, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27045454670954805, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2889111664300133, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141185.3618643} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23223741451512933, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1429593093449715, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141185.3618643} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.959975242614746, "x": 50.11811007600361, "y": 2.189717915538396, "z": null, "yaw": 0.8520522753443125, "pitch": null, "roll": null}, "v": 1.1462932782422763, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27045454670954805, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2889111664300133, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141185.3818643} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23223741451512933, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1422720324992128, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141185.3818643} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.959975242614746, "x": 50.11811007600361, "y": 2.189717915538396, "z": null, "yaw": 0.8520522753443125, "pitch": null, "roll": null}, "v": 1.1462932782422763, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27045454670954805, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2889111664300133, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141185.4018643} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23223741451512933, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1408989804398044, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141185.4018643} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.959975242614746, "x": 50.11811007600361, "y": 2.189717915538396, "z": null, "yaw": 0.8520522753443125, "pitch": null, "roll": null}, "v": 1.1462932782422763, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27045454670954805, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2889111664300133, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141185.4218643} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23223741451512933, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1395279274983368, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141185.4218643} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141185.4318643, "x": 54.19969172736096, "y": 7.285373507057322, "z": null, "yaw": 0.8797766185909499, "pitch": null, "roll": null}, "v": 1.1388431495520284, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26991179467041726, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.28703343983874013, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141185.4418643} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23190127519855375, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1381588700125198, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141185.4418643} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.06997513771057, "x": 50.19969172736096, "y": 2.2853735070573222, "z": null, "yaw": 0.8797766185909499, "pitch": null, "roll": null}, "v": 1.1388431495520284, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26991179467041726, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.28703343983874013, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141185.4618642} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23201998906276824, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1367498021977898, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141185.4618642} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.06997513771057, "x": 50.19969172736096, "y": 2.2853735070573222, "z": null, "yaw": 0.8797766185909499, "pitch": null, "roll": null}, "v": 1.1388431495520284, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26991179467041726, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.28703343983874013, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141185.4818642} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23201998906276824, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1353576174443305, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141185.4818642} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.06997513771057, "x": 50.19969172736096, "y": 2.2853735070573222, "z": null, "yaw": 0.8797766185909499, "pitch": null, "roll": null}, "v": 1.1388431495520284, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26991179467041726, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.28703343983874013, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141185.5018642} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23201998906276824, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.133967456584443, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141185.5018642} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.06997513771057, "x": 50.19969172736096, "y": 2.2853735070573222, "z": null, "yaw": 0.8797766185909499, "pitch": null, "roll": null}, "v": 1.1388431495520284, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26991179467041726, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.28703343983874013, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141185.5218642} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23201998906276824, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.132579315903147, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141185.5218642} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141185.5418642, "x": 54.278066855071074, "y": 7.382604282141002, "z": null, "yaw": 0.9075009618375873, "pitch": null, "roll": null}, "v": 1.131193191694229, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2693556399540652, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.28510534840717705, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141185.5418642} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.221800702456456, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.131193191694229, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141185.5418642} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.179975032806396, "x": 50.278066855071074, "y": 2.382604282141002, "z": null, "yaw": 0.9075009618375873, "pitch": null, "roll": null}, "v": 1.131193191694229, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2693556399540652, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.28510534840717705, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141185.5618641} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22662465812894494, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.128532133157748, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141185.5618641} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.179975032806396, "x": 50.278066855071074, "y": 2.382604282141002, "z": null, "yaw": 0.9075009618375873, "pitch": null, "roll": null}, "v": 1.131193191694229, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2693556399540652, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.28510534840717705, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141185.581864} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22662465812894494, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1264777119538871, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141185.581864} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.179975032806396, "x": 50.278066855071074, "y": 2.382604282141002, "z": null, "yaw": 0.9075009618375873, "pitch": null, "roll": null}, "v": 1.131193191694229, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2693556399540652, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.28510534840717705, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141185.601864} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22662465812894494, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1244262702162846, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141185.601864} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.179975032806396, "x": 50.278066855071074, "y": 2.382604282141002, "z": null, "yaw": 0.9075009618375873, "pitch": null, "roll": null}, "v": 1.131193191694229, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2693556399540652, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.28510534840717705, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141185.621864} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22662465812894494, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1223778019411532, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141185.621864} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.179975032806396, "x": 50.278066855071074, "y": 2.382604282141002, "z": null, "yaw": 0.9075009618375873, "pitch": null, "roll": null}, "v": 1.131193191694229, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2693556399540652, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.28510534840717705, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141185.641864} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22662465812894494, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.120332301140726, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141185.641864} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141185.651864, "x": 54.35306275355269, "y": 7.481109839455847, "z": null, "yaw": 0.9352253050842247, "pitch": null, "roll": null}, "v": 1.1193106616767168, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26849409665726753, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.28211048167223185, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141185.661864} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2324528388991174, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.118289761843203, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141185.661864} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.28997492790222, "x": 50.35306275355269, "y": 2.481109839455847, "z": null, "yaw": 0.9352253050842247, "pitch": null, "roll": null}, "v": 1.1193106616767168, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26849409665726753, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.28211048167223185, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141185.681864} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22961187190961593, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1169784371494373, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141185.681864} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.28997492790222, "x": 50.35306275355269, "y": 2.481109839455847, "z": null, "yaw": 0.9352253050842247, "pitch": null, "roll": null}, "v": 1.1193106616767168, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26849409665726753, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.28211048167223185, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141185.701864} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22961187190961593, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1153140167009603, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141185.701864} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.28997492790222, "x": 50.35306275355269, "y": 2.481109839455847, "z": null, "yaw": 0.9352253050842247, "pitch": null, "roll": null}, "v": 1.1193106616767168, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26849409665726753, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.28211048167223185, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141185.721864} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22961187190961593, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1136520026202514, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141185.721864} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.28997492790222, "x": 50.35306275355269, "y": 2.481109839455847, "z": null, "yaw": 0.9352253050842247, "pitch": null, "roll": null}, "v": 1.1193106616767168, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26849409665726753, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.28211048167223185, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141185.741864} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22961187190961593, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.111992390323741, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141185.741864} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141185.761864, "x": 54.42463857003546, "y": 7.580738157588129, "z": null, "yaw": 0.9629496483308622, "pitch": null, "roll": null}, "v": 1.110335175239272, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26784520077569984, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.27984830470134775, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141185.761864} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22618621967708322, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.110335175239272, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141185.761864} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.399974822998047, "x": 50.42463857003546, "y": 2.5807381575881294, "z": null, "yaw": 0.9629496483308622, "pitch": null, "roll": null}, "v": 1.110335175239272, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26784520077569984, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.27984830470134775, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141185.781864} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2277680437489315, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1082523008338807, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141185.781864} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.399974822998047, "x": 50.42463857003546, "y": 2.5807381575881294, "z": null, "yaw": 0.9629496483308622, "pitch": null, "roll": null}, "v": 1.110335175239272, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26784520077569984, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.27984830470134775, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141185.801864} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2277680437489315, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1063700886753165, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141185.801864} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.399974822998047, "x": 50.42463857003546, "y": 2.5807381575881294, "z": null, "yaw": 0.9629496483308622, "pitch": null, "roll": null}, "v": 1.110335175239272, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26784520077569984, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.27984830470134775, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141185.821864} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2277680437489315, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1044905910731535, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141185.821864} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.399974822998047, "x": 50.42463857003546, "y": 2.5807381575881294, "z": null, "yaw": 0.9629496483308622, "pitch": null, "roll": null}, "v": 1.110335175239272, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26784520077569984, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.27984830470134775, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141185.8418639} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2277680437489315, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1026138026999195, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141185.8418639} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.399974822998047, "x": 50.42463857003546, "y": 2.5807381575881294, "z": null, "yaw": 0.9629496483308622, "pitch": null, "roll": null}, "v": 1.110335175239272, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26784520077569984, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.27984830470134775, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141185.8618639} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2277680437489315, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1007397182419307, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141185.8618639} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141185.8718638, "x": 54.492821455303684, "y": 7.681420186392918, "z": null, "yaw": 0.9906739915774996, "pitch": null, "roll": null}, "v": 1.0998036883243865, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2670858659447386, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2771939541729318, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141185.8818638} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23775711118674894, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0988683323992472, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141185.8818638} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.509974718093872, "x": 50.492821455303684, "y": 2.681420186392918, "z": null, "yaw": 0.9906739915774996, "pitch": null, "roll": null}, "v": 1.0998036883243865, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2670858659447386, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2771939541729318, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141185.9018638} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23294255591939622, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.098247824026355, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141185.9018638} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.509974718093872, "x": 50.492821455303684, "y": 2.681420186392918, "z": null, "yaw": 0.9906739915774996, "pitch": null, "roll": null}, "v": 1.0998036883243865, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2670858659447386, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2771939541729318, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141185.9218638} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23294255591939622, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0970266055811668, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141185.9218638} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.509974718093872, "x": 50.492821455303684, "y": 2.681420186392918, "z": null, "yaw": 0.9906739915774996, "pitch": null, "roll": null}, "v": 1.0998036883243865, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2670858659447386, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2771939541729318, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141185.9418638} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23294255591939622, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0958071437551238, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141185.9418638} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.509974718093872, "x": 50.492821455303684, "y": 2.681420186392918, "z": null, "yaw": 0.9906739915774996, "pitch": null, "roll": null}, "v": 1.0998036883243865, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2670858659447386, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2771939541729318, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141185.9618638} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23294255591939622, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0945894354268566, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141185.9618638} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141185.9818637, "x": 54.55768135376727, "y": 7.783162152464809, "z": null, "yaw": 1.018398334824137, "pitch": null, "roll": null}, "v": 1.0933734774820505, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26662332948671447, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.27557328714983026, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141185.9818637} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23059063721099912, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0933734774820505, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141185.9818637} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.619974613189697, "x": 50.55768135376727, "y": 2.7831621524648087, "z": null, "yaw": 1.018398334824137, "pitch": null, "roll": null}, "v": 1.0933734774820505, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26662332948671447, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.27557328714983026, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141186.0018637} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23167535816958523, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0918653825963878, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141186.0018637} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.619974613189697, "x": 50.55768135376727, "y": 2.7831621524648087, "z": null, "yaw": 1.018398334824137, "pitch": null, "roll": null}, "v": 1.0933734774820505, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26662332948671447, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.27557328714983026, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141186.0218637} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23167535816958523, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0904949953367673, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141186.0218637} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.619974613189697, "x": 50.55768135376727, "y": 2.7831621524648087, "z": null, "yaw": 1.018398334824137, "pitch": null, "roll": null}, "v": 1.0933734774820505, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26662332948671447, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.27557328714983026, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141186.0418637} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23167535816958523, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.089126575705652, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141186.0418637} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.619974613189697, "x": 50.55768135376727, "y": 2.7831621524648087, "z": null, "yaw": 1.018398334824137, "pitch": null, "roll": null}, "v": 1.0933734774820505, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26662332948671447, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.27557328714983026, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141186.0618637} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23167535816958523, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0877601201291227, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141186.0618637} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.619974613189697, "x": 50.55768135376727, "y": 2.7831621524648087, "z": null, "yaw": 1.018398334824137, "pitch": null, "roll": null}, "v": 1.0933734774820505, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26662332948671447, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.27557328714983026, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141186.0818636} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23167535816958523, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0863956250416138, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141186.0818636} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141186.0918636, "x": 54.61929544518396, "y": 7.885993842978079, "z": null, "yaw": 1.0461226780707744, "pitch": null, "roll": null}, "v": 1.0857141115692812, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2660734568990708, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2736428245169466, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141186.1018636} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23042541332479505, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0850330868858895, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141186.1018636} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.729974508285522, "x": 50.61929544518396, "y": 2.8859938429780794, "z": null, "yaw": 1.0461226780707744, "pitch": null, "roll": null}, "v": 1.0857141115692812, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2660734568990708, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2736428245169466, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141186.1218636} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2309787303777569, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0835163150098472, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141186.1218636} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.729974508285522, "x": 50.61929544518396, "y": 2.8859938429780794, "z": null, "yaw": 1.0461226780707744, "pitch": null, "roll": null}, "v": 1.0857141115692812, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2660734568990708, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2736428245169466, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141186.1418636} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2309787303777569, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.081348904073308, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141186.1418636} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.729974508285522, "x": 50.61929544518396, "y": 2.8859938429780794, "z": null, "yaw": 1.0461226780707744, "pitch": null, "roll": null}, "v": 1.0857141115692812, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2660734568990708, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2736428245169466, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141186.1618636} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2309787303777569, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.080627468724647, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141186.1618636} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.729974508285522, "x": 50.61929544518396, "y": 2.8859938429780794, "z": null, "yaw": 1.0461226780707744, "pitch": null, "roll": null}, "v": 1.0857141115692812, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2660734568990708, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2736428245169466, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141186.1918635} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2309787303777569, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0777468894953945, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141186.1918635} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141186.2018635, "x": 54.67761786706798, "y": 7.989751190331485, "z": null, "yaw": 1.0738470213174118, "pitch": null, "roll": null}, "v": 1.0777468894953945, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26550272805293973, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.27163476997605007, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141186.2118635} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22724911017463648, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0760765892946005, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141186.2118635} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.839974403381348, "x": 50.67761786706798, "y": 2.989751190331485, "z": null, "yaw": 1.0738470213174118, "pitch": null, "roll": null}, "v": 1.0777468894953945, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26550272805293973, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.27163476997605007, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141186.2318635} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22898163655808026, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0751258263032653, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141186.2318635} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.839974403381348, "x": 50.67761786706798, "y": 2.989751190331485, "z": null, "yaw": 1.0738470213174118, "pitch": null, "roll": null}, "v": 1.0777468894953945, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26550272805293973, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.27163476997605007, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141186.2518635} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22898163655808026, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0734428277756969, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141186.2518635} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.839974403381348, "x": 50.67761786706798, "y": 2.989751190331485, "z": null, "yaw": 1.0738470213174118, "pitch": null, "roll": null}, "v": 1.0777468894953945, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26550272805293973, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.27163476997605007, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141186.2718635} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22898163655808026, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.070922838050276, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141186.2718635} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.839974403381348, "x": 50.67761786706798, "y": 2.989751190331485, "z": null, "yaw": 1.0738470213174118, "pitch": null, "roll": null}, "v": 1.0777468894953945, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26550272805293973, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.27163476997605007, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141186.2918634} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22898163655808026, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.070084041343625, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141186.2918634} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141186.3118634, "x": 54.732601409128335, "y": 8.094247935427179, "z": null, "yaw": 1.1015713645640492, "pitch": null, "roll": null}, "v": 1.068408244317938, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2648353739811623, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.26928106266370133, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141186.3118634} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2313095422570049, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0675712428630062, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141186.3118634} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.949974298477173, "x": 50.732601409128335, "y": 3.0942479354271786, "z": null, "yaw": 1.1015713645640492, "pitch": null, "roll": null}, "v": 1.068408244317938, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2648353739811623, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.26928106266370133, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141186.3318634} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23015016913003356, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0661899156569923, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141186.3318634} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.949974298477173, "x": 50.732601409128335, "y": 3.0942479354271786, "z": null, "yaw": 1.1015713645640492, "pitch": null, "roll": null}, "v": 1.068408244317938, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2648353739811623, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.26928106266370133, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141186.3518634} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23015016913003356, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0646656883994994, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141186.3518634} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.949974298477173, "x": 50.732601409128335, "y": 3.0942479354271786, "z": null, "yaw": 1.1015713645640492, "pitch": null, "roll": null}, "v": 1.068408244317938, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2648353739811623, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.26928106266370133, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141186.3718634} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23015016913003356, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0631436339437683, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141186.3718634} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.949974298477173, "x": 50.732601409128335, "y": 3.0942479354271786, "z": null, "yaw": 1.1015713645640492, "pitch": null, "roll": null}, "v": 1.068408244317938, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2648353739811623, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.26928106266370133, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141186.3918633} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23015016913003356, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0616237482661177, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141186.3918633} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.949974298477173, "x": 50.732601409128335, "y": 3.0942479354271786, "z": null, "yaw": 1.1015713645640492, "pitch": null, "roll": null}, "v": 1.068408244317938, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2648353739811623, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.26928106266370133, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141186.4118633} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23015016913003356, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0608646174643235, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141186.4118633} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141186.4218633, "x": 54.78423800918613, "y": 8.199355924920626, "z": null, "yaw": 1.1292957078106867, "pitch": null, "roll": null}, "v": 1.0601060273525595, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2642435492599202, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2671885761831905, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141186.4318633} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24827788286445063, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0593479774305874, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141186.4318633} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.059974193572998, "x": 50.78423800918613, "y": 3.199355924920626, "z": null, "yaw": 1.1292957078106867, "pitch": null, "roll": null}, "v": 1.0601060273525595, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2642435492599202, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2671885761831905, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141186.4518633} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23960054248697057, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.059931257545543, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141186.4518633} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.059974193572998, "x": 50.78423800918613, "y": 3.199355924920626, "z": null, "yaw": 1.1292957078106867, "pitch": null, "roll": null}, "v": 1.0601060273525595, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2642435492599202, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2671885761831905, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141186.4718633} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23960054248697057, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0597639803951338, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141186.4718633} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.059974193572998, "x": 50.78423800918613, "y": 3.199355924920626, "z": null, "yaw": 1.1292957078106867, "pitch": null, "roll": null}, "v": 1.0601060273525595, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2642435492599202, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2671885761831905, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141186.4918633} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23960054248697057, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0592628631598477, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141186.4918633} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.059974193572998, "x": 50.78423800918613, "y": 3.199355924920626, "z": null, "yaw": 1.1292957078106867, "pitch": null, "roll": null}, "v": 1.0601060273525595, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2642435492599202, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2671885761831905, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141186.5118632} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23960054248697057, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.058929379280063, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141186.5118632} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141186.5318632, "x": 54.83270747329708, "y": 8.305348462371377, "z": null, "yaw": 1.157020051057324, "pitch": null, "roll": null}, "v": 1.0587628153528283, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2641479277593799, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2668500337237945, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141186.5318632} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21803907054917504, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0585963699806702, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141186.5318632} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.169974088668823, "x": 50.83270747329708, "y": 3.305348462371377, "z": null, "yaw": 1.157020051057324, "pitch": null, "roll": null}, "v": 1.0587628153528283, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2641479277593799, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2668500337237945, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141186.5518632} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2282991578163031, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.054699099269265, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141186.5518632} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.169974088668823, "x": 50.83270747329708, "y": 3.305348462371377, "z": null, "yaw": 1.157020051057324, "pitch": null, "roll": null}, "v": 1.0587628153528283, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2641479277593799, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2668500337237945, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141186.5718632} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2282991578163031, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0538292080641494, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141186.5718632} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.169974088668823, "x": 50.83270747329708, "y": 3.305348462371377, "z": null, "yaw": 1.157020051057324, "pitch": null, "roll": null}, "v": 1.0587628153528283, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2641479277593799, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2668500337237945, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141186.6018631} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2282991578163031, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.05122324227431, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141186.6018631} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.169974088668823, "x": 50.83270747329708, "y": 3.305348462371377, "z": null, "yaw": 1.157020051057324, "pitch": null, "roll": null}, "v": 1.0587628153528283, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2641479277593799, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2668500337237945, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141186.6218631} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2282991578163031, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.050355820986182, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141186.6218631} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141186.641863, "x": 54.87798559064078, "y": 8.412084816951632, "z": null, "yaw": 1.1847443943039615, "pitch": null, "roll": null}, "v": 1.0486228258403985, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.263427239600755, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2642943559987045, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141186.641863} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23154235446455054, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0486228258403985, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141186.641863} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.27997398376465, "x": 50.87798559064078, "y": 3.412084816951632, "z": null, "yaw": 1.1847443943039615, "pitch": null, "roll": null}, "v": 1.0486228258403985, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.263427239600755, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2642943559987045, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141186.661863} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22994306473533668, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0472975457713547, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141186.661863} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.27997398376465, "x": 50.87798559064078, "y": 3.412084816951632, "z": null, "yaw": 1.1847443943039615, "pitch": null, "roll": null}, "v": 1.0486228258403985, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.263427239600755, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2642943559987045, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141186.681863} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22994306473533668, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.045774305359996, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141186.681863} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.27997398376465, "x": 50.87798559064078, "y": 3.412084816951632, "z": null, "yaw": 1.1847443943039615, "pitch": null, "roll": null}, "v": 1.0486228258403985, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.263427239600755, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2642943559987045, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141186.701863} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22994306473533668, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0442532248412268, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141186.701863} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.27997398376465, "x": 50.87798559064078, "y": 3.412084816951632, "z": null, "yaw": 1.1847443943039615, "pitch": null, "roll": null}, "v": 1.0486228258403985, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.263427239600755, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2642943559987045, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141186.721863} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22994306473533668, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0427343002272618, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141186.721863} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.27997398376465, "x": 50.87798559064078, "y": 3.412084816951632, "z": null, "yaw": 1.1847443943039615, "pitch": null, "roll": null}, "v": 1.0486228258403985, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.263427239600755, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2642943559987045, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141186.741863} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22994306473533668, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.041217527539901, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141186.741863} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141186.751863, "x": 54.91992292518208, "y": 8.51910650923519, "z": null, "yaw": 1.212468737550599, "pitch": null, "roll": null}, "v": 1.040459946928124, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26284856635802295, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2622369882092078, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141186.761863} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2283915914794366, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0397029028105023, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141186.761863} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.389973878860474, "x": 50.91992292518208, "y": 3.51910650923519, "z": null, "yaw": 1.212468737550599, "pitch": null, "roll": null}, "v": 1.040459946928124, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26284856635802295, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2622369882092078, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141186.781863} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2290862992250749, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.037996556554283, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141186.781863} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.389973878860474, "x": 50.91992292518208, "y": 3.51910650923519, "z": null, "yaw": 1.212468737550599, "pitch": null, "roll": null}, "v": 1.040459946928124, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26284856635802295, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2622369882092078, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141186.801863} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2290862992250749, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.036379432305629, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141186.801863} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.389973878860474, "x": 50.91992292518208, "y": 3.51910650923519, "z": null, "yaw": 1.212468737550599, "pitch": null, "roll": null}, "v": 1.040459946928124, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26284856635802295, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2622369882092078, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141186.821863} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2290862992250749, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0347645950154154, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141186.821863} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.389973878860474, "x": 50.91992292518208, "y": 3.51910650923519, "z": null, "yaw": 1.212468737550599, "pitch": null, "roll": null}, "v": 1.040459946928124, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26284856635802295, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2622369882092078, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141186.841863} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2290862992250749, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0331520404066843, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141186.841863} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141186.861863, "x": 54.958557328263254, "y": 8.626360407126036, "z": null, "yaw": 1.2401930807972363, "pitch": null, "roll": null}, "v": 1.0315417642129456, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26221787232380284, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2599892540389185, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141186.861863} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22814379303233476, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0315417642129456, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141186.861863} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.4999737739563, "x": 50.958557328263254, "y": 3.626360407126036, "z": null, "yaw": 1.2401930807972363, "pitch": null, "roll": null}, "v": 1.0315417642129456, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26221787232380284, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2599892540389185, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141186.8818629} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22854455282646746, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.02981599050048, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141186.8818629} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.4999737739563, "x": 50.958557328263254, "y": 3.626360407126036, "z": null, "yaw": 1.2401930807972363, "pitch": null, "roll": null}, "v": 1.0315417642129456, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26221787232380284, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2599892540389185, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141186.9018629} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22854455282646746, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.027306985626214, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141186.9018629} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.4999737739563, "x": 50.958557328263254, "y": 3.626360407126036, "z": null, "yaw": 1.2401930807972363, "pitch": null, "roll": null}, "v": 1.0315417642129456, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26221787232380284, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2599892540389185, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141186.9218628} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22854455282646746, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0264718307207834, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141186.9218628} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.4999737739563, "x": 50.958557328263254, "y": 3.626360407126036, "z": null, "yaw": 1.2401930807972363, "pitch": null, "roll": null}, "v": 1.0315417642129456, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26221787232380284, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2599892540389185, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141186.9418628} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22854455282646746, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0248032876544293, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141186.9418628} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.4999737739563, "x": 50.958557328263254, "y": 3.626360407126036, "z": null, "yaw": 1.2401930807972363, "pitch": null, "roll": null}, "v": 1.0315417642129456, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26221787232380284, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2599892540389185, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141186.9618628} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22854455282646746, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0231370965516, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141186.9618628} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141186.9718628, "x": 54.99389148901977, "y": 8.733695307589265, "z": null, "yaw": 1.2679174240438738, "pitch": null, "roll": null}, "v": 1.0223048816031444, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2615663167896534, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2576611949116183, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141186.9818628} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24474279393453405, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.021473252986902, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141186.9818628} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.609973669052124, "x": 50.99389148901977, "y": 3.733695307589265, "z": null, "yaw": 1.2679174240438738, "pitch": null, "roll": null}, "v": 1.0223048816031444, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2615663167896534, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2576611949116183, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141187.0018628} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2369796995834195, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.021835819729243, "gear": 1, "accelerator_pedal_position": 0.24474279393453405, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141187.0018628} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.609973669052124, "x": 50.99389148901977, "y": 3.733695307589265, "z": null, "yaw": 1.2679174240438738, "pitch": null, "roll": null}, "v": 1.0223048816031444, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2615663167896534, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2576611949116183, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141187.0218627} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2369796995834195, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0212278308588294, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141187.0218627} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.609973669052124, "x": 50.99389148901977, "y": 3.733695307589265, "z": null, "yaw": 1.2679174240438738, "pitch": null, "roll": null}, "v": 1.0223048816031444, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2615663167896534, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2576611949116183, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141187.0418627} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2369796995834195, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.020620698070761, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141187.0418627} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.609973669052124, "x": 50.99389148901977, "y": 3.733695307589265, "z": null, "yaw": 1.2679174240438738, "pitch": null, "roll": null}, "v": 1.0223048816031444, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2615663167896534, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2576611949116183, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141187.0618627} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2369796995834195, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0197116010844884, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141187.0618627} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141187.0818627, "x": 55.02603795302883, "y": 8.84130908169531, "z": null, "yaw": 1.2956417672905112, "pitch": null, "roll": null}, "v": 1.0194089953329712, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26136239676430634, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2569313172301865, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141187.0818627} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22799399375384535, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0194089953329712, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141187.0818627} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.71997356414795, "x": 51.02603795302883, "y": 3.841309081695311, "z": null, "yaw": 1.2956417672905112, "pitch": null, "roll": null}, "v": 1.0194089953329712, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26136239676430634, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2569313172301865, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141187.1018627} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23225736665764285, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.017681604695689, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141187.1018627} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.71997356414795, "x": 51.02603795302883, "y": 3.841309081695311, "z": null, "yaw": 1.2956417672905112, "pitch": null, "roll": null}, "v": 1.0194089953329712, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26136239676430634, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2569313172301865, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141187.1218626} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23225736665764285, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0164893782528004, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141187.1218626} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.71997356414795, "x": 51.02603795302883, "y": 3.841309081695311, "z": null, "yaw": 1.2956417672905112, "pitch": null, "roll": null}, "v": 1.0194089953329712, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26136239676430634, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2569313172301865, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141187.1418626} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23225736665764285, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.015298828342943, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141187.1418626} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.71997356414795, "x": 51.02603795302883, "y": 3.841309081695311, "z": null, "yaw": 1.2956417672905112, "pitch": null, "roll": null}, "v": 1.0194089953329712, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26136239676430634, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2569313172301865, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141187.1618626} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23225736665764285, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0141099520417773, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141187.1618626} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.71997356414795, "x": 51.02603795302883, "y": 3.841309081695311, "z": null, "yaw": 1.2956417672905112, "pitch": null, "roll": null}, "v": 1.0194089953329712, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26136239676430634, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2569313172301865, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141187.1818626} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23225736665764285, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0129227464314654, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141187.1818626} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141187.1918626, "x": 55.055044740833466, "y": 8.949231931597232, "z": null, "yaw": 1.3233661105371486, "pitch": null, "roll": null}, "v": 1.0123297692253286, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2608646040778645, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.25514707273446974, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141187.2018626} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23451509487945987, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0117372086006526, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141187.2018626} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.829973459243774, "x": 51.055044740833466, "y": 3.9492319315972324, "z": null, "yaw": 1.3233661105371486, "pitch": null, "roll": null}, "v": 1.0123297692253286, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2608646040778645, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.25514707273446974, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141187.2218626} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23340205858456975, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.010835452580044, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141187.2218626} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.829973459243774, "x": 51.055044740833466, "y": 3.9492319315972324, "z": null, "yaw": 1.3233661105371486, "pitch": null, "roll": null}, "v": 1.0123297692253286, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2608646040778645, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.25514707273446974, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141187.2418625} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23340205858456975, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0097958818654047, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141187.2418625} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.829973459243774, "x": 51.055044740833466, "y": 3.9492319315972324, "z": null, "yaw": 1.3233661105371486, "pitch": null, "roll": null}, "v": 1.0123297692253286, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2608646040778645, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.25514707273446974, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141187.2618625} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23340205858456975, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0087577702189583, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141187.2618625} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.829973459243774, "x": 51.055044740833466, "y": 3.9492319315972324, "z": null, "yaw": 1.3233661105371486, "pitch": null, "roll": null}, "v": 1.0123297692253286, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2608646040778645, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.25514707273446974, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141187.2818625} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23340205858456975, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0077211151619405, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141187.2818625} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141187.3018625, "x": 55.080889769565474, "y": 9.05725462446423, "z": null, "yaw": 1.351090453783786, "pitch": null, "roll": null}, "v": 1.0066859142208788, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26046846100995125, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2537245984310369, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141187.3018625} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22883253868397158, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0058832632785275, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141187.3018625} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.9399733543396, "x": 51.080889769565474, "y": 4.05725462446423, "z": null, "yaw": 1.351090453783786, "pitch": null, "roll": null}, "v": 1.0066859142208788, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26046846100995125, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2537245984310369, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141187.3118625} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23097831928432658, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0058832632785275, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141187.3118625} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.9399733543396, "x": 51.080889769565474, "y": 4.05725462446423, "z": null, "yaw": 1.351090453783786, "pitch": null, "roll": null}, "v": 1.0066859142208788, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26046846100995125, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2537245984310369, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141187.3418624} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23097831928432658, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0038807374654575, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141187.3418624} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.9399733543396, "x": 51.080889769565474, "y": 4.05725462446423, "z": null, "yaw": 1.351090453783786, "pitch": null, "roll": null}, "v": 1.0066859142208788, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26046846100995125, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2537245984310369, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141187.3618624} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23097831928432658, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0018824190707223, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141187.3618624} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.9399733543396, "x": 51.080889769565474, "y": 4.05725462446423, "z": null, "yaw": 1.351090453783786, "pitch": null, "roll": null}, "v": 1.0066859142208788, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26046846100995125, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2537245984310369, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141187.3818624} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23097831928432658, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.001217245978293, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141187.3818624} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.9399733543396, "x": 51.080889769565474, "y": 4.05725462446423, "z": null, "yaw": 1.351090453783786, "pitch": null, "roll": null}, "v": 1.0066859142208788, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26046846100995125, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2537245984310369, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141187.4018624} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23097831928432658, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9998882968608512, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141187.4018624} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141187.4118624, "x": 55.10358282379753, "y": 9.165247737066029, "z": null, "yaw": 1.3788147970304234, "pitch": null, "roll": null}, "v": 0.9992245200070713, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2599457224141872, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.25184403248301807, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141187.4218624} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2384452019452758, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9985612077381998, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141187.4218624} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.049973249435425, "x": 51.10358282379753, "y": 4.165247737066029, "z": null, "yaw": 1.3788147970304234, "pitch": null, "roll": null}, "v": 0.9992245200070713, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2599457224141872, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.25184403248301807, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141187.4418623} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23484971403666227, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9981690091337556, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141187.4418623} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.049973249435425, "x": 51.10358282379753, "y": 4.165247737066029, "z": null, "yaw": 1.3788147970304234, "pitch": null, "roll": null}, "v": 0.9992245200070713, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2599457224141872, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.25184403248301807, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141187.4618623} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23484971403666227, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9973280803613871, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141187.4618623} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.049973249435425, "x": 51.10358282379753, "y": 4.165247737066029, "z": null, "yaw": 1.3788147970304234, "pitch": null, "roll": null}, "v": 0.9992245200070713, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2599457224141872, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.25184403248301807, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141187.4818623} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23484971403666227, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9964883276498074, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141187.4818623} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.049973249435425, "x": 51.10358282379753, "y": 4.165247737066029, "z": null, "yaw": 1.3788147970304234, "pitch": null, "roll": null}, "v": 0.9992245200070713, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2599457224141872, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.25184403248301807, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141187.5018623} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23484971403666227, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9956497490722896, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141187.5018623} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141187.5218623, "x": 55.1231553785236, "y": 9.273181397675755, "z": null, "yaw": 1.4065391402770608, "pitch": null, "roll": null}, "v": 0.9948123427059836, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25963713310730085, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.25073198959246923, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141187.5218623} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23046340537058937, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9948123427059836, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141187.5218623} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.15997314453125, "x": 51.1231553785236, "y": 4.273181397675755, "z": null, "yaw": 1.4065391402770608, "pitch": null, "roll": null}, "v": 0.9948123427059836, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25963713310730085, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.25073198959246923, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141187.5418622} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23252861324842766, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9934280096347695, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141187.5418622} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.15997314453125, "x": 51.1231553785236, "y": 4.273181397675755, "z": null, "yaw": 1.4065391402770608, "pitch": null, "roll": null}, "v": 0.9948123427059836, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25963713310730085, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.25073198959246923, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141187.5618622} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23252861324842766, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9923036713242436, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141187.5618622} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.15997314453125, "x": 51.1231553785236, "y": 4.273181397675755, "z": null, "yaw": 1.4065391402770608, "pitch": null, "roll": null}, "v": 0.9948123427059836, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25963713310730085, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.25073198959246923, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141187.5818622} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23252861324842766, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9911809032039054, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141187.5818622} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.15997314453125, "x": 51.1231553785236, "y": 4.273181397675755, "z": null, "yaw": 1.4065391402770608, "pitch": null, "roll": null}, "v": 0.9948123427059836, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25963713310730085, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.25073198959246923, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141187.6018622} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23252861324842766, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9900597025768447, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141187.6018622} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.15997314453125, "x": 51.1231553785236, "y": 4.273181397675755, "z": null, "yaw": 1.4065391402770608, "pitch": null, "roll": null}, "v": 0.9948123427059836, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25963713310730085, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.25073198959246923, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141187.6218622} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23252861324842766, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9889400667520281, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141187.6218622} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141187.6318622, "x": 55.13963802597892, "y": 9.381021291700321, "z": null, "yaw": 1.4342634835236983, "pitch": null, "roll": null}, "v": 0.988380834801116, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2591880084860773, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24911099565839645, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141187.6418622} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23327067924731754, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.987821993044282, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141187.6418622} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.269973039627075, "x": 51.13963802597892, "y": 4.381021291700321, "z": null, "yaw": 1.4342634835236983, "pitch": null, "roll": null}, "v": 0.988380834801116, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2591880084860773, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24911099565839645, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141187.6618621} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23288309527356638, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9867982046766777, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141187.6618621} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.269973039627075, "x": 51.13963802597892, "y": 4.381021291700321, "z": null, "yaw": 1.4342634835236983, "pitch": null, "roll": null}, "v": 0.988380834801116, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2591880084860773, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24911099565839645, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141187.681862} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23288309527356638, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9857274127069329, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141187.681862} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.269973039627075, "x": 51.13963802597892, "y": 4.381021291700321, "z": null, "yaw": 1.4342634835236983, "pitch": null, "roll": null}, "v": 0.988380834801116, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2591880084860773, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24911099565839645, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141187.701862} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23288309527356638, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9846581133269589, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141187.701862} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.269973039627075, "x": 51.13963802597892, "y": 4.381021291700321, "z": null, "yaw": 1.4342634835236983, "pitch": null, "roll": null}, "v": 0.988380834801116, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2591880084860773, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24911099565839645, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141187.721862} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23288309527356638, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9835903039990157, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141187.721862} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141187.741862, "x": 55.153042419245864, "y": 9.488615312240713, "z": null, "yaw": 1.4619878267703357, "pitch": null, "roll": null}, "v": 0.9825239821908113, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25877973286534145, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24763483754827778, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141187.741862} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24191446245402365, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9825239821908113, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141187.741862} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.3799729347229, "x": 51.153042419245864, "y": 4.488615312240713, "z": null, "yaw": 1.4619878267703357, "pitch": null, "roll": null}, "v": 0.9825239821908113, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25877973286534145, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24763483754827778, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141187.761862} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2375827025378465, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9825876731518988, "gear": 1, "accelerator_pedal_position": 0.24191446245402365, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141187.761862} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.3799729347229, "x": 51.153042419245864, "y": 4.488615312240713, "z": null, "yaw": 1.4619878267703357, "pitch": null, "roll": null}, "v": 0.9825239821908113, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25877973286534145, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24763483754827778, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141187.781862} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2375827025378465, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9821099939970901, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141187.781862} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.3799729347229, "x": 51.153042419245864, "y": 4.488615312240713, "z": null, "yaw": 1.4619878267703357, "pitch": null, "roll": null}, "v": 0.9825239821908113, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25877973286534145, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24763483754827778, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141187.801862} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2375827025378465, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9816329799659586, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141187.801862} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.3799729347229, "x": 51.153042419245864, "y": 4.488615312240713, "z": null, "yaw": 1.4619878267703357, "pitch": null, "roll": null}, "v": 0.9825239821908113, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25877973286534145, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24763483754827778, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141187.811862} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2375827025378465, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9809187038017235, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141187.811862} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.3799729347229, "x": 51.153042419245864, "y": 4.488615312240713, "z": null, "yaw": 1.4619878267703357, "pitch": null, "roll": null}, "v": 0.9825239821908113, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25877973286534145, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24763483754827778, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141187.831862} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2375827025378465, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9809187038017235, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141187.831862} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141187.851862, "x": 55.16341672696181, "y": 9.59611024802469, "z": null, "yaw": 1.489712170016973, "pitch": null, "roll": null}, "v": 0.9804433481338655, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2586348589956927, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24711043561404683, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141187.861862} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2299951457377056, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9794944317376473, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141187.861862} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.489972829818726, "x": 51.16341672696181, "y": 4.59611024802469, "z": null, "yaw": 1.489712170016973, "pitch": null, "roll": null}, "v": 0.9804433481338655, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2586348589956927, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24711043561404683, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141187.891862} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23359723181377026, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9773629408510904, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141187.891862} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23359723181377026, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9763945210717082, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141187.901862} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.489972829818726, "x": 51.16341672696181, "y": 4.59611024802469, "z": null, "yaw": 1.489712170016973, "pitch": null, "roll": null}, "v": 0.9804433481338655, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2586348589956927, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24711043561404683, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141187.9318619} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23359723181377026, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9759108161734551, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141187.9318619} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.489972829818726, "x": 51.16341672696181, "y": 4.59611024802469, "z": null, "yaw": 1.489712170016973, "pitch": null, "roll": null}, "v": 0.9804433481338655, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2586348589956927, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24711043561404683, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141187.9518619} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23359723181377026, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9749444149556508, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141187.9518619} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141187.9618618, "x": 55.170776848931, "y": 9.703393848113036, "z": null, "yaw": 1.5174365132636105, "pitch": null, "roll": null}, "v": 0.9744617180753082, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25821884230370823, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24560282866024824, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141187.9718618} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23128355057336342, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9739793566406318, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141187.9718618} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.59997272491455, "x": 51.170776848931, "y": 4.703393848113036, "z": null, "yaw": 1.5174365132636105, "pitch": null, "roll": null}, "v": 0.9744617180753082, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25821884230370823, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24560282866024824, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141187.9918618} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23235360756966045, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9727265292898347, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141187.9918618} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.59997272491455, "x": 51.170776848931, "y": 4.703393848113036, "z": null, "yaw": 1.5174365132636105, "pitch": null, "roll": null}, "v": 0.9744617180753082, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25821884230370823, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24560282866024824, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141188.0118618} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23235360756966045, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9716091524645647, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141188.0118618} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.59997272491455, "x": 51.170776848931, "y": 4.703393848113036, "z": null, "yaw": 1.5174365132636105, "pitch": null, "roll": null}, "v": 0.9744617180753082, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25821884230370823, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24560282866024824, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141188.0318618} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23235360756966045, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9704933268636816, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141188.0318618} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.59997272491455, "x": 51.170776848931, "y": 4.703393848113036, "z": null, "yaw": 1.5174365132636105, "pitch": null, "roll": null}, "v": 0.9744617180753082, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25821884230370823, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24560282866024824, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141188.0518618} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23235360756966045, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9688224912097678, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141188.0518618} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141188.0718617, "x": 55.17513326610645, "y": 9.810181420314786, "z": null, "yaw": 1.545160856510248, "pitch": null, "roll": null}, "v": 0.9682663187353193, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25778871257673847, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24404134340704972, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141188.0718617} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23818054507138683, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9682663187353193, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141188.0718617} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.709972620010376, "x": 51.17513326610645, "y": 4.810181420314786, "z": null, "yaw": 1.545160856510248, "pitch": null, "roll": null}, "v": 0.9682663187353193, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25778871257673847, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24404134340704972, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141188.0918617} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23537303973651452, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9678832455201238, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141188.0918617} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.709972620010376, "x": 51.17513326610645, "y": 4.810181420314786, "z": null, "yaw": 1.545160856510248, "pitch": null, "roll": null}, "v": 0.9682663187353193, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25778871257673847, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24404134340704972, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141188.1118617} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23537303973651452, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.967149887041201, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141188.1118617} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.709972620010376, "x": 51.17513326610645, "y": 4.810181420314786, "z": null, "yaw": 1.545160856510248, "pitch": null, "roll": null}, "v": 0.9682663187353193, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25778871257673847, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24404134340704972, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141188.1318617} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23537303973651452, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9664175453289161, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141188.1318617} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.709972620010376, "x": 51.17513326610645, "y": 4.810181420314786, "z": null, "yaw": 1.545160856510248, "pitch": null, "roll": null}, "v": 0.9682663187353193, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25778871257673847, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24404134340704972, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141188.1518617} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23537303973651452, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.965686218759115, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141188.1518617} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.709972620010376, "x": 51.17513326610645, "y": 4.810181420314786, "z": null, "yaw": 1.545160856510248, "pitch": null, "roll": null}, "v": 0.9682663187353193, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25778871257673847, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24404134340704972, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141188.1718616} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23537303973651452, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9649559057107869, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141188.1718616} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141188.1818616, "x": 55.17652013182413, "y": 9.916510064309527, "z": null, "yaw": 1.5728851997568853, "pitch": null, "roll": null}, "v": 0.9645911287514671, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25753391689423366, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2431150504196959, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141188.1918616} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23176960479521733, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9642266045660569, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141188.1918616} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.8199725151062, "x": 51.17652013182413, "y": 4.916510064309527, "z": null, "yaw": 1.5728851997568853, "pitch": null, "roll": null}, "v": 0.9645911287514671, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25753391689423366, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2431150504196959, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141188.2118616} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2334661140389342, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9630480403599757, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141188.2118616} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.8199725151062, "x": 51.17652013182413, "y": 4.916510064309527, "z": null, "yaw": 1.5728851997568853, "pitch": null, "roll": null}, "v": 0.9645911287514671, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25753391689423366, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2431150504196959, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141188.2318616} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2334661140389342, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9620830985253279, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141188.2318616} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.8199725151062, "x": 51.17652013182413, "y": 4.916510064309527, "z": null, "yaw": 1.5728851997568853, "pitch": null, "roll": null}, "v": 0.9645911287514671, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25753391689423366, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2431150504196959, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141188.2518616} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2334661140389342, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9611194926046533, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141188.2518616} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.8199725151062, "x": 51.17652013182413, "y": 4.916510064309527, "z": null, "yaw": 1.5728851997568853, "pitch": null, "roll": null}, "v": 0.9645911287514671, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25753391689423366, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2431150504196959, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141188.2718616} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2334661140389342, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9601572203771596, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141188.2718616} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141188.2918615, "x": 55.174966831923435, "y": 10.022328743129757, "z": null, "yaw": 1.6006095430035228, "pitch": null, "roll": null}, "v": 0.9591962796266694, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25716038900982996, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24175533542969851, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141188.2918615} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24461381253563313, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9591962796266694, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141188.2918615} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.929972410202026, "x": 51.174966831923435, "y": 5.022328743129757, "z": null, "yaw": 1.6006095430035228, "pitch": null, "roll": null}, "v": 0.9591962796266694, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25716038900982996, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24175533542969851, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141188.3118615} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23927692274666948, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.959629648446071, "gear": 1, "accelerator_pedal_position": 0.24461381253563313, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141188.3118615} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.929972410202026, "x": 51.174966831923435, "y": 5.022328743129757, "z": null, "yaw": 1.6006095430035228, "pitch": null, "roll": null}, "v": 0.9591962796266694, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25716038900982996, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24175533542969851, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141188.3318615} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23927692274666948, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9593955373489514, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141188.3318615} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.929972410202026, "x": 51.174966831923435, "y": 5.022328743129757, "z": null, "yaw": 1.6006095430035228, "pitch": null, "roll": null}, "v": 0.9591962796266694, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25716038900982996, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24175533542969851, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141188.3518615} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23927692274666948, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9591617500983964, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141188.3518615} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.929972410202026, "x": 51.174966831923435, "y": 5.022328743129757, "z": null, "yaw": 1.6006095430035228, "pitch": null, "roll": null}, "v": 0.9591962796266694, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25716038900982996, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24175533542969851, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141188.3718615} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23927692274666948, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.958928286224573, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141188.3718615} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.929972410202026, "x": 51.174966831923435, "y": 5.022328743129757, "z": null, "yaw": 1.6006095430035228, "pitch": null, "roll": null}, "v": 0.9591962796266694, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25716038900982996, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24175533542969851, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141188.3918614} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23927692274666948, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.958695145258389, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141188.3918614} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141188.4018614, "x": 55.17049326646794, "y": 10.127741183849482, "z": null, "yaw": 1.6283338862501602, "pitch": null, "roll": null}, "v": 0.9585786957192723, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25711766594483226, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2415996799003142, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141188.4118614} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2278961258439049, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9584623267314909, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141188.4118614} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.03997230529785, "x": 51.17049326646794, "y": 5.127741183849482, "z": null, "yaw": 1.6283338862501602, "pitch": null, "roll": null}, "v": 0.9585786957192723, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25711766594483226, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2415996799003142, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141188.4318614} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23331230055540886, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.956807722496997, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141188.4318614} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.03997230529785, "x": 51.17049326646794, "y": 5.127741183849482, "z": null, "yaw": 1.6283338862501602, "pitch": null, "roll": null}, "v": 0.9585786957192723, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25711766594483226, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2415996799003142, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141188.4518614} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23331230055540886, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.955832193454788, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141188.4518614} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.03997230529785, "x": 51.17049326646794, "y": 5.127741183849482, "z": null, "yaw": 1.6283338862501602, "pitch": null, "roll": null}, "v": 0.9585786957192723, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25711766594483226, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2415996799003142, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141188.4718614} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23331230055540886, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9548580125475586, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141188.4718614} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.03997230529785, "x": 51.17049326646794, "y": 5.127741183849482, "z": null, "yaw": 1.6283338862501602, "pitch": null, "roll": null}, "v": 0.9585786957192723, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25711766594483226, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2415996799003142, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141188.4918613} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23331230055540886, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.95388517753277, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141188.4918613} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141188.5118613, "x": 55.16312550787167, "y": 10.2326343470035, "z": null, "yaw": 1.6560582294967976, "pitch": null, "roll": null}, "v": 0.9529136861725539, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25672612924157734, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2401718738169624, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141188.5118613} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24046344715487264, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9529136861725539, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141188.5118613} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.149972200393677, "x": 51.16312550787167, "y": 5.232634347003501, "z": null, "yaw": 1.6560582294967976, "pitch": null, "roll": null}, "v": 0.9529136861725539, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25672612924157734, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2401718738169624, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141188.5318613} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23702830616649603, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9528371209283845, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141188.5318613} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.149972200393677, "x": 51.16312550787167, "y": 5.232634347003501, "z": null, "yaw": 1.6560582294967976, "pitch": null, "roll": null}, "v": 0.9529136861725539, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25672612924157734, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2401718738169624, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141188.5518613} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23702830616649603, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9523314170276955, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141188.5518613} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.149972200393677, "x": 51.16312550787167, "y": 5.232634347003501, "z": null, "yaw": 1.6560582294967976, "pitch": null, "roll": null}, "v": 0.9529136861725539, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25672612924157734, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2401718738169624, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141188.5718613} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23702830616649603, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9518264112544659, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141188.5718613} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.149972200393677, "x": 51.16312550787167, "y": 5.232634347003501, "z": null, "yaw": 1.6560582294967976, "pitch": null, "roll": null}, "v": 0.9529136861725539, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25672612924157734, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2401718738169624, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141188.5918612} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23702830616649603, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.951322102542949, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141188.5918612} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.149972200393677, "x": 51.16312550787167, "y": 5.232634347003501, "z": null, "yaw": 1.6560582294967976, "pitch": null, "roll": null}, "v": 0.9529136861725539, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25672612924157734, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2401718738169624, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141188.6118612} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23702830616649603, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9508184898292916, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141188.6118612} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141188.6218612, "x": 55.15289427293393, "y": 10.336852337615548, "z": null, "yaw": 1.683782572743435, "pitch": null, "roll": null}, "v": 0.9505669441397229, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25656412235989745, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.239580402165785, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141188.6318612} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23111492983334042, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9503155720515299, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141188.6318612} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.259972095489502, "x": 51.15289427293393, "y": 5.336852337615548, "z": null, "yaw": 1.683782572743435, "pitch": null, "roll": null}, "v": 0.9505669441397229, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25656412235989745, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.239580402165785, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141188.6518612} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23391848134435442, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9490744311133941, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141188.6518612} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.259972095489502, "x": 51.15289427293393, "y": 5.336852337615548, "z": null, "yaw": 1.683782572743435, "pitch": null, "roll": null}, "v": 0.9505669441397229, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25656412235989745, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.239580402165785, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141188.6718612} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23391848134435442, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9481853251404565, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141188.6718612} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.259972095489502, "x": 51.15289427293393, "y": 5.336852337615548, "z": null, "yaw": 1.683782572743435, "pitch": null, "roll": null}, "v": 0.9505669441397229, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25656412235989745, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.239580402165785, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141188.6918612} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23391848134435442, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9472974451445517, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141188.6918612} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.259972095489502, "x": 51.15289427293393, "y": 5.336852337615548, "z": null, "yaw": 1.683782572743435, "pitch": null, "roll": null}, "v": 0.9505669441397229, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25656412235989745, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.239580402165785, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141188.7118611} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23391848134435442, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9464107891199718, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141188.7118611} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141188.731861, "x": 55.139830607973366, "y": 10.440335086463552, "z": null, "yaw": 1.7115069159900724, "pitch": null, "roll": null}, "v": 0.9455253550650773, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2562164497239633, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2383097226565671, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141188.731861} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2391943306991729, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9455253550650773, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141188.731861} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.369971990585327, "x": 51.139830607973366, "y": 5.440335086463552, "z": null, "yaw": 1.7115069159900724, "pitch": null, "roll": null}, "v": 0.9455253550650773, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2562164497239633, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2383097226565671, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141188.751861} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.236655530870661, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9453003949440238, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141188.751861} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.369971990585327, "x": 51.139830607973366, "y": 5.440335086463552, "z": null, "yaw": 1.7115069159900724, "pitch": null, "roll": null}, "v": 0.9455253550650773, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2562164497239633, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2383097226565671, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141188.771861} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.236655530870661, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9447585040952481, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141188.771861} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.369971990585327, "x": 51.139830607973366, "y": 5.440335086463552, "z": null, "yaw": 1.7115069159900724, "pitch": null, "roll": null}, "v": 0.9455253550650773, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2562164497239633, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2383097226565671, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141188.791861} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.236655530870661, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9442173596918597, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141188.791861} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.369971990585327, "x": 51.139830607973366, "y": 5.440335086463552, "z": null, "yaw": 1.7115069159900724, "pitch": null, "roll": null}, "v": 0.9455253550650773, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2562164497239633, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2383097226565671, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141188.811861} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.236655530870661, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9436769605885483, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141188.811861} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.369971990585327, "x": 51.139830607973366, "y": 5.440335086463552, "z": null, "yaw": 1.7115069159900724, "pitch": null, "roll": null}, "v": 0.9455253550650773, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2562164497239633, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2383097226565671, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141188.831861} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.236655530870661, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9431373056420649, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141188.831861} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141188.841861, "x": 55.12396663083707, "y": 10.543002379379919, "z": null, "yaw": 1.7392312592367098, "pitch": null, "roll": null}, "v": 0.9428677568709308, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2560333839130148, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23763990297887475, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141188.851861} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24189038521639633, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.942598393711217, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141188.851861} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.479971885681152, "x": 51.12396663083707, "y": 5.543002379379919, "z": null, "yaw": 1.7392312592367098, "pitch": null, "roll": null}, "v": 0.9428677568709308, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2560333839130148, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23763990297887475, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141188.871861} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23938364830917788, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9427143551882261, "gear": 1, "accelerator_pedal_position": 0.24189038521639633, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141188.871861} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.479971885681152, "x": 51.12396663083707, "y": 5.543002379379919, "z": null, "yaw": 1.7392312592367098, "pitch": null, "roll": null}, "v": 0.9428677568709308, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2560333839130148, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23763990297887475, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141188.891861} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23938364830917788, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9425169227933563, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141188.891861} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.479971885681152, "x": 51.12396663083707, "y": 5.543002379379919, "z": null, "yaw": 1.7392312592367098, "pitch": null, "roll": null}, "v": 0.9428677568709308, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2560333839130148, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23763990297887475, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141188.911861} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23938364830917788, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9423197621745371, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141188.911861} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.479971885681152, "x": 51.12396663083707, "y": 5.543002379379919, "z": null, "yaw": 1.7392312592367098, "pitch": null, "roll": null}, "v": 0.9428677568709308, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2560333839130148, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23763990297887475, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141188.931861} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23938364830917788, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9421228729421108, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141188.931861} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141188.951861, "x": 55.10530154974893, "y": 10.644975703943379, "z": null, "yaw": 1.7669556024833473, "pitch": null, "roll": null}, "v": 0.9419262547070205, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.255968563428415, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2374026072592411, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141188.951861} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23307294103423604, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9419262547070205, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141188.951861} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.589971780776978, "x": 51.10530154974893, "y": 5.644975703943379, "z": null, "yaw": 1.7669556024833473, "pitch": null, "roll": null}, "v": 0.9419262547070205, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.255968563428415, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2374026072592411, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141188.971861} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2360731025317125, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9409413401605005, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141188.971861} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.589971780776978, "x": 51.10530154974893, "y": 5.644975703943379, "z": null, "yaw": 1.7669556024833473, "pitch": null, "roll": null}, "v": 0.9419262547070205, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.255968563428415, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2374026072592411, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141188.9918609} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2360731025317125, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.940332672017637, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141188.9918609} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.589971780776978, "x": 51.10530154974893, "y": 5.644975703943379, "z": null, "yaw": 1.7669556024833473, "pitch": null, "roll": null}, "v": 0.9419262547070205, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.255968563428415, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2374026072592411, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141189.0118608} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2360731025317125, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9397248412320027, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141189.0118608} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.589971780776978, "x": 51.10530154974893, "y": 5.644975703943379, "z": null, "yaw": 1.7669556024833473, "pitch": null, "roll": null}, "v": 0.9419262547070205, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.255968563428415, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2374026072592411, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141189.0318608} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2360731025317125, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9391178465038955, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141189.0318608} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.589971780776978, "x": 51.10530154974893, "y": 5.644975703943379, "z": null, "yaw": 1.7669556024833473, "pitch": null, "roll": null}, "v": 0.9419262547070205, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.255968563428415, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2374026072592411, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141189.0518608} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2360731025317125, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9385116865360108, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141189.0518608} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141189.0618608, "x": 55.08387181128817, "y": 10.746136402955832, "z": null, "yaw": 1.7946799457299847, "pitch": null, "roll": null}, "v": 0.9382089191823983, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.255712805719454, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2364656919315362, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141189.0718608} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24925145762780043, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9379063600334359, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141189.0718608} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.699971675872803, "x": 51.08387181128817, "y": 5.746136402955832, "z": null, "yaw": 1.7946799457299847, "pitch": null, "roll": null}, "v": 0.9382089191823983, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.255712805719454, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2364656919315362, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141189.0918608} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2429565609929761, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9389485937482372, "gear": 1, "accelerator_pedal_position": 0.24925145762780043, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141189.0918608} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.699971675872803, "x": 51.08387181128817, "y": 5.746136402955832, "z": null, "yaw": 1.7946799457299847, "pitch": null, "roll": null}, "v": 0.9382089191823983, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.255712805719454, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2364656919315362, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141189.1118608} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2429565609929761, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9392028029333475, "gear": 1, "accelerator_pedal_position": 0.2429565609929761, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141189.1118608} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.699971675872803, "x": 51.08387181128817, "y": 5.746136402955832, "z": null, "yaw": 1.7946799457299847, "pitch": null, "roll": null}, "v": 0.9382089191823983, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.255712805719454, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2364656919315362, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141189.1318607} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2429565609929761, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9394566625344134, "gear": 1, "accelerator_pedal_position": 0.2429565609929761, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141189.1318607} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.699971675872803, "x": 51.08387181128817, "y": 5.746136402955832, "z": null, "yaw": 1.7946799457299847, "pitch": null, "roll": null}, "v": 0.9382089191823983, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.255712805719454, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2364656919315362, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141189.1518607} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2429565609929761, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9397101730064081, "gear": 1, "accelerator_pedal_position": 0.2429565609929761, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141189.1518607} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141189.1718607, "x": 55.05967092345398, "y": 10.846554939749364, "z": null, "yaw": 1.822404288976622, "pitch": null, "roll": null}, "v": 0.939963334803785, "accelerator_pedal_position": 0.2429565609929761, "brake_pedal_position": 0.0, "acceleration": 0.012645028758156762, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23690787393957788, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141189.1718607} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25305120858135455, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.939963334803785, "gear": 1, "accelerator_pedal_position": 0.2429565609929761, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141189.1718607} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.809971570968628, "x": 51.05967092345398, "y": 5.846554939749364, "z": null, "yaw": 1.822404288976622, "pitch": null, "roll": null}, "v": 0.939963334803785, "accelerator_pedal_position": 0.2429565609929761, "brake_pedal_position": 0.0, "acceleration": 0.012645028758156762, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23690787393957788, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141189.1918607} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24825342517902352, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9414775452080448, "gear": 1, "accelerator_pedal_position": 0.25305120858135455, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141189.1918607} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.809971570968628, "x": 51.05967092345398, "y": 5.846554939749364, "z": null, "yaw": 1.822404288976622, "pitch": null, "roll": null}, "v": 0.939963334803785, "accelerator_pedal_position": 0.2429565609929761, "brake_pedal_position": 0.0, "acceleration": 0.012645028758156762, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23690787393957788, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141189.2018607} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24825342517902352, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9428459896901402, "gear": 1, "accelerator_pedal_position": 0.24825342517902352, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141189.2018607} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.809971570968628, "x": 51.05967092345398, "y": 5.846554939749364, "z": null, "yaw": 1.822404288976622, "pitch": null, "roll": null}, "v": 0.939963334803785, "accelerator_pedal_position": 0.2429565609929761, "brake_pedal_position": 0.0, "acceleration": 0.012645028758156762, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23690787393957788, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141189.2218606} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24825342517902352, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9428459896901402, "gear": 1, "accelerator_pedal_position": 0.24825342517902352, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141189.2218606} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.809971570968628, "x": 51.05967092345398, "y": 5.846554939749364, "z": null, "yaw": 1.822404288976622, "pitch": null, "roll": null}, "v": 0.939963334803785, "accelerator_pedal_position": 0.2429565609929761, "brake_pedal_position": 0.0, "acceleration": 0.012645028758156762, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23690787393957788, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141189.2518606} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24825342517902352, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9442116094993029, "gear": 1, "accelerator_pedal_position": 0.24825342517902352, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141189.2518606} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.809971570968628, "x": 51.05967092345398, "y": 5.846554939749364, "z": null, "yaw": 1.822404288976622, "pitch": null, "roll": null}, "v": 0.939963334803785, "accelerator_pedal_position": 0.2429565609929761, "brake_pedal_position": 0.0, "acceleration": 0.012645028758156762, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23690787393957788, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141189.2718606} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24825342517902352, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.94512045577007, "gear": 1, "accelerator_pedal_position": 0.24825342517902352, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141189.2718606} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141189.2818606, "x": 55.03258853501855, "y": 10.946656669663424, "z": null, "yaw": 1.8501286322232595, "pitch": null, "roll": null}, "v": 0.9455744093482824, "accelerator_pedal_position": 0.24825342517902352, "brake_pedal_position": 0.0, "acceleration": 0.04536407726533925, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23832208627279708, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141189.2918606} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22241405737144268, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9460280501209358, "gear": 1, "accelerator_pedal_position": 0.24825342517902352, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141189.2918606} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.919971466064453, "x": 51.03258853501855, "y": 5.946656669663424, "z": null, "yaw": 1.8501286322232595, "pitch": null, "roll": null}, "v": 0.9455744093482824, "accelerator_pedal_position": 0.24825342517902352, "brake_pedal_position": 0.0, "acceleration": 0.04536407726533925, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23832208627279708, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141189.3118606} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23474796078632773, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.943316422629425, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141189.3118606} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.919971466064453, "x": 51.03258853501855, "y": 5.946656669663424, "z": null, "yaw": 1.8501286322232595, "pitch": null, "roll": null}, "v": 0.9455744093482824, "accelerator_pedal_position": 0.24825342517902352, "brake_pedal_position": 0.0, "acceleration": 0.04536407726533925, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23832208627279708, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141189.3318605} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23474796078632773, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9429275273799356, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141189.3318605} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.919971466064453, "x": 51.03258853501855, "y": 5.946656669663424, "z": null, "yaw": 1.8501286322232595, "pitch": null, "roll": null}, "v": 0.9455744093482824, "accelerator_pedal_position": 0.24825342517902352, "brake_pedal_position": 0.0, "acceleration": 0.04536407726533925, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23832208627279708, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141189.3518605} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23474796078632773, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9413746222642657, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141189.3518605} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.919971466064453, "x": 51.03258853501855, "y": 5.946656669663424, "z": null, "yaw": 1.8501286322232595, "pitch": null, "roll": null}, "v": 0.9455744093482824, "accelerator_pedal_position": 0.24825342517902352, "brake_pedal_position": 0.0, "acceleration": 0.04536407726533925, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23832208627279708, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141189.3718605} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23474796078632773, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9413746222642657, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141189.3718605} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141189.3918605, "x": 55.002730347880444, "y": 11.046016362831844, "z": null, "yaw": 1.877852975469897, "pitch": null, "roll": null}, "v": 0.9405997722360983, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2558772679271109, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23706828130165475, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141189.3918605} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23829967530160023, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9402127471059726, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141189.3918605} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.02997136116028, "x": 51.002730347880444, "y": 6.046016362831844, "z": null, "yaw": 1.877852975469897, "pitch": null, "roll": null}, "v": 0.9405997722360983, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2558772679271109, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23706828130165475, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141189.4118605} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2365822818420186, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9397759700490224, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141189.4118605} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.02997136116028, "x": 51.002730347880444, "y": 6.046016362831844, "z": null, "yaw": 1.877852975469897, "pitch": null, "roll": null}, "v": 0.9405997722360983, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2558772679271109, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23706828130165475, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141189.4318604} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2365822818420186, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9395041567917358, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141189.4318604} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.02997136116028, "x": 51.002730347880444, "y": 6.046016362831844, "z": null, "yaw": 1.877852975469897, "pitch": null, "roll": null}, "v": 0.9405997722360983, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2558772679271109, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23706828130165475, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141189.4518604} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2365822818420186, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9386898383741469, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141189.4518604} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.02997136116028, "x": 51.002730347880444, "y": 6.046016362831844, "z": null, "yaw": 1.877852975469897, "pitch": null, "roll": null}, "v": 0.9405997722360983, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2558772679271109, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23706828130165475, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141189.4718604} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2365822818420186, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9384187722088193, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141189.4718604} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.02997136116028, "x": 51.002730347880444, "y": 6.046016362831844, "z": null, "yaw": 1.877852975469897, "pitch": null, "roll": null}, "v": 0.9405997722360983, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2558772679271109, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23706828130165475, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141189.4918604} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2365822818420186, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9378771989807221, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141189.4918604} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141189.5018604, "x": 54.97026622166127, "y": 11.144094522787874, "z": null, "yaw": 1.9055773187165344, "pitch": null, "roll": null}, "v": 0.9376066916323211, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2556713976635531, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23631390681052777, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141189.5118604} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23250496443651145, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9373363702708117, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141189.5118604} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.139971256256104, "x": 50.97026622166127, "y": 6.144094522787874, "z": null, "yaw": 1.9055773187165344, "pitch": null, "roll": null}, "v": 0.9376066916323211, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2556713976635531, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23631390681052777, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141189.5318604} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23443085976207456, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9362867954315595, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141189.5318604} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.139971256256104, "x": 50.97026622166127, "y": 6.144094522787874, "z": null, "yaw": 1.9055773187165344, "pitch": null, "roll": null}, "v": 0.9376066916323211, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2556713976635531, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23631390681052777, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141189.5518603} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23443085976207456, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9350759939868462, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141189.5518603} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.139971256256104, "x": 50.97026622166127, "y": 6.144094522787874, "z": null, "yaw": 1.9055773187165344, "pitch": null, "roll": null}, "v": 0.9376066916323211, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2556713976635531, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23631390681052777, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141189.5718603} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23443085976207456, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9346729480135293, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141189.5718603} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.139971256256104, "x": 50.97026622166127, "y": 6.144094522787874, "z": null, "yaw": 1.9055773187165344, "pitch": null, "roll": null}, "v": 0.9376066916323211, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2556713976635531, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23631390681052777, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141189.5918603} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23443085976207456, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9338676864916233, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141189.5918603} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141189.6118603, "x": 54.9352347597052, "y": 11.240852413381328, "z": null, "yaw": 1.9333016619631718, "pitch": null, "roll": null}, "v": 0.9330635307193393, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2553592520595514, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23516885087801678, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141189.6118603} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.239093410221445, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9329532763375842, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141189.6118603} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.24997115135193, "x": 50.9352347597052, "y": 6.240852413381328, "z": null, "yaw": 1.9333016619631718, "pitch": null, "roll": null}, "v": 0.9330635307193393, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2553592520595514, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23516885087801678, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141189.6318603} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2368493644547267, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9328430976566728, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141189.6318603} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.24997115135193, "x": 50.9352347597052, "y": 6.240852413381328, "z": null, "yaw": 1.9333016619631718, "pitch": null, "roll": null}, "v": 0.9330635307193393, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2553592520595514, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23516885087801678, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141189.6518602} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2368493644547267, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9323425577471212, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141189.6518602} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.24997115135193, "x": 50.9352347597052, "y": 6.240852413381328, "z": null, "yaw": 1.9333016619631718, "pitch": null, "roll": null}, "v": 0.9330635307193393, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2553592520595514, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23516885087801678, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141189.6718602} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2368493644547267, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9318427048365143, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141189.6718602} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.24997115135193, "x": 50.9352347597052, "y": 6.240852413381328, "z": null, "yaw": 1.9333016619631718, "pitch": null, "roll": null}, "v": 0.9330635307193393, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2553592520595514, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23516885087801678, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141189.6918602} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2368493644547267, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9313435378820285, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141189.6918602} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.24997115135193, "x": 50.9352347597052, "y": 6.240852413381328, "z": null, "yaw": 1.9333016619631718, "pitch": null, "roll": null}, "v": 0.9330635307193393, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2553592520595514, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23516885087801678, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141189.7118602} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2368493644547267, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9305960713413827, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141189.7118602} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141189.7218602, "x": 54.89767383371573, "y": 11.336246872002782, "z": null, "yaw": 1.9610260052098092, "pitch": null, "roll": null}, "v": 0.9305960713413827, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2551898940470293, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23454695368945677, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141189.7318602} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24034672429611484, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9303472576793328, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141189.7318602} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.359971046447754, "x": 50.89767383371573, "y": 6.336246872002782, "z": null, "yaw": 1.9610260052098092, "pitch": null, "roll": null}, "v": 0.9305960713413827, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2551898940470293, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23454695368945677, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141189.7518601} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.238668410541823, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9301522510336804, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141189.7518601} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.359971046447754, "x": 50.89767383371573, "y": 6.336246872002782, "z": null, "yaw": 1.9610260052098092, "pitch": null, "roll": null}, "v": 0.9305960713413827, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2551898940470293, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23454695368945677, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141189.7718601} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.238668410541823, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9300174322460172, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141189.7718601} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.359971046447754, "x": 50.89767383371573, "y": 6.336246872002782, "z": null, "yaw": 1.9610260052098092, "pitch": null, "roll": null}, "v": 0.9305960713413827, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2551898940470293, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23454695368945677, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141189.79186} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.238668410541823, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.929748072067539, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141189.79186} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.359971046447754, "x": 50.89767383371573, "y": 6.336246872002782, "z": null, "yaw": 1.9610260052098092, "pitch": null, "roll": null}, "v": 0.9305960713413827, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2551898940470293, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23454695368945677, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141189.81186} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.238668410541823, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9293447242865469, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141189.81186} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141189.83186, "x": 54.85757210663852, "y": 11.430353396032649, "z": null, "yaw": 1.9887503484564466, "pitch": null, "roll": null}, "v": 0.9292104594216116, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25509484375006586, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2341977247760898, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141189.83186} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23906866489074982, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9290762866429749, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141189.83186} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.46997094154358, "x": 50.85757210663852, "y": 6.430353396032649, "z": null, "yaw": 1.9887503484564466, "pitch": null, "roll": null}, "v": 0.9292104594216116, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25509484375006586, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2341977247760898, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141189.86186} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23887082555551997, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9287369514354519, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141189.86186} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23887082555551997, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9287369514354519, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141189.87186} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.46997094154358, "x": 50.85757210663852, "y": 6.430353396032649, "z": null, "yaw": 1.9887503484564466, "pitch": null, "roll": null}, "v": 0.9292104594216116, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25509484375006586, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2341977247760898, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141189.89186} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23887082555551997, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9284946403225978, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141189.89186} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.46997094154358, "x": 50.85757210663852, "y": 6.430353396032649, "z": null, "yaw": 1.9887503484564466, "pitch": null, "roll": null}, "v": 0.9292104594216116, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25509484375006586, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2341977247760898, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141189.91186} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23887082555551997, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9282526614066233, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141189.91186} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.46997094154358, "x": 50.85757210663852, "y": 6.430353396032649, "z": null, "yaw": 1.9887503484564466, "pitch": null, "roll": null}, "v": 0.9292104594216116, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25509484375006586, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2341977247760898, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141189.93186} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23887082555551997, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9280110142086889, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141189.93186} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141189.94186, "x": 54.81493992355842, "y": 11.52317528065126, "z": null, "yaw": 2.016474691703084, "pitch": null, "roll": null}, "v": 0.9278903148545553, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2550043201067366, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23386499622052387, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141189.95186} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23544712695398895, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9276491643375034, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141189.95186} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.579970836639404, "x": 50.81493992355842, "y": 6.523175280651261, "z": null, "yaw": 2.016474691703084, "pitch": null, "roll": null}, "v": 0.9278903148545553, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2550043201067366, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23386499622052387, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141189.97186} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23707056339287033, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9269805287002287, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141189.97186} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.579970836639404, "x": 50.81493992355842, "y": 6.523175280651261, "z": null, "yaw": 2.016474691703084, "pitch": null, "roll": null}, "v": 0.9278903148545553, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2550043201067366, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23386499622052387, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141189.99186} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23707056339287033, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9267480193578741, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141189.99186} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.579970836639404, "x": 50.81493992355842, "y": 6.523175280651261, "z": null, "yaw": 2.016474691703084, "pitch": null, "roll": null}, "v": 0.9278903148545553, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2550043201067366, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23386499622052387, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141190.01186} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23707056339287033, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.926283478619921, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141190.01186} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.579970836639404, "x": 50.81493992355842, "y": 6.523175280651261, "z": null, "yaw": 2.016474691703084, "pitch": null, "roll": null}, "v": 0.9278903148545553, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2550043201067366, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23386499622052387, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141190.0318599} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23707056339287033, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9258195743447051, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141190.0318599} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141190.0518599, "x": 54.76984033402232, "y": 11.614599430297716, "z": null, "yaw": 2.044199034949721, "pitch": null, "roll": null}, "v": 0.9253563055741615, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2548306582013667, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2332263258288893, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141190.0518599} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24042403729757206, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.925334501323246, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141190.0518599} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.68997073173523, "x": 50.76984033402232, "y": 6.614599430297716, "z": null, "yaw": 2.044199034949721, "pitch": null, "roll": null}, "v": 0.9253563055741615, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2548306582013667, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2332263258288893, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141190.0718598} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.238813912774406, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9253127120097487, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141190.0718598} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.68997073173523, "x": 50.76984033402232, "y": 6.614599430297716, "z": null, "yaw": 2.044199034949721, "pitch": null, "roll": null}, "v": 0.9253563055741615, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2548306582013667, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2332263258288893, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141190.0918598} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.238813912774406, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9250679815266065, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141190.0918598} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.68997073173523, "x": 50.76984033402232, "y": 6.614599430297716, "z": null, "yaw": 2.044199034949721, "pitch": null, "roll": null}, "v": 0.9253563055741615, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2548306582013667, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2332263258288893, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141190.1118598} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.238813912774406, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9247015141107562, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141190.1118598} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.68997073173523, "x": 50.76984033402232, "y": 6.614599430297716, "z": null, "yaw": 2.044199034949721, "pitch": null, "roll": null}, "v": 0.9253563055741615, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2548306582013667, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2332263258288893, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141190.1318598} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.238813912774406, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9245795256130813, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141190.1318598} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.68997073173523, "x": 50.76984033402232, "y": 6.614599430297716, "z": null, "yaw": 2.044199034949721, "pitch": null, "roll": null}, "v": 0.9253563055741615, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2548306582013667, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2332263258288893, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141190.1518598} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.238813912774406, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9242140611994017, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141190.1518598} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141190.1618598, "x": 54.72231917546873, "y": 11.7045567781929, "z": null, "yaw": 2.0719233781963586, "pitch": null, "roll": null}, "v": 0.9242140611994017, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.254752419369157, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23293843514600407, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141190.1718597} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23353684712739736, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9240924065541105, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141190.1718597} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.799970626831055, "x": 50.72231917546873, "y": 6.7045567781929005, "z": null, "yaw": 2.0719233781963586, "pitch": null, "roll": null}, "v": 0.9242140611994017, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.254752419369157, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23293843514600407, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141190.1918597} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23604377572917254, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9231899397817362, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141190.1918597} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.799970626831055, "x": 50.72231917546873, "y": 6.7045567781929005, "z": null, "yaw": 2.0719233781963586, "pitch": null, "roll": null}, "v": 0.9242140611994017, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.254752419369157, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23293843514600407, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141190.2118597} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23604377572917254, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9220147993548898, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141190.2118597} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.799970626831055, "x": 50.72231917546873, "y": 6.7045567781929005, "z": null, "yaw": 2.0719233781963586, "pitch": null, "roll": null}, "v": 0.9242140611994017, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.254752419369157, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23293843514600407, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141190.2318597} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23604377572917254, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9220147993548898, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141190.2318597} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.799970626831055, "x": 50.72231917546873, "y": 6.7045567781929005, "z": null, "yaw": 2.0719233781963586, "pitch": null, "roll": null}, "v": 0.9242140611994017, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.254752419369157, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23293843514600407, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141190.2518597} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23604377572917254, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9211355537079818, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141190.2518597} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141190.2718596, "x": 54.67244526267776, "y": 11.792945994238593, "z": null, "yaw": 2.099647721442996, "pitch": null, "roll": null}, "v": 0.9208428728433706, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2545216596068329, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23208876257207975, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141190.2718596} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2401255487193253, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9208428728433706, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141190.2718596} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.90997052192688, "x": 50.67244526267776, "y": 6.792945994238593, "z": null, "yaw": 2.099647721442996, "pitch": null, "roll": null}, "v": 0.9208428728433706, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2545216596068329, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23208876257207975, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141190.2918596} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23816426461951884, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9207308401235798, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141190.2918596} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.90997052192688, "x": 50.67244526267776, "y": 6.792945994238593, "z": null, "yaw": 2.099647721442996, "pitch": null, "roll": null}, "v": 0.9208428728433706, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2545216596068329, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23208876257207975, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141190.3118596} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23816426461951884, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9205709667142424, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141190.3118596} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.90997052192688, "x": 50.67244526267776, "y": 6.792945994238593, "z": null, "yaw": 2.099647721442996, "pitch": null, "roll": null}, "v": 0.9208428728433706, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2545216596068329, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23208876257207975, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141190.3318596} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23816426461951884, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9202515479383082, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141190.3318596} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.90997052192688, "x": 50.67244526267776, "y": 6.792945994238593, "z": null, "yaw": 2.099647721442996, "pitch": null, "roll": null}, "v": 0.9208428728433706, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2545216596068329, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23208876257207975, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141190.3518596} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23816426461951884, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9199325660201344, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141190.3518596} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.90997052192688, "x": 50.67244526267776, "y": 6.792945994238593, "z": null, "yaw": 2.099647721442996, "pitch": null, "roll": null}, "v": 0.9208428728433706, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2545216596068329, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23208876257207975, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141190.3718596} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23816426461951884, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9196140203215603, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141190.3718596} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141190.3818595, "x": 54.62027102231954, "y": 11.879700336766403, "z": null, "yaw": 2.1273720646896335, "pitch": null, "roll": null}, "v": 0.9194549108554823, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25442671887373675, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.231738941348757, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141190.3918595} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24120340539593832, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9192959102054649, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141190.3918595} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.019970417022705, "x": 50.62027102231954, "y": 6.879700336766403, "z": null, "yaw": 2.1273720646896335, "pitch": null, "roll": null}, "v": 0.9194549108554823, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25442671887373675, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.231738941348757, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141190.4118595} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23974896119618236, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9193579977387247, "gear": 1, "accelerator_pedal_position": 0.24120340539593832, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141190.4118595} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.019970417022705, "x": 50.62027102231954, "y": 6.879700336766403, "z": null, "yaw": 2.1273720646896335, "pitch": null, "roll": null}, "v": 0.9194549108554823, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25442671887373675, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.231738941348757, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141190.4318595} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23974896119618236, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9191784480711243, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141190.4318595} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.019970417022705, "x": 50.62027102231954, "y": 6.879700336766403, "z": null, "yaw": 2.1273720646896335, "pitch": null, "roll": null}, "v": 0.9194549108554823, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25442671887373675, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.231738941348757, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141190.4518595} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23974896119618236, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9191186800199103, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141190.4518595} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.019970417022705, "x": 50.62027102231954, "y": 6.879700336766403, "z": null, "yaw": 2.1273720646896335, "pitch": null, "roll": null}, "v": 0.9194549108554823, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25442671887373675, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.231738941348757, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141190.4718595} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23974896119618236, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9189396209786544, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141190.4718595} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141190.4918594, "x": 54.565779242082826, "y": 11.964869396477374, "z": null, "yaw": 2.155096407936271, "pitch": null, "roll": null}, "v": 0.9188800162402261, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2543874056544677, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23159404520653878, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141190.4918594} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24232028419249782, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9188800162402261, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141190.4918594} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.12997031211853, "x": 50.565779242082826, "y": 6.964869396477374, "z": null, "yaw": 2.155096407936271, "pitch": null, "roll": null}, "v": 0.9188800162402261, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2543874056544677, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23159404520653878, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141190.5118594} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24109284876438852, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9190822344905373, "gear": 1, "accelerator_pedal_position": 0.24232028419249782, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141190.5118594} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.12997031211853, "x": 50.565779242082826, "y": 6.964869396477374, "z": null, "yaw": 2.155096407936271, "pitch": null, "roll": null}, "v": 0.9188800162402261, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2543874056544677, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23159404520653878, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141190.5318594} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24109284876438852, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9191550568158895, "gear": 1, "accelerator_pedal_position": 0.24109284876438852, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141190.5318594} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.12997031211853, "x": 50.565779242082826, "y": 6.964869396477374, "z": null, "yaw": 2.155096407936271, "pitch": null, "roll": null}, "v": 0.9188800162402261, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2543874056544677, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23159404520653878, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141190.5518594} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24109284876438852, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9191792977334088, "gear": 1, "accelerator_pedal_position": 0.24109284876438852, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141190.5518594} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.12997031211853, "x": 50.565779242082826, "y": 6.964869396477374, "z": null, "yaw": 2.155096407936271, "pitch": null, "roll": null}, "v": 0.9188800162402261, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2543874056544677, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23159404520653878, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141190.5718594} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24109284876438852, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.919227729849416, "gear": 1, "accelerator_pedal_position": 0.24109284876438852, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141190.5718594} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.12997031211853, "x": 50.565779242082826, "y": 6.964869396477374, "z": null, "yaw": 2.155096407936271, "pitch": null, "roll": null}, "v": 0.9188800162402261, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2543874056544677, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23159404520653878, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141190.5918593} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24109284876438852, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9192760957481331, "gear": 1, "accelerator_pedal_position": 0.24109284876438852, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141190.5918593} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141190.6018593, "x": 54.508951719116105, "y": 12.048488488143066, "z": null, "yaw": 2.1828207511829083, "pitch": null, "roll": null}, "v": 0.9193002538940119, "accelerator_pedal_position": 0.24109284876438852, "brake_pedal_position": 0.0, "acceleration": 0.0024141625146316126, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23169996168798168, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141190.6118593} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23368427357867577, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9188854846856462, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141190.6118593} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.239970207214355, "x": 50.508951719116105, "y": 7.048488488143066, "z": null, "yaw": 2.1828207511829083, "pitch": null, "roll": null}, "v": 0.9193002538940119, "accelerator_pedal_position": 0.24109284876438852, "brake_pedal_position": 0.0, "acceleration": 0.0024141625146316126, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23169996168798168, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141190.6318593} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2372143577435572, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.918446873988574, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141190.6318593} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.239970207214355, "x": 50.508951719116105, "y": 7.048488488143066, "z": null, "yaw": 2.1828207511829083, "pitch": null, "roll": null}, "v": 0.9193002538940119, "accelerator_pedal_position": 0.24109284876438852, "brake_pedal_position": 0.0, "acceleration": 0.0024141625146316126, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23169996168798168, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141190.6518593} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2372143577435572, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9177942787086047, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141190.6518593} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.239970207214355, "x": 50.508951719116105, "y": 7.048488488143066, "z": null, "yaw": 2.1828207511829083, "pitch": null, "roll": null}, "v": 0.9193002538940119, "accelerator_pedal_position": 0.24109284876438852, "brake_pedal_position": 0.0, "acceleration": 0.0024141625146316126, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23169996168798168, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141190.6718593} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2372143577435572, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9175770442944198, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141190.6718593} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.239970207214355, "x": 50.508951719116105, "y": 7.048488488143066, "z": null, "yaw": 2.1828207511829083, "pitch": null, "roll": null}, "v": 0.9193002538940119, "accelerator_pedal_position": 0.24109284876438852, "brake_pedal_position": 0.0, "acceleration": 0.0024141625146316126, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23169996168798168, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141190.6918592} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2372143577435572, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9169262315349894, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141190.6918592} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141190.7118592, "x": 54.44989579164944, "y": 12.13040751155124, "z": null, "yaw": 2.2105450944295457, "pitch": null, "roll": null}, "v": 0.9167095904067866, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2542390442517771, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23104701219928747, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141190.7118592} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2483389251665456, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9164930973232411, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141190.7118592} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.34997010231018, "x": 50.44989579164944, "y": 7.13040751155124, "z": null, "yaw": 2.2105450944295457, "pitch": null, "roll": null}, "v": 0.9167095904067866, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2542390442517771, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23104701219928747, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141190.7318592} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2430280162731567, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9174506506700537, "gear": 1, "accelerator_pedal_position": 0.2483389251665456, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141190.7318592} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.34997010231018, "x": 50.44989579164944, "y": 7.13040751155124, "z": null, "yaw": 2.2105450944295457, "pitch": null, "roll": null}, "v": 0.9167095904067866, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2542390442517771, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23104701219928747, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141190.7518592} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2430280162731567, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9175970047921495, "gear": 1, "accelerator_pedal_position": 0.2430280162731567, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141190.7518592} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.34997010231018, "x": 50.44989579164944, "y": 7.13040751155124, "z": null, "yaw": 2.2105450944295457, "pitch": null, "roll": null}, "v": 0.9167095904067866, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2542390442517771, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23104701219928747, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141190.7718592} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2430280162731567, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9178894129992153, "gear": 1, "accelerator_pedal_position": 0.2430280162731567, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141190.7718592} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.34997010231018, "x": 50.44989579164944, "y": 7.13040751155124, "z": null, "yaw": 2.2105450944295457, "pitch": null, "roll": null}, "v": 0.9167095904067866, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2542390442517771, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23104701219928747, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141190.7918591} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2430280162731567, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9183272761778848, "gear": 1, "accelerator_pedal_position": 0.2430280162731567, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141190.7918591} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.34997010231018, "x": 50.44989579164944, "y": 7.13040751155124, "z": null, "yaw": 2.2105450944295457, "pitch": null, "roll": null}, "v": 0.9167095904067866, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2542390442517771, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23104701219928747, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141190.8118591} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2430280162731567, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.918473031058251, "gear": 1, "accelerator_pedal_position": 0.2430280162731567, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141190.8118591} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141190.8218591, "x": 54.38862184305216, "y": 12.210616499631104, "z": null, "yaw": 2.238269437676183, "pitch": null, "roll": null}, "v": 0.918618686288916, "accelerator_pedal_position": 0.2430280162731567, "brake_pedal_position": 0.0, "acceleration": 0.014555564484791783, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23152817974044104, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141190.831859} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23887150990687223, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9187642419337639, "gear": 1, "accelerator_pedal_position": 0.2430280162731567, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141190.831859} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.459969997406006, "x": 50.38862184305216, "y": 7.210616499631104, "z": null, "yaw": 2.238269437676183, "pitch": null, "roll": null}, "v": 0.918618686288916, "accelerator_pedal_position": 0.2430280162731567, "brake_pedal_position": 0.0, "acceleration": 0.014555564484791783, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23152817974044104, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141190.851859} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24086074196800444, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9185356690528342, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141190.851859} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.459969997406006, "x": 50.38862184305216, "y": 7.210616499631104, "z": null, "yaw": 2.238269437676183, "pitch": null, "roll": null}, "v": 0.918618686288916, "accelerator_pedal_position": 0.2430280162731567, "brake_pedal_position": 0.0, "acceleration": 0.014555564484791783, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23152817974044104, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141190.871859} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24086074196800444, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9185661215055549, "gear": 1, "accelerator_pedal_position": 0.24086074196800444, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141190.871859} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.459969997406006, "x": 50.38862184305216, "y": 7.210616499631104, "z": null, "yaw": 2.238269437676183, "pitch": null, "roll": null}, "v": 0.918618686288916, "accelerator_pedal_position": 0.2430280162731567, "brake_pedal_position": 0.0, "acceleration": 0.014555564484791783, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23152817974044104, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141190.891859} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24086074196800444, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9185762584458447, "gear": 1, "accelerator_pedal_position": 0.24086074196800444, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141190.891859} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.459969997406006, "x": 50.38862184305216, "y": 7.210616499631104, "z": null, "yaw": 2.238269437676183, "pitch": null, "roll": null}, "v": 0.918618686288916, "accelerator_pedal_position": 0.2430280162731567, "brake_pedal_position": 0.0, "acceleration": 0.014555564484791783, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23152817974044104, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141190.911859} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24086074196800444, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.918596511538831, "gear": 1, "accelerator_pedal_position": 0.24086074196800444, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141190.911859} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141190.931859, "x": 54.325080944213575, "y": 12.28917987651631, "z": null, "yaw": 2.2659937809228206, "pitch": null, "roll": null}, "v": 0.918616736946465, "accelerator_pedal_position": 0.24086074196800444, "brake_pedal_position": 0.0, "acceleration": 0.0010102333587227452, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23152768842917545, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141190.931859} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23515574660534933, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.918616736946465, "gear": 1, "accelerator_pedal_position": 0.24086074196800444, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141190.931859} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.56996989250183, "x": 50.325080944213575, "y": 7.289179876516309, "z": null, "yaw": 2.2659937809228206, "pitch": null, "roll": null}, "v": 0.918616736946465, "accelerator_pedal_position": 0.24086074196800444, "brake_pedal_position": 0.0, "acceleration": 0.0010102333587227452, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23152768842917545, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141190.951859} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23787240226609174, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9175780677429101, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141190.951859} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.56996989250183, "x": 50.325080944213575, "y": 7.289179876516309, "z": null, "yaw": 2.2659937809228206, "pitch": null, "roll": null}, "v": 0.918616736946465, "accelerator_pedal_position": 0.24086074196800444, "brake_pedal_position": 0.0, "acceleration": 0.0010102333587227452, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23152768842917545, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141190.971859} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23787240226609174, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.917402108899629, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141190.971859} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.56996989250183, "x": 50.325080944213575, "y": 7.289179876516309, "z": null, "yaw": 2.2659937809228206, "pitch": null, "roll": null}, "v": 0.918616736946465, "accelerator_pedal_position": 0.24086074196800444, "brake_pedal_position": 0.0, "acceleration": 0.0010102333587227452, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23152768842917545, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141190.991859} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23787240226609174, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9170505519272402, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141190.991859} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.56996989250183, "x": 50.325080944213575, "y": 7.289179876516309, "z": null, "yaw": 2.2659937809228206, "pitch": null, "roll": null}, "v": 0.918616736946465, "accelerator_pedal_position": 0.24086074196800444, "brake_pedal_position": 0.0, "acceleration": 0.0010102333587227452, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23152768842917545, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141191.011859} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23787240226609174, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9166994753181904, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141191.011859} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.56996989250183, "x": 50.325080944213575, "y": 7.289179876516309, "z": null, "yaw": 2.2659937809228206, "pitch": null, "roll": null}, "v": 0.918616736946465, "accelerator_pedal_position": 0.24086074196800444, "brake_pedal_position": 0.0, "acceleration": 0.0010102333587227452, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23152768842917545, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141191.031859} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23787240226609174, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.916348878366832, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141191.031859} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141191.041859, "x": 54.25947864802481, "y": 12.365845006706706, "z": null, "yaw": 2.293718124169458, "pitch": null, "roll": null}, "v": 0.9161737595425908, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2542024315538736, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23091196166473196, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141191.051859} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24167042996837124, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9159987603686829, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141191.051859} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.679969787597656, "x": 50.25947864802481, "y": 7.3658450067067065, "z": null, "yaw": 2.293718124169458, "pitch": null, "roll": null}, "v": 0.9161737595425908, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2542024315538736, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23091196166473196, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141191.071859} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23984912273270656, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9161237119101537, "gear": 1, "accelerator_pedal_position": 0.24167042996837124, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141191.071859} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.679969787597656, "x": 50.25947864802481, "y": 7.3658450067067065, "z": null, "yaw": 2.293718124169458, "pitch": null, "roll": null}, "v": 0.9161737595425908, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2542024315538736, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23091196166473196, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141191.0918589} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23984912273270656, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9160209071398453, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141191.0918589} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.679969787597656, "x": 50.25947864802481, "y": 7.3658450067067065, "z": null, "yaw": 2.293718124169458, "pitch": null, "roll": null}, "v": 0.9161737595425908, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2542024315538736, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23091196166473196, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141191.1218588} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23984912273270656, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9157133346032947, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141191.1218588} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141191.1518588, "x": 54.19187480288094, "y": 12.44055257632611, "z": null, "yaw": 2.3214424674160954, "pitch": null, "roll": null}, "v": 0.9157133346032947, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2541709758418676, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23079591640058328, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141191.1518588} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2436930359755222, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9158513349410945, "gear": 1, "accelerator_pedal_position": 0.2436930359755222, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141191.1518588} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.78996968269348, "x": 50.19187480288094, "y": 7.440552576326111, "z": null, "yaw": 2.3214424674160954, "pitch": null, "roll": null}, "v": 0.9157133346032947, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2541709758418676, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23079591640058328, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141191.1818588} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24186020355673443, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9160403456553228, "gear": 1, "accelerator_pedal_position": 0.2436930359755222, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141191.1818588} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.78996968269348, "x": 50.19187480288094, "y": 7.440552576326111, "z": null, "yaw": 2.3214424674160954, "pitch": null, "roll": null}, "v": 0.9157133346032947, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2541709758418676, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23079591640058328, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141191.2018588} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24186020355673443, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9161889539881792, "gear": 1, "accelerator_pedal_position": 0.24186020355673443, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141191.2018588} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.78996968269348, "x": 50.19187480288094, "y": 7.440552576326111, "z": null, "yaw": 2.3214424674160954, "pitch": null, "roll": null}, "v": 0.9157133346032947, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2541709758418676, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23079591640058328, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141191.2218587} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24186020355673443, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9163373593229578, "gear": 1, "accelerator_pedal_position": 0.24186020355673443, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141191.2218587} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.78996968269348, "x": 50.19187480288094, "y": 7.440552576326111, "z": null, "yaw": 2.3214424674160954, "pitch": null, "roll": null}, "v": 0.9157133346032947, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2541709758418676, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23079591640058328, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141191.2418587} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24186020355673443, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9164855619281459, "gear": 1, "accelerator_pedal_position": 0.24186020355673443, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141191.2418587} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141191.2618587, "x": 54.12221299768802, "y": 12.513370475463544, "z": null, "yaw": 2.349166810662733, "pitch": null, "roll": null}, "v": 0.9166335620719004, "accelerator_pedal_position": 0.24186020355673443, "brake_pedal_position": 0.0, "acceleration": 0.0073924232548288615, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23102785005698878, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141191.2618587} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2419591895037419, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9166335620719004, "gear": 1, "accelerator_pedal_position": 0.24186020355673443, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141191.2618587} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.899969577789307, "x": 50.12221299768802, "y": 7.513370475463544, "z": null, "yaw": 2.349166810662733, "pitch": null, "roll": null}, "v": 0.9166335620719004, "accelerator_pedal_position": 0.24186020355673443, "brake_pedal_position": 0.0, "acceleration": 0.0073924232548288615, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23102785005698878, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141191.2818587} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2419168436512814, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9167937290378444, "gear": 1, "accelerator_pedal_position": 0.2419591895037419, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141191.2818587} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.899969577789307, "x": 50.12221299768802, "y": 7.513370475463544, "z": null, "yaw": 2.349166810662733, "pitch": null, "roll": null}, "v": 0.9166335620719004, "accelerator_pedal_position": 0.24186020355673443, "brake_pedal_position": 0.0, "acceleration": 0.0073924232548288615, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23102785005698878, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141191.3018587} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2419168436512814, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9170256348563393, "gear": 1, "accelerator_pedal_position": 0.2419168436512814, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141191.3018587} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.899969577789307, "x": 50.12221299768802, "y": 7.513370475463544, "z": null, "yaw": 2.349166810662733, "pitch": null, "roll": null}, "v": 0.9166335620719004, "accelerator_pedal_position": 0.24186020355673443, "brake_pedal_position": 0.0, "acceleration": 0.0073924232548288615, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23102785005698878, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141191.3218586} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2419168436512814, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9171028311656179, "gear": 1, "accelerator_pedal_position": 0.2419168436512814, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141191.3218586} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.899969577789307, "x": 50.12221299768802, "y": 7.513370475463544, "z": null, "yaw": 2.349166810662733, "pitch": null, "roll": null}, "v": 0.9166335620719004, "accelerator_pedal_position": 0.24186020355673443, "brake_pedal_position": 0.0, "acceleration": 0.0073924232548288615, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23102785005698878, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141191.3418586} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2419168436512814, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9172570655481908, "gear": 1, "accelerator_pedal_position": 0.2419168436512814, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141191.3418586} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.899969577789307, "x": 50.12221299768802, "y": 7.513370475463544, "z": null, "yaw": 2.349166810662733, "pitch": null, "roll": null}, "v": 0.9166335620719004, "accelerator_pedal_position": 0.24186020355673443, "brake_pedal_position": 0.0, "acceleration": 0.0073924232548288615, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23102785005698878, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141191.3618586} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2419168436512814, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9174110891817719, "gear": 1, "accelerator_pedal_position": 0.2419168436512814, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141191.3618586} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141191.3718586, "x": 54.0504908545313, "y": 12.584297139799208, "z": null, "yaw": 2.3768911539093702, "pitch": null, "roll": null}, "v": 0.9174880220547308, "accelerator_pedal_position": 0.2419168436512814, "brake_pedal_position": 0.0, "acceleration": 0.0076880290116331795, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23124320771021156, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141191.3818586} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24361320734778738, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9175649023448471, "gear": 1, "accelerator_pedal_position": 0.2419168436512814, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141191.3818586} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.00996947288513, "x": 50.0504908545313, "y": 7.584297139799208, "z": null, "yaw": 2.3768911539093702, "pitch": null, "roll": null}, "v": 0.9174880220547308, "accelerator_pedal_position": 0.2419168436512814, "brake_pedal_position": 0.0, "acceleration": 0.0076880290116331795, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23124320771021156, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141191.4018586} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.242809863840269, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9179304783069574, "gear": 1, "accelerator_pedal_position": 0.24361320734778738, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141191.4018586} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.00996947288513, "x": 50.0504908545313, "y": 7.584297139799208, "z": null, "yaw": 2.3768911539093702, "pitch": null, "roll": null}, "v": 0.9174880220547308, "accelerator_pedal_position": 0.2419168436512814, "brake_pedal_position": 0.0, "acceleration": 0.0076880290116331795, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23124320771021156, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141191.4218585} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.242809863840269, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9181951710332634, "gear": 1, "accelerator_pedal_position": 0.242809863840269, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141191.4218585} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.00996947288513, "x": 50.0504908545313, "y": 7.584297139799208, "z": null, "yaw": 2.3768911539093702, "pitch": null, "roll": null}, "v": 0.9174880220547308, "accelerator_pedal_position": 0.2419168436512814, "brake_pedal_position": 0.0, "acceleration": 0.0076880290116331795, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23124320771021156, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141191.4418585} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.242809863840269, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9184595019817212, "gear": 1, "accelerator_pedal_position": 0.242809863840269, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141191.4418585} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.00996947288513, "x": 50.0504908545313, "y": 7.584297139799208, "z": null, "yaw": 2.3768911539093702, "pitch": null, "roll": null}, "v": 0.9174880220547308, "accelerator_pedal_position": 0.2419168436512814, "brake_pedal_position": 0.0, "acceleration": 0.0076880290116331795, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23124320771021156, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141191.4618585} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.242809863840269, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9187234716188641, "gear": 1, "accelerator_pedal_position": 0.242809863840269, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141191.4618585} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141191.4818585, "x": 53.97673745454146, "y": 12.653294819123518, "z": null, "yaw": 2.4046154971560076, "pitch": null, "roll": null}, "v": 0.9189870804107025, "accelerator_pedal_position": 0.242809863840269, "brake_pedal_position": 0.0, "acceleration": 0.013166922441528228, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.231621029604827, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141191.4818585} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23584411202339664, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9189870804107025, "gear": 1, "accelerator_pedal_position": 0.242809863840269, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141191.4818585} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.11996936798096, "x": 49.97673745454146, "y": 7.653294819123518, "z": null, "yaw": 2.4046154971560076, "pitch": null, "roll": null}, "v": 0.9189870804107025, "accelerator_pedal_position": 0.242809863840269, "brake_pedal_position": 0.0, "acceleration": 0.013166922441528228, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.231621029604827, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141191.5018585} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23916894656861903, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9183799075358192, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141191.5018585} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.11996936798096, "x": 49.97673745454146, "y": 7.653294819123518, "z": null, "yaw": 2.4046154971560076, "pitch": null, "roll": null}, "v": 0.9189870804107025, "accelerator_pedal_position": 0.242809863840269, "brake_pedal_position": 0.0, "acceleration": 0.013166922441528228, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.231621029604827, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141191.5218585} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23916894656861903, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.918189026890105, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141191.5218585} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.11996936798096, "x": 49.97673745454146, "y": 7.653294819123518, "z": null, "yaw": 2.4046154971560076, "pitch": null, "roll": null}, "v": 0.9189870804107025, "accelerator_pedal_position": 0.242809863840269, "brake_pedal_position": 0.0, "acceleration": 0.013166922441528228, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.231621029604827, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141191.5418584} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23916894656861903, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9179984071452743, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141191.5418584} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.11996936798096, "x": 49.97673745454146, "y": 7.653294819123518, "z": null, "yaw": 2.4046154971560076, "pitch": null, "roll": null}, "v": 0.9189870804107025, "accelerator_pedal_position": 0.242809863840269, "brake_pedal_position": 0.0, "acceleration": 0.013166922441528228, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.231621029604827, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141191.5618584} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23916894656861903, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9178080479301914, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141191.5618584} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.11996936798096, "x": 49.97673745454146, "y": 7.653294819123518, "z": null, "yaw": 2.4046154971560076, "pitch": null, "roll": null}, "v": 0.9189870804107025, "accelerator_pedal_position": 0.242809863840269, "brake_pedal_position": 0.0, "acceleration": 0.013166922441528228, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.231621029604827, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141191.5818584} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23916894656861903, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9176179488742873, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141191.5818584} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141191.5918584, "x": 53.9011023663734, "y": 12.720220111754914, "z": null, "yaw": 2.432339840402645, "pitch": null, "roll": null}, "v": 0.9175229967903792, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25429463433591093, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23125202272453954, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141191.6018584} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.251268846089637, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9174281096075587, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141191.6018584} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.22996926307678, "x": 49.9011023663734, "y": 7.720220111754914, "z": null, "yaw": 2.432339840402645, "pitch": null, "roll": null}, "v": 0.9175229967903792, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25429463433591093, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23125202272453954, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141191.6218584} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2454993602185283, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9187505002761368, "gear": 1, "accelerator_pedal_position": 0.251268846089637, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141191.6218584} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.22996926307678, "x": 49.9011023663734, "y": 7.720220111754914, "z": null, "yaw": 2.432339840402645, "pitch": null, "roll": null}, "v": 0.9175229967903792, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25429463433591093, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23125202272453954, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141191.6418583} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2454993602185283, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9193501442244124, "gear": 1, "accelerator_pedal_position": 0.2454993602185283, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141191.6418583} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.22996926307678, "x": 49.9011023663734, "y": 7.720220111754914, "z": null, "yaw": 2.432339840402645, "pitch": null, "roll": null}, "v": 0.9175229967903792, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25429463433591093, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23125202272453954, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141191.6618583} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2454993602185283, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.919948968332025, "gear": 1, "accelerator_pedal_position": 0.2454993602185283, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141191.6618583} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.22996926307678, "x": 49.9011023663734, "y": 7.720220111754914, "z": null, "yaw": 2.432339840402645, "pitch": null, "roll": null}, "v": 0.9175229967903792, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25429463433591093, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23125202272453954, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141191.6818583} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2454993602185283, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9205469735764837, "gear": 1, "accelerator_pedal_position": 0.2454993602185283, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141191.6818583} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141191.7018583, "x": 53.82354998644381, "y": 12.785097555871038, "z": null, "yaw": 2.4600641836492825, "pitch": null, "roll": null}, "v": 0.9211441609345494, "accelerator_pedal_position": 0.2454993602185283, "brake_pedal_position": 0.0, "acceleration": 0.029828727666836197, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23216469906713397, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141191.7018583} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25479277892302843, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9211441609345494, "gear": 1, "accelerator_pedal_position": 0.2454993602185283, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141191.7018583} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.33996915817261, "x": 49.82354998644381, "y": 7.7850975558710385, "z": null, "yaw": 2.4600641836492825, "pitch": null, "roll": null}, "v": 0.9211441609345494, "accelerator_pedal_position": 0.2454993602185283, "brake_pedal_position": 0.0, "acceleration": 0.029828727666836197, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23216469906713397, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141191.7218583} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2503862070044145, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9229018112253432, "gear": 1, "accelerator_pedal_position": 0.25479277892302843, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141191.7218583} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.33996915817261, "x": 49.82354998644381, "y": 7.7850975558710385, "z": null, "yaw": 2.4600641836492825, "pitch": null, "roll": null}, "v": 0.9211441609345494, "accelerator_pedal_position": 0.2454993602185283, "brake_pedal_position": 0.0, "acceleration": 0.029828727666836197, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23216469906713397, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141191.7418582} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2503862070044145, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.924106423234676, "gear": 1, "accelerator_pedal_position": 0.2503862070044145, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141191.7418582} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.33996915817261, "x": 49.82354998644381, "y": 7.7850975558710385, "z": null, "yaw": 2.4600641836492825, "pitch": null, "roll": null}, "v": 0.9211441609345494, "accelerator_pedal_position": 0.2454993602185283, "brake_pedal_position": 0.0, "acceleration": 0.029828727666836197, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23216469906713397, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141191.7618582} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2503862070044145, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9253093860661197, "gear": 1, "accelerator_pedal_position": 0.2503862070044145, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141191.7618582} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.33996915817261, "x": 49.82354998644381, "y": 7.7850975558710385, "z": null, "yaw": 2.4600641836492825, "pitch": null, "roll": null}, "v": 0.9211441609345494, "accelerator_pedal_position": 0.2454993602185283, "brake_pedal_position": 0.0, "acceleration": 0.029828727666836197, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23216469906713397, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141191.7818582} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2503862070044145, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9265107013988368, "gear": 1, "accelerator_pedal_position": 0.2503862070044145, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141191.7818582} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.33996915817261, "x": 49.82354998644381, "y": 7.7850975558710385, "z": null, "yaw": 2.4600641836492825, "pitch": null, "roll": null}, "v": 0.9211441609345494, "accelerator_pedal_position": 0.2454993602185283, "brake_pedal_position": 0.0, "acceleration": 0.029828727666836197, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23216469906713397, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141191.8018582} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2503862070044145, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9277103709120675, "gear": 1, "accelerator_pedal_position": 0.2503862070044145, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141191.8018582} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141191.8118582, "x": 53.7437616413725, "y": 12.848168659393352, "z": null, "yaw": 2.48778852689592, "pitch": null, "roll": null}, "v": 0.9283095890111577, "accelerator_pedal_position": 0.2503862070044145, "brake_pedal_position": 0.0, "acceleration": 0.059880727396531996, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23397066986263376, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141191.8218582} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23207346801791734, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.928908396285123, "gear": 1, "accelerator_pedal_position": 0.2503862070044145, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141191.8218582} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.44996905326843, "x": 49.7437616413725, "y": 7.848168659393352, "z": null, "yaw": 2.48778852689592, "pitch": null, "roll": null}, "v": 0.9283095890111577, "accelerator_pedal_position": 0.2503862070044145, "brake_pedal_position": 0.0, "acceleration": 0.059880727396531996, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23397066986263376, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141191.8418581} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24083121801928753, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9278164717388522, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141191.8418581} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.44996905326843, "x": 49.7437616413725, "y": 7.848168659393352, "z": null, "yaw": 2.48778852689592, "pitch": null, "roll": null}, "v": 0.9283095890111577, "accelerator_pedal_position": 0.2503862070044145, "brake_pedal_position": 0.0, "acceleration": 0.059880727396531996, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23397066986263376, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141191.8618581} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24083121801928753, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.927820387495768, "gear": 1, "accelerator_pedal_position": 0.24083121801928753, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141191.8618581} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.44996905326843, "x": 49.7437616413725, "y": 7.848168659393352, "z": null, "yaw": 2.48778852689592, "pitch": null, "roll": null}, "v": 0.9283095890111577, "accelerator_pedal_position": 0.2503862070044145, "brake_pedal_position": 0.0, "acceleration": 0.059880727396531996, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23397066986263376, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141191.881858} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24083121801928753, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9278242978855212, "gear": 1, "accelerator_pedal_position": 0.24083121801928753, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141191.881858} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.44996905326843, "x": 49.7437616413725, "y": 7.848168659393352, "z": null, "yaw": 2.48778852689592, "pitch": null, "roll": null}, "v": 0.9283095890111577, "accelerator_pedal_position": 0.2503862070044145, "brake_pedal_position": 0.0, "acceleration": 0.059880727396531996, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23397066986263376, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141191.901858} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24083121801928753, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9278282029154623, "gear": 1, "accelerator_pedal_position": 0.24083121801928753, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141191.901858} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141191.921858, "x": 53.66195843822704, "y": 12.909227981399017, "z": null, "yaw": 2.5155128701425573, "pitch": null, "roll": null}, "v": 0.9278321025929315, "accelerator_pedal_position": 0.24083121801928753, "brake_pedal_position": 0.0, "acceleration": 0.00019478338488021496, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2338503244321382, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141191.921858} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24021670981242862, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9278321025929315, "gear": 1, "accelerator_pedal_position": 0.24083121801928753, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141191.921858} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.55996894836426, "x": 49.66195843822704, "y": 7.909227981399017, "z": null, "yaw": 2.5155128701425573, "pitch": null, "roll": null}, "v": 0.9278321025929315, "accelerator_pedal_position": 0.24083121801928753, "brake_pedal_position": 0.0, "acceleration": 0.00019478338488021496, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2338503244321382, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141191.941858} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24050683865431124, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9277592097296563, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141191.941858} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.55996894836426, "x": 49.66195843822704, "y": 7.909227981399017, "z": null, "yaw": 2.5155128701425573, "pitch": null, "roll": null}, "v": 0.9278321025929315, "accelerator_pedal_position": 0.24083121801928753, "brake_pedal_position": 0.0, "acceleration": 0.00019478338488021496, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2338503244321382, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141191.961858} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24050683865431124, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9277226704505143, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141191.961858} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.55996894836426, "x": 49.66195843822704, "y": 7.909227981399017, "z": null, "yaw": 2.5155128701425573, "pitch": null, "roll": null}, "v": 0.9278321025929315, "accelerator_pedal_position": 0.24083121801928753, "brake_pedal_position": 0.0, "acceleration": 0.00019478338488021496, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2338503244321382, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141191.981858} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24050683865431124, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9276861812529394, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141191.981858} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.55996894836426, "x": 49.66195843822704, "y": 7.909227981399017, "z": null, "yaw": 2.5155128701425573, "pitch": null, "roll": null}, "v": 0.9278321025929315, "accelerator_pedal_position": 0.24083121801928753, "brake_pedal_position": 0.0, "acceleration": 0.00019478338488021496, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2338503244321382, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141192.001858} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24050683865431124, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9276497420677565, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141192.001858} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.55996894836426, "x": 49.66195843822704, "y": 7.909227981399017, "z": null, "yaw": 2.5155128701425573, "pitch": null, "roll": null}, "v": 0.9278321025929315, "accelerator_pedal_position": 0.24083121801928753, "brake_pedal_position": 0.0, "acceleration": 0.00019478338488021496, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2338503244321382, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141192.021858} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24050683865431124, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9276133528258871, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141192.021858} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141192.031858, "x": 53.578521467707894, "y": 12.967976703944196, "z": null, "yaw": 2.5432372133891947, "pitch": null, "roll": null}, "v": 0.9275951769121346, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2549840869679133, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2337906098057895, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141192.041858} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2344146394748763, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9275770134583499, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141192.041858} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.66996884346008, "x": 49.578521467707894, "y": 7.9679767039441955, "z": null, "yaw": 2.5432372133891947, "pitch": null, "roll": null}, "v": 0.9275951769121346, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2549840869679133, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2337906098057895, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141192.061858} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23731445064564646, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9267794600014737, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141192.061858} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.66996884346008, "x": 49.578521467707894, "y": 7.9679767039441955, "z": null, "yaw": 2.5432372133891947, "pitch": null, "roll": null}, "v": 0.9275951769121346, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2549840869679133, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2337906098057895, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141192.081858} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23731445064564646, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9263453516443201, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141192.081858} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.66996884346008, "x": 49.578521467707894, "y": 7.9679767039441955, "z": null, "yaw": 2.5432372133891947, "pitch": null, "roll": null}, "v": 0.9275951769121346, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2549840869679133, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2337906098057895, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141192.101858} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23731445064564646, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.925911838064211, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141192.101858} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.66996884346008, "x": 49.578521467707894, "y": 7.9679767039441955, "z": null, "yaw": 2.5432372133891947, "pitch": null, "roll": null}, "v": 0.9275951769121346, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2549840869679133, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2337906098057895, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141192.121858} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23731445064564646, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9254789183710875, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141192.121858} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141192.1418579, "x": 53.493607407055514, "y": 13.02431143207167, "z": null, "yaw": 2.570961556635832, "pitch": null, "roll": null}, "v": 0.925046591676419, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25480944155154256, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23314826569789596, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141192.1418579} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24099557006561176, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.925046591676419, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141192.1418579} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.77996873855591, "x": 49.493607407055514, "y": 8.02431143207167, "z": null, "yaw": 2.570961556635832, "pitch": null, "roll": null}, "v": 0.925046591676419, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25480944155154256, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23314826569789596, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141192.1618578} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23922934885636205, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9250748394252692, "gear": 1, "accelerator_pedal_position": 0.24099557006561176, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141192.1618578} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.77996873855591, "x": 49.493607407055514, "y": 8.02431143207167, "z": null, "yaw": 2.570961556635832, "pitch": null, "roll": null}, "v": 0.925046591676419, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25480944155154256, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23314826569789596, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141192.1818578} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23922934885636205, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9248823464531273, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141192.1818578} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.77996873855591, "x": 49.493607407055514, "y": 8.02431143207167, "z": null, "yaw": 2.570961556635832, "pitch": null, "roll": null}, "v": 0.925046591676419, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25480944155154256, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23314826569789596, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141192.2018578} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23922934885636205, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.924690117100686, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141192.2018578} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.77996873855591, "x": 49.493607407055514, "y": 8.02431143207167, "z": null, "yaw": 2.570961556635832, "pitch": null, "roll": null}, "v": 0.925046591676419, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25480944155154256, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23314826569789596, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141192.2218578} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23922934885636205, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9244981509921416, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141192.2218578} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.77996873855591, "x": 49.493607407055514, "y": 8.02431143207167, "z": null, "yaw": 2.570961556635832, "pitch": null, "roll": null}, "v": 0.925046591676419, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25480944155154256, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23314826569789596, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141192.2418578} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23922934885636205, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9243064477522656, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141192.2418578} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141192.2518578, "x": 53.40731843733344, "y": 13.078173910073689, "z": null, "yaw": 2.5986858998824696, "pitch": null, "roll": null}, "v": 0.9242106945909764, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25475218880951217, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23293758662775346, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141192.2618577} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24185776529604439, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9241150070064039, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141192.2618577} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.88996863365173, "x": 49.40731843733344, "y": 8.078173910073689, "z": null, "yaw": 2.5986858998824696, "pitch": null, "roll": null}, "v": 0.9242106945909764, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25475218880951217, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23293758662775346, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141192.2818577} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.240601775678905, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9242522679358771, "gear": 1, "accelerator_pedal_position": 0.24185776529604439, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141192.2818577} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.88996863365173, "x": 49.40731843733344, "y": 8.078173910073689, "z": null, "yaw": 2.5986858998824696, "pitch": null, "roll": null}, "v": 0.9242106945909764, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25475218880951217, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23293758662775346, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141192.3018577} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.240601775678905, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9242323959838261, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141192.3018577} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.88996863365173, "x": 49.40731843733344, "y": 8.078173910073689, "z": null, "yaw": 2.5986858998824696, "pitch": null, "roll": null}, "v": 0.9242106945909764, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25475218880951217, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23293758662775346, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141192.3218577} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.240601775678905, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9242125512409671, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141192.3218577} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.88996863365173, "x": 49.40731843733344, "y": 8.078173910073689, "z": null, "yaw": 2.5986858998824696, "pitch": null, "roll": null}, "v": 0.9242106945909764, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25475218880951217, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23293758662775346, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141192.3418577} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.240601775678905, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9241927336698872, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141192.3418577} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141192.3618577, "x": 53.31962176873757, "y": 13.129592786676351, "z": null, "yaw": 2.626410243129107, "pitch": null, "roll": null}, "v": 0.9241729432332252, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2547496034517049, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2329280717950233, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141192.3618577} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24273678059592413, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9241729432332252, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141192.3618577} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.99996852874756, "x": 49.31962176873757, "y": 8.129592786676351, "z": null, "yaw": 2.626410243129107, "pitch": null, "roll": null}, "v": 0.9241729432332252, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2547496034517049, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2329280717950233, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141192.3818576} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24171991410020807, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9244199641239566, "gear": 1, "accelerator_pedal_position": 0.24273678059592413, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141192.3818576} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.99996852874756, "x": 49.31962176873757, "y": 8.129592786676351, "z": null, "yaw": 2.626410243129107, "pitch": null, "roll": null}, "v": 0.9241729432332252, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2547496034517049, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2329280717950233, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141192.4018576} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24171991410020807, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9245395819917729, "gear": 1, "accelerator_pedal_position": 0.24171991410020807, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141192.4018576} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.99996852874756, "x": 49.31962176873757, "y": 8.129592786676351, "z": null, "yaw": 2.626410243129107, "pitch": null, "roll": null}, "v": 0.9241729432332252, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2547496034517049, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2329280717950233, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141192.4218576} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24171991410020807, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.924659036062683, "gear": 1, "accelerator_pedal_position": 0.24171991410020807, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141192.4218576} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.99996852874756, "x": 49.31962176873757, "y": 8.129592786676351, "z": null, "yaw": 2.626410243129107, "pitch": null, "roll": null}, "v": 0.9241729432332252, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2547496034517049, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2329280717950233, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141192.4418576} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24171991410020807, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9247783265552738, "gear": 1, "accelerator_pedal_position": 0.24171991410020807, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141192.4418576} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.99996852874756, "x": 49.31962176873757, "y": 8.129592786676351, "z": null, "yaw": 2.626410243129107, "pitch": null, "roll": null}, "v": 0.9241729432332252, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2547496034517049, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2329280717950233, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141192.4618576} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24171991410020807, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9248974536878566, "gear": 1, "accelerator_pedal_position": 0.24171991410020807, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141192.4618576} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141192.4718575, "x": 53.230496973905026, "y": 13.17858070946744, "z": null, "yaw": 2.6541345863757444, "pitch": null, "roll": null}, "v": 0.9249569560622918, "accelerator_pedal_position": 0.24171991410020807, "brake_pedal_position": 0.0, "acceleration": 0.005946161617505552, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23312567398395792, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141192.4818575} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24404539341072706, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9250164176784669, "gear": 1, "accelerator_pedal_position": 0.24171991410020807, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141192.4818575} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.109968423843384, "x": 49.230496973905026, "y": 8.17858070946744, "z": null, "yaw": 2.6541345863757444, "pitch": null, "roll": null}, "v": 0.9249569560622918, "accelerator_pedal_position": 0.24171991410020807, "brake_pedal_position": 0.0, "acceleration": 0.005946161617505552, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23312567398395792, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141192.5018575} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24294211303988336, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9254258040947799, "gear": 1, "accelerator_pedal_position": 0.24404539341072706, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141192.5018575} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.109968423843384, "x": 49.230496973905026, "y": 8.17858070946744, "z": null, "yaw": 2.6541345863757444, "pitch": null, "roll": null}, "v": 0.9249569560622918, "accelerator_pedal_position": 0.24171991410020807, "brake_pedal_position": 0.0, "acceleration": 0.005946161617505552, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23312567398395792, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141192.5218575} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24294211303988336, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9256967669869235, "gear": 1, "accelerator_pedal_position": 0.24294211303988336, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141192.5218575} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.109968423843384, "x": 49.230496973905026, "y": 8.17858070946744, "z": null, "yaw": 2.6541345863757444, "pitch": null, "roll": null}, "v": 0.9249569560622918, "accelerator_pedal_position": 0.24171991410020807, "brake_pedal_position": 0.0, "acceleration": 0.005946161617505552, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23312567398395792, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141192.5418575} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24294211303988336, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9259673587189196, "gear": 1, "accelerator_pedal_position": 0.24294211303988336, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141192.5418575} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.109968423843384, "x": 49.230496973905026, "y": 8.17858070946744, "z": null, "yaw": 2.6541345863757444, "pitch": null, "roll": null}, "v": 0.9249569560622918, "accelerator_pedal_position": 0.24171991410020807, "brake_pedal_position": 0.0, "acceleration": 0.005946161617505552, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23312567398395792, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141192.5618575} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24294211303988336, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9262375797698987, "gear": 1, "accelerator_pedal_position": 0.24294211303988336, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141192.5618575} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141192.5818574, "x": 53.13994170743928, "y": 13.225133828565383, "z": null, "yaw": 2.681858929622382, "pitch": null, "roll": null}, "v": 0.9265074306184556, "accelerator_pedal_position": 0.24294211303988336, "brake_pedal_position": 0.0, "acceleration": 0.013478674778436006, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23351645479114214, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141192.5818574} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25365191271097887, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9265074306184556, "gear": 1, "accelerator_pedal_position": 0.24294211303988336, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141192.5818574} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.21996831893921, "x": 49.13994170743928, "y": 8.225133828565383, "z": null, "yaw": 2.681858929622382, "pitch": null, "roll": null}, "v": 0.9265074306184556, "accelerator_pedal_position": 0.24294211303988336, "brake_pedal_position": 0.0, "acceleration": 0.013478674778436006, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23351645479114214, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141192.6018574} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24856009929255318, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9281151779235852, "gear": 1, "accelerator_pedal_position": 0.25365191271097887, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141192.6018574} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.21996831893921, "x": 49.13994170743928, "y": 8.225133828565383, "z": null, "yaw": 2.681858929622382, "pitch": null, "roll": null}, "v": 0.9265074306184556, "accelerator_pedal_position": 0.24294211303988336, "brake_pedal_position": 0.0, "acceleration": 0.013478674778436006, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23351645479114214, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141192.6218574} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24856009929255318, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9290844631809209, "gear": 1, "accelerator_pedal_position": 0.24856009929255318, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141192.6218574} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.21996831893921, "x": 49.13994170743928, "y": 8.225133828565383, "z": null, "yaw": 2.681858929622382, "pitch": null, "roll": null}, "v": 0.9265074306184556, "accelerator_pedal_position": 0.24294211303988336, "brake_pedal_position": 0.0, "acceleration": 0.013478674778436006, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23351645479114214, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141192.6418574} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24856009929255318, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9300524194836675, "gear": 1, "accelerator_pedal_position": 0.24856009929255318, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141192.6418574} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.21996831893921, "x": 49.13994170743928, "y": 8.225133828565383, "z": null, "yaw": 2.681858929622382, "pitch": null, "roll": null}, "v": 0.9265074306184556, "accelerator_pedal_position": 0.24294211303988336, "brake_pedal_position": 0.0, "acceleration": 0.013478674778436006, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23351645479114214, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141192.6618574} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24856009929255318, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9310190482792627, "gear": 1, "accelerator_pedal_position": 0.24856009929255318, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141192.6618574} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.21996831893921, "x": 49.13994170743928, "y": 8.225133828565383, "z": null, "yaw": 2.681858929622382, "pitch": null, "roll": null}, "v": 0.9265074306184556, "accelerator_pedal_position": 0.24294211303988336, "brake_pedal_position": 0.0, "acceleration": 0.013478674778436006, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23351645479114214, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141192.6818573} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24856009929255318, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9319843510147009, "gear": 1, "accelerator_pedal_position": 0.24856009929255318, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141192.6818573} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141192.6918573, "x": 53.04775258780785, "y": 13.269338965269586, "z": null, "yaw": 2.7095832728690192, "pitch": null, "roll": null}, "v": 0.9324665055619245, "accelerator_pedal_position": 0.24856009929255318, "brake_pedal_position": 0.0, "acceleration": 0.04818235746041244, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2350183769653709, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141192.7018573} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2290862355525905, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9329483291365286, "gear": 1, "accelerator_pedal_position": 0.24856009929255318, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141192.7018573} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.329968214035034, "x": 49.04775258780785, "y": 8.269338965269586, "z": null, "yaw": 2.7095832728690192, "pitch": null, "roll": null}, "v": 0.9324665055619245, "accelerator_pedal_position": 0.24856009929255318, "brake_pedal_position": 0.0, "acceleration": 0.04818235746041244, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2350183769653709, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141192.7218573} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23839065008794078, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.931477586752015, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141192.7218573} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.329968214035034, "x": 49.04775258780785, "y": 8.269338965269586, "z": null, "yaw": 2.7095832728690192, "pitch": null, "roll": null}, "v": 0.9324665055619245, "accelerator_pedal_position": 0.24856009929255318, "brake_pedal_position": 0.0, "acceleration": 0.04818235746041244, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2350183769653709, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141192.7418573} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23839065008794078, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9311715153887415, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141192.7418573} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.329968214035034, "x": 49.04775258780785, "y": 8.269338965269586, "z": null, "yaw": 2.7095832728690192, "pitch": null, "roll": null}, "v": 0.9324665055619245, "accelerator_pedal_position": 0.24856009929255318, "brake_pedal_position": 0.0, "acceleration": 0.04818235746041244, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2350183769653709, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141192.7618573} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23839065008794078, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9308658639640359, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141192.7618573} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.329968214035034, "x": 49.04775258780785, "y": 8.269338965269586, "z": null, "yaw": 2.7095832728690192, "pitch": null, "roll": null}, "v": 0.9324665055619245, "accelerator_pedal_position": 0.24856009929255318, "brake_pedal_position": 0.0, "acceleration": 0.04818235746041244, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2350183769653709, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141192.7818573} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23839065008794078, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.930560631864374, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141192.7818573} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141192.8018572, "x": 52.954183593485766, "y": 13.31105853451733, "z": null, "yaw": 2.7373076161156566, "pitch": null, "roll": null}, "v": 0.9302558184772275, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25516654980196873, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23446119653312503, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141192.8018572} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24226238244321807, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9301035686097041, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141192.8018572} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.43996810913086, "x": 48.954183593485766, "y": 8.31105853451733, "z": null, "yaw": 2.7373076161156566, "pitch": null, "roll": null}, "v": 0.9302558184772275, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25516654980196873, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23446119653312503, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141192.8218572} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24040714033270572, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9301934064632663, "gear": 1, "accelerator_pedal_position": 0.24226238244321807, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141192.8218572} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.43996810913086, "x": 48.954183593485766, "y": 8.31105853451733, "z": null, "yaw": 2.7373076161156566, "pitch": null, "roll": null}, "v": 0.9302558184772275, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25516654980196873, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23446119653312503, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141192.8418572} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24040714033270572, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.930114931095352, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141192.8418572} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.43996810913086, "x": 48.954183593485766, "y": 8.31105853451733, "z": null, "yaw": 2.7373076161156566, "pitch": null, "roll": null}, "v": 0.9302558184772275, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25516654980196873, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23446119653312503, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141192.8618572} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24040714033270572, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9300627038694531, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141192.8618572} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.43996810913086, "x": 48.954183593485766, "y": 8.31105853451733, "z": null, "yaw": 2.7373076161156566, "pitch": null, "roll": null}, "v": 0.9302558184772275, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25516654980196873, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23446119653312503, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141192.8818572} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24040714033270572, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9300366171249996, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141192.8818572} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.43996810913086, "x": 48.954183593485766, "y": 8.31105853451733, "z": null, "yaw": 2.7373076161156566, "pitch": null, "roll": null}, "v": 0.9302558184772275, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25516654980196873, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23446119653312503, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141192.9018571} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24040714033270572, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9299844973109773, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141192.9018571} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141192.9118571, "x": 52.859623303503554, "y": 13.35011424463165, "z": null, "yaw": 2.765031959362294, "pitch": null, "roll": null}, "v": 0.9299584642165921, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25514615066251045, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23438625151869133, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141192.921857} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24318280498204728, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9299324489807611, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141192.921857} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.549968004226685, "x": 48.859623303503554, "y": 8.35011424463165, "z": null, "yaw": 2.765031959362294, "pitch": null, "roll": null}, "v": 0.9299584642165921, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25514615066251045, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23438625151869133, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141192.941857} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2418595050297369, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9302273111100077, "gear": 1, "accelerator_pedal_position": 0.24318280498204728, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141192.941857} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.549968004226685, "x": 48.859623303503554, "y": 8.35011424463165, "z": null, "yaw": 2.765031959362294, "pitch": null, "roll": null}, "v": 0.9299584642165921, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25514615066251045, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23438625151869133, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141192.961857} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2418595050297369, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9304208976093307, "gear": 1, "accelerator_pedal_position": 0.2418595050297369, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141192.961857} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.549968004226685, "x": 48.859623303503554, "y": 8.35011424463165, "z": null, "yaw": 2.765031959362294, "pitch": null, "roll": null}, "v": 0.9299584642165921, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25514615066251045, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23438625151869133, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141192.981857} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2418595050297369, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9304853379202137, "gear": 1, "accelerator_pedal_position": 0.2418595050297369, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141192.981857} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.549968004226685, "x": 48.859623303503554, "y": 8.35011424463165, "z": null, "yaw": 2.765031959362294, "pitch": null, "roll": null}, "v": 0.9299584642165921, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25514615066251045, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23438625151869133, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141193.001857} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2418595050297369, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9306140859358043, "gear": 1, "accelerator_pedal_position": 0.2418595050297369, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141193.001857} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141193.021857, "x": 52.76399383928208, "y": 13.38654207465485, "z": null, "yaw": 2.7927563026089315, "pitch": null, "roll": null}, "v": 0.9307426573397597, "accelerator_pedal_position": 0.2418595050297369, "brake_pedal_position": 0.0, "acceleration": 0.006421954626948834, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23458389914885816, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141193.021857} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24413197128747138, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9307426573397597, "gear": 1, "accelerator_pedal_position": 0.2418595050297369, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141193.021857} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.65996789932251, "x": 48.76399383928208, "y": 8.38654207465485, "z": null, "yaw": 2.7927563026089315, "pitch": null, "roll": null}, "v": 0.9307426573397597, "accelerator_pedal_position": 0.2418595050297369, "brake_pedal_position": 0.0, "acceleration": 0.006421954626948834, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23458389914885816, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141193.041857} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24305394309451536, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9311550131930276, "gear": 1, "accelerator_pedal_position": 0.24413197128747138, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141193.041857} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.65996789932251, "x": 48.76399383928208, "y": 8.38654207465485, "z": null, "yaw": 2.7927563026089315, "pitch": null, "roll": null}, "v": 0.9307426573397597, "accelerator_pedal_position": 0.2418595050297369, "brake_pedal_position": 0.0, "acceleration": 0.006421954626948834, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23458389914885816, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141193.061857} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24305394309451536, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9314320960289609, "gear": 1, "accelerator_pedal_position": 0.24305394309451536, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141193.061857} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.65996789932251, "x": 48.76399383928208, "y": 8.38654207465485, "z": null, "yaw": 2.7927563026089315, "pitch": null, "roll": null}, "v": 0.9307426573397597, "accelerator_pedal_position": 0.2418595050297369, "brake_pedal_position": 0.0, "acceleration": 0.006421954626948834, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23458389914885816, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141193.081857} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24305394309451536, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9317087986866974, "gear": 1, "accelerator_pedal_position": 0.24305394309451536, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141193.081857} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.65996789932251, "x": 48.76399383928208, "y": 8.38654207465485, "z": null, "yaw": 2.7927563026089315, "pitch": null, "roll": null}, "v": 0.9307426573397597, "accelerator_pedal_position": 0.2418595050297369, "brake_pedal_position": 0.0, "acceleration": 0.006421954626948834, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23458389914885816, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141193.101857} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24305394309451536, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9321231409131342, "gear": 1, "accelerator_pedal_position": 0.24305394309451536, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141193.101857} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.65996789932251, "x": 48.76399383928208, "y": 8.38654207465485, "z": null, "yaw": 2.7927563026089315, "pitch": null, "roll": null}, "v": 0.9307426573397597, "accelerator_pedal_position": 0.2418595050297369, "brake_pedal_position": 0.0, "acceleration": 0.006421954626948834, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23458389914885816, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141193.121857} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24305394309451536, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9322610654311022, "gear": 1, "accelerator_pedal_position": 0.24305394309451536, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141193.121857} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141193.131857, "x": 52.66726407035984, "y": 13.420349246731858, "z": null, "yaw": 2.820480645855569, "pitch": null, "roll": null}, "v": 0.932398895272382, "accelerator_pedal_position": 0.24305394309451536, "brake_pedal_position": 0.0, "acceleration": 0.013773522578050257, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23500133650287744, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141193.141857} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23682994588845402, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9325366304981625, "gear": 1, "accelerator_pedal_position": 0.24305394309451536, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141193.141857} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.769967794418335, "x": 48.66726407035984, "y": 8.420349246731858, "z": null, "yaw": 2.820480645855569, "pitch": null, "roll": null}, "v": 0.932398895272382, "accelerator_pedal_position": 0.24305394309451536, "brake_pedal_position": 0.0, "acceleration": 0.013773522578050257, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23500133650287744, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141193.161857} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23980241613460113, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9319688499563876, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141193.161857} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.769967794418335, "x": 48.66726407035984, "y": 8.420349246731858, "z": null, "yaw": 2.820480645855569, "pitch": null, "roll": null}, "v": 0.932398895272382, "accelerator_pedal_position": 0.24305394309451536, "brake_pedal_position": 0.0, "acceleration": 0.013773522578050257, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23500133650287744, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141193.1818569} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23980241613460113, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9319036599460931, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141193.1818569} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.769967794418335, "x": 48.66726407035984, "y": 8.420349246731858, "z": null, "yaw": 2.820480645855569, "pitch": null, "roll": null}, "v": 0.932398895272382, "accelerator_pedal_position": 0.24305394309451536, "brake_pedal_position": 0.0, "acceleration": 0.013773522578050257, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23500133650287744, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141193.2018569} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23980241613460113, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9317734141307181, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141193.2018569} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.769967794418335, "x": 48.66726407035984, "y": 8.420349246731858, "z": null, "yaw": 2.820480645855569, "pitch": null, "roll": null}, "v": 0.932398895272382, "accelerator_pedal_position": 0.24305394309451536, "brake_pedal_position": 0.0, "acceleration": 0.013773522578050257, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23500133650287744, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141193.2218568} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23980241613460113, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9316433470453329, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141193.2218568} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141193.2418568, "x": 52.56959067237764, "y": 13.451476602223257, "z": null, "yaw": 2.8482049891022063, "pitch": null, "roll": null}, "v": 0.9315134584379104, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25525284615440513, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23477817145994923, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141193.2418568} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24324427341741311, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9315134584379104, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141193.2418568} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.87996768951416, "x": 48.56959067237764, "y": 8.451476602223257, "z": null, "yaw": 2.8482049891022063, "pitch": null, "roll": null}, "v": 0.9315134584379104, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25525284615440513, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23477817145994923, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141193.2618568} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2416006624153412, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9318138325805676, "gear": 1, "accelerator_pedal_position": 0.24324427341741311, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141193.2618568} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.87996768951416, "x": 48.56959067237764, "y": 8.451476602223257, "z": null, "yaw": 2.8482049891022063, "pitch": null, "roll": null}, "v": 0.9315134584379104, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25525284615440513, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23477817145994923, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141193.2818568} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2416006624153412, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9319084136763489, "gear": 1, "accelerator_pedal_position": 0.2416006624153412, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141193.2818568} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.87996768951416, "x": 48.56959067237764, "y": 8.451476602223257, "z": null, "yaw": 2.8482049891022063, "pitch": null, "roll": null}, "v": 0.9315134584379104, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25525284615440513, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23477817145994923, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141193.3018568} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2416006624153412, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9320028649801202, "gear": 1, "accelerator_pedal_position": 0.2416006624153412, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141193.3018568} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.87996768951416, "x": 48.56959067237764, "y": 8.451476602223257, "z": null, "yaw": 2.8482049891022063, "pitch": null, "roll": null}, "v": 0.9315134584379104, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25525284615440513, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23477817145994923, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141193.3218567} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2416006624153412, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9320971866664255, "gear": 1, "accelerator_pedal_position": 0.2416006624153412, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141193.3218567} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.87996768951416, "x": 48.56959067237764, "y": 8.451476602223257, "z": null, "yaw": 2.8482049891022063, "pitch": null, "roll": null}, "v": 0.9315134584379104, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25525284615440513, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23477817145994923, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141193.3418567} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2416006624153412, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9321913789095841, "gear": 1, "accelerator_pedal_position": 0.2416006624153412, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141193.3418567} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141193.3518567, "x": 52.47109630919893, "y": 13.479882712268063, "z": null, "yaw": 2.8759293323488437, "pitch": null, "roll": null}, "v": 0.9322384265443968, "accelerator_pedal_position": 0.2416006624153412, "brake_pedal_position": 0.0, "acceleration": 0.0047015339294028125, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23496089204746826, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141193.3618567} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2423754701577446, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9323808504330933, "gear": 1, "accelerator_pedal_position": 0.2423754701577446, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141193.3618567} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.989967584609985, "x": 48.47109630919893, "y": 8.479882712268063, "z": null, "yaw": 2.8759293323488437, "pitch": null, "roll": null}, "v": 0.9322384265443968, "accelerator_pedal_position": 0.2416006624153412, "brake_pedal_position": 0.0, "acceleration": 0.0047015339294028125, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23496089204746826, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141193.3818567} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2420103051465328, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9324761934877103, "gear": 1, "accelerator_pedal_position": 0.2423754701577446, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141193.3818567} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.989967584609985, "x": 48.47109630919893, "y": 8.479882712268063, "z": null, "yaw": 2.8759293323488437, "pitch": null, "roll": null}, "v": 0.9322384265443968, "accelerator_pedal_position": 0.2416006624153412, "brake_pedal_position": 0.0, "acceleration": 0.0047015339294028125, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23496089204746826, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141193.4018567} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2420103051465328, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9327657143368122, "gear": 1, "accelerator_pedal_position": 0.2420103051465328, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141193.4018567} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.989967584609985, "x": 48.47109630919893, "y": 8.479882712268063, "z": null, "yaw": 2.8759293323488437, "pitch": null, "roll": null}, "v": 0.9322384265443968, "accelerator_pedal_position": 0.2416006624153412, "brake_pedal_position": 0.0, "acceleration": 0.0047015339294028125, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23496089204746826, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141193.4218566} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2420103051465328, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9327657143368122, "gear": 1, "accelerator_pedal_position": 0.2420103051465328, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141193.4218566} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.989967584609985, "x": 48.47109630919893, "y": 8.479882712268063, "z": null, "yaw": 2.8759293323488437, "pitch": null, "roll": null}, "v": 0.9322384265443968, "accelerator_pedal_position": 0.2416006624153412, "brake_pedal_position": 0.0, "acceleration": 0.0047015339294028125, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23496089204746826, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141193.4418566} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2420103051465328, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9329101767820992, "gear": 1, "accelerator_pedal_position": 0.2420103051465328, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141193.4418566} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141193.4618566, "x": 52.371779367268154, "y": 13.505566396097427, "z": null, "yaw": 2.903653675595481, "pitch": null, "roll": null}, "v": 0.9330544409269318, "accelerator_pedal_position": 0.2420103051465328, "brake_pedal_position": 0.0, "acceleration": 0.0072057792221486006, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23516655989142815, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141193.4618566} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25199763206273484, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9331264987191533, "gear": 1, "accelerator_pedal_position": 0.2420103051465328, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141193.4618566} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.09996747970581, "x": 48.371779367268154, "y": 8.505566396097427, "z": null, "yaw": 2.903653675595481, "pitch": null, "roll": null}, "v": 0.9330544409269318, "accelerator_pedal_position": 0.2420103051465328, "brake_pedal_position": 0.0, "acceleration": 0.0072057792221486006, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23516655989142815, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141193.4818566} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24724602805488685, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9338227149674535, "gear": 1, "accelerator_pedal_position": 0.25199763206273484, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141193.4818566} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.09996747970581, "x": 48.371779367268154, "y": 8.505566396097427, "z": null, "yaw": 2.903653675595481, "pitch": null, "roll": null}, "v": 0.9330544409269318, "accelerator_pedal_position": 0.2420103051465328, "brake_pedal_position": 0.0, "acceleration": 0.0072057792221486006, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23516655989142815, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141193.5118566} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24724602805488685, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.935018182236338, "gear": 1, "accelerator_pedal_position": 0.24724602805488685, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141193.5118566} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.09996747970581, "x": 48.371779367268154, "y": 8.505566396097427, "z": null, "yaw": 2.903653675595481, "pitch": null, "roll": null}, "v": 0.9330544409269318, "accelerator_pedal_position": 0.2420103051465328, "brake_pedal_position": 0.0, "acceleration": 0.0072057792221486006, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23516655989142815, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141193.5218565} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24724602805488685, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9358137923574665, "gear": 1, "accelerator_pedal_position": 0.24724602805488685, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141193.5218565} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.09996747970581, "x": 48.371779367268154, "y": 8.505566396097427, "z": null, "yaw": 2.903653675595481, "pitch": null, "roll": null}, "v": 0.9330544409269318, "accelerator_pedal_position": 0.2420103051465328, "brake_pedal_position": 0.0, "acceleration": 0.0072057792221486006, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23516655989142815, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141193.5418565} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24724602805488685, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.936608309490263, "gear": 1, "accelerator_pedal_position": 0.24724602805488685, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141193.5418565} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.09996747970581, "x": 48.371779367268154, "y": 8.505566396097427, "z": null, "yaw": 2.903653675595481, "pitch": null, "roll": null}, "v": 0.9330544409269318, "accelerator_pedal_position": 0.2420103051465328, "brake_pedal_position": 0.0, "acceleration": 0.0072057792221486006, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23516655989142815, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141193.5618565} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24724602805488685, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9374017348838299, "gear": 1, "accelerator_pedal_position": 0.24724602805488685, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141193.5618565} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141193.5718565, "x": 52.27153326439415, "y": 13.528544656667783, "z": null, "yaw": 2.9313780188421186, "pitch": null, "roll": null}, "v": 0.9374017348838299, "accelerator_pedal_position": 0.24724602805488685, "brake_pedal_position": 0.0, "acceleration": 0.039630368473219046, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23626224961738337, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141193.5818565} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2343094133151978, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9377980385685621, "gear": 1, "accelerator_pedal_position": 0.24724602805488685, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141193.5818565} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.209967374801636, "x": 48.27153326439415, "y": 8.528544656667783, "z": null, "yaw": 2.9313780188421186, "pitch": null, "roll": null}, "v": 0.9374017348838299, "accelerator_pedal_position": 0.24724602805488685, "brake_pedal_position": 0.0, "acceleration": 0.039630368473219046, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23626224961738337, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141193.6018565} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24049246562669868, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9365613675488078, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141193.6018565} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.209967374801636, "x": 48.27153326439415, "y": 8.528544656667783, "z": null, "yaw": 2.9313780188421186, "pitch": null, "roll": null}, "v": 0.9374017348838299, "accelerator_pedal_position": 0.24724602805488685, "brake_pedal_position": 0.0, "acceleration": 0.039630368473219046, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23626224961738337, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141193.6218565} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24049246562669868, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9365361512471836, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141193.6218565} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.209967374801636, "x": 48.27153326439415, "y": 8.528544656667783, "z": null, "yaw": 2.9313780188421186, "pitch": null, "roll": null}, "v": 0.9374017348838299, "accelerator_pedal_position": 0.24724602805488685, "brake_pedal_position": 0.0, "acceleration": 0.039630368473219046, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23626224961738337, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141193.6418564} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24049246562669868, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9364606062826231, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141193.6418564} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.209967374801636, "x": 48.27153326439415, "y": 8.528544656667783, "z": null, "yaw": 2.9313780188421186, "pitch": null, "roll": null}, "v": 0.9374017348838299, "accelerator_pedal_position": 0.24724602805488685, "brake_pedal_position": 0.0, "acceleration": 0.039630368473219046, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23626224961738337, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141193.6618564} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24049246562669868, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9364103294695588, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141193.6618564} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141193.6818564, "x": 52.17049249537037, "y": 13.548775990114223, "z": null, "yaw": 2.959102362088756, "pitch": null, "roll": null}, "v": 0.936385216975979, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25558743359451047, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23600604696835054, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141193.6818564} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24454834999225392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.936385216975979, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141193.6818564} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.31996726989746, "x": 48.17049249537037, "y": 8.548775990114223, "z": null, "yaw": 2.959102362088756, "pitch": null, "roll": null}, "v": 0.936385216975979, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25558743359451047, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23600604696835054, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141193.7018564} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24261165183926223, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9369488951217929, "gear": 1, "accelerator_pedal_position": 0.24261165183926223, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141193.7018564} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.31996726989746, "x": 48.17049249537037, "y": 8.548775990114223, "z": null, "yaw": 2.959102362088756, "pitch": null, "roll": null}, "v": 0.936385216975979, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25558743359451047, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23600604696835054, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141193.7218564} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24261165183926223, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9370558615909789, "gear": 1, "accelerator_pedal_position": 0.24261165183926223, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141193.7218564} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.31996726989746, "x": 48.17049249537037, "y": 8.548775990114223, "z": null, "yaw": 2.959102362088756, "pitch": null, "roll": null}, "v": 0.936385216975979, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25558743359451047, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23600604696835054, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141193.7418563} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24261165183926223, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9373763200187286, "gear": 1, "accelerator_pedal_position": 0.24261165183926223, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141193.7418563} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.31996726989746, "x": 48.17049249537037, "y": 8.548775990114223, "z": null, "yaw": 2.959102362088756, "pitch": null, "roll": null}, "v": 0.936385216975979, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25558743359451047, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23600604696835054, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141193.7618563} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24261165183926223, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9376961179892818, "gear": 1, "accelerator_pedal_position": 0.24261165183926223, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141193.7618563} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.31996726989746, "x": 48.17049249537037, "y": 8.548775990114223, "z": null, "yaw": 2.959102362088756, "pitch": null, "roll": null}, "v": 0.936385216975979, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25558743359451047, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23600604696835054, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141193.7818563} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24261165183926223, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9376961179892818, "gear": 1, "accelerator_pedal_position": 0.24261165183926223, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141193.7818563} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141193.7918563, "x": 52.06889547302094, "y": 13.566203787418134, "z": null, "yaw": 2.9868267053353934, "pitch": null, "roll": null}, "v": 0.9378025707692718, "accelerator_pedal_position": 0.24261165183926223, "brake_pedal_position": 0.0, "acceleration": 0.010637958839510686, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.236363276087143, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141193.8018563} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24784987148861207, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9384488788799634, "gear": 1, "accelerator_pedal_position": 0.24784987148861207, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141193.8018563} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.429967164993286, "x": 48.06889547302094, "y": 8.566203787418134, "z": null, "yaw": 2.9868267053353934, "pitch": null, "roll": null}, "v": 0.9378025707692718, "accelerator_pedal_position": 0.24261165183926223, "brake_pedal_position": 0.0, "acceleration": 0.010637958839510686, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.236363276087143, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141193.8218563} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24536290329410518, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9384488788799634, "gear": 1, "accelerator_pedal_position": 0.24784987148861207, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141193.8218563} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.429967164993286, "x": 48.06889547302094, "y": 8.566203787418134, "z": null, "yaw": 2.9868267053353934, "pitch": null, "roll": null}, "v": 0.9378025707692718, "accelerator_pedal_position": 0.24261165183926223, "brake_pedal_position": 0.0, "acceleration": 0.010637958839510686, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.236363276087143, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141193.8518562} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24536290329410518, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9392819708296337, "gear": 1, "accelerator_pedal_position": 0.24536290329410518, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141193.8518562} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.429967164993286, "x": 48.06889547302094, "y": 8.566203787418134, "z": null, "yaw": 2.9868267053353934, "pitch": null, "roll": null}, "v": 0.9378025707692718, "accelerator_pedal_position": 0.24261165183926223, "brake_pedal_position": 0.0, "acceleration": 0.010637958839510686, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.236363276087143, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141193.8618562} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24536290329410518, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9395592862380279, "gear": 1, "accelerator_pedal_position": 0.24536290329410518, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141193.8618562} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.429967164993286, "x": 48.06889547302094, "y": 8.566203787418134, "z": null, "yaw": 2.9868267053353934, "pitch": null, "roll": null}, "v": 0.9378025707692718, "accelerator_pedal_position": 0.24261165183926223, "brake_pedal_position": 0.0, "acceleration": 0.010637958839510686, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.236363276087143, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141193.8818562} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24536290329410518, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.940113344888071, "gear": 1, "accelerator_pedal_position": 0.24536290329410518, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141193.8818562} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141193.9018562, "x": 51.9666497620206, "y": 13.580837403285276, "z": null, "yaw": 3.014551048582031, "pitch": null, "roll": null}, "v": 0.9406666414212569, "accelerator_pedal_position": 0.24536290329410518, "brake_pedal_position": 0.0, "acceleration": 0.027636276214266953, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23708513497658168, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141193.9018562} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2361754623519846, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.940368789124517, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141193.9018562} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.53996706008911, "x": 47.9666497620206, "y": 8.580837403285276, "z": null, "yaw": 3.014551048582031, "pitch": null, "roll": null}, "v": 0.9406666414212569, "accelerator_pedal_position": 0.24536290329410518, "brake_pedal_position": 0.0, "acceleration": 0.027636276214266953, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23708513497658168, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141193.9218562} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24056544626735551, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9400711417809978, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141193.9218562} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.53996706008911, "x": 47.9666497620206, "y": 8.580837403285276, "z": null, "yaw": 3.014551048582031, "pitch": null, "roll": null}, "v": 0.9406666414212569, "accelerator_pedal_position": 0.24536290329410518, "brake_pedal_position": 0.0, "acceleration": 0.027636276214266953, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23708513497658168, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141193.9418561} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24056544626735551, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9400250205437547, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141193.9418561} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.53996706008911, "x": 47.9666497620206, "y": 8.580837403285276, "z": null, "yaw": 3.014551048582031, "pitch": null, "roll": null}, "v": 0.9406666414212569, "accelerator_pedal_position": 0.24536290329410518, "brake_pedal_position": 0.0, "acceleration": 0.027636276214266953, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23708513497658168, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141193.971856} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24056544626735551, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9399559576134715, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141193.971856} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.53996706008911, "x": 47.9666497620206, "y": 8.580837403285276, "z": null, "yaw": 3.014551048582031, "pitch": null, "roll": null}, "v": 0.9406666414212569, "accelerator_pedal_position": 0.24536290329410518, "brake_pedal_position": 0.0, "acceleration": 0.027636276214266953, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23708513497658168, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141193.981856} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24056544626735551, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9399099948152149, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141193.981856} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141194.011856, "x": 51.86392098005588, "y": 13.592645400861702, "z": null, "yaw": 3.0422753918286682, "pitch": null, "roll": null}, "v": 0.9398640952385701, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2558266499371147, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2368828616507627, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141194.011856} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24451110169138326, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9398640952385701, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141194.011856} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.64996695518494, "x": 47.86392098005588, "y": 8.592645400861702, "z": null, "yaw": 3.0422753918286682, "pitch": null, "roll": null}, "v": 0.9398640952385701, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2558266499371147, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2368828616507627, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141194.021856} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2426280100202625, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9400877725949104, "gear": 1, "accelerator_pedal_position": 0.24451110169138326, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141194.021856} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.64996695518494, "x": 47.86392098005588, "y": 8.592645400861702, "z": null, "yaw": 3.0422753918286682, "pitch": null, "roll": null}, "v": 0.9398640952385701, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2558266499371147, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2368828616507627, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141194.041856} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2426280100202625, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9404050449140785, "gear": 1, "accelerator_pedal_position": 0.2426280100202625, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141194.041856} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.64996695518494, "x": 47.86392098005588, "y": 8.592645400861702, "z": null, "yaw": 3.0422753918286682, "pitch": null, "roll": null}, "v": 0.9398640952385701, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2558266499371147, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2368828616507627, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141194.061856} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2426280100202625, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9406161961213124, "gear": 1, "accelerator_pedal_position": 0.2426280100202625, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141194.061856} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.64996695518494, "x": 47.86392098005588, "y": 8.592645400861702, "z": null, "yaw": 3.0422753918286682, "pitch": null, "roll": null}, "v": 0.9398640952385701, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2558266499371147, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2368828616507627, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141194.081856} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2426280100202625, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9407216627666776, "gear": 1, "accelerator_pedal_position": 0.2426280100202625, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141194.081856} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.64996695518494, "x": 47.86392098005588, "y": 8.592645400861702, "z": null, "yaw": 3.0422753918286682, "pitch": null, "roll": null}, "v": 0.9398640952385701, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2558266499371147, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2368828616507627, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141194.101856} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2426280100202625, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9410376274426494, "gear": 1, "accelerator_pedal_position": 0.2426280100202625, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141194.101856} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141194.121856, "x": 51.76085799559004, "y": 13.601604697137187, "z": null, "yaw": 3.0699997350753057, "pitch": null, "roll": null}, "v": 0.9411428040735682, "accelerator_pedal_position": 0.2426280100202625, "brake_pedal_position": 0.0, "acceleration": 0.010510424646367478, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23720514676579904, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141194.121856} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24539802559021984, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9411428040735682, "gear": 1, "accelerator_pedal_position": 0.2426280100202625, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141194.121856} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.75996685028076, "x": 47.76085799559004, "y": 8.601604697137187, "z": null, "yaw": 3.0699997350753057, "pitch": null, "roll": null}, "v": 0.9411428040735682, "accelerator_pedal_position": 0.2426280100202625, "brake_pedal_position": 0.0, "acceleration": 0.010510424646367478, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23720514676579904, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141194.141856} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24408567375223705, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9416990730190155, "gear": 1, "accelerator_pedal_position": 0.24539802559021984, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141194.141856} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.75996685028076, "x": 47.76085799559004, "y": 8.601604697137187, "z": null, "yaw": 3.0699997350753057, "pitch": null, "roll": null}, "v": 0.9411428040735682, "accelerator_pedal_position": 0.2426280100202625, "brake_pedal_position": 0.0, "acceleration": 0.010510424646367478, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23720514676579904, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141194.161856} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24408567375223705, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9422861447852446, "gear": 1, "accelerator_pedal_position": 0.24408567375223705, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141194.161856} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.75996685028076, "x": 47.76085799559004, "y": 8.601604697137187, "z": null, "yaw": 3.0699997350753057, "pitch": null, "roll": null}, "v": 0.9411428040735682, "accelerator_pedal_position": 0.2426280100202625, "brake_pedal_position": 0.0, "acceleration": 0.010510424646367478, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23720514676579904, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141194.181856} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24408567375223705, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9424815660045014, "gear": 1, "accelerator_pedal_position": 0.24408567375223705, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141194.181856} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.75996685028076, "x": 47.76085799559004, "y": 8.601604697137187, "z": null, "yaw": 3.0699997350753057, "pitch": null, "roll": null}, "v": 0.9411428040735682, "accelerator_pedal_position": 0.2426280100202625, "brake_pedal_position": 0.0, "acceleration": 0.010510424646367478, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23720514676579904, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141194.201856} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24408567375223705, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9430670227444077, "gear": 1, "accelerator_pedal_position": 0.24408567375223705, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141194.201856} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.75996685028076, "x": 47.76085799559004, "y": 8.601604697137187, "z": null, "yaw": 3.0699997350753057, "pitch": null, "roll": null}, "v": 0.9411428040735682, "accelerator_pedal_position": 0.2426280100202625, "brake_pedal_position": 0.0, "acceleration": 0.010510424646367478, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23720514676579904, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141194.2218559} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24408567375223705, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9432619063016114, "gear": 1, "accelerator_pedal_position": 0.24408567375223705, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141194.2218559} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141194.2318559, "x": 51.657392602519, "y": 13.60771473625961, "z": null, "yaw": 3.097724078321943, "pitch": null, "roll": null}, "v": 0.9434566556555875, "accelerator_pedal_position": 0.24408567375223705, "brake_pedal_position": 0.0, "acceleration": 0.01946152355769387, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23778832872472336, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141194.2418559} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24433364123294737, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9436512708911644, "gear": 1, "accelerator_pedal_position": 0.24408567375223705, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141194.2418559} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.86996674537659, "x": 47.657392602519, "y": 8.60771473625961, "z": null, "yaw": 3.097724078321943, "pitch": null, "roll": null}, "v": 0.9434566556555875, "accelerator_pedal_position": 0.24408567375223705, "brake_pedal_position": 0.0, "acceleration": 0.01946152355769387, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23778832872472336, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141194.2618558} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2442276985254777, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9444616159505954, "gear": 1, "accelerator_pedal_position": 0.2442276985254777, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141194.2618558} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.86996674537659, "x": 47.657392602519, "y": 8.60771473625961, "z": null, "yaw": 3.097724078321943, "pitch": null, "roll": null}, "v": 0.9434566556555875, "accelerator_pedal_position": 0.24408567375223705, "brake_pedal_position": 0.0, "acceleration": 0.01946152355769387, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23778832872472336, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141194.2818558} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2442276985254777, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9446644155260621, "gear": 1, "accelerator_pedal_position": 0.2442276985254777, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141194.2818558} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.86996674537659, "x": 47.657392602519, "y": 8.60771473625961, "z": null, "yaw": 3.097724078321943, "pitch": null, "roll": null}, "v": 0.9434566556555875, "accelerator_pedal_position": 0.24408567375223705, "brake_pedal_position": 0.0, "acceleration": 0.01946152355769387, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23778832872472336, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141194.3118558} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2442276985254777, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9450695956314769, "gear": 1, "accelerator_pedal_position": 0.2442276985254777, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141194.3118558} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.86996674537659, "x": 47.657392602519, "y": 8.60771473625961, "z": null, "yaw": 3.097724078321943, "pitch": null, "roll": null}, "v": 0.9434566556555875, "accelerator_pedal_position": 0.24408567375223705, "brake_pedal_position": 0.0, "acceleration": 0.01946152355769387, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23778832872472336, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141194.3318558} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2442276985254777, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9454742175961935, "gear": 1, "accelerator_pedal_position": 0.2442276985254777, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141194.3318558} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141194.3418558, "x": 51.55355589230437, "y": 13.610961854056125, "z": null, "yaw": 3.1254484215685805, "pitch": null, "roll": null}, "v": 0.9456763194956239, "accelerator_pedal_position": 0.2442276985254777, "brake_pedal_position": 0.0, "acceleration": 0.020196262796906506, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2383477716537535, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141194.3518558} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24086150871600095, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9458782821235929, "gear": 1, "accelerator_pedal_position": 0.2442276985254777, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141194.3518558} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.97996664047241, "x": 47.55355589230437, "y": 8.610961854056125, "z": null, "yaw": 3.1254484215685805, "pitch": null, "roll": null}, "v": 0.9456763194956239, "accelerator_pedal_position": 0.2442276985254777, "brake_pedal_position": 0.0, "acceleration": 0.020196262796906506, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2383477716537535, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141194.3718557} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24247610776277484, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9458611611877432, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141194.3718557} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.97996664047241, "x": 47.55355589230437, "y": 8.610961854056125, "z": null, "yaw": 3.1254484215685805, "pitch": null, "roll": null}, "v": 0.9456763194956239, "accelerator_pedal_position": 0.2442276985254777, "brake_pedal_position": 0.0, "acceleration": 0.020196262796906506, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2383477716537535, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141194.3918557} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24247610776277484, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9460458191762874, "gear": 1, "accelerator_pedal_position": 0.24247610776277484, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141194.3918557} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.97996664047241, "x": 47.55355589230437, "y": 8.610961854056125, "z": null, "yaw": 3.1254484215685805, "pitch": null, "roll": null}, "v": 0.9456763194956239, "accelerator_pedal_position": 0.2442276985254777, "brake_pedal_position": 0.0, "acceleration": 0.020196262796906506, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2383477716537535, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141194.4118557} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24247610776277484, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9462302227199988, "gear": 1, "accelerator_pedal_position": 0.24247610776277484, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141194.4118557} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.97996664047241, "x": 47.55355589230437, "y": 8.610961854056125, "z": null, "yaw": 3.1254484215685805, "pitch": null, "roll": null}, "v": 0.9456763194956239, "accelerator_pedal_position": 0.2442276985254777, "brake_pedal_position": 0.0, "acceleration": 0.020196262796906506, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2383477716537535, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141194.4318557} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24247610776277484, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9464143721558861, "gear": 1, "accelerator_pedal_position": 0.24247610776277484, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141194.4318557} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141194.4518557, "x": 51.44949088839364, "y": 13.61133026455034, "z": null, "yaw": 3.153172764815218, "pitch": null, "roll": null}, "v": 0.9465982678205497, "accelerator_pedal_position": 0.24247610776277484, "brake_pedal_position": 0.0, "acceleration": 0.009185277319906537, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2385801390338981, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141194.4518557} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24577552482258774, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9465982678205497, "gear": 1, "accelerator_pedal_position": 0.24247610776277484, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141194.4518557} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.08996653556824, "x": 47.44949088839364, "y": 8.61133026455034, "z": null, "yaw": 3.153172764815218, "pitch": null, "roll": null}, "v": 0.9465982678205497, "accelerator_pedal_position": 0.24247610776277484, "brake_pedal_position": 0.0, "acceleration": 0.009185277319906537, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2385801390338981, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141194.4718556} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24420921444672072, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9471941950275543, "gear": 1, "accelerator_pedal_position": 0.24577552482258774, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141194.4718556} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.08996653556824, "x": 47.44949088839364, "y": 8.61133026455034, "z": null, "yaw": 3.153172764815218, "pitch": null, "roll": null}, "v": 0.9465982678205497, "accelerator_pedal_position": 0.24247610776277484, "brake_pedal_position": 0.0, "acceleration": 0.009185277319906537, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2385801390338981, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141194.4918556} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24420921444672072, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9475935795426822, "gear": 1, "accelerator_pedal_position": 0.24420921444672072, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141194.4918556} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.08996653556824, "x": 47.44949088839364, "y": 8.61133026455034, "z": null, "yaw": 3.153172764815218, "pitch": null, "roll": null}, "v": 0.9465982678205497, "accelerator_pedal_position": 0.24247610776277484, "brake_pedal_position": 0.0, "acceleration": 0.009185277319906537, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2385801390338981, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141194.5118556} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24420921444672072, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9479924134974411, "gear": 1, "accelerator_pedal_position": 0.24420921444672072, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141194.5118556} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.08996653556824, "x": 47.44949088839364, "y": 8.61133026455034, "z": null, "yaw": 3.153172764815218, "pitch": null, "roll": null}, "v": 0.9465982678205497, "accelerator_pedal_position": 0.24247610776277484, "brake_pedal_position": 0.0, "acceleration": 0.009185277319906537, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2385801390338981, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141194.5318556} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24420921444672072, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9483906975871852, "gear": 1, "accelerator_pedal_position": 0.24420921444672072, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141194.5318556} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.08996653556824, "x": 47.44949088839364, "y": 8.61133026455034, "z": null, "yaw": 3.153172764815218, "pitch": null, "roll": null}, "v": 0.9465982678205497, "accelerator_pedal_position": 0.24247610776277484, "brake_pedal_position": 0.0, "acceleration": 0.009185277319906537, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2385801390338981, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141194.5518556} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24420921444672072, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9487884325065731, "gear": 1, "accelerator_pedal_position": 0.24420921444672072, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141194.5518556} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141194.5618556, "x": 51.345270471862214, "y": 13.60880891855126, "z": null, "yaw": 3.1808971080618553, "pitch": null, "roll": null}, "v": 0.948987094244274, "accelerator_pedal_position": 0.24420921444672072, "brake_pedal_position": 0.0, "acceleration": 0.019852470529368837, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2391822176132433, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141194.5718555} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2467453885964112, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9491856189495677, "gear": 1, "accelerator_pedal_position": 0.24420921444672072, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141194.5718555} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.19996643066406, "x": 47.345270471862214, "y": 8.60880891855126, "z": null, "yaw": 3.1808971080618553, "pitch": null, "roll": null}, "v": 0.948987094244274, "accelerator_pedal_position": 0.24420921444672072, "brake_pedal_position": 0.0, "acceleration": 0.019852470529368837, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2391822176132433, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141194.5918555} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24555023639020973, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9498991700226538, "gear": 1, "accelerator_pedal_position": 0.2467453885964112, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141194.5918555} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.19996643066406, "x": 47.345270471862214, "y": 8.60880891855126, "z": null, "yaw": 3.1808971080618553, "pitch": null, "roll": null}, "v": 0.948987094244274, "accelerator_pedal_position": 0.24420921444672072, "brake_pedal_position": 0.0, "acceleration": 0.019852470529368837, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2391822176132433, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141194.6118555} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24555023639020973, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9504623943330615, "gear": 1, "accelerator_pedal_position": 0.24555023639020973, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141194.6118555} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.19996643066406, "x": 47.345270471862214, "y": 8.60880891855126, "z": null, "yaw": 3.1808971080618553, "pitch": null, "roll": null}, "v": 0.948987094244274, "accelerator_pedal_position": 0.24420921444672072, "brake_pedal_position": 0.0, "acceleration": 0.019852470529368837, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2391822176132433, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141194.6318555} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24555023639020973, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9510248415896824, "gear": 1, "accelerator_pedal_position": 0.24555023639020973, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141194.6318555} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.19996643066406, "x": 47.345270471862214, "y": 8.60880891855126, "z": null, "yaw": 3.1808971080618553, "pitch": null, "roll": null}, "v": 0.948987094244274, "accelerator_pedal_position": 0.24420921444672072, "brake_pedal_position": 0.0, "acceleration": 0.019852470529368837, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2391822176132433, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141194.6518555} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24555023639020973, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9515865127380855, "gear": 1, "accelerator_pedal_position": 0.24555023639020973, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141194.6518555} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141194.6718554, "x": 51.240866783011654, "y": 13.60338401340085, "z": null, "yaw": 3.2086214513084927, "pitch": null, "roll": null}, "v": 0.9521474087230586, "accelerator_pedal_position": 0.24555023639020973, "brake_pedal_position": 0.0, "acceleration": 0.028015760123277444, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23997874164394453, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141194.6718554} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2399205317219288, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9521474087230586, "gear": 1, "accelerator_pedal_position": 0.24555023639020973, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141194.6718554} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.30996632575989, "x": 47.240866783011654, "y": 8.60338401340085, "z": null, "yaw": 3.2086214513084927, "pitch": null, "roll": null}, "v": 0.9521474087230586, "accelerator_pedal_position": 0.24555023639020973, "brake_pedal_position": 0.0, "acceleration": 0.028015760123277444, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23997874164394453, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141194.6918554} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24261796177262465, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9520040603445372, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141194.6918554} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.30996632575989, "x": 47.240866783011654, "y": 8.60338401340085, "z": null, "yaw": 3.2086214513084927, "pitch": null, "roll": null}, "v": 0.9521474087230586, "accelerator_pedal_position": 0.24555023639020973, "brake_pedal_position": 0.0, "acceleration": 0.028015760123277444, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23997874164394453, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141194.7118554} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24261796177262465, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9521979721970819, "gear": 1, "accelerator_pedal_position": 0.24261796177262465, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141194.7118554} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.30996632575989, "x": 47.240866783011654, "y": 8.60338401340085, "z": null, "yaw": 3.2086214513084927, "pitch": null, "roll": null}, "v": 0.9521474087230586, "accelerator_pedal_position": 0.24555023639020973, "brake_pedal_position": 0.0, "acceleration": 0.028015760123277444, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23997874164394453, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141194.7318554} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24261796177262465, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9523916163769829, "gear": 1, "accelerator_pedal_position": 0.24261796177262465, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141194.7318554} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.30996632575989, "x": 47.240866783011654, "y": 8.60338401340085, "z": null, "yaw": 3.2086214513084927, "pitch": null, "roll": null}, "v": 0.9521474087230586, "accelerator_pedal_position": 0.24555023639020973, "brake_pedal_position": 0.0, "acceleration": 0.028015760123277444, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23997874164394453, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141194.7518554} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24261796177262465, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9525849932387369, "gear": 1, "accelerator_pedal_position": 0.24261796177262465, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141194.7518554} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.30996632575989, "x": 47.240866783011654, "y": 8.60338401340085, "z": null, "yaw": 3.2086214513084927, "pitch": null, "roll": null}, "v": 0.9521474087230586, "accelerator_pedal_position": 0.24555023639020973, "brake_pedal_position": 0.0, "acceleration": 0.028015760123277444, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.23997874164394453, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141194.7718554} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24261796177262465, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9527781031364135, "gear": 1, "accelerator_pedal_position": 0.24261796177262465, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141194.7718554} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141194.7818553, "x": 51.13644462111461, "y": 13.595050966035165, "z": null, "yaw": 3.23634579455513, "pitch": null, "roll": null}, "v": 0.9528745580842527, "accelerator_pedal_position": 0.24261796177262465, "brake_pedal_position": 0.0, "acceleration": 0.009638833940248726, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24016201199377474, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141194.7918553} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24623660042076861, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9529709464236552, "gear": 1, "accelerator_pedal_position": 0.24261796177262465, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141194.7918553} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.41996622085571, "x": 47.13644462111461, "y": 8.595050966035165, "z": null, "yaw": 3.23634579455513, "pitch": null, "roll": null}, "v": 0.9528745580842527, "accelerator_pedal_position": 0.24261796177262465, "brake_pedal_position": 0.0, "acceleration": 0.009638833940248726, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24016201199377474, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141194.8118553} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24451726381119704, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9536156970870476, "gear": 1, "accelerator_pedal_position": 0.24623660042076861, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141194.8118553} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.41996622085571, "x": 47.13644462111461, "y": 8.595050966035165, "z": null, "yaw": 3.23634579455513, "pitch": null, "roll": null}, "v": 0.9528745580842527, "accelerator_pedal_position": 0.24261796177262465, "brake_pedal_position": 0.0, "acceleration": 0.009638833940248726, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24016201199377474, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141194.8318553} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24451726381119704, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9540447145648697, "gear": 1, "accelerator_pedal_position": 0.24451726381119704, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141194.8318553} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.41996622085571, "x": 47.13644462111461, "y": 8.595050966035165, "z": null, "yaw": 3.23634579455513, "pitch": null, "roll": null}, "v": 0.9528745580842527, "accelerator_pedal_position": 0.24261796177262465, "brake_pedal_position": 0.0, "acceleration": 0.009638833940248726, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24016201199377474, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141194.8518553} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24451726381119704, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9544731395276048, "gear": 1, "accelerator_pedal_position": 0.24451726381119704, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141194.8518553} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.41996622085571, "x": 47.13644462111461, "y": 8.595050966035165, "z": null, "yaw": 3.23634579455513, "pitch": null, "roll": null}, "v": 0.9528745580842527, "accelerator_pedal_position": 0.24261796177262465, "brake_pedal_position": 0.0, "acceleration": 0.009638833940248726, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24016201199377474, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141194.8718553} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24451726381119704, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9549009727201803, "gear": 1, "accelerator_pedal_position": 0.24451726381119704, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141194.8718553} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141194.8918552, "x": 51.032111503935106, "y": 13.58380640318773, "z": null, "yaw": 3.2640701378017676, "pitch": null, "roll": null}, "v": 0.9553282148867988, "accelerator_pedal_position": 0.24451726381119704, "brake_pedal_position": 0.0, "acceleration": 0.021339968094053474, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24078043038834956, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141194.8918552} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24712974252661182, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9553282148867988, "gear": 1, "accelerator_pedal_position": 0.24451726381119704, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141194.8918552} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.52996611595154, "x": 47.032111503935106, "y": 8.58380640318773, "z": null, "yaw": 3.2640701378017676, "pitch": null, "roll": null}, "v": 0.9553282148867988, "accelerator_pedal_position": 0.24451726381119704, "brake_pedal_position": 0.0, "acceleration": 0.021339968094053474, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24078043038834956, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141194.9118552} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2458986189871113, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9560813137635874, "gear": 1, "accelerator_pedal_position": 0.24712974252661182, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141194.9118552} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.52996611595154, "x": 47.032111503935106, "y": 8.58380640318773, "z": null, "yaw": 3.2640701378017676, "pitch": null, "roll": null}, "v": 0.9553282148867988, "accelerator_pedal_position": 0.24451726381119704, "brake_pedal_position": 0.0, "acceleration": 0.021339968094053474, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24078043038834956, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141194.9318552} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2458986189871113, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.956679534697053, "gear": 1, "accelerator_pedal_position": 0.2458986189871113, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141194.9318552} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.52996611595154, "x": 47.032111503935106, "y": 8.58380640318773, "z": null, "yaw": 3.2640701378017676, "pitch": null, "roll": null}, "v": 0.9553282148867988, "accelerator_pedal_position": 0.24451726381119704, "brake_pedal_position": 0.0, "acceleration": 0.021339968094053474, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24078043038834956, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141194.9518552} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2458986189871113, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9572769288089868, "gear": 1, "accelerator_pedal_position": 0.2458986189871113, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141194.9518552} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.52996611595154, "x": 47.032111503935106, "y": 8.58380640318773, "z": null, "yaw": 3.2640701378017676, "pitch": null, "roll": null}, "v": 0.9553282148867988, "accelerator_pedal_position": 0.24451726381119704, "brake_pedal_position": 0.0, "acceleration": 0.021339968094053474, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24078043038834956, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141194.9718552} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2458986189871113, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9578734970994645, "gear": 1, "accelerator_pedal_position": 0.2458986189871113, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141194.9718552} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.52996611595154, "x": 47.032111503935106, "y": 8.58380640318773, "z": null, "yaw": 3.2640701378017676, "pitch": null, "roll": null}, "v": 0.9553282148867988, "accelerator_pedal_position": 0.24451726381119704, "brake_pedal_position": 0.0, "acceleration": 0.021339968094053474, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24078043038834956, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141194.9918551} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2458986189871113, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9584692405677708, "gear": 1, "accelerator_pedal_position": 0.2458986189871113, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141194.9918551} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141195.0018551, "x": 50.92780863840963, "y": 13.56963004285187, "z": null, "yaw": 3.291794481048405, "pitch": null, "roll": null}, "v": 0.95876680330567, "accelerator_pedal_position": 0.2458986189871113, "brake_pedal_position": 0.0, "acceleration": 0.029735690672952286, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2416470904393377, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141195.0118551} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24041659706280682, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9590641602123995, "gear": 1, "accelerator_pedal_position": 0.2458986189871113, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141195.0118551} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.63996601104736, "x": 46.92780863840963, "y": 8.56963004285187, "z": null, "yaw": 3.291794481048405, "pitch": null, "roll": null}, "v": 0.95876680330567, "accelerator_pedal_position": 0.2458986189871113, "brake_pedal_position": 0.0, "acceleration": 0.029735690672952286, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2416470904393377, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141195.031855} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2430451990842869, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9589732413324565, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141195.031855} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.63996601104736, "x": 46.92780863840963, "y": 8.56963004285187, "z": null, "yaw": 3.291794481048405, "pitch": null, "roll": null}, "v": 0.95876680330567, "accelerator_pedal_position": 0.2458986189871113, "brake_pedal_position": 0.0, "acceleration": 0.029735690672952286, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2416470904393377, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141195.051855} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2430451990842869, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9592109098023945, "gear": 1, "accelerator_pedal_position": 0.2430451990842869, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141195.051855} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.63996601104736, "x": 46.92780863840963, "y": 8.56963004285187, "z": null, "yaw": 3.291794481048405, "pitch": null, "roll": null}, "v": 0.95876680330567, "accelerator_pedal_position": 0.2458986189871113, "brake_pedal_position": 0.0, "acceleration": 0.029735690672952286, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2416470904393377, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141195.071855} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2430451990842869, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9594482495335925, "gear": 1, "accelerator_pedal_position": 0.2430451990842869, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141195.071855} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.63996601104736, "x": 46.92780863840963, "y": 8.56963004285187, "z": null, "yaw": 3.291794481048405, "pitch": null, "roll": null}, "v": 0.95876680330567, "accelerator_pedal_position": 0.2458986189871113, "brake_pedal_position": 0.0, "acceleration": 0.029735690672952286, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2416470904393377, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141195.091855} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2430451990842869, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9596852609582318, "gear": 1, "accelerator_pedal_position": 0.2430451990842869, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141195.091855} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141195.111855, "x": 50.823687710249786, "y": 13.552527121663086, "z": null, "yaw": 3.3195188242950424, "pitch": null, "roll": null}, "v": 0.9599219445079892, "accelerator_pedal_position": 0.2430451990842869, "brake_pedal_position": 0.0, "acceleration": 0.011821895655913572, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24193823163198708, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141195.111855} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2551076637796229, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9599219445079892, "gear": 1, "accelerator_pedal_position": 0.2430451990842869, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141195.111855} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.74996590614319, "x": 46.823687710249786, "y": 8.552527121663086, "z": null, "yaw": 3.3195188242950424, "pitch": null, "roll": null}, "v": 0.9599219445079892, "accelerator_pedal_position": 0.2430451990842869, "brake_pedal_position": 0.0, "acceleration": 0.011821895655913572, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24193823163198708, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141195.131855} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2493697192963955, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9616655869364633, "gear": 1, "accelerator_pedal_position": 0.2551076637796229, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141195.131855} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.74996590614319, "x": 46.823687710249786, "y": 8.552527121663086, "z": null, "yaw": 3.3195188242950424, "pitch": null, "roll": null}, "v": 0.9599219445079892, "accelerator_pedal_position": 0.2430451990842869, "brake_pedal_position": 0.0, "acceleration": 0.011821895655913572, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24193823163198708, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141195.151855} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2493697192963955, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9626898214166, "gear": 1, "accelerator_pedal_position": 0.2493697192963955, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141195.151855} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.74996590614319, "x": 46.823687710249786, "y": 8.552527121663086, "z": null, "yaw": 3.3195188242950424, "pitch": null, "roll": null}, "v": 0.9599219445079892, "accelerator_pedal_position": 0.2430451990842869, "brake_pedal_position": 0.0, "acceleration": 0.011821895655913572, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24193823163198708, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141195.171855} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2493697192963955, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9637126378503141, "gear": 1, "accelerator_pedal_position": 0.2493697192963955, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141195.171855} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.74996590614319, "x": 46.823687710249786, "y": 8.552527121663086, "z": null, "yaw": 3.3195188242950424, "pitch": null, "roll": null}, "v": 0.9599219445079892, "accelerator_pedal_position": 0.2430451990842869, "brake_pedal_position": 0.0, "acceleration": 0.011821895655913572, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24193823163198708, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141195.191855} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2493697192963955, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.964734037782566, "gear": 1, "accelerator_pedal_position": 0.2493697192963955, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141195.191855} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.74996590614319, "x": 46.823687710249786, "y": 8.552527121663086, "z": null, "yaw": 3.3195188242950424, "pitch": null, "roll": null}, "v": 0.9599219445079892, "accelerator_pedal_position": 0.2430451990842869, "brake_pedal_position": 0.0, "acceleration": 0.011821895655913572, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24193823163198708, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141195.211855} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2493697192963955, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9657540227579138, "gear": 1, "accelerator_pedal_position": 0.2493697192963955, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141195.211855} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141195.221855, "x": 50.71966718938867, "y": 13.532463363362382, "z": null, "yaw": 3.34724316754168, "pitch": null, "roll": null}, "v": 0.9662634851193123, "accelerator_pedal_position": 0.2493697192963955, "brake_pedal_position": 0.0, "acceleration": 0.050910920119757064, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24353655025581258, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141195.231855} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25853062740234534, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9667725943205099, "gear": 1, "accelerator_pedal_position": 0.2493697192963955, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141195.231855} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.859965801239014, "x": 46.71966718938867, "y": 8.532463363362382, "z": null, "yaw": 3.34724316754168, "pitch": null, "roll": null}, "v": 0.9662634851193123, "accelerator_pedal_position": 0.2493697192963955, "brake_pedal_position": 0.0, "acceleration": 0.050910920119757064, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24353655025581258, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141195.251855} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25420175295033287, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9689344704514846, "gear": 1, "accelerator_pedal_position": 0.25853062740234534, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141195.251855} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.859965801239014, "x": 46.71966718938867, "y": 8.532463363362382, "z": null, "yaw": 3.34724316754168, "pitch": null, "roll": null}, "v": 0.9662634851193123, "accelerator_pedal_position": 0.2493697192963955, "brake_pedal_position": 0.0, "acceleration": 0.050910920119757064, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24353655025581258, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141195.2718549} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25420175295033287, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9705524267794939, "gear": 1, "accelerator_pedal_position": 0.25420175295033287, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141195.2718549} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.859965801239014, "x": 46.71966718938867, "y": 8.532463363362382, "z": null, "yaw": 3.34724316754168, "pitch": null, "roll": null}, "v": 0.9662634851193123, "accelerator_pedal_position": 0.2493697192963955, "brake_pedal_position": 0.0, "acceleration": 0.050910920119757064, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24353655025581258, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141195.2918549} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25420175295033287, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9721681380678006, "gear": 1, "accelerator_pedal_position": 0.25420175295033287, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141195.2918549} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.859965801239014, "x": 46.71966718938867, "y": 8.532463363362382, "z": null, "yaw": 3.34724316754168, "pitch": null, "roll": null}, "v": 0.9662634851193123, "accelerator_pedal_position": 0.2493697192963955, "brake_pedal_position": 0.0, "acceleration": 0.050910920119757064, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24353655025581258, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141195.3118548} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25420175295033287, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9737816063877239, "gear": 1, "accelerator_pedal_position": 0.25420175295033287, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141195.3118548} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141195.3318548, "x": 50.61545346643915, "y": 13.509347894335995, "z": null, "yaw": 3.3749675107883172, "pitch": null, "roll": null}, "v": 0.975392833812055, "accelerator_pedal_position": 0.25420175295033287, "brake_pedal_position": 0.0, "acceleration": 0.08047740244645851, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24583750659013837, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141195.3318548} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26190221273565945, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.975392833812055, "gear": 1, "accelerator_pedal_position": 0.25420175295033287, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141195.3318548} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.96996569633484, "x": 46.61545346643915, "y": 8.509347894335995, "z": null, "yaw": 3.3749675107883172, "pitch": null, "roll": null}, "v": 0.975392833812055, "accelerator_pedal_position": 0.25420175295033287, "brake_pedal_position": 0.0, "acceleration": 0.08047740244645851, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24583750659013837, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141195.3518548} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25828360935483685, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.977964045261047, "gear": 1, "accelerator_pedal_position": 0.26190221273565945, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141195.3518548} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.96996569633484, "x": 46.61545346643915, "y": 8.509347894335995, "z": null, "yaw": 3.3749675107883172, "pitch": null, "roll": null}, "v": 0.975392833812055, "accelerator_pedal_position": 0.25420175295033287, "brake_pedal_position": 0.0, "acceleration": 0.08047740244645851, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24583750659013837, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141195.3718548} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25828360935483685, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9800795135301399, "gear": 1, "accelerator_pedal_position": 0.25828360935483685, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141195.3718548} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.96996569633484, "x": 46.61545346643915, "y": 8.509347894335995, "z": null, "yaw": 3.3749675107883172, "pitch": null, "roll": null}, "v": 0.975392833812055, "accelerator_pedal_position": 0.25420175295033287, "brake_pedal_position": 0.0, "acceleration": 0.08047740244645851, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24583750659013837, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141195.3918548} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25828360935483685, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9821920384722971, "gear": 1, "accelerator_pedal_position": 0.25828360935483685, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141195.3918548} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.96996569633484, "x": 46.61545346643915, "y": 8.509347894335995, "z": null, "yaw": 3.3749675107883172, "pitch": null, "roll": null}, "v": 0.975392833812055, "accelerator_pedal_position": 0.25420175295033287, "brake_pedal_position": 0.0, "acceleration": 0.08047740244645851, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24583750659013837, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141195.4118547} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25828360935483685, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9843016223981916, "gear": 1, "accelerator_pedal_position": 0.25828360935483685, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141195.4118547} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.96996569633484, "x": 46.61545346643915, "y": 8.509347894335995, "z": null, "yaw": 3.3749675107883172, "pitch": null, "roll": null}, "v": 0.975392833812055, "accelerator_pedal_position": 0.25420175295033287, "brake_pedal_position": 0.0, "acceleration": 0.08047740244645851, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24583750659013837, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141195.4318547} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25828360935483685, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9864082676227313, "gear": 1, "accelerator_pedal_position": 0.25828360935483685, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141195.4318547} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141195.4418547, "x": 50.5107880762992, "y": 13.483067414180889, "z": null, "yaw": 3.4026918540349547, "pitch": null, "roll": null}, "v": 0.9874604889465538, "accelerator_pedal_position": 0.25828360935483685, "brake_pedal_position": 0.0, "acceleration": 0.10514875184809686, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24887903216405552, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141195.4518547} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22062586111789492, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9885119764650347, "gear": 1, "accelerator_pedal_position": 0.25828360935483685, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141195.4518547} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.079965591430664, "x": 46.5107880762992, "y": 8.483067414180889, "z": null, "yaw": 3.4026918540349547, "pitch": null, "roll": null}, "v": 0.9874604889465538, "accelerator_pedal_position": 0.25828360935483685, "brake_pedal_position": 0.0, "acceleration": 0.10514875184809686, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24887903216405552, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141195.4718547} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2386221504588676, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9859071747782768, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141195.4718547} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.079965591430664, "x": 46.5107880762992, "y": 8.483067414180889, "z": null, "yaw": 3.4026918540349547, "pitch": null, "roll": null}, "v": 0.9874604889465538, "accelerator_pedal_position": 0.25828360935483685, "brake_pedal_position": 0.0, "acceleration": 0.10514875184809686, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24887903216405552, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141195.4918547} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2386221504588676, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9855547567087999, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141195.4918547} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.079965591430664, "x": 46.5107880762992, "y": 8.483067414180889, "z": null, "yaw": 3.4026918540349547, "pitch": null, "roll": null}, "v": 0.9874604889465538, "accelerator_pedal_position": 0.25828360935483685, "brake_pedal_position": 0.0, "acceleration": 0.10514875184809686, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24887903216405552, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141195.5118546} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2386221504588676, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9852028298294674, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141195.5118546} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.079965591430664, "x": 46.5107880762992, "y": 8.483067414180889, "z": null, "yaw": 3.4026918540349547, "pitch": null, "roll": null}, "v": 0.9874604889465538, "accelerator_pedal_position": 0.25828360935483685, "brake_pedal_position": 0.0, "acceleration": 0.10514875184809686, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24887903216405552, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141195.5318546} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2386221504588676, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.984851393406149, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141195.5318546} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141195.5518546, "x": 50.40637305543765, "y": 13.453754185351885, "z": null, "yaw": 3.430416197281592, "pitch": null, "roll": null}, "v": 0.9845004467059444, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2589174336309393, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2481329846449355, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141195.5518546} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23682104132774168, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9845004467059444, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141195.5518546} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.18996548652649, "x": 46.40637305543765, "y": 8.453754185351885, "z": null, "yaw": 3.430416197281592, "pitch": null, "roll": null}, "v": 0.9845004467059444, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2589174336309393, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2481329846449355, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141195.5718546} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23766298910687178, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9839249288001464, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141195.5718546} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.18996548652649, "x": 46.40637305543765, "y": 8.453754185351885, "z": null, "yaw": 3.430416197281592, "pitch": null, "roll": null}, "v": 0.9845004467059444, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2589174336309393, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2481329846449355, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141195.5918546} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23766298910687178, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9834554194816152, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141195.5918546} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.18996548652649, "x": 46.40637305543765, "y": 8.453754185351885, "z": null, "yaw": 3.430416197281592, "pitch": null, "roll": null}, "v": 0.9845004467059444, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2589174336309393, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2481329846449355, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141195.6118546} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23766298910687178, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9829865641631426, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141195.6118546} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.18996548652649, "x": 46.40637305543765, "y": 8.453754185351885, "z": null, "yaw": 3.430416197281592, "pitch": null, "roll": null}, "v": 0.9845004467059444, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2589174336309393, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2481329846449355, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141195.6318545} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23766298910687178, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9825183618458436, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141195.6318545} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.18996548652649, "x": 46.40637305543765, "y": 8.453754185351885, "z": null, "yaw": 3.430416197281592, "pitch": null, "roll": null}, "v": 0.9845004467059444, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2589174336309393, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2481329846449355, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141195.6518545} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23766298910687178, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9820508115325922, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141195.6518545} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141195.6618545, "x": 50.303096460379976, "y": 13.421646309355221, "z": null, "yaw": 3.4581405405282295, "pitch": null, "roll": null}, "v": 0.9818172805663622, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2587305157525054, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24745672083546708, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141195.6718545} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24369827757135373, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9815839122280167, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141195.6718545} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.299965381622314, "x": 46.303096460379976, "y": 8.421646309355221, "z": null, "yaw": 3.4581405405282295, "pitch": null, "roll": null}, "v": 0.9818172805663622, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2587305157525054, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24745672083546708, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141195.6918545} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24081008787856187, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9818718113453815, "gear": 1, "accelerator_pedal_position": 0.24369827757135373, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141195.6918545} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.299965381622314, "x": 46.303096460379976, "y": 8.421646309355221, "z": null, "yaw": 3.4581405405282295, "pitch": null, "roll": null}, "v": 0.9818172805663622, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2587305157525054, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24745672083546708, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141195.7118545} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24081008787856187, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.981798411633679, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141195.7118545} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.299965381622314, "x": 46.303096460379976, "y": 8.421646309355221, "z": null, "yaw": 3.4581405405282295, "pitch": null, "roll": null}, "v": 0.9818172805663622, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2587305157525054, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24745672083546708, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141195.7318544} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24081008787856187, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.981725114112122, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141195.7318544} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.299965381622314, "x": 46.303096460379976, "y": 8.421646309355221, "z": null, "yaw": 3.4581405405282295, "pitch": null, "roll": null}, "v": 0.9818172805663622, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2587305157525054, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24745672083546708, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141195.7518544} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24081008787856187, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9816519186362892, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141195.7518544} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141195.7718544, "x": 50.20090614176631, "y": 13.386740656869378, "z": null, "yaw": 3.485864883774867, "pitch": null, "roll": null}, "v": 0.9815788250619687, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2587139111511988, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24739662063316836, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141195.7718544} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24537859135869328, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9815788250619687, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141195.7718544} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.40996527671814, "x": 46.20090614176631, "y": 8.386740656869378, "z": null, "yaw": 3.485864883774867, "pitch": null, "roll": null}, "v": 0.9815788250619687, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2587139111511988, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24739662063316836, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141195.7918544} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2432018473111524, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9820766973540449, "gear": 1, "accelerator_pedal_position": 0.24537859135869328, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141195.7918544} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.40996527671814, "x": 46.20090614176631, "y": 8.386740656869378, "z": null, "yaw": 3.485864883774867, "pitch": null, "roll": null}, "v": 0.9815788250619687, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2587139111511988, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24739662063316836, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141195.8118544} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2432018473111524, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9823018782044073, "gear": 1, "accelerator_pedal_position": 0.2432018473111524, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141195.8118544} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.40996527671814, "x": 46.20090614176631, "y": 8.386740656869378, "z": null, "yaw": 3.485864883774867, "pitch": null, "roll": null}, "v": 0.9815788250619687, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2587139111511988, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24739662063316836, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141195.8318543} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2432018473111524, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9825267455099848, "gear": 1, "accelerator_pedal_position": 0.2432018473111524, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141195.8318543} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.40996527671814, "x": 46.20090614176631, "y": 8.386740656869378, "z": null, "yaw": 3.485864883774867, "pitch": null, "roll": null}, "v": 0.9815788250619687, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2587139111511988, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24739662063316836, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141195.8518543} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2432018473111524, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9827512996871423, "gear": 1, "accelerator_pedal_position": 0.2432018473111524, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141195.8518543} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.40996527671814, "x": 46.20090614176631, "y": 8.386740656869378, "z": null, "yaw": 3.485864883774867, "pitch": null, "roll": null}, "v": 0.9815788250619687, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2587139111511988, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24739662063316836, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141195.8718543} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2432018473111524, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9829755411517492, "gear": 1, "accelerator_pedal_position": 0.2432018473111524, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141195.8718543} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141195.8818543, "x": 50.09965661889847, "y": 13.348990565009663, "z": null, "yaw": 3.5135892270215043, "pitch": null, "roll": null}, "v": 0.9830875447466701, "accelerator_pedal_position": 0.2432018473111524, "brake_pedal_position": 0.0, "acceleration": 0.011192557251008595, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2477768775640922, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141195.8918543} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24471854200067958, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9831994703191802, "gear": 1, "accelerator_pedal_position": 0.2432018473111524, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141195.8918543} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.519965171813965, "x": 46.09965661889847, "y": 8.348990565009663, "z": null, "yaw": 3.5135892270215043, "pitch": null, "roll": null}, "v": 0.9830875447466701, "accelerator_pedal_position": 0.2432018473111524, "brake_pedal_position": 0.0, "acceleration": 0.011192557251008595, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2477768775640922, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141195.9118543} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24400431196640096, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9836126084006105, "gear": 1, "accelerator_pedal_position": 0.24471854200067958, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141195.9118543} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.519965171813965, "x": 46.09965661889847, "y": 8.348990565009663, "z": null, "yaw": 3.5135892270215043, "pitch": null, "roll": null}, "v": 0.9830875447466701, "accelerator_pedal_position": 0.2432018473111524, "brake_pedal_position": 0.0, "acceleration": 0.011192557251008595, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2477768775640922, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141195.9318542} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24400431196640096, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9839359233630554, "gear": 1, "accelerator_pedal_position": 0.24400431196640096, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141195.9318542} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.519965171813965, "x": 46.09965661889847, "y": 8.348990565009663, "z": null, "yaw": 3.5135892270215043, "pitch": null, "roll": null}, "v": 0.9830875447466701, "accelerator_pedal_position": 0.2432018473111524, "brake_pedal_position": 0.0, "acceleration": 0.011192557251008595, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2477768775640922, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141195.9518542} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24400431196640096, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9842587879294783, "gear": 1, "accelerator_pedal_position": 0.24400431196640096, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141195.9518542} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.519965171813965, "x": 46.09965661889847, "y": 8.348990565009663, "z": null, "yaw": 3.5135892270215043, "pitch": null, "roll": null}, "v": 0.9830875447466701, "accelerator_pedal_position": 0.2432018473111524, "brake_pedal_position": 0.0, "acceleration": 0.011192557251008595, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2477768775640922, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141195.9718542} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24400431196640096, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9845812026856244, "gear": 1, "accelerator_pedal_position": 0.24400431196640096, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141195.9718542} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141195.9918542, "x": 49.999335203599635, "y": 13.308384496068246, "z": null, "yaw": 3.5413135702681418, "pitch": null, "roll": null}, "v": 0.984903168216597, "accelerator_pedal_position": 0.24400431196640096, "brake_pedal_position": 0.0, "acceleration": 0.016081448871545112, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24823448636670037, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141195.9918542} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2387315714812556, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.984903168216597, "gear": 1, "accelerator_pedal_position": 0.24400431196640096, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141195.9918542} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.62996506690979, "x": 45.999335203599635, "y": 8.308384496068246, "z": null, "yaw": 3.5413135702681418, "pitch": null, "roll": null}, "v": 0.984903168216597, "accelerator_pedal_position": 0.24400431196640096, "brake_pedal_position": 0.0, "acceleration": 0.016081448871545112, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24823448636670037, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141196.0118542} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24125204058848673, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9845658222333287, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141196.0118542} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.62996506690979, "x": 45.999335203599635, "y": 8.308384496068246, "z": null, "yaw": 3.5413135702681418, "pitch": null, "roll": null}, "v": 0.984903168216597, "accelerator_pedal_position": 0.24400431196640096, "brake_pedal_position": 0.0, "acceleration": 0.016081448871545112, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24823448636670037, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141196.0318542} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24125204058848673, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9845438951562798, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141196.0318542} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.62996506690979, "x": 45.999335203599635, "y": 8.308384496068246, "z": null, "yaw": 3.5413135702681418, "pitch": null, "roll": null}, "v": 0.984903168216597, "accelerator_pedal_position": 0.24400431196640096, "brake_pedal_position": 0.0, "acceleration": 0.016081448871545112, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24823448636670037, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141196.0518541} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24125204058848673, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9845219986309744, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141196.0518541} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.62996506690979, "x": 45.999335203599635, "y": 8.308384496068246, "z": null, "yaw": 3.5413135702681418, "pitch": null, "roll": null}, "v": 0.984903168216597, "accelerator_pedal_position": 0.24400431196640096, "brake_pedal_position": 0.0, "acceleration": 0.016081448871545112, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24823448636670037, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141196.071854} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24125204058848673, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9845001326146521, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141196.071854} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.62996506690979, "x": 45.999335203599635, "y": 8.308384496068246, "z": null, "yaw": 3.5413135702681418, "pitch": null, "roll": null}, "v": 0.984903168216597, "accelerator_pedal_position": 0.24400431196640096, "brake_pedal_position": 0.0, "acceleration": 0.016081448871545112, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24823448636670037, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141196.091854} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24125204058848673, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9844782970646125, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141196.091854} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141196.101854, "x": 49.900111604691666, "y": 13.26498461486635, "z": null, "yaw": 3.569037913514779, "pitch": null, "roll": null}, "v": 0.9844673907011215, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25891512996859484, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24812465322653487, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141196.111854} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25361577469674584, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.984456491938216, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141196.111854} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.739964962005615, "x": 45.900111604691666, "y": 8.26498461486635, "z": null, "yaw": 3.569037913514779, "pitch": null, "roll": null}, "v": 0.9844673907011215, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25891512996859484, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24812465322653487, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141196.131854} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24772596534489175, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.985979645387217, "gear": 1, "accelerator_pedal_position": 0.25361577469674584, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141196.131854} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.739964962005615, "x": 45.900111604691666, "y": 8.26498461486635, "z": null, "yaw": 3.569037913514779, "pitch": null, "roll": null}, "v": 0.9844673907011215, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25891512996859484, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24812465322653487, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141196.151854} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24772596534489175, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9867647064561686, "gear": 1, "accelerator_pedal_position": 0.24772596534489175, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141196.151854} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.739964962005615, "x": 45.900111604691666, "y": 8.26498461486635, "z": null, "yaw": 3.569037913514779, "pitch": null, "roll": null}, "v": 0.9844673907011215, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25891512996859484, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24812465322653487, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141196.171854} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24772596534489175, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9875486730392158, "gear": 1, "accelerator_pedal_position": 0.24772596534489175, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141196.171854} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.739964962005615, "x": 45.900111604691666, "y": 8.26498461486635, "z": null, "yaw": 3.569037913514779, "pitch": null, "roll": null}, "v": 0.9844673907011215, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25891512996859484, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24812465322653487, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141196.191854} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24772596534489175, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9883315464164706, "gear": 1, "accelerator_pedal_position": 0.24772596534489175, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141196.191854} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141196.211854, "x": 49.80192510655846, "y": 13.218753296502193, "z": null, "yaw": 3.5967622567614166, "pitch": null, "roll": null}, "v": 0.9891133278672879, "accelerator_pedal_position": 0.24772596534489175, "brake_pedal_position": 0.0, "acceleration": 0.03904816525856197, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24929561283287216, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141196.211854} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2382285903704384, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9891133278672879, "gear": 1, "accelerator_pedal_position": 0.24772596534489175, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141196.211854} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.84996485710144, "x": 45.80192510655846, "y": 8.218753296502193, "z": null, "yaw": 3.5967622567614166, "pitch": null, "roll": null}, "v": 0.9891133278672879, "accelerator_pedal_position": 0.24772596534489175, "brake_pedal_position": 0.0, "acceleration": 0.03904816525856197, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24929561283287216, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141196.231854} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24277583696722482, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9887072610272997, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141196.231854} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.84996485710144, "x": 45.80192510655846, "y": 8.218753296502193, "z": null, "yaw": 3.5967622567614166, "pitch": null, "roll": null}, "v": 0.9891133278672879, "accelerator_pedal_position": 0.24772596534489175, "brake_pedal_position": 0.0, "acceleration": 0.03904816525856197, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24929561283287216, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141196.251854} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24277583696722482, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9888699681933341, "gear": 1, "accelerator_pedal_position": 0.24277583696722482, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141196.251854} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.84996485710144, "x": 45.80192510655846, "y": 8.218753296502193, "z": null, "yaw": 3.5967622567614166, "pitch": null, "roll": null}, "v": 0.9891133278672879, "accelerator_pedal_position": 0.24772596534489175, "brake_pedal_position": 0.0, "acceleration": 0.03904816525856197, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24929561283287216, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141196.271854} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24277583696722482, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.989032448375577, "gear": 1, "accelerator_pedal_position": 0.24277583696722482, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141196.271854} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.84996485710144, "x": 45.80192510655846, "y": 8.218753296502193, "z": null, "yaw": 3.5967622567614166, "pitch": null, "roll": null}, "v": 0.9891133278672879, "accelerator_pedal_position": 0.24772596534489175, "brake_pedal_position": 0.0, "acceleration": 0.03904816525856197, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24929561283287216, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141196.291854} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24277583696722482, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9891947018801249, "gear": 1, "accelerator_pedal_position": 0.24277583696722482, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141196.291854} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.84996485710144, "x": 45.80192510655846, "y": 8.218753296502193, "z": null, "yaw": 3.5967622567614166, "pitch": null, "roll": null}, "v": 0.9891133278672879, "accelerator_pedal_position": 0.24772596534489175, "brake_pedal_position": 0.0, "acceleration": 0.03904816525856197, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24929561283287216, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141196.311854} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24277583696722482, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9893567290126912, "gear": 1, "accelerator_pedal_position": 0.24277583696722482, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141196.311854} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141196.3218539, "x": 49.70482217929864, "y": 13.169700094108142, "z": null, "yaw": 3.624486600008054, "pitch": null, "roll": null}, "v": 0.9894376577849122, "accelerator_pedal_position": 0.24277583696722482, "brake_pedal_position": 0.0, "acceleration": 0.00808722936948053, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24937735677797554, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141196.3318539} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2480018744934235, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.989518530078607, "gear": 1, "accelerator_pedal_position": 0.24277583696722482, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141196.3318539} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.959964752197266, "x": 45.70482217929864, "y": 8.169700094108142, "z": null, "yaw": 3.624486600008054, "pitch": null, "roll": null}, "v": 0.9894376577849122, "accelerator_pedal_position": 0.24277583696722482, "brake_pedal_position": 0.0, "acceleration": 0.00808722936948053, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24937735677797554, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141196.3518538} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24551500841226212, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9903331321032133, "gear": 1, "accelerator_pedal_position": 0.2480018744934235, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141196.3518538} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.959964752197266, "x": 45.70482217929864, "y": 8.169700094108142, "z": null, "yaw": 3.624486600008054, "pitch": null, "roll": null}, "v": 0.9894376577849122, "accelerator_pedal_position": 0.24277583696722482, "brake_pedal_position": 0.0, "acceleration": 0.00808722936948053, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24937735677797554, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141196.3718538} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24551500841226212, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9908358475481083, "gear": 1, "accelerator_pedal_position": 0.24551500841226212, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141196.3718538} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.959964752197266, "x": 45.70482217929864, "y": 8.169700094108142, "z": null, "yaw": 3.624486600008054, "pitch": null, "roll": null}, "v": 0.9894376577849122, "accelerator_pedal_position": 0.24277583696722482, "brake_pedal_position": 0.0, "acceleration": 0.00808722936948053, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24937735677797554, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141196.3918538} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24551500841226212, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9913378613044705, "gear": 1, "accelerator_pedal_position": 0.24551500841226212, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141196.3918538} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.959964752197266, "x": 45.70482217929864, "y": 8.169700094108142, "z": null, "yaw": 3.624486600008054, "pitch": null, "roll": null}, "v": 0.9894376577849122, "accelerator_pedal_position": 0.24277583696722482, "brake_pedal_position": 0.0, "acceleration": 0.00808722936948053, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.24937735677797554, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141196.4118538} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24551500841226212, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9918391742509426, "gear": 1, "accelerator_pedal_position": 0.24551500841226212, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141196.4118538} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141196.4318538, "x": 49.60894719582471, "y": 13.117881824957642, "z": null, "yaw": 3.6522109432546914, "pitch": null, "roll": null}, "v": 0.9923397872653625, "accelerator_pedal_position": 0.24551500841226212, "brake_pedal_position": 0.0, "acceleration": 0.02500443067947139, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2501088079949045, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141196.4318538} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2494339151540064, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9923397872653625, "gear": 1, "accelerator_pedal_position": 0.24551500841226212, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141196.4318538} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.06996464729309, "x": 45.60894719582471, "y": 8.117881824957642, "z": null, "yaw": 3.6522109432546914, "pitch": null, "roll": null}, "v": 0.9923397872653625, "accelerator_pedal_position": 0.24551500841226212, "brake_pedal_position": 0.0, "acceleration": 0.02500443067947139, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2501088079949045, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141196.4518538} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2475832058931603, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9933293934723094, "gear": 1, "accelerator_pedal_position": 0.2494339151540064, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141196.4518538} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.06996464729309, "x": 45.60894719582471, "y": 8.117881824957642, "z": null, "yaw": 3.6522109432546914, "pitch": null, "roll": null}, "v": 0.9923397872653625, "accelerator_pedal_position": 0.24551500841226212, "brake_pedal_position": 0.0, "acceleration": 0.02500443067947139, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2501088079949045, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141196.4718537} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2475832058931603, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9940863596187385, "gear": 1, "accelerator_pedal_position": 0.2475832058931603, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141196.4718537} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.06996464729309, "x": 45.60894719582471, "y": 8.117881824957642, "z": null, "yaw": 3.6522109432546914, "pitch": null, "roll": null}, "v": 0.9923397872653625, "accelerator_pedal_position": 0.24551500841226212, "brake_pedal_position": 0.0, "acceleration": 0.02500443067947139, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2501088079949045, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141196.4918537} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2475832058931603, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9948422682300736, "gear": 1, "accelerator_pedal_position": 0.2475832058931603, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141196.4918537} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.06996464729309, "x": 45.60894719582471, "y": 8.117881824957642, "z": null, "yaw": 3.6522109432546914, "pitch": null, "roll": null}, "v": 0.9923397872653625, "accelerator_pedal_position": 0.24551500841226212, "brake_pedal_position": 0.0, "acceleration": 0.02500443067947139, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2501088079949045, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141196.5118537} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2475832058931603, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9955971205552866, "gear": 1, "accelerator_pedal_position": 0.2475832058931603, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141196.5118537} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.06996464729309, "x": 45.60894719582471, "y": 8.117881824957642, "z": null, "yaw": 3.6522109432546914, "pitch": null, "roll": null}, "v": 0.9923397872653625, "accelerator_pedal_position": 0.24551500841226212, "brake_pedal_position": 0.0, "acceleration": 0.02500443067947139, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2501088079949045, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141196.5318537} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2475832058931603, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9963509178425617, "gear": 1, "accelerator_pedal_position": 0.2475832058931603, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141196.5318537} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141196.5418537, "x": 49.5141977255293, "y": 13.063224743879735, "z": null, "yaw": 3.679935286501329, "pitch": null, "roll": null}, "v": 0.9967274212368143, "accelerator_pedal_position": 0.2475832058931603, "brake_pedal_position": 0.0, "acceleration": 0.03762401024795714, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2512146649973148, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141196.5518537} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24350062979440562, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.997103661339294, "gear": 1, "accelerator_pedal_position": 0.2475832058931603, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141196.5518537} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.179964542388916, "x": 45.5141977255293, "y": 8.063224743879735, "z": null, "yaw": 3.679935286501329, "pitch": null, "roll": null}, "v": 0.9967274212368143, "accelerator_pedal_position": 0.2475832058931603, "brake_pedal_position": 0.0, "acceleration": 0.03762401024795714, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2512146649973148, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141196.5718536} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2454680788004205, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.997345208757317, "gear": 1, "accelerator_pedal_position": 0.24350062979440562, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141196.5718536} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.179964542388916, "x": 45.5141977255293, "y": 8.063224743879735, "z": null, "yaw": 3.679935286501329, "pitch": null, "roll": null}, "v": 0.9967274212368143, "accelerator_pedal_position": 0.2475832058931603, "brake_pedal_position": 0.0, "acceleration": 0.03762401024795714, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2512146649973148, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141196.5918536} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2454680788004205, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9978322635001377, "gear": 1, "accelerator_pedal_position": 0.2454680788004205, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141196.5918536} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.179964542388916, "x": 45.5141977255293, "y": 8.063224743879735, "z": null, "yaw": 3.679935286501329, "pitch": null, "roll": null}, "v": 0.9967274212368143, "accelerator_pedal_position": 0.2475832058931603, "brake_pedal_position": 0.0, "acceleration": 0.03762401024795714, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2512146649973148, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141196.6118536} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2454680788004205, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.998318637050716, "gear": 1, "accelerator_pedal_position": 0.2454680788004205, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141196.6118536} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.179964542388916, "x": 45.5141977255293, "y": 8.063224743879735, "z": null, "yaw": 3.679935286501329, "pitch": null, "roll": null}, "v": 0.9967274212368143, "accelerator_pedal_position": 0.2475832058931603, "brake_pedal_position": 0.0, "acceleration": 0.03762401024795714, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2512146649973148, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141196.6318536} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2454680788004205, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9988043302671735, "gear": 1, "accelerator_pedal_position": 0.2454680788004205, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141196.6318536} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141196.6518536, "x": 49.42067680837816, "y": 13.005764229074456, "z": null, "yaw": 3.7076596297479663, "pitch": null, "roll": null}, "v": 0.999289344006828, "accelerator_pedal_position": 0.2454680788004205, "brake_pedal_position": 0.0, "acceleration": 0.024225233371830746, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.25186037069047146, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141196.6518536} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24890815523184306, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.999289344006828, "gear": 1, "accelerator_pedal_position": 0.2454680788004205, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141196.6518536} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.28996443748474, "x": 45.42067680837816, "y": 8.005764229074456, "z": null, "yaw": 3.7076596297479663, "pitch": null, "roll": null}, "v": 0.999289344006828, "accelerator_pedal_position": 0.2454680788004205, "brake_pedal_position": 0.0, "acceleration": 0.024225233371830746, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.25186037069047146, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141196.6718535} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24728367859940215, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0002035381922971, "gear": 1, "accelerator_pedal_position": 0.24890815523184306, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141196.6718535} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.28996443748474, "x": 45.42067680837816, "y": 8.005764229074456, "z": null, "yaw": 3.7076596297479663, "pitch": null, "roll": null}, "v": 0.999289344006828, "accelerator_pedal_position": 0.2454680788004205, "brake_pedal_position": 0.0, "acceleration": 0.024225233371830746, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.25186037069047146, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141196.6918535} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24728367859940215, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.000913464467202, "gear": 1, "accelerator_pedal_position": 0.24728367859940215, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141196.6918535} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.28996443748474, "x": 45.42067680837816, "y": 8.005764229074456, "z": null, "yaw": 3.7076596297479663, "pitch": null, "roll": null}, "v": 0.999289344006828, "accelerator_pedal_position": 0.2454680788004205, "brake_pedal_position": 0.0, "acceleration": 0.024225233371830746, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.25186037069047146, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141196.7118535} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24728367859940215, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0016223969843525, "gear": 1, "accelerator_pedal_position": 0.24728367859940215, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141196.7118535} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.28996443748474, "x": 45.42067680837816, "y": 8.005764229074456, "z": null, "yaw": 3.7076596297479663, "pitch": null, "roll": null}, "v": 0.999289344006828, "accelerator_pedal_position": 0.2454680788004205, "brake_pedal_position": 0.0, "acceleration": 0.024225233371830746, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.25186037069047146, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141196.7318535} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24728367859940215, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.002330336933851, "gear": 1, "accelerator_pedal_position": 0.24728367859940215, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141196.7318535} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.28996443748474, "x": 45.42067680837816, "y": 8.005764229074456, "z": null, "yaw": 3.7076596297479663, "pitch": null, "roll": null}, "v": 0.999289344006828, "accelerator_pedal_position": 0.2454680788004205, "brake_pedal_position": 0.0, "acceleration": 0.024225233371830746, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.25186037069047146, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141196.7518535} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24728367859940215, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0030372855049776, "gear": 1, "accelerator_pedal_position": 0.24728367859940215, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141196.7518535} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141196.7618535, "x": 49.32847513499999, "y": 12.94553063655331, "z": null, "yaw": 3.7353839729946037, "pitch": null, "roll": null}, "v": 1.0033903883950765, "accelerator_pedal_position": 0.24728367859940215, "brake_pedal_position": 0.0, "acceleration": 0.035285549111273296, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2528939958021942, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141196.7718534} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2583004697219624, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0037432438861893, "gear": 1, "accelerator_pedal_position": 0.24728367859940215, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141196.7718534} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.399964332580566, "x": 45.32847513499999, "y": 7.945530636553309, "z": null, "yaw": 3.7353839729946037, "pitch": null, "roll": null}, "v": 1.0033903883950765, "accelerator_pedal_position": 0.24728367859940215, "brake_pedal_position": 0.0, "acceleration": 0.035285549111273296, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2528939958021942, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141196.7918534} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25307625671134004, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0058248295593766, "gear": 1, "accelerator_pedal_position": 0.2583004697219624, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141196.7918534} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.399964332580566, "x": 45.32847513499999, "y": 7.945530636553309, "z": null, "yaw": 3.7353839729946037, "pitch": null, "roll": null}, "v": 1.0033903883950765, "accelerator_pedal_position": 0.24728367859940215, "brake_pedal_position": 0.0, "acceleration": 0.035285549111273296, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2528939958021942, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141196.8118534} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25307625671134004, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0072506999897937, "gear": 1, "accelerator_pedal_position": 0.25307625671134004, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141196.8118534} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.399964332580566, "x": 45.32847513499999, "y": 7.945530636553309, "z": null, "yaw": 3.7353839729946037, "pitch": null, "roll": null}, "v": 1.0033903883950765, "accelerator_pedal_position": 0.24728367859940215, "brake_pedal_position": 0.0, "acceleration": 0.035285549111273296, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2528939958021942, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141196.8318534} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25307625671134004, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0086745709709983, "gear": 1, "accelerator_pedal_position": 0.25307625671134004, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141196.8318534} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.399964332580566, "x": 45.32847513499999, "y": 7.945530636553309, "z": null, "yaw": 3.7353839729946037, "pitch": null, "roll": null}, "v": 1.0033903883950765, "accelerator_pedal_position": 0.24728367859940215, "brake_pedal_position": 0.0, "acceleration": 0.035285549111273296, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2528939958021942, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141196.8518534} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25307625671134004, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0100964444960703, "gear": 1, "accelerator_pedal_position": 0.25307625671134004, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141196.8518534} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141196.8718534, "x": 49.23744655596597, "y": 12.882393950596684, "z": null, "yaw": 3.763108316241241, "pitch": null, "roll": null}, "v": 1.0115163225587052, "accelerator_pedal_position": 0.25307625671134004, "brake_pedal_position": 0.0, "acceleration": 0.07091913560991309, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2549420520563034, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141196.8718534} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2455606534206199, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0115163225587052, "gear": 1, "accelerator_pedal_position": 0.25307625671134004, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141196.8718534} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.50996422767639, "x": 45.23744655596597, "y": 7.8823939505966845, "z": null, "yaw": 3.763108316241241, "pitch": null, "roll": null}, "v": 1.0115163225587052, "accelerator_pedal_position": 0.25307625671134004, "brake_pedal_position": 0.0, "acceleration": 0.07091913560991309, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2549420520563034, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141196.8918533} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24918294454576767, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0119950866759697, "gear": 1, "accelerator_pedal_position": 0.2455606534206199, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141196.8918533} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.50996422767639, "x": 45.23744655596597, "y": 7.8823939505966845, "z": null, "yaw": 3.763108316241241, "pitch": null, "roll": null}, "v": 1.0115163225587052, "accelerator_pedal_position": 0.25307625671134004, "brake_pedal_position": 0.0, "acceleration": 0.07091913560991309, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2549420520563034, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141196.9118533} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24918294454576767, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0129258058417947, "gear": 1, "accelerator_pedal_position": 0.24918294454576767, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141196.9118533} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.50996422767639, "x": 45.23744655596597, "y": 7.8823939505966845, "z": null, "yaw": 3.763108316241241, "pitch": null, "roll": null}, "v": 1.0115163225587052, "accelerator_pedal_position": 0.25307625671134004, "brake_pedal_position": 0.0, "acceleration": 0.07091913560991309, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2549420520563034, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141196.9318533} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24918294454576767, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.01385521773469, "gear": 1, "accelerator_pedal_position": 0.24918294454576767, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141196.9318533} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.50996422767639, "x": 45.23744655596597, "y": 7.8823939505966845, "z": null, "yaw": 3.763108316241241, "pitch": null, "roll": null}, "v": 1.0115163225587052, "accelerator_pedal_position": 0.25307625671134004, "brake_pedal_position": 0.0, "acceleration": 0.07091913560991309, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2549420520563034, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141196.9518533} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24918294454576767, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0147833238454282, "gear": 1, "accelerator_pedal_position": 0.24918294454576767, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141196.9518533} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.50996422767639, "x": 45.23744655596597, "y": 7.8823939505966845, "z": null, "yaw": 3.763108316241241, "pitch": null, "roll": null}, "v": 1.0115163225587052, "accelerator_pedal_position": 0.25307625671134004, "brake_pedal_position": 0.0, "acceleration": 0.07091913560991309, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2549420520563034, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141196.9718533} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24918294454576767, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0157101256641439, "gear": 1, "accelerator_pedal_position": 0.24918294454576767, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141196.9718533} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141196.9818532, "x": 49.1476427464045, "y": 12.816347104326422, "z": null, "yaw": 3.7908326594878785, "pitch": null, "roll": null}, "v": 1.0161730379294847, "accelerator_pedal_position": 0.24918294454576767, "brake_pedal_position": 0.0, "acceleration": 0.046258675084425216, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2561157281957705, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141196.9918532} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2535679120740106, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.016635624680329, "gear": 1, "accelerator_pedal_position": 0.24918294454576767, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141196.9918532} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.61996412277222, "x": 45.1476427464045, "y": 7.816347104326422, "z": null, "yaw": 3.7908326594878785, "pitch": null, "roll": null}, "v": 1.0161730379294847, "accelerator_pedal_position": 0.24918294454576767, "brake_pedal_position": 0.0, "acceleration": 0.046258675084425216, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2561157281957705, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141197.0118532} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25150476532445615, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0181077505368492, "gear": 1, "accelerator_pedal_position": 0.2535679120740106, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141197.0118532} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.61996412277222, "x": 45.1476427464045, "y": 7.816347104326422, "z": null, "yaw": 3.7908326594878785, "pitch": null, "roll": null}, "v": 1.0161730379294847, "accelerator_pedal_position": 0.24918294454576767, "brake_pedal_position": 0.0, "acceleration": 0.046258675084425216, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2561157281957705, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141197.0318532} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25150476532445615, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0193200031031417, "gear": 1, "accelerator_pedal_position": 0.25150476532445615, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141197.0318532} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.61996412277222, "x": 45.1476427464045, "y": 7.816347104326422, "z": null, "yaw": 3.7908326594878785, "pitch": null, "roll": null}, "v": 1.0161730379294847, "accelerator_pedal_position": 0.24918294454576767, "brake_pedal_position": 0.0, "acceleration": 0.046258675084425216, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2561157281957705, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141197.0518532} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25150476532445615, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0205305498950357, "gear": 1, "accelerator_pedal_position": 0.25150476532445615, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141197.0518532} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.61996412277222, "x": 45.1476427464045, "y": 7.816347104326422, "z": null, "yaw": 3.7908326594878785, "pitch": null, "roll": null}, "v": 1.0161730379294847, "accelerator_pedal_position": 0.24918294454576767, "brake_pedal_position": 0.0, "acceleration": 0.046258675084425216, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2561157281957705, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141197.0718532} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25150476532445615, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0217393927267824, "gear": 1, "accelerator_pedal_position": 0.25150476532445615, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141197.0718532} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141197.0918531, "x": 49.05919949173834, "y": 12.747442255592109, "z": null, "yaw": 3.818557002734516, "pitch": null, "roll": null}, "v": 1.0229465334125536, "accelerator_pedal_position": 0.25150476532445615, "brake_pedal_position": 0.0, "acceleration": 0.0602932605050156, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2578229165026082, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141197.0918531} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25674077658955996, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0229465334125536, "gear": 1, "accelerator_pedal_position": 0.25150476532445615, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141197.0918531} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.72996401786804, "x": 45.05919949173834, "y": 7.747442255592109, "z": null, "yaw": 3.818557002734516, "pitch": null, "roll": null}, "v": 1.0229465334125536, "accelerator_pedal_position": 0.25150476532445615, "brake_pedal_position": 0.0, "acceleration": 0.0602932605050156, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2578229165026082, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141197.1118531} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2542837638604082, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.024806244547055, "gear": 1, "accelerator_pedal_position": 0.25674077658955996, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141197.1118531} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.72996401786804, "x": 45.05919949173834, "y": 7.747442255592109, "z": null, "yaw": 3.818557002734516, "pitch": null, "roll": null}, "v": 1.0229465334125536, "accelerator_pedal_position": 0.25150476532445615, "brake_pedal_position": 0.0, "acceleration": 0.0602932605050156, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2578229165026082, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141197.131853} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2542837638604082, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0263563165941387, "gear": 1, "accelerator_pedal_position": 0.2542837638604082, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141197.131853} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.72996401786804, "x": 45.05919949173834, "y": 7.747442255592109, "z": null, "yaw": 3.818557002734516, "pitch": null, "roll": null}, "v": 1.0229465334125536, "accelerator_pedal_position": 0.25150476532445615, "brake_pedal_position": 0.0, "acceleration": 0.0602932605050156, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2578229165026082, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141197.151853} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2542837638604082, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0279042032098857, "gear": 1, "accelerator_pedal_position": 0.2542837638604082, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141197.151853} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.72996401786804, "x": 45.05919949173834, "y": 7.747442255592109, "z": null, "yaw": 3.818557002734516, "pitch": null, "roll": null}, "v": 1.0229465334125536, "accelerator_pedal_position": 0.25150476532445615, "brake_pedal_position": 0.0, "acceleration": 0.0602932605050156, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2578229165026082, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141197.171853} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2542837638604082, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0294499065174711, "gear": 1, "accelerator_pedal_position": 0.2542837638604082, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141197.171853} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.72996401786804, "x": 45.05919949173834, "y": 7.747442255592109, "z": null, "yaw": 3.818557002734516, "pitch": null, "roll": null}, "v": 1.0229465334125536, "accelerator_pedal_position": 0.25150476532445615, "brake_pedal_position": 0.0, "acceleration": 0.0602932605050156, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2578229165026082, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141197.191853} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2542837638604082, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.030993428641128, "gear": 1, "accelerator_pedal_position": 0.2542837638604082, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141197.191853} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141197.201853, "x": 48.97203753148475, "y": 12.67556501744407, "z": null, "yaw": 3.8462813459811533, "pitch": null, "roll": null}, "v": 1.0317643724230927, "accelerator_pedal_position": 0.2542837638604082, "brake_pedal_position": 0.0, "acceleration": 0.07703992830438022, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2600453600973516, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141197.211853} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25348215893682413, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0325347717061366, "gear": 1, "accelerator_pedal_position": 0.2542837638604082, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141197.211853} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.83996391296387, "x": 44.97203753148475, "y": 7.67556501744407, "z": null, "yaw": 3.8462813459811533, "pitch": null, "roll": null}, "v": 1.0317643724230927, "accelerator_pedal_position": 0.2542837638604082, "brake_pedal_position": 0.0, "acceleration": 0.07703992830438022, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2600453600973516, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141197.231853} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25391127182339324, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0339737726270415, "gear": 1, "accelerator_pedal_position": 0.25348215893682413, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141197.231853} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.83996391296387, "x": 44.97203753148475, "y": 7.67556501744407, "z": null, "yaw": 3.8462813459811533, "pitch": null, "roll": null}, "v": 1.0317643724230927, "accelerator_pedal_position": 0.2542837638604082, "brake_pedal_position": 0.0, "acceleration": 0.07703992830438022, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2600453600973516, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141197.251853} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25391127182339324, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0354643604681788, "gear": 1, "accelerator_pedal_position": 0.25391127182339324, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141197.251853} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.83996391296387, "x": 44.97203753148475, "y": 7.67556501744407, "z": null, "yaw": 3.8462813459811533, "pitch": null, "roll": null}, "v": 1.0317643724230927, "accelerator_pedal_position": 0.2542837638604082, "brake_pedal_position": 0.0, "acceleration": 0.07703992830438022, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2600453600973516, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141197.271853} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25391127182339324, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0369528413086118, "gear": 1, "accelerator_pedal_position": 0.25391127182339324, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141197.271853} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.83996391296387, "x": 44.97203753148475, "y": 7.67556501744407, "z": null, "yaw": 3.8462813459811533, "pitch": null, "roll": null}, "v": 1.0317643724230927, "accelerator_pedal_position": 0.2542837638604082, "brake_pedal_position": 0.0, "acceleration": 0.07703992830438022, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2600453600973516, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141197.291853} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25391127182339324, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0384392172407466, "gear": 1, "accelerator_pedal_position": 0.25391127182339324, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141197.291853} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141197.311853, "x": 48.88620633651172, "y": 12.60069296258602, "z": null, "yaw": 3.8740056892277908, "pitch": null, "roll": null}, "v": 1.0399234903577885, "accelerator_pedal_position": 0.25391127182339324, "brake_pedal_position": 0.0, "acceleration": 0.07413486572033895, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.26210177997199974, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141197.311853} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.260376665016275, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0399234903577885, "gear": 1, "accelerator_pedal_position": 0.25391127182339324, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141197.311853} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.94996380805969, "x": 44.88620633651172, "y": 7.60069296258602, "z": null, "yaw": 3.8740056892277908, "pitch": null, "roll": null}, "v": 1.0399234903577885, "accelerator_pedal_position": 0.25391127182339324, "brake_pedal_position": 0.0, "acceleration": 0.07413486572033895, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.26210177997199974, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141197.331853} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2573418657781411, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0422135507391324, "gear": 1, "accelerator_pedal_position": 0.260376665016275, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141197.331853} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.94996380805969, "x": 44.88620633651172, "y": 7.60069296258602, "z": null, "yaw": 3.8740056892277908, "pitch": null, "roll": null}, "v": 1.0399234903577885, "accelerator_pedal_position": 0.25391127182339324, "brake_pedal_position": 0.0, "acceleration": 0.07413486572033895, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.26210177997199974, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141197.351853} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2573418657781411, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0441211525497864, "gear": 1, "accelerator_pedal_position": 0.2573418657781411, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141197.351853} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.94996380805969, "x": 44.88620633651172, "y": 7.60069296258602, "z": null, "yaw": 3.8740056892277908, "pitch": null, "roll": null}, "v": 1.0399234903577885, "accelerator_pedal_position": 0.25391127182339324, "brake_pedal_position": 0.0, "acceleration": 0.07413486572033895, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.26210177997199974, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141197.3718529} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2573418657781411, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0460260513738746, "gear": 1, "accelerator_pedal_position": 0.2573418657781411, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141197.3718529} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.94996380805969, "x": 44.88620633651172, "y": 7.60069296258602, "z": null, "yaw": 3.8740056892277908, "pitch": null, "roll": null}, "v": 1.0399234903577885, "accelerator_pedal_position": 0.25391127182339324, "brake_pedal_position": 0.0, "acceleration": 0.07413486572033895, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.26210177997199974, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141197.3918529} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2573418657781411, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0479282495904665, "gear": 1, "accelerator_pedal_position": 0.2573418657781411, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141197.3918529} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.94996380805969, "x": 44.88620633651172, "y": 7.60069296258602, "z": null, "yaw": 3.8740056892277908, "pitch": null, "roll": null}, "v": 1.0399234903577885, "accelerator_pedal_position": 0.25391127182339324, "brake_pedal_position": 0.0, "acceleration": 0.07413486572033895, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.26210177997199974, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141197.4118528} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2573418657781411, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0498277495814294, "gear": 1, "accelerator_pedal_position": 0.2573418657781411, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141197.4118528} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141197.4218528, "x": 48.801712152375586, "y": 12.522757918749512, "z": null, "yaw": 3.901730032474428, "pitch": null, "roll": null}, "v": 1.0507764884873934, "accelerator_pedal_position": 0.2573418657781411, "brake_pedal_position": 0.0, "acceleration": 0.09480652440143322, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.26483716402109314, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141197.4318528} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26351580937946945, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.835851739706024, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0517245537314077, "gear": 1, "accelerator_pedal_position": 0.2573418657781411, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141197.4318528} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.05996370315552, "x": 44.801712152375586, "y": 7.522757918749512, "z": null, "yaw": 3.901730032474428, "pitch": null, "roll": null}, "v": 1.0507764884873934, "accelerator_pedal_position": 0.2573418657781411, "brake_pedal_position": 0.0, "acceleration": 0.09480652440143322, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.26483716402109314, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141197.4518528} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26063446744699154, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.835851739706024, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0543901331881274, "gear": 1, "accelerator_pedal_position": 0.26351580937946945, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141197.4518528} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.05996370315552, "x": 44.801712152375586, "y": 7.522757918749512, "z": null, "yaw": 3.901730032474428, "pitch": null, "roll": null}, "v": 1.0507764884873934, "accelerator_pedal_position": 0.2573418657781411, "brake_pedal_position": 0.0, "acceleration": 0.09480652440143322, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.26483716402109314, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141197.4718528} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26063446744699154, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.835851739706024, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0566918852192568, "gear": 1, "accelerator_pedal_position": 0.26063446744699154, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141197.4718528} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.05996370315552, "x": 44.801712152375586, "y": 7.522757918749512, "z": null, "yaw": 3.901730032474428, "pitch": null, "roll": null}, "v": 1.0507764884873934, "accelerator_pedal_position": 0.2573418657781411, "brake_pedal_position": 0.0, "acceleration": 0.09480652440143322, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.26483716402109314, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141197.4918528} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26063446744699154, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.835851739706024, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0589903642955873, "gear": 1, "accelerator_pedal_position": 0.26063446744699154, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141197.4918528} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.05996370315552, "x": 44.801712152375586, "y": 7.522757918749512, "z": null, "yaw": 3.901730032474428, "pitch": null, "roll": null}, "v": 1.0507764884873934, "accelerator_pedal_position": 0.2573418657781411, "brake_pedal_position": 0.0, "acceleration": 0.09480652440143322, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.26483716402109314, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141197.5118527} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26063446744699154, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.835851739706024, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0612855729586157, "gear": 1, "accelerator_pedal_position": 0.26063446744699154, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141197.5118527} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141197.5318527, "x": 48.71849720157497, "y": 12.44161899587243, "z": null, "yaw": 3.9294543757210656, "pitch": null, "roll": null}, "v": 1.0635775137552377, "accelerator_pedal_position": 0.26063446744699154, "brake_pedal_position": 0.0, "acceleration": 0.11447457457827742, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2680635278250439, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141197.5318527} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26542864468857674, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.447792481240613, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0635775137552377, "gear": 1, "accelerator_pedal_position": 0.26063446744699154, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141197.5318527} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.16996359825134, "x": 44.71849720157497, "y": 7.44161899587243, "z": null, "yaw": 3.9294543757210656, "pitch": null, "roll": null}, "v": 1.0635775137552377, "accelerator_pedal_position": 0.26063446744699154, "brake_pedal_position": 0.0, "acceleration": 0.11447457457827742, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2680635278250439, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141197.5518527} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2632150894870807, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.447792481240613, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.06646524776006, "gear": 1, "accelerator_pedal_position": 0.26542864468857674, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141197.5518527} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.16996359825134, "x": 44.71849720157497, "y": 7.44161899587243, "z": null, "yaw": 3.9294543757210656, "pitch": null, "roll": null}, "v": 1.0635775137552377, "accelerator_pedal_position": 0.26063446744699154, "brake_pedal_position": 0.0, "acceleration": 0.11447457457827742, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2680635278250439, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141197.5718527} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2632150894870807, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.447792481240613, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0690722687864411, "gear": 1, "accelerator_pedal_position": 0.2632150894870807, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141197.5718527} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.16996359825134, "x": 44.71849720157497, "y": 7.44161899587243, "z": null, "yaw": 3.9294543757210656, "pitch": null, "roll": null}, "v": 1.0635775137552377, "accelerator_pedal_position": 0.26063446744699154, "brake_pedal_position": 0.0, "acceleration": 0.11447457457827742, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2680635278250439, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141197.5918527} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2632150894870807, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.447792481240613, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0716755699620137, "gear": 1, "accelerator_pedal_position": 0.2632150894870807, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141197.5918527} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.16996359825134, "x": 44.71849720157497, "y": 7.44161899587243, "z": null, "yaw": 3.9294543757210656, "pitch": null, "roll": null}, "v": 1.0635775137552377, "accelerator_pedal_position": 0.26063446744699154, "brake_pedal_position": 0.0, "acceleration": 0.11447457457827742, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2680635278250439, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141197.6118526} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2632150894870807, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.447792481240613, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0742751538845763, "gear": 1, "accelerator_pedal_position": 0.2632150894870807, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141197.6118526} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.16996359825134, "x": 44.71849720157497, "y": 7.44161899587243, "z": null, "yaw": 3.9294543757210656, "pitch": null, "roll": null}, "v": 1.0635775137552377, "accelerator_pedal_position": 0.26063446744699154, "brake_pedal_position": 0.0, "acceleration": 0.11447457457827742, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.2680635278250439, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141197.6318526} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2632150894870807, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.447792481240613, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0768710231598242, "gear": 1, "accelerator_pedal_position": 0.2632150894870807, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141197.6318526} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141197.6418526, "x": 48.636513781590835, "y": 12.357122098280648, "z": null, "yaw": 3.957178718967703, "pitch": null, "roll": null}, "v": 1.0781675656211347, "accelerator_pedal_position": 0.2632150894870807, "brake_pedal_position": 0.0, "acceleration": 0.12956147801762363, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.27174079696973813, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141197.6518526} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2641833518126291, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.91839658421268, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0794631804013108, "gear": 1, "accelerator_pedal_position": 0.2632150894870807, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141197.6518526} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.27996349334717, "x": 44.636513781590835, "y": 7.357122098280648, "z": null, "yaw": 3.957178718967703, "pitch": null, "roll": null}, "v": 1.0781675656211347, "accelerator_pedal_position": 0.2632150894870807, "brake_pedal_position": 0.0, "acceleration": 0.12956147801762363, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.27174079696973813, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141197.6718526} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2638016636049332, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.91839658421268, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0821726176818252, "gear": 1, "accelerator_pedal_position": 0.2641833518126291, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141197.6718526} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.27996349334717, "x": 44.636513781590835, "y": 7.357122098280648, "z": null, "yaw": 3.957178718967703, "pitch": null, "roll": null}, "v": 1.0781675656211347, "accelerator_pedal_position": 0.2632150894870807, "brake_pedal_position": 0.0, "acceleration": 0.12956147801762363, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.27174079696973813, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141197.6918526} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2638016636049332, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.91839658421268, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0848304808894134, "gear": 1, "accelerator_pedal_position": 0.2638016636049332, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141197.6918526} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.27996349334717, "x": 44.636513781590835, "y": 7.357122098280648, "z": null, "yaw": 3.957178718967703, "pitch": null, "roll": null}, "v": 1.0781675656211347, "accelerator_pedal_position": 0.2632150894870807, "brake_pedal_position": 0.0, "acceleration": 0.12956147801762363, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.27174079696973813, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141197.7118526} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2638016636049332, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.91839658421268, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0874845349738047, "gear": 1, "accelerator_pedal_position": 0.2638016636049332, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141197.7118526} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.27996349334717, "x": 44.636513781590835, "y": 7.357122098280648, "z": null, "yaw": 3.957178718967703, "pitch": null, "roll": null}, "v": 1.0781675656211347, "accelerator_pedal_position": 0.2632150894870807, "brake_pedal_position": 0.0, "acceleration": 0.12956147801762363, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.27174079696973813, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141197.7318525} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2638016636049332, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.91839658421268, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.090134782577462, "gear": 1, "accelerator_pedal_position": 0.2638016636049332, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141197.7318525} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141197.7518525, "x": 48.55582671297258, "y": 12.269211110637235, "z": null, "yaw": 3.9849030622143404, "pitch": null, "roll": null}, "v": 1.0927812263511754, "accelerator_pedal_position": 0.2638016636049332, "brake_pedal_position": 0.0, "acceleration": 0.1321796281266177, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.27542401648037035, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141197.7518525} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2710517194010681, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.449218396786083, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0927812263511754, "gear": 1, "accelerator_pedal_position": 0.2638016636049332, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.437991240545463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141197.7518525} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.38996338844299, "x": 44.55582671297258, "y": 7.269211110637235, "z": null, "yaw": 3.9849030622143404, "pitch": null, "roll": null}, "v": 1.0927812263511754, "accelerator_pedal_position": 0.2638016636049332, "brake_pedal_position": 0.0, "acceleration": 0.1321796281266177, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.27542401648037035, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141197.7718525} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2676791530993136, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.449218396786083, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0963298001899116, "gear": 1, "accelerator_pedal_position": 0.2710517194010681, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.361961467776476, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141197.7718525} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.38996338844299, "x": 44.55582671297258, "y": 7.269211110637235, "z": null, "yaw": 3.9849030622143404, "pitch": null, "roll": null}, "v": 1.0927812263511754, "accelerator_pedal_position": 0.2638016636049332, "brake_pedal_position": 0.0, "acceleration": 0.1321796281266177, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.27542401648037035, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141197.7918525} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2676791530993136, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.449218396786083, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0994518532798403, "gear": 1, "accelerator_pedal_position": 0.2676791530993136, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.285598927027875, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141197.7918525} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.38996338844299, "x": 44.55582671297258, "y": 7.269211110637235, "z": null, "yaw": 3.9849030622143404, "pitch": null, "roll": null}, "v": 1.0927812263511754, "accelerator_pedal_position": 0.2638016636049332, "brake_pedal_position": 0.0, "acceleration": 0.1321796281266177, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.27542401648037035, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141197.8118525} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2676791530993136, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.449218396786083, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1025694138902065, "gear": 1, "accelerator_pedal_position": 0.2676791530993136, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.208903618299658, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141197.8118525} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.38996338844299, "x": 44.55582671297258, "y": 7.269211110637235, "z": null, "yaw": 3.9849030622143404, "pitch": null, "roll": null}, "v": 1.0927812263511754, "accelerator_pedal_position": 0.2638016636049332, "brake_pedal_position": 0.0, "acceleration": 0.1321796281266177, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.27542401648037035, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141197.8318524} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2676791530993136, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.449218396786083, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1056824845991913, "gear": 1, "accelerator_pedal_position": 0.2676791530993136, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.131875541591825, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141197.8318524} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.38996338844299, "x": 44.55582671297258, "y": 7.269211110637235, "z": null, "yaw": 3.9849030622143404, "pitch": null, "roll": null}, "v": 1.0927812263511754, "accelerator_pedal_position": 0.2638016636049332, "brake_pedal_position": 0.0, "acceleration": 0.1321796281266177, "steering_wheel_angle": 10.437991240545463, "front_wheel_angle": 0.5730083585690458, "heading_rate": 0.27542401648037035, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141197.8518524} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2676791530993136, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.449218396786083, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1087910679980502, "gear": 1, "accelerator_pedal_position": 0.2676791530993136, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.054514696904377, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141197.8518524} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141197.8618524, "x": 48.476425401618144, "y": 12.177773730692568, "z": null, "yaw": 4.011848932128006, "pitch": null, "roll": null}, "v": 1.110343677769511, "accelerator_pedal_position": 0.2676791530993136, "brake_pedal_position": 0.0, "acceleration": 0.15514889215460725, "steering_wheel_angle": 10.054514696904377, "front_wheel_angle": 0.5471292201103017, "heading_rate": 0.26421072042156807, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141197.8718524} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.273268282713963, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.87467626173756, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.111895166691057, "gear": 1, "accelerator_pedal_position": 0.2676791530993136, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.054514696904377, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141197.8718524} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.49996328353882, "x": 44.476425401618144, "y": 7.177773730692568, "z": null, "yaw": 4.011848932128006, "pitch": null, "roll": null}, "v": 1.110343677769511, "accelerator_pedal_position": 0.2676791530993136, "brake_pedal_position": 0.0, "acceleration": 0.15514889215460725, "steering_wheel_angle": 10.054514696904377, "front_wheel_angle": 0.5471292201103017, "heading_rate": 0.26421072042156807, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141197.8918524} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.270703175544605, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.87467626173756, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1156931720348837, "gear": 1, "accelerator_pedal_position": 0.273268282713963, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.979047593306221, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141197.8918524} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.49996328353882, "x": 44.476425401618144, "y": 7.177773730692568, "z": null, "yaw": 4.011848932128006, "pitch": null, "roll": null}, "v": 1.110343677769511, "accelerator_pedal_position": 0.2676791530993136, "brake_pedal_position": 0.0, "acceleration": 0.15514889215460725, "steering_wheel_angle": 10.054514696904377, "front_wheel_angle": 0.5471292201103017, "heading_rate": 0.26421072042156807, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141197.9118524} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.270703175544605, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.87467626173756, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1208992782551248, "gear": 1, "accelerator_pedal_position": 0.270703175544605, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.865258174607956, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141197.9118524} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.49996328353882, "x": 44.476425401618144, "y": 7.177773730692568, "z": null, "yaw": 4.011848932128006, "pitch": null, "roll": null}, "v": 1.110343677769511, "accelerator_pedal_position": 0.2676791530993136, "brake_pedal_position": 0.0, "acceleration": 0.15514889215460725, "steering_wheel_angle": 10.054514696904377, "front_wheel_angle": 0.5471292201103017, "heading_rate": 0.26421072042156807, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141197.9318523} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.270703175544605, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.87467626173756, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1226321355683357, "gear": 1, "accelerator_pedal_position": 0.270703175544605, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.827171364828258, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141197.9318523} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.49996328353882, "x": 44.476425401618144, "y": 7.177773730692568, "z": null, "yaw": 4.011848932128006, "pitch": null, "roll": null}, "v": 1.110343677769511, "accelerator_pedal_position": 0.2676791530993136, "brake_pedal_position": 0.0, "acceleration": 0.15514889215460725, "steering_wheel_angle": 10.054514696904377, "front_wheel_angle": 0.5471292201103017, "heading_rate": 0.26421072042156807, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141197.9518523} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.270703175544605, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.87467626173756, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1295510159132125, "gear": 1, "accelerator_pedal_position": 0.270703175544605, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.674039107974755, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141197.9518523} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141197.9718523, "x": 48.39818753194882, "y": 12.082737147637843, "z": null, "yaw": 4.0374237531765775, "pitch": null, "roll": null}, "v": 1.1295510159132125, "accelerator_pedal_position": 0.270703175544605, "brake_pedal_position": 0.0, "acceleration": 0.17265844138261477, "steering_wheel_angle": 9.674039107974755, "front_wheel_angle": 0.521990174902317, "heading_rate": 0.2537992839256667, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141197.9718523} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28034035121237116, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.390720431421991, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1295510159132125, "gear": 1, "accelerator_pedal_position": 0.270703175544605, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.674039107974755, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141197.9718523} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.609963178634644, "x": 44.39818753194882, "y": 7.082737147637843, "z": null, "yaw": 4.0374237531765775, "pitch": null, "roll": null}, "v": 1.1295510159132125, "accelerator_pedal_position": 0.270703175544605, "brake_pedal_position": 0.0, "acceleration": 0.17265844138261477, "steering_wheel_angle": 9.674039107974755, "front_wheel_angle": 0.521990174902317, "heading_rate": 0.2537992839256667, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141197.9918523} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27585716749713174, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.390720431421991, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1342071405789524, "gear": 1, "accelerator_pedal_position": 0.28034035121237116, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.598772030173048, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141197.9918523} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.609963178634644, "x": 44.39818753194882, "y": 7.082737147637843, "z": null, "yaw": 4.0374237531765775, "pitch": null, "roll": null}, "v": 1.1295510159132125, "accelerator_pedal_position": 0.270703175544605, "brake_pedal_position": 0.0, "acceleration": 0.17265844138261477, "steering_wheel_angle": 9.674039107974755, "front_wheel_angle": 0.521990174902317, "heading_rate": 0.2537992839256667, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141198.0118523} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27585716749713174, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.390720431421991, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.138296307161368, "gear": 1, "accelerator_pedal_position": 0.27585716749713174, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.523205181195468, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141198.0118523} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.609963178634644, "x": 44.39818753194882, "y": 7.082737147637843, "z": null, "yaw": 4.0374237531765775, "pitch": null, "roll": null}, "v": 1.1295510159132125, "accelerator_pedal_position": 0.270703175544605, "brake_pedal_position": 0.0, "acceleration": 0.17265844138261477, "steering_wheel_angle": 9.674039107974755, "front_wheel_angle": 0.521990174902317, "heading_rate": 0.2537992839256667, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141198.0318522} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27585716749713174, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.390720431421991, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.142379526540597, "gear": 1, "accelerator_pedal_position": 0.27585716749713174, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.447338561042018, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141198.0318522} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.609963178634644, "x": 44.39818753194882, "y": 7.082737147637843, "z": null, "yaw": 4.0374237531765775, "pitch": null, "roll": null}, "v": 1.1295510159132125, "accelerator_pedal_position": 0.270703175544605, "brake_pedal_position": 0.0, "acceleration": 0.17265844138261477, "steering_wheel_angle": 9.674039107974755, "front_wheel_angle": 0.521990174902317, "heading_rate": 0.2537992839256667, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141198.0518522} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27585716749713174, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.390720431421991, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.146456800699489, "gear": 1, "accelerator_pedal_position": 0.27585716749713174, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.371172169712699, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141198.0518522} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.609963178634644, "x": 44.39818753194882, "y": 7.082737147637843, "z": null, "yaw": 4.0374237531765775, "pitch": null, "roll": null}, "v": 1.1295510159132125, "accelerator_pedal_position": 0.270703175544605, "brake_pedal_position": 0.0, "acceleration": 0.17265844138261477, "steering_wheel_angle": 9.674039107974755, "front_wheel_angle": 0.521990174902317, "heading_rate": 0.2537992839256667, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141198.0718522} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27585716749713174, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.390720431421991, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1505281316471196, "gear": 1, "accelerator_pedal_position": 0.27585716749713174, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.294706007207504, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141198.0718522} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141198.0818522, "x": 48.32090337309049, "y": 11.983951557256278, "z": null, "yaw": 4.061444180070348, "pitch": null, "roll": null}, "v": 1.1525615690516957, "accelerator_pedal_position": 0.27585716749713174, "brake_pedal_position": 0.0, "acceleration": 0.20319523669993944, "steering_wheel_angle": 9.256360511763956, "front_wheel_angle": 0.4949713367331617, "heading_rate": 0.2430243032681532, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141198.0918522} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28339512730103633, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.75068488629775, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.154593521418695, "gear": 1, "accelerator_pedal_position": 0.27585716749713174, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.21794007352644, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141198.0918522} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.71996307373047, "x": 44.32090337309049, "y": 6.983951557256278, "z": null, "yaw": 4.061444180070348, "pitch": null, "roll": null}, "v": 1.1525615690516957, "accelerator_pedal_position": 0.27585716749713174, "brake_pedal_position": 0.0, "acceleration": 0.20319523669993944, "steering_wheel_angle": 9.256360511763956, "front_wheel_angle": 0.4949713367331617, "heading_rate": 0.2430243032681532, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141198.1118522} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2799332898087688, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.75068488629775, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1595948724851937, "gear": 1, "accelerator_pedal_position": 0.28339512730103633, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.143089924852177, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141198.1118522} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.71996307373047, "x": 44.32090337309049, "y": 6.983951557256278, "z": null, "yaw": 4.061444180070348, "pitch": null, "roll": null}, "v": 1.1525615690516957, "accelerator_pedal_position": 0.27585716749713174, "brake_pedal_position": 0.0, "acceleration": 0.20319523669993944, "steering_wheel_angle": 9.256360511763956, "front_wheel_angle": 0.4949713367331617, "heading_rate": 0.2430243032681532, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141198.1318521} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2799332898087688, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.75068488629775, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1641563363423022, "gear": 1, "accelerator_pedal_position": 0.2799332898087688, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.06795696187314, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141198.1318521} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.71996307373047, "x": 44.32090337309049, "y": 6.983951557256278, "z": null, "yaw": 4.061444180070348, "pitch": null, "roll": null}, "v": 1.1525615690516957, "accelerator_pedal_position": 0.27585716749713174, "brake_pedal_position": 0.0, "acceleration": 0.20319523669993944, "steering_wheel_angle": 9.256360511763956, "front_wheel_angle": 0.4949713367331617, "heading_rate": 0.2430243032681532, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141198.1518521} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2799332898087688, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.75068488629775, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1687111191623607, "gear": 1, "accelerator_pedal_position": 0.2799332898087688, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.99254118458933, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141198.1518521} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.71996307373047, "x": 44.32090337309049, "y": 6.983951557256278, "z": null, "yaw": 4.061444180070348, "pitch": null, "roll": null}, "v": 1.1525615690516957, "accelerator_pedal_position": 0.27585716749713174, "brake_pedal_position": 0.0, "acceleration": 0.20319523669993944, "steering_wheel_angle": 9.256360511763956, "front_wheel_angle": 0.4949713367331617, "heading_rate": 0.2430243032681532, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141198.171852} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2799332898087688, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.75068488629775, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.173259222435504, "gear": 1, "accelerator_pedal_position": 0.2799332898087688, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.916842593000741, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141198.171852} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141198.191852, "x": 48.24437964500018, "y": 11.881288437446575, "z": null, "yaw": 4.083978733952438, "pitch": null, "roll": null}, "v": 1.1778006476861658, "accelerator_pedal_position": 0.2799332898087688, "brake_pedal_position": 0.0, "acceleration": 0.22682088526359717, "steering_wheel_angle": 8.84086118710738, "front_wheel_angle": 0.4686573148759764, "heading_rate": 0.23292751969948497, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141198.191852} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2901266345458958, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.235736976865799, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1778006476861658, "gear": 1, "accelerator_pedal_position": 0.2799332898087688, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.84086118710738, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141198.191852} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.829962968826294, "x": 44.24437964500018, "y": 6.881288437446575, "z": null, "yaw": 4.083978733952438, "pitch": null, "roll": null}, "v": 1.1778006476861658, "accelerator_pedal_position": 0.2799332898087688, "brake_pedal_position": 0.0, "acceleration": 0.22682088526359717, "steering_wheel_angle": 8.84086118710738, "front_wheel_angle": 0.4686573148759764, "heading_rate": 0.23292751969948497, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141198.211852} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.285413619717408, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.235736976865799, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.183609095621885, "gear": 1, "accelerator_pedal_position": 0.2901266345458958, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.766278360498385, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141198.211852} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.829962968826294, "x": 44.24437964500018, "y": 6.881288437446575, "z": null, "yaw": 4.083978733952438, "pitch": null, "roll": null}, "v": 1.1778006476861658, "accelerator_pedal_position": 0.2799332898087688, "brake_pedal_position": 0.0, "acceleration": 0.22682088526359717, "steering_wheel_angle": 8.84086118710738, "front_wheel_angle": 0.4686573148759764, "heading_rate": 0.23292751969948497, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141198.231852} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.285413619717408, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.235736976865799, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1888200819820676, "gear": 1, "accelerator_pedal_position": 0.285413619717408, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.691425030429032, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141198.231852} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.829962968826294, "x": 44.24437964500018, "y": 6.881288437446575, "z": null, "yaw": 4.083978733952438, "pitch": null, "roll": null}, "v": 1.1778006476861658, "accelerator_pedal_position": 0.2799332898087688, "brake_pedal_position": 0.0, "acceleration": 0.22682088526359717, "steering_wheel_angle": 8.84086118710738, "front_wheel_angle": 0.4686573148759764, "heading_rate": 0.23292751969948497, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141198.251852} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.285413619717408, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.235736976865799, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1940233849365496, "gear": 1, "accelerator_pedal_position": 0.285413619717408, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.616301196899329, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141198.251852} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.829962968826294, "x": 44.24437964500018, "y": 6.881288437446575, "z": null, "yaw": 4.083978733952438, "pitch": null, "roll": null}, "v": 1.1778006476861658, "accelerator_pedal_position": 0.2799332898087688, "brake_pedal_position": 0.0, "acceleration": 0.22682088526359717, "steering_wheel_angle": 8.84086118710738, "front_wheel_angle": 0.4686573148759764, "heading_rate": 0.23292751969948497, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141198.271852} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.285413619717408, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.235736976865799, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.19921900498848, "gear": 1, "accelerator_pedal_position": 0.285413619717408, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.54090685990927, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141198.271852} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.829962968826294, "x": 44.24437964500018, "y": 6.881288437446575, "z": null, "yaw": 4.083978733952438, "pitch": null, "roll": null}, "v": 1.1778006476861658, "accelerator_pedal_position": 0.2799332898087688, "brake_pedal_position": 0.0, "acceleration": 0.22682088526359717, "steering_wheel_angle": 8.84086118710738, "front_wheel_angle": 0.4686573148759764, "heading_rate": 0.23292751969948497, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141198.291852} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.285413619717408, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.235736976865799, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2044069426882025, "gear": 1, "accelerator_pedal_position": 0.285413619717408, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.46524201945886, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141198.291852} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141198.301852, "x": 48.16838242223861, "y": 11.774531729058172, "z": null, "yaw": 4.105108182956409, "pitch": null, "roll": null}, "v": 1.2069980308408368, "accelerator_pedal_position": 0.285413619717408, "brake_pedal_position": 0.0, "acceleration": 0.25891677922722134, "steering_wheel_angle": 8.42730816043602, "front_wheel_angle": 0.44299131741887415, "heading_rate": 0.2236906760964291, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141198.311852} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29542247165911906, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.386758166863227, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.209587198633109, "gear": 1, "accelerator_pedal_position": 0.285413619717408, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.389306675548095, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141198.311852} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.93996286392212, "x": 44.16838242223861, "y": 6.774531729058172, "z": null, "yaw": 4.105108182956409, "pitch": null, "roll": null}, "v": 1.2069980308408368, "accelerator_pedal_position": 0.285413619717408, "brake_pedal_position": 0.0, "acceleration": 0.25891677922722134, "steering_wheel_angle": 8.42730816043602, "front_wheel_angle": 0.44299131741887415, "heading_rate": 0.2236906760964291, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141198.331852} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2908206288520824, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.386758166863227, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2160104154885232, "gear": 1, "accelerator_pedal_position": 0.29542247165911906, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.31570087972197, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141198.331852} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.93996286392212, "x": 44.16838242223861, "y": 6.774531729058172, "z": null, "yaw": 4.105108182956409, "pitch": null, "roll": null}, "v": 1.2069980308408368, "accelerator_pedal_position": 0.285413619717408, "brake_pedal_position": 0.0, "acceleration": 0.25891677922722134, "steering_wheel_angle": 8.42730816043602, "front_wheel_angle": 0.44299131741887415, "heading_rate": 0.2236906760964291, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141198.351852} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2908206288520824, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.386758166863227, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2218490761013199, "gear": 1, "accelerator_pedal_position": 0.2908206288520824, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.241842693534167, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141198.351852} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.93996286392212, "x": 44.16838242223861, "y": 6.774531729058172, "z": null, "yaw": 4.105108182956409, "pitch": null, "roll": null}, "v": 1.2069980308408368, "accelerator_pedal_position": 0.285413619717408, "brake_pedal_position": 0.0, "acceleration": 0.25891677922722134, "steering_wheel_angle": 8.42730816043602, "front_wheel_angle": 0.44299131741887415, "heading_rate": 0.2236906760964291, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141198.371852} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2908206288520824, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.386758166863227, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2276790511115212, "gear": 1, "accelerator_pedal_position": 0.2908206288520824, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.16773211698468, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141198.371852} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.93996286392212, "x": 44.16838242223861, "y": 6.774531729058172, "z": null, "yaw": 4.105108182956409, "pitch": null, "roll": null}, "v": 1.2069980308408368, "accelerator_pedal_position": 0.285413619717408, "brake_pedal_position": 0.0, "acceleration": 0.25891677922722134, "steering_wheel_angle": 8.42730816043602, "front_wheel_angle": 0.44299131741887415, "heading_rate": 0.2236906760964291, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141198.391852} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2908206288520824, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.386758166863227, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2335003398494668, "gear": 1, "accelerator_pedal_position": 0.2908206288520824, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.093369150073512, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141198.391852} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141198.411852, "x": 48.092707877535936, "y": 11.663474239280934, "z": null, "yaw": 4.124901657168187, "pitch": null, "roll": null}, "v": 1.2393129417072166, "accelerator_pedal_position": 0.2908206288520824, "brake_pedal_position": 0.0, "acceleration": 0.290304317565324, "steering_wheel_angle": 8.018753792800666, "front_wheel_angle": 0.41812004193153784, "heading_rate": 0.2150980406752381, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141198.411852} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3047897994690868, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.61373813498016, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2393129417072166, "gear": 1, "accelerator_pedal_position": 0.2908206288520824, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.018753792800666, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141198.411852} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.049962759017944, "x": 44.092707877535936, "y": 6.663474239280934, "z": null, "yaw": 4.124901657168187, "pitch": null, "roll": null}, "v": 1.2393129417072166, "accelerator_pedal_position": 0.2908206288520824, "brake_pedal_position": 0.0, "acceleration": 0.290304317565324, "steering_wheel_angle": 8.018753792800666, "front_wheel_angle": 0.41812004193153784, "heading_rate": 0.2150980406752381, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141198.4318519} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2983211449917939, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.61373813498016, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.246862348943604, "gear": 1, "accelerator_pedal_position": 0.3047897994690868, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.946072617824263, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141198.4318519} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.049962759017944, "x": 44.092707877535936, "y": 6.663474239280934, "z": null, "yaw": 4.124901657168187, "pitch": null, "roll": null}, "v": 1.2393129417072166, "accelerator_pedal_position": 0.2908206288520824, "brake_pedal_position": 0.0, "acceleration": 0.290304317565324, "steering_wheel_angle": 8.018753792800666, "front_wheel_angle": 0.41812004193153784, "heading_rate": 0.2150980406752381, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141198.4518518} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2983211449917939, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.61373813498016, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.253592172924093, "gear": 1, "accelerator_pedal_position": 0.2983211449917939, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.873153556345899, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141198.4518518} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.049962759017944, "x": 44.092707877535936, "y": 6.663474239280934, "z": null, "yaw": 4.124901657168187, "pitch": null, "roll": null}, "v": 1.2393129417072166, "accelerator_pedal_position": 0.2908206288520824, "brake_pedal_position": 0.0, "acceleration": 0.290304317565324, "steering_wheel_angle": 8.018753792800666, "front_wheel_angle": 0.41812004193153784, "heading_rate": 0.2150980406752381, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141198.4718518} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2983211449917939, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.61373813498016, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2603119008188675, "gear": 1, "accelerator_pedal_position": 0.2983211449917939, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.799996608365583, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141198.4718518} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.049962759017944, "x": 44.092707877535936, "y": 6.663474239280934, "z": null, "yaw": 4.124901657168187, "pitch": null, "roll": null}, "v": 1.2393129417072166, "accelerator_pedal_position": 0.2908206288520824, "brake_pedal_position": 0.0, "acceleration": 0.290304317565324, "steering_wheel_angle": 8.018753792800666, "front_wheel_angle": 0.41812004193153784, "heading_rate": 0.2150980406752381, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141198.4918518} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2983211449917939, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.61373813498016, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2670215297189698, "gear": 1, "accelerator_pedal_position": 0.2983211449917939, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.726601773883309, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141198.4918518} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.049962759017944, "x": 44.092707877535936, "y": 6.663474239280934, "z": null, "yaw": 4.124901657168187, "pitch": null, "roll": null}, "v": 1.2393129417072166, "accelerator_pedal_position": 0.2908206288520824, "brake_pedal_position": 0.0, "acceleration": 0.290304317565324, "steering_wheel_angle": 8.018753792800666, "front_wheel_angle": 0.41812004193153784, "heading_rate": 0.2150980406752381, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141198.5118518} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2983211449917939, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.61373813498016, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2737210568011825, "gear": 1, "accelerator_pedal_position": 0.2983211449917939, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.6529690528990795, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141198.5118518} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141198.5218518, "x": 48.0170693039257, "y": 11.547751761805358, "z": null, "yaw": 4.143434364088499, "pitch": null, "roll": null}, "v": 1.2770670313017152, "accelerator_pedal_position": 0.2983211449917939, "brake_pedal_position": 0.0, "acceleration": 0.33434480260924837, "steering_wheel_angle": 7.616063484968729, "front_wheel_angle": 0.39405112021144245, "heading_rate": 0.207422854777392, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141198.5318518} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3155018576893649, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.832398371030336, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2804104793278077, "gear": 1, "accelerator_pedal_position": 0.2983211449917939, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.579098445412892, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141198.5318518} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.15996265411377, "x": 44.0170693039257, "y": 6.547751761805358, "z": null, "yaw": 4.143434364088499, "pitch": null, "roll": null}, "v": 1.2770670313017152, "accelerator_pedal_position": 0.2983211449917939, "brake_pedal_position": 0.0, "acceleration": 0.33434480260924837, "steering_wheel_angle": 7.616063484968729, "front_wheel_angle": 0.39405112021144245, "heading_rate": 0.207422854777392, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141198.5518517} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.30753677077479535, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.832398371030336, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2892365710240152, "gear": 1, "accelerator_pedal_position": 0.3155018576893649, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.507056004910667, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141198.5518517} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.15996265411377, "x": 44.0170693039257, "y": 6.547751761805358, "z": null, "yaw": 4.143434364088499, "pitch": null, "roll": null}, "v": 1.2770670313017152, "accelerator_pedal_position": 0.2983211449917939, "brake_pedal_position": 0.0, "acceleration": 0.33434480260924837, "steering_wheel_angle": 7.616063484968729, "front_wheel_angle": 0.39405112021144245, "heading_rate": 0.207422854777392, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141198.5718517} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.30753677077479535, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.832398371030336, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2970540397363524, "gear": 1, "accelerator_pedal_position": 0.30753677077479535, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.434788736891963, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141198.5718517} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.15996265411377, "x": 44.0170693039257, "y": 6.547751761805358, "z": null, "yaw": 4.143434364088499, "pitch": null, "roll": null}, "v": 1.2770670313017152, "accelerator_pedal_position": 0.2983211449917939, "brake_pedal_position": 0.0, "acceleration": 0.33434480260924837, "steering_wheel_angle": 7.616063484968729, "front_wheel_angle": 0.39405112021144245, "heading_rate": 0.207422854777392, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141198.5918517} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.30753677077479535, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.832398371030336, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3048596457255566, "gear": 1, "accelerator_pedal_position": 0.30753677077479535, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.362296641356775, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141198.5918517} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.15996265411377, "x": 44.0170693039257, "y": 6.547751761805358, "z": null, "yaw": 4.143434364088499, "pitch": null, "roll": null}, "v": 1.2770670313017152, "accelerator_pedal_position": 0.2983211449917939, "brake_pedal_position": 0.0, "acceleration": 0.33434480260924837, "steering_wheel_angle": 7.616063484968729, "front_wheel_angle": 0.39405112021144245, "heading_rate": 0.207422854777392, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141198.6118517} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.30753677077479535, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.832398371030336, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3126533826311486, "gear": 1, "accelerator_pedal_position": 0.30753677077479535, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.289579718305109, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141198.6118517} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141198.6318517, "x": 47.94118121402655, "y": 11.426958623482234, "z": null, "yaw": 4.160765169583577, "pitch": null, "roll": null}, "v": 1.3204352442133958, "accelerator_pedal_position": 0.30753677077479535, "brake_pedal_position": 0.0, "acceleration": 0.38864756279019214, "steering_wheel_angle": 7.216637967736961, "front_wheel_angle": 0.3705912589634455, "heading_rate": 0.20040881389964577, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141198.6318517} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.32959863386925115, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.9560775513942925, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3204352442133958, "gear": 1, "accelerator_pedal_position": 0.30753677077479535, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.216637967736961, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141198.6318517} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.269962549209595, "x": 43.94118121402655, "y": 6.426958623482234, "z": null, "yaw": 4.160765169583577, "pitch": null, "roll": null}, "v": 1.3204352442133958, "accelerator_pedal_position": 0.30753677077479535, "brake_pedal_position": 0.0, "acceleration": 0.38864756279019214, "steering_wheel_angle": 7.216637967736961, "front_wheel_angle": 0.3705912589634455, "heading_rate": 0.20040881389964577, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141198.6518517} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3193440197273827, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.9560775513942925, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3309619024039394, "gear": 1, "accelerator_pedal_position": 0.32959863386925115, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.145628056431741, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141198.6518517} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.269962549209595, "x": 43.94118121402655, "y": 6.426958623482234, "z": null, "yaw": 4.160765169583577, "pitch": null, "roll": null}, "v": 1.3204352442133958, "accelerator_pedal_position": 0.30753677077479535, "brake_pedal_position": 0.0, "acceleration": 0.38864756279019214, "steering_wheel_angle": 7.216637967736961, "front_wheel_angle": 0.3705912589634455, "heading_rate": 0.20040881389964577, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141198.6718516} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3193440197273827, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.9560775513942925, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3401911118884051, "gear": 1, "accelerator_pedal_position": 0.3193440197273827, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.074406357202268, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141198.6718516} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.269962549209595, "x": 43.94118121402655, "y": 6.426958623482234, "z": null, "yaw": 4.160765169583577, "pitch": null, "roll": null}, "v": 1.3204352442133958, "accelerator_pedal_position": 0.30753677077479535, "brake_pedal_position": 0.0, "acceleration": 0.38864756279019214, "steering_wheel_angle": 7.216637967736961, "front_wheel_angle": 0.3705912589634455, "heading_rate": 0.20040881389964577, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141198.6918516} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3193440197273827, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.9560775513942925, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3494061585602832, "gear": 1, "accelerator_pedal_position": 0.3193440197273827, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.0029728700485405, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141198.6918516} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.269962549209595, "x": 43.94118121402655, "y": 6.426958623482234, "z": null, "yaw": 4.160765169583577, "pitch": null, "roll": null}, "v": 1.3204352442133958, "accelerator_pedal_position": 0.30753677077479535, "brake_pedal_position": 0.0, "acceleration": 0.38864756279019214, "steering_wheel_angle": 7.216637967736961, "front_wheel_angle": 0.3705912589634455, "heading_rate": 0.20040881389964577, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141198.7118516} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3193440197273827, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.9560775513942925, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.358607030199547, "gear": 1, "accelerator_pedal_position": 0.3193440197273827, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.931327594970562, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141198.7118516} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.269962549209595, "x": 43.94118121402655, "y": 6.426958623482234, "z": null, "yaw": 4.160765169583577, "pitch": null, "roll": null}, "v": 1.3204352442133958, "accelerator_pedal_position": 0.30753677077479535, "brake_pedal_position": 0.0, "acceleration": 0.38864756279019214, "steering_wheel_angle": 7.216637967736961, "front_wheel_angle": 0.3705912589634455, "heading_rate": 0.20040881389964577, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141198.7318516} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3193440197273827, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.9560775513942925, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3677937147615613, "gear": 1, "accelerator_pedal_position": 0.3193440197273827, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.859470531968325, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141198.7318516} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141198.7418516, "x": 47.86461550613445, "y": 11.30041356442342, "z": null, "yaw": 4.176952686027693, "pitch": null, "roll": null}, "v": 1.3723817331725279, "accelerator_pedal_position": 0.3193440197273827, "brake_pedal_position": 0.0, "acceleration": 0.4584467204220589, "steering_wheel_angle": 6.8234625799956135, "front_wheel_angle": 0.3478809871991353, "heading_rate": 0.1944005448415169, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141198.7518516} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.34411423980096667, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.0901496765544083, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3769662003767484, "gear": 1, "accelerator_pedal_position": 0.3193440197273827, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.787401681041837, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141198.7518516} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.37996244430542, "x": 43.86461550613445, "y": 6.300413564423421, "z": null, "yaw": 4.176952686027693, "pitch": null, "roll": null}, "v": 1.3723817331725279, "accelerator_pedal_position": 0.3193440197273827, "brake_pedal_position": 0.0, "acceleration": 0.4584467204220589, "steering_wheel_angle": 6.8234625799956135, "front_wheel_angle": 0.3478809871991353, "heading_rate": 0.1944005448415169, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141198.7718515} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.33262335961215317, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.0901496765544083, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3892195507850738, "gear": 1, "accelerator_pedal_position": 0.34411423980096667, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.717110109244519, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141198.7718515} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.37996244430542, "x": 43.86461550613445, "y": 6.300413564423421, "z": null, "yaw": 4.176952686027693, "pitch": null, "roll": null}, "v": 1.3723817331725279, "accelerator_pedal_position": 0.3193440197273827, "brake_pedal_position": 0.0, "acceleration": 0.4584467204220589, "steering_wheel_angle": 6.8234625799956135, "front_wheel_angle": 0.3478809871991353, "heading_rate": 0.1944005448415169, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141198.7918515} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.33262335961215317, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.0901496765544083, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.400018060663555, "gear": 1, "accelerator_pedal_position": 0.33262335961215317, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.646618229256891, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141198.7918515} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.37996244430542, "x": 43.86461550613445, "y": 6.300413564423421, "z": null, "yaw": 4.176952686027693, "pitch": null, "roll": null}, "v": 1.3723817331725279, "accelerator_pedal_position": 0.3193440197273827, "brake_pedal_position": 0.0, "acceleration": 0.4584467204220589, "steering_wheel_angle": 6.8234625799956135, "front_wheel_angle": 0.3478809871991353, "heading_rate": 0.1944005448415169, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141198.8118515} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.33262335961215317, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.0901496765544083, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4107997430147143, "gear": 1, "accelerator_pedal_position": 0.33262335961215317, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.575926041078952, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141198.8118515} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.37996244430542, "x": 43.86461550613445, "y": 6.300413564423421, "z": null, "yaw": 4.176952686027693, "pitch": null, "roll": null}, "v": 1.3723817331725279, "accelerator_pedal_position": 0.3193440197273827, "brake_pedal_position": 0.0, "acceleration": 0.4584467204220589, "steering_wheel_angle": 6.8234625799956135, "front_wheel_angle": 0.3478809871991353, "heading_rate": 0.1944005448415169, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141198.8318515} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.33262335961215317, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.0901496765544083, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4215645775815142, "gear": 1, "accelerator_pedal_position": 0.33262335961215317, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.505033544710702, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141198.8318515} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141198.8518515, "x": 47.786986478032574, "y": 11.16744489206888, "z": null, "yaw": 4.192046253744036, "pitch": null, "roll": null}, "v": 1.4323125443563123, "accelerator_pedal_position": 0.33262335961215317, "brake_pedal_position": 0.0, "acceleration": 0.5367651781109369, "steering_wheel_angle": 6.433940740152141, "front_wheel_angle": 0.3257380493594217, "heading_rate": 0.18898122141025225, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141198.8518515} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.38186299802388385, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.752113569770735, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4323125443563123, "gear": 1, "accelerator_pedal_position": 0.33262335961215317, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.433940740152141, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141198.8518515} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.489962339401245, "x": 43.786986478032574, "y": 6.167444892068881, "z": null, "yaw": 4.192046253744036, "pitch": null, "roll": null}, "v": 1.4323125443563123, "accelerator_pedal_position": 0.33262335961215317, "brake_pedal_position": 0.0, "acceleration": 0.5367651781109369, "steering_wheel_angle": 6.433940740152141, "front_wheel_angle": 0.3257380493594217, "heading_rate": 0.18898122141025225, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141198.8718514} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.35877191422355453, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.752113569770735, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4491961538104927, "gear": 1, "accelerator_pedal_position": 0.38186299802388385, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.365461688254533, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141198.8718514} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.489962339401245, "x": 43.786986478032574, "y": 6.167444892068881, "z": null, "yaw": 4.192046253744036, "pitch": null, "roll": null}, "v": 1.4323125443563123, "accelerator_pedal_position": 0.33262335961215317, "brake_pedal_position": 0.0, "acceleration": 0.5367651781109369, "steering_wheel_angle": 6.433940740152141, "front_wheel_angle": 0.3257380493594217, "heading_rate": 0.18898122141025225, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141198.8918514} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.35877191422355453, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.752113569770735, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4631678882582508, "gear": 1, "accelerator_pedal_position": 0.35877191422355453, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.296797808626215, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141198.8918514} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.489962339401245, "x": 43.786986478032574, "y": 6.167444892068881, "z": null, "yaw": 4.192046253744036, "pitch": null, "roll": null}, "v": 1.4323125443563123, "accelerator_pedal_position": 0.33262335961215317, "brake_pedal_position": 0.0, "acceleration": 0.5367651781109369, "steering_wheel_angle": 6.433940740152141, "front_wheel_angle": 0.3257380493594217, "heading_rate": 0.18898122141025225, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141198.9118514} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.35877191422355453, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.752113569770735, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4771175020654637, "gear": 1, "accelerator_pedal_position": 0.35877191422355453, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.2279491012671855, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141198.9118514} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.489962339401245, "x": 43.786986478032574, "y": 6.167444892068881, "z": null, "yaw": 4.192046253744036, "pitch": null, "roll": null}, "v": 1.4323125443563123, "accelerator_pedal_position": 0.33262335961215317, "brake_pedal_position": 0.0, "acceleration": 0.5367651781109369, "steering_wheel_angle": 6.433940740152141, "front_wheel_angle": 0.3257380493594217, "heading_rate": 0.18898122141025225, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141198.9318514} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.35877191422355453, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.752113569770735, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4910449524487064, "gear": 1, "accelerator_pedal_position": 0.35877191422355453, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.1589155661774475, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141198.9318514} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.489962339401245, "x": 43.786986478032574, "y": 6.167444892068881, "z": null, "yaw": 4.192046253744036, "pitch": null, "roll": null}, "v": 1.4323125443563123, "accelerator_pedal_position": 0.33262335961215317, "brake_pedal_position": 0.0, "acceleration": 0.5367651781109369, "steering_wheel_angle": 6.433940740152141, "front_wheel_angle": 0.3257380493594217, "heading_rate": 0.18898122141025225, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141198.9518514} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.35877191422355453, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.752113569770735, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.50495019706306, "gear": 1, "accelerator_pedal_position": 0.35877191422355453, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.089697203357001, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141198.9518514} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141198.9618514, "x": 47.707526881451564, "y": 11.026651398397647, "z": null, "yaw": 4.206100221623138, "pitch": null, "roll": null}, "v": 1.5118944790939368, "accelerator_pedal_position": 0.35877191422355453, "brake_pedal_position": 0.0, "acceleration": 0.6938714907833716, "steering_wheel_angle": 6.055018711547761, "front_wheel_angle": 0.3045224502664368, "heading_rate": 0.18561955153952509, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141198.9718513} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4077524756982151, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.47921821403475584, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5188331940017705, "gear": 1, "accelerator_pedal_position": 0.35877191422355453, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.020294012805843, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141198.9718513} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.59996223449707, "x": 43.707526881451564, "y": 6.026651398397647, "z": null, "yaw": 4.206100221623138, "pitch": null, "roll": null}, "v": 1.5118944790939368, "accelerator_pedal_position": 0.35877191422355453, "brake_pedal_position": 0.0, "acceleration": 0.6938714907833716, "steering_wheel_angle": 6.055018711547761, "front_wheel_angle": 0.3045224502664368, "heading_rate": 0.18561955153952509, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141198.9918513} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.388365349908773, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.47921821403475584, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.538814006239382, "gear": 1, "accelerator_pedal_position": 0.4077524756982151, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.953134251346531, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141198.9918513} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.59996223449707, "x": 43.707526881451564, "y": 6.026651398397647, "z": null, "yaw": 4.206100221623138, "pitch": null, "roll": null}, "v": 1.5118944790939368, "accelerator_pedal_position": 0.35877191422355453, "brake_pedal_position": 0.0, "acceleration": 0.6938714907833716, "steering_wheel_angle": 6.055018711547761, "front_wheel_angle": 0.3045224502664368, "heading_rate": 0.18561955153952509, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141199.0118513} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.388365349908773, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.47921821403475584, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5563401822175598, "gear": 1, "accelerator_pedal_position": 0.388365349908773, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.885802320202629, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141199.0118513} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.59996223449707, "x": 43.707526881451564, "y": 6.026651398397647, "z": null, "yaw": 4.206100221623138, "pitch": null, "roll": null}, "v": 1.5118944790939368, "accelerator_pedal_position": 0.35877191422355453, "brake_pedal_position": 0.0, "acceleration": 0.6938714907833716, "steering_wheel_angle": 6.055018711547761, "front_wheel_angle": 0.3045224502664368, "heading_rate": 0.18561955153952509, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141199.0318513} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.388365349908773, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.47921821403475584, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5738379635821442, "gear": 1, "accelerator_pedal_position": 0.388365349908773, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.818298219374138, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141199.0318513} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.59996223449707, "x": 43.707526881451564, "y": 6.026651398397647, "z": null, "yaw": 4.206100221623138, "pitch": null, "roll": null}, "v": 1.5118944790939368, "accelerator_pedal_position": 0.35877191422355453, "brake_pedal_position": 0.0, "acceleration": 0.6938714907833716, "steering_wheel_angle": 6.055018711547761, "front_wheel_angle": 0.3045224502664368, "heading_rate": 0.18561955153952509, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141199.0518513} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.388365349908773, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.47921821403475584, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.591307273916898, "gear": 1, "accelerator_pedal_position": 0.388365349908773, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.750621948861061, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141199.0518513} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141199.0718513, "x": 47.62544270533802, "y": 10.876469647373165, "z": null, "yaw": 4.2191646964126175, "pitch": null, "roll": null}, "v": 1.6087480375268493, "accelerator_pedal_position": 0.388365349908773, "brake_pedal_position": 0.0, "acceleration": 0.8709653325710239, "steering_wheel_angle": 5.682773508663394, "front_wheel_angle": 0.283979001587694, "heading_rate": 0.18341443116261985, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141199.0718513} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3142734196629349, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.092787195618109, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6087480375268493, "gear": 1, "accelerator_pedal_position": 0.388365349908773, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.682773508663394, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141199.0718513} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.709962129592896, "x": 43.62544270533802, "y": 5.876469647373165, "z": null, "yaw": 4.2191646964126175, "pitch": null, "roll": null}, "v": 1.6087480375268493, "accelerator_pedal_position": 0.388365349908773, "brake_pedal_position": 0.0, "acceleration": 0.8709653325710239, "steering_wheel_angle": 5.682773508663394, "front_wheel_angle": 0.283979001587694, "heading_rate": 0.18341443116261985, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141199.0918512} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3501545572276223, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.092787195618109, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6169024993930017, "gear": 1, "accelerator_pedal_position": 0.3142734196629349, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.613677034062857, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141199.0918512} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.709962129592896, "x": 43.62544270533802, "y": 5.876469647373165, "z": null, "yaw": 4.2191646964126175, "pitch": null, "roll": null}, "v": 1.6087480375268493, "accelerator_pedal_position": 0.388365349908773, "brake_pedal_position": 0.0, "acceleration": 0.8709653325710239, "steering_wheel_angle": 5.682773508663394, "front_wheel_angle": 0.283979001587694, "heading_rate": 0.18341443116261985, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141199.1118512} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3501545572276223, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.092787195618109, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6295268383614456, "gear": 1, "accelerator_pedal_position": 0.3501545572276223, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.544402907480878, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141199.1118512} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.709962129592896, "x": 43.62544270533802, "y": 5.876469647373165, "z": null, "yaw": 4.2191646964126175, "pitch": null, "roll": null}, "v": 1.6087480375268493, "accelerator_pedal_position": 0.388365349908773, "brake_pedal_position": 0.0, "acceleration": 0.8709653325710239, "steering_wheel_angle": 5.682773508663394, "front_wheel_angle": 0.283979001587694, "heading_rate": 0.18341443116261985, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141199.1318512} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3501545572276223, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.092787195618109, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6421303488533638, "gear": 1, "accelerator_pedal_position": 0.3501545572276223, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.474951128917457, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141199.1318512} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.709962129592896, "x": 43.62544270533802, "y": 5.876469647373165, "z": null, "yaw": 4.2191646964126175, "pitch": null, "roll": null}, "v": 1.6087480375268493, "accelerator_pedal_position": 0.388365349908773, "brake_pedal_position": 0.0, "acceleration": 0.8709653325710239, "steering_wheel_angle": 5.682773508663394, "front_wheel_angle": 0.283979001587694, "heading_rate": 0.18341443116261985, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141199.1518512} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3501545572276223, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.092787195618109, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6547130017198726, "gear": 1, "accelerator_pedal_position": 0.3501545572276223, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.405321698372597, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141199.1518512} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.709962129592896, "x": 43.62544270533802, "y": 5.876469647373165, "z": null, "yaw": 4.2191646964126175, "pitch": null, "roll": null}, "v": 1.6087480375268493, "accelerator_pedal_position": 0.388365349908773, "brake_pedal_position": 0.0, "acceleration": 0.8709653325710239, "steering_wheel_angle": 5.682773508663394, "front_wheel_angle": 0.283979001587694, "heading_rate": 0.18341443116261985, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141199.1718512} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3501545572276223, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.092787195618109, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6672747681754103, "gear": 1, "accelerator_pedal_position": 0.3501545572276223, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.335514615846296, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141199.1718512} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141199.1818511, "x": 47.54110870894473, "y": 10.717442882123281, "z": null, "yaw": 4.23126668615399, "pitch": null, "roll": null}, "v": 1.6735478101027896, "accelerator_pedal_position": 0.3501545572276223, "brake_pedal_position": 0.0, "acceleration": 0.6267809694405013, "steering_wheel_angle": 5.300544455090104, "front_wheel_angle": 0.2631793163780685, "heading_rate": 0.17613354825929514, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141199.1918511} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23774538013897914, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.4124222638125548, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6798156197971947, "gear": 1, "accelerator_pedal_position": 0.3501545572276223, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.265529881338553, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141199.1918511} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.81996202468872, "x": 43.54110870894473, "y": 5.717442882123281, "z": null, "yaw": 4.23126668615399, "pitch": null, "roll": null}, "v": 1.6735478101027896, "accelerator_pedal_position": 0.3501545572276223, "brake_pedal_position": 0.0, "acceleration": 0.6267809694405013, "steering_wheel_angle": 5.300544455090104, "front_wheel_angle": 0.2631793163780685, "heading_rate": 0.17613354825929514, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141199.2118511} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2916824939916745, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.4124222638125548, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6782902583727817, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.19264339749084, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141199.2118511} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.81996202468872, "x": 43.54110870894473, "y": 5.717442882123281, "z": null, "yaw": 4.23126668615399, "pitch": null, "roll": null}, "v": 1.6735478101027896, "accelerator_pedal_position": 0.3501545572276223, "brake_pedal_position": 0.0, "acceleration": 0.6267809694405013, "steering_wheel_angle": 5.300544455090104, "front_wheel_angle": 0.2631793163780685, "heading_rate": 0.17613354825929514, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141199.231851} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2916824939916745, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.4124222638125548, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6835067670241333, "gear": 1, "accelerator_pedal_position": 0.2916824939916745, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.1195652177922595, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141199.231851} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.81996202468872, "x": 43.54110870894473, "y": 5.717442882123281, "z": null, "yaw": 4.23126668615399, "pitch": null, "roll": null}, "v": 1.6735478101027896, "accelerator_pedal_position": 0.3501545572276223, "brake_pedal_position": 0.0, "acceleration": 0.6267809694405013, "steering_wheel_angle": 5.300544455090104, "front_wheel_angle": 0.2631793163780685, "heading_rate": 0.17613354825929514, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141199.251851} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2916824939916745, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.4124222638125548, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6887145527277603, "gear": 1, "accelerator_pedal_position": 0.2916824939916745, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.046295342242817, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141199.251851} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.81996202468872, "x": 43.54110870894473, "y": 5.717442882123281, "z": null, "yaw": 4.23126668615399, "pitch": null, "roll": null}, "v": 1.6735478101027896, "accelerator_pedal_position": 0.3501545572276223, "brake_pedal_position": 0.0, "acceleration": 0.6267809694405013, "steering_wheel_angle": 5.300544455090104, "front_wheel_angle": 0.2631793163780685, "heading_rate": 0.17613354825929514, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141199.271851} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2916824939916745, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.4124222638125548, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6939136192261397, "gear": 1, "accelerator_pedal_position": 0.2916824939916745, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.972833770842509, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141199.271851} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141199.291851, "x": 47.4561969959988, "y": 10.552725080569026, "z": null, "yaw": 4.242395765913909, "pitch": null, "roll": null}, "v": 1.699103970309932, "accelerator_pedal_position": 0.2916824939916745, "brake_pedal_position": 0.0, "acceleration": 0.25919084591323927, "steering_wheel_angle": 4.899180503591334, "front_wheel_angle": 0.24164644951937958, "heading_rate": 0.16358021057423622, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141199.291851} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23939234881473637, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.176839437071222, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.699103970309932, "gear": 1, "accelerator_pedal_position": 0.2916824939916745, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.899180503591334, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141199.291851} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.929961919784546, "x": 43.4561969959988, "y": 5.552725080569026, "z": null, "yaw": 4.242395765913909, "pitch": null, "roll": null}, "v": 1.699103970309932, "accelerator_pedal_position": 0.2916824939916745, "brake_pedal_position": 0.0, "acceleration": 0.25919084591323927, "steering_wheel_angle": 4.899180503591334, "front_wheel_angle": 0.24164644951937958, "heading_rate": 0.16358021057423622, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141199.311851} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26445545738502185, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.176839437071222, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.697752086943684, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.82358206813705, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141199.311851} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.929961919784546, "x": 43.4561969959988, "y": 5.552725080569026, "z": null, "yaw": 4.242395765913909, "pitch": null, "roll": null}, "v": 1.699103970309932, "accelerator_pedal_position": 0.2916824939916745, "brake_pedal_position": 0.0, "acceleration": 0.25919084591323927, "steering_wheel_angle": 4.899180503591334, "front_wheel_angle": 0.24164644951937958, "heading_rate": 0.16358021057423622, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141199.331851} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26445545738502185, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.176839437071222, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.699534046184194, "gear": 1, "accelerator_pedal_position": 0.26445545738502185, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.74778273735419, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141199.331851} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.929961919784546, "x": 43.4561969959988, "y": 5.552725080569026, "z": null, "yaw": 4.242395765913909, "pitch": null, "roll": null}, "v": 1.699103970309932, "accelerator_pedal_position": 0.2916824939916745, "brake_pedal_position": 0.0, "acceleration": 0.25919084591323927, "steering_wheel_angle": 4.899180503591334, "front_wheel_angle": 0.24164644951937958, "heading_rate": 0.16358021057423622, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141199.351851} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26445545738502185, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.176839437071222, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.70131301363978, "gear": 1, "accelerator_pedal_position": 0.26445545738502185, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.671782511242757, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141199.351851} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.929961919784546, "x": 43.4561969959988, "y": 5.552725080569026, "z": null, "yaw": 4.242395765913909, "pitch": null, "roll": null}, "v": 1.699103970309932, "accelerator_pedal_position": 0.2916824939916745, "brake_pedal_position": 0.0, "acceleration": 0.25919084591323927, "steering_wheel_angle": 4.899180503591334, "front_wheel_angle": 0.24164644951937958, "heading_rate": 0.16358021057423622, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141199.371851} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26445545738502185, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.176839437071222, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.703088993068081, "gear": 1, "accelerator_pedal_position": 0.26445545738502185, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.595581389802749, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141199.371851} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.929961919784546, "x": 43.4561969959988, "y": 5.552725080569026, "z": null, "yaw": 4.242395765913909, "pitch": null, "roll": null}, "v": 1.699103970309932, "accelerator_pedal_position": 0.2916824939916745, "brake_pedal_position": 0.0, "acceleration": 0.25919084591323927, "steering_wheel_angle": 4.899180503591334, "front_wheel_angle": 0.24164644951937958, "heading_rate": 0.16358021057423622, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141199.391851} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26445545738502185, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.176839437071222, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7048619882268, "gear": 1, "accelerator_pedal_position": 0.26445545738502185, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.5191793730341665, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141199.391851} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141199.401851, "x": 47.372250234104555, "y": 10.385523014662864, "z": null, "yaw": 4.252529255029305, "pitch": null, "roll": null}, "v": 1.7057473678793602, "accelerator_pedal_position": 0.26445545738502185, "brake_pedal_position": 0.0, "acceleration": 0.08846349943214482, "steering_wheel_angle": 4.480903028901659, "front_wheel_angle": 0.21952789949754456, "heading_rate": 0.14866905309000827, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141199.411851} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.11196005224075, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7066320028736817, "gear": 1, "accelerator_pedal_position": 0.26445545738502185, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.442576460937009, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141199.411851} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.03996181488037, "x": 43.372250234104555, "y": 5.385523014662864, "z": null, "yaw": 4.252529255029305, "pitch": null, "roll": null}, "v": 1.7057473678793602, "accelerator_pedal_position": 0.26445545738502185, "brake_pedal_position": 0.0, "acceleration": 0.08846349943214482, "steering_wheel_angle": 4.480903028901659, "front_wheel_angle": 0.21952789949754456, "heading_rate": 0.14866905309000827, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141199.431851} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2347387290810606, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.11196005224075, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7003454969375282, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.363410641681593, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141199.431851} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.03996181488037, "x": 43.372250234104555, "y": 5.385523014662864, "z": null, "yaw": 4.252529255029305, "pitch": null, "roll": null}, "v": 1.7057473678793602, "accelerator_pedal_position": 0.26445545738502185, "brake_pedal_position": 0.0, "acceleration": 0.08846349943214482, "steering_wheel_angle": 4.480903028901659, "front_wheel_angle": 0.21952789949754456, "heading_rate": 0.14866905309000827, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141199.451851} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2347387290810606, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.11196005224075, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6984100708076189, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.284031397632118, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141199.451851} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.03996181488037, "x": 43.372250234104555, "y": 5.385523014662864, "z": null, "yaw": 4.252529255029305, "pitch": null, "roll": null}, "v": 1.7057473678793602, "accelerator_pedal_position": 0.26445545738502185, "brake_pedal_position": 0.0, "acceleration": 0.08846349943214482, "steering_wheel_angle": 4.480903028901659, "front_wheel_angle": 0.21952789949754456, "heading_rate": 0.14866905309000827, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141199.4718509} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2347387290810606, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.11196005224075, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6964778939725587, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.204438728788585, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141199.4718509} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.03996181488037, "x": 43.372250234104555, "y": 5.385523014662864, "z": null, "yaw": 4.252529255029305, "pitch": null, "roll": null}, "v": 1.7057473678793602, "accelerator_pedal_position": 0.26445545738502185, "brake_pedal_position": 0.0, "acceleration": 0.08846349943214482, "steering_wheel_angle": 4.480903028901659, "front_wheel_angle": 0.21952789949754456, "heading_rate": 0.14866905309000827, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141199.4918509} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2347387290810606, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.11196005224075, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6945489594845642, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.124632635150992, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141199.4918509} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141199.5118508, "x": 47.29000162341231, "y": 10.21767666266868, "z": null, "yaw": 4.261653157245606, "pitch": null, "roll": null}, "v": 1.6926232604150266, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3132808980377313, "steering_wheel_angle": 4.044613116719342, "front_wheel_angle": 0.19679179077394804, "heading_rate": 0.13182107365400877, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141199.5118508} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2779892875231982, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.894095118000306, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6926232604150266, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.044613116719342, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141199.5118508} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.149961709976196, "x": 43.29000162341231, "y": 5.21767666266868, "z": null, "yaw": 4.261653157245606, "pitch": null, "roll": null}, "v": 1.6926232604150266, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3132808980377313, "steering_wheel_angle": 4.044613116719342, "front_wheel_angle": 0.19679179077394804, "heading_rate": 0.13182107365400877, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141199.5318508} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25730979517766006, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.894095118000306, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6961048427826808, "gear": 1, "accelerator_pedal_position": 0.2779892875231982, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.9649575732116595, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141199.5318508} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.149961709976196, "x": 43.29000162341231, "y": 5.21767666266868, "z": null, "yaw": 4.261653157245606, "pitch": null, "roll": null}, "v": 1.6926232604150266, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3132808980377313, "steering_wheel_angle": 4.044613116719342, "front_wheel_angle": 0.19679179077394804, "heading_rate": 0.13182107365400877, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141199.5518508} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25730979517766006, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.894095118000306, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.696996733585816, "gear": 1, "accelerator_pedal_position": 0.25730979517766006, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.8850916616756432, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141199.5518508} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.149961709976196, "x": 43.29000162341231, "y": 5.21767666266868, "z": null, "yaw": 4.261653157245606, "pitch": null, "roll": null}, "v": 1.6926232604150266, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3132808980377313, "steering_wheel_angle": 4.044613116719342, "front_wheel_angle": 0.19679179077394804, "heading_rate": 0.13182107365400877, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141199.5718508} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25730979517766006, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.894095118000306, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6978871277917684, "gear": 1, "accelerator_pedal_position": 0.25730979517766006, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.8050153821112938, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141199.5718508} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.149961709976196, "x": 43.29000162341231, "y": 5.21767666266868, "z": null, "yaw": 4.261653157245606, "pitch": null, "roll": null}, "v": 1.6926232604150266, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3132808980377313, "steering_wheel_angle": 4.044613116719342, "front_wheel_angle": 0.19679179077394804, "heading_rate": 0.13182107365400877, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141199.5918508} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25730979517766006, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.894095118000306, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6987760275948474, "gear": 1, "accelerator_pedal_position": 0.25730979517766006, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.724728734518611, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141199.5918508} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.149961709976196, "x": 43.29000162341231, "y": 5.21767666266868, "z": null, "yaw": 4.261653157245606, "pitch": null, "roll": null}, "v": 1.6926232604150266, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3132808980377313, "steering_wheel_angle": 4.044613116719342, "front_wheel_angle": 0.19679179077394804, "heading_rate": 0.13182107365400877, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141199.6118507} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25730979517766006, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.894095118000306, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.699663435187276, "gear": 1, "accelerator_pedal_position": 0.25730979517766006, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.644231718897595, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141199.6118507} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141199.6218507, "x": 47.20931331412669, "y": 10.04933628726646, "z": null, "yaw": 4.269761567236672, "pitch": null, "roll": null}, "v": 1.7001065800889947, "accelerator_pedal_position": 0.25730979517766006, "brake_pedal_position": 0.0, "acceleration": 0.044277267019306565, "steering_wheel_angle": 3.603904323076461, "front_wheel_angle": 0.17415777560360052, "heading_rate": 0.11684260919065767, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141199.6318507} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2750266983081272, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.9037195666033386, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7005493527591877, "gear": 1, "accelerator_pedal_position": 0.25730979517766006, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.5635243352482453, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141199.6318507} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.25996160507202, "x": 43.20931331412669, "y": 5.04933628726646, "z": null, "yaw": 4.269761567236672, "pitch": null, "roll": null}, "v": 1.7001065800889947, "accelerator_pedal_position": 0.25730979517766006, "brake_pedal_position": 0.0, "acceleration": 0.044277267019306565, "steering_wheel_angle": 3.603904323076461, "front_wheel_angle": 0.17415777560360052, "heading_rate": 0.11684260919065767, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141199.6518507} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26663792537379094, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.9037195666033386, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7036474649102717, "gear": 1, "accelerator_pedal_position": 0.2750266983081272, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.4825809393142735, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141199.6518507} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.25996160507202, "x": 43.20931331412669, "y": 5.04933628726646, "z": null, "yaw": 4.269761567236672, "pitch": null, "roll": null}, "v": 1.7001065800889947, "accelerator_pedal_position": 0.25730979517766006, "brake_pedal_position": 0.0, "acceleration": 0.044277267019306565, "steering_wheel_angle": 3.603904323076461, "front_wheel_angle": 0.17415777560360052, "heading_rate": 0.11684260919065767, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141199.6718507} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26663792537379094, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.9037195666033386, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7056922151730907, "gear": 1, "accelerator_pedal_position": 0.26663792537379094, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.401427042165405, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141199.6718507} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.25996160507202, "x": 43.20931331412669, "y": 5.04933628726646, "z": null, "yaw": 4.269761567236672, "pitch": null, "roll": null}, "v": 1.7001065800889947, "accelerator_pedal_position": 0.25730979517766006, "brake_pedal_position": 0.0, "acceleration": 0.044277267019306565, "steering_wheel_angle": 3.603904323076461, "front_wheel_angle": 0.17415777560360052, "heading_rate": 0.11684260919065767, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141199.6918507} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26663792537379094, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.9037195666033386, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7077335274644183, "gear": 1, "accelerator_pedal_position": 0.26663792537379094, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.3200626438016405, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141199.6918507} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.25996160507202, "x": 43.20931331412669, "y": 5.04933628726646, "z": null, "yaw": 4.269761567236672, "pitch": null, "roll": null}, "v": 1.7001065800889947, "accelerator_pedal_position": 0.25730979517766006, "brake_pedal_position": 0.0, "acceleration": 0.044277267019306565, "steering_wheel_angle": 3.603904323076461, "front_wheel_angle": 0.17415777560360052, "heading_rate": 0.11684260919065767, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141199.7118506} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26663792537379094, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.9037195666033386, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7097714058986577, "gear": 1, "accelerator_pedal_position": 0.26663792537379094, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.2384877442229802, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141199.7118506} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141199.7318506, "x": 47.12952196786303, "y": 9.879545467038193, "z": null, "yaw": 4.276866741595276, "pitch": null, "roll": null}, "v": 1.7118058545916979, "accelerator_pedal_position": 0.26663792537379094, "brake_pedal_position": 0.0, "acceleration": 0.10159394801846428, "steering_wheel_angle": 3.1567023434294246, "front_wheel_angle": 0.15151724788621967, "heading_rate": 0.10209817262162205, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141199.7318506} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2234719347674548, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.793184548858021, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7118058545916979, "gear": 1, "accelerator_pedal_position": 0.26663792537379094, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.1567023434294246, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141199.7318506} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.36996150016785, "x": 43.12952196786303, "y": 4.879545467038193, "z": null, "yaw": 4.276866741595276, "pitch": null, "roll": null}, "v": 1.7118058545916979, "accelerator_pedal_position": 0.26663792537379094, "brake_pedal_position": 0.0, "acceleration": 0.10159394801846428, "steering_wheel_angle": 3.1567023434294246, "front_wheel_angle": 0.15151724788621967, "heading_rate": 0.10209817262162205, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141199.7518506} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24410216023629747, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.793184548858021, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.708443401240064, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.0721936350142194, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141199.7518506} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.36996150016785, "x": 43.12952196786303, "y": 4.879545467038193, "z": null, "yaw": 4.276866741595276, "pitch": null, "roll": null}, "v": 1.7118058545916979, "accelerator_pedal_position": 0.26663792537379094, "brake_pedal_position": 0.0, "acceleration": 0.10159394801846428, "steering_wheel_angle": 3.1567023434294246, "front_wheel_angle": 0.15151724788621967, "heading_rate": 0.10209817262162205, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141199.7718506} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24410216023629747, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.793184548858021, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7076643001004683, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.987461343424606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141199.7718506} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.36996150016785, "x": 43.12952196786303, "y": 4.879545467038193, "z": null, "yaw": 4.276866741595276, "pitch": null, "roll": null}, "v": 1.7118058545916979, "accelerator_pedal_position": 0.26663792537379094, "brake_pedal_position": 0.0, "acceleration": 0.10159394801846428, "steering_wheel_angle": 3.1567023434294246, "front_wheel_angle": 0.15151724788621967, "heading_rate": 0.10209817262162205, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141199.7918506} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24410216023629747, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.793184548858021, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7068865097482255, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.9025054686605833, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141199.7918506} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.36996150016785, "x": 43.12952196786303, "y": 4.879545467038193, "z": null, "yaw": 4.276866741595276, "pitch": null, "roll": null}, "v": 1.7118058545916979, "accelerator_pedal_position": 0.26663792537379094, "brake_pedal_position": 0.0, "acceleration": 0.10159394801846428, "steering_wheel_angle": 3.1567023434294246, "front_wheel_angle": 0.15151724788621967, "heading_rate": 0.10209817262162205, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141199.8118505} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24410216023629747, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.793184548858021, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7061100277361392, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.8173260107221507, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141199.8118505} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.36996150016785, "x": 43.12952196786303, "y": 4.879545467038193, "z": null, "yaw": 4.276866741595276, "pitch": null, "roll": null}, "v": 1.7118058545916979, "accelerator_pedal_position": 0.26663792537379094, "brake_pedal_position": 0.0, "acceleration": 0.10159394801846428, "steering_wheel_angle": 3.1567023434294246, "front_wheel_angle": 0.15151724788621967, "heading_rate": 0.10209817262162205, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141199.8318505} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24410216023629747, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.793184548858021, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7053348516223499, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.7319229696093092, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141199.8318505} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141199.8418505, "x": 47.05076201809416, "y": 9.709015943398196, "z": null, "yaw": 4.282962178794693, "pitch": null, "roll": null}, "v": 1.7049477525156915, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3143158560138677, "steering_wheel_angle": 2.689137605362485, "front_wheel_angle": 0.12818313506743462, "heading_rate": 0.0858400138598616, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141199.8518505} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.649848604071026, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7045609789703215, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.6462963453220585, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141199.8518505} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.47996139526367, "x": 43.05076201809416, "y": 4.709015943398196, "z": null, "yaw": 4.282962178794693, "pitch": null, "roll": null}, "v": 1.7049477525156915, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3143158560138677, "steering_wheel_angle": 2.689137605362485, "front_wheel_angle": 0.12818313506743462, "heading_rate": 0.0858400138598616, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141199.8718505} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22669812715179932, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.649848604071026, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.698277954224259, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.5577518359012847, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141199.8718505} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.47996139526367, "x": 43.05076201809416, "y": 4.709015943398196, "z": null, "yaw": 4.282962178794693, "pitch": null, "roll": null}, "v": 1.7049477525156915, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3143158560138677, "steering_wheel_angle": 2.689137605362485, "front_wheel_angle": 0.12818313506743462, "heading_rate": 0.0858400138598616, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141199.8918505} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22669812715179932, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.649848604071026, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6953413457338642, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.468969508742618, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141199.8918505} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.47996139526367, "x": 43.05076201809416, "y": 4.709015943398196, "z": null, "yaw": 4.282962178794693, "pitch": null, "roll": null}, "v": 1.7049477525156915, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3143158560138677, "steering_wheel_angle": 2.689137605362485, "front_wheel_angle": 0.12818313506743462, "heading_rate": 0.0858400138598616, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141199.9118505} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22669812715179932, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.649848604071026, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.692409664068004, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.3799493638460576, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141199.9118505} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.47996139526367, "x": 43.05076201809416, "y": 4.709015943398196, "z": null, "yaw": 4.282962178794693, "pitch": null, "roll": null}, "v": 1.7049477525156915, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3143158560138677, "steering_wheel_angle": 2.689137605362485, "front_wheel_angle": 0.12818313506743462, "heading_rate": 0.0858400138598616, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141199.9318504} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22669812715179932, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.649848604071026, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6894828975243532, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.290691401211604, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141199.9318504} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141199.9518504, "x": 46.97349204716573, "y": 9.539209451833013, "z": null, "yaw": 4.288026109250623, "pitch": null, "roll": null}, "v": 1.6865610344374944, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.31277293295070346, "steering_wheel_angle": 2.201195620839258, "front_wheel_angle": 0.10418417684982026, "heading_rate": 0.06888730278409778, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141199.9518504} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.488519109567147, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6865610344374944, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.201195620839258, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141199.9518504} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.5899612903595, "x": 42.97349204716573, "y": 4.539209451833013, "z": null, "yaw": 4.288026109250623, "pitch": null, "roll": null}, "v": 1.6865610344374944, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.31277293295070346, "steering_wheel_angle": 2.201195620839258, "front_wheel_angle": 0.10418417684982026, "heading_rate": 0.06888730278409778, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141199.9718504} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.488519109567147, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6803081936861586, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.108523624822855, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141199.9718504} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.5899612903595, "x": 42.97349204716573, "y": 4.539209451833013, "z": null, "yaw": 4.288026109250623, "pitch": null, "roll": null}, "v": 1.6865610344374944, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.31277293295070346, "steering_wheel_angle": 2.201195620839258, "front_wheel_angle": 0.10418417684982026, "heading_rate": 0.06888730278409778, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141199.9918504} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.488519109567147, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6740658079928297, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.0155980029797576, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141199.9918504} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.5899612903595, "x": 42.97349204716573, "y": 4.539209451833013, "z": null, "yaw": 4.288026109250623, "pitch": null, "roll": null}, "v": 1.6865610344374944, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.31277293295070346, "steering_wheel_angle": 2.201195620839258, "front_wheel_angle": 0.10418417684982026, "heading_rate": 0.06888730278409778, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141200.0118504} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.488519109567147, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.667833844295684, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.9224187553099663, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141200.0118504} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.5899612903595, "x": 42.97349204716573, "y": 4.539209451833013, "z": null, "yaw": 4.288026109250623, "pitch": null, "roll": null}, "v": 1.6865610344374944, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.31277293295070346, "steering_wheel_angle": 2.201195620839258, "front_wheel_angle": 0.10418417684982026, "heading_rate": 0.06888730278409778, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141200.0318503} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.488519109567147, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6616122696661633, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.8289858818134803, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141200.0318503} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.5899612903595, "x": 42.97349204716573, "y": 4.539209451833013, "z": null, "yaw": 4.288026109250623, "pitch": null, "roll": null}, "v": 1.6865610344374944, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.31277293295070346, "steering_wheel_angle": 2.201195620839258, "front_wheel_angle": 0.10418417684982026, "heading_rate": 0.06888730278409778, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141200.0518503} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.488519109567147, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6554010513082928, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.7352993824903002, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141200.0518503} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141200.0618503, "x": 46.898130540571586, "y": 9.37156352144941, "z": null, "yaw": 4.292029099398755, "pitch": null, "roll": null}, "v": 1.6522993155185715, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30991589605656, "steering_wheel_angle": 1.6883610231436996, "front_wheel_angle": 0.07933176899900476, "heading_rate": 0.05131074474921378, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141200.0718503} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.123677589427992, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.649200156558006, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.641359257340426, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141200.0718503} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.69996118545532, "x": 42.898130540571586, "y": 4.37156352144941, "z": null, "yaw": 4.292029099398755, "pitch": null, "roll": null}, "v": 1.6522993155185715, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30991589605656, "steering_wheel_angle": 1.6883610231436996, "front_wheel_angle": 0.07933176899900476, "heading_rate": 0.05131074474921378, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141200.0918503} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.123677589427992, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6430095528824693, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.5446977303399692, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141200.0918503} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.69996118545532, "x": 42.898130540571586, "y": 4.37156352144941, "z": null, "yaw": 4.292029099398755, "pitch": null, "roll": null}, "v": 1.6522993155185715, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30991589605656, "steering_wheel_angle": 1.6883610231436996, "front_wheel_angle": 0.07933176899900476, "heading_rate": 0.05131074474921378, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141200.1118503} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.123677589427992, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6368292078794155, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.4477691327889517, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141200.1118503} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.69996118545532, "x": 42.898130540571586, "y": 4.37156352144941, "z": null, "yaw": 4.292029099398755, "pitch": null, "roll": null}, "v": 1.6522993155185715, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30991589605656, "steering_wheel_angle": 1.6883610231436996, "front_wheel_angle": 0.07933176899900476, "heading_rate": 0.05131074474921378, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141200.1318502} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.123677589427992, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6306590892764785, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.350573464687373, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141200.1318502} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.69996118545532, "x": 42.898130540571586, "y": 4.37156352144941, "z": null, "yaw": 4.292029099398755, "pitch": null, "roll": null}, "v": 1.6522993155185715, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30991589605656, "steering_wheel_angle": 1.6883610231436996, "front_wheel_angle": 0.07933176899900476, "heading_rate": 0.05131074474921378, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141200.1518502} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.123677589427992, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.624499164930532, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.2531107260352337, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141200.1518502} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141200.1718502, "x": 46.82488524013349, "y": 9.207082373858738, "z": null, "yaw": 4.294946725399292, "pitch": null, "roll": null}, "v": 1.6183494028270335, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30710801803765786, "steering_wheel_angle": 1.1553809168325337, "front_wheel_angle": 0.05388826264082518, "heading_rate": 0.034099434980692754, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141200.1718502} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.7671961107341465, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6183494028270335, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.1553809168325337, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141200.1718502} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.80996108055115, "x": 42.82488524013349, "y": 4.2070823738587375, "z": null, "yaw": 4.294946725399292, "pitch": null, "roll": null}, "v": 1.6183494028270335, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30710801803765786, "steering_wheel_angle": 1.1553809168325337, "front_wheel_angle": 0.05388826264082518, "heading_rate": 0.034099434980692754, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141200.1918502} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.7671961107341465, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6122097710793724, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.0546376150667327, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141200.1918502} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.80996108055115, "x": 42.82488524013349, "y": 4.2070823738587375, "z": null, "yaw": 4.294946725399292, "pitch": null, "roll": null}, "v": 1.6183494028270335, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30710801803765786, "steering_wheel_angle": 1.1553809168325337, "front_wheel_angle": 0.05388826264082518, "heading_rate": 0.034099434980692754, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141200.2118502} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.7671961107341465, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.60608023792822, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.9536120848817979, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141200.2118502} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.80996108055115, "x": 42.82488524013349, "y": 4.2070823738587375, "z": null, "yaw": 4.294946725399292, "pitch": null, "roll": null}, "v": 1.6183494028270335, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30710801803765786, "steering_wheel_angle": 1.1553809168325337, "front_wheel_angle": 0.05388826264082518, "heading_rate": 0.034099434980692754, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141200.2318501} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.7671961107341465, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.599960771740886, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.8523043262777296, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141200.2318501} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.80996108055115, "x": 42.82488524013349, "y": 4.2070823738587375, "z": null, "yaw": 4.294946725399292, "pitch": null, "roll": null}, "v": 1.6183494028270335, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30710801803765786, "steering_wheel_angle": 1.1553809168325337, "front_wheel_angle": 0.05388826264082518, "heading_rate": 0.034099434980692754, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141200.2518501} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.7671961107341465, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5938513410106763, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.7507143392545269, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141200.2518501} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.80996108055115, "x": 42.82488524013349, "y": 4.2070823738587375, "z": null, "yaw": 4.294946725399292, "pitch": null, "roll": null}, "v": 1.6183494028270335, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30710801803765786, "steering_wheel_angle": 1.1553809168325337, "front_wheel_angle": 0.05388826264082518, "heading_rate": 0.034099434980692754, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141200.27185} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.7671961107341465, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5877519143562575, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.6488421238121908, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141200.27185} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141200.28185, "x": 46.753542243018416, "y": 9.045825836463239, "z": null, "yaw": 4.296751361191159, "pitch": null, "roll": null}, "v": 1.5847059427849253, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30434822639022485, "steering_wheel_angle": 0.5978001804338475, "front_wheel_angle": 0.02767191991608528, "heading_rate": 0.017134004819484575, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141200.29185} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.560362678095213, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.581662460521023, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5466876799507207, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141200.29185} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.91996097564697, "x": 42.753542243018416, "y": 4.045825836463239, "z": null, "yaw": 4.296751361191159, "pitch": null, "roll": null}, "v": 1.5847059427849253, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30434822639022485, "steering_wheel_angle": 0.5978001804338475, "front_wheel_angle": 0.02767191991608528, "heading_rate": 0.017134004819484575, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141200.31185} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.560362678095213, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5755829483724637, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.44046299530929117, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141200.31185} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.91996097564697, "x": 42.753542243018416, "y": 4.045825836463239, "z": null, "yaw": 4.296751361191159, "pitch": null, "roll": null}, "v": 1.5847059427849253, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30434822639022485, "steering_wheel_angle": 0.5978001804338475, "front_wheel_angle": 0.02767191991608528, "heading_rate": 0.017134004819484575, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141200.33185} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.560362678095213, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.569513346901543, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3339348541027355, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141200.33185} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.91996097564697, "x": 42.753542243018416, "y": 4.045825836463239, "z": null, "yaw": 4.296751361191159, "pitch": null, "roll": null}, "v": 1.5847059427849253, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30434822639022485, "steering_wheel_angle": 0.5978001804338475, "front_wheel_angle": 0.02767191991608528, "heading_rate": 0.017134004819484575, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141200.35185} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.560362678095213, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5634536252220748, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.22710325633105372, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141200.35185} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.91996097564697, "x": 42.753542243018416, "y": 4.045825836463239, "z": null, "yaw": 4.296751361191159, "pitch": null, "roll": null}, "v": 1.5847059427849253, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30434822639022485, "steering_wheel_angle": 0.5978001804338475, "front_wheel_angle": 0.02767191991608528, "heading_rate": 0.017134004819484575, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141200.37185} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.560362678095213, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5574037525701048, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.11996820199424592, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141200.37185} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141200.39185, "x": 46.6838941887436, "y": 8.88784982796237, "z": null, "yaw": 4.297412973664053, "pitch": null, "roll": null}, "v": 1.5513636983032975, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3016354781592977, "steering_wheel_angle": 0.01252969109231201, "front_wheel_angle": 0.000575510824749064, "heading_rate": 0.0003487604297141176, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141200.39185} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21692388851710478, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.883278154491553, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5513636983032975, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.01252969109231201, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141200.39185} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.0299608707428, "x": 42.6838941887436, "y": 3.88784982796237, "z": null, "yaw": 4.297412973664053, "pitch": null, "roll": null}, "v": 1.5513636983032975, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3016354781592977, "steering_wheel_angle": 0.01252969109231201, "front_wheel_angle": 0.000575510824749064, "heading_rate": 0.0003487604297141176, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141200.41185} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.883278154491553, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5474480614308415, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.09665783629929017, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141200.41185} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.0299608707428, "x": 42.6838941887436, "y": 3.88784982796237, "z": null, "yaw": 4.297412973664053, "pitch": null, "roll": null}, "v": 1.5513636983032975, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3016354781592977, "steering_wheel_angle": 0.01252969109231201, "front_wheel_angle": 0.000575510824749064, "heading_rate": 0.0003487604297141176, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141200.43185} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.883278154491553, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5414241325017266, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.20553643531817412, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141200.43185} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.0299608707428, "x": 42.6838941887436, "y": 3.88784982796237, "z": null, "yaw": 4.297412973664053, "pitch": null, "roll": null}, "v": 1.5513636983032975, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3016354781592977, "steering_wheel_angle": 0.01252969109231201, "front_wheel_angle": 0.000575510824749064, "heading_rate": 0.0003487604297141176, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141200.45185} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.883278154491553, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.535409941365035, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3141019917311476, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141200.45185} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.0299608707428, "x": 42.6838941887436, "y": 3.88784982796237, "z": null, "yaw": 4.297412973664053, "pitch": null, "roll": null}, "v": 1.5513636983032975, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3016354781592977, "steering_wheel_angle": 0.01252969109231201, "front_wheel_angle": 0.000575510824749064, "heading_rate": 0.0003487604297141176, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141200.47185} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.883278154491553, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5294054578170813, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4223545055382107, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141200.47185} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.0299608707428, "x": 42.6838941887436, "y": 3.88784982796237, "z": null, "yaw": 4.297412973664053, "pitch": null, "roll": null}, "v": 1.5513636983032975, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3016354781592977, "steering_wheel_angle": 0.01252969109231201, "front_wheel_angle": 0.000575510824749064, "heading_rate": 0.0003487604297141176, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141200.49185} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.883278154491553, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5234106517729895, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5302939767393633, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141200.49185} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141200.50185, "x": 46.615659149374636, "y": 8.733024016187768, "z": null, "yaw": 4.296898379053646, "pitch": null, "roll": null}, "v": 1.5204168684457096, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2991375179608281, "steering_wheel_angle": -0.5841463213627232, "front_wheel_angle": -0.02703493755652157, "heading_rate": -0.01606030947512449, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141200.5118499} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.054687854316584114, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.134989227963827, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5174254932661013, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6379204053346054, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141200.5118499} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.13996076583862, "x": 42.615659149374636, "y": 3.733024016187768, "z": null, "yaw": 4.296898379053646, "pitch": null, "roll": null}, "v": 1.5204168684457096, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2991375179608281, "steering_wheel_angle": -0.5841463213627232, "front_wheel_angle": -0.02703493755652157, "heading_rate": -0.01606030947512449, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141200.5318499} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.026459183599203698, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.134989227963827, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.502703406497358, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.054687854316584114, "steering_wheel_angle": -0.7524651470791636, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141200.5318499} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.13996076583862, "x": 42.615659149374636, "y": 3.733024016187768, "z": null, "yaw": 4.296898379053646, "pitch": null, "roll": null}, "v": 1.5204168684457096, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2991375179608281, "steering_wheel_angle": -0.5841463213627232, "front_wheel_angle": -0.02703493755652157, "heading_rate": -0.01606030947512449, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141200.5518498} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.026459183599203698, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.134989227963827, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.492519685487319, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.026459183599203698, "steering_wheel_angle": -0.8666531655253255, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141200.5518498} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.13996076583862, "x": 42.615659149374636, "y": 3.733024016187768, "z": null, "yaw": 4.296898379053646, "pitch": null, "roll": null}, "v": 1.5204168684457096, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2991375179608281, "steering_wheel_angle": -0.5841463213627232, "front_wheel_angle": -0.02703493755652157, "heading_rate": -0.01606030947512449, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141200.5718498} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.026459183599203698, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.134989227963827, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4823522318333688, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.026459183599203698, "steering_wheel_angle": -0.980484460673091, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141200.5718498} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.13996076583862, "x": 42.615659149374636, "y": 3.733024016187768, "z": null, "yaw": 4.296898379053646, "pitch": null, "roll": null}, "v": 1.5204168684457096, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2991375179608281, "steering_wheel_angle": -0.5841463213627232, "front_wheel_angle": -0.02703493755652157, "heading_rate": -0.01606030947512449, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141200.5918498} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.026459183599203698, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.134989227963827, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4722009782158327, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.026459183599203698, "steering_wheel_angle": -1.0939590325224602, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141200.5918498} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141200.6118498, "x": 46.54925112953671, "y": 8.582774133497963, "z": null, "yaw": 4.295166616563127, "pitch": null, "roll": null}, "v": 1.4620658576200023, "accelerator_pedal_position": 0, "brake_pedal_position": 0.026459183599203698, "acceleration": -0.5061531273948109, "steering_wheel_angle": -1.2070768810734331, "front_wheel_angle": -0.056339424606632806, "heading_rate": -0.03221063010331051, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141200.6118498} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.405636987373967, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4620658576200023, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.026459183599203698, "steering_wheel_angle": -1.2070768810734331, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141200.6118498} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.24996066093445, "x": 42.54925112953671, "y": 3.5827741334979635, "z": null, "yaw": 4.295166616563127, "pitch": null, "roll": null}, "v": 1.4620658576200023, "accelerator_pedal_position": 0, "brake_pedal_position": 0.026459183599203698, "acceleration": -0.5061531273948109, "steering_wheel_angle": -1.2070768810734331, "front_wheel_angle": -0.056339424606632806, "heading_rate": -0.03221063010331051, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141200.6318498} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.405636987373967, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.456178597076398, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.3215757414981522, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141200.6318498} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.24996066093445, "x": 42.54925112953671, "y": 3.5827741334979635, "z": null, "yaw": 4.295166616563127, "pitch": null, "roll": null}, "v": 1.4620658576200023, "accelerator_pedal_position": 0, "brake_pedal_position": 0.026459183599203698, "acceleration": -0.5061531273948109, "steering_wheel_angle": -1.2070768810734331, "front_wheel_angle": -0.056339424606632806, "heading_rate": -0.03221063010331051, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141200.6518497} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.405636987373967, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4503006527333255, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.4357067811872277, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141200.6518497} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.24996066093445, "x": 42.54925112953671, "y": 3.5827741334979635, "z": null, "yaw": 4.295166616563127, "pitch": null, "roll": null}, "v": 1.4620658576200023, "accelerator_pedal_position": 0, "brake_pedal_position": 0.026459183599203698, "acceleration": -0.5061531273948109, "steering_wheel_angle": -1.2070768810734331, "front_wheel_angle": -0.056339424606632806, "heading_rate": -0.03221063010331051, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141200.6718497} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.405636987373967, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4444319960338767, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.5494700001406592, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141200.6718497} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.24996066093445, "x": 42.54925112953671, "y": 3.5827741334979635, "z": null, "yaw": 4.295166616563127, "pitch": null, "roll": null}, "v": 1.4620658576200023, "accelerator_pedal_position": 0, "brake_pedal_position": 0.026459183599203698, "acceleration": -0.5061531273948109, "steering_wheel_angle": -1.2070768810734331, "front_wheel_angle": -0.056339424606632806, "heading_rate": -0.03221063010331051, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141200.6918497} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.405636987373967, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.438572598531775, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.6628653983584472, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141200.6918497} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.24996066093445, "x": 42.54925112953671, "y": 3.5827741334979635, "z": null, "yaw": 4.295166616563127, "pitch": null, "roll": null}, "v": 1.4620658576200023, "accelerator_pedal_position": 0, "brake_pedal_position": 0.026459183599203698, "acceleration": -0.5061531273948109, "steering_wheel_angle": -1.2070768810734331, "front_wheel_angle": -0.056339424606632806, "heading_rate": -0.03221063010331051, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141200.7118497} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.405636987373967, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4298008013182002, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.8322688318057971, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141200.7118497} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141200.7218497, "x": 46.484552279769325, "y": 8.437301372435304, "z": null, "yaw": 4.292156099887886, "pitch": null, "roll": null}, "v": 1.4298008013182002, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2919333433804117, "steering_wheel_angle": -1.8322688318057971, "front_wheel_angle": -0.08626826144770929, "heading_rate": -0.048302083252557186, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141200.7318497} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.030747818153220287, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4268814678843962, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.8885527325870917, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141200.7318497} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.35996055603027, "x": 42.484552279769325, "y": 3.4373013724353036, "z": null, "yaw": 4.292156099887886, "pitch": null, "roll": null}, "v": 1.4298008013182002, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2919333433804117, "steering_wheel_angle": -1.8322688318057971, "front_wheel_angle": -0.08626826144770929, "heading_rate": -0.048302083252557186, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141200.7518497} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.02172084193982856, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4161319573387579, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.030747818153220287, "steering_wheel_angle": -2.004760771579866, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141200.7518497} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.35996055603027, "x": 42.484552279769325, "y": 3.4373013724353036, "z": null, "yaw": 4.292156099887886, "pitch": null, "roll": null}, "v": 1.4298008013182002, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2919333433804117, "steering_wheel_angle": -1.8322688318057971, "front_wheel_angle": -0.08626826144770929, "heading_rate": -0.048302083252557186, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141200.7718496} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.02172084193982856, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4068430416543638, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.02172084193982856, "steering_wheel_angle": -2.1205748424242694, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141200.7718496} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.35996055603027, "x": 42.484552279769325, "y": 3.4373013724353036, "z": null, "yaw": 4.292156099887886, "pitch": null, "roll": null}, "v": 1.4298008013182002, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2919333433804117, "steering_wheel_angle": -1.8322688318057971, "front_wheel_angle": -0.08626826144770929, "heading_rate": -0.048302083252557186, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141200.7918496} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.02172084193982856, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.397568645058009, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.02172084193982856, "steering_wheel_angle": -2.235994945120303, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141200.7918496} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.35996055603027, "x": 42.484552279769325, "y": 3.4373013724353036, "z": null, "yaw": 4.292156099887886, "pitch": null, "roll": null}, "v": 1.4298008013182002, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2919333433804117, "steering_wheel_angle": -1.8322688318057971, "front_wheel_angle": -0.08626826144770929, "heading_rate": -0.048302083252557186, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141200.8118496} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.02172084193982856, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3883087104631835, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.02172084193982856, "steering_wheel_angle": -2.351021079667967, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141200.8118496} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141200.8318496, "x": 46.421148853608585, "y": 8.29611070081116, "z": null, "yaw": 4.287833166502522, "pitch": null, "roll": null}, "v": 1.3790631810333807, "accelerator_pedal_position": 0, "brake_pedal_position": 0.02172084193982856, "acceleration": -0.4617380471431166, "steering_wheel_angle": -2.465653246067261, "front_wheel_angle": -0.11714757054013791, "heading_rate": -0.0633972703065185, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141200.8318496} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.015354320281619774, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3790631810333807, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.02172084193982856, "steering_wheel_angle": -2.465653246067261, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141200.8318496} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.4699604511261, "x": 42.421148853608585, "y": 3.2961107008111608, "z": null, "yaw": 4.287833166502522, "pitch": null, "roll": null}, "v": 1.3790631810333807, "accelerator_pedal_position": 0, "brake_pedal_position": 0.02172084193982856, "acceleration": -0.4617380471431166, "steering_wheel_angle": -2.465653246067261, "front_wheel_angle": -0.11714757054013791, "heading_rate": -0.0633972703065185, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141200.8518496} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.018621834117551993, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3664871540577115, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.018621834117551993, "steering_wheel_angle": -2.636862805388008, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141200.8518496} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.4699604511261, "x": 42.421148853608585, "y": 3.2961107008111608, "z": null, "yaw": 4.287833166502522, "pitch": null, "roll": null}, "v": 1.3790631810333807, "accelerator_pedal_position": 0, "brake_pedal_position": 0.02172084193982856, "acceleration": -0.4617380471431166, "steering_wheel_angle": -2.465653246067261, "front_wheel_angle": -0.11714757054013791, "heading_rate": -0.0633972703065185, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141200.8718495} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.018621834117551993, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.362127435037058, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.018621834117551993, "steering_wheel_angle": -2.693735674420738, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141200.8718495} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.4699604511261, "x": 42.421148853608585, "y": 3.2961107008111608, "z": null, "yaw": 4.287833166502522, "pitch": null, "roll": null}, "v": 1.3790631810333807, "accelerator_pedal_position": 0, "brake_pedal_position": 0.02172084193982856, "acceleration": -0.4617380471431166, "steering_wheel_angle": -2.465653246067261, "front_wheel_angle": -0.11714757054013791, "heading_rate": -0.0633972703065185, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141200.8918495} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.018621834117551993, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3534180989710103, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.018621834117551993, "steering_wheel_angle": -2.8071859363749216, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141200.8918495} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.4699604511261, "x": 42.421148853608585, "y": 3.2961107008111608, "z": null, "yaw": 4.287833166502522, "pitch": null, "roll": null}, "v": 1.3790631810333807, "accelerator_pedal_position": 0, "brake_pedal_position": 0.02172084193982856, "acceleration": -0.4617380471431166, "steering_wheel_angle": -2.465653246067261, "front_wheel_angle": -0.11714757054013791, "heading_rate": -0.0633972703065185, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141200.9118495} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.018621834117551993, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3403792539987196, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.018621834117551993, "steering_wheel_angle": -2.976622639028004, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141200.9118495} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.4699604511261, "x": 42.421148853608585, "y": 3.2961107008111608, "z": null, "yaw": 4.287833166502522, "pitch": null, "roll": null}, "v": 1.3790631810333807, "accelerator_pedal_position": 0, "brake_pedal_position": 0.02172084193982856, "acceleration": -0.4617380471431166, "steering_wheel_angle": -2.465653246067261, "front_wheel_angle": -0.11714757054013791, "heading_rate": -0.0633972703065185, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141200.9318495} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.018621834117551993, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3360396559878611, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.018621834117551993, "steering_wheel_angle": -3.03290455583818, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141200.9318495} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141200.9418495, "x": 46.35929653446644, "y": 8.160172103244676, "z": null, "yaw": 4.282161465102958, "pitch": null, "roll": null}, "v": 1.3317033892342258, "accelerator_pedal_position": 0, "brake_pedal_position": 0.018621834117551993, "acceleration": -0.4332941815711065, "steering_wheel_angle": -3.089087980611263, "front_wheel_angle": -0.14812192685770167, "heading_rate": -0.07762103138641466, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141200.9518495} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3273704474185148, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.018621834117551993, "steering_wheel_angle": -3.145172913347254, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141200.9518495} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.579960346221924, "x": 42.35929653446644, "y": 3.160172103244676, "z": null, "yaw": 4.282161465102958, "pitch": null, "roll": null}, "v": 1.3317033892342258, "accelerator_pedal_position": 0, "brake_pedal_position": 0.018621834117551993, "acceleration": -0.4332941815711065, "steering_wheel_angle": -3.089087980611263, "front_wheel_angle": -0.14812192685770167, "heading_rate": -0.07762103138641466, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141200.9718494} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.012587943115859729, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3216928675555135, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.257047302707958, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141200.9718494} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.579960346221924, "x": 42.35929653446644, "y": 3.160172103244676, "z": null, "yaw": 4.282161465102958, "pitch": null, "roll": null}, "v": 1.3317033892342258, "accelerator_pedal_position": 0, "brake_pedal_position": 0.018621834117551993, "acceleration": -0.4332941815711065, "steering_wheel_angle": -3.089087980611263, "front_wheel_angle": -0.14812192685770167, "heading_rate": -0.07762103138641466, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141200.9918494} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.012587943115859729, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3140106649294316, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.012587943115859729, "steering_wheel_angle": -3.368527723920292, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141200.9918494} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.579960346221924, "x": 42.35929653446644, "y": 3.160172103244676, "z": null, "yaw": 4.282161465102958, "pitch": null, "roll": null}, "v": 1.3317033892342258, "accelerator_pedal_position": 0, "brake_pedal_position": 0.018621834117551993, "acceleration": -0.4332941815711065, "steering_wheel_angle": -3.089087980611263, "front_wheel_angle": -0.14812192685770167, "heading_rate": -0.07762103138641466, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141201.0118494} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.012587943115859729, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3063401837337987, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.012587943115859729, "steering_wheel_angle": -3.479614176984256, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141201.0118494} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.579960346221924, "x": 42.35929653446644, "y": 3.160172103244676, "z": null, "yaw": 4.282161465102958, "pitch": null, "roll": null}, "v": 1.3317033892342258, "accelerator_pedal_position": 0, "brake_pedal_position": 0.018621834117551993, "acceleration": -0.4332941815711065, "steering_wheel_angle": -3.089087980611263, "front_wheel_angle": -0.14812192685770167, "heading_rate": -0.07762103138641466, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141201.0318494} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.012587943115859729, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2986813825586079, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.012587943115859729, "steering_wheel_angle": -3.5903066618998496, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141201.0318494} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141201.0518494, "x": 46.298627783898134, "y": 8.029028448863682, "z": null, "yaw": 4.275129539085201, "pitch": null, "roll": null}, "v": 1.2910342201644318, "accelerator_pedal_position": 0, "brake_pedal_position": 0.012587943115859729, "acceleration": -0.3819229495114553, "steering_wheel_angle": -3.7006051786670735, "front_wheel_angle": -0.17909628317526546, "heading_rate": -0.09129832958157537, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141201.0518494} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2910342201644318, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.012587943115859729, "steering_wheel_angle": -3.7006051786670735, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141201.0518494} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.68996024131775, "x": 42.298627783898134, "y": 3.0290284488636825, "z": null, "yaw": 4.275129539085201, "pitch": null, "roll": null}, "v": 1.2910342201644318, "accelerator_pedal_position": 0, "brake_pedal_position": 0.012587943115859729, "acceleration": -0.3819229495114553, "steering_wheel_angle": -3.7006051786670735, "front_wheel_angle": -0.17909628317526546, "heading_rate": -0.09129832958157537, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141201.0718493} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.285411963506669, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.810509727285927, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141201.0718493} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.68996024131775, "x": 42.298627783898134, "y": 3.0290284488636825, "z": null, "yaw": 4.275129539085201, "pitch": null, "roll": null}, "v": 1.2910342201644318, "accelerator_pedal_position": 0, "brake_pedal_position": 0.012587943115859729, "acceleration": -0.3819229495114553, "steering_wheel_angle": -3.7006051786670735, "front_wheel_angle": -0.17909628317526546, "heading_rate": -0.09129832958157537, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141201.0918493} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2797982198092013, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.9200203077564115, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141201.0918493} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.68996024131775, "x": 42.298627783898134, "y": 3.0290284488636825, "z": null, "yaw": 4.275129539085201, "pitch": null, "roll": null}, "v": 1.2910342201644318, "accelerator_pedal_position": 0, "brake_pedal_position": 0.012587943115859729, "acceleration": -0.3819229495114553, "steering_wheel_angle": -3.7006051786670735, "front_wheel_angle": -0.17909628317526546, "heading_rate": -0.09129832958157537, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141201.1118493} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.274192963581213, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.029136920078526, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141201.1118493} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.68996024131775, "x": 42.298627783898134, "y": 3.0290284488636825, "z": null, "yaw": 4.275129539085201, "pitch": null, "roll": null}, "v": 1.2910342201644318, "accelerator_pedal_position": 0, "brake_pedal_position": 0.012587943115859729, "acceleration": -0.3819229495114553, "steering_wheel_angle": -3.7006051786670735, "front_wheel_angle": -0.17909628317526546, "heading_rate": -0.09129832958157537, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141201.1318493} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2685961694276036, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.1378595642522695, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141201.1318493} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.68996024131775, "x": 42.298627783898134, "y": 3.0290284488636825, "z": null, "yaw": 4.275129539085201, "pitch": null, "roll": null}, "v": 1.2910342201644318, "accelerator_pedal_position": 0, "brake_pedal_position": 0.012587943115859729, "acceleration": -0.3819229495114553, "steering_wheel_angle": -3.7006051786670735, "front_wheel_angle": -0.17909628317526546, "heading_rate": -0.09129832958157537, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141201.1518493} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2546410398219459, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.407942564037511, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141201.1518493} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141201.1618493, "x": 46.238675353151066, "y": 7.901994705981535, "z": null, "yaw": 4.266723521455816, "pitch": null, "roll": null}, "v": 1.260216789269175, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2788923030230178, "steering_wheel_angle": -4.300204840234692, "front_wheel_angle": -0.21007063949282956, "heading_rate": -0.10496045062265189, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141201.1818492} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2546410398219459, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.407942564037511, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141201.1818492} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.799960136413574, "x": 42.238675353151066, "y": 2.9019947059815348, "z": null, "yaw": 4.266723521455816, "pitch": null, "roll": null}, "v": 1.260216789269175, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2788923030230178, "steering_wheel_angle": -4.300204840234692, "front_wheel_angle": -0.21007063949282956, "heading_rate": -0.10496045062265189, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141201.2018492} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2462931089793559, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.568810459463547, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141201.2018492} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.799960136413574, "x": 42.238675353151066, "y": 2.9019947059815348, "z": null, "yaw": 4.266723521455816, "pitch": null, "roll": null}, "v": 1.260216789269175, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2788923030230178, "steering_wheel_angle": -4.300204840234692, "front_wheel_angle": -0.21007063949282956, "heading_rate": -0.10496045062265189, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141201.2218492} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2435146377735173, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.622236107198041, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141201.2218492} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.799960136413574, "x": 42.238675353151066, "y": 2.9019947059815348, "z": null, "yaw": 4.266723521455816, "pitch": null, "roll": null}, "v": 1.260216789269175, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2788923030230178, "steering_wheel_angle": -4.300204840234692, "front_wheel_angle": -0.21007063949282956, "heading_rate": -0.10496045062265189, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141201.2418492} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2379639353254972, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.72879192655575, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141201.2418492} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.799960136413574, "x": 42.238675353151066, "y": 2.9019947059815348, "z": null, "yaw": 4.266723521455816, "pitch": null, "roll": null}, "v": 1.260216789269175, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2788923030230178, "steering_wheel_angle": -4.300204840234692, "front_wheel_angle": -0.21007063949282956, "heading_rate": -0.10496045062265189, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141201.2618492} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2296534351359292, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.887886965314119, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141201.2618492} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141201.2718492, "x": 46.179046770013706, "y": 7.778548839185964, "z": null, "yaw": 4.25692664978525, "pitch": null, "roll": null}, "v": 1.2296534351359292, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2766031474622124, "steering_wheel_angle": -4.887886965314119, "front_wheel_angle": -0.24104499581039335, "heading_rate": -0.11807774160125534, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141201.2818491} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.226887403661307, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.940721660826057, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141201.2818491} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.9099600315094, "x": 42.179046770013706, "y": 2.778548839185964, "z": null, "yaw": 4.25692664978525, "pitch": null, "roll": null}, "v": 1.2296534351359292, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2766031474622124, "steering_wheel_angle": -4.887886965314119, "front_wheel_angle": -0.24104499581039335, "heading_rate": -0.11807774160125534, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141201.3018491} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2213615251536698, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.046095575738658, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141201.3018491} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.9099600315094, "x": 42.179046770013706, "y": 2.778548839185964, "z": null, "yaw": 4.25692664978525, "pitch": null, "roll": null}, "v": 1.2296534351359292, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2766031474622124, "steering_wheel_angle": -4.887886965314119, "front_wheel_angle": -0.24104499581039335, "heading_rate": -0.11807774160125534, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141201.321849} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.215843872154085, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.151075522502887, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141201.321849} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.9099600315094, "x": 42.179046770013706, "y": 2.778548839185964, "z": null, "yaw": 4.25692664978525, "pitch": null, "roll": null}, "v": 1.2296534351359292, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2766031474622124, "steering_wheel_angle": -4.887886965314119, "front_wheel_angle": -0.24104499581039335, "heading_rate": -0.11807774160125534, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141201.341849} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2103344202452537, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.2556615011187455, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141201.341849} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.9099600315094, "x": 42.179046770013706, "y": 2.778548839185964, "z": null, "yaw": 4.25692664978525, "pitch": null, "roll": null}, "v": 1.2296534351359292, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2766031474622124, "steering_wheel_angle": -4.887886965314119, "front_wheel_angle": -0.24104499581039335, "heading_rate": -0.11807774160125534, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141201.361849} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1993400224831927, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.463651553905354, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141201.361849} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141201.381849, "x": 46.11962182600618, "y": 7.658732573135921, "z": null, "yaw": 4.245719129806404, "pitch": null, "roll": null}, "v": 1.1993400224831927, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27435116601945947, "steering_wheel_angle": -5.463651553905354, "front_wheel_angle": -0.2720193521279571, "heading_rate": -0.1306781113683637, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141201.381849} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1993400224831927, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.463651553905354, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141201.381849} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.019959926605225, "x": 42.11962182600618, "y": 2.6587325731359206, "z": null, "yaw": 4.245719129806404, "pitch": null, "roll": null}, "v": 1.1993400224831927, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27435116601945947, "steering_wheel_angle": -5.463651553905354, "front_wheel_angle": -0.2720193521279571, "heading_rate": -0.1306781113683637, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141201.401849} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1883781383332437, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.6700657340984835, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141201.401849} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.019959926605225, "x": 42.11962182600618, "y": 2.6587325731359206, "z": null, "yaw": 4.245719129806404, "pitch": null, "roll": null}, "v": 1.1993400224831927, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27435116601945947, "steering_wheel_angle": -5.463651553905354, "front_wheel_angle": -0.2720193521279571, "heading_rate": -0.1306781113683637, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141201.421849} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1856427250041102, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.721423049054035, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141201.421849} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.019959926605225, "x": 42.11962182600618, "y": 2.6587325731359206, "z": null, "yaw": 4.245719129806404, "pitch": null, "roll": null}, "v": 1.1993400224831927, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27435116601945947, "steering_wheel_angle": -5.463651553905354, "front_wheel_angle": -0.2720193521279571, "heading_rate": -0.1306781113683637, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141201.441849} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1829093287744725, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.772681871972493, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141201.441849} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.019959926605225, "x": 42.11962182600618, "y": 2.6587325731359206, "z": null, "yaw": 4.245719129806404, "pitch": null, "roll": null}, "v": 1.1993400224831927, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27435116601945947, "steering_wheel_angle": -5.463651553905354, "front_wheel_angle": -0.2720193521279571, "heading_rate": -0.1306781113683637, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141201.461849} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1719958552882364, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.976732243275401, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141201.461849} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.019959926605225, "x": 42.11962182600618, "y": 2.6587325731359206, "z": null, "yaw": 4.245719129806404, "pitch": null, "roll": null}, "v": 1.1993400224831927, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27435116601945947, "steering_wheel_angle": -5.463651553905354, "front_wheel_angle": -0.2720193521279571, "heading_rate": -0.1306781113683637, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141201.481849} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.169272499932111, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.027498606008399, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141201.481849} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141201.491849, "x": 46.06029216801477, "y": 7.542587759659869, "z": null, "yaw": 4.233077971197378, "pitch": null, "roll": null}, "v": 1.169272499932111, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2721356067875805, "steering_wheel_angle": -6.027498606008399, "front_wheel_angle": -0.3029937084455212, "heading_rate": -0.14278802842890276, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141201.501849} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.166551143864235, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.078166476704301, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141201.501849} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.12995982170105, "x": 42.06029216801477, "y": 2.5425877596598694, "z": null, "yaw": 4.233077971197378, "pitch": null, "roll": null}, "v": 1.169272499932111, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2721356067875805, "steering_wheel_angle": -6.027498606008399, "front_wheel_angle": -0.3029937084455212, "heading_rate": -0.14278802842890276, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141201.521849} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.161114417800934, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.179206741984831, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141201.521849} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.12995982170105, "x": 42.06029216801477, "y": 2.5425877596598694, "z": null, "yaw": 4.233077971197378, "pitch": null, "roll": null}, "v": 1.169272499932111, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2721356067875805, "steering_wheel_angle": -6.027498606008399, "front_wheel_angle": -0.3029937084455212, "heading_rate": -0.14278802842890276, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141201.541849} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1529742498081466, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.330028449627432, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141201.541849} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.12995982170105, "x": 42.06029216801477, "y": 2.5425877596598694, "z": null, "yaw": 4.233077971197378, "pitch": null, "roll": null}, "v": 1.169272499932111, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2721356067875805, "steering_wheel_angle": -6.027498606008399, "front_wheel_angle": -0.3029937084455212, "heading_rate": -0.14278802842890276, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141201.5618489} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1475573843899207, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.430083794537037, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141201.5618489} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.12995982170105, "x": 42.06029216801477, "y": 2.5425877596598694, "z": null, "yaw": 4.233077971197378, "pitch": null, "roll": null}, "v": 1.169272499932111, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2721356067875805, "steering_wheel_angle": -6.027498606008399, "front_wheel_angle": -0.3029937084455212, "heading_rate": -0.14278802842890276, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141201.5818489} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.144851916902679, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.4799637289362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141201.5818489} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141201.6018488, "x": 46.00096124138342, "y": 7.430156765138453, "z": null, "yaw": 4.21897679257393, "pitch": null, "roll": null}, "v": 1.1394468978400192, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2699557372219734, "steering_wheel_angle": -6.57942812162325, "front_wheel_angle": -0.333968064763085, "heading_rate": -0.15443268142440306, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141201.6018488} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1394468978400192, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.57942812162325, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141201.6018488} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.239959716796875, "x": 42.00096124138342, "y": 2.4301567651384532, "z": null, "yaw": 4.21897679257393, "pitch": null, "roll": null}, "v": 1.1394468978400192, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2699557372219734, "steering_wheel_angle": -6.57942812162325, "front_wheel_angle": -0.333968064763085, "heading_rate": -0.15443268142440306, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141201.6218488} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.131354115589341, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.727886020375629, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141201.6218488} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.239959716796875, "x": 42.00096124138342, "y": 2.4301567651384532, "z": null, "yaw": 4.21897679257393, "pitch": null, "roll": null}, "v": 1.1394468978400192, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2699557372219734, "steering_wheel_angle": -6.57942812162325, "front_wheel_angle": -0.333968064763085, "heading_rate": -0.15443268142440306, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141201.6418488} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1286604423180602, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.777175002552239, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141201.6418488} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.239959716796875, "x": 42.00096124138342, "y": 2.4301567651384532, "z": null, "yaw": 4.21897679257393, "pitch": null, "roll": null}, "v": 1.1394468978400192, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2699557372219734, "steering_wheel_angle": -6.57942812162325, "front_wheel_angle": -0.333968064763085, "heading_rate": -0.15443268142440306, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141201.6618488} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1205911446962682, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.924450996859509, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141201.6618488} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.239959716796875, "x": 42.00096124138342, "y": 2.4301567651384532, "z": null, "yaw": 4.21897679257393, "pitch": null, "roll": null}, "v": 1.1394468978400192, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2699557372219734, "steering_wheel_angle": -6.57942812162325, "front_wheel_angle": -0.333968064763085, "heading_rate": -0.15443268142440306, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141201.6818488} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1179052766725628, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.973346010887748, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141201.6818488} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.239959716796875, "x": 42.00096124138342, "y": 2.4301567651384532, "z": null, "yaw": 4.21897679257393, "pitch": null, "roll": null}, "v": 1.1394468978400192, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2699557372219734, "steering_wheel_angle": -6.57942812162325, "front_wheel_angle": -0.333968064763085, "heading_rate": -0.15443268142440306, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141201.7018487} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.109859326200306, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.11944010074991, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141201.7018487} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141201.7118487, "x": 45.941544270014745, "y": 7.321482796321145, "z": null, "yaw": 4.203385592056693, "pitch": null, "roll": null}, "v": 1.109859326200306, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2678108435495533, "steering_wheel_angle": -7.11944010074991, "front_wheel_angle": -0.3649424210806487, "heading_rate": -0.16563613136085428, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141201.7218487} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2344879527721841, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1071812177648106, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.1679411466297775, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141201.7218487} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.3499596118927, "x": 41.941544270014745, "y": 2.3214827963211446, "z": null, "yaw": 4.203385592056693, "pitch": null, "roll": null}, "v": 1.109859326200306, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2678108435495533, "steering_wheel_angle": -7.11944010074991, "front_wheel_angle": -0.3649424210806487, "heading_rate": -0.16563613136085428, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141201.7418487} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2226837526515618, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1061402362030668, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.264647762278236, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141201.7418487} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.3499596118927, "x": 41.941544270014745, "y": 2.3214827963211446, "z": null, "yaw": 4.203385592056693, "pitch": null, "roll": null}, "v": 1.109859326200306, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2678108435495533, "steering_wheel_angle": -7.11944010074991, "front_wheel_angle": -0.3649424210806487, "heading_rate": -0.16563613136085428, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141201.7618487} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2226837526515618, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.102369885404091, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.4089689954727325, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141201.7618487} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.3499596118927, "x": 41.941544270014745, "y": 2.3214827963211446, "z": null, "yaw": 4.203385592056693, "pitch": null, "roll": null}, "v": 1.109859326200306, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2678108435495533, "steering_wheel_angle": -7.11944010074991, "front_wheel_angle": -0.3649424210806487, "heading_rate": -0.16563613136085428, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141201.7818487} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2226837526515618, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.101114913065687, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.456879089130046, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141201.7818487} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.3499596118927, "x": 41.941544270014745, "y": 2.3214827963211446, "z": null, "yaw": 4.203385592056693, "pitch": null, "roll": null}, "v": 1.109859326200306, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2678108435495533, "steering_wheel_angle": -7.11944010074991, "front_wheel_angle": -0.3649424210806487, "heading_rate": -0.16563613136085428, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141201.8018486} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2226837526515618, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0973554162929138, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.600018417879433, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141201.8018486} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141201.8218486, "x": 45.88158974407971, "y": 7.215949028342137, "z": null, "yaw": 4.1862704789977085, "pitch": null, "roll": null}, "v": 1.0961040542345233, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2668196436888198, "steering_wheel_angle": -7.6475345433883755, "front_wheel_angle": -0.3959167773982125, "heading_rate": -0.17896826118917383, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141201.8218486} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0961040542345233, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.6475345433883755, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141201.8218486} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.459959506988525, "x": 41.88158974407971, "y": 2.215949028342137, "z": null, "yaw": 4.1862704789977085, "pitch": null, "roll": null}, "v": 1.0961040542345233, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2668196436888198, "steering_wheel_angle": -7.6475345433883755, "front_wheel_angle": -0.3959167773982125, "heading_rate": -0.17896826118917383, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141201.8418486} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21772485629914365, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0881052170537953, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.789491967692652, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141201.8418486} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.459959506988525, "x": 41.88158974407971, "y": 2.215949028342137, "z": null, "yaw": 4.1862704789977085, "pitch": null, "roll": null}, "v": 1.0961040542345233, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2668196436888198, "steering_wheel_angle": -7.6475345433883755, "front_wheel_angle": -0.3959167773982125, "heading_rate": -0.17896826118917383, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141201.8618486} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21772485629914365, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0849970396867277, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.883637790376708, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141201.8618486} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.459959506988525, "x": 41.88158974407971, "y": 2.215949028342137, "z": null, "yaw": 4.1862704789977085, "pitch": null, "roll": null}, "v": 1.0961040542345233, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2668196436888198, "steering_wheel_angle": -7.6475345433883755, "front_wheel_angle": -0.3959167773982125, "heading_rate": -0.17896826118917383, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141201.8818486} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21772485629914365, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.081893318810177, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.9773896449123916, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141201.8818486} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.459959506988525, "x": 41.88158974407971, "y": 2.215949028342137, "z": null, "yaw": 4.1862704789977085, "pitch": null, "roll": null}, "v": 1.0961040542345233, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2668196436888198, "steering_wheel_angle": -7.6475345433883755, "front_wheel_angle": -0.3959167773982125, "heading_rate": -0.17896826118917383, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141201.9018486} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21772485629914365, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0772460710202219, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.117278736437726, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141201.9018486} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.459959506988525, "x": 41.88158974407971, "y": 2.215949028342137, "z": null, "yaw": 4.1862704789977085, "pitch": null, "roll": null}, "v": 1.0961040542345233, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2668196436888198, "steering_wheel_angle": -7.6475345433883755, "front_wheel_angle": -0.3959167773982125, "heading_rate": -0.17896826118917383, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141201.9218485} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21772485629914365, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0772460710202219, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.117278736437726, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141201.9218485} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141201.9318485, "x": 45.82076361751371, "y": 7.113186415075929, "z": null, "yaw": 4.167593361518875, "pitch": null, "roll": null}, "v": 1.0756992055936554, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26535624808883096, "steering_wheel_angle": -8.163711449538651, "front_wheel_angle": -0.4268911337157763, "heading_rate": -0.19113141327155078, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141201.9418485} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22587581890612676, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0741534466314635, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.210045670602486, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141201.9418485} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.56995940208435, "x": 41.82076361751371, "y": 2.113186415075929, "z": null, "yaw": 4.167593361518875, "pitch": null, "roll": null}, "v": 1.0756992055936554, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26535624808883096, "steering_wheel_angle": -8.163711449538651, "front_wheel_angle": -0.4268911337157763, "heading_rate": -0.19113141327155078, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141201.9618485} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22188290933864574, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0710500097719928, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.348457381571432, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141201.9618485} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.56995940208435, "x": 41.82076361751371, "y": 2.113186415075929, "z": null, "yaw": 4.167593361518875, "pitch": null, "roll": null}, "v": 1.0756992055936554, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26535624808883096, "steering_wheel_angle": -8.163711449538651, "front_wheel_angle": -0.4268911337157763, "heading_rate": -0.19113141327155078, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141201.9818485} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22188290933864574, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0684858096561096, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.44023939536527, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141201.9818485} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.56995940208435, "x": 41.82076361751371, "y": 2.113186415075929, "z": null, "yaw": 4.167593361518875, "pitch": null, "roll": null}, "v": 1.0756992055936554, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26535624808883096, "steering_wheel_angle": -8.163711449538651, "front_wheel_angle": -0.4268911337157763, "heading_rate": -0.19113141327155078, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141202.0018485} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22188290933864574, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.065925269016084, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.531627441010732, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141202.0018485} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.56995940208435, "x": 41.82076361751371, "y": 2.113186415075929, "z": null, "yaw": 4.167593361518875, "pitch": null, "roll": null}, "v": 1.0756992055936554, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26535624808883096, "steering_wheel_angle": -8.163711449538651, "front_wheel_angle": -0.4268911337157763, "heading_rate": -0.19113141327155078, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141202.0218484} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22188290933864574, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0646463685473286, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.577173725777826, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141202.0218484} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141202.0418484, "x": 45.75888124254921, "y": 7.0131223823104865, "z": null, "yaw": 4.147311583392119, "pitch": null, "roll": null}, "v": 1.0620913024202157, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2643849444677775, "steering_wheel_angle": -8.667970819200736, "front_wheel_angle": -0.4578654900333401, "heading_rate": -0.204449715758092, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141202.0418484} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23114957383162127, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0620913024202157, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.667970819200736, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141202.0418484} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.679959297180176, "x": 41.75888124254921, "y": 2.0131223823104865, "z": null, "yaw": 4.147311583392119, "pitch": null, "roll": null}, "v": 1.0620913024202157, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2643849444677775, "steering_wheel_angle": -8.667970819200736, "front_wheel_angle": -0.4578654900333401, "heading_rate": -0.204449715758092, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141202.0618484} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22666287012729575, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0597213692704943, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.803427769056908, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141202.0618484} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.679959297180176, "x": 41.75888124254921, "y": 2.0131223823104865, "z": null, "yaw": 4.147311583392119, "pitch": null, "roll": null}, "v": 1.0620913024202157, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2643849444677775, "steering_wheel_angle": -8.667970819200736, "front_wheel_angle": -0.4578654900333401, "heading_rate": -0.204449715758092, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141202.0818484} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22666287012729575, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0587456370307662, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.848383101601447, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141202.0818484} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.679959297180176, "x": 41.75888124254921, "y": 2.0131223823104865, "z": null, "yaw": 4.147311583392119, "pitch": null, "roll": null}, "v": 1.0620913024202157, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2643849444677775, "steering_wheel_angle": -8.667970819200736, "front_wheel_angle": -0.4578654900333401, "heading_rate": -0.204449715758092, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141202.1018484} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22666287012729575, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0567962555820007, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.937998290579248, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141202.1018484} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.679959297180176, "x": 41.75888124254921, "y": 2.0131223823104865, "z": null, "yaw": 4.147311583392119, "pitch": null, "roll": null}, "v": 1.0620913024202157, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2643849444677775, "steering_wheel_angle": -8.667970819200736, "front_wheel_angle": -0.4578654900333401, "heading_rate": -0.204449715758092, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141202.1218483} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22666287012729575, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0548496469477142, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.027219511408678, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141202.1218483} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.679959297180176, "x": 41.75888124254921, "y": 2.0131223823104865, "z": null, "yaw": 4.147311583392119, "pitch": null, "roll": null}, "v": 1.0620913024202157, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2643849444677775, "steering_wheel_angle": -8.667970819200736, "front_wheel_angle": -0.4578654900333401, "heading_rate": -0.204449715758092, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141202.1418483} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22666287012729575, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0529058056686598, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.116046764089738, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141202.1418483} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141202.1518483, "x": 45.695619724009894, "y": 6.915480143787171, "z": null, "yaw": 4.125377502426807, "pitch": null, "roll": null}, "v": 1.0519349210852202, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2636624168362467, "steering_wheel_angle": -9.160312652374627, "front_wheel_angle": -0.488839846350904, "heading_rate": -0.21856366072533573, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141202.1618483} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22624131513661663, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0480055982795446, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.33639128514327, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141202.1618483} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.789959192276, "x": 41.695619724009894, "y": 1.9154801437871711, "z": null, "yaw": 4.125377502426807, "pitch": null, "roll": null}, "v": 1.0519349210852202, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2636624168362467, "steering_wheel_angle": -9.160312652374627, "front_wheel_angle": -0.488839846350904, "heading_rate": -0.21856366072533573, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141202.1918483} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22638700595684041, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0480055982795446, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.33639128514327, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141202.1918483} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.789959192276, "x": 41.695619724009894, "y": 1.9154801437871711, "z": null, "yaw": 4.125377502426807, "pitch": null, "roll": null}, "v": 1.0519349210852202, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2636624168362467, "steering_wheel_angle": -9.160312652374627, "front_wheel_angle": -0.488839846350904, "heading_rate": -0.21856366072533573, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141202.2118483} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22638700595684041, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.045053753917379, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.467416093330279, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141202.2118483} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.789959192276, "x": 41.695619724009894, "y": 1.9154801437871711, "z": null, "yaw": 4.125377502426807, "pitch": null, "roll": null}, "v": 1.0519349210852202, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2636624168362467, "steering_wheel_angle": -9.160312652374627, "front_wheel_angle": -0.488839846350904, "heading_rate": -0.21856366072533573, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141202.2318482} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22638700595684041, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.043089344982266, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.55427350526949, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141202.2318482} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141202.2618482, "x": 45.63081871227869, "y": 6.820269868832263, "z": null, "yaw": 4.101738000859786, "pitch": null, "roll": null}, "v": 1.0411277194770463, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26289585525648707, "steering_wheel_angle": -9.64073694906033, "front_wheel_angle": -0.5198142026684679, "heading_rate": -0.232755143242352, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141202.2618482} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2293503290316292, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0403331564889582, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.68382093290011, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141202.2618482} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.899959087371826, "x": 41.63081871227869, "y": 1.8202698688322627, "z": null, "yaw": 4.101738000859786, "pitch": null, "roll": null}, "v": 1.0411277194770463, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26289585525648707, "steering_wheel_angle": -9.64073694906033, "front_wheel_angle": -0.5198142026684679, "heading_rate": -0.232755143242352, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141202.2718482} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22788081737966281, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0403331564889582, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.68382093290011, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141202.2718482} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.899959087371826, "x": 41.63081871227869, "y": 1.8202698688322627, "z": null, "yaw": 4.101738000859786, "pitch": null, "roll": null}, "v": 1.0411277194770463, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26289585525648707, "steering_wheel_angle": -9.64073694906033, "front_wheel_angle": -0.5198142026684679, "heading_rate": -0.232755143242352, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141202.2918482} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22788081737966281, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0376775029651855, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.8124819321969, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141202.2918482} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.899959087371826, "x": 41.63081871227869, "y": 1.8202698688322627, "z": null, "yaw": 4.101738000859786, "pitch": null, "roll": null}, "v": 1.0411277194770463, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26289585525648707, "steering_wheel_angle": -9.64073694906033, "front_wheel_angle": -0.5198142026684679, "heading_rate": -0.232755143242352, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141202.3118482} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22788081737966281, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0367935378399158, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.855171947888309, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141202.3118482} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.899959087371826, "x": 41.63081871227869, "y": 1.8202698688322627, "z": null, "yaw": 4.101738000859786, "pitch": null, "roll": null}, "v": 1.0411277194770463, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26289585525648707, "steering_wheel_angle": -9.64073694906033, "front_wheel_angle": -0.5198142026684679, "heading_rate": -0.232755143242352, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141202.3318481} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22788081737966281, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0350274830665593, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.940256503159855, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141202.3318481} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.899959087371826, "x": 41.63081871227869, "y": 1.8202698688322627, "z": null, "yaw": 4.101738000859786, "pitch": null, "roll": null}, "v": 1.0411277194770463, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26289585525648707, "steering_wheel_angle": -9.64073694906033, "front_wheel_angle": -0.5198142026684679, "heading_rate": -0.232755143242352, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141202.3518481} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22788081737966281, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0323830806329757, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.067144645788982, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141202.3518481} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141202.371848, "x": 45.56436700485335, "y": 6.727586891202685, "z": null, "yaw": 4.076333916183328, "pitch": null, "roll": null}, "v": 1.0315028586963704, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2622151244098064, "steering_wheel_angle": -10.109243709257836, "front_wheel_angle": -0.5507885589860317, "heading_rate": -0.24747635873555401, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141202.371848} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23059038942837154, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0315028586963704, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.109243709257836, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141202.371848} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.00995898246765, "x": 41.56436700485335, "y": 1.7275868912026846, "z": null, "yaw": 4.076333916183328, "pitch": null, "roll": null}, "v": 1.0315028586963704, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2622151244098064, "steering_wheel_angle": -10.109243709257836, "front_wheel_angle": -0.5507885589860317, "heading_rate": -0.24747635873555401, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141202.391848} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22924825114640165, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.029373607329508, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.23494994744185, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141202.391848} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.00995898246765, "x": 41.56436700485335, "y": 1.7275868912026846, "z": null, "yaw": 4.076333916183328, "pitch": null, "roll": null}, "v": 1.0315028586963704, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2622151244098064, "steering_wheel_angle": -10.109243709257836, "front_wheel_angle": -0.5507885589860317, "heading_rate": -0.24747635873555401, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141202.411848} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22924825114640165, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0277889025469282, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.318261646045734, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141202.411848} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.00995898246765, "x": 41.56436700485335, "y": 1.7275868912026846, "z": null, "yaw": 4.076333916183328, "pitch": null, "roll": null}, "v": 1.0315028586963704, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2622151244098064, "steering_wheel_angle": -10.109243709257836, "front_wheel_angle": -0.5507885589860317, "heading_rate": -0.24747635873555401, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141202.431848} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22924825114640165, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0262064334280823, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.401179376501242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141202.431848} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.00995898246765, "x": 41.56436700485335, "y": 1.7275868912026846, "z": null, "yaw": 4.076333916183328, "pitch": null, "roll": null}, "v": 1.0315028586963704, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2622151244098064, "steering_wheel_angle": -10.109243709257836, "front_wheel_angle": -0.5507885589860317, "heading_rate": -0.24747635873555401, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141202.451848} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22924825114640165, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0246261958176186, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141202.451848} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.00995898246765, "x": 41.56436700485335, "y": 1.7275868912026846, "z": null, "yaw": 4.076333916183328, "pitch": null, "roll": null}, "v": 1.0315028586963704, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2622151244098064, "steering_wheel_angle": -10.109243709257836, "front_wheel_angle": -0.5507885589860317, "heading_rate": -0.24747635873555401, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141202.471848} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22924825114640165, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0238369125322444, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141202.471848} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141202.481848, "x": 45.496108198801245, "y": 6.637471837764666, "z": null, "yaw": 4.049146275079782, "pitch": null, "roll": null}, "v": 1.023048185570282, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26161868517850057, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.25802233536423935, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141202.491848} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23583000266910678, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0214723985508825, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141202.491848} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.11995887756348, "x": 41.496108198801245, "y": 1.6374718377646662, "z": null, "yaw": 4.049146275079782, "pitch": null, "roll": null}, "v": 1.023048185570282, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26161868517850057, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.25802233536423935, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141202.511848} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23265039069993548, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0207212599042306, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141202.511848} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.11995887756348, "x": 41.496108198801245, "y": 1.6374718377646662, "z": null, "yaw": 4.049146275079782, "pitch": null, "roll": null}, "v": 1.023048185570282, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26161868517850057, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.25802233536423935, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141202.531848} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23265039069993548, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0201473615039824, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141202.531848} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.11995887756348, "x": 41.496108198801245, "y": 1.6374718377646662, "z": null, "yaw": 4.049146275079782, "pitch": null, "roll": null}, "v": 1.023048185570282, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26161868517850057, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.25802233536423935, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141202.551848} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23265039069993548, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0184280893483433, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141202.551848} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.11995887756348, "x": 41.496108198801245, "y": 1.6374718377646662, "z": null, "yaw": 4.049146275079782, "pitch": null, "roll": null}, "v": 1.023048185570282, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26161868517850057, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.25802233536423935, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141202.571848} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23265039069993548, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0172839236172644, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141202.571848} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141202.591848, "x": 45.42591788498981, "y": 6.549931261084468, "z": null, "yaw": 4.021403244702146, "pitch": null, "roll": null}, "v": 1.0167124444160767, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.261172664167109, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.2564244020978213, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141202.591848} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24966121187963944, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0167124444160767, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141202.591848} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.2299587726593, "x": 41.42591788498981, "y": 1.5499312610844678, "z": null, "yaw": 4.021403244702146, "pitch": null, "roll": null}, "v": 1.0167124444160767, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.261172664167109, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.2564244020978213, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141202.6118479} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24152683422495927, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.018187703498318, "gear": 1, "accelerator_pedal_position": 0.24966121187963944, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141202.6118479} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.2299587726593, "x": 41.42591788498981, "y": 1.5499312610844678, "z": null, "yaw": 4.021403244702146, "pitch": null, "roll": null}, "v": 1.0167124444160767, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.261172664167109, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.2564244020978213, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141202.6318479} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24152683422495927, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0181703661656734, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141202.6318479} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.2299587726593, "x": 41.42591788498981, "y": 1.5499312610844678, "z": null, "yaw": 4.021403244702146, "pitch": null, "roll": null}, "v": 1.0167124444160767, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.261172664167109, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.2564244020978213, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141202.6518478} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24152683422495927, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0181184273281785, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141202.6518478} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.2299587726593, "x": 41.42591788498981, "y": 1.5499312610844678, "z": null, "yaw": 4.021403244702146, "pitch": null, "roll": null}, "v": 1.0167124444160767, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.261172664167109, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.2564244020978213, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141202.6718478} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24152683422495927, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0181011387403678, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141202.6718478} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.2299587726593, "x": 41.42591788498981, "y": 1.5499312610844678, "z": null, "yaw": 4.021403244702146, "pitch": null, "roll": null}, "v": 1.0167124444160767, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.261172664167109, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.2564244020978213, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141202.6918478} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24152683422495927, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0180665980500174, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141202.6918478} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141202.7018478, "x": 45.35348179916213, "y": 6.464557559479596, "z": null, "yaw": 3.993660214324508, "pitch": null, "roll": null}, "v": 1.0180493459302458, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2612667120040023, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.2567615811825441, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141202.7118478} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2545994927969253, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0188319192592246, "gear": 1, "accelerator_pedal_position": 0.2545994927969253, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141202.7118478} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.33995866775513, "x": 41.35348179916213, "y": 1.464557559479596, "z": null, "yaw": 3.993660214324508, "pitch": null, "roll": null}, "v": 1.0180493459302458, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2612667120040023, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.2567615811825441, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141202.7318478} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2483815797298236, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0196311697514326, "gear": 1, "accelerator_pedal_position": 0.2545994927969253, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141202.7318478} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.33995866775513, "x": 41.35348179916213, "y": 1.464557559479596, "z": null, "yaw": 3.993660214324508, "pitch": null, "roll": null}, "v": 1.0180493459302458, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2612667120040023, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.2567615811825441, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141202.7518477} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2483815797298236, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0204510178287403, "gear": 1, "accelerator_pedal_position": 0.2483815797298236, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141202.7518477} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.33995866775513, "x": 41.35348179916213, "y": 1.464557559479596, "z": null, "yaw": 3.993660214324508, "pitch": null, "roll": null}, "v": 1.0180493459302458, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2612667120040023, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.2567615811825441, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141202.7718477} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2483815797298236, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.021269711885674, "gear": 1, "accelerator_pedal_position": 0.2483815797298236, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141202.7718477} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.33995866775513, "x": 41.35348179916213, "y": 1.464557559479596, "z": null, "yaw": 3.993660214324508, "pitch": null, "roll": null}, "v": 1.0180493459302458, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2612667120040023, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.2567615811825441, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141202.7918477} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2483815797298236, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0220872532786263, "gear": 1, "accelerator_pedal_position": 0.2483815797298236, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141202.7918477} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141202.8118477, "x": 45.27852564882235, "y": 6.381027271179486, "z": null, "yaw": 3.9659171839468668, "pitch": null, "roll": null}, "v": 1.022903643363212, "accelerator_pedal_position": 0.2483815797298236, "brake_pedal_position": 0.0, "acceleration": 0.04077637250717958, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.2579858804656794, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141202.8118477} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25981193884315257, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0233114070882838, "gear": 1, "accelerator_pedal_position": 0.2483815797298236, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141202.8118477} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.44995856285095, "x": 41.27852564882235, "y": 1.3810272711794864, "z": null, "yaw": 3.9659171839468668, "pitch": null, "roll": null}, "v": 1.022903643363212, "accelerator_pedal_position": 0.2483815797298236, "brake_pedal_position": 0.0, "acceleration": 0.04077637250717958, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.2579858804656794, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141202.8318477} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2543949490393702, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.024433280938849, "gear": 1, "accelerator_pedal_position": 0.25981193884315257, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141202.8318477} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.44995856285095, "x": 41.27852564882235, "y": 1.3810272711794864, "z": null, "yaw": 3.9659171839468668, "pitch": null, "roll": null}, "v": 1.022903643363212, "accelerator_pedal_position": 0.2483815797298236, "brake_pedal_position": 0.0, "acceleration": 0.04077637250717958, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.2579858804656794, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141202.8518476} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2543949490393702, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.025997771928342, "gear": 1, "accelerator_pedal_position": 0.2543949490393702, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141202.8518476} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.44995856285095, "x": 41.27852564882235, "y": 1.3810272711794864, "z": null, "yaw": 3.9659171839468668, "pitch": null, "roll": null}, "v": 1.022903643363212, "accelerator_pedal_position": 0.2483815797298236, "brake_pedal_position": 0.0, "acceleration": 0.04077637250717958, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.2579858804656794, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141202.8718476} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2543949490393702, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0283403737029615, "gear": 1, "accelerator_pedal_position": 0.2543949490393702, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141202.8718476} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.44995856285095, "x": 41.27852564882235, "y": 1.3810272711794864, "z": null, "yaw": 3.9659171839468668, "pitch": null, "roll": null}, "v": 1.022903643363212, "accelerator_pedal_position": 0.2483815797298236, "brake_pedal_position": 0.0, "acceleration": 0.04077637250717958, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.2579858804656794, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141202.8918476} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2543949490393702, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0298993548577535, "gear": 1, "accelerator_pedal_position": 0.2543949490393702, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141202.8918476} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.44995856285095, "x": 41.27852564882235, "y": 1.3810272711794864, "z": null, "yaw": 3.9659171839468668, "pitch": null, "roll": null}, "v": 1.022903643363212, "accelerator_pedal_position": 0.2483815797298236, "brake_pedal_position": 0.0, "acceleration": 0.04077637250717958, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.2579858804656794, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141202.9118476} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2543949490393702, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0314561358138807, "gear": 1, "accelerator_pedal_position": 0.2543949490393702, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141202.9118476} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141202.9218476, "x": 45.200793255559375, "y": 6.299095304126485, "z": null, "yaw": 3.9381741535692254, "pitch": null, "roll": null}, "v": 1.0314561358138807, "accelerator_pedal_position": 0.2543949490393702, "brake_pedal_position": 0.0, "acceleration": 0.07775660710428872, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.2601428991735289, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141202.9318476} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2640211032313264, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0322337018849237, "gear": 1, "accelerator_pedal_position": 0.2543949490393702, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141202.9318476} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.55995845794678, "x": 41.200793255559375, "y": 1.2990953041264852, "z": null, "yaw": 3.9381741535692254, "pitch": null, "roll": null}, "v": 1.0314561358138807, "accelerator_pedal_position": 0.2543949490393702, "brake_pedal_position": 0.0, "acceleration": 0.07775660710428872, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.2601428991735289, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141202.9518476} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2594831855273206, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0357659497035445, "gear": 1, "accelerator_pedal_position": 0.2640211032313264, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141202.9518476} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.55995845794678, "x": 41.200793255559375, "y": 1.2990953041264852, "z": null, "yaw": 3.9381741535692254, "pitch": null, "roll": null}, "v": 1.0314561358138807, "accelerator_pedal_position": 0.2543949490393702, "brake_pedal_position": 0.0, "acceleration": 0.07775660710428872, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.2601428991735289, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141202.9718475} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2594831855273206, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.037950247015262, "gear": 1, "accelerator_pedal_position": 0.2594831855273206, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141202.9718475} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.55995845794678, "x": 41.200793255559375, "y": 1.2990953041264852, "z": null, "yaw": 3.9381741535692254, "pitch": null, "roll": null}, "v": 1.0314561358138807, "accelerator_pedal_position": 0.2543949490393702, "brake_pedal_position": 0.0, "acceleration": 0.07775660710428872, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.2601428991735289, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141202.9918475} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2594831855273206, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0401314547234823, "gear": 1, "accelerator_pedal_position": 0.2594831855273206, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141202.9918475} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.55995845794678, "x": 41.200793255559375, "y": 1.2990953041264852, "z": null, "yaw": 3.9381741535692254, "pitch": null, "roll": null}, "v": 1.0314561358138807, "accelerator_pedal_position": 0.2543949490393702, "brake_pedal_position": 0.0, "acceleration": 0.07775660710428872, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.2601428991735289, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141203.0118475} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2594831855273206, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0412209007472677, "gear": 1, "accelerator_pedal_position": 0.2594831855273206, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141203.0118475} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141203.0318475, "x": 45.12003757514063, "y": 6.218574176583067, "z": null, "yaw": 3.910431123191584, "pitch": null, "roll": null}, "v": 1.0433974786786706, "accelerator_pedal_position": 0.2594831855273206, "brake_pedal_position": 0.0, "acceleration": 0.10871325262668996, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.26315461769941695, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141203.0318475} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0444846112049375, "gear": 1, "accelerator_pedal_position": 0.2594831855273206, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141203.0318475} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.6699583530426, "x": 41.12003757514063, "y": 1.2185741765830667, "z": null, "yaw": 3.910431123191584, "pitch": null, "roll": null}, "v": 1.0433974786786706, "accelerator_pedal_position": 0.2594831855273206, "brake_pedal_position": 0.0, "acceleration": 0.10871325262668996, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.26315461769941695, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141203.0518475} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23534085009263972, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0418532740890307, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141203.0518475} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.6699583530426, "x": 41.12003757514063, "y": 1.2185741765830667, "z": null, "yaw": 3.910431123191584, "pitch": null, "roll": null}, "v": 1.0433974786786706, "accelerator_pedal_position": 0.2594831855273206, "brake_pedal_position": 0.0, "acceleration": 0.10871325262668996, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.26315461769941695, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141203.0718474} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23534085009263972, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0410122333996885, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141203.0718474} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.6699583530426, "x": 41.12003757514063, "y": 1.2185741765830667, "z": null, "yaw": 3.910431123191584, "pitch": null, "roll": null}, "v": 1.0433974786786706, "accelerator_pedal_position": 0.2594831855273206, "brake_pedal_position": 0.0, "acceleration": 0.10871325262668996, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.26315461769941695, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141203.0918474} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23534085009263972, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0397529046935996, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141203.0918474} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.6699583530426, "x": 41.12003757514063, "y": 1.2185741765830667, "z": null, "yaw": 3.910431123191584, "pitch": null, "roll": null}, "v": 1.0433974786786706, "accelerator_pedal_position": 0.2594831855273206, "brake_pedal_position": 0.0, "acceleration": 0.10871325262668996, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.26315461769941695, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141203.1118474} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23534085009263972, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.038914837572443, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141203.1118474} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.6699583530426, "x": 41.12003757514063, "y": 1.2185741765830667, "z": null, "yaw": 3.910431123191584, "pitch": null, "roll": null}, "v": 1.0433974786786706, "accelerator_pedal_position": 0.2594831855273206, "brake_pedal_position": 0.0, "acceleration": 0.10871325262668996, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.26315461769941695, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141203.1318474} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23534085009263972, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.038496248880474, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141203.1318474} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141203.1418474, "x": 45.03675462038544, "y": 6.14001153467595, "z": null, "yaw": 3.8826880928139427, "pitch": null, "roll": null}, "v": 1.03807795644093, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2626799562585323, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.2618129843627245, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141203.1518474} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23965932328054015, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0372422593406594, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141203.1518474} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.77995824813843, "x": 41.03675462038544, "y": 1.14001153467595, "z": null, "yaw": 3.8826880928139427, "pitch": null, "roll": null}, "v": 1.03807795644093, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2626799562585323, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.2618129843627245, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141203.1718473} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23757420543246344, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0369473625373515, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141203.1718473} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.77995824813843, "x": 41.03675462038544, "y": 1.14001153467595, "z": null, "yaw": 3.8826880928139427, "pitch": null, "roll": null}, "v": 1.03807795644093, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2626799562585323, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.2618129843627245, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141203.1918473} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23757420543246344, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0363923352593132, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141203.1918473} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.77995824813843, "x": 41.03675462038544, "y": 1.14001153467595, "z": null, "yaw": 3.8826880928139427, "pitch": null, "roll": null}, "v": 1.03807795644093, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2626799562585323, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.2618129843627245, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141203.2118473} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23757420543246344, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0358380928521058, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141203.2118473} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.77995824813843, "x": 41.03675462038544, "y": 1.14001153467595, "z": null, "yaw": 3.8826880928139427, "pitch": null, "roll": null}, "v": 1.03807795644093, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2626799562585323, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.2618129843627245, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141203.2318473} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23757420543246344, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0355612655897484, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141203.2318473} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141203.2518473, "x": 44.951671337182646, "y": 6.064099855467537, "z": null, "yaw": 3.8549450624363013, "pitch": null, "roll": null}, "v": 1.035008198178134, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2624628296118662, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.2610387625742085, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141203.2518473} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24627423850275704, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0347319577215444, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141203.2518473} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.88995814323425, "x": 40.951671337182646, "y": 1.0640998554675374, "z": null, "yaw": 3.8549450624363013, "pitch": null, "roll": null}, "v": 1.035008198178134, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2624628296118662, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.2610387625742085, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141203.2718472} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2421148205517269, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.035267182270204, "gear": 1, "accelerator_pedal_position": 0.24627423850275704, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141203.2718472} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.88995814323425, "x": 40.951671337182646, "y": 1.0640998554675374, "z": null, "yaw": 3.8549450624363013, "pitch": null, "roll": null}, "v": 1.035008198178134, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2624628296118662, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.2610387625742085, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141203.2918472} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2421148205517269, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0352819068217936, "gear": 1, "accelerator_pedal_position": 0.2421148205517269, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141203.2918472} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.88995814323425, "x": 40.951671337182646, "y": 1.0640998554675374, "z": null, "yaw": 3.8549450624363013, "pitch": null, "roll": null}, "v": 1.035008198178134, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2624628296118662, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.2610387625742085, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141203.3118472} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2421148205517269, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.03529661055859, "gear": 1, "accelerator_pedal_position": 0.2421148205517269, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141203.3118472} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.88995814323425, "x": 40.951671337182646, "y": 1.0640998554675374, "z": null, "yaw": 3.8549450624363013, "pitch": null, "roll": null}, "v": 1.035008198178134, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2624628296118662, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.2610387625742085, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141203.3318472} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2421148205517269, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0353112935099305, "gear": 1, "accelerator_pedal_position": 0.2421148205517269, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141203.3318472} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.88995814323425, "x": 40.951671337182646, "y": 1.0640998554675374, "z": null, "yaw": 3.8549450624363013, "pitch": null, "roll": null}, "v": 1.035008198178134, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2624628296118662, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.2610387625742085, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141203.3518472} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2421148205517269, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0353259557051115, "gear": 1, "accelerator_pedal_position": 0.2421148205517269, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141203.3518472} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141203.3618472, "x": 44.864635260981665, "y": 5.9906800822543556, "z": null, "yaw": 3.82720203205866, "pitch": null, "roll": null}, "v": 1.0353259557051115, "accelerator_pedal_position": 0.2421148205517269, "brake_pedal_position": 0.0, "acceleration": 0.0007323323174703855, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.26111890399896903, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141203.3718472} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24597246111472676, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0353332790282863, "gear": 1, "accelerator_pedal_position": 0.2421148205517269, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141203.3718472} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.99995803833008, "x": 40.864635260981665, "y": 0.9906800822543556, "z": null, "yaw": 3.82720203205866, "pitch": null, "roll": null}, "v": 1.0353259557051115, "accelerator_pedal_position": 0.2421148205517269, "brake_pedal_position": 0.0, "acceleration": 0.0007323323174703855, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.26111890399896903, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141203.3918471} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24413720023604482, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0358299447327153, "gear": 1, "accelerator_pedal_position": 0.24597246111472676, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141203.3918471} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.99995803833008, "x": 40.864635260981665, "y": 0.9906800822543556, "z": null, "yaw": 3.82720203205866, "pitch": null, "roll": null}, "v": 1.0353259557051115, "accelerator_pedal_position": 0.2421148205517269, "brake_pedal_position": 0.0, "acceleration": 0.0007323323174703855, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.26111890399896903, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141203.411847} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24413720023604482, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.036229758880352, "gear": 1, "accelerator_pedal_position": 0.24413720023604482, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141203.411847} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.99995803833008, "x": 40.864635260981665, "y": 0.9906800822543556, "z": null, "yaw": 3.82720203205866, "pitch": null, "roll": null}, "v": 1.0353259557051115, "accelerator_pedal_position": 0.2421148205517269, "brake_pedal_position": 0.0, "acceleration": 0.0007323323174703855, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.26111890399896903, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141203.431847} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24413720023604482, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0363628418043456, "gear": 1, "accelerator_pedal_position": 0.24413720023604482, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141203.431847} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.99995803833008, "x": 40.864635260981665, "y": 0.9906800822543556, "z": null, "yaw": 3.82720203205866, "pitch": null, "roll": null}, "v": 1.0353259557051115, "accelerator_pedal_position": 0.2421148205517269, "brake_pedal_position": 0.0, "acceleration": 0.0007323323174703855, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.26111890399896903, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141203.451847} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24413720023604482, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0367615260836343, "gear": 1, "accelerator_pedal_position": 0.24413720023604482, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141203.451847} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141203.471847, "x": 44.77552138105827, "y": 5.919643746669005, "z": null, "yaw": 3.7994590016810186, "pitch": null, "roll": null}, "v": 1.0368942328891486, "accelerator_pedal_position": 0.24413720023604482, "brake_pedal_position": 0.0, "acceleration": 0.013261293328834856, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.26151443819494447, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141203.471847} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2495970519471779, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.037026845822437, "gear": 1, "accelerator_pedal_position": 0.24413720023604482, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141203.471847} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.1099579334259, "x": 40.77552138105827, "y": 0.9196437466690046, "z": null, "yaw": 3.7994590016810186, "pitch": null, "roll": null}, "v": 1.0368942328891486, "accelerator_pedal_position": 0.24413720023604482, "brake_pedal_position": 0.0, "acceleration": 0.013261293328834856, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.26151443819494447, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141203.491847} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.247005571705652, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.03797403037151, "gear": 1, "accelerator_pedal_position": 0.2495970519471779, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141203.491847} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.1099579334259, "x": 40.77552138105827, "y": 0.9196437466690046, "z": null, "yaw": 3.7994590016810186, "pitch": null, "roll": null}, "v": 1.0368942328891486, "accelerator_pedal_position": 0.24413720023604482, "brake_pedal_position": 0.0, "acceleration": 0.013261293328834856, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.26151443819494447, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141203.511847} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.247005571705652, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0382851525791548, "gear": 1, "accelerator_pedal_position": 0.247005571705652, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141203.511847} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.1099579334259, "x": 40.77552138105827, "y": 0.9196437466690046, "z": null, "yaw": 3.7994590016810186, "pitch": null, "roll": null}, "v": 1.0368942328891486, "accelerator_pedal_position": 0.24413720023604482, "brake_pedal_position": 0.0, "acceleration": 0.013261293328834856, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.26151443819494447, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141203.531847} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.247005571705652, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0392171987990098, "gear": 1, "accelerator_pedal_position": 0.247005571705652, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141203.531847} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.1099579334259, "x": 40.77552138105827, "y": 0.9196437466690046, "z": null, "yaw": 3.7994590016810186, "pitch": null, "roll": null}, "v": 1.0368942328891486, "accelerator_pedal_position": 0.24413720023604482, "brake_pedal_position": 0.0, "acceleration": 0.013261293328834856, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.26151443819494447, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141203.561847} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.247005571705652, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.039837463973493, "gear": 1, "accelerator_pedal_position": 0.247005571705652, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141203.561847} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.1099579334259, "x": 40.77552138105827, "y": 0.9196437466690046, "z": null, "yaw": 3.7994590016810186, "pitch": null, "roll": null}, "v": 1.0368942328891486, "accelerator_pedal_position": 0.24413720023604482, "brake_pedal_position": 0.0, "acceleration": 0.013261293328834856, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.26151443819494447, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141203.571847} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.247005571705652, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0401472672779613, "gear": 1, "accelerator_pedal_position": 0.247005571705652, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141203.571847} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141203.581847, "x": 44.68425284169525, "y": 5.8509429277244625, "z": null, "yaw": 3.771715971303377, "pitch": null, "roll": null}, "v": 1.040456851242163, "accelerator_pedal_position": 0.247005571705652, "brake_pedal_position": 0.0, "acceleration": 0.03093647600524907, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.2624129639148683, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141203.591847} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2476509850016396, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0410753616941806, "gear": 1, "accelerator_pedal_position": 0.247005571705652, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141203.591847} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.21995782852173, "x": 40.68425284169525, "y": 0.8509429277244625, "z": null, "yaw": 3.771715971303377, "pitch": null, "roll": null}, "v": 1.040456851242163, "accelerator_pedal_position": 0.247005571705652, "brake_pedal_position": 0.0, "acceleration": 0.03093647600524907, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.2624129639148683, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141203.611847} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2473628557840842, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0417736445089458, "gear": 1, "accelerator_pedal_position": 0.2476509850016396, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141203.611847} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.21995782852173, "x": 40.68425284169525, "y": 0.8509429277244625, "z": null, "yaw": 3.771715971303377, "pitch": null, "roll": null}, "v": 1.040456851242163, "accelerator_pedal_position": 0.247005571705652, "brake_pedal_position": 0.0, "acceleration": 0.03093647600524907, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.2624129639148683, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141203.631847} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2473628557840842, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0424349350640956, "gear": 1, "accelerator_pedal_position": 0.2473628557840842, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141203.631847} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.21995782852173, "x": 40.68425284169525, "y": 0.8509429277244625, "z": null, "yaw": 3.771715971303377, "pitch": null, "roll": null}, "v": 1.040456851242163, "accelerator_pedal_position": 0.247005571705652, "brake_pedal_position": 0.0, "acceleration": 0.03093647600524907, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.2624129639148683, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141203.651847} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2473628557840842, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.043095288963392, "gear": 1, "accelerator_pedal_position": 0.2473628557840842, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141203.651847} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.21995782852173, "x": 40.68425284169525, "y": 0.8509429277244625, "z": null, "yaw": 3.771715971303377, "pitch": null, "roll": null}, "v": 1.040456851242163, "accelerator_pedal_position": 0.247005571705652, "brake_pedal_position": 0.0, "acceleration": 0.03093647600524907, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.2624129639148683, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141203.6718469} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2473628557840842, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0434251150272298, "gear": 1, "accelerator_pedal_position": 0.2473628557840842, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141203.6718469} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141203.6918468, "x": 44.59079440491641, "y": 5.784573531249784, "z": null, "yaw": 3.743972940925736, "pitch": null, "roll": null}, "v": 1.0440840661030666, "accelerator_pedal_position": 0.2473628557840842, "brake_pedal_position": 0.0, "acceleration": 0.03291252997446975, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.2633277814791617, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141203.6918468} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25287346122496557, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0444131914028112, "gear": 1, "accelerator_pedal_position": 0.2473628557840842, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141203.6918468} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.329957723617554, "x": 40.59079440491641, "y": 0.7845735312497837, "z": null, "yaw": 3.743972940925736, "pitch": null, "roll": null}, "v": 1.0440840661030666, "accelerator_pedal_position": 0.2473628557840842, "brake_pedal_position": 0.0, "acceleration": 0.03291252997446975, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.2633277814791617, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141203.7118468} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25026894087745366, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0457593237422091, "gear": 1, "accelerator_pedal_position": 0.25287346122496557, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141203.7118468} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.329957723617554, "x": 40.59079440491641, "y": 0.7845735312497837, "z": null, "yaw": 3.743972940925736, "pitch": null, "roll": null}, "v": 1.0440840661030666, "accelerator_pedal_position": 0.2473628557840842, "brake_pedal_position": 0.0, "acceleration": 0.03291252997446975, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.2633277814791617, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141203.7318468} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25026894087745366, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.046778098128527, "gear": 1, "accelerator_pedal_position": 0.25026894087745366, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141203.7318468} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.329957723617554, "x": 40.59079440491641, "y": 0.7845735312497837, "z": null, "yaw": 3.743972940925736, "pitch": null, "roll": null}, "v": 1.0440840661030666, "accelerator_pedal_position": 0.2473628557840842, "brake_pedal_position": 0.0, "acceleration": 0.03291252997446975, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.2633277814791617, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141203.7518468} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25026894087745366, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0477954277845585, "gear": 1, "accelerator_pedal_position": 0.25026894087745366, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141203.7518468} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.329957723617554, "x": 40.59079440491641, "y": 0.7845735312497837, "z": null, "yaw": 3.743972940925736, "pitch": null, "roll": null}, "v": 1.0440840661030666, "accelerator_pedal_position": 0.2473628557840842, "brake_pedal_position": 0.0, "acceleration": 0.03291252997446975, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.2633277814791617, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141203.7718468} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25026894087745366, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.048811314345247, "gear": 1, "accelerator_pedal_position": 0.25026894087745366, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141203.7718468} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.329957723617554, "x": 40.59079440491641, "y": 0.7845735312497837, "z": null, "yaw": 3.743972940925736, "pitch": null, "roll": null}, "v": 1.0440840661030666, "accelerator_pedal_position": 0.2473628557840842, "brake_pedal_position": 0.0, "acceleration": 0.03291252997446975, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.2633277814791617, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141203.7918468} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25026894087745366, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0493187169756055, "gear": 1, "accelerator_pedal_position": 0.25026894087745366, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141203.7918468} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141203.8018467, "x": 44.49510815597043, "y": 5.720539932799471, "z": null, "yaw": 3.7162299105480945, "pitch": null, "roll": null}, "v": 1.0498257594449791, "accelerator_pedal_position": 0.25026894087745366, "brake_pedal_position": 0.0, "acceleration": 0.050668251259894104, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.26477589032283244, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141203.8118467} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25542455921556106, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.834262457018296, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0508387647175774, "gear": 1, "accelerator_pedal_position": 0.25026894087745366, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141203.8118467} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.43995761871338, "x": 40.49510815597043, "y": 0.720539932799471, "z": null, "yaw": 3.7162299105480945, "pitch": null, "roll": null}, "v": 1.0498257594449791, "accelerator_pedal_position": 0.25026894087745366, "brake_pedal_position": 0.0, "acceleration": 0.050668251259894104, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.26477589032283244, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141203.8318467} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25300053483779505, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.834262457018296, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0524945552109535, "gear": 1, "accelerator_pedal_position": 0.25542455921556106, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141203.8318467} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.43995761871338, "x": 40.49510815597043, "y": 0.720539932799471, "z": null, "yaw": 3.7162299105480945, "pitch": null, "roll": null}, "v": 1.0498257594449791, "accelerator_pedal_position": 0.25026894087745366, "brake_pedal_position": 0.0, "acceleration": 0.050668251259894104, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.26477589032283244, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141203.8518467} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25300053483779505, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.834262457018296, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0531700668818353, "gear": 1, "accelerator_pedal_position": 0.25300053483779505, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141203.8518467} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.43995761871338, "x": 40.49510815597043, "y": 0.720539932799471, "z": null, "yaw": 3.7162299105480945, "pitch": null, "roll": null}, "v": 1.0498257594449791, "accelerator_pedal_position": 0.25026894087745366, "brake_pedal_position": 0.0, "acceleration": 0.050668251259894104, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.26477589032283244, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141203.8718467} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25300053483779505, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.834262457018296, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0551937229184811, "gear": 1, "accelerator_pedal_position": 0.25300053483779505, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141203.8718467} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.43995761871338, "x": 40.49510815597043, "y": 0.720539932799471, "z": null, "yaw": 3.7162299105480945, "pitch": null, "roll": null}, "v": 1.0498257594449791, "accelerator_pedal_position": 0.25026894087745366, "brake_pedal_position": 0.0, "acceleration": 0.050668251259894104, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.26477589032283244, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141203.8918467} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25300053483779505, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.834262457018296, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0558673161050953, "gear": 1, "accelerator_pedal_position": 0.25300053483779505, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141203.8918467} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141203.9118466, "x": 44.39708664320925, "y": 5.6588105398694255, "z": null, "yaw": 3.688486880170453, "pitch": null, "roll": null}, "v": 1.0572130657396126, "accelerator_pedal_position": 0.25300053483779505, "brake_pedal_position": 0.0, "acceleration": 0.06721569478553291, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.26663903816775014, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141203.9118466} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26223954477011147, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.560271408724656, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.057885222687468, "gear": 1, "accelerator_pedal_position": 0.25300053483779505, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141203.9118466} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.549957513809204, "x": 40.39708664320925, "y": 0.6588105398694255, "z": null, "yaw": 3.688486880170453, "pitch": null, "roll": null}, "v": 1.0572130657396126, "accelerator_pedal_position": 0.25300053483779505, "brake_pedal_position": 0.0, "acceleration": 0.06721569478553291, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.26663903816775014, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141203.9318466} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2578800154799184, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.560271408724656, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.059134339509818, "gear": 1, "accelerator_pedal_position": 0.26223954477011147, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141203.9318466} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.549957513809204, "x": 40.39708664320925, "y": 0.6588105398694255, "z": null, "yaw": 3.688486880170453, "pitch": null, "roll": null}, "v": 1.0572130657396126, "accelerator_pedal_position": 0.25300053483779505, "brake_pedal_position": 0.0, "acceleration": 0.06721569478553291, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.26663903816775014, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141203.9518466} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2578800154799184, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.560271408724656, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.062059527546335, "gear": 1, "accelerator_pedal_position": 0.2578800154799184, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141203.9518466} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.549957513809204, "x": 40.39708664320925, "y": 0.6588105398694255, "z": null, "yaw": 3.688486880170453, "pitch": null, "roll": null}, "v": 1.0572130657396126, "accelerator_pedal_position": 0.25300053483779505, "brake_pedal_position": 0.0, "acceleration": 0.06721569478553291, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.26663903816775014, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141203.9718466} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2578800154799184, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.560271408724656, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0640061821139004, "gear": 1, "accelerator_pedal_position": 0.2578800154799184, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141203.9718466} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.549957513809204, "x": 40.39708664320925, "y": 0.6588105398694255, "z": null, "yaw": 3.688486880170453, "pitch": null, "roll": null}, "v": 1.0572130657396126, "accelerator_pedal_position": 0.25300053483779505, "brake_pedal_position": 0.0, "acceleration": 0.06721569478553291, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.26663903816775014, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141203.9918466} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2578800154799184, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.560271408724656, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0649784690747808, "gear": 1, "accelerator_pedal_position": 0.2578800154799184, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141203.9918466} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.549957513809204, "x": 40.39708664320925, "y": 0.6588105398694255, "z": null, "yaw": 3.688486880170453, "pitch": null, "roll": null}, "v": 1.0572130657396126, "accelerator_pedal_position": 0.25300053483779505, "brake_pedal_position": 0.0, "acceleration": 0.06721569478553291, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.26663903816775014, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141204.0118465} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2578800154799184, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.560271408724656, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0678911723274098, "gear": 1, "accelerator_pedal_position": 0.2578800154799184, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141204.0118465} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141204.0218465, "x": 44.29654599984664, "y": 5.599325226359849, "z": null, "yaw": 3.6607438497928118, "pitch": null, "roll": null}, "v": 1.0678911723274098, "accelerator_pedal_position": 0.2578800154799184, "brake_pedal_position": 0.0, "acceleration": 0.09695162257377132, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.2693321566717587, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141204.0318465} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25771718761273965, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.140969833465734, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0698295128592124, "gear": 1, "accelerator_pedal_position": 0.2578800154799184, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141204.0318465} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.65995740890503, "x": 40.29654599984664, "y": 0.5993252263598494, "z": null, "yaw": 3.6607438497928118, "pitch": null, "roll": null}, "v": 1.0678911723274098, "accelerator_pedal_position": 0.2578800154799184, "brake_pedal_position": 0.0, "acceleration": 0.09695162257377132, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.2693321566717587, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141204.0518465} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2578526924724226, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.140969833465734, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.071744740720976, "gear": 1, "accelerator_pedal_position": 0.25771718761273965, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141204.0518465} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.65995740890503, "x": 40.29654599984664, "y": 0.5993252263598494, "z": null, "yaw": 3.6607438497928118, "pitch": null, "roll": null}, "v": 1.0678911723274098, "accelerator_pedal_position": 0.2578800154799184, "brake_pedal_position": 0.0, "acceleration": 0.09695162257377132, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.2693321566717587, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141204.0718465} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2578526924724226, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.140969833465734, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0727097979512155, "gear": 1, "accelerator_pedal_position": 0.2578526924724226, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141204.0718465} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.65995740890503, "x": 40.29654599984664, "y": 0.5993252263598494, "z": null, "yaw": 3.6607438497928118, "pitch": null, "roll": null}, "v": 1.0678911723274098, "accelerator_pedal_position": 0.2578800154799184, "brake_pedal_position": 0.0, "acceleration": 0.09695162257377132, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.2693321566717587, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141204.0918465} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2578526924724226, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.140969833465734, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.074637844275971, "gear": 1, "accelerator_pedal_position": 0.2578526924724226, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141204.0918465} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.65995740890503, "x": 40.29654599984664, "y": 0.5993252263598494, "z": null, "yaw": 3.6607438497928118, "pitch": null, "roll": null}, "v": 1.0678911723274098, "accelerator_pedal_position": 0.2578800154799184, "brake_pedal_position": 0.0, "acceleration": 0.09695162257377132, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.2693321566717587, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141204.1118464} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2578526924724226, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.140969833465734, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0765631351308522, "gear": 1, "accelerator_pedal_position": 0.2578526924724226, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141204.1118464} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141204.1318464, "x": 44.193367017063196, "y": 5.542081914370931, "z": null, "yaw": 3.6330008194151704, "pitch": null, "roll": null}, "v": 1.0784856729716747, "accelerator_pedal_position": 0.2578526924724226, "brake_pedal_position": 0.0, "acceleration": 0.09602373083600574, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.27200418897366574, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141204.1318464} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2714815046081872, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -9.886402353839166, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.079445910280035, "gear": 1, "accelerator_pedal_position": 0.2578526924724226, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141204.1318464} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.769957304000854, "x": 40.193367017063196, "y": 0.5420819143709306, "z": null, "yaw": 3.6330008194151704, "pitch": null, "roll": null}, "v": 1.0784856729716747, "accelerator_pedal_position": 0.2578526924724226, "brake_pedal_position": 0.0, "acceleration": 0.09602373083600574, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.27200418897366574, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141204.1518464} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2650492764115711, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -9.886402353839166, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0830673146966385, "gear": 1, "accelerator_pedal_position": 0.2714815046081872, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141204.1518464} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.769957304000854, "x": 40.193367017063196, "y": 0.5420819143709306, "z": null, "yaw": 3.6330008194151704, "pitch": null, "roll": null}, "v": 1.0784856729716747, "accelerator_pedal_position": 0.2578526924724226, "brake_pedal_position": 0.0, "acceleration": 0.09602373083600574, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.27200418897366574, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141204.1718464} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2650492764115711, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -9.886402353839166, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0844740573341969, "gear": 1, "accelerator_pedal_position": 0.2650492764115711, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141204.1718464} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.769957304000854, "x": 40.193367017063196, "y": 0.5420819143709306, "z": null, "yaw": 3.6330008194151704, "pitch": null, "roll": null}, "v": 1.0784856729716747, "accelerator_pedal_position": 0.2578526924724226, "brake_pedal_position": 0.0, "acceleration": 0.09602373083600574, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.27200418897366574, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141204.1918464} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2650492764115711, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -9.886402353839166, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.087284518070833, "gear": 1, "accelerator_pedal_position": 0.2650492764115711, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141204.1918464} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.769957304000854, "x": 40.193367017063196, "y": 0.5420819143709306, "z": null, "yaw": 3.6330008194151704, "pitch": null, "roll": null}, "v": 1.0784856729716747, "accelerator_pedal_position": 0.2578526924724226, "brake_pedal_position": 0.0, "acceleration": 0.09602373083600574, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.27200418897366574, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141204.2118464} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2650492764115711, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -9.886402353839166, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0914926527488422, "gear": 1, "accelerator_pedal_position": 0.2650492764115711, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141204.2118464} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.769957304000854, "x": 40.193367017063196, "y": 0.5420819143709306, "z": null, "yaw": 3.6330008194151704, "pitch": null, "roll": null}, "v": 1.0784856729716747, "accelerator_pedal_position": 0.2578526924724226, "brake_pedal_position": 0.0, "acceleration": 0.09602373083600574, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.27200418897366574, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141204.2318463} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2650492764115711, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -9.886402353839166, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0942930420899517, "gear": 1, "accelerator_pedal_position": 0.2650492764115711, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141204.2318463} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141204.2418463, "x": 44.08736795554843, "y": 5.4870641054041664, "z": null, "yaw": 3.605257789037529, "pitch": null, "roll": null}, "v": 1.0942930420899517, "accelerator_pedal_position": 0.2650492764115711, "brake_pedal_position": 0.0, "acceleration": 0.13986855284815697, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.2759909555340197, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141204.2518463} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26431551898394634, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -9.411047240692742, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0970894074941502, "gear": 1, "accelerator_pedal_position": 0.2650492764115711, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.442490503673362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141204.2518463} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.87995719909668, "x": 40.08736795554843, "y": 0.48706410540416645, "z": null, "yaw": 3.605257789037529, "pitch": null, "roll": null}, "v": 1.0942930420899517, "accelerator_pedal_position": 0.2650492764115711, "brake_pedal_position": 0.0, "acceleration": 0.13986855284815697, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.2759909555340197, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141204.2718463} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2647513143658495, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -9.411047240692742, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0997900649433108, "gear": 1, "accelerator_pedal_position": 0.26431551898394634, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.366788211459255, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141204.2718463} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.87995719909668, "x": 40.08736795554843, "y": 0.48706410540416645, "z": null, "yaw": 3.605257789037529, "pitch": null, "roll": null}, "v": 1.0942930420899517, "accelerator_pedal_position": 0.2650492764115711, "brake_pedal_position": 0.0, "acceleration": 0.13986855284815697, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.2759909555340197, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141204.2918463} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2647513143658495, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -9.411047240692742, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1025412906071468, "gear": 1, "accelerator_pedal_position": 0.2647513143658495, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.290755834532984, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141204.2918463} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.87995719909668, "x": 40.08736795554843, "y": 0.48706410540416645, "z": null, "yaw": 3.605257789037529, "pitch": null, "roll": null}, "v": 1.0942930420899517, "accelerator_pedal_position": 0.2650492764115711, "brake_pedal_position": 0.0, "acceleration": 0.13986855284815697, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.2759909555340197, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141204.3118463} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2647513143658495, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -9.411047240692742, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.105288553894262, "gear": 1, "accelerator_pedal_position": 0.2647513143658495, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.214393372894554, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141204.3118463} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.87995719909668, "x": 40.08736795554843, "y": 0.48706410540416645, "z": null, "yaw": 3.605257789037529, "pitch": null, "roll": null}, "v": 1.0942930420899517, "accelerator_pedal_position": 0.2650492764115711, "brake_pedal_position": 0.0, "acceleration": 0.13986855284815697, "steering_wheel_angle": -10.442490503673362, "front_wheel_angle": -0.5733153635806238, "heading_rate": -0.2759909555340197, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141204.3318462} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2647513143658495, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -9.411047240692742, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1080318574934658, "gear": 1, "accelerator_pedal_position": 0.2647513143658495, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.137700826543961, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141204.3318462} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141204.3518462, "x": 43.97836069458286, "y": 5.434255330276299, "z": null, "yaw": 3.5780235588723084, "pitch": null, "roll": null}, "v": 1.1094020252528627, "accelerator_pedal_position": 0.2647513143658495, "brake_pedal_position": 0.0, "acceleration": 0.13691788498756452, "steering_wheel_angle": -10.099230771601604, "front_wheel_angle": -0.5501182331779233, "heading_rate": -0.26576587982936534, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141204.3518462} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26791070377284193, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.977719509079698, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1107712041027384, "gear": 1, "accelerator_pedal_position": 0.2647513143658495, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.06067819548121, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141204.3518462} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.989957094192505, "x": 39.97836069458286, "y": 0.43425533027629903, "z": null, "yaw": 3.5780235588723084, "pitch": null, "roll": null}, "v": 1.1094020252528627, "accelerator_pedal_position": 0.2647513143658495, "brake_pedal_position": 0.0, "acceleration": 0.13691788498756452, "steering_wheel_angle": -10.099230771601604, "front_wheel_angle": -0.5501182331779233, "heading_rate": -0.26576587982936534, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141204.3718462} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2664891580174704, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.977719509079698, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1139013774492257, "gear": 1, "accelerator_pedal_position": 0.26791070377284193, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.985001867185387, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141204.3718462} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.989957094192505, "x": 39.97836069458286, "y": 0.43425533027629903, "z": null, "yaw": 3.5780235588723084, "pitch": null, "roll": null}, "v": 1.1094020252528627, "accelerator_pedal_position": 0.2647513143658495, "brake_pedal_position": 0.0, "acceleration": 0.13691788498756452, "steering_wheel_angle": -10.099230771601604, "front_wheel_angle": -0.5501182331779233, "heading_rate": -0.26576587982936534, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141204.3918462} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2664891580174704, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.977719509079698, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.116849399579434, "gear": 1, "accelerator_pedal_position": 0.2664891580174704, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.90900957717296, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141204.3918462} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.989957094192505, "x": 39.97836069458286, "y": 0.43425533027629903, "z": null, "yaw": 3.5780235588723084, "pitch": null, "roll": null}, "v": 1.1094020252528627, "accelerator_pedal_position": 0.2647513143658495, "brake_pedal_position": 0.0, "acceleration": 0.13691788498756452, "steering_wheel_angle": -10.099230771601604, "front_wheel_angle": -0.5501182331779233, "heading_rate": -0.26576587982936534, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141204.4118462} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2664891580174704, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.977719509079698, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1197931591001762, "gear": 1, "accelerator_pedal_position": 0.2664891580174704, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.832701325443931, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141204.4118462} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.989957094192505, "x": 39.97836069458286, "y": 0.43425533027629903, "z": null, "yaw": 3.5780235588723084, "pitch": null, "roll": null}, "v": 1.1094020252528627, "accelerator_pedal_position": 0.2647513143658495, "brake_pedal_position": 0.0, "acceleration": 0.13691788498756452, "steering_wheel_angle": -10.099230771601604, "front_wheel_angle": -0.5501182331779233, "heading_rate": -0.26576587982936534, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141204.4318461} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2664891580174704, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.977719509079698, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1212634412248013, "gear": 1, "accelerator_pedal_position": 0.2664891580174704, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.794428713935693, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141204.4318461} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.989957094192505, "x": 39.97836069458286, "y": 0.43425533027629903, "z": null, "yaw": 3.5780235588723084, "pitch": null, "roll": null}, "v": 1.1094020252528627, "accelerator_pedal_position": 0.2647513143658495, "brake_pedal_position": 0.0, "acceleration": 0.13691788498756452, "steering_wheel_angle": -10.099230771601604, "front_wheel_angle": -0.5501182331779233, "heading_rate": -0.26576587982936534, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141204.4518461} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2664891580174704, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.977719509079698, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.12566790111786, "gear": 1, "accelerator_pedal_position": 0.2664891580174704, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.679136936836068, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141204.4518461} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141204.461846, "x": 43.86642411589704, "y": 5.3836452913551875, "z": null, "yaw": 3.5524127966512373, "pitch": null, "roll": null}, "v": 1.12566790111786, "accelerator_pedal_position": 0.2664891580174704, "brake_pedal_position": 0.0, "acceleration": 0.14660256031722613, "steering_wheel_angle": -9.679136936836068, "front_wheel_angle": -0.5223236080006736, "heading_rate": -0.25312194754578876, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141204.471846} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2777916419836705, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.693420849426593, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1271339267210323, "gear": 1, "accelerator_pedal_position": 0.2664891580174704, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.640548363611227, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141204.471846} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.09995698928833, "x": 39.86642411589704, "y": 0.38364529135518755, "z": null, "yaw": 3.5524127966512373, "pitch": null, "roll": null}, "v": 1.12566790111786, "accelerator_pedal_position": 0.2664891580174704, "brake_pedal_position": 0.0, "acceleration": 0.14660256031722613, "steering_wheel_angle": -9.679136936836068, "front_wheel_angle": -0.5223236080006736, "heading_rate": -0.25312194754578876, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141204.491846} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27249916868874174, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.693420849426593, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1336433027186281, "gear": 1, "accelerator_pedal_position": 0.2777916419836705, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.525911445191594, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141204.491846} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.09995698928833, "x": 39.86642411589704, "y": 0.38364529135518755, "z": null, "yaw": 3.5524127966512373, "pitch": null, "roll": null}, "v": 1.12566790111786, "accelerator_pedal_position": 0.2664891580174704, "brake_pedal_position": 0.0, "acceleration": 0.14660256031722613, "steering_wheel_angle": -9.679136936836068, "front_wheel_angle": -0.5223236080006736, "heading_rate": -0.25312194754578876, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141204.511846} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27249916868874174, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.693420849426593, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1373136915641053, "gear": 1, "accelerator_pedal_position": 0.27249916868874174, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.449102664794648, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141204.511846} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.09995698928833, "x": 39.86642411589704, "y": 0.38364529135518755, "z": null, "yaw": 3.5524127966512373, "pitch": null, "roll": null}, "v": 1.12566790111786, "accelerator_pedal_position": 0.2664891580174704, "brake_pedal_position": 0.0, "acceleration": 0.14660256031722613, "steering_wheel_angle": -9.679136936836068, "front_wheel_angle": -0.5223236080006736, "heading_rate": -0.25312194754578876, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141204.531846} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27249916868874174, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.693420849426593, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1409787435564043, "gear": 1, "accelerator_pedal_position": 0.27249916868874174, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.371986549903951, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141204.531846} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.09995698928833, "x": 39.86642411589704, "y": 0.38364529135518755, "z": null, "yaw": 3.5524127966512373, "pitch": null, "roll": null}, "v": 1.12566790111786, "accelerator_pedal_position": 0.2664891580174704, "brake_pedal_position": 0.0, "acceleration": 0.14660256031722613, "steering_wheel_angle": -9.679136936836068, "front_wheel_angle": -0.5223236080006736, "heading_rate": -0.25312194754578876, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141204.551846} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27249916868874174, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.693420849426593, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1446384610843787, "gear": 1, "accelerator_pedal_position": 0.27249916868874174, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.294563100519504, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141204.551846} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141204.571846, "x": 43.75139556953641, "y": 5.335048172650993, "z": null, "yaw": 3.528383973782513, "pitch": null, "roll": null}, "v": 1.1464663201762235, "accelerator_pedal_position": 0.27249916868874174, "brake_pedal_position": 0.0, "acceleration": 0.18265263806284054, "steering_wheel_angle": -9.294563100519504, "front_wheel_angle": -0.4974184318009393, "heading_rate": -0.2431561803738081, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141204.571846} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.265011580268387, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.165085590528516, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1482928465568518, "gear": 1, "accelerator_pedal_position": 0.27249916868874174, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.294563100519504, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141204.571846} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.209956884384155, "x": 39.75139556953641, "y": 0.3350481726509926, "z": null, "yaw": 3.528383973782513, "pitch": null, "roll": null}, "v": 1.1464663201762235, "accelerator_pedal_position": 0.27249916868874174, "brake_pedal_position": 0.0, "acceleration": 0.18265263806284054, "steering_wheel_angle": -9.294563100519504, "front_wheel_angle": -0.4974184318009393, "heading_rate": -0.2431561803738081, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141204.591846} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26869233765581363, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.165085590528516, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1510062954603655, "gear": 1, "accelerator_pedal_position": 0.265011580268387, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.218736091872158, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141204.591846} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.209956884384155, "x": 39.75139556953641, "y": 0.3350481726509926, "z": null, "yaw": 3.528383973782513, "pitch": null, "roll": null}, "v": 1.1464663201762235, "accelerator_pedal_position": 0.27249916868874174, "brake_pedal_position": 0.0, "acceleration": 0.18265263806284054, "steering_wheel_angle": -9.294563100519504, "front_wheel_angle": -0.4974184318009393, "heading_rate": -0.2431561803738081, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141204.611846} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26869233765581363, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.165085590528516, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1541757104440007, "gear": 1, "accelerator_pedal_position": 0.26869233765581363, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.142616590522964, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141204.611846} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.209956884384155, "x": 39.75139556953641, "y": 0.3350481726509926, "z": null, "yaw": 3.528383973782513, "pitch": null, "roll": null}, "v": 1.1464663201762235, "accelerator_pedal_position": 0.27249916868874174, "brake_pedal_position": 0.0, "acceleration": 0.18265263806284054, "steering_wheel_angle": -9.294563100519504, "front_wheel_angle": -0.4974184318009393, "heading_rate": -0.2431561803738081, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141204.631846} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26869233765581363, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.165085590528516, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1557586815352092, "gear": 1, "accelerator_pedal_position": 0.26869233765581363, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.10444715508517, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141204.631846} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.209956884384155, "x": 39.75139556953641, "y": 0.3350481726509926, "z": null, "yaw": 3.528383973782513, "pitch": null, "roll": null}, "v": 1.1464663201762235, "accelerator_pedal_position": 0.27249916868874174, "brake_pedal_position": 0.0, "acceleration": 0.18265263806284054, "steering_wheel_angle": -9.294563100519504, "front_wheel_angle": -0.4974184318009393, "heading_rate": -0.2431561803738081, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141204.651846} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26869233765581363, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.165085590528516, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1605006533417983, "gear": 1, "accelerator_pedal_position": 0.26869233765581363, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.989500109719012, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141204.651846} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.209956884384155, "x": 39.75139556953641, "y": 0.3350481726509926, "z": null, "yaw": 3.528383973782513, "pitch": null, "roll": null}, "v": 1.1464663201762235, "accelerator_pedal_position": 0.27249916868874174, "brake_pedal_position": 0.0, "acceleration": 0.18265263806284054, "steering_wheel_angle": -9.294563100519504, "front_wheel_angle": -0.4974184318009393, "heading_rate": -0.2431561803738081, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141204.671846} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26869233765581363, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.165085590528516, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1636561867867465, "gear": 1, "accelerator_pedal_position": 0.26869233765581363, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.912503130264263, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141204.671846} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141204.681846, "x": 43.63331376527277, "y": 5.288391758968841, "z": null, "yaw": 3.5056015715470465, "pitch": null, "roll": null}, "v": 1.1636561867867465, "accelerator_pedal_position": 0.26869233765581363, "brake_pedal_position": 0.0, "acceleration": 0.15760334379902702, "steering_wheel_angle": -8.912503130264263, "front_wheel_angle": -0.47315587493344596, "heading_rate": -0.23270508618249228, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141204.691846} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2789638722898052, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.9108630750651345, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1652322202247367, "gear": 1, "accelerator_pedal_position": 0.26869233765581363, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.873894955773693, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141204.691846} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.31995677947998, "x": 39.63331376527277, "y": 0.2883917589688414, "z": null, "yaw": 3.5056015715470465, "pitch": null, "roll": null}, "v": 1.1636561867867465, "accelerator_pedal_position": 0.26869233765581363, "brake_pedal_position": 0.0, "acceleration": 0.15760334379902702, "steering_wheel_angle": -8.912503130264263, "front_wheel_angle": -0.47315587493344596, "heading_rate": -0.23270508618249228, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141204.7118459} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2741684039015404, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.9108630750651345, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1718778916859751, "gear": 1, "accelerator_pedal_position": 0.2789638722898052, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.758963116184713, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141204.7118459} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.31995677947998, "x": 39.63331376527277, "y": 0.2883917589688414, "z": null, "yaw": 3.5056015715470465, "pitch": null, "roll": null}, "v": 1.1636561867867465, "accelerator_pedal_position": 0.26869233765581363, "brake_pedal_position": 0.0, "acceleration": 0.15760334379902702, "steering_wheel_angle": -8.912503130264263, "front_wheel_angle": -0.47315587493344596, "heading_rate": -0.23270508618249228, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141204.7318459} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2741684039015404, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.9108630750651345, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1737901482046762, "gear": 1, "accelerator_pedal_position": 0.2741684039015404, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.720509577785537, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141204.7318459} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.31995677947998, "x": 39.63331376527277, "y": 0.2883917589688414, "z": null, "yaw": 3.5056015715470465, "pitch": null, "roll": null}, "v": 1.1636561867867465, "accelerator_pedal_position": 0.26869233765581363, "brake_pedal_position": 0.0, "acceleration": 0.15760334379902702, "steering_wheel_angle": -8.912503130264263, "front_wheel_angle": -0.47315587493344596, "heading_rate": -0.23270508618249228, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141204.7518458} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2741684039015404, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.9108630750651345, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1795184908863803, "gear": 1, "accelerator_pedal_position": 0.2741684039015404, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.604720186979458, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141204.7518458} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.31995677947998, "x": 39.63331376527277, "y": 0.2883917589688414, "z": null, "yaw": 3.5056015715470465, "pitch": null, "roll": null}, "v": 1.1636561867867465, "accelerator_pedal_position": 0.26869233765581363, "brake_pedal_position": 0.0, "acceleration": 0.15760334379902702, "steering_wheel_angle": -8.912503130264263, "front_wheel_angle": -0.47315587493344596, "heading_rate": -0.23270508618249228, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141204.7718458} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2741684039015404, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.9108630750651345, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1833303666424493, "gear": 1, "accelerator_pedal_position": 0.2741684039015404, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.565980798174582, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141204.7718458} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141204.7918458, "x": 43.51223495660372, "y": 5.243623715976689, "z": null, "yaw": 3.4842387316121317, "pitch": null, "roll": null}, "v": 1.1852341996273126, "accelerator_pedal_position": 0.2741684039015404, "brake_pedal_position": 0.0, "acceleration": 0.19024301332359983, "steering_wheel_angle": -8.565980798174582, "front_wheel_angle": -0.4515412334074489, "heading_rate": -0.22452657751701954, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141204.7918458} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2698714583392329, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.472126595402328, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1852341996273126, "gear": 1, "accelerator_pedal_position": 0.2741684039015404, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.565980798174582, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141204.7918458} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.429956674575806, "x": 39.51223495660372, "y": 0.24362371597668897, "z": null, "yaw": 3.4842387316121317, "pitch": null, "roll": null}, "v": 1.1852341996273126, "accelerator_pedal_position": 0.2741684039015404, "brake_pedal_position": 0.0, "acceleration": 0.19024301332359983, "steering_wheel_angle": -8.565980798174582, "front_wheel_angle": -0.4515412334074489, "heading_rate": -0.22452657751701954, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141204.8118458} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27203844260464216, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.472126595402328, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1901321995694345, "gear": 1, "accelerator_pedal_position": 0.2698714583392329, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.451560585431634, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141204.8118458} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.429956674575806, "x": 39.51223495660372, "y": 0.24362371597668897, "z": null, "yaw": 3.4842387316121317, "pitch": null, "roll": null}, "v": 1.1852341996273126, "accelerator_pedal_position": 0.2741684039015404, "brake_pedal_position": 0.0, "acceleration": 0.19024301332359983, "steering_wheel_angle": -8.565980798174582, "front_wheel_angle": -0.4515412334074489, "heading_rate": -0.22452657751701954, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141204.8318458} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27203844260464216, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.472126595402328, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1918978946671948, "gear": 1, "accelerator_pedal_position": 0.27203844260464216, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.4132829795297, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141204.8318458} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.429956674575806, "x": 39.51223495660372, "y": 0.24362371597668897, "z": null, "yaw": 3.4842387316121317, "pitch": null, "roll": null}, "v": 1.1852341996273126, "accelerator_pedal_position": 0.2741684039015404, "brake_pedal_position": 0.0, "acceleration": 0.19024301332359983, "steering_wheel_angle": -8.565980798174582, "front_wheel_angle": -0.4515412334074489, "heading_rate": -0.22452657751701954, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141204.8518457} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27203844260464216, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.472126595402328, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1971871606704303, "gear": 1, "accelerator_pedal_position": 0.27203844260464216, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.298037556861049, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141204.8518457} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.429956674575806, "x": 39.51223495660372, "y": 0.24362371597668897, "z": null, "yaw": 3.4842387316121317, "pitch": null, "roll": null}, "v": 1.1852341996273126, "accelerator_pedal_position": 0.2741684039015404, "brake_pedal_position": 0.0, "acceleration": 0.19024301332359983, "steering_wheel_angle": -8.565980798174582, "front_wheel_angle": -0.4515412334074489, "heading_rate": -0.22452657751701954, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141204.8718457} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27203844260464216, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.472126595402328, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1989476440431177, "gear": 1, "accelerator_pedal_position": 0.27203844260464216, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.25948488098388, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141204.8718457} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.429956674575806, "x": 39.51223495660372, "y": 0.24362371597668897, "z": null, "yaw": 3.4842387316121317, "pitch": null, "roll": null}, "v": 1.1852341996273126, "accelerator_pedal_position": 0.2741684039015404, "brake_pedal_position": 0.0, "acceleration": 0.19024301332359983, "steering_wheel_angle": -8.565980798174582, "front_wheel_angle": -0.4515412334074489, "heading_rate": -0.22452657751701954, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141204.8918457} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27203844260464216, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.472126595402328, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2042212830743366, "gear": 1, "accelerator_pedal_position": 0.27203844260464216, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.143414248389524, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141204.8918457} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141204.9018457, "x": 43.38815380430732, "y": 5.2006624678048174, "z": null, "yaw": 3.4640202281859924, "pitch": null, "roll": null}, "v": 1.2042212830743366, "accelerator_pedal_position": 0.27203844260464216, "brake_pedal_position": 0.0, "acceleration": 0.17552771313920457, "steering_wheel_angle": -8.143414248389524, "front_wheel_angle": -0.42565950184444273, "heading_rate": -0.21326851986239254, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141204.9118457} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2807059198916218, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.246767627291572, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2059765602057286, "gear": 1, "accelerator_pedal_position": 0.27203844260464216, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.10458650253712, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141204.9118457} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.53995656967163, "x": 39.38815380430732, "y": 0.20066246780481745, "z": null, "yaw": 3.4640202281859924, "pitch": null, "roll": null}, "v": 1.2042212830743366, "accelerator_pedal_position": 0.27203844260464216, "brake_pedal_position": 0.0, "acceleration": 0.17552771313920457, "steering_wheel_angle": -8.143414248389524, "front_wheel_angle": -0.42565950184444273, "heading_rate": -0.21326851986239254, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141204.9318457} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2766854461906602, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.246767627291572, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2105662456547437, "gear": 1, "accelerator_pedal_position": 0.2807059198916218, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.027469384589537, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141204.9318457} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.53995656967163, "x": 39.38815380430732, "y": 0.20066246780481745, "z": null, "yaw": 3.4640202281859924, "pitch": null, "roll": null}, "v": 1.2042212830743366, "accelerator_pedal_position": 0.27203844260464216, "brake_pedal_position": 0.0, "acceleration": 0.17552771313920457, "steering_wheel_angle": -8.143414248389524, "front_wheel_angle": -0.42565950184444273, "heading_rate": -0.21326851986239254, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141204.9518456} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2766854461906602, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.246767627291572, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2166847313170748, "gear": 1, "accelerator_pedal_position": 0.2766854461906602, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.911287752687044, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141204.9518456} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.53995656967163, "x": 39.38815380430732, "y": 0.20066246780481745, "z": null, "yaw": 3.4640202281859924, "pitch": null, "roll": null}, "v": 1.2042212830743366, "accelerator_pedal_position": 0.27203844260464216, "brake_pedal_position": 0.0, "acceleration": 0.17552771313920457, "steering_wheel_angle": -8.143414248389524, "front_wheel_angle": -0.42565950184444273, "heading_rate": -0.21326851986239254, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141204.9718456} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2766854461906602, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.246767627291572, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2187211971647904, "gear": 1, "accelerator_pedal_position": 0.2766854461906602, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.911287752687044, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141204.9718456} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.53995656967163, "x": 39.38815380430732, "y": 0.20066246780481745, "z": null, "yaw": 3.4640202281859924, "pitch": null, "roll": null}, "v": 1.2042212830743366, "accelerator_pedal_position": 0.27203844260464216, "brake_pedal_position": 0.0, "acceleration": 0.17552771313920457, "steering_wheel_angle": -8.143414248389524, "front_wheel_angle": -0.42565950184444273, "heading_rate": -0.21326851986239254, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141204.9918456} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2766854461906602, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.246767627291572, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2227895865725025, "gear": 1, "accelerator_pedal_position": 0.2766854461906602, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.911287752687044, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141204.9918456} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141205.0118456, "x": 43.26107488909417, "y": 5.1594369027621285, "z": null, "yaw": 3.445031355165193, "pitch": null, "roll": null}, "v": 1.2268519215870668, "accelerator_pedal_position": 0.2766854461906602, "brake_pedal_position": 0.0, "acceleration": 0.20288978623725412, "steering_wheel_angle": -7.911287752687044, "front_wheel_angle": -0.4116545130708142, "heading_rate": -0.20923560777112857, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141205.0118456} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2715249448132791, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.8345865876947585, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2288808194494394, "gear": 1, "accelerator_pedal_position": 0.2766854461906602, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.911287752687044, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141205.0118456} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.649956464767456, "x": 39.26107488909417, "y": 0.15943690276212852, "z": null, "yaw": 3.445031355165193, "pitch": null, "roll": null}, "v": 1.2268519215870668, "accelerator_pedal_position": 0.2766854461906602, "brake_pedal_position": 0.0, "acceleration": 0.20288978623725412, "steering_wheel_angle": -7.911287752687044, "front_wheel_angle": -0.4116545130708142, "heading_rate": -0.20923560777112857, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141205.0318456} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27411045718471794, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.8345865876947585, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2305856732837035, "gear": 1, "accelerator_pedal_position": 0.2715249448132791, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.87308444739601, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141205.0318456} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.649956464767456, "x": 39.26107488909417, "y": 0.15943690276212852, "z": null, "yaw": 3.445031355165193, "pitch": null, "roll": null}, "v": 1.2268519215870668, "accelerator_pedal_position": 0.2766854461906602, "brake_pedal_position": 0.0, "acceleration": 0.20288978623725412, "steering_wheel_angle": -7.911287752687044, "front_wheel_angle": -0.4116545130708142, "heading_rate": -0.20923560777112857, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141205.0518456} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27411045718471794, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.8345865876947585, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.236177027545585, "gear": 1, "accelerator_pedal_position": 0.27411045718471794, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.758083363570726, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141205.0518456} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.649956464767456, "x": 39.26107488909417, "y": 0.15943690276212852, "z": null, "yaw": 3.445031355165193, "pitch": null, "roll": null}, "v": 1.2268519215870668, "accelerator_pedal_position": 0.2766854461906602, "brake_pedal_position": 0.0, "acceleration": 0.20288978623725412, "steering_wheel_angle": -7.911287752687044, "front_wheel_angle": -0.4116545130708142, "heading_rate": -0.20923560777112857, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141205.0718455} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27411045718471794, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.8345865876947585, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2398976399847532, "gear": 1, "accelerator_pedal_position": 0.27411045718471794, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.681090001060383, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141205.0718455} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.649956464767456, "x": 39.26107488909417, "y": 0.15943690276212852, "z": null, "yaw": 3.445031355165193, "pitch": null, "roll": null}, "v": 1.2268519215870668, "accelerator_pedal_position": 0.2766854461906602, "brake_pedal_position": 0.0, "acceleration": 0.20288978623725412, "steering_wheel_angle": -7.911287752687044, "front_wheel_angle": -0.4116545130708142, "heading_rate": -0.20923560777112857, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141205.0918455} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27411045718471794, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.8345865876947585, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2436126900054103, "gear": 1, "accelerator_pedal_position": 0.27411045718471794, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.60383585991525, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141205.0918455} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.649956464767456, "x": 39.26107488909417, "y": 0.15943690276212852, "z": null, "yaw": 3.445031355165193, "pitch": null, "roll": null}, "v": 1.2268519215870668, "accelerator_pedal_position": 0.2766854461906602, "brake_pedal_position": 0.0, "acceleration": 0.20288978623725412, "steering_wheel_angle": -7.911287752687044, "front_wheel_angle": -0.4116545130708142, "heading_rate": -0.20923560777112857, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141205.1118455} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27411045718471794, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.8345865876947585, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.247322180404952, "gear": 1, "accelerator_pedal_position": 0.27411045718471794, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.526320940135328, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141205.1118455} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141205.1218455, "x": 43.13097050584864, "y": 5.119902285092066, "z": null, "yaw": 3.4267477029437496, "pitch": null, "roll": null}, "v": 1.247322180404952, "accelerator_pedal_position": 0.27411045718471794, "brake_pedal_position": 0.0, "acceleration": 0.18526612216693783, "steering_wheel_angle": -7.526320940135328, "front_wheel_angle": -0.38874504250116176, "heading_rate": -0.1995660274802065, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141205.1318455} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27392231123423527, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.503701022833569, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2491748416266213, "gear": 1, "accelerator_pedal_position": 0.27411045718471794, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.48746568825732, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141205.1318455} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.75995635986328, "x": 39.13097050584864, "y": 0.11990228509206613, "z": null, "yaw": 3.4267477029437496, "pitch": null, "roll": null}, "v": 1.247322180404952, "accelerator_pedal_position": 0.27411045718471794, "brake_pedal_position": 0.0, "acceleration": 0.18526612216693783, "steering_wheel_angle": -7.526320940135328, "front_wheel_angle": -0.38874504250116176, "heading_rate": -0.1995660274802065, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141205.1518455} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2741284747637901, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.503701022833569, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2546892427346648, "gear": 1, "accelerator_pedal_position": 0.27392231123423527, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.372058271163889, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141205.1518455} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.75995635986328, "x": 39.13097050584864, "y": 0.11990228509206613, "z": null, "yaw": 3.4267477029437496, "pitch": null, "roll": null}, "v": 1.247322180404952, "accelerator_pedal_position": 0.27411045718471794, "brake_pedal_position": 0.0, "acceleration": 0.18526612216693783, "steering_wheel_angle": -7.526320940135328, "front_wheel_angle": -0.38874504250116176, "heading_rate": -0.1995660274802065, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141205.1718454} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2741284747637901, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.503701022833569, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2583843755478357, "gear": 1, "accelerator_pedal_position": 0.2741284747637901, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.2948025788769, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141205.1718454} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.75995635986328, "x": 39.13097050584864, "y": 0.11990228509206613, "z": null, "yaw": 3.4267477029437496, "pitch": null, "roll": null}, "v": 1.247322180404952, "accelerator_pedal_position": 0.27411045718471794, "brake_pedal_position": 0.0, "acceleration": 0.18526612216693783, "steering_wheel_angle": -7.526320940135328, "front_wheel_angle": -0.38874504250116176, "heading_rate": -0.1995660274802065, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141205.1918454} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2741284747637901, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.503701022833569, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2602298599091364, "gear": 1, "accelerator_pedal_position": 0.2741284747637901, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.2560795084659935, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141205.1918454} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.75995635986328, "x": 39.13097050584864, "y": 0.11990228509206613, "z": null, "yaw": 3.4267477029437496, "pitch": null, "roll": null}, "v": 1.247322180404952, "accelerator_pedal_position": 0.27411045718471794, "brake_pedal_position": 0.0, "acceleration": 0.18526612216693783, "steering_wheel_angle": -7.526320940135328, "front_wheel_angle": -0.38874504250116176, "heading_rate": -0.1995660274802065, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141205.2118454} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2741284747637901, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.503701022833569, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2657579891547053, "gear": 1, "accelerator_pedal_position": 0.2741284747637901, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.178442919109359, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141205.2118454} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141205.2318454, "x": 42.99803233406831, "y": 5.082065516284159, "z": null, "yaw": 3.409702994184936, "pitch": null, "roll": null}, "v": 1.2675979255041538, "accelerator_pedal_position": 0.2741284747637901, "brake_pedal_position": 0.0, "acceleration": 0.18385502599105596, "steering_wheel_angle": -7.178442919109359, "front_wheel_angle": -0.3683687327647752, "heading_rate": -0.19112389695707085, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141205.2318454} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27432042587112015, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.209086517204088, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2675979255041538, "gear": 1, "accelerator_pedal_position": 0.2741284747637901, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.178442919109359, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141205.2318454} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.869956254959106, "x": 38.99803233406831, "y": 0.08206551628415859, "z": null, "yaw": 3.409702994184936, "pitch": null, "roll": null}, "v": 1.2675979255041538, "accelerator_pedal_position": 0.2741284747637901, "brake_pedal_position": 0.0, "acceleration": 0.18385502599105596, "steering_wheel_angle": -7.178442919109359, "front_wheel_angle": -0.3683687327647752, "heading_rate": -0.19112389695707085, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141205.2518454} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2743451124833966, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.209086517204088, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2731453831855788, "gear": 1, "accelerator_pedal_position": 0.27432042587112015, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.062858497911212, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141205.2518454} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.869956254959106, "x": 38.99803233406831, "y": 0.08206551628415859, "z": null, "yaw": 3.409702994184936, "pitch": null, "roll": null}, "v": 1.2675979255041538, "accelerator_pedal_position": 0.2741284747637901, "brake_pedal_position": 0.0, "acceleration": 0.18385502599105596, "steering_wheel_angle": -7.178442919109359, "front_wheel_angle": -0.3683687327647752, "heading_rate": -0.19112389695707085, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141205.2718453} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2743451124833966, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.209086517204088, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2768398022037022, "gear": 1, "accelerator_pedal_position": 0.2743451124833966, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.985492054102863, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141205.2718453} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.869956254959106, "x": 38.99803233406831, "y": 0.08206551628415859, "z": null, "yaw": 3.409702994184936, "pitch": null, "roll": null}, "v": 1.2675979255041538, "accelerator_pedal_position": 0.2741284747637901, "brake_pedal_position": 0.0, "acceleration": 0.18385502599105596, "steering_wheel_angle": -7.178442919109359, "front_wheel_angle": -0.3683687327647752, "heading_rate": -0.19112389695707085, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141205.2918453} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2743451124833966, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.209086517204088, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2805286434026295, "gear": 1, "accelerator_pedal_position": 0.2743451124833966, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.907877479886849, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141205.2918453} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.869956254959106, "x": 38.99803233406831, "y": 0.08206551628415859, "z": null, "yaw": 3.409702994184936, "pitch": null, "roll": null}, "v": 1.2675979255041538, "accelerator_pedal_position": 0.2741284747637901, "brake_pedal_position": 0.0, "acceleration": 0.18385502599105596, "steering_wheel_angle": -7.178442919109359, "front_wheel_angle": -0.3683687327647752, "heading_rate": -0.19112389695707085, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141205.3118453} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2743451124833966, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.209086517204088, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2842119097627667, "gear": 1, "accelerator_pedal_position": 0.2743451124833966, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.907877479886849, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141205.3118453} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.869956254959106, "x": 38.99803233406831, "y": 0.08206551628415859, "z": null, "yaw": 3.409702994184936, "pitch": null, "roll": null}, "v": 1.2675979255041538, "accelerator_pedal_position": 0.2741284747637901, "brake_pedal_position": 0.0, "acceleration": 0.18385502599105596, "steering_wheel_angle": -7.178442919109359, "front_wheel_angle": -0.3683687327647752, "heading_rate": -0.19112389695707085, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141205.3318453} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2743451124833966, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.209086517204088, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.28605145331518, "gear": 1, "accelerator_pedal_position": 0.2743451124833966, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.907877479886849, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141205.3318453} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141205.3418453, "x": 42.86232785418771, "y": 5.04586396687962, "z": null, "yaw": 3.3936066088582058, "pitch": null, "roll": null}, "v": 1.2878896042846772, "accelerator_pedal_position": 0.2743451124833966, "brake_pedal_position": 0.0, "acceleration": 0.18367587647874933, "steering_wheel_angle": -6.907877479886849, "front_wheel_angle": -0.35272583943766656, "heading_rate": -0.1851948150113876, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141205.3518453} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27574458798792234, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.9509835896193435, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2897263630494646, "gear": 1, "accelerator_pedal_position": 0.2743451124833966, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.907877479886849, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141205.3518453} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.97995615005493, "x": 38.86232785418771, "y": 0.04586396687961969, "z": null, "yaw": 3.3936066088582058, "pitch": null, "roll": null}, "v": 1.2878896042846772, "accelerator_pedal_position": 0.2743451124833966, "brake_pedal_position": 0.0, "acceleration": 0.18367587647874933, "steering_wheel_angle": -6.907877479886849, "front_wheel_angle": -0.35272583943766656, "heading_rate": -0.1851948150113876, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141205.3718452} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27519498111196483, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.9509835896193435, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.293570573593807, "gear": 1, "accelerator_pedal_position": 0.27574458798792234, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.830783635766101, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141205.3718452} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.97995615005493, "x": 38.86232785418771, "y": 0.04586396687961969, "z": null, "yaw": 3.3936066088582058, "pitch": null, "roll": null}, "v": 1.2878896042846772, "accelerator_pedal_position": 0.2743451124833966, "brake_pedal_position": 0.0, "acceleration": 0.18367587647874933, "steering_wheel_angle": -6.907877479886849, "front_wheel_angle": -0.35272583943766656, "heading_rate": -0.1851948150113876, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141205.3918452} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27519498111196483, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.9509835896193435, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2973402797304252, "gear": 1, "accelerator_pedal_position": 0.27519498111196483, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.753446529761109, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141205.3918452} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.97995615005493, "x": 38.86232785418771, "y": 0.04586396687961969, "z": null, "yaw": 3.3936066088582058, "pitch": null, "roll": null}, "v": 1.2878896042846772, "accelerator_pedal_position": 0.2743451124833966, "brake_pedal_position": 0.0, "acceleration": 0.18367587647874933, "steering_wheel_angle": -6.907877479886849, "front_wheel_angle": -0.35272583943766656, "heading_rate": -0.1851948150113876, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141205.4118452} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27519498111196483, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.9509835896193435, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3029841104764082, "gear": 1, "accelerator_pedal_position": 0.27519498111196483, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.636984754720661, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141205.4118452} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.97995615005493, "x": 38.86232785418771, "y": 0.04586396687961969, "z": null, "yaw": 3.3936066088582058, "pitch": null, "roll": null}, "v": 1.2878896042846772, "accelerator_pedal_position": 0.2743451124833966, "brake_pedal_position": 0.0, "acceleration": 0.18367587647874933, "steering_wheel_angle": -6.907877479886849, "front_wheel_angle": -0.35272583943766656, "heading_rate": -0.1851948150113876, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141205.4318452} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27519498111196483, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.9509835896193435, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3067395164152664, "gear": 1, "accelerator_pedal_position": 0.27519498111196483, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.636984754720661, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141205.4318452} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141205.4518452, "x": 42.72388219628387, "y": 5.011262729970245, "z": null, "yaw": 3.378199264918338, "pitch": null, "roll": null}, "v": 1.3086150761601805, "accelerator_pedal_position": 0.27519498111196483, "brake_pedal_position": 0.0, "acceleration": 0.18741314396623393, "steering_wheel_angle": -6.636984754720661, "front_wheel_angle": -0.33723716959612465, "heading_rate": -0.17923495588573124, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141205.4518452} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27542551861324216, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.679363793522763, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3086150761601805, "gear": 1, "accelerator_pedal_position": 0.27519498111196483, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.636984754720661, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141205.4518452} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.08995604515076, "x": 38.72388219628387, "y": 0.011262729970244578, "z": null, "yaw": 3.378199264918338, "pitch": null, "roll": null}, "v": 1.3086150761601805, "accelerator_pedal_position": 0.27519498111196483, "brake_pedal_position": 0.0, "acceleration": 0.18741314396623393, "steering_wheel_angle": -6.636984754720661, "front_wheel_angle": -0.33723716959612465, "heading_rate": -0.17923495588573124, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141205.4718451} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2754356940132269, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.679363793522763, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3123907173260978, "gear": 1, "accelerator_pedal_position": 0.27542551861324216, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.559833187803182, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141205.4718451} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.08995604515076, "x": 38.72388219628387, "y": 0.011262729970244578, "z": null, "yaw": 3.378199264918338, "pitch": null, "roll": null}, "v": 1.3086150761601805, "accelerator_pedal_position": 0.27519498111196483, "brake_pedal_position": 0.0, "acceleration": 0.18741314396623393, "steering_wheel_angle": -6.636984754720661, "front_wheel_angle": -0.33723716959612465, "heading_rate": -0.17923495588573124, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141205.4918451} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2754356940132269, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.679363793522763, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3180452975937373, "gear": 1, "accelerator_pedal_position": 0.2754356940132269, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.443658948912948, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141205.4918451} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.08995604515076, "x": 38.72388219628387, "y": 0.011262729970244578, "z": null, "yaw": 3.378199264918338, "pitch": null, "roll": null}, "v": 1.3086150761601805, "accelerator_pedal_position": 0.27519498111196483, "brake_pedal_position": 0.0, "acceleration": 0.18741314396623393, "steering_wheel_angle": -6.636984754720661, "front_wheel_angle": -0.33723716959612465, "heading_rate": -0.17923495588573124, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141205.511845} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2754356940132269, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.679363793522763, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3218078279123633, "gear": 1, "accelerator_pedal_position": 0.2754356940132269, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.365911530643445, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141205.511845} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.08995604515076, "x": 38.72388219628387, "y": 0.011262729970244578, "z": null, "yaw": 3.378199264918338, "pitch": null, "roll": null}, "v": 1.3086150761601805, "accelerator_pedal_position": 0.27519498111196483, "brake_pedal_position": 0.0, "acceleration": 0.18741314396623393, "steering_wheel_angle": -6.636984754720661, "front_wheel_angle": -0.33723716959612465, "heading_rate": -0.17923495588573124, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141205.531845} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2754356940132269, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.679363793522763, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3236869372808406, "gear": 1, "accelerator_pedal_position": 0.2754356940132269, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.365911530643445, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141205.531845} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.08995604515076, "x": 38.72388219628387, "y": 0.011262729970244578, "z": null, "yaw": 3.378199264918338, "pitch": null, "roll": null}, "v": 1.3086150761601805, "accelerator_pedal_position": 0.27519498111196483, "brake_pedal_position": 0.0, "acceleration": 0.18741314396623393, "steering_wheel_angle": -6.636984754720661, "front_wheel_angle": -0.33723716959612465, "heading_rate": -0.17923495588573124, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141205.551845} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2754356940132269, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.679363793522763, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3293156469271115, "gear": 1, "accelerator_pedal_position": 0.2754356940132269, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.365911530643445, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141205.551845} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141205.561845, "x": 42.58271320494714, "y": 4.97822689358041, "z": null, "yaw": 3.3636017453050746, "pitch": null, "roll": null}, "v": 1.3293156469271115, "accelerator_pedal_position": 0.2754356940132269, "brake_pedal_position": 0.0, "acceleration": 0.18733650434465982, "steering_wheel_angle": -6.365911530643445, "front_wheel_angle": -0.3219059731170858, "heading_rate": -0.17317764987867176, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141205.571845} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29208509845545316, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.725899055862442, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3330609419218404, "gear": 1, "accelerator_pedal_position": 0.2754356940132269, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.365911530643445, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141205.571845} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.19995594024658, "x": 38.58271320494714, "y": -0.02177310641959007, "z": null, "yaw": 3.3636017453050746, "pitch": null, "roll": null}, "v": 1.3293156469271115, "accelerator_pedal_position": 0.2754356940132269, "brake_pedal_position": 0.0, "acceleration": 0.18733650434465982, "steering_wheel_angle": -6.365911530643445, "front_wheel_angle": -0.3219059731170858, "heading_rate": -0.17317764987867176, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141205.591845} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28427727112581064, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.725899055862442, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3388808754726982, "gear": 1, "accelerator_pedal_position": 0.29208509845545316, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.365911530643445, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141205.591845} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.19995594024658, "x": 38.58271320494714, "y": -0.02177310641959007, "z": null, "yaw": 3.3636017453050746, "pitch": null, "roll": null}, "v": 1.3293156469271115, "accelerator_pedal_position": 0.2754356940132269, "brake_pedal_position": 0.0, "acceleration": 0.18733650434465982, "steering_wheel_angle": -6.365911530643445, "front_wheel_angle": -0.3219059731170858, "heading_rate": -0.17317764987867176, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141205.611845} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28427727112581064, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.725899055862442, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.343716275537659, "gear": 1, "accelerator_pedal_position": 0.28427727112581064, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.365911530643445, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141205.611845} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.19995594024658, "x": 38.58271320494714, "y": -0.02177310641959007, "z": null, "yaw": 3.3636017453050746, "pitch": null, "roll": null}, "v": 1.3293156469271115, "accelerator_pedal_position": 0.2754356940132269, "brake_pedal_position": 0.0, "acceleration": 0.18733650434465982, "steering_wheel_angle": -6.365911530643445, "front_wheel_angle": -0.3219059731170858, "heading_rate": -0.17317764987867176, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141205.631845} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28427727112581064, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.725899055862442, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.346131189502339, "gear": 1, "accelerator_pedal_position": 0.28427727112581064, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.365911530643445, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141205.631845} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.19995594024658, "x": 38.58271320494714, "y": -0.02177310641959007, "z": null, "yaw": 3.3636017453050746, "pitch": null, "roll": null}, "v": 1.3293156469271115, "accelerator_pedal_position": 0.2754356940132269, "brake_pedal_position": 0.0, "acceleration": 0.18733650434465982, "steering_wheel_angle": -6.365911530643445, "front_wheel_angle": -0.3219059731170858, "heading_rate": -0.17317764987867176, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141205.651845} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28427727112581064, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.725899055862442, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3533647902588966, "gear": 1, "accelerator_pedal_position": 0.28427727112581064, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.365911530643445, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141205.651845} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141205.671845, "x": 42.438601521759, "y": 4.946685296160793, "z": null, "yaw": 3.3492714080893142, "pitch": null, "roll": null}, "v": 1.355772277683579, "accelerator_pedal_position": 0.28427727112581064, "brake_pedal_position": 0.0, "acceleration": 0.24056314596278427, "steering_wheel_angle": -6.365911530643445, "front_wheel_angle": -0.3219059731170858, "heading_rate": -0.1766243084271542, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141205.671845} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2910799806346134, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.6330065086332795, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.355772277683579, "gear": 1, "accelerator_pedal_position": 0.28427727112581064, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.365911530643445, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141205.671845} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.30995583534241, "x": 38.438601521759, "y": -0.05331470383920678, "z": null, "yaw": 3.3492714080893142, "pitch": null, "roll": null}, "v": 1.355772277683579, "accelerator_pedal_position": 0.28427727112581064, "brake_pedal_position": 0.0, "acceleration": 0.24056314596278427, "steering_wheel_angle": -6.365911530643445, "front_wheel_angle": -0.3219059731170858, "heading_rate": -0.1766243084271542, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141205.691845} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28799550525801226, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.6330065086332795, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3610068542550102, "gear": 1, "accelerator_pedal_position": 0.2910799806346134, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.327015586390324, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141205.691845} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.30995583534241, "x": 38.438601521759, "y": -0.05331470383920678, "z": null, "yaw": 3.3492714080893142, "pitch": null, "roll": null}, "v": 1.355772277683579, "accelerator_pedal_position": 0.28427727112581064, "brake_pedal_position": 0.0, "acceleration": 0.24056314596278427, "steering_wheel_angle": -6.365911530643445, "front_wheel_angle": -0.3219059731170858, "heading_rate": -0.1766243084271542, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141205.711845} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28799550525801226, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.6330065086332795, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3689026955238799, "gear": 1, "accelerator_pedal_position": 0.28799550525801226, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.327015586390324, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141205.711845} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.30995583534241, "x": 38.438601521759, "y": -0.05331470383920678, "z": null, "yaw": 3.3492714080893142, "pitch": null, "roll": null}, "v": 1.355772277683579, "accelerator_pedal_position": 0.28427727112581064, "brake_pedal_position": 0.0, "acceleration": 0.24056314596278427, "steering_wheel_angle": -6.365911530643445, "front_wheel_angle": -0.3219059731170858, "heading_rate": -0.1766243084271542, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141205.731845} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28799550525801226, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.6330065086332795, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3741564179760046, "gear": 1, "accelerator_pedal_position": 0.28799550525801226, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.327015586390324, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141205.731845} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.30995583534241, "x": 38.438601521759, "y": -0.05331470383920678, "z": null, "yaw": 3.3492714080893142, "pitch": null, "roll": null}, "v": 1.355772277683579, "accelerator_pedal_position": 0.28427727112581064, "brake_pedal_position": 0.0, "acceleration": 0.24056314596278427, "steering_wheel_angle": -6.365911530643445, "front_wheel_angle": -0.3219059731170858, "heading_rate": -0.1766243084271542, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141205.751845} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28799550525801226, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.6330065086332795, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3794020048443392, "gear": 1, "accelerator_pedal_position": 0.28799550525801226, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.327015586390324, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141205.751845} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.30995583534241, "x": 38.438601521759, "y": -0.05331470383920678, "z": null, "yaw": 3.3492714080893142, "pitch": null, "roll": null}, "v": 1.355772277683579, "accelerator_pedal_position": 0.28427727112581064, "brake_pedal_position": 0.0, "acceleration": 0.24056314596278427, "steering_wheel_angle": -6.365911530643445, "front_wheel_angle": -0.3219059731170858, "heading_rate": -0.1766243084271542, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141205.7718449} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28799550525801226, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.6330065086332795, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3820217479314458, "gear": 1, "accelerator_pedal_position": 0.28799550525801226, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.327015586390324, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141205.7718449} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141205.7818449, "x": 42.29106275673214, "y": 4.916597783679711, "z": null, "yaw": 3.335026423859277, "pitch": null, "roll": null}, "v": 1.3846394577249304, "accelerator_pedal_position": 0.28799550525801226, "brake_pedal_position": 0.0, "acceleration": 0.26156767069744213, "steering_wheel_angle": -6.327015586390324, "front_wheel_angle": -0.3197195734936544, "heading_rate": -0.17907185750753138, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141205.7918448} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28564581167819264, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.356441303210973, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3872551344319048, "gear": 1, "accelerator_pedal_position": 0.28799550525801226, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.327015586390324, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141205.7918448} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.41995573043823, "x": 38.29106275673214, "y": -0.08340221632028921, "z": null, "yaw": 3.335026423859277, "pitch": null, "roll": null}, "v": 1.3846394577249304, "accelerator_pedal_position": 0.28799550525801226, "brake_pedal_position": 0.0, "acceleration": 0.26156767069744213, "steering_wheel_angle": -6.327015586390324, "front_wheel_angle": -0.3197195734936544, "heading_rate": -0.17907185750753138, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141205.8118448} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2869349569671656, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.356441303210973, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3947303149883727, "gear": 1, "accelerator_pedal_position": 0.2869349569671656, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.211157308332131, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141205.8118448} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.41995573043823, "x": 38.29106275673214, "y": -0.08340221632028921, "z": null, "yaw": 3.335026423859277, "pitch": null, "roll": null}, "v": 1.3846394577249304, "accelerator_pedal_position": 0.28799550525801226, "brake_pedal_position": 0.0, "acceleration": 0.26156767069744213, "steering_wheel_angle": -6.327015586390324, "front_wheel_angle": -0.3197195734936544, "heading_rate": -0.17907185750753138, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141205.8318448} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2869349569671656, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.356441303210973, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3972718573761715, "gear": 1, "accelerator_pedal_position": 0.2869349569671656, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.172421510975287, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141205.8318448} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.41995573043823, "x": 38.29106275673214, "y": -0.08340221632028921, "z": null, "yaw": 3.335026423859277, "pitch": null, "roll": null}, "v": 1.3846394577249304, "accelerator_pedal_position": 0.28799550525801226, "brake_pedal_position": 0.0, "acceleration": 0.26156767069744213, "steering_wheel_angle": -6.327015586390324, "front_wheel_angle": -0.3197195734936544, "heading_rate": -0.17907185750753138, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141205.8518448} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2869349569671656, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.356441303210973, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4048846033310127, "gear": 1, "accelerator_pedal_position": 0.2869349569671656, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.055865004892415, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141205.8518448} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.41995573043823, "x": 38.29106275673214, "y": -0.08340221632028921, "z": null, "yaw": 3.335026423859277, "pitch": null, "roll": null}, "v": 1.3846394577249304, "accelerator_pedal_position": 0.28799550525801226, "brake_pedal_position": 0.0, "acceleration": 0.26156767069744213, "steering_wheel_angle": -6.327015586390324, "front_wheel_angle": -0.3197195734936544, "heading_rate": -0.17907185750753138, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141205.8718448} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2869349569671656, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.356441303210973, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4074182257649275, "gear": 1, "accelerator_pedal_position": 0.2869349569671656, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.055865004892415, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141205.8718448} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141205.8918447, "x": 42.14004266202615, "y": 4.888016013438754, "z": null, "yaw": 3.3211928369799417, "pitch": null, "roll": null}, "v": 1.4124795328690223, "accelerator_pedal_position": 0.2869349569671656, "brake_pedal_position": 0.0, "acceleration": 0.25276852009359474, "steering_wheel_angle": -6.055865004892415, "front_wheel_angle": -0.3045694874329021, "heading_rate": -0.17344261493019816, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141205.8918447} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.290466220018856, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.199214308596593, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4124795328690223, "gear": 1, "accelerator_pedal_position": 0.2869349569671656, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.055865004892415, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141205.8918447} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.52995562553406, "x": 38.14004266202615, "y": -0.11198398656124642, "z": null, "yaw": 3.3211928369799417, "pitch": null, "roll": null}, "v": 1.4124795328690223, "accelerator_pedal_position": 0.2869349569671656, "brake_pedal_position": 0.0, "acceleration": 0.25276852009359474, "steering_wheel_angle": -6.055865004892415, "front_wheel_angle": -0.3045694874329021, "heading_rate": -0.17344261493019816, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141205.9118447} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28895005390626405, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.199214308596593, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4206234860111986, "gear": 1, "accelerator_pedal_position": 0.28895005390626405, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.939450048931138, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141205.9118447} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.52995562553406, "x": 38.14004266202615, "y": -0.11198398656124642, "z": null, "yaw": 3.3211928369799417, "pitch": null, "roll": null}, "v": 1.4124795328690223, "accelerator_pedal_position": 0.2869349569671656, "brake_pedal_position": 0.0, "acceleration": 0.25276852009359474, "steering_wheel_angle": -6.055865004892415, "front_wheel_angle": -0.3045694874329021, "heading_rate": -0.17344261493019816, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141205.9318447} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28895005390626405, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.199214308596593, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4232707355284338, "gear": 1, "accelerator_pedal_position": 0.28895005390626405, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.900530007986481, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141205.9318447} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.52995562553406, "x": 38.14004266202615, "y": -0.11198398656124642, "z": null, "yaw": 3.3211928369799417, "pitch": null, "roll": null}, "v": 1.4124795328690223, "accelerator_pedal_position": 0.2869349569671656, "brake_pedal_position": 0.0, "acceleration": 0.25276852009359474, "steering_wheel_angle": -6.055865004892415, "front_wheel_angle": -0.3045694874329021, "heading_rate": -0.17344261493019816, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141205.9518447} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28895005390626405, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.199214308596593, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.43120002615145, "gear": 1, "accelerator_pedal_position": 0.28895005390626405, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.900530007986481, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141205.9518447} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.52995562553406, "x": 38.14004266202615, "y": -0.11198398656124642, "z": null, "yaw": 3.3211928369799417, "pitch": null, "roll": null}, "v": 1.4124795328690223, "accelerator_pedal_position": 0.2869349569671656, "brake_pedal_position": 0.0, "acceleration": 0.25276852009359474, "steering_wheel_angle": -6.055865004892415, "front_wheel_angle": -0.3045694874329021, "heading_rate": -0.17344261493019816, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141205.9718447} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28895005390626405, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.199214308596593, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.436475840620073, "gear": 1, "accelerator_pedal_position": 0.28895005390626405, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.900530007986481, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141205.9718447} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.52995562553406, "x": 38.14004266202615, "y": -0.11198398656124642, "z": null, "yaw": 3.3211928369799417, "pitch": null, "roll": null}, "v": 1.4124795328690223, "accelerator_pedal_position": 0.2869349569671656, "brake_pedal_position": 0.0, "acceleration": 0.25276852009359474, "steering_wheel_angle": -6.055865004892415, "front_wheel_angle": -0.3045694874329021, "heading_rate": -0.17344261493019816, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141205.9918447} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28895005390626405, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.199214308596593, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.44174335389467, "gear": 1, "accelerator_pedal_position": 0.28895005390626405, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.900530007986481, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141205.9918447} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141206.0018446, "x": 41.98555308920282, "y": 4.860932336516457, "z": null, "yaw": 3.307998886794142, "pitch": null, "roll": null}, "v": 1.44174335389467, "accelerator_pedal_position": 0.28895005390626405, "brake_pedal_position": 0.0, "acceleration": 0.26306443023442216, "steering_wheel_angle": -5.900530007986481, "front_wheel_angle": -0.29596137432464553, "heading_rate": -0.17172327414512775, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141206.0118446} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.291415375493642, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.051866775573054, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4470025679423906, "gear": 1, "accelerator_pedal_position": 0.28895005390626405, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.900530007986481, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141206.0118446} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.63995552062988, "x": 37.98555308920282, "y": -0.1390676634835426, "z": null, "yaw": 3.307998886794142, "pitch": null, "roll": null}, "v": 1.44174335389467, "accelerator_pedal_position": 0.28895005390626405, "brake_pedal_position": 0.0, "acceleration": 0.26306443023442216, "steering_wheel_angle": -5.900530007986481, "front_wheel_angle": -0.29596137432464553, "heading_rate": -0.17172327414512775, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141206.0318446} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29041653200857515, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.051866775573054, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4497831459836088, "gear": 1, "accelerator_pedal_position": 0.291415375493642, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.861757460915612, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141206.0318446} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.63995552062988, "x": 37.98555308920282, "y": -0.1390676634835426, "z": null, "yaw": 3.307998886794142, "pitch": null, "roll": null}, "v": 1.44174335389467, "accelerator_pedal_position": 0.28895005390626405, "brake_pedal_position": 0.0, "acceleration": 0.26306443023442216, "steering_wheel_angle": -5.900530007986481, "front_wheel_angle": -0.29596137432464553, "heading_rate": -0.17172327414512775, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141206.0518446} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29041653200857515, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.051866775573054, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4579245712157491, "gear": 1, "accelerator_pedal_position": 0.29041653200857515, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.784041592812641, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141206.0518446} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.63995552062988, "x": 37.98555308920282, "y": -0.1390676634835426, "z": null, "yaw": 3.307998886794142, "pitch": null, "roll": null}, "v": 1.44174335389467, "accelerator_pedal_position": 0.28895005390626405, "brake_pedal_position": 0.0, "acceleration": 0.26306443023442216, "steering_wheel_angle": -5.900530007986481, "front_wheel_angle": -0.29596137432464553, "heading_rate": -0.17172327414512775, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141206.0718446} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29041653200857515, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.051866775573054, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4633414587879532, "gear": 1, "accelerator_pedal_position": 0.29041653200857515, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.784041592812641, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141206.0718446} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.63995552062988, "x": 37.98555308920282, "y": -0.1390676634835426, "z": null, "yaw": 3.307998886794142, "pitch": null, "roll": null}, "v": 1.44174335389467, "accelerator_pedal_position": 0.28895005390626405, "brake_pedal_position": 0.0, "acceleration": 0.26306443023442216, "steering_wheel_angle": -5.900530007986481, "front_wheel_angle": -0.29596137432464553, "heading_rate": -0.17172327414512775, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141206.0918446} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29041653200857515, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.051866775573054, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4660466844865945, "gear": 1, "accelerator_pedal_position": 0.29041653200857515, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.784041592812641, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141206.0918446} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141206.1118445, "x": 41.82753794225987, "y": 4.835353772215542, "z": null, "yaw": 3.29508858218896, "pitch": null, "roll": null}, "v": 1.4714507008875102, "accelerator_pedal_position": 0.29041653200857515, "brake_pedal_position": 0.0, "acceleration": 0.26987911835779566, "steering_wheel_angle": -5.784041592812641, "front_wheel_angle": -0.28953922353535033, "heading_rate": -0.17123492916239835, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141206.1118445} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2847335514598174, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.701962312905515, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4714507008875102, "gear": 1, "accelerator_pedal_position": 0.29041653200857515, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.784041592812641, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141206.1118445} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.74995541572571, "x": 37.82753794225987, "y": -0.16464622778445825, "z": null, "yaw": 3.29508858218896, "pitch": null, "roll": null}, "v": 1.4714507008875102, "accelerator_pedal_position": 0.29041653200857515, "brake_pedal_position": 0.0, "acceleration": 0.26987911835779566, "steering_wheel_angle": -5.784041592812641, "front_wheel_angle": -0.28953922353535033, "heading_rate": -0.17123492916239835, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141206.1318445} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2876188426874936, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.701962312905515, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4784759298130725, "gear": 1, "accelerator_pedal_position": 0.2847335514598174, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.66847382973211, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141206.1318445} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.74995541572571, "x": 37.82753794225987, "y": -0.16464622778445825, "z": null, "yaw": 3.29508858218896, "pitch": null, "roll": null}, "v": 1.4714507008875102, "accelerator_pedal_position": 0.29041653200857515, "brake_pedal_position": 0.0, "acceleration": 0.26987911835779566, "steering_wheel_angle": -5.784041592812641, "front_wheel_angle": -0.28953922353535033, "heading_rate": -0.17123492916239835, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141206.1518445} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2876188426874936, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.701962312905515, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4835106265305344, "gear": 1, "accelerator_pedal_position": 0.2876188426874936, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.591150945404218, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141206.1518445} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.74995541572571, "x": 37.82753794225987, "y": -0.16464622778445825, "z": null, "yaw": 3.29508858218896, "pitch": null, "roll": null}, "v": 1.4714507008875102, "accelerator_pedal_position": 0.29041653200857515, "brake_pedal_position": 0.0, "acceleration": 0.26987911835779566, "steering_wheel_angle": -5.784041592812641, "front_wheel_angle": -0.28953922353535033, "heading_rate": -0.17123492916239835, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141206.1718445} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2876188426874936, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.701962312905515, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4885373066703464, "gear": 1, "accelerator_pedal_position": 0.2876188426874936, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.513605893923628, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141206.1718445} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.74995541572571, "x": 37.82753794225987, "y": -0.16464622778445825, "z": null, "yaw": 3.29508858218896, "pitch": null, "roll": null}, "v": 1.4714507008875102, "accelerator_pedal_position": 0.29041653200857515, "brake_pedal_position": 0.0, "acceleration": 0.26987911835779566, "steering_wheel_angle": -5.784041592812641, "front_wheel_angle": -0.28953922353535033, "heading_rate": -0.17123492916239835, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141206.1918445} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2876188426874936, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.701962312905515, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4935559728940575, "gear": 1, "accelerator_pedal_position": 0.2876188426874936, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.435838675290342, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141206.1918445} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.74995541572571, "x": 37.82753794225987, "y": -0.16464622778445825, "z": null, "yaw": 3.29508858218896, "pitch": null, "roll": null}, "v": 1.4714507008875102, "accelerator_pedal_position": 0.29041653200857515, "brake_pedal_position": 0.0, "acceleration": 0.26987911835779566, "steering_wheel_angle": -5.784041592812641, "front_wheel_angle": -0.28953922353535033, "heading_rate": -0.17123492916239835, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141206.2118444} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2876188426874936, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.701962312905515, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4985666279072787, "gear": 1, "accelerator_pedal_position": 0.2876188426874936, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.435838675290342, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141206.2118444} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141206.2218444, "x": 41.66612214614476, "y": 4.811322403375983, "z": null, "yaw": 3.2827713151036884, "pitch": null, "roll": null}, "v": 1.4985666279072787, "accelerator_pedal_position": 0.2876188426874936, "brake_pedal_position": 0.0, "acceleration": 0.25023241601869706, "steering_wheel_angle": -5.435838675290342, "front_wheel_angle": -0.27050822905917943, "heading_rate": -0.16232834879262695, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141206.2318444} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28299251562660593, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.362958725348171, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5035692744595142, "gear": 1, "accelerator_pedal_position": 0.2876188426874936, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.435838675290342, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141206.2318444} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.85995531082153, "x": 37.66612214614476, "y": -0.18867759662401706, "z": null, "yaw": 3.2827713151036884, "pitch": null, "roll": null}, "v": 1.4985666279072787, "accelerator_pedal_position": 0.2876188426874936, "brake_pedal_position": 0.0, "acceleration": 0.25023241601869706, "steering_wheel_angle": -5.435838675290342, "front_wheel_angle": -0.27050822905917943, "heading_rate": -0.16232834879262695, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141206.2518444} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2853601882922485, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.362958725348171, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5079858561202577, "gear": 1, "accelerator_pedal_position": 0.28299251562660593, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.358752452547616, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141206.2518444} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.85995531082153, "x": 37.66612214614476, "y": -0.18867759662401706, "z": null, "yaw": 3.2827713151036884, "pitch": null, "roll": null}, "v": 1.4985666279072787, "accelerator_pedal_position": 0.2876188426874936, "brake_pedal_position": 0.0, "acceleration": 0.25023241601869706, "steering_wheel_angle": -5.435838675290342, "front_wheel_angle": -0.27050822905917943, "heading_rate": -0.16232834879262695, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141206.2718444} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2853601882922485, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.362958725348171, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5103394728262372, "gear": 1, "accelerator_pedal_position": 0.2853601882922485, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.320127944259389, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141206.2718444} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.85995531082153, "x": 37.66612214614476, "y": -0.18867759662401706, "z": null, "yaw": 3.2827713151036884, "pitch": null, "roll": null}, "v": 1.4985666279072787, "accelerator_pedal_position": 0.2876188426874936, "brake_pedal_position": 0.0, "acceleration": 0.25023241601869706, "steering_wheel_angle": -5.435838675290342, "front_wheel_angle": -0.27050822905917943, "heading_rate": -0.16232834879262695, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141206.2918444} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2853601882922485, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.362958725348171, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5173890013344566, "gear": 1, "accelerator_pedal_position": 0.2853601882922485, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.20392883172725, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141206.2918444} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.85995531082153, "x": 37.66612214614476, "y": -0.18867759662401706, "z": null, "yaw": 3.2827713151036884, "pitch": null, "roll": null}, "v": 1.4985666279072787, "accelerator_pedal_position": 0.2876188426874936, "brake_pedal_position": 0.0, "acceleration": 0.25023241601869706, "steering_wheel_angle": -5.435838675290342, "front_wheel_angle": -0.27050822905917943, "heading_rate": -0.16232834879262695, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141206.3118443} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2853601882922485, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.362958725348171, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.522079256427547, "gear": 1, "accelerator_pedal_position": 0.2853601882922485, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.126191433649607, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141206.3118443} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141206.3318443, "x": 41.50151054068959, "y": 4.788827506228281, "z": null, "yaw": 3.271171353207392, "pitch": null, "roll": null}, "v": 1.524421556041314, "accelerator_pedal_position": 0.2853601882922485, "brake_pedal_position": 0.0, "acceleration": 0.23404148821925325, "steering_wheel_angle": -5.0872413376939205, "front_wheel_angle": -0.25169731486861774, "heading_rate": -0.15312736273570535, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141206.3318443} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2864410572641989, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.166652730357027, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.524421556041314, "gear": 1, "accelerator_pedal_position": 0.2853601882922485, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.0872413376939205, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141206.3318443} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.96995520591736, "x": 37.50151054068959, "y": -0.21117249377171898, "z": null, "yaw": 3.271171353207392, "pitch": null, "roll": null}, "v": 1.524421556041314, "accelerator_pedal_position": 0.2853601882922485, "brake_pedal_position": 0.0, "acceleration": 0.23404148821925325, "steering_wheel_angle": -5.0872413376939205, "front_wheel_angle": -0.25169731486861774, "heading_rate": -0.15312736273570535, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141206.3518443} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2860844023625654, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.166652730357027, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.529235555710736, "gear": 1, "accelerator_pedal_position": 0.2864410572641989, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.0096936566549815, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141206.3518443} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.96995520591736, "x": 37.50151054068959, "y": -0.21117249377171898, "z": null, "yaw": 3.271171353207392, "pitch": null, "roll": null}, "v": 1.524421556041314, "accelerator_pedal_position": 0.2853601882922485, "brake_pedal_position": 0.0, "acceleration": 0.23404148821925325, "steering_wheel_angle": -5.0872413376939205, "front_wheel_angle": -0.25169731486861774, "heading_rate": -0.15312736273570535, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141206.3718443} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2860844023625654, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.166652730357027, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5339972382384366, "gear": 1, "accelerator_pedal_position": 0.2860844023625654, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.931931769452873, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141206.3718443} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.96995520591736, "x": 37.50151054068959, "y": -0.21117249377171898, "z": null, "yaw": 3.271171353207392, "pitch": null, "roll": null}, "v": 1.524421556041314, "accelerator_pedal_position": 0.2853601882922485, "brake_pedal_position": 0.0, "acceleration": 0.23404148821925325, "steering_wheel_angle": -5.0872413376939205, "front_wheel_angle": -0.25169731486861774, "heading_rate": -0.15312736273570535, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141206.3918443} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2860844023625654, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.166652730357027, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5387512426864167, "gear": 1, "accelerator_pedal_position": 0.2860844023625654, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.89297049854063, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141206.3918443} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.96995520591736, "x": 37.50151054068959, "y": -0.21117249377171898, "z": null, "yaw": 3.271171353207392, "pitch": null, "roll": null}, "v": 1.524421556041314, "accelerator_pedal_position": 0.2853601882922485, "brake_pedal_position": 0.0, "acceleration": 0.23404148821925325, "steering_wheel_angle": -5.0872413376939205, "front_wheel_angle": -0.25169731486861774, "heading_rate": -0.15312736273570535, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141206.4118443} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2860844023625654, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.166652730357027, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5434975723987896, "gear": 1, "accelerator_pedal_position": 0.2860844023625654, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.89297049854063, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141206.4118443} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.96995520591736, "x": 37.50151054068959, "y": -0.21117249377171898, "z": null, "yaw": 3.271171353207392, "pitch": null, "roll": null}, "v": 1.524421556041314, "accelerator_pedal_position": 0.2853601882922485, "brake_pedal_position": 0.0, "acceleration": 0.23404148821925325, "steering_wheel_angle": -5.0872413376939205, "front_wheel_angle": -0.25169731486861774, "heading_rate": -0.15312736273570535, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141206.4318442} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2860844023625654, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.166652730357027, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5482362307580224, "gear": 1, "accelerator_pedal_position": 0.2860844023625654, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.89297049854063, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141206.4318442} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141206.4418442, "x": 41.3338231159173, "y": 4.7678154986894965, "z": null, "yaw": 3.2604669699136792, "pitch": null, "roll": null}, "v": 1.5506026842476806, "accelerator_pedal_position": 0.2860844023625654, "brake_pedal_position": 0.0, "acceleration": 0.23645369370968844, "steering_wheel_angle": -4.89297049854063, "front_wheel_angle": -0.24131569710667994, "heading_rate": -0.14907084868081688, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141206.4518442} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2841912671012558, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.9229804789109997, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5529672211847774, "gear": 1, "accelerator_pedal_position": 0.2860844023625654, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.89297049854063, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141206.4518442} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.079955101013184, "x": 37.3338231159173, "y": -0.2321845013105035, "z": null, "yaw": 3.2604669699136792, "pitch": null, "roll": null}, "v": 1.5506026842476806, "accelerator_pedal_position": 0.2860844023625654, "brake_pedal_position": 0.0, "acceleration": 0.23645369370968844, "steering_wheel_angle": -4.89297049854063, "front_wheel_angle": -0.24131569710667994, "heading_rate": -0.14907084868081688, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141206.4718442} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28525383737165455, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.9229804789109997, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5574540011947897, "gear": 1, "accelerator_pedal_position": 0.2841912671012558, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.81551729074314, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141206.4718442} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.079955101013184, "x": 37.3338231159173, "y": -0.2321845013105035, "z": null, "yaw": 3.2604669699136792, "pitch": null, "roll": null}, "v": 1.5506026842476806, "accelerator_pedal_position": 0.2860844023625654, "brake_pedal_position": 0.0, "acceleration": 0.23645369370968844, "steering_wheel_angle": -4.89297049854063, "front_wheel_angle": -0.24131569710667994, "heading_rate": -0.14907084868081688, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141206.4918442} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28525383737165455, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.9229804789109997, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5643695981685612, "gear": 1, "accelerator_pedal_position": 0.28525383737165455, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.698942288556795, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141206.4918442} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.079955101013184, "x": 37.3338231159173, "y": -0.2321845013105035, "z": null, "yaw": 3.2604669699136792, "pitch": null, "roll": null}, "v": 1.5506026842476806, "accelerator_pedal_position": 0.2860844023625654, "brake_pedal_position": 0.0, "acceleration": 0.23645369370968844, "steering_wheel_angle": -4.89297049854063, "front_wheel_angle": -0.24131569710667994, "heading_rate": -0.14907084868081688, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141206.5118442} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28525383737165455, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.9229804789109997, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.568970636471651, "gear": 1, "accelerator_pedal_position": 0.28525383737165455, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.659978570363984, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141206.5118442} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.079955101013184, "x": 37.3338231159173, "y": -0.2321845013105035, "z": null, "yaw": 3.2604669699136792, "pitch": null, "roll": null}, "v": 1.5506026842476806, "accelerator_pedal_position": 0.2860844023625654, "brake_pedal_position": 0.0, "acceleration": 0.23645369370968844, "steering_wheel_angle": -4.89297049854063, "front_wheel_angle": -0.24131569710667994, "heading_rate": -0.14907084868081688, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141206.5318441} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28525383737165455, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.9229804789109997, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.57356419134202, "gear": 1, "accelerator_pedal_position": 0.28525383737165455, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.659978570363984, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141206.5318441} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141206.5518441, "x": 41.16311293646668, "y": 4.748244966659612, "z": null, "yaw": 3.250223786471403, "pitch": null, "roll": null}, "v": 1.57585816365565, "accelerator_pedal_position": 0.28525383737165455, "brake_pedal_position": 0.0, "acceleration": 0.22921028587045678, "steering_wheel_angle": -4.659978570363984, "front_wheel_angle": -0.22895813203198762, "heading_rate": -0.1434551968995213, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141206.5518441} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28610100625085555, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.7490052290269418, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5781502665143545, "gear": 1, "accelerator_pedal_position": 0.28525383737165455, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.659978570363984, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141206.5518441} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.18995499610901, "x": 37.16311293646668, "y": -0.2517550333403884, "z": null, "yaw": 3.250223786471403, "pitch": null, "roll": null}, "v": 1.57585816365565, "accelerator_pedal_position": 0.28525383737165455, "brake_pedal_position": 0.0, "acceleration": 0.22921028587045678, "steering_wheel_angle": -4.659978570363984, "front_wheel_angle": -0.22895813203198762, "heading_rate": -0.1434551968995213, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141206.571844} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2858539639294306, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.7490052290269418, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5804934484454058, "gear": 1, "accelerator_pedal_position": 0.28610100625085555, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.621183948470004, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141206.571844} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.18995499610901, "x": 37.16311293646668, "y": -0.2517550333403884, "z": null, "yaw": 3.250223786471403, "pitch": null, "roll": null}, "v": 1.57585816365565, "accelerator_pedal_position": 0.28525383737165455, "brake_pedal_position": 0.0, "acceleration": 0.22921028587045678, "steering_wheel_angle": -4.659978570363984, "front_wheel_angle": -0.22895813203198762, "heading_rate": -0.1434551968995213, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141206.591844} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2858539639294306, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.7490052290269418, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5874652431732283, "gear": 1, "accelerator_pedal_position": 0.2858539639294306, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.504487512111775, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141206.591844} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.18995499610901, "x": 37.16311293646668, "y": -0.2517550333403884, "z": null, "yaw": 3.250223786471403, "pitch": null, "roll": null}, "v": 1.57585816365565, "accelerator_pedal_position": 0.28525383737165455, "brake_pedal_position": 0.0, "acceleration": 0.22921028587045678, "steering_wheel_angle": -4.659978570363984, "front_wheel_angle": -0.22895813203198762, "heading_rate": -0.1434551968995213, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141206.611844} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2858539639294306, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.7490052290269418, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5921036170086034, "gear": 1, "accelerator_pedal_position": 0.2858539639294306, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.504487512111775, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141206.611844} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.18995499610901, "x": 37.16311293646668, "y": -0.2517550333403884, "z": null, "yaw": 3.250223786471403, "pitch": null, "roll": null}, "v": 1.57585816365565, "accelerator_pedal_position": 0.28525383737165455, "brake_pedal_position": 0.0, "acceleration": 0.22921028587045678, "steering_wheel_angle": -4.659978570363984, "front_wheel_angle": -0.22895813203198762, "heading_rate": -0.1434551968995213, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141206.631844} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2858539639294306, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.7490052290269418, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.596734403818849, "gear": 1, "accelerator_pedal_position": 0.2858539639294306, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.504487512111775, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141206.631844} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.18995499610901, "x": 37.16311293646668, "y": -0.2517550333403884, "z": null, "yaw": 3.250223786471403, "pitch": null, "roll": null}, "v": 1.57585816365565, "accelerator_pedal_position": 0.28525383737165455, "brake_pedal_position": 0.0, "acceleration": 0.22921028587045678, "steering_wheel_angle": -4.659978570363984, "front_wheel_angle": -0.22895813203198762, "heading_rate": -0.1434551968995213, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141206.651844} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2858539639294306, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.7490052290269418, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6013576074399594, "gear": 1, "accelerator_pedal_position": 0.2858539639294306, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.504487512111775, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141206.651844} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141206.661844, "x": 40.98943951085071, "y": 4.73009240978086, "z": null, "yaw": 3.2404627337084726, "pitch": null, "roll": null}, "v": 1.6013576074399594, "accelerator_pedal_position": 0.2858539639294306, "brake_pedal_position": 0.0, "acceleration": 0.23087593231788478, "steering_wheel_angle": -4.504487512111775, "front_wheel_angle": -0.2207665548571875, "heading_rate": -0.14038429486579115, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141206.671844} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28222799792797315, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.459134970385826, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6059732317437572, "gear": 1, "accelerator_pedal_position": 0.2858539639294306, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.504487512111775, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141206.671844} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.299954891204834, "x": 36.98943951085071, "y": -0.2699075902191401, "z": null, "yaw": 3.2404627337084726, "pitch": null, "roll": null}, "v": 1.6013576074399594, "accelerator_pedal_position": 0.2858539639294306, "brake_pedal_position": 0.0, "acceleration": 0.23087593231788478, "steering_wheel_angle": -4.504487512111775, "front_wheel_angle": -0.2207665548571875, "heading_rate": -0.14038429486579115, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141206.691844} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28411351750208447, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.459134970385826, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6101282210883832, "gear": 1, "accelerator_pedal_position": 0.28222799792797315, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.427156818458842, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141206.691844} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.299954891204834, "x": 36.98943951085071, "y": -0.2699075902191401, "z": null, "yaw": 3.2404627337084726, "pitch": null, "roll": null}, "v": 1.6013576074399594, "accelerator_pedal_position": 0.2858539639294306, "brake_pedal_position": 0.0, "acceleration": 0.23087593231788478, "steering_wheel_angle": -4.504487512111775, "front_wheel_angle": -0.2207665548571875, "heading_rate": -0.14038429486579115, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141206.711844} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28411351750208447, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.459134970385826, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6145119769756227, "gear": 1, "accelerator_pedal_position": 0.28411351750208447, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.349621604880844, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141206.711844} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.299954891204834, "x": 36.98943951085071, "y": -0.2699075902191401, "z": null, "yaw": 3.2404627337084726, "pitch": null, "roll": null}, "v": 1.6013576074399594, "accelerator_pedal_position": 0.2858539639294306, "brake_pedal_position": 0.0, "acceleration": 0.23087593231788478, "steering_wheel_angle": -4.504487512111775, "front_wheel_angle": -0.2207665548571875, "heading_rate": -0.14038429486579115, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141206.731844} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28411351750208447, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.459134970385826, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6188885229459016, "gear": 1, "accelerator_pedal_position": 0.28411351750208447, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.271881871377783, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141206.731844} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.299954891204834, "x": 36.98943951085071, "y": -0.2699075902191401, "z": null, "yaw": 3.2404627337084726, "pitch": null, "roll": null}, "v": 1.6013576074399594, "accelerator_pedal_position": 0.2858539639294306, "brake_pedal_position": 0.0, "acceleration": 0.23087593231788478, "steering_wheel_angle": -4.504487512111775, "front_wheel_angle": -0.2207665548571875, "heading_rate": -0.14038429486579115, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141206.751844} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28411351750208447, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.459134970385826, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6232578631987857, "gear": 1, "accelerator_pedal_position": 0.28411351750208447, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.232935309654352, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141206.751844} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141206.771844, "x": 40.812872829452495, "y": 4.713350116651062, "z": null, "yaw": 3.231110144632493, "pitch": null, "roll": null}, "v": 1.625439832502023, "accelerator_pedal_position": 0.28411351750208447, "brake_pedal_position": 0.0, "acceleration": 0.21801694627208468, "steering_wheel_angle": -4.232935309654352, "front_wheel_angle": -0.20656470549941106, "heading_rate": -0.13305348808949696, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141206.771844} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2854486705938967, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.298865750228787, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.625439832502023, "gear": 1, "accelerator_pedal_position": 0.28411351750208447, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.232935309654352, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141206.771844} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.40995478630066, "x": 36.812872829452495, "y": -0.2866498833489377, "z": null, "yaw": 3.231110144632493, "pitch": null, "roll": null}, "v": 1.625439832502023, "accelerator_pedal_position": 0.28411351750208447, "brake_pedal_position": 0.0, "acceleration": 0.21801694627208468, "steering_wheel_angle": -4.232935309654352, "front_wheel_angle": -0.20656470549941106, "heading_rate": -0.13305348808949696, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141206.791844} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28496383142225534, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.298865750228787, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6322250780277556, "gear": 1, "accelerator_pedal_position": 0.2854486705938967, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.116385415544194, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141206.791844} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.40995478630066, "x": 36.812872829452495, "y": -0.2866498833489377, "z": null, "yaw": 3.231110144632493, "pitch": null, "roll": null}, "v": 1.625439832502023, "accelerator_pedal_position": 0.28411351750208447, "brake_pedal_position": 0.0, "acceleration": 0.21801694627208468, "steering_wheel_angle": -4.232935309654352, "front_wheel_angle": -0.20656470549941106, "heading_rate": -0.13305348808949696, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141206.8118439} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28496383142225534, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.298865750228787, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6366786585594744, "gear": 1, "accelerator_pedal_position": 0.28496383142225534, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.0774342277275695, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141206.8118439} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.40995478630066, "x": 36.812872829452495, "y": -0.2866498833489377, "z": null, "yaw": 3.231110144632493, "pitch": null, "roll": null}, "v": 1.625439832502023, "accelerator_pedal_position": 0.28411351750208447, "brake_pedal_position": 0.0, "acceleration": 0.21801694627208468, "steering_wheel_angle": -4.232935309654352, "front_wheel_angle": -0.20656470549941106, "heading_rate": -0.13305348808949696, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141206.8318439} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28496383142225534, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.298865750228787, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6411248749096, "gear": 1, "accelerator_pedal_position": 0.28496383142225534, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.0774342277275695, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141206.8318439} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.40995478630066, "x": 36.812872829452495, "y": -0.2866498833489377, "z": null, "yaw": 3.231110144632493, "pitch": null, "roll": null}, "v": 1.625439832502023, "accelerator_pedal_position": 0.28411351750208447, "brake_pedal_position": 0.0, "acceleration": 0.21801694627208468, "steering_wheel_angle": -4.232935309654352, "front_wheel_angle": -0.20656470549941106, "heading_rate": -0.13305348808949696, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141206.8518438} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28496383142225534, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.298865750228787, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6433452228505314, "gear": 1, "accelerator_pedal_position": 0.28496383142225534, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.0774342277275695, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141206.8518438} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.40995478630066, "x": 36.812872829452495, "y": -0.2866498833489377, "z": null, "yaw": 3.231110144632493, "pitch": null, "roll": null}, "v": 1.625439832502023, "accelerator_pedal_position": 0.28411351750208447, "brake_pedal_position": 0.0, "acceleration": 0.21801694627208468, "steering_wheel_angle": -4.232935309654352, "front_wheel_angle": -0.20656470549941106, "heading_rate": -0.13305348808949696, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141206.8718438} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28496383142225534, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.298865750228787, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6477804009496722, "gear": 1, "accelerator_pedal_position": 0.28496383142225534, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.0774342277275695, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141206.8718438} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141206.8818438, "x": 40.633499379736634, "y": 4.697974221681741, "z": null, "yaw": 3.22238530910261, "pitch": null, "roll": null}, "v": 1.6499952321881128, "accelerator_pedal_position": 0.28496383142225534, "brake_pedal_position": 0.0, "acceleration": 0.2212993421172551, "steering_wheel_angle": -4.0774342277275695, "front_wheel_angle": -0.19849060996869194, "heading_rate": -0.12964006226371505, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141206.8918438} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28181519605972033, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.038861383053518, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6522082256092854, "gear": 1, "accelerator_pedal_position": 0.28496383142225534, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.0774342277275695, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141206.8918438} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.519954681396484, "x": 36.633499379736634, "y": -0.30202577831825916, "z": null, "yaw": 3.22238530910261, "pitch": null, "roll": null}, "v": 1.6499952321881128, "accelerator_pedal_position": 0.28496383142225534, "brake_pedal_position": 0.0, "acceleration": 0.2212993421172551, "steering_wheel_angle": -4.0774342277275695, "front_wheel_angle": -0.19849060996869194, "heading_rate": -0.12964006226371505, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141206.9118438} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2834693711467572, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.038861383053518, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6562352852674405, "gear": 1, "accelerator_pedal_position": 0.28181519605972033, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.000014978805834, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141206.9118438} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.519954681396484, "x": 36.633499379736634, "y": -0.30202577831825916, "z": null, "yaw": 3.22238530910261, "pitch": null, "roll": null}, "v": 1.6499952321881128, "accelerator_pedal_position": 0.28496383142225534, "brake_pedal_position": 0.0, "acceleration": 0.2212993421172551, "steering_wheel_angle": -4.0774342277275695, "front_wheel_angle": -0.19849060996869194, "heading_rate": -0.12964006226371505, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141206.9318438} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2834693711467572, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.038861383053518, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6604623402702146, "gear": 1, "accelerator_pedal_position": 0.2834693711467572, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.922396559813811, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141206.9318438} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.519954681396484, "x": 36.633499379736634, "y": -0.30202577831825916, "z": null, "yaw": 3.22238530910261, "pitch": null, "roll": null}, "v": 1.6499952321881128, "accelerator_pedal_position": 0.28496383142225534, "brake_pedal_position": 0.0, "acceleration": 0.2212993421172551, "steering_wheel_angle": -4.0774342277275695, "front_wheel_angle": -0.19849060996869194, "heading_rate": -0.12964006226371505, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141206.9518437} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2834693711467572, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.038861383053518, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.664682365384503, "gear": 1, "accelerator_pedal_position": 0.2834693711467572, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.8445789707514977, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141206.9518437} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.519954681396484, "x": 36.633499379736634, "y": -0.30202577831825916, "z": null, "yaw": 3.22238530910261, "pitch": null, "roll": null}, "v": 1.6499952321881128, "accelerator_pedal_position": 0.28496383142225534, "brake_pedal_position": 0.0, "acceleration": 0.2212993421172551, "steering_wheel_angle": -4.0774342277275695, "front_wheel_angle": -0.19849060996869194, "heading_rate": -0.12964006226371505, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141206.9718437} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2834693711467572, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.038861383053518, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6688953651810223, "gear": 1, "accelerator_pedal_position": 0.2834693711467572, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.805595487443983, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141206.9718437} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141206.9918437, "x": 40.45138617165204, "y": 4.683934263751524, "z": null, "yaw": 3.21408361383655, "pitch": null, "roll": null}, "v": 1.673101344258432, "accelerator_pedal_position": 0.2834693711467572, "brake_pedal_position": 0.0, "acceleration": 0.21003582137271704, "steering_wheel_angle": -3.805595487443983, "front_wheel_angle": -0.1844757382302936, "heading_rate": -0.12195161973525857, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141206.9918437} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28032544713785484, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.769020077741069, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.673101344258432, "gear": 1, "accelerator_pedal_position": 0.2834693711467572, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.805595487443983, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141206.9918437} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.62995457649231, "x": 36.45138617165204, "y": -0.31606573624847556, "z": null, "yaw": 3.21408361383655, "pitch": null, "roll": null}, "v": 1.673101344258432, "accelerator_pedal_position": 0.2834693711467572, "brake_pedal_position": 0.0, "acceleration": 0.21003582137271704, "steering_wheel_angle": -3.805595487443983, "front_wheel_angle": -0.1844757382302936, "heading_rate": -0.12195161973525857, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141207.0118437} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2819690798886975, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.769020077741069, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.678808165655469, "gear": 1, "accelerator_pedal_position": 0.28032544713785484, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.6893205001717972, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141207.0118437} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.62995457649231, "x": 36.45138617165204, "y": -0.31606573624847556, "z": null, "yaw": 3.21408361383655, "pitch": null, "roll": null}, "v": 1.673101344258432, "accelerator_pedal_position": 0.2834693711467572, "brake_pedal_position": 0.0, "acceleration": 0.21003582137271704, "steering_wheel_angle": -3.805595487443983, "front_wheel_angle": -0.1844757382302936, "heading_rate": -0.12195161973525857, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141207.0318437} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2819690798886975, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.769020077741069, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6808099893799777, "gear": 1, "accelerator_pedal_position": 0.2819690798886975, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.6504642309604187, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141207.0318437} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.62995457649231, "x": 36.45138617165204, "y": -0.31606573624847556, "z": null, "yaw": 3.21408361383655, "pitch": null, "roll": null}, "v": 1.673101344258432, "accelerator_pedal_position": 0.2834693711467572, "brake_pedal_position": 0.0, "acceleration": 0.21003582137271704, "steering_wheel_angle": -3.805595487443983, "front_wheel_angle": -0.1844757382302936, "heading_rate": -0.12195161973525857, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141207.0518436} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2819690798886975, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.769020077741069, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6868054222597761, "gear": 1, "accelerator_pedal_position": 0.2819690798886975, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.5336016029643336, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141207.0518436} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.62995457649231, "x": 36.45138617165204, "y": -0.31606573624847556, "z": null, "yaw": 3.21408361383655, "pitch": null, "roll": null}, "v": 1.673101344258432, "accelerator_pedal_position": 0.2834693711467572, "brake_pedal_position": 0.0, "acceleration": 0.21003582137271704, "steering_wheel_angle": -3.805595487443983, "front_wheel_angle": -0.1844757382302936, "heading_rate": -0.12195161973525857, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141207.0718436} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2819690798886975, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.769020077741069, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6888005557884334, "gear": 1, "accelerator_pedal_position": 0.2819690798886975, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.5336016029643336, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141207.0718436} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.62995457649231, "x": 36.45138617165204, "y": -0.31606573624847556, "z": null, "yaw": 3.21408361383655, "pitch": null, "roll": null}, "v": 1.673101344258432, "accelerator_pedal_position": 0.2834693711467572, "brake_pedal_position": 0.0, "acceleration": 0.21003582137271704, "steering_wheel_angle": -3.805595487443983, "front_wheel_angle": -0.1844757382302936, "heading_rate": -0.12195161973525857, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141207.0918436} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2819690798886975, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.769020077741069, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6927858103145448, "gear": 1, "accelerator_pedal_position": 0.2819690798886975, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.5336016029643336, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141207.0918436} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141207.1018436, "x": 40.26671217275545, "y": 4.671179734587689, "z": null, "yaw": 3.20645820341377, "pitch": null, "roll": null}, "v": 1.694775932522471, "accelerator_pedal_position": 0.2819690798886975, "brake_pedal_position": 0.0, "acceleration": 0.1988452980636617, "steering_wheel_angle": -3.5336016029643336, "front_wheel_angle": -0.17057709508342878, "heading_rate": -0.11403391280526402, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141207.1118436} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2856353192446944, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.7006891280402203, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6967643855031076, "gear": 1, "accelerator_pedal_position": 0.2819690798886975, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.5336016029643336, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141207.1118436} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.739954471588135, "x": 36.26671217275545, "y": -0.32882026541231113, "z": null, "yaw": 3.20645820341377, "pitch": null, "roll": null}, "v": 1.694775932522471, "accelerator_pedal_position": 0.2819690798886975, "brake_pedal_position": 0.0, "acceleration": 0.1988452980636617, "steering_wheel_angle": -3.5336016029643336, "front_wheel_angle": -0.17057709508342878, "heading_rate": -0.11403391280526402, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141207.1318436} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28402767706798415, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.7006891280402203, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7011943737137218, "gear": 1, "accelerator_pedal_position": 0.2856353192446944, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.494630921138949, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141207.1318436} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.739954471588135, "x": 36.26671217275545, "y": -0.32882026541231113, "z": null, "yaw": 3.20645820341377, "pitch": null, "roll": null}, "v": 1.694775932522471, "accelerator_pedal_position": 0.2819690798886975, "brake_pedal_position": 0.0, "acceleration": 0.1988452980636617, "steering_wheel_angle": -3.5336016029643336, "front_wheel_angle": -0.17057709508342878, "heading_rate": -0.11403391280526402, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141207.1518435} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28402767706798415, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.7006891280402203, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.705416051713522, "gear": 1, "accelerator_pedal_position": 0.28402767706798415, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.494630921138949, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141207.1518435} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.739954471588135, "x": 36.26671217275545, "y": -0.32882026541231113, "z": null, "yaw": 3.20645820341377, "pitch": null, "roll": null}, "v": 1.694775932522471, "accelerator_pedal_position": 0.2819690798886975, "brake_pedal_position": 0.0, "acceleration": 0.1988452980636617, "steering_wheel_angle": -3.5336016029643336, "front_wheel_angle": -0.17057709508342878, "heading_rate": -0.11403391280526402, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141207.1718435} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28402767706798415, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.7006891280402203, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7096306329163613, "gear": 1, "accelerator_pedal_position": 0.28402767706798415, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.494630921138949, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141207.1718435} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.739954471588135, "x": 36.26671217275545, "y": -0.32882026541231113, "z": null, "yaw": 3.20645820341377, "pitch": null, "roll": null}, "v": 1.694775932522471, "accelerator_pedal_position": 0.2819690798886975, "brake_pedal_position": 0.0, "acceleration": 0.1988452980636617, "steering_wheel_angle": -3.5336016029643336, "front_wheel_angle": -0.17057709508342878, "heading_rate": -0.11403391280526402, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141207.1918435} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28402767706798415, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.7006891280402203, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.715939208794909, "gear": 1, "accelerator_pedal_position": 0.28402767706798415, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.494630921138949, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141207.1918435} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141207.2118435, "x": 40.07947640784794, "y": 4.659646613612227, "z": null, "yaw": 3.1991284944053757, "pitch": null, "roll": null}, "v": 1.7180385242704326, "accelerator_pedal_position": 0.28402767706798415, "brake_pedal_position": 0.0, "acceleration": 0.20975449175260596, "steering_wheel_angle": -3.494630921138949, "front_wheel_angle": -0.1685957140858385, "heading_rate": -0.11423043857029952, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141207.2118435} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2868096147345417, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.633485926996054, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7201360691879586, "gear": 1, "accelerator_pedal_position": 0.28402767706798415, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.494630921138949, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141207.2118435} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.84995436668396, "x": 36.07947640784794, "y": -0.3403533863877728, "z": null, "yaw": 3.1991284944053757, "pitch": null, "roll": null}, "v": 1.7180385242704326, "accelerator_pedal_position": 0.28402767706798415, "brake_pedal_position": 0.0, "acceleration": 0.20975449175260596, "steering_wheel_angle": -3.494630921138949, "front_wheel_angle": -0.1685957140858385, "heading_rate": -0.11423043857029952, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141207.2318435} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2856339896341694, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.633485926996054, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7224057152646213, "gear": 1, "accelerator_pedal_position": 0.2868096147345417, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.455691200714457, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141207.2318435} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.84995436668396, "x": 36.07947640784794, "y": -0.3403533863877728, "z": null, "yaw": 3.1991284944053757, "pitch": null, "roll": null}, "v": 1.7180385242704326, "accelerator_pedal_position": 0.28402767706798415, "brake_pedal_position": 0.0, "acceleration": 0.20975449175260596, "steering_wheel_angle": -3.494630921138949, "front_wheel_angle": -0.1685957140858385, "heading_rate": -0.11423043857029952, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141207.2518435} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2856339896341694, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.633485926996054, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.726792368476981, "gear": 1, "accelerator_pedal_position": 0.2856339896341694, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.416702913161841, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141207.2518435} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.84995436668396, "x": 36.07947640784794, "y": -0.3403533863877728, "z": null, "yaw": 3.1991284944053757, "pitch": null, "roll": null}, "v": 1.7180385242704326, "accelerator_pedal_position": 0.28402767706798415, "brake_pedal_position": 0.0, "acceleration": 0.20975449175260596, "steering_wheel_angle": -3.494630921138949, "front_wheel_angle": -0.1685957140858385, "heading_rate": -0.11423043857029952, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141207.2718434} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2856339896341694, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.633485926996054, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7311716101587085, "gear": 1, "accelerator_pedal_position": 0.2856339896341694, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.416702913161841, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141207.2718434} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.84995436668396, "x": 36.07947640784794, "y": -0.3403533863877728, "z": null, "yaw": 3.1991284944053757, "pitch": null, "roll": null}, "v": 1.7180385242704326, "accelerator_pedal_position": 0.28402767706798415, "brake_pedal_position": 0.0, "acceleration": 0.20975449175260596, "steering_wheel_angle": -3.494630921138949, "front_wheel_angle": -0.1685957140858385, "heading_rate": -0.11423043857029952, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141207.2918434} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2856339896341694, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.633485926996054, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7355434451641978, "gear": 1, "accelerator_pedal_position": 0.2856339896341694, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.416702913161841, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141207.2918434} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.84995436668396, "x": 36.07947640784794, "y": -0.3403533863877728, "z": null, "yaw": 3.1991284944053757, "pitch": null, "roll": null}, "v": 1.7180385242704326, "accelerator_pedal_position": 0.28402767706798415, "brake_pedal_position": 0.0, "acceleration": 0.20975449175260596, "steering_wheel_angle": -3.494630921138949, "front_wheel_angle": -0.1685957140858385, "heading_rate": -0.11423043857029952, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141207.3118434} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2856339896341694, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.633485926996054, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.739907878378529, "gear": 1, "accelerator_pedal_position": 0.2856339896341694, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.416702913161841, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141207.3118434} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141207.3218434, "x": 39.88956996623156, "y": 4.649334194431179, "z": null, "yaw": 3.191949742896657, "pitch": null, "roll": null}, "v": 1.742087320848951, "accelerator_pedal_position": 0.2856339896341694, "brake_pedal_position": 0.0, "acceleration": 0.21775938683648444, "steering_wheel_angle": -3.416702913161841, "front_wheel_angle": -0.16464104405932445, "heading_rate": -0.11306213161910474, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141207.3318434} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2837307012263144, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.411268215503953, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7463217050773303, "gear": 1, "accelerator_pedal_position": 0.2837307012263144, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.3779269002460763, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141207.3318434} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.959954261779785, "x": 35.88956996623156, "y": -0.35066580556882077, "z": null, "yaw": 3.191949742896657, "pitch": null, "roll": null}, "v": 1.742087320848951, "accelerator_pedal_position": 0.2856339896341694, "brake_pedal_position": 0.0, "acceleration": 0.21775938683648444, "steering_wheel_angle": -3.416702913161841, "front_wheel_angle": -0.16464104405932445, "heading_rate": -0.11306213161910474, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141207.3518434} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28479204354727256, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.411268215503953, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.748376749101674, "gear": 1, "accelerator_pedal_position": 0.2837307012263144, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.339102966680505, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141207.3518434} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.959954261779785, "x": 35.88956996623156, "y": -0.35066580556882077, "z": null, "yaw": 3.191949742896657, "pitch": null, "roll": null}, "v": 1.742087320848951, "accelerator_pedal_position": 0.2856339896341694, "brake_pedal_position": 0.0, "acceleration": 0.21775938683648444, "steering_wheel_angle": -3.416702913161841, "front_wheel_angle": -0.16464104405932445, "heading_rate": -0.11306213161910474, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141207.3718433} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28479204354727256, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.411268215503953, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7526142120960881, "gear": 1, "accelerator_pedal_position": 0.28479204354727256, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.261311337599943, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141207.3718433} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.959954261779785, "x": 35.88956996623156, "y": -0.35066580556882077, "z": null, "yaw": 3.191949742896657, "pitch": null, "roll": null}, "v": 1.742087320848951, "accelerator_pedal_position": 0.2856339896341694, "brake_pedal_position": 0.0, "acceleration": 0.21775938683648444, "steering_wheel_angle": -3.416702913161841, "front_wheel_angle": -0.16464104405932445, "heading_rate": -0.11306213161910474, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141207.3918433} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28479204354727256, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.411268215503953, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7589569020685074, "gear": 1, "accelerator_pedal_position": 0.28479204354727256, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.1833280259201544, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141207.3918433} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.959954261779785, "x": 35.88956996623156, "y": -0.35066580556882077, "z": null, "yaw": 3.191949742896657, "pitch": null, "roll": null}, "v": 1.742087320848951, "accelerator_pedal_position": 0.2856339896341694, "brake_pedal_position": 0.0, "acceleration": 0.21775938683648444, "steering_wheel_angle": -3.416702913161841, "front_wheel_angle": -0.16464104405932445, "heading_rate": -0.11306213161910474, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141207.4118433} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28479204354727256, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.411268215503953, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7631763664701285, "gear": 1, "accelerator_pedal_position": 0.28479204354727256, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.1833280259201544, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141207.4118433} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141207.4318433, "x": 39.696995570811744, "y": 4.640240316446033, "z": null, "yaw": 3.1851176836976776, "pitch": null, "roll": null}, "v": 1.76528340191867, "accelerator_pedal_position": 0.28479204354727256, "brake_pedal_position": 0.0, "acceleration": 0.21052384718362438, "steering_wheel_angle": -3.1833280259201544, "front_wheel_angle": -0.15285625958137017, "heading_rate": -0.10623281714883315, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141207.4318433} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2861622719306764, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.2846401489434975, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7673886403905064, "gear": 1, "accelerator_pedal_position": 0.28479204354727256, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.1833280259201544, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141207.4318433} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.06995415687561, "x": 35.696995570811744, "y": -0.3597596835539667, "z": null, "yaw": 3.1851176836976776, "pitch": null, "roll": null}, "v": 1.76528340191867, "accelerator_pedal_position": 0.28479204354727256, "brake_pedal_position": 0.0, "acceleration": 0.21052384718362438, "steering_wheel_angle": -3.1833280259201544, "front_wheel_angle": -0.15285625958137017, "heading_rate": -0.10623281714883315, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141207.4518433} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2856601344770544, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.2846401489434975, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7695777218053603, "gear": 1, "accelerator_pedal_position": 0.2861622719306764, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.144411892545511, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141207.4518433} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.06995415687561, "x": 35.696995570811744, "y": -0.3597596835539667, "z": null, "yaw": 3.1851176836976776, "pitch": null, "roll": null}, "v": 1.76528340191867, "accelerator_pedal_position": 0.28479204354727256, "brake_pedal_position": 0.0, "acceleration": 0.21052384718362438, "steering_wheel_angle": -3.1833280259201544, "front_wheel_angle": -0.15285625958137017, "heading_rate": -0.10623281714883315, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141207.4718432} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2856601344770544, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.2846401489434975, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.77388753846982, "gear": 1, "accelerator_pedal_position": 0.2856601344770544, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.0664369460904575, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141207.4718432} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.06995415687561, "x": 35.696995570811744, "y": -0.3597596835539667, "z": null, "yaw": 3.1851176836976776, "pitch": null, "roll": null}, "v": 1.76528340191867, "accelerator_pedal_position": 0.28479204354727256, "brake_pedal_position": 0.0, "acceleration": 0.21052384718362438, "steering_wheel_angle": -3.1833280259201544, "front_wheel_angle": -0.15285625958137017, "heading_rate": -0.10623281714883315, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141207.4918432} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2856601344770544, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.2846401489434975, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7803384597150058, "gear": 1, "accelerator_pedal_position": 0.2856601344770544, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.0664369460904575, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141207.4918432} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.06995415687561, "x": 35.696995570811744, "y": -0.3597596835539667, "z": null, "yaw": 3.1851176836976776, "pitch": null, "roll": null}, "v": 1.76528340191867, "accelerator_pedal_position": 0.28479204354727256, "brake_pedal_position": 0.0, "acceleration": 0.21052384718362438, "steering_wheel_angle": -3.1833280259201544, "front_wheel_angle": -0.15285625958137017, "heading_rate": -0.10623281714883315, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141207.5118432} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2856601344770544, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.2846401489434975, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7846298789384405, "gear": 1, "accelerator_pedal_position": 0.2856601344770544, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.0664369460904575, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141207.5118432} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.06995415687561, "x": 35.696995570811744, "y": -0.3597596835539667, "z": null, "yaw": 3.1851176836976776, "pitch": null, "roll": null}, "v": 1.76528340191867, "accelerator_pedal_position": 0.28479204354727256, "brake_pedal_position": 0.0, "acceleration": 0.21052384718362438, "steering_wheel_angle": -3.1833280259201544, "front_wheel_angle": -0.15285625958137017, "heading_rate": -0.10623281714883315, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141207.5318432} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2856601344770544, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.2846401489434975, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7889139482967857, "gear": 1, "accelerator_pedal_position": 0.2856601344770544, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.0664369460904575, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141207.5318432} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141207.5418432, "x": 39.5017933858543, "y": 4.632316727930646, "z": null, "yaw": 3.17868564283609, "pitch": null, "roll": null}, "v": 1.7889139482967857, "accelerator_pedal_position": 0.2856601344770544, "brake_pedal_position": 0.0, "acceleration": 0.21392801192264266, "steering_wheel_angle": -3.0664369460904575, "front_wheel_angle": -0.1469860882814915, "heading_rate": -0.10345922279569525, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141207.5518432} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.286353529379593, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.158720571128796, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.793190673039918, "gear": 1, "accelerator_pedal_position": 0.2856601344770544, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.0664369460904575, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141207.5518432} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.179954051971436, "x": 35.5017933858543, "y": -0.36768327206935414, "z": null, "yaw": 3.17868564283609, "pitch": null, "roll": null}, "v": 1.7889139482967857, "accelerator_pedal_position": 0.2856601344770544, "brake_pedal_position": 0.0, "acceleration": 0.21392801192264266, "steering_wheel_angle": -3.0664369460904575, "front_wheel_angle": -0.1469860882814915, "heading_rate": -0.10345922279569525, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141207.5718431} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2861773529434901, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.158720571128796, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7975466955796087, "gear": 1, "accelerator_pedal_position": 0.286353529379593, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.9885630489479786, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141207.5718431} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.179954051971436, "x": 35.5017933858543, "y": -0.36768327206935414, "z": null, "yaw": 3.17868564283609, "pitch": null, "roll": null}, "v": 1.7889139482967857, "accelerator_pedal_position": 0.2856601344770544, "brake_pedal_position": 0.0, "acceleration": 0.21392801192264266, "steering_wheel_angle": -3.0664369460904575, "front_wheel_angle": -0.1469860882814915, "heading_rate": -0.10345922279569525, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141207.5918431} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2861773529434901, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.158720571128796, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.799710889378508, "gear": 1, "accelerator_pedal_position": 0.2861773529434901, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.9495552905992, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141207.5918431} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.179954051971436, "x": 35.5017933858543, "y": -0.36768327206935414, "z": null, "yaw": 3.17868564283609, "pitch": null, "roll": null}, "v": 1.7889139482967857, "accelerator_pedal_position": 0.2856601344770544, "brake_pedal_position": 0.0, "acceleration": 0.21392801192264266, "steering_wheel_angle": -3.0664369460904575, "front_wheel_angle": -0.1469860882814915, "heading_rate": -0.10345922279569525, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141207.611843} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2861773529434901, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.158720571128796, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8061923097544281, "gear": 1, "accelerator_pedal_position": 0.2861773529434901, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.9495552905992, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141207.611843} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.179954051971436, "x": 35.5017933858543, "y": -0.36768327206935414, "z": null, "yaw": 3.17868564283609, "pitch": null, "roll": null}, "v": 1.7889139482967857, "accelerator_pedal_position": 0.2856601344770544, "brake_pedal_position": 0.0, "acceleration": 0.21392801192264266, "steering_wheel_angle": -3.0664369460904575, "front_wheel_angle": -0.1469860882814915, "heading_rate": -0.10345922279569525, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141207.631843} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2861773529434901, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.158720571128796, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8105039624848371, "gear": 1, "accelerator_pedal_position": 0.2861773529434901, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.9495552905992, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141207.631843} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141207.651843, "x": 39.30394236041365, "y": 4.625539702541268, "z": null, "yaw": 3.172487243321482, "pitch": null, "roll": null}, "v": 1.8126570026027455, "accelerator_pedal_position": 0.2861773529434901, "brake_pedal_position": 0.0, "acceleration": 0.21511835167582816, "steering_wheel_angle": -2.9495552905992, "front_wheel_angle": -0.14113776616270568, "heading_rate": -0.10060419318539043, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141207.651843} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28517987636340414, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.9572768225612496, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8148081861195038, "gear": 1, "accelerator_pedal_position": 0.2861773529434901, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.9495552905992, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141207.651843} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.28995394706726, "x": 35.30394236041365, "y": -0.3744602974587323, "z": null, "yaw": 3.172487243321482, "pitch": null, "roll": null}, "v": 1.8126570026027455, "accelerator_pedal_position": 0.2861773529434901, "brake_pedal_position": 0.0, "acceleration": 0.21511835167582816, "steering_wheel_angle": -2.9495552905992, "front_wheel_angle": -0.14113776616270568, "heading_rate": -0.10060419318539043, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141207.671843} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2858104674812748, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.9572768225612496, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8189803553045225, "gear": 1, "accelerator_pedal_position": 0.28517987636340414, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.8718591267625566, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141207.671843} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.28995394706726, "x": 35.30394236041365, "y": -0.3744602974587323, "z": null, "yaw": 3.172487243321482, "pitch": null, "roll": null}, "v": 1.8126570026027455, "accelerator_pedal_position": 0.2861773529434901, "brake_pedal_position": 0.0, "acceleration": 0.21511835167582816, "steering_wheel_angle": -2.9495552905992, "front_wheel_angle": -0.14113776616270568, "heading_rate": -0.10060419318539043, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141207.691843} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2858104674812748, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.9572768225612496, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.823224111365099, "gear": 1, "accelerator_pedal_position": 0.2858104674812748, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.793976355028199, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141207.691843} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.28995394706726, "x": 35.30394236041365, "y": -0.3744602974587323, "z": null, "yaw": 3.172487243321482, "pitch": null, "roll": null}, "v": 1.8126570026027455, "accelerator_pedal_position": 0.2861773529434901, "brake_pedal_position": 0.0, "acceleration": 0.21511835167582816, "steering_wheel_angle": -2.9495552905992, "front_wheel_angle": -0.14113776616270568, "heading_rate": -0.10060419318539043, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141207.711843} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2858104674812748, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.9572768225612496, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8274605337151102, "gear": 1, "accelerator_pedal_position": 0.2858104674812748, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.7549649911993783, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141207.711843} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.28995394706726, "x": 35.30394236041365, "y": -0.3744602974587323, "z": null, "yaw": 3.172487243321482, "pitch": null, "roll": null}, "v": 1.8126570026027455, "accelerator_pedal_position": 0.2861773529434901, "brake_pedal_position": 0.0, "acceleration": 0.21511835167582816, "steering_wheel_angle": -2.9495552905992, "front_wheel_angle": -0.14113776616270568, "heading_rate": -0.10060419318539043, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141207.731843} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2858104674812748, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.9572768225612496, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8295759964656038, "gear": 1, "accelerator_pedal_position": 0.2858104674812748, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.7549649911993783, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141207.731843} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.28995394706726, "x": 35.30394236041365, "y": -0.3744602974587323, "z": null, "yaw": 3.172487243321482, "pitch": null, "roll": null}, "v": 1.8126570026027455, "accelerator_pedal_position": 0.2861773529434901, "brake_pedal_position": 0.0, "acceleration": 0.21511835167582816, "steering_wheel_angle": -2.9495552905992, "front_wheel_angle": -0.14113776616270568, "heading_rate": -0.10060419318539043, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141207.751843} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2858104674812748, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.9572768225612496, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8359113993019969, "gear": 1, "accelerator_pedal_position": 0.2858104674812748, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.7549649911993783, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141207.751843} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141207.761843, "x": 39.10346694090853, "y": 4.619886694874676, "z": null, "yaw": 3.166652119940384, "pitch": null, "roll": null}, "v": 1.8359113993019969, "accelerator_pedal_position": 0.2858104674812748, "brake_pedal_position": 0.0, "acceleration": 0.21081414513199748, "steering_wheel_angle": -2.7549649911993783, "front_wheel_angle": -0.13144798288617582, "heading_rate": -0.09481502032935789, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141207.771843} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28624373412007403, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.8027638794965368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8380195407533169, "gear": 1, "accelerator_pedal_position": 0.2858104674812748, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.7549649911993783, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141207.771843} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.399953842163086, "x": 35.10346694090853, "y": -0.3801133051253238, "z": null, "yaw": 3.166652119940384, "pitch": null, "roll": null}, "v": 1.8359113993019969, "accelerator_pedal_position": 0.2858104674812748, "brake_pedal_position": 0.0, "acceleration": 0.21081414513199748, "steering_wheel_angle": -2.7549649911993783, "front_wheel_angle": -0.13144798288617582, "heading_rate": -0.09481502032935789, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141207.791843} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2861906488297453, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.8027638794965368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8444141633544335, "gear": 1, "accelerator_pedal_position": 0.28624373412007403, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.6381769022970896, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141207.791843} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.399953842163086, "x": 35.10346694090853, "y": -0.3801133051253238, "z": null, "yaw": 3.166652119940384, "pitch": null, "roll": null}, "v": 1.8359113993019969, "accelerator_pedal_position": 0.2858104674812748, "brake_pedal_position": 0.0, "acceleration": 0.21081414513199748, "steering_wheel_angle": -2.7549649911993783, "front_wheel_angle": -0.13144798288617582, "heading_rate": -0.09481502032935789, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141207.811843} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2861906488297453, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.8027638794965368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8486613611614526, "gear": 1, "accelerator_pedal_position": 0.2861906488297453, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.5991550685811196, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141207.811843} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.399953842163086, "x": 35.10346694090853, "y": -0.3801133051253238, "z": null, "yaw": 3.166652119940384, "pitch": null, "roll": null}, "v": 1.8359113993019969, "accelerator_pedal_position": 0.2858104674812748, "brake_pedal_position": 0.0, "acceleration": 0.21081414513199748, "steering_wheel_angle": -2.7549649911993783, "front_wheel_angle": -0.13144798288617582, "heading_rate": -0.09481502032935789, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141207.831843} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2861906488297453, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.8027638794965368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8529011761342822, "gear": 1, "accelerator_pedal_position": 0.2861906488297453, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.5991550685811196, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141207.831843} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.399953842163086, "x": 35.10346694090853, "y": -0.3801133051253238, "z": null, "yaw": 3.166652119940384, "pitch": null, "roll": null}, "v": 1.8359113993019969, "accelerator_pedal_position": 0.2858104674812748, "brake_pedal_position": 0.0, "acceleration": 0.21081414513199748, "steering_wheel_angle": -2.7549649911993783, "front_wheel_angle": -0.13144798288617582, "heading_rate": -0.09481502032935789, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141207.8518429} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2861906488297453, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.8027638794965368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8571336139190964, "gear": 1, "accelerator_pedal_position": 0.2861906488297453, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.5991550685811196, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141207.8518429} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141207.8718429, "x": 38.90040061188828, "y": 4.615308562814619, "z": null, "yaw": 3.1612010362980305, "pitch": null, "roll": null}, "v": 1.8592470681380011, "accelerator_pedal_position": 0.2861906488297453, "brake_pedal_position": 0.0, "acceleration": 0.21116120517521053, "steering_wheel_angle": -2.5991550685811196, "front_wheel_angle": -0.12373084562416041, "heading_rate": -0.09032320166738647, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141207.8718429} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2859582219885927, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.633661066047041, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8592470681380011, "gear": 1, "accelerator_pedal_position": 0.2861906488297453, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.5991550685811196, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141207.8718429} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.50995373725891, "x": 34.90040061188828, "y": -0.38469143718538135, "z": null, "yaw": 3.1612010362980305, "pitch": null, "roll": null}, "v": 1.8592470681380011, "accelerator_pedal_position": 0.2861906488297453, "brake_pedal_position": 0.0, "acceleration": 0.21116120517521053, "steering_wheel_angle": -2.5991550685811196, "front_wheel_angle": -0.12373084562416041, "heading_rate": -0.09032320166738647, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141207.8918428} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2862234976366852, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.633661066047041, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8634394101039307, "gear": 1, "accelerator_pedal_position": 0.2859582219885927, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.521352408442349, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141207.8918428} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.50995373725891, "x": 34.90040061188828, "y": -0.38469143718538135, "z": null, "yaw": 3.1612010362980305, "pitch": null, "roll": null}, "v": 1.8592470681380011, "accelerator_pedal_position": 0.2861906488297453, "brake_pedal_position": 0.0, "acceleration": 0.21116120517521053, "steering_wheel_angle": -2.5991550685811196, "front_wheel_angle": -0.12373084562416041, "heading_rate": -0.09032320166738647, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141207.9118428} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2862234976366852, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.633661066047041, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8697639101120367, "gear": 1, "accelerator_pedal_position": 0.2862234976366852, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.4433665967771487, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141207.9118428} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.50995373725891, "x": 34.90040061188828, "y": -0.38469143718538135, "z": null, "yaw": 3.1612010362980305, "pitch": null, "roll": null}, "v": 1.8592470681380011, "accelerator_pedal_position": 0.2861906488297453, "brake_pedal_position": 0.0, "acceleration": 0.21116120517521053, "steering_wheel_angle": -2.5991550685811196, "front_wheel_angle": -0.12373084562416041, "heading_rate": -0.09032320166738647, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141207.9318428} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2862234976366852, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.633661066047041, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8718683950513177, "gear": 1, "accelerator_pedal_position": 0.2862234976366852, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.4433665967771487, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141207.9318428} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.50995373725891, "x": 34.90040061188828, "y": -0.38469143718538135, "z": null, "yaw": 3.1612010362980305, "pitch": null, "roll": null}, "v": 1.8592470681380011, "accelerator_pedal_position": 0.2861906488297453, "brake_pedal_position": 0.0, "acceleration": 0.21116120517521053, "steering_wheel_angle": -2.5991550685811196, "front_wheel_angle": -0.12373084562416041, "heading_rate": -0.09032320166738647, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141207.9518428} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2862234976366852, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.633661066047041, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8781708147849534, "gear": 1, "accelerator_pedal_position": 0.2862234976366852, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.4433665967771487, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141207.9518428} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.50995373725891, "x": 34.90040061188828, "y": -0.38469143718538135, "z": null, "yaw": 3.1612010362980305, "pitch": null, "roll": null}, "v": 1.8592470681380011, "accelerator_pedal_position": 0.2861906488297453, "brake_pedal_position": 0.0, "acceleration": 0.21116120517521053, "steering_wheel_angle": -2.5991550685811196, "front_wheel_angle": -0.12373084562416041, "heading_rate": -0.09032320166738647, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141207.9718428} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2862234976366852, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.633661066047041, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8823632392938292, "gear": 1, "accelerator_pedal_position": 0.2862234976366852, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.4433665967771487, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141207.9718428} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141207.9818428, "x": 38.69475796442384, "y": 4.611757974775083, "z": null, "yaw": 3.156115887967607, "pitch": null, "roll": null}, "v": 1.8823632392938292, "accelerator_pedal_position": 0.2862234976366852, "brake_pedal_position": 0.0, "acceleration": 0.20934578461814335, "steering_wheel_angle": -2.4433665967771487, "front_wheel_angle": -0.11605114462114513, "heading_rate": -0.08571734674898543, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141207.9918427} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2878411056662601, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.5765386322787658, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.886548319689394, "gear": 1, "accelerator_pedal_position": 0.2862234976366852, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.4433665967771487, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141207.9918427} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.619953632354736, "x": 34.69475796442384, "y": -0.38824202522491724, "z": null, "yaw": 3.156115887967607, "pitch": null, "roll": null}, "v": 1.8823632392938292, "accelerator_pedal_position": 0.2862234976366852, "brake_pedal_position": 0.0, "acceleration": 0.20934578461814335, "steering_wheel_angle": -2.4433665967771487, "front_wheel_angle": -0.11605114462114513, "heading_rate": -0.08571734674898543, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141208.0118427} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2872247758662315, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.5765386322787658, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.89092817409784, "gear": 1, "accelerator_pedal_position": 0.2878411056662601, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.3653252528099773, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141208.0118427} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.619953632354736, "x": 34.69475796442384, "y": -0.38824202522491724, "z": null, "yaw": 3.156115887967607, "pitch": null, "roll": null}, "v": 1.8823632392938292, "accelerator_pedal_position": 0.2862234976366852, "brake_pedal_position": 0.0, "acceleration": 0.20934578461814335, "steering_wheel_angle": -2.4433665967771487, "front_wheel_angle": -0.11605114462114513, "heading_rate": -0.08571734674898543, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141208.0318427} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2872247758662315, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.5765386322787658, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.893076697566471, "gear": 1, "accelerator_pedal_position": 0.2872247758662315, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.3653252528099773, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141208.0318427} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.619953632354736, "x": 34.69475796442384, "y": -0.38824202522491724, "z": null, "yaw": 3.156115887967607, "pitch": null, "roll": null}, "v": 1.8823632392938292, "accelerator_pedal_position": 0.2862234976366852, "brake_pedal_position": 0.0, "acceleration": 0.20934578461814335, "steering_wheel_angle": -2.4433665967771487, "front_wheel_angle": -0.11605114462114513, "heading_rate": -0.08571734674898543, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141208.0518427} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2872247758662315, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.5765386322787658, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8995109473328147, "gear": 1, "accelerator_pedal_position": 0.2872247758662315, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.3653252528099773, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141208.0518427} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.619953632354736, "x": 34.69475796442384, "y": -0.38824202522491724, "z": null, "yaw": 3.156115887967607, "pitch": null, "roll": null}, "v": 1.8823632392938292, "accelerator_pedal_position": 0.2862234976366852, "brake_pedal_position": 0.0, "acceleration": 0.20934578461814335, "steering_wheel_angle": -2.4433665967771487, "front_wheel_angle": -0.11605114462114513, "heading_rate": -0.08571734674898543, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141208.0718427} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2872247758662315, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.5765386322787658, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.901651926166884, "gear": 1, "accelerator_pedal_position": 0.2872247758662315, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.3653252528099773, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141208.0718427} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141208.0918427, "x": 38.486537282092485, "y": 4.609201911624778, "z": null, "yaw": 3.151220597757799, "pitch": null, "roll": null}, "v": 1.9059282316468584, "accelerator_pedal_position": 0.2872247758662315, "brake_pedal_position": 0.0, "acceleration": 0.21353281333971885, "steering_wheel_angle": -2.3653252528099773, "front_wheel_angle": -0.11221755576419878, "heading_rate": -0.08389880015061094, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141208.0918427} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2871535063392714, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.427518857127144, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9080635597802555, "gear": 1, "accelerator_pedal_position": 0.2872247758662315, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.3653252528099773, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141208.0918427} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.72995352745056, "x": 34.486537282092485, "y": -0.390798088375222, "z": null, "yaw": 3.151220597757799, "pitch": null, "roll": null}, "v": 1.9059282316468584, "accelerator_pedal_position": 0.2872247758662315, "brake_pedal_position": 0.0, "acceleration": 0.21353281333971885, "steering_wheel_angle": -2.3653252528099773, "front_wheel_angle": -0.11221755576419878, "heading_rate": -0.08389880015061094, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141208.1118426} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2873452317498344, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.427518857127144, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9123196658038348, "gear": 1, "accelerator_pedal_position": 0.2871535063392714, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.28743213664694, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141208.1118426} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.72995352745056, "x": 34.486537282092485, "y": -0.390798088375222, "z": null, "yaw": 3.151220597757799, "pitch": null, "roll": null}, "v": 1.9059282316468584, "accelerator_pedal_position": 0.2872247758662315, "brake_pedal_position": 0.0, "acceleration": 0.21353281333971885, "steering_wheel_angle": -2.3653252528099773, "front_wheel_angle": -0.11221755576419878, "heading_rate": -0.08389880015061094, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141208.1318426} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2873452317498344, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.427518857127144, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.916592220329136, "gear": 1, "accelerator_pedal_position": 0.2873452317498344, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.2484176976376733, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141208.1318426} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.72995352745056, "x": 34.486537282092485, "y": -0.390798088375222, "z": null, "yaw": 3.151220597757799, "pitch": null, "roll": null}, "v": 1.9059282316468584, "accelerator_pedal_position": 0.2872247758662315, "brake_pedal_position": 0.0, "acceleration": 0.21353281333971885, "steering_wheel_angle": -2.3653252528099773, "front_wheel_angle": -0.11221755576419878, "heading_rate": -0.08389880015061094, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141208.1518426} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2873452317498344, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.427518857127144, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9187256686294334, "gear": 1, "accelerator_pedal_position": 0.2873452317498344, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.2484176976376733, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141208.1518426} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.72995352745056, "x": 34.486537282092485, "y": -0.390798088375222, "z": null, "yaw": 3.151220597757799, "pitch": null, "roll": null}, "v": 1.9059282316468584, "accelerator_pedal_position": 0.2872247758662315, "brake_pedal_position": 0.0, "acceleration": 0.21353281333971885, "steering_wheel_angle": -2.3653252528099773, "front_wheel_angle": -0.11221755576419878, "heading_rate": -0.08389880015061094, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141208.1718426} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2873452317498344, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.427518857127144, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9251147067409726, "gear": 1, "accelerator_pedal_position": 0.2873452317498344, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.2484176976376733, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141208.1718426} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.72995352745056, "x": 34.486537282092485, "y": -0.390798088375222, "z": null, "yaw": 3.151220597757799, "pitch": null, "roll": null}, "v": 1.9059282316468584, "accelerator_pedal_position": 0.2872247758662315, "brake_pedal_position": 0.0, "acceleration": 0.21353281333971885, "steering_wheel_angle": -2.3653252528099773, "front_wheel_angle": -0.11221755576419878, "heading_rate": -0.08389880015061094, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141208.1918426} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2873452317498344, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.427518857127144, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9293646507424405, "gear": 1, "accelerator_pedal_position": 0.2873452317498344, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.2484176976376733, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141208.1918426} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141208.2018425, "x": 38.27571858692918, "y": 4.607624841298016, "z": null, "yaw": 3.146559511355149, "pitch": null, "roll": null}, "v": 1.9293646507424405, "accelerator_pedal_position": 0.2873452317498344, "brake_pedal_position": 0.0, "acceleration": 0.21221498634399788, "steering_wheel_angle": -2.2484176976376733, "front_wheel_angle": -0.10649146068888918, "heading_rate": -0.08056291828262595, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141208.2118425} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28789149719151214, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2983175694472218, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9336070700638508, "gear": 1, "accelerator_pedal_position": 0.2873452317498344, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.2484176976376733, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141208.2118425} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.83995342254639, "x": 34.27571858692918, "y": -0.39237515870198436, "z": null, "yaw": 3.146559511355149, "pitch": null, "roll": null}, "v": 1.9293646507424405, "accelerator_pedal_position": 0.2873452317498344, "brake_pedal_position": 0.0, "acceleration": 0.21221498634399788, "steering_wheel_angle": -2.2484176976376733, "front_wheel_angle": -0.10649146068888918, "heading_rate": -0.08056291828262595, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141208.2318425} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2877891365504931, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2983175694472218, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9357596014731482, "gear": 1, "accelerator_pedal_position": 0.28789149719151214, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.2095000445600004, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141208.2318425} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.83995342254639, "x": 34.27571858692918, "y": -0.39237515870198436, "z": null, "yaw": 3.146559511355149, "pitch": null, "roll": null}, "v": 1.9293646507424405, "accelerator_pedal_position": 0.2873452317498344, "brake_pedal_position": 0.0, "acceleration": 0.21221498634399788, "steering_wheel_angle": -2.2484176976376733, "front_wheel_angle": -0.10649146068888918, "heading_rate": -0.08056291828262595, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141208.2518425} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2877891365504931, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2983175694472218, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.942186568235317, "gear": 1, "accelerator_pedal_position": 0.2877891365504931, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.092477531672693, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141208.2518425} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.83995342254639, "x": 34.27571858692918, "y": -0.39237515870198436, "z": null, "yaw": 3.146559511355149, "pitch": null, "roll": null}, "v": 1.9293646507424405, "accelerator_pedal_position": 0.2873452317498344, "brake_pedal_position": 0.0, "acceleration": 0.21221498634399788, "steering_wheel_angle": -2.2484176976376733, "front_wheel_angle": -0.10649146068888918, "heading_rate": -0.08056291828262595, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141208.2718425} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2877891365504931, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2983175694472218, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9443250871190219, "gear": 1, "accelerator_pedal_position": 0.2877891365504931, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.092477531672693, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141208.2718425} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.83995342254639, "x": 34.27571858692918, "y": -0.39237515870198436, "z": null, "yaw": 3.146559511355149, "pitch": null, "roll": null}, "v": 1.9293646507424405, "accelerator_pedal_position": 0.2873452317498344, "brake_pedal_position": 0.0, "acceleration": 0.21221498634399788, "steering_wheel_angle": -2.2484176976376733, "front_wheel_angle": -0.10649146068888918, "heading_rate": -0.08056291828262595, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141208.2918425} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2877891365504931, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2983175694472218, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9485964244698923, "gear": 1, "accelerator_pedal_position": 0.2877891365504931, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.092477531672693, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141208.2918425} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141208.3118424, "x": 38.06231499988855, "y": 4.607000602658647, "z": null, "yaw": 3.142161544816269, "pitch": null, "roll": null}, "v": 1.9528601664431477, "accelerator_pedal_position": 0.2877891365504931, "brake_pedal_position": 0.0, "acceleration": 0.21290246682162078, "steering_wheel_angle": -2.092477531672693, "front_wheel_angle": -0.09888441503093795, "heading_rate": -0.07567942049498956, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141208.3118424} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2880433859785753, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1794932173486479, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.955005081700619, "gear": 1, "accelerator_pedal_position": 0.2880433859785753, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.0535100461242157, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141208.3118424} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.94995331764221, "x": 34.06231499988855, "y": -0.39299939734135325, "z": null, "yaw": 3.142161544816269, "pitch": null, "roll": null}, "v": 1.9528601664431477, "accelerator_pedal_position": 0.2877891365504931, "brake_pedal_position": 0.0, "acceleration": 0.21290246682162078, "steering_wheel_angle": -2.092477531672693, "front_wheel_angle": -0.09888441503093795, "heading_rate": -0.07567942049498956, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141208.3318424} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28808131861474184, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1794932173486479, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.957148086296482, "gear": 1, "accelerator_pedal_position": 0.2880433859785753, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.0144979327601855, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141208.3318424} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.94995331764221, "x": 34.06231499988855, "y": -0.39299939734135325, "z": null, "yaw": 3.142161544816269, "pitch": null, "roll": null}, "v": 1.9528601664431477, "accelerator_pedal_position": 0.2877891365504931, "brake_pedal_position": 0.0, "acceleration": 0.21290246682162078, "steering_wheel_angle": -2.092477531672693, "front_wheel_angle": -0.09888441503093795, "heading_rate": -0.07567942049498956, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141208.3518424} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28808131861474184, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1794932173486479, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.963572749980007, "gear": 1, "accelerator_pedal_position": 0.28808131861474184, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.9754411915806025, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141208.3518424} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.94995331764221, "x": 34.06231499988855, "y": -0.39299939734135325, "z": null, "yaw": 3.142161544816269, "pitch": null, "roll": null}, "v": 1.9528601664431477, "accelerator_pedal_position": 0.2877891365504931, "brake_pedal_position": 0.0, "acceleration": 0.21290246682162078, "steering_wheel_angle": -2.092477531672693, "front_wheel_angle": -0.09888441503093795, "heading_rate": -0.07567942049498956, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141208.3718424} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28808131861474184, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1794932173486479, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.965710484223992, "gear": 1, "accelerator_pedal_position": 0.28808131861474184, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.9754411915806025, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141208.3718424} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.94995331764221, "x": 34.06231499988855, "y": -0.39299939734135325, "z": null, "yaw": 3.142161544816269, "pitch": null, "roll": null}, "v": 1.9528601664431477, "accelerator_pedal_position": 0.2877891365504931, "brake_pedal_position": 0.0, "acceleration": 0.21290246682162078, "steering_wheel_angle": -2.092477531672693, "front_wheel_angle": -0.09888441503093795, "heading_rate": -0.07567942049498956, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141208.3918424} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28808131861474184, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1794932173486479, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9721122370637696, "gear": 1, "accelerator_pedal_position": 0.28808131861474184, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.9754411915806025, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141208.3918424} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.94995331764221, "x": 34.06231499988855, "y": -0.39299939734135325, "z": null, "yaw": 3.142161544816269, "pitch": null, "roll": null}, "v": 1.9528601664431477, "accelerator_pedal_position": 0.2877891365504931, "brake_pedal_position": 0.0, "acceleration": 0.21290246682162078, "steering_wheel_angle": -2.092477531672693, "front_wheel_angle": -0.09888441503093795, "heading_rate": -0.07567942049498956, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141208.4118423} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28808131861474184, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1794932173486479, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9742423406911014, "gear": 1, "accelerator_pedal_position": 0.28808131861474184, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.9754411915806025, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141208.4118423} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141208.4218423, "x": 37.84632330502231, "y": 4.607281115770487, "z": null, "yaw": 3.138100473733557, "pitch": null, "roll": null}, "v": 1.9763705386521995, "accelerator_pedal_position": 0.28808131861474184, "brake_pedal_position": 0.0, "acceleration": 0.21262930934900265, "steering_wheel_angle": -1.9754411915806025, "front_wheel_angle": -0.09319807122512239, "heading_rate": -0.07215979573690366, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141208.4318423} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.288449640244233, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0907042651748726, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9784968317456895, "gear": 1, "accelerator_pedal_position": 0.28808131861474184, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.9754411915806025, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141208.4318423} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.05995321273804, "x": 33.84632330502231, "y": -0.39271888422951307, "z": null, "yaw": 3.138100473733557, "pitch": null, "roll": null}, "v": 1.9763705386521995, "accelerator_pedal_position": 0.28808131861474184, "brake_pedal_position": 0.0, "acceleration": 0.21262930934900265, "steering_wheel_angle": -1.9754411915806025, "front_wheel_angle": -0.09319807122512239, "heading_rate": -0.07215979573690366, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141208.4518423} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2884341952986016, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0907042651748726, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9849332882501103, "gear": 1, "accelerator_pedal_position": 0.288449640244233, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.8973871110010359, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141208.4518423} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.05995321273804, "x": 33.84632330502231, "y": -0.39271888422951307, "z": null, "yaw": 3.138100473733557, "pitch": null, "roll": null}, "v": 1.9763705386521995, "accelerator_pedal_position": 0.28808131861474184, "brake_pedal_position": 0.0, "acceleration": 0.21262930934900265, "steering_wheel_angle": -1.9754411915806025, "front_wheel_angle": -0.09319807122512239, "heading_rate": -0.07215979573690366, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141208.4718423} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2884341952986016, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0907042651748726, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9870739627962675, "gear": 1, "accelerator_pedal_position": 0.2884341952986016, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.8973871110010359, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141208.4718423} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.05995321273804, "x": 33.84632330502231, "y": -0.39271888422951307, "z": null, "yaw": 3.138100473733557, "pitch": null, "roll": null}, "v": 1.9763705386521995, "accelerator_pedal_position": 0.28808131861474184, "brake_pedal_position": 0.0, "acceleration": 0.21262930934900265, "steering_wheel_angle": -1.9754411915806025, "front_wheel_angle": -0.09319807122512239, "heading_rate": -0.07215979573690366, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141208.4918423} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2884341952986016, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0907042651748726, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9913495508522292, "gear": 1, "accelerator_pedal_position": 0.2884341952986016, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.8973871110010359, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141208.4918423} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.05995321273804, "x": 33.84632330502231, "y": -0.39271888422951307, "z": null, "yaw": 3.138100473733557, "pitch": null, "roll": null}, "v": 1.9763705386521995, "accelerator_pedal_position": 0.28808131861474184, "brake_pedal_position": 0.0, "acceleration": 0.21262930934900265, "steering_wheel_angle": -1.9754411915806025, "front_wheel_angle": -0.09319807122512239, "heading_rate": -0.07215979573690366, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141208.5118423} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2884341952986016, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0907042651748726, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9956174629211605, "gear": 1, "accelerator_pedal_position": 0.2884341952986016, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.8973871110010359, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141208.5118423} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141208.5318422, "x": 37.62774927259029, "y": 4.608434805937776, "z": null, "yaw": 3.1342108472796113, "pitch": null, "roll": null}, "v": 1.9998777055010464, "accelerator_pedal_position": 0.2884341952986016, "brake_pedal_position": 0.0, "acceleration": 0.21272472697160627, "steering_wheel_angle": -1.8973871110010359, "front_wheel_angle": -0.08941652891377648, "heading_rate": -0.07003915295325958, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141208.5318422} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28861775232805464, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9321159552915381, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9998777055010464, "gear": 1, "accelerator_pedal_position": 0.2884341952986016, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.8973871110010359, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141208.5318422} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.16995310783386, "x": 33.62774927259029, "y": -0.391565194062224, "z": null, "yaw": 3.1342108472796113, "pitch": null, "roll": null}, "v": 1.9998777055010464, "accelerator_pedal_position": 0.2884341952986016, "brake_pedal_position": 0.0, "acceleration": 0.21272472697160627, "steering_wheel_angle": -1.8973871110010359, "front_wheel_angle": -0.08941652891377648, "heading_rate": -0.07003915295325958, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141208.5518422} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28869111085745763, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9321159552915381, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.004153219416433, "gear": 1, "accelerator_pedal_position": 0.28861775232805464, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.8194978738704635, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141208.5518422} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.16995310783386, "x": 33.62774927259029, "y": -0.391565194062224, "z": null, "yaw": 3.1342108472796113, "pitch": null, "roll": null}, "v": 1.9998777055010464, "accelerator_pedal_position": 0.2884341952986016, "brake_pedal_position": 0.0, "acceleration": 0.21272472697160627, "steering_wheel_angle": -1.8973871110010359, "front_wheel_angle": -0.08941652891377648, "heading_rate": -0.07003915295325958, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141208.5718422} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28869111085745763, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9321159552915381, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.008430201284642, "gear": 1, "accelerator_pedal_position": 0.28869111085745763, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.741432555380674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141208.5718422} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.16995310783386, "x": 33.62774927259029, "y": -0.391565194062224, "z": null, "yaw": 3.1342108472796113, "pitch": null, "roll": null}, "v": 1.9998777055010464, "accelerator_pedal_position": 0.2884341952986016, "brake_pedal_position": 0.0, "acceleration": 0.21272472697160627, "steering_wheel_angle": -1.8973871110010359, "front_wheel_angle": -0.08941652891377648, "heading_rate": -0.07003915295325958, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141208.5918422} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28869111085745763, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9321159552915381, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0126994754689402, "gear": 1, "accelerator_pedal_position": 0.28869111085745763, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.741432555380674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141208.5918422} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.16995310783386, "x": 33.62774927259029, "y": -0.391565194062224, "z": null, "yaw": 3.1342108472796113, "pitch": null, "roll": null}, "v": 1.9998777055010464, "accelerator_pedal_position": 0.2884341952986016, "brake_pedal_position": 0.0, "acceleration": 0.21272472697160627, "steering_wheel_angle": -1.8973871110010359, "front_wheel_angle": -0.08941652891377648, "heading_rate": -0.07003915295325958, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141208.6118422} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28869111085745763, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9321159552915381, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.019088949289353, "gear": 1, "accelerator_pedal_position": 0.28869111085745763, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.741432555380674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141208.6118422} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.16995310783386, "x": 33.62774927259029, "y": -0.391565194062224, "z": null, "yaw": 3.1342108472796113, "pitch": null, "roll": null}, "v": 1.9998777055010464, "accelerator_pedal_position": 0.2884341952986016, "brake_pedal_position": 0.0, "acceleration": 0.21272472697160627, "steering_wheel_angle": -1.8973871110010359, "front_wheel_angle": -0.08941652891377648, "heading_rate": -0.07003915295325958, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141208.6318421} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28869111085745763, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9321159552915381, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.021214927224785, "gear": 1, "accelerator_pedal_position": 0.28869111085745763, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.741432555380674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141208.6318421} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141208.6418421, "x": 37.40659712819528, "y": 4.610436022220932, "z": null, "yaw": 3.1306103346606684, "pitch": null, "roll": null}, "v": 2.02333898321156, "accelerator_pedal_position": 0.28869111085745763, "brake_pedal_position": 0.0, "acceleration": 0.21221348728869627, "steering_wheel_angle": -1.741432555380674, "front_wheel_angle": -0.08188651581768254, "heading_rate": -0.06486543044734437, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141208.651842} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2891239513959193, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8803455796890486, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.025461118084447, "gear": 1, "accelerator_pedal_position": 0.28869111085745763, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.741432555380674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141208.651842} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.27995300292969, "x": 33.40659712819528, "y": -0.38956397777906826, "z": null, "yaw": 3.1306103346606684, "pitch": null, "roll": null}, "v": 2.02333898321156, "accelerator_pedal_position": 0.28869111085745763, "brake_pedal_position": 0.0, "acceleration": 0.21221348728869627, "steering_wheel_angle": -1.741432555380674, "front_wheel_angle": -0.08188651581768254, "heading_rate": -0.06486543044734437, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141208.671842} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28907912916860484, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8803455796890486, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.029753708406822, "gear": 1, "accelerator_pedal_position": 0.2891239513959193, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.7023894681436817, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141208.671842} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.27995300292969, "x": 33.40659712819528, "y": -0.38956397777906826, "z": null, "yaw": 3.1306103346606684, "pitch": null, "roll": null}, "v": 2.02333898321156, "accelerator_pedal_position": 0.28869111085745763, "brake_pedal_position": 0.0, "acceleration": 0.21221348728869627, "steering_wheel_angle": -1.741432555380674, "front_wheel_angle": -0.08188651581768254, "heading_rate": -0.06486543044734437, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141208.691842} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28907912916860484, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8803455796890486, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0340329261040577, "gear": 1, "accelerator_pedal_position": 0.28907912916860484, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.7023894681436817, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141208.691842} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.27995300292969, "x": 33.40659712819528, "y": -0.38956397777906826, "z": null, "yaw": 3.1306103346606684, "pitch": null, "roll": null}, "v": 2.02333898321156, "accelerator_pedal_position": 0.28869111085745763, "brake_pedal_position": 0.0, "acceleration": 0.21221348728869627, "steering_wheel_angle": -1.741432555380674, "front_wheel_angle": -0.08188651581768254, "heading_rate": -0.06486543044734437, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141208.711842} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28907912916860484, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8803455796890486, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0383043883048497, "gear": 1, "accelerator_pedal_position": 0.28907912916860484, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.7023894681436817, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141208.711842} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.27995300292969, "x": 33.40659712819528, "y": -0.38956397777906826, "z": null, "yaw": 3.1306103346606684, "pitch": null, "roll": null}, "v": 2.02333898321156, "accelerator_pedal_position": 0.28869111085745763, "brake_pedal_position": 0.0, "acceleration": 0.21221348728869627, "steering_wheel_angle": -1.741432555380674, "front_wheel_angle": -0.08188651581768254, "heading_rate": -0.06486543044734437, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141208.731842} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28907912916860484, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8803455796890486, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.042568101770128, "gear": 1, "accelerator_pedal_position": 0.28907912916860484, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.7023894681436817, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141208.731842} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141208.751842, "x": 37.18287224078224, "y": 4.613247130130901, "z": null, "yaw": 3.1271504104672885, "pitch": null, "roll": null}, "v": 2.046824073288248, "accelerator_pedal_position": 0.28907912916860484, "brake_pedal_position": 0.0, "acceleration": 0.21250846576944477, "steering_wheel_angle": -1.7023894681436817, "front_wheel_angle": -0.08000668816054082, "heading_rate": -0.06410543928979767, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141208.751842} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28976077108167886, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7542568770894194, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.046824073288248, "gear": 1, "accelerator_pedal_position": 0.28907912916860484, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.7023894681436817, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141208.751842} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.38995289802551, "x": 33.18287224078224, "y": -0.38675286986909896, "z": null, "yaw": 3.1271504104672885, "pitch": null, "roll": null}, "v": 2.046824073288248, "accelerator_pedal_position": 0.28907912916860484, "brake_pedal_position": 0.0, "acceleration": 0.21250846576944477, "steering_wheel_angle": -1.7023894681436817, "front_wheel_angle": -0.08000668816054082, "heading_rate": -0.06410543928979767, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141208.771842} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28959847568686875, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7542568770894194, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0511574761543447, "gear": 1, "accelerator_pedal_position": 0.28976077108167886, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.624441083344099, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141208.771842} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.38995289802551, "x": 33.18287224078224, "y": -0.38675286986909896, "z": null, "yaw": 3.1271504104672885, "pitch": null, "roll": null}, "v": 2.046824073288248, "accelerator_pedal_position": 0.28907912916860484, "brake_pedal_position": 0.0, "acceleration": 0.21250846576944477, "steering_wheel_angle": -1.7023894681436817, "front_wheel_angle": -0.08000668816054082, "heading_rate": -0.06410543928979767, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141208.791842} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28959847568686875, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7542568770894194, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.057612398674047, "gear": 1, "accelerator_pedal_position": 0.28959847568686875, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.5854015003971254, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141208.791842} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.38995289802551, "x": 33.18287224078224, "y": -0.38675286986909896, "z": null, "yaw": 3.1271504104672885, "pitch": null, "roll": null}, "v": 2.046824073288248, "accelerator_pedal_position": 0.28907912916860484, "brake_pedal_position": 0.0, "acceleration": 0.21250846576944477, "steering_wheel_angle": -1.7023894681436817, "front_wheel_angle": -0.08000668816054082, "heading_rate": -0.06410543928979767, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141208.811842} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28959847568686875, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7542568770894194, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0597601203268217, "gear": 1, "accelerator_pedal_position": 0.28959847568686875, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.5854015003971254, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141208.811842} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.38995289802551, "x": 33.18287224078224, "y": -0.38675286986909896, "z": null, "yaw": 3.1271504104672885, "pitch": null, "roll": null}, "v": 2.046824073288248, "accelerator_pedal_position": 0.28907912916860484, "brake_pedal_position": 0.0, "acceleration": 0.21250846576944477, "steering_wheel_angle": -1.7023894681436817, "front_wheel_angle": -0.08000668816054082, "heading_rate": -0.06410543928979767, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141208.831842} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28959847568686875, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7542568770894194, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0640496900229035, "gear": 1, "accelerator_pedal_position": 0.28959847568686875, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.5854015003971254, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141208.831842} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.38995289802551, "x": 33.18287224078224, "y": -0.38675286986909896, "z": null, "yaw": 3.1271504104672885, "pitch": null, "roll": null}, "v": 2.046824073288248, "accelerator_pedal_position": 0.28907912916860484, "brake_pedal_position": 0.0, "acceleration": 0.21250846576944477, "steering_wheel_angle": -1.7023894681436817, "front_wheel_angle": -0.08000668816054082, "heading_rate": -0.06410543928979767, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141208.851842} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28959847568686875, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7542568770894194, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.070469373529986, "gear": 1, "accelerator_pedal_position": 0.28959847568686875, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.5854015003971254, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141208.851842} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141208.861842, "x": 36.95656510448297, "y": 4.616854395595674, "z": null, "yaw": 3.1239040368055475, "pitch": null, "roll": null}, "v": 2.070469373529986, "accelerator_pedal_position": 0.28959847568686875, "brake_pedal_position": 0.0, "acceleration": 0.2135985700991737, "steering_wheel_angle": -1.5854015003971254, "front_wheel_angle": -0.07438661258420168, "heading_rate": -0.06027340140427419, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141208.871842} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.290355257077819, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6568585769488684, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.072605359230978, "gear": 1, "accelerator_pedal_position": 0.28959847568686875, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.5854015003971254, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141208.871842} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.49995279312134, "x": 32.95656510448297, "y": -0.38314560440432643, "z": null, "yaw": 3.1239040368055475, "pitch": null, "roll": null}, "v": 2.070469373529986, "accelerator_pedal_position": 0.28959847568686875, "brake_pedal_position": 0.0, "acceleration": 0.2135985700991737, "steering_wheel_angle": -1.5854015003971254, "front_wheel_angle": -0.07438661258420168, "heading_rate": -0.06027340140427419, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141208.891842} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29015913718678044, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6568585769488684, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.076966027061927, "gear": 1, "accelerator_pedal_position": 0.290355257077819, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.5073985080981167, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141208.891842} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.49995279312134, "x": 32.95656510448297, "y": -0.38314560440432643, "z": null, "yaw": 3.1239040368055475, "pitch": null, "roll": null}, "v": 2.070469373529986, "accelerator_pedal_position": 0.28959847568686875, "brake_pedal_position": 0.0, "acceleration": 0.2135985700991737, "steering_wheel_angle": -1.5854015003971254, "front_wheel_angle": -0.07438661258420168, "heading_rate": -0.06027340140427419, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141208.9118419} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29015913718678044, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6568585769488684, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0834553336428585, "gear": 1, "accelerator_pedal_position": 0.29015913718678044, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.4683319666256878, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141208.9118419} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.49995279312134, "x": 32.95656510448297, "y": -0.38314560440432643, "z": null, "yaw": 3.1239040368055475, "pitch": null, "roll": null}, "v": 2.070469373529986, "accelerator_pedal_position": 0.28959847568686875, "brake_pedal_position": 0.0, "acceleration": 0.2135985700991737, "steering_wheel_angle": -1.5854015003971254, "front_wheel_angle": -0.07438661258420168, "heading_rate": -0.06027340140427419, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141208.9318419} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29015913718678044, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6568585769488684, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.085614473437482, "gear": 1, "accelerator_pedal_position": 0.29015913718678044, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.4683319666256878, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141208.9318419} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.49995279312134, "x": 32.95656510448297, "y": -0.38314560440432643, "z": null, "yaw": 3.1239040368055475, "pitch": null, "roll": null}, "v": 2.070469373529986, "accelerator_pedal_position": 0.28959847568686875, "brake_pedal_position": 0.0, "acceleration": 0.2135985700991737, "steering_wheel_angle": -1.5854015003971254, "front_wheel_angle": -0.07438661258420168, "heading_rate": -0.06027340140427419, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141208.9518418} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29015913718678044, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6568585769488684, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0920800179775387, "gear": 1, "accelerator_pedal_position": 0.29015913718678044, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.4683319666256878, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141208.9518418} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141208.9718418, "x": 36.72766589664321, "y": 4.621224687457269, "z": null, "yaw": 3.120877896734427, "pitch": null, "roll": null}, "v": 2.0942312441625615, "accelerator_pedal_position": 0.29015913718678044, "brake_pedal_position": 0.0, "acceleration": 0.21492500016898286, "steering_wheel_angle": -1.4683319666256878, "front_wheel_angle": -0.06878139201408089, "heading_rate": -0.05635614167605015, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141208.9718418} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.290304333634033, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5823782046672459, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0942312441625615, "gear": 1, "accelerator_pedal_position": 0.29015913718678044, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.4683319666256878, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141208.9718418} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.60995268821716, "x": 32.72766589664321, "y": -0.37877531254273133, "z": null, "yaw": 3.120877896734427, "pitch": null, "roll": null}, "v": 2.0942312441625615, "accelerator_pedal_position": 0.29015913718678044, "brake_pedal_position": 0.0, "acceleration": 0.21492500016898286, "steering_wheel_angle": -1.4683319666256878, "front_wheel_angle": -0.06878139201408089, "heading_rate": -0.05635614167605015, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141208.9918418} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2904011128449926, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5823782046672459, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1007002684907925, "gear": 1, "accelerator_pedal_position": 0.290304333634033, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.4293008135354117, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141208.9918418} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.60995268821716, "x": 32.72766589664321, "y": -0.37877531254273133, "z": null, "yaw": 3.120877896734427, "pitch": null, "roll": null}, "v": 2.0942312441625615, "accelerator_pedal_position": 0.29015913718678044, "brake_pedal_position": 0.0, "acceleration": 0.21492500016898286, "steering_wheel_angle": -1.4683319666256878, "front_wheel_angle": -0.06878139201408089, "heading_rate": -0.05635614167605015, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141209.0118418} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2904011128449926, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5823782046672459, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1050151324849065, "gear": 1, "accelerator_pedal_position": 0.2904011128449926, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.4293008135354117, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141209.0118418} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.60995268821716, "x": 32.72766589664321, "y": -0.37877531254273133, "z": null, "yaw": 3.120877896734427, "pitch": null, "roll": null}, "v": 2.0942312441625615, "accelerator_pedal_position": 0.29015913718678044, "brake_pedal_position": 0.0, "acceleration": 0.21492500016898286, "steering_wheel_angle": -1.4683319666256878, "front_wheel_angle": -0.06878139201408089, "heading_rate": -0.05635614167605015, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141209.0318418} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2904011128449926, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5823782046672459, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1093220539944406, "gear": 1, "accelerator_pedal_position": 0.2904011128449926, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.4293008135354117, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141209.0318418} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.60995268821716, "x": 32.72766589664321, "y": -0.37877531254273133, "z": null, "yaw": 3.120877896734427, "pitch": null, "roll": null}, "v": 2.0942312441625615, "accelerator_pedal_position": 0.29015913718678044, "brake_pedal_position": 0.0, "acceleration": 0.21492500016898286, "steering_wheel_angle": -1.4683319666256878, "front_wheel_angle": -0.06878139201408089, "heading_rate": -0.05635614167605015, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141209.0518417} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2904011128449926, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5823782046672459, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1136210402229247, "gear": 1, "accelerator_pedal_position": 0.2904011128449926, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.4293008135354117, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141209.0518417} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.60995268821716, "x": 32.72766589664321, "y": -0.37877531254273133, "z": null, "yaw": 3.120877896734427, "pitch": null, "roll": null}, "v": 2.0942312441625615, "accelerator_pedal_position": 0.29015913718678044, "brake_pedal_position": 0.0, "acceleration": 0.21492500016898286, "steering_wheel_angle": -1.4683319666256878, "front_wheel_angle": -0.06878139201408089, "heading_rate": -0.05635614167605015, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141209.0718417} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2904011128449926, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5823782046672459, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.115767559865458, "gear": 1, "accelerator_pedal_position": 0.2904011128449926, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.4293008135354117, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141209.0718417} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141209.0818417, "x": 36.496171241557306, "y": 4.626326037772139, "z": null, "yaw": 3.11799095095625, "pitch": null, "roll": null}, "v": 2.1179120984015993, "accelerator_pedal_position": 0.2904011128449926, "brake_pedal_position": 0.0, "acceleration": 0.21425583379556495, "steering_wheel_angle": -1.4293008135354117, "front_wheel_angle": -0.0669167453118565, "heading_rate": -0.0554436341355282, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141209.0918417} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29230375875542636, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.43335791152429176, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1221952357892406, "gear": 1, "accelerator_pedal_position": 0.2904011128449926, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.4293008135354117, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141209.0918417} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.71995258331299, "x": 32.496171241557306, "y": -0.3736739622278611, "z": null, "yaw": 3.11799095095625, "pitch": null, "roll": null}, "v": 2.1179120984015993, "accelerator_pedal_position": 0.2904011128449926, "brake_pedal_position": 0.0, "acceleration": 0.21425583379556495, "steering_wheel_angle": -1.4293008135354117, "front_wheel_angle": -0.0669167453118565, "heading_rate": -0.0554436341355282, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141209.1118417} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2915639471322987, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.43335791152429176, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1244527518316794, "gear": 1, "accelerator_pedal_position": 0.29230375875542636, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.390382793368585, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141209.1118417} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.71995258331299, "x": 32.496171241557306, "y": -0.3736739622278611, "z": null, "yaw": 3.11799095095625, "pitch": null, "roll": null}, "v": 2.1179120984015993, "accelerator_pedal_position": 0.2904011128449926, "brake_pedal_position": 0.0, "acceleration": 0.21425583379556495, "steering_wheel_angle": -1.4293008135354117, "front_wheel_angle": -0.0669167453118565, "heading_rate": -0.0554436341355282, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141209.1318417} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2915639471322987, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.43335791152429176, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.131074192616703, "gear": 1, "accelerator_pedal_position": 0.2915639471322987, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.273371665873887, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141209.1318417} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.71995258331299, "x": 32.496171241557306, "y": -0.3736739622278611, "z": null, "yaw": 3.11799095095625, "pitch": null, "roll": null}, "v": 2.1179120984015993, "accelerator_pedal_position": 0.2904011128449926, "brake_pedal_position": 0.0, "acceleration": 0.21425583379556495, "steering_wheel_angle": -1.4293008135354117, "front_wheel_angle": -0.0669167453118565, "heading_rate": -0.0554436341355282, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141209.1518416} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2915639471322987, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.43335791152429176, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1332772544947196, "gear": 1, "accelerator_pedal_position": 0.2915639471322987, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.273371665873887, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141209.1518416} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.71995258331299, "x": 32.496171241557306, "y": -0.3736739622278611, "z": null, "yaw": 3.11799095095625, "pitch": null, "roll": null}, "v": 2.1179120984015993, "accelerator_pedal_position": 0.2904011128449926, "brake_pedal_position": 0.0, "acceleration": 0.21425583379556495, "steering_wheel_angle": -1.4293008135354117, "front_wheel_angle": -0.0669167453118565, "heading_rate": -0.0554436341355282, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141209.1818416} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2915639471322987, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.43335791152429176, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1398741978529143, "gear": 1, "accelerator_pedal_position": 0.2915639471322987, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.273371665873887, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141209.1818416} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141209.1918416, "x": 36.26206842545065, "y": 4.63214800682649, "z": null, "yaw": 3.115300708462461, "pitch": null, "roll": null}, "v": 2.1420691012914927, "accelerator_pedal_position": 0.2915639471322987, "brake_pedal_position": 0.0, "acceleration": 0.21928661416521478, "steering_wheel_angle": -1.273371665873887, "front_wheel_angle": -0.05948798115708896, "heading_rate": -0.04983511467992782, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141209.1918416} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29108409089074433, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.3868399765955599, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.144261967433145, "gear": 1, "accelerator_pedal_position": 0.2915639471322987, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.273371665873887, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141209.1918416} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.82995247840881, "x": 32.26206842545065, "y": -0.3678519931735096, "z": null, "yaw": 3.115300708462461, "pitch": null, "roll": null}, "v": 2.1420691012914927, "accelerator_pedal_position": 0.2915639471322987, "brake_pedal_position": 0.0, "acceleration": 0.21928661416521478, "steering_wheel_angle": -1.273371665873887, "front_wheel_angle": -0.05948798115708896, "heading_rate": -0.04983511467992782, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141209.2118416} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29148302712322877, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.3868399765955599, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1485816373828834, "gear": 1, "accelerator_pedal_position": 0.29108409089074433, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.2343308951866099, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141209.2118416} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.82995247840881, "x": 32.26206842545065, "y": -0.3678519931735096, "z": null, "yaw": 3.115300708462461, "pitch": null, "roll": null}, "v": 2.1420691012914927, "accelerator_pedal_position": 0.2915639471322987, "brake_pedal_position": 0.0, "acceleration": 0.21928661416521478, "steering_wheel_angle": -1.273371665873887, "front_wheel_angle": -0.05948798115708896, "heading_rate": -0.04983511467992782, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141209.2318416} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29148302712322877, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.3868399765955599, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.150763395454144, "gear": 1, "accelerator_pedal_position": 0.29148302712322877, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.2343308951866099, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141209.2318416} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.82995247840881, "x": 32.26206842545065, "y": -0.3678519931735096, "z": null, "yaw": 3.115300708462461, "pitch": null, "roll": null}, "v": 2.1420691012914927, "accelerator_pedal_position": 0.2915639471322987, "brake_pedal_position": 0.0, "acceleration": 0.21928661416521478, "steering_wheel_angle": -1.273371665873887, "front_wheel_angle": -0.05948798115708896, "heading_rate": -0.04983511467992782, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141209.2518415} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29148302712322877, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.3868399765955599, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.15729650006126, "gear": 1, "accelerator_pedal_position": 0.29148302712322877, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.2343308951866099, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141209.2518415} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.82995247840881, "x": 32.26206842545065, "y": -0.3678519931735096, "z": null, "yaw": 3.115300708462461, "pitch": null, "roll": null}, "v": 2.1420691012914927, "accelerator_pedal_position": 0.2915639471322987, "brake_pedal_position": 0.0, "acceleration": 0.21928661416521478, "steering_wheel_angle": -1.273371665873887, "front_wheel_angle": -0.05948798115708896, "heading_rate": -0.04983511467992782, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141209.2718415} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29148302712322877, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.3868399765955599, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1594701481875136, "gear": 1, "accelerator_pedal_position": 0.29148302712322877, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.2343308951866099, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141209.2718415} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.82995247840881, "x": 32.26206842545065, "y": -0.3678519931735096, "z": null, "yaw": 3.115300708462461, "pitch": null, "roll": null}, "v": 2.1420691012914927, "accelerator_pedal_position": 0.2915639471322987, "brake_pedal_position": 0.0, "acceleration": 0.21928661416521478, "steering_wheel_angle": -1.273371665873887, "front_wheel_angle": -0.05948798115708896, "heading_rate": -0.04983511467992782, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141209.2918415} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29148302712322877, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.3868399765955599, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1659789455171885, "gear": 1, "accelerator_pedal_position": 0.29148302712322877, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.2343308951866099, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141209.2918415} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141209.3018415, "x": 36.02533377163607, "y": 4.63864414006465, "z": null, "yaw": 3.112806999630823, "pitch": null, "roll": null}, "v": 2.1659789455171885, "accelerator_pedal_position": 0.29148302712322877, "brake_pedal_position": 0.0, "acceleration": 0.21655532432008273, "steering_wheel_angle": -1.2343308951866099, "front_wheel_angle": -0.057633099212725546, "heading_rate": -0.0488165923212785, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141209.3118415} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2943022626736332, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.2694804549672786, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.17030803064946, "gear": 1, "accelerator_pedal_position": 0.29148302712322877, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.2343308951866099, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141209.3118415} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.93995237350464, "x": 32.02533377163607, "y": -0.36135585993535013, "z": null, "yaw": 3.112806999630823, "pitch": null, "roll": null}, "v": 2.1659789455171885, "accelerator_pedal_position": 0.29148302712322877, "brake_pedal_position": 0.0, "acceleration": 0.21655532432008273, "steering_wheel_angle": -1.2343308951866099, "front_wheel_angle": -0.057633099212725546, "heading_rate": -0.0488165923212785, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141209.3318415} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2931293339047263, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.2694804549672786, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1749812739483243, "gear": 1, "accelerator_pedal_position": 0.2943022626736332, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1563654324139012, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141209.3318415} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.93995237350464, "x": 32.02533377163607, "y": -0.36135585993535013, "z": null, "yaw": 3.112806999630823, "pitch": null, "roll": null}, "v": 2.1659789455171885, "accelerator_pedal_position": 0.29148302712322877, "brake_pedal_position": 0.0, "acceleration": 0.21655532432008273, "steering_wheel_angle": -1.2343308951866099, "front_wheel_angle": -0.057633099212725546, "heading_rate": -0.0488165923212785, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141209.3518414} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2931293339047263, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.2694804549672786, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.179499237065865, "gear": 1, "accelerator_pedal_position": 0.2931293339047263, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1173189934128167, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141209.3518414} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.93995237350464, "x": 32.02533377163607, "y": -0.36135585993535013, "z": null, "yaw": 3.112806999630823, "pitch": null, "roll": null}, "v": 2.1659789455171885, "accelerator_pedal_position": 0.29148302712322877, "brake_pedal_position": 0.0, "acceleration": 0.21655532432008273, "steering_wheel_angle": -1.2343308951866099, "front_wheel_angle": -0.057633099212725546, "heading_rate": -0.0488165923212785, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141209.3718414} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2931293339047263, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.2694804549672786, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1817550491239404, "gear": 1, "accelerator_pedal_position": 0.2931293339047263, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1173189934128167, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141209.3718414} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.93995237350464, "x": 32.02533377163607, "y": -0.36135585993535013, "z": null, "yaw": 3.112806999630823, "pitch": null, "roll": null}, "v": 2.1659789455171885, "accelerator_pedal_position": 0.29148302712322877, "brake_pedal_position": 0.0, "acceleration": 0.21655532432008273, "steering_wheel_angle": -1.2343308951866099, "front_wheel_angle": -0.057633099212725546, "heading_rate": -0.0488165923212785, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141209.3918414} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2931293339047263, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.2694804549672786, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1885098188040577, "gear": 1, "accelerator_pedal_position": 0.2931293339047263, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1173189934128167, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141209.3918414} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141209.4118414, "x": 35.78594734588006, "y": 4.645797361633792, "z": null, "yaw": 3.1104799761588944, "pitch": null, "roll": null}, "v": 2.1907571897410008, "accelerator_pedal_position": 0.2931293339047263, "brake_pedal_position": 0.0, "acceleration": 0.2245263067734703, "steering_wheel_angle": -1.1173189934128167, "front_wheel_angle": -0.05208581595517879, "heading_rate": -0.044613545473984675, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141209.4118414} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2924017448253229, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.2239918679824762, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1907571897410008, "gear": 1, "accelerator_pedal_position": 0.2931293339047263, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1173189934128167, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141209.4118414} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.049952268600464, "x": 31.78594734588006, "y": -0.3542026383662078, "z": null, "yaw": 3.1104799761588944, "pitch": null, "roll": null}, "v": 2.1907571897410008, "accelerator_pedal_position": 0.2931293339047263, "brake_pedal_position": 0.0, "acceleration": 0.2245263067734703, "steering_wheel_angle": -1.1173189934128167, "front_wheel_angle": -0.05208581595517879, "heading_rate": -0.044613545473984675, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141209.4318414} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2929248587382406, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.2239918679824762, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1973503643057093, "gear": 1, "accelerator_pedal_position": 0.2924017448253229, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.0782772222903152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141209.4318414} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.049952268600464, "x": 31.78594734588006, "y": -0.3542026383662078, "z": null, "yaw": 3.1104799761588944, "pitch": null, "roll": null}, "v": 2.1907571897410008, "accelerator_pedal_position": 0.2931293339047263, "brake_pedal_position": 0.0, "acceleration": 0.2245263067734703, "steering_wheel_angle": -1.1173189934128167, "front_wheel_angle": -0.05208581595517879, "heading_rate": -0.044613545473984675, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141209.4518414} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2929248587382406, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.2239918679824762, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.199576657932345, "gear": 1, "accelerator_pedal_position": 0.2929248587382406, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.0782772222903152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141209.4518414} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.049952268600464, "x": 31.78594734588006, "y": -0.3542026383662078, "z": null, "yaw": 3.1104799761588944, "pitch": null, "roll": null}, "v": 2.1907571897410008, "accelerator_pedal_position": 0.2931293339047263, "brake_pedal_position": 0.0, "acceleration": 0.2245263067734703, "steering_wheel_angle": -1.1173189934128167, "front_wheel_angle": -0.05208581595517879, "heading_rate": -0.044613545473984675, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141209.4718413} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2929248587382406, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.2239918679824762, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.204022970065982, "gear": 1, "accelerator_pedal_position": 0.2929248587382406, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.0782772222903152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141209.4718413} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.049952268600464, "x": 31.78594734588006, "y": -0.3542026383662078, "z": null, "yaw": 3.1104799761588944, "pitch": null, "roll": null}, "v": 2.1907571897410008, "accelerator_pedal_position": 0.2931293339047263, "brake_pedal_position": 0.0, "acceleration": 0.2245263067734703, "steering_wheel_angle": -1.1173189934128167, "front_wheel_angle": -0.05208581595517879, "heading_rate": -0.044613545473984675, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141209.4918413} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2929248587382406, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.2239918679824762, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.208460921889383, "gear": 1, "accelerator_pedal_position": 0.2929248587382406, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.0782772222903152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141209.4918413} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.049952268600464, "x": 31.78594734588006, "y": -0.3542026383662078, "z": null, "yaw": 3.1104799761588944, "pitch": null, "roll": null}, "v": 2.1907571897410008, "accelerator_pedal_position": 0.2931293339047263, "brake_pedal_position": 0.0, "acceleration": 0.2245263067734703, "steering_wheel_angle": -1.1173189934128167, "front_wheel_angle": -0.05208581595517879, "heading_rate": -0.044613545473984675, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141209.5118413} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2929248587382406, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.2239918679824762, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.215102191212422, "gear": 1, "accelerator_pedal_position": 0.2929248587382406, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.0782772222903152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141209.5118413} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141209.5218413, "x": 35.54387328044857, "y": 4.653571406079385, "z": null, "yaw": 3.108312220035275, "pitch": null, "roll": null}, "v": 2.215102191212422, "accelerator_pedal_position": 0.2929248587382406, "brake_pedal_position": 0.0, "acceleration": 0.22095848037824173, "steering_wheel_angle": -1.0782772222903152, "front_wheel_angle": -0.05023895025861872, "heading_rate": -0.043507081612453355, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141209.5318413} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29200210292680234, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.17809980092007252, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.21951927664813, "gear": 1, "accelerator_pedal_position": 0.2929248587382406, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.0782772222903152, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141209.5318413} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.15995216369629, "x": 31.543873280448572, "y": -0.3464285939206153, "z": null, "yaw": 3.108312220035275, "pitch": null, "roll": null}, "v": 2.215102191212422, "accelerator_pedal_position": 0.2929248587382406, "brake_pedal_position": 0.0, "acceleration": 0.22095848037824173, "steering_wheel_angle": -1.0782772222903152, "front_wheel_angle": -0.05023895025861872, "heading_rate": -0.043507081612453355, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141209.5518413} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29261597602783457, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.17809980092007252, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.22166702186079, "gear": 1, "accelerator_pedal_position": 0.29200210292680234, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.0392405185171847, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141209.5518413} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.15995216369629, "x": 31.543873280448572, "y": -0.3464285939206153, "z": null, "yaw": 3.108312220035275, "pitch": null, "roll": null}, "v": 2.215102191212422, "accelerator_pedal_position": 0.2929248587382406, "brake_pedal_position": 0.0, "acceleration": 0.22095848037824173, "steering_wheel_angle": -1.0782772222903152, "front_wheel_angle": -0.05023895025861872, "heading_rate": -0.043507081612453355, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141209.5718412} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29261597602783457, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.17809980092007252, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.226033127990178, "gear": 1, "accelerator_pedal_position": 0.29261597602783457, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.000161548052301, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141209.5718412} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.15995216369629, "x": 31.543873280448572, "y": -0.3464285939206153, "z": null, "yaw": 3.108312220035275, "pitch": null, "roll": null}, "v": 2.215102191212422, "accelerator_pedal_position": 0.2929248587382406, "brake_pedal_position": 0.0, "acceleration": 0.22095848037824173, "steering_wheel_angle": -1.0782772222903152, "front_wheel_angle": -0.05023895025861872, "heading_rate": -0.043507081612453355, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141209.5918412} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29261597602783457, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.17809980092007252, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2303909861808155, "gear": 1, "accelerator_pedal_position": 0.29261597602783457, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.000161548052301, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141209.5918412} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.15995216369629, "x": 31.543873280448572, "y": -0.3464285939206153, "z": null, "yaw": 3.108312220035275, "pitch": null, "roll": null}, "v": 2.215102191212422, "accelerator_pedal_position": 0.2929248587382406, "brake_pedal_position": 0.0, "acceleration": 0.22095848037824173, "steering_wheel_angle": -1.0782772222903152, "front_wheel_angle": -0.05023895025861872, "heading_rate": -0.043507081612453355, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141209.6118412} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29261597602783457, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.17809980092007252, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.236912326063591, "gear": 1, "accelerator_pedal_position": 0.29261597602783457, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.000161548052301, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141209.6118412} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141209.6318412, "x": 35.29915369572876, "y": 4.661951954981324, "z": null, "yaw": 3.106260034964197, "pitch": null, "roll": null}, "v": 2.2390819907268495, "accelerator_pedal_position": 0.29261597602783457, "brake_pedal_position": 0.0, "acceleration": 0.21676086902565034, "steering_wheel_angle": -1.000161548052301, "front_wheel_angle": -0.04654969955465771, "heading_rate": -0.040743727611022275, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141209.6318412} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2983534206809477, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.059574221719807946, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.241249599417106, "gear": 1, "accelerator_pedal_position": 0.29261597602783457, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.000161548052301, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141209.6318412} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.269952058792114, "x": 31.299153695728762, "y": -0.3380480450186756, "z": null, "yaw": 3.106260034964197, "pitch": null, "roll": null}, "v": 2.2390819907268495, "accelerator_pedal_position": 0.29261597602783457, "brake_pedal_position": 0.0, "acceleration": 0.21676086902565034, "steering_wheel_angle": -1.000161548052301, "front_wheel_angle": -0.04654969955465771, "heading_rate": -0.040743727611022275, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141209.6518412} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.295794033903801, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.059574221719807946, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2462954932929384, "gear": 1, "accelerator_pedal_position": 0.2983534206809477, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.9221210381546441, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141209.6518412} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.269952058792114, "x": 31.299153695728762, "y": -0.3380480450186756, "z": null, "yaw": 3.106260034964197, "pitch": null, "roll": null}, "v": 2.2390819907268495, "accelerator_pedal_position": 0.29261597602783457, "brake_pedal_position": 0.0, "acceleration": 0.21676086902565034, "steering_wheel_angle": -1.000161548052301, "front_wheel_angle": -0.04654969955465771, "heading_rate": -0.040743727611022275, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141209.6718411} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.295794033903801, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.059574221719807946, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2510120431151104, "gear": 1, "accelerator_pedal_position": 0.295794033903801, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.8830377777153027, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141209.6718411} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.269952058792114, "x": 31.299153695728762, "y": -0.3380480450186756, "z": null, "yaw": 3.106260034964197, "pitch": null, "roll": null}, "v": 2.2390819907268495, "accelerator_pedal_position": 0.29261597602783457, "brake_pedal_position": 0.0, "acceleration": 0.21676086902565034, "steering_wheel_angle": -1.000161548052301, "front_wheel_angle": -0.04654969955465771, "heading_rate": -0.040743727611022275, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141209.6918411} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.295794033903801, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.059574221719807946, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2533669586907155, "gear": 1, "accelerator_pedal_position": 0.295794033903801, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.8830377777153027, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141209.6918411} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.269952058792114, "x": 31.299153695728762, "y": -0.3380480450186756, "z": null, "yaw": 3.106260034964197, "pitch": null, "roll": null}, "v": 2.2390819907268495, "accelerator_pedal_position": 0.29261597602783457, "brake_pedal_position": 0.0, "acceleration": 0.21676086902565034, "steering_wheel_angle": -1.000161548052301, "front_wheel_angle": -0.04654969955465771, "heading_rate": -0.040743727611022275, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141209.711841} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.295794033903801, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.059574221719807946, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2604182802925363, "gear": 1, "accelerator_pedal_position": 0.295794033903801, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.8830377777153027, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141209.711841} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.269952058792114, "x": 31.299153695728762, "y": -0.3380480450186756, "z": null, "yaw": 3.106260034964197, "pitch": null, "roll": null}, "v": 2.2390819907268495, "accelerator_pedal_position": 0.29261597602783457, "brake_pedal_position": 0.0, "acceleration": 0.21676086902565034, "steering_wheel_angle": -1.000161548052301, "front_wheel_angle": -0.04654969955465771, "heading_rate": -0.040743727611022275, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141209.731841} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.295794033903801, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.059574221719807946, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.26510798398084, "gear": 1, "accelerator_pedal_position": 0.295794033903801, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.8830377777153027, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141209.731841} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141209.741841, "x": 35.05171177523437, "y": 4.670910439031051, "z": null, "yaw": 3.1044311350676796, "pitch": null, "roll": null}, "v": 2.26510798398084, "accelerator_pedal_position": 0.295794033903801, "brake_pedal_position": 0.0, "acceleration": 0.23415017090877666, "steering_wheel_angle": -0.8830377777153027, "front_wheel_angle": -0.04103306940575083, "heading_rate": -0.036326770362393596, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141209.751841} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2942711158055835, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.011483038775950817, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2696935729679164, "gear": 1, "accelerator_pedal_position": 0.2942711158055835, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.84394101431166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141209.751841} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.37995195388794, "x": 31.051711775234367, "y": -0.32908956096894926, "z": null, "yaw": 3.1044311350676796, "pitch": null, "roll": null}, "v": 2.26510798398084, "accelerator_pedal_position": 0.295794033903801, "brake_pedal_position": 0.0, "acceleration": 0.23415017090877666, "steering_wheel_angle": -0.8830377777153027, "front_wheel_angle": -0.04103306940575083, "heading_rate": -0.036326770362393596, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141209.771841} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2951847770586085, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.011483038775950817, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2719355200277644, "gear": 1, "accelerator_pedal_position": 0.2942711158055835, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.84394101431166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141209.771841} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.37995195388794, "x": 31.051711775234367, "y": -0.32908956096894926, "z": null, "yaw": 3.1044311350676796, "pitch": null, "roll": null}, "v": 2.26510798398084, "accelerator_pedal_position": 0.295794033903801, "brake_pedal_position": 0.0, "acceleration": 0.23415017090877666, "steering_wheel_angle": -0.8830377777153027, "front_wheel_angle": -0.04103306940575083, "heading_rate": -0.036326770362393596, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141209.791841} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2951847770586085, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.011483038775950817, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.276527150768139, "gear": 1, "accelerator_pedal_position": 0.2951847770586085, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.84394101431166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141209.791841} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.37995195388794, "x": 31.051711775234367, "y": -0.32908956096894926, "z": null, "yaw": 3.1044311350676796, "pitch": null, "roll": null}, "v": 2.26510798398084, "accelerator_pedal_position": 0.295794033903801, "brake_pedal_position": 0.0, "acceleration": 0.23415017090877666, "steering_wheel_angle": -0.8830377777153027, "front_wheel_angle": -0.04103306940575083, "heading_rate": -0.036326770362393596, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141209.811841} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2951847770586085, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.011483038775950817, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.283398162255237, "gear": 1, "accelerator_pedal_position": 0.2951847770586085, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.84394101431166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141209.811841} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.37995195388794, "x": 31.051711775234367, "y": -0.32908956096894926, "z": null, "yaw": 3.1044311350676796, "pitch": null, "roll": null}, "v": 2.26510798398084, "accelerator_pedal_position": 0.295794033903801, "brake_pedal_position": 0.0, "acceleration": 0.23415017090877666, "steering_wheel_angle": -0.8830377777153027, "front_wheel_angle": -0.04103306940575083, "heading_rate": -0.036326770362393596, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141209.831841} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2951847770586085, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.011483038775950817, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2856841210235332, "gear": 1, "accelerator_pedal_position": 0.2951847770586085, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.84394101431166, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141209.831841} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141209.851841, "x": 34.80147276881152, "y": 4.680409419048394, "z": null, "yaw": 3.102731710184579, "pitch": null, "roll": null}, "v": 2.2902494772514306, "accelerator_pedal_position": 0.2951847770586085, "brake_pedal_position": 0.0, "acceleration": 0.2279399560732271, "steering_wheel_angle": -0.84394101431166, "front_wheel_angle": -0.039195531496243365, "heading_rate": -0.035083415405491786, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141209.851841} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2787597255983794, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.07780011740584666, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2915023110958987, "gear": 1, "accelerator_pedal_position": 0.2787597255983794, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.8047137376798009, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141209.851841} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.489951848983765, "x": 30.80147276881152, "y": -0.31959058095160575, "z": null, "yaw": 3.102731710184579, "pitch": null, "roll": null}, "v": 2.2902494772514306, "accelerator_pedal_position": 0.2951847770586085, "brake_pedal_position": 0.0, "acceleration": 0.2279399560732271, "steering_wheel_angle": -0.84394101431166, "front_wheel_angle": -0.039195531496243365, "heading_rate": -0.035083415405491786, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141209.861841} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2867642195916046, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.07780011740584666, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2915023110958987, "gear": 1, "accelerator_pedal_position": 0.2787597255983794, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.8047137376798009, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141209.861841} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.489951848983765, "x": 30.80147276881152, "y": -0.31959058095160575, "z": null, "yaw": 3.102731710184579, "pitch": null, "roll": null}, "v": 2.2902494772514306, "accelerator_pedal_position": 0.2951847770586085, "brake_pedal_position": 0.0, "acceleration": 0.2279399560732271, "steering_wheel_angle": -0.84394101431166, "front_wheel_angle": -0.039195531496243365, "heading_rate": -0.035083415405491786, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141209.891841} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2867642195916046, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.07780011740584666, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.296753017445068, "gear": 1, "accelerator_pedal_position": 0.2867642195916046, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.765444328583314, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141209.891841} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.489951848983765, "x": 30.80147276881152, "y": -0.31959058095160575, "z": null, "yaw": 3.102731710184579, "pitch": null, "roll": null}, "v": 2.2902494772514306, "accelerator_pedal_position": 0.2951847770586085, "brake_pedal_position": 0.0, "acceleration": 0.2279399560732271, "steering_wheel_angle": -0.84394101431166, "front_wheel_angle": -0.039195531496243365, "heading_rate": -0.035083415405491786, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141209.921841} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2867642195916046, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.07780011740584666, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3037304834832466, "gear": 1, "accelerator_pedal_position": 0.2867642195916046, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.765444328583314, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141209.921841} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.489951848983765, "x": 30.80147276881152, "y": -0.31959058095160575, "z": null, "yaw": 3.102731710184579, "pitch": null, "roll": null}, "v": 2.2902494772514306, "accelerator_pedal_position": 0.2951847770586085, "brake_pedal_position": 0.0, "acceleration": 0.2279399560732271, "steering_wheel_angle": -0.84394101431166, "front_wheel_angle": -0.039195531496243365, "heading_rate": -0.035083415405491786, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141209.941841} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2867642195916046, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.07780011740584666, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3054706645519274, "gear": 1, "accelerator_pedal_position": 0.2867642195916046, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.765444328583314, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141209.941841} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141209.9618409, "x": 34.54883168790226, "y": 4.690412880821024, "z": null, "yaw": 3.101183543974923, "pitch": null, "roll": null}, "v": 2.3089460111663653, "accelerator_pedal_position": 0.2867642195916046, "brake_pedal_position": 0.0, "acceleration": 0.17351675506439962, "steering_wheel_angle": -0.765444328583314, "front_wheel_angle": -0.035512143461823915, "heading_rate": -0.03204301091949533, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141209.9618409} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2767379350367617, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.11705913322043361, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3106811787170094, "gear": 1, "accelerator_pedal_position": 0.2867642195916046, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.765444328583314, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141209.9618409} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.59995174407959, "x": 30.548831687902258, "y": -0.30958711917897563, "z": null, "yaw": 3.101183543974923, "pitch": null, "roll": null}, "v": 2.3089460111663653, "accelerator_pedal_position": 0.2867642195916046, "brake_pedal_position": 0.0, "acceleration": 0.17351675506439962, "steering_wheel_angle": -0.765444328583314, "front_wheel_angle": -0.035512143461823915, "heading_rate": -0.03204301091949533, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141209.9818408} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28164909903736524, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.11705913322043361, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3117880343164807, "gear": 1, "accelerator_pedal_position": 0.2767379350367617, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7260920617971741, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141209.9818408} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.59995174407959, "x": 30.548831687902258, "y": -0.30958711917897563, "z": null, "yaw": 3.101183543974923, "pitch": null, "roll": null}, "v": 2.3089460111663653, "accelerator_pedal_position": 0.2867642195916046, "brake_pedal_position": 0.0, "acceleration": 0.17351675506439962, "steering_wheel_angle": -0.765444328583314, "front_wheel_angle": -0.035512143461823915, "heading_rate": -0.03204301091949533, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141210.0018408} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28164909903736524, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.11705913322043361, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3160221707929627, "gear": 1, "accelerator_pedal_position": 0.28164909903736524, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7260920617971741, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141210.0018408} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.59995174407959, "x": 30.548831687902258, "y": -0.30958711917897563, "z": null, "yaw": 3.101183543974923, "pitch": null, "roll": null}, "v": 2.3089460111663653, "accelerator_pedal_position": 0.2867642195916046, "brake_pedal_position": 0.0, "acceleration": 0.17351675506439962, "steering_wheel_angle": -0.765444328583314, "front_wheel_angle": -0.035512143461823915, "heading_rate": -0.03204301091949533, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141210.0218408} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28164909903736524, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.11705913322043361, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3188381372350575, "gear": 1, "accelerator_pedal_position": 0.28164909903736524, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7260920617971741, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141210.0218408} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.59995174407959, "x": 30.548831687902258, "y": -0.30958711917897563, "z": null, "yaw": 3.101183543974923, "pitch": null, "roll": null}, "v": 2.3089460111663653, "accelerator_pedal_position": 0.2867642195916046, "brake_pedal_position": 0.0, "acceleration": 0.17351675506439962, "steering_wheel_angle": -0.765444328583314, "front_wheel_angle": -0.035512143461823915, "heading_rate": -0.03204301091949533, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141210.0418408} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28164909903736524, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.11705913322043361, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.321648679210748, "gear": 1, "accelerator_pedal_position": 0.28164909903736524, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7260920617971741, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141210.0418408} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.59995174407959, "x": 30.548831687902258, "y": -0.30958711917897563, "z": null, "yaw": 3.101183543974923, "pitch": null, "roll": null}, "v": 2.3089460111663653, "accelerator_pedal_position": 0.2867642195916046, "brake_pedal_position": 0.0, "acceleration": 0.17351675506439962, "steering_wheel_angle": -0.765444328583314, "front_wheel_angle": -0.035512143461823915, "heading_rate": -0.03204301091949533, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141210.0618408} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28164909903736524, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.11705913322043361, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3244538040111813, "gear": 1, "accelerator_pedal_position": 0.28164909903736524, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7260920617971741, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141210.0618408} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141210.0718408, "x": 34.294282008521726, "y": 4.700875719113997, "z": null, "yaw": 3.099721881512458, "pitch": null, "roll": null}, "v": 2.3244538040111813, "accelerator_pedal_position": 0.28164909903736524, "brake_pedal_position": 0.0, "acceleration": 0.140053323913153, "steering_wheel_angle": -0.7260920617971741, "front_wheel_angle": -0.033668542544312056, "heading_rate": -0.030582248694143256, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141210.0818408} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27293968133263435, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.15718685538627705, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3258543372503127, "gear": 1, "accelerator_pedal_position": 0.28164909903736524, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7260920617971741, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141210.0818408} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.709951639175415, "x": 30.294282008521726, "y": -0.2991242808860033, "z": null, "yaw": 3.099721881512458, "pitch": null, "roll": null}, "v": 2.3244538040111813, "accelerator_pedal_position": 0.28164909903736524, "brake_pedal_position": 0.0, "acceleration": 0.140053323913153, "steering_wheel_angle": -0.7260920617971741, "front_wheel_angle": -0.033668542544312056, "heading_rate": -0.030582248694143256, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141210.1018407} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2772008482873168, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.15718685538627705, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.328416391697285, "gear": 1, "accelerator_pedal_position": 0.27293968133263435, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6866557730473404, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141210.1018407} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.709951639175415, "x": 30.294282008521726, "y": -0.2991242808860033, "z": null, "yaw": 3.099721881512458, "pitch": null, "roll": null}, "v": 2.3244538040111813, "accelerator_pedal_position": 0.28164909903736524, "brake_pedal_position": 0.0, "acceleration": 0.140053323913153, "steering_wheel_angle": -0.7260920617971741, "front_wheel_angle": -0.033668542544312056, "heading_rate": -0.030582248694143256, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141210.1218407} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2772008482873168, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.15718685538627705, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.330652696335058, "gear": 1, "accelerator_pedal_position": 0.2772008482873168, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6866557730473404, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141210.1218407} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.709951639175415, "x": 30.294282008521726, "y": -0.2991242808860033, "z": null, "yaw": 3.099721881512458, "pitch": null, "roll": null}, "v": 2.3244538040111813, "accelerator_pedal_position": 0.28164909903736524, "brake_pedal_position": 0.0, "acceleration": 0.140053323913153, "steering_wheel_angle": -0.7260920617971741, "front_wheel_angle": -0.033668542544312056, "heading_rate": -0.030582248694143256, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141210.1418407} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2772008482873168, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.15718685538627705, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3317692288057543, "gear": 1, "accelerator_pedal_position": 0.2772008482873168, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6866557730473404, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141210.1418407} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.709951639175415, "x": 30.294282008521726, "y": -0.2991242808860033, "z": null, "yaw": 3.099721881512458, "pitch": null, "roll": null}, "v": 2.3244538040111813, "accelerator_pedal_position": 0.28164909903736524, "brake_pedal_position": 0.0, "acceleration": 0.140053323913153, "steering_wheel_angle": -0.7260920617971741, "front_wheel_angle": -0.033668542544312056, "heading_rate": -0.030582248694143256, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141210.1618407} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2772008482873168, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.15718685538627705, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3339990580182537, "gear": 1, "accelerator_pedal_position": 0.2772008482873168, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6866557730473404, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141210.1618407} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141210.1818407, "x": 34.038243997454714, "y": 4.711765315210165, "z": null, "yaw": 3.0983395919076964, "pitch": null, "roll": null}, "v": 2.336224578215026, "accelerator_pedal_position": 0.2772008482873168, "brake_pedal_position": 0.0, "acceleration": 0.11111462008641876, "steering_wheel_angle": -0.6866557730473404, "front_wheel_angle": -0.03182298639720416, "heading_rate": -0.029051074146729534, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141210.1818407} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26561718604490325, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.21593887868272693, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.336224578215026, "gear": 1, "accelerator_pedal_position": 0.2772008482873168, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6866557730473404, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141210.1818407} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.81995153427124, "x": 30.038243997454714, "y": -0.2882346847898347, "z": null, "yaw": 3.0983395919076964, "pitch": null, "roll": null}, "v": 2.336224578215026, "accelerator_pedal_position": 0.2772008482873168, "brake_pedal_position": 0.0, "acceleration": 0.11111462008641876, "steering_wheel_angle": -0.6866557730473404, "front_wheel_angle": -0.03182298639720416, "heading_rate": -0.029051074146729534, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141210.2018406} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27121985746494076, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.21593887868272693, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3384709969200395, "gear": 1, "accelerator_pedal_position": 0.27121985746494076, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6471156646650172, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141210.2018406} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.81995153427124, "x": 30.038243997454714, "y": -0.2882346847898347, "z": null, "yaw": 3.0983395919076964, "pitch": null, "roll": null}, "v": 2.336224578215026, "accelerator_pedal_position": 0.2772008482873168, "brake_pedal_position": 0.0, "acceleration": 0.11111462008641876, "steering_wheel_angle": -0.6866557730473404, "front_wheel_angle": -0.03182298639720416, "heading_rate": -0.029051074146729534, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141210.2218406} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27121985746494076, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.21593887868272693, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3384709969200395, "gear": 1, "accelerator_pedal_position": 0.27121985746494076, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6471156646650172, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141210.2218406} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.81995153427124, "x": 30.038243997454714, "y": -0.2882346847898347, "z": null, "yaw": 3.0983395919076964, "pitch": null, "roll": null}, "v": 2.336224578215026, "accelerator_pedal_position": 0.2772008482873168, "brake_pedal_position": 0.0, "acceleration": 0.11111462008641876, "steering_wheel_angle": -0.6866557730473404, "front_wheel_angle": -0.03182298639720416, "heading_rate": -0.029051074146729534, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141210.2418406} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27121985746494076, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.21593887868272693, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3399406073205333, "gear": 1, "accelerator_pedal_position": 0.27121985746494076, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6471156646650172, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141210.2418406} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.81995153427124, "x": 30.038243997454714, "y": -0.2882346847898347, "z": null, "yaw": 3.0983395919076964, "pitch": null, "roll": null}, "v": 2.336224578215026, "accelerator_pedal_position": 0.2772008482873168, "brake_pedal_position": 0.0, "acceleration": 0.11111462008641876, "steering_wheel_angle": -0.6866557730473404, "front_wheel_angle": -0.03182298639720416, "heading_rate": -0.029051074146729534, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141210.2618406} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27121985746494076, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.21593887868272693, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.342871302149541, "gear": 1, "accelerator_pedal_position": 0.27121985746494076, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6471156646650172, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141210.2618406} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.81995153427124, "x": 30.038243997454714, "y": -0.2882346847898347, "z": null, "yaw": 3.0983395919076964, "pitch": null, "roll": null}, "v": 2.336224578215026, "accelerator_pedal_position": 0.2772008482873168, "brake_pedal_position": 0.0, "acceleration": 0.11111462008641876, "steering_wheel_angle": -0.6866557730473404, "front_wheel_angle": -0.03182298639720416, "heading_rate": -0.029051074146729534, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141210.2818406} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27121985746494076, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.21593887868272693, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.342871302149541, "gear": 1, "accelerator_pedal_position": 0.27121985746494076, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6471156646650172, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141210.2818406} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141210.2918406, "x": 33.781168514264245, "y": 4.723044171117563, "z": null, "yaw": 3.097044009487512, "pitch": null, "roll": null}, "v": 2.3436022029961814, "accelerator_pedal_position": 0.27121985746494076, "brake_pedal_position": 0.0, "acceleration": 0.07301928614718506, "steering_wheel_angle": -0.6471156646650172, "front_wheel_angle": -0.02997455629361206, "heading_rate": -0.027449016611646542, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141210.3118405} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26555768279939795, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.25787294813687295, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.345436774024644, "gear": 1, "accelerator_pedal_position": 0.26555768279939795, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.607488988775224, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141210.3118405} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.929951429367065, "x": 29.781168514264245, "y": -0.2769558288824374, "z": null, "yaw": 3.097044009487512, "pitch": null, "roll": null}, "v": 2.3436022029961814, "accelerator_pedal_position": 0.27121985746494076, "brake_pedal_position": 0.0, "acceleration": 0.07301928614718506, "steering_wheel_angle": -0.6471156646650172, "front_wheel_angle": -0.02997455629361206, "heading_rate": -0.027449016611646542, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141210.3318405} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2683083685894115, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.25787294813687295, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.345811303446499, "gear": 1, "accelerator_pedal_position": 0.26555768279939795, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5678197770259017, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141210.3318405} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.929951429367065, "x": 29.781168514264245, "y": -0.2769558288824374, "z": null, "yaw": 3.097044009487512, "pitch": null, "roll": null}, "v": 2.3436022029961814, "accelerator_pedal_position": 0.27121985746494076, "brake_pedal_position": 0.0, "acceleration": 0.07301928614718506, "steering_wheel_angle": -0.6471156646650172, "front_wheel_angle": -0.02997455629361206, "heading_rate": -0.027449016611646542, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141210.3518405} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2683083685894115, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.25787294813687295, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3474479690314585, "gear": 1, "accelerator_pedal_position": 0.2683083685894115, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5678197770259017, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141210.3518405} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.929951429367065, "x": 29.781168514264245, "y": -0.2769558288824374, "z": null, "yaw": 3.097044009487512, "pitch": null, "roll": null}, "v": 2.3436022029961814, "accelerator_pedal_position": 0.27121985746494076, "brake_pedal_position": 0.0, "acceleration": 0.07301928614718506, "steering_wheel_angle": -0.6471156646650172, "front_wheel_angle": -0.02997455629361206, "heading_rate": -0.027449016611646542, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141210.3718405} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2683083685894115, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.25787294813687295, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.34799246688705, "gear": 1, "accelerator_pedal_position": 0.2683083685894115, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5678197770259017, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141210.3718405} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.929951429367065, "x": 29.781168514264245, "y": -0.2769558288824374, "z": null, "yaw": 3.097044009487512, "pitch": null, "roll": null}, "v": 2.3436022029961814, "accelerator_pedal_position": 0.27121985746494076, "brake_pedal_position": 0.0, "acceleration": 0.07301928614718506, "steering_wheel_angle": -0.6471156646650172, "front_wheel_angle": -0.02997455629361206, "heading_rate": -0.027449016611646542, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141210.3918405} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2683083685894115, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.25787294813687295, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.349079879306902, "gear": 1, "accelerator_pedal_position": 0.2683083685894115, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5678197770259017, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141210.3918405} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141210.4018404, "x": 33.52332538932723, "y": 4.734681374752645, "z": null, "yaw": 3.095864167830999, "pitch": null, "roll": null}, "v": 2.3496227947761503, "accelerator_pedal_position": 0.2683083685894115, "brake_pedal_position": 0.0, "acceleration": 0.05423889116769731, "steering_wheel_angle": -0.5678197770259017, "front_wheel_angle": -0.02627357707008632, "heading_rate": -0.024120001674736304, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141210.4118404} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2556746918837526, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.32393742705847245, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3501651836878272, "gear": 1, "accelerator_pedal_position": 0.2683083685894115, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5678197770259017, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141210.4118404} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.03995132446289, "x": 29.523325389327233, "y": -0.26531862524735494, "z": null, "yaw": 3.095864167830999, "pitch": null, "roll": null}, "v": 2.3496227947761503, "accelerator_pedal_position": 0.2683083685894115, "brake_pedal_position": 0.0, "acceleration": 0.05423889116769731, "steering_wheel_angle": -0.5678197770259017, "front_wheel_angle": -0.02627357707008632, "heading_rate": -0.024120001674736304, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141210.4318404} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26173519540021395, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.32393742705847245, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.34966994002326, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.528038061122304, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141210.4318404} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.03995132446289, "x": 29.523325389327233, "y": -0.26531862524735494, "z": null, "yaw": 3.095864167830999, "pitch": null, "roll": null}, "v": 2.3496227947761503, "accelerator_pedal_position": 0.2683083685894115, "brake_pedal_position": 0.0, "acceleration": 0.05423889116769731, "steering_wheel_angle": -0.5678197770259017, "front_wheel_angle": -0.02627357707008632, "heading_rate": -0.024120001674736304, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141210.4518404} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26173519540021395, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.32393742705847245, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3499328521755416, "gear": 1, "accelerator_pedal_position": 0.26173519540021395, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.528038061122304, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141210.4518404} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.03995132446289, "x": 29.523325389327233, "y": -0.26531862524735494, "z": null, "yaw": 3.095864167830999, "pitch": null, "roll": null}, "v": 2.3496227947761503, "accelerator_pedal_position": 0.2683083685894115, "brake_pedal_position": 0.0, "acceleration": 0.05423889116769731, "steering_wheel_angle": -0.5678197770259017, "front_wheel_angle": -0.02627357707008632, "heading_rate": -0.024120001674736304, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141210.4718404} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26173519540021395, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.32393742705847245, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3501952545395857, "gear": 1, "accelerator_pedal_position": 0.26173519540021395, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.528038061122304, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141210.4718404} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.03995132446289, "x": 29.523325389327233, "y": -0.26531862524735494, "z": null, "yaw": 3.095864167830999, "pitch": null, "roll": null}, "v": 2.3496227947761503, "accelerator_pedal_position": 0.2683083685894115, "brake_pedal_position": 0.0, "acceleration": 0.05423889116769731, "steering_wheel_angle": -0.5678197770259017, "front_wheel_angle": -0.02627357707008632, "heading_rate": -0.024120001674736304, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141210.4918404} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26173519540021395, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.32393742705847245, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.350457148076346, "gear": 1, "accelerator_pedal_position": 0.26173519540021395, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.528038061122304, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141210.4918404} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141210.5118403, "x": 33.26509404877087, "y": 4.746624836301868, "z": null, "yaw": 3.09480017796735, "pitch": null, "roll": null}, "v": 2.3507185337450727, "accelerator_pedal_position": 0.26173519540021395, "brake_pedal_position": 0.0, "acceleration": 0.013050268315157598, "steering_wheel_angle": -0.528038061122304, "front_wheel_angle": -0.02441982882117243, "heading_rate": -0.022427952144598473, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141210.5118403} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2511811452010906, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3772670659490965, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3507185337450727, "gear": 1, "accelerator_pedal_position": 0.26173519540021395, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.528038061122304, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141210.5118403} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.149951219558716, "x": 29.26509404877087, "y": -0.2533751636981316, "z": null, "yaw": 3.09480017796735, "pitch": null, "roll": null}, "v": 2.3507185337450727, "accelerator_pedal_position": 0.26173519540021395, "brake_pedal_position": 0.0, "acceleration": 0.013050268315157598, "steering_wheel_angle": -0.528038061122304, "front_wheel_angle": -0.02441982882117243, "heading_rate": -0.022427952144598473, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141210.5318403} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2562149842234903, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3772670659490965, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3496607961362175, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4881568470976463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141210.5318403} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.149951219558716, "x": 29.26509404877087, "y": -0.2533751636981316, "z": null, "yaw": 3.09480017796735, "pitch": null, "roll": null}, "v": 2.3507185337450727, "accelerator_pedal_position": 0.26173519540021395, "brake_pedal_position": 0.0, "acceleration": 0.013050268315157598, "steering_wheel_angle": -0.528038061122304, "front_wheel_angle": -0.02441982882117243, "heading_rate": -0.022427952144598473, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141210.5518403} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2562149842234903, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3772670659490965, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.349234034257533, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4881568470976463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141210.5518403} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.149951219558716, "x": 29.26509404877087, "y": -0.2533751636981316, "z": null, "yaw": 3.09480017796735, "pitch": null, "roll": null}, "v": 2.3507185337450727, "accelerator_pedal_position": 0.26173519540021395, "brake_pedal_position": 0.0, "acceleration": 0.013050268315157598, "steering_wheel_angle": -0.528038061122304, "front_wheel_angle": -0.02441982882117243, "heading_rate": -0.022427952144598473, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141210.5718403} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2562149842234903, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3772670659490965, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.348808099782929, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4881568470976463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141210.5718403} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.149951219558716, "x": 29.26509404877087, "y": -0.2533751636981316, "z": null, "yaw": 3.09480017796735, "pitch": null, "roll": null}, "v": 2.3507185337450727, "accelerator_pedal_position": 0.26173519540021395, "brake_pedal_position": 0.0, "acceleration": 0.013050268315157598, "steering_wheel_angle": -0.528038061122304, "front_wheel_angle": -0.02441982882117243, "heading_rate": -0.022427952144598473, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141210.5918403} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2562149842234903, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3772670659490965, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.348382991035706, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4881568470976463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141210.5918403} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.149951219558716, "x": 29.26509404877087, "y": -0.2533751636981316, "z": null, "yaw": 3.09480017796735, "pitch": null, "roll": null}, "v": 2.3507185337450727, "accelerator_pedal_position": 0.26173519540021395, "brake_pedal_position": 0.0, "acceleration": 0.013050268315157598, "steering_wheel_angle": -0.528038061122304, "front_wheel_angle": -0.02441982882117243, "heading_rate": -0.022427952144598473, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141210.6118402} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2562149842234903, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3772670659490965, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3479587063428355, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4881568470976463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141210.6118402} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141210.6218402, "x": 33.006980458875795, "y": 4.758827134181598, "z": null, "yaw": 3.093823235164446, "pitch": null, "roll": null}, "v": 2.3477468724949633, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37250649739784697, "steering_wheel_angle": -0.4881568470976463, "front_wheel_angle": -0.022563437487968668, "heading_rate": -0.020696184116719713, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141210.6318402} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25453020603347914, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4194297856471186, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.347535244034953, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4881568470976463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141210.6318402} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.25995111465454, "x": 29.006980458875795, "y": -0.24117286581840158, "z": null, "yaw": 3.093823235164446, "pitch": null, "roll": null}, "v": 2.3477468724949633, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37250649739784697, "steering_wheel_angle": -0.4881568470976463, "front_wheel_angle": -0.022563437487968668, "heading_rate": -0.020696184116719713, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141210.6518402} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25531052323465214, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4194297856471186, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3469021072548055, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4081756254276651, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141210.6518402} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.25995111465454, "x": 29.006980458875795, "y": -0.24117286581840158, "z": null, "yaw": 3.093823235164446, "pitch": null, "roll": null}, "v": 2.3477468724949633, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37250649739784697, "steering_wheel_angle": -0.4881568470976463, "front_wheel_angle": -0.022563437487968668, "heading_rate": -0.020696184116719713, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141210.6718402} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25531052323465214, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4194297856471186, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3463676897970434, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4081756254276651, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141210.6718402} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.25995111465454, "x": 29.006980458875795, "y": -0.24117286581840158, "z": null, "yaw": 3.093823235164446, "pitch": null, "roll": null}, "v": 2.3477468724949633, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37250649739784697, "steering_wheel_angle": -0.4881568470976463, "front_wheel_angle": -0.022563437487968668, "heading_rate": -0.020696184116719713, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141210.6918402} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25531052323465214, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4194297856471186, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.345834307859147, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4081756254276651, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141210.6918402} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.25995111465454, "x": 29.006980458875795, "y": -0.24117286581840158, "z": null, "yaw": 3.093823235164446, "pitch": null, "roll": null}, "v": 2.3477468724949633, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37250649739784697, "steering_wheel_angle": -0.4881568470976463, "front_wheel_angle": -0.022563437487968668, "heading_rate": -0.020696184116719713, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141210.7118402} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25531052323465214, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4194297856471186, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.345036171915352, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4081756254276651, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141210.7118402} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141210.7318401, "x": 32.74917736034416, "y": 4.771254565099135, "z": null, "yaw": 3.0929770165246673, "pitch": null, "roll": null}, "v": 2.344770642066801, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37221802574232365, "steering_wheel_angle": -0.4081756254276651, "front_wheel_angle": -0.018846459503576145, "heading_rate": -0.017264006915165404, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141210.7318401} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25401403302966113, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4627633486837702, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.344770642066801, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4081756254276651, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141210.7318401} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.369951009750366, "x": 28.749177360344163, "y": -0.22874543490086463, "z": null, "yaw": 3.0929770165246673, "pitch": null, "roll": null}, "v": 2.344770642066801, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37221802574232365, "steering_wheel_angle": -0.4081756254276651, "front_wheel_angle": -0.018846459503576145, "heading_rate": -0.017264006915165404, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141210.75184} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2546094308223775, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4627633486837702, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3440783712205784, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.36807400779418875, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141210.75184} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.369951009750366, "x": 28.749177360344163, "y": -0.22874543490086463, "z": null, "yaw": 3.0929770165246673, "pitch": null, "roll": null}, "v": 2.344770642066801, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37221802574232365, "steering_wheel_angle": -0.4081756254276651, "front_wheel_angle": -0.018846459503576145, "heading_rate": -0.017264006915165404, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141210.77184} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2546094308223775, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4627633486837702, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.343461829812785, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.36807400779418875, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141210.77184} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.369951009750366, "x": 28.749177360344163, "y": -0.22874543490086463, "z": null, "yaw": 3.0929770165246673, "pitch": null, "roll": null}, "v": 2.344770642066801, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37221802574232365, "steering_wheel_angle": -0.4081756254276651, "front_wheel_angle": -0.018846459503576145, "heading_rate": -0.017264006915165404, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141210.79184} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2546094308223775, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4627633486837702, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.342846482342355, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.36807400779418875, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141210.79184} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.369951009750366, "x": 28.749177360344163, "y": -0.22874543490086463, "z": null, "yaw": 3.0929770165246673, "pitch": null, "roll": null}, "v": 2.344770642066801, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37221802574232365, "steering_wheel_angle": -0.4081756254276651, "front_wheel_angle": -0.018846459503576145, "heading_rate": -0.017264006915165404, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141210.81184} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2546094308223775, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4627633486837702, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3422323263458313, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.36807400779418875, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141210.81184} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.369951009750366, "x": 28.749177360344163, "y": -0.22874543490086463, "z": null, "yaw": 3.0929770165246673, "pitch": null, "roll": null}, "v": 2.344770642066801, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37221802574232365, "steering_wheel_angle": -0.4081756254276651, "front_wheel_angle": -0.018846459503576145, "heading_rate": -0.017264006915165404, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141210.83184} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2546094308223775, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4627633486837702, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.341619359365406, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.36807400779418875, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141210.83184} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141210.84184, "x": 32.49173792715288, "y": 4.783867317653335, "z": null, "yaw": 3.092239816913404, "pitch": null, "roll": null}, "v": 2.3413133209897063, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3718831467199238, "steering_wheel_angle": -0.36807400779418875, "front_wheel_angle": -0.016985807174195608, "heading_rate": -0.015536297555283296, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141210.85184} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2519860037341851, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5042490763868812, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3410075789489055, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.36807400779418875, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141210.85184} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.47995090484619, "x": 28.491737927152883, "y": -0.21613268234666538, "z": null, "yaw": 3.092239816913404, "pitch": null, "roll": null}, "v": 2.3413133209897063, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3718831467199238, "steering_wheel_angle": -0.36807400779418875, "front_wheel_angle": -0.016985807174195608, "heading_rate": -0.015536297555283296, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141210.87184} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2532097407476897, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5042490763868812, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3400692130014273, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3278845238214161, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141210.87184} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.47995090484619, "x": 28.491737927152883, "y": -0.21613268234666538, "z": null, "yaw": 3.092239816913404, "pitch": null, "roll": null}, "v": 2.3413133209897063, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3718831467199238, "steering_wheel_angle": -0.36807400779418875, "front_wheel_angle": -0.016985807174195608, "heading_rate": -0.015536297555283296, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141210.89184} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2532097407476897, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5042490763868812, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.339285556061238, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3278845238214161, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141210.89184} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.47995090484619, "x": 28.491737927152883, "y": -0.21613268234666538, "z": null, "yaw": 3.092239816913404, "pitch": null, "roll": null}, "v": 2.3413133209897063, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3718831467199238, "steering_wheel_angle": -0.36807400779418875, "front_wheel_angle": -0.016985807174195608, "heading_rate": -0.015536297555283296, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141210.91184} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2532097407476897, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5042490763868812, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.338112912650889, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3278845238214161, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141210.91184} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.47995090484619, "x": 28.491737927152883, "y": -0.21613268234666538, "z": null, "yaw": 3.092239816913404, "pitch": null, "roll": null}, "v": 2.3413133209897063, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3718831467199238, "steering_wheel_angle": -0.36807400779418875, "front_wheel_angle": -0.016985807174195608, "heading_rate": -0.015536297555283296, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141210.93184} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2532097407476897, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5042490763868812, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3377227877920634, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3278845238214161, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141210.93184} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141210.95184, "x": 32.234730596743454, "y": 4.796640984058348, "z": null, "yaw": 3.091575391331149, "pitch": null, "roll": null}, "v": 2.3369436701139863, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37146024067855765, "steering_wheel_angle": -0.3278845238214161, "front_wheel_angle": -0.015123076662775257, "heading_rate": -0.013806434701379112, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141210.95184} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2450579821433342, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5356830004496769, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3369436701139863, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3278845238214161, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141210.95184} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.58995079994202, "x": 28.234730596743454, "y": -0.2033590159416523, "z": null, "yaw": 3.091575391331149, "pitch": null, "roll": null}, "v": 2.3369436701139863, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37146024067855765, "steering_wheel_angle": -0.3278845238214161, "front_wheel_angle": -0.015123076662775257, "heading_rate": -0.013806434701379112, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141210.97184} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24890755246528512, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5356830004496769, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3351475821656065, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3278845238214161, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141210.97184} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.58995079994202, "x": 28.234730596743454, "y": -0.2033590159416523, "z": null, "yaw": 3.091575391331149, "pitch": null, "roll": null}, "v": 2.3369436701139863, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37146024067855765, "steering_wheel_angle": -0.3278845238214161, "front_wheel_angle": -0.015123076662775257, "heading_rate": -0.013806434701379112, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141210.99184} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24890755246528512, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5356830004496769, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.333835930262277, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3278845238214161, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141210.99184} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.58995079994202, "x": 28.234730596743454, "y": -0.2033590159416523, "z": null, "yaw": 3.091575391331149, "pitch": null, "roll": null}, "v": 2.3369436701139863, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37146024067855765, "steering_wheel_angle": -0.3278845238214161, "front_wheel_angle": -0.015123076662775257, "heading_rate": -0.013806434701379112, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141211.0118399} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24890755246528512, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5356830004496769, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3325268134290265, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3278845238214161, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141211.0118399} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.58995079994202, "x": 28.234730596743454, "y": -0.2033590159416523, "z": null, "yaw": 3.091575391331149, "pitch": null, "roll": null}, "v": 2.3369436701139863, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37146024067855765, "steering_wheel_angle": -0.3278845238214161, "front_wheel_angle": -0.015123076662775257, "heading_rate": -0.013806434701379112, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141211.0318398} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24890755246528512, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5356830004496769, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3312202260810624, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3278845238214161, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141211.0318398} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.58995079994202, "x": 28.234730596743454, "y": -0.2033590159416523, "z": null, "yaw": 3.091575391331149, "pitch": null, "roll": null}, "v": 2.3369436701139863, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37146024067855765, "steering_wheel_angle": -0.3278845238214161, "front_wheel_angle": -0.015123076662775257, "heading_rate": -0.013806434701379112, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141211.0518398} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24890755246528512, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5356830004496769, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3299161626483555, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3278845238214161, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141211.0518398} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141211.0618398, "x": 31.978397885622606, "y": 4.809548612514597, "z": null, "yaw": 3.0909255220867276, "pitch": null, "roll": null}, "v": 2.329265075663615, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.370718011710243, "steering_wheel_angle": -0.3278845238214161, "front_wheel_angle": -0.015123076662775257, "heading_rate": -0.013761070316163849, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141211.0718398} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24951245796291982, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.581611350283588, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.328614617575593, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3278845238214161, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141211.0718398} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.69995069503784, "x": 27.978397885622606, "y": -0.19045138748540325, "z": null, "yaw": 3.0909255220867276, "pitch": null, "roll": null}, "v": 2.329265075663615, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.370718011710243, "steering_wheel_angle": -0.3278845238214161, "front_wheel_angle": -0.015123076662775257, "heading_rate": -0.013761070316163849, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141211.0918398} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24916785677526931, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.581611350283588, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.327391162003408, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.24720777083683684, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141211.0918398} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.69995069503784, "x": 27.978397885622606, "y": -0.19045138748540325, "z": null, "yaw": 3.0909255220867276, "pitch": null, "roll": null}, "v": 2.329265075663615, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.370718011710243, "steering_wheel_angle": -0.3278845238214161, "front_wheel_angle": -0.015123076662775257, "heading_rate": -0.013761070316163849, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141211.1118398} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24916785677526931, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.581611350283588, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.326127013522765, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.24720777083683684, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141211.1118398} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.69995069503784, "x": 27.978397885622606, "y": -0.19045138748540325, "z": null, "yaw": 3.0909255220867276, "pitch": null, "roll": null}, "v": 2.329265075663615, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.370718011710243, "steering_wheel_angle": -0.3278845238214161, "front_wheel_angle": -0.015123076662775257, "heading_rate": -0.013761070316163849, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141211.1318398} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24916785677526931, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.581611350283588, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3248653044005483, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.24720777083683684, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141211.1318398} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.69995069503784, "x": 27.978397885622606, "y": -0.19045138748540325, "z": null, "yaw": 3.0909255220867276, "pitch": null, "roll": null}, "v": 2.329265075663615, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.370718011710243, "steering_wheel_angle": -0.3278845238214161, "front_wheel_angle": -0.015123076662775257, "heading_rate": -0.013761070316163849, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141211.1518397} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24916785677526931, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.581611350283588, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3236060292932033, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.24720777083683684, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141211.1518397} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141211.1718397, "x": 31.72285614559708, "y": 4.822572047697693, "z": null, "yaw": 3.0903996304898347, "pitch": null, "roll": null}, "v": 2.322349182871168, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3700505164153822, "steering_wheel_angle": -0.24720777083683684, "front_wheel_angle": -0.011389827539450812, "heading_rate": -0.010332929905744841, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141211.1718397} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24984930665322086, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6290961758733254, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.322349182871168, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.24720777083683684, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141211.1718397} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.80995059013367, "x": 27.72285614559708, "y": -0.177427952302307, "z": null, "yaw": 3.0903996304898347, "pitch": null, "roll": null}, "v": 2.322349182871168, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3700505164153822, "steering_wheel_angle": -0.24720777083683684, "front_wheel_angle": -0.011389827539450812, "heading_rate": -0.010332929905744841, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141211.1918397} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24947394973946166, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6290961758733254, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.32117989998137, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2067524473162525, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141211.1918397} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.80995059013367, "x": 27.72285614559708, "y": -0.177427952302307, "z": null, "yaw": 3.0903996304898347, "pitch": null, "roll": null}, "v": 2.322349182871168, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3700505164153822, "steering_wheel_angle": -0.24720777083683684, "front_wheel_angle": -0.011389827539450812, "heading_rate": -0.010332929905744841, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141211.2118397} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24947394973946166, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6290961758733254, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.319965974074129, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2067524473162525, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141211.2118397} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.80995059013367, "x": 27.72285614559708, "y": -0.177427952302307, "z": null, "yaw": 3.0903996304898347, "pitch": null, "roll": null}, "v": 2.322349182871168, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3700505164153822, "steering_wheel_angle": -0.24720777083683684, "front_wheel_angle": -0.011389827539450812, "heading_rate": -0.010332929905744841, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141211.2318397} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24947394973946166, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6290961758733254, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.318754387618725, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2067524473162525, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141211.2318397} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.80995059013367, "x": 27.72285614559708, "y": -0.177427952302307, "z": null, "yaw": 3.0903996304898347, "pitch": null, "roll": null}, "v": 2.322349182871168, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3700505164153822, "steering_wheel_angle": -0.24720777083683684, "front_wheel_angle": -0.011389827539450812, "heading_rate": -0.010332929905744841, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141211.2518396} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24947394973946166, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6290961758733254, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3175451355197225, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2067524473162525, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141211.2518396} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.80995059013367, "x": 27.72285614559708, "y": -0.177427952302307, "z": null, "yaw": 3.0903996304898347, "pitch": null, "roll": null}, "v": 2.322349182871168, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3700505164153822, "steering_wheel_angle": -0.24720777083683684, "front_wheel_angle": -0.011389827539450812, "heading_rate": -0.010332929905744841, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141211.2718396} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24947394973946166, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6290961758733254, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.316338212694897, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2067524473162525, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141211.2718396} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141211.2818396, "x": 31.46806369964373, "y": 4.835676226363928, "z": null, "yaw": 3.0899832195375043, "pitch": null, "roll": null}, "v": 2.3157356231757067, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3694130959232351, "steering_wheel_angle": -0.2067524473162525, "front_wheel_angle": -0.009520800686933287, "heading_rate": -0.008612626371388122, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141211.2918396} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24346659331162174, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6585800562870109, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3151336140751906, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2067524473162525, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141211.2918396} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.91995048522949, "x": 27.46806369964373, "y": -0.1643237736360721, "z": null, "yaw": 3.0899832195375043, "pitch": null, "roll": null}, "v": 2.3157356231757067, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3694130959232351, "steering_wheel_angle": -0.2067524473162525, "front_wheel_angle": -0.009520800686933287, "heading_rate": -0.008612626371388122, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141211.3118396} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24627867526356828, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6585800562870109, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3131807765697316, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.1662212920421808, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141211.3118396} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.91995048522949, "x": 27.46806369964373, "y": -0.1643237736360721, "z": null, "yaw": 3.0899832195375043, "pitch": null, "roll": null}, "v": 2.3157356231757067, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3694130959232351, "steering_wheel_angle": -0.2067524473162525, "front_wheel_angle": -0.009520800686933287, "heading_rate": -0.008612626371388122, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141211.3318396} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24627867526356828, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6585800562870109, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.311583038466732, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.1662212920421808, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141211.3318396} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24627867526356828, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6585800562870109, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3107853225370993, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.1662212920421808, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141211.3418396} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.91995048522949, "x": 27.46806369964373, "y": -0.1643237736360721, "z": null, "yaw": 3.0899832195375043, "pitch": null, "roll": null}, "v": 2.3157356231757067, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3694130959232351, "steering_wheel_angle": -0.2067524473162525, "front_wheel_angle": -0.009520800686933287, "heading_rate": -0.008612626371388122, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141211.3718395} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24627867526356828, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6585800562870109, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3083967768365476, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.1662212920421808, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141211.3718395} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141211.3918395, "x": 31.21412303575522, "y": 4.8488348403608725, "z": null, "yaw": 3.0896398757174044, "pitch": null, "roll": null}, "v": 2.3068082394678715, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36855405451016215, "steering_wheel_angle": -0.1662212920421808, "front_wheel_angle": -0.007650277548456579, "heading_rate": -0.0068937763980463345, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141211.3918395} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24806430808666982, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7069166667516936, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3068082394678715, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.1662212920421808, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141211.3918395} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.02995038032532, "x": 27.21412303575522, "y": -0.15116515963912747, "z": null, "yaw": 3.0896398757174044, "pitch": null, "roll": null}, "v": 2.3068082394678715, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36855405451016215, "steering_wheel_angle": -0.1662212920421808, "front_wheel_angle": -0.007650277548456579, "heading_rate": -0.0068937763980463345, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141211.4118395} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24714855551054798, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7069166667516936, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.305445852030485, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.12559326671577062, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141211.4118395} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.02995038032532, "x": 27.21412303575522, "y": -0.15116515963912747, "z": null, "yaw": 3.0896398757174044, "pitch": null, "roll": null}, "v": 2.3068082394678715, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36855405451016215, "steering_wheel_angle": -0.1662212920421808, "front_wheel_angle": -0.007650277548456579, "heading_rate": -0.0068937763980463345, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141211.4218395} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24714855551054798, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7069166667516936, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3039716681991798, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.12559326671577062, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141211.4218395} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.02995038032532, "x": 27.21412303575522, "y": -0.15116515963912747, "z": null, "yaw": 3.0896398757174044, "pitch": null, "roll": null}, "v": 2.3068082394678715, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36855405451016215, "steering_wheel_angle": -0.1662212920421808, "front_wheel_angle": -0.007650277548456579, "heading_rate": -0.0068937763980463345, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141211.4518394} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24714855551054798, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7069166667516936, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.302500315999178, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.12559326671577062, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141211.4518394} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.02995038032532, "x": 27.21412303575522, "y": -0.15116515963912747, "z": null, "yaw": 3.0896398757174044, "pitch": null, "roll": null}, "v": 2.3068082394678715, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36855405451016215, "steering_wheel_angle": -0.1662212920421808, "front_wheel_angle": -0.007650277548456579, "heading_rate": -0.0068937763980463345, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141211.4718394} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24714855551054798, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7069166667516936, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3010317891259118, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.12559326671577062, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141211.4718394} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.02995038032532, "x": 27.21412303575522, "y": -0.15116515963912747, "z": null, "yaw": 3.0896398757174044, "pitch": null, "roll": null}, "v": 2.3068082394678715, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36855405451016215, "steering_wheel_angle": -0.1662212920421808, "front_wheel_angle": -0.007650277548456579, "heading_rate": -0.0068937763980463345, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141211.4918394} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24714855551054798, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7069166667516936, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.299566081291903, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.12559326671577062, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141211.4918394} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141211.5018394, "x": 30.961111856103575, "y": 4.86202160895656, "z": null, "yaw": 3.089384313196913, "pitch": null, "roll": null}, "v": 2.2988342825544437, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36778810471419826, "steering_wheel_angle": -0.12559326671577062, "front_wheel_angle": -0.005777293567149367, "heading_rate": -0.0051879641701102356, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141211.5118394} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2434963450275285, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7346979435734794, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2981031862267107, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.12559326671577062, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141211.5118394} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.13995027542114, "x": 26.961111856103575, "y": -0.13797839104343979, "z": null, "yaw": 3.089384313196913, "pitch": null, "roll": null}, "v": 2.2988342825544437, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36778810471419826, "steering_wheel_angle": -0.12559326671577062, "front_wheel_angle": -0.005777293567149367, "heading_rate": -0.0051879641701102356, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141211.5218394} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24517713563652124, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7346979435734794, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2971445283723635, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.12559326671577062, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141211.5218394} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.13995027542114, "x": 26.961111856103575, "y": -0.13797839104343979, "z": null, "yaw": 3.089384313196913, "pitch": null, "roll": null}, "v": 2.2988342825544437, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36778810471419826, "steering_wheel_angle": -0.12559326671577062, "front_wheel_angle": -0.005777293567149367, "heading_rate": -0.0051879641701102356, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141211.5518394} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24517713563652124, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7346979435734794, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.294588915750519, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.12559326671577062, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141211.5518394} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.13995027542114, "x": 26.961111856103575, "y": -0.13797839104343979, "z": null, "yaw": 3.089384313196913, "pitch": null, "roll": null}, "v": 2.2988342825544437, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36778810471419826, "steering_wheel_angle": -0.12559326671577062, "front_wheel_angle": -0.005777293567149367, "heading_rate": -0.0051879641701102356, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141211.5718393} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24517713563652124, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7346979435734794, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2928892563662626, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.12559326671577062, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141211.5718393} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.13995027542114, "x": 26.961111856103575, "y": -0.13797839104343979, "z": null, "yaw": 3.089384313196913, "pitch": null, "roll": null}, "v": 2.2988342825544437, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36778810471419826, "steering_wheel_angle": -0.12559326671577062, "front_wheel_angle": -0.005777293567149367, "heading_rate": -0.0051879641701102356, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141211.5918393} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24517713563652124, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7346979435734794, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.291192854220664, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.12559326671577062, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141211.5918393} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141211.6118393, "x": 30.7090511580965, "y": 4.875221748110235, "z": null, "yaw": 3.0891360673520314, "pitch": null, "roll": null}, "v": 2.289499701920968, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3668930739470105, "steering_wheel_angle": -0.12559326671577062, "front_wheel_angle": -0.005777293567149367, "heading_rate": -0.005166898071419701, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141211.6118393} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24725362773746434, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7858435004667172, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.289499701920968, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.12559326671577062, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141211.6118393} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.24995017051697, "x": 26.7090511580965, "y": -0.1247782518897651, "z": null, "yaw": 3.0891360673520314, "pitch": null, "roll": null}, "v": 2.289499701920968, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3668930739470105, "steering_wheel_angle": -0.12559326671577062, "front_wheel_angle": -0.005777293567149367, "heading_rate": -0.005166898071419701, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141211.6318393} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24619662862673608, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7858435004667172, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.288069229311093, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.04403078488017093, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141211.6318393} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.24995017051697, "x": 26.7090511580965, "y": -0.1247782518897651, "z": null, "yaw": 3.0891360673520314, "pitch": null, "roll": null}, "v": 2.289499701920968, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3668930739470105, "steering_wheel_angle": -0.12559326671577062, "front_wheel_angle": -0.005777293567149367, "heading_rate": -0.005166898071419701, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141211.6518393} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24619662862673608, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7858435004667172, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2865094336383187, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.04403078488017093, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141211.6518393} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.24995017051697, "x": 26.7090511580965, "y": -0.1247782518897651, "z": null, "yaw": 3.0891360673520314, "pitch": null, "roll": null}, "v": 2.289499701920968, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3668930739470105, "steering_wheel_angle": -0.12559326671577062, "front_wheel_angle": -0.005777293567149367, "heading_rate": -0.005166898071419701, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141211.6718392} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24619662862673608, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7858435004667172, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2849526231699664, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.04403078488017093, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141211.6718392} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.24995017051697, "x": 26.7090511580965, "y": -0.1247782518897651, "z": null, "yaw": 3.0891360673520314, "pitch": null, "roll": null}, "v": 2.289499701920968, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3668930739470105, "steering_wheel_angle": -0.12559326671577062, "front_wheel_angle": -0.005777293567149367, "heading_rate": -0.005166898071419701, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141211.6918392} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24619662862673608, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7858435004667172, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2833987912238225, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.04403078488017093, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141211.6918392} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.24995017051697, "x": 26.7090511580965, "y": -0.1247782518897651, "z": null, "yaw": 3.0891360673520314, "pitch": null, "roll": null}, "v": 2.289499701920968, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3668930739470105, "steering_wheel_angle": -0.12559326671577062, "front_wheel_angle": -0.005777293567149367, "heading_rate": -0.005166898071419701, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141211.7118392} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24619662862673608, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7858435004667172, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2818479311360202, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.04403078488017093, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141211.7118392} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141211.7218392, "x": 30.45796898446322, "y": 4.888419564340593, "z": null, "yaw": 3.0890271341556095, "pitch": null, "roll": null}, "v": 2.2810736134615404, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36608664897338195, "steering_wheel_angle": -0.04403078488017093, "front_wheel_angle": -0.0020232472665460363, "heading_rate": -0.0018028055666756391, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141211.7318392} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24647714673996887, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.82947784486128, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2803000362609773, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.04403078488017093, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141211.7318392} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.35995006561279, "x": 26.45796898446322, "y": -0.11158043565940723, "z": null, "yaw": 3.0890271341556095, "pitch": null, "roll": null}, "v": 2.2810736134615404, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36608664897338195, "steering_wheel_angle": -0.04403078488017093, "front_wheel_angle": -0.0020232472665460363, "heading_rate": -0.0018028055666756391, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141211.7518392} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24628212468587382, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.82947784486128, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2787901479761583, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.0031350321006435432, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141211.7518392} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.35995006561279, "x": 26.45796898446322, "y": -0.11158043565940723, "z": null, "yaw": 3.0890271341556095, "pitch": null, "roll": null}, "v": 2.2810736134615404, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36608664897338195, "steering_wheel_angle": -0.04403078488017093, "front_wheel_angle": -0.0020232472665460363, "heading_rate": -0.0018028055666756391, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141211.7718391} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24628212468587382, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.82947784486128, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2772587786066714, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.0031350321006435432, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141211.7718391} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.35995006561279, "x": 26.45796898446322, "y": -0.11158043565940723, "z": null, "yaw": 3.0890271341556095, "pitch": null, "roll": null}, "v": 2.2810736134615404, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36608664897338195, "steering_wheel_angle": -0.04403078488017093, "front_wheel_angle": -0.0020232472665460363, "heading_rate": -0.0018028055666756391, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141211.7918391} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24628212468587382, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.82947784486128, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.275730334372718, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.0031350321006435432, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141211.7918391} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.35995006561279, "x": 26.45796898446322, "y": -0.11158043565940723, "z": null, "yaw": 3.0890271341556095, "pitch": null, "roll": null}, "v": 2.2810736134615404, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36608664897338195, "steering_wheel_angle": -0.04403078488017093, "front_wheel_angle": -0.0020232472665460363, "heading_rate": -0.0018028055666756391, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141211.811839} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24628212468587382, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.82947784486128, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2742048087528586, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.0031350321006435432, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141211.811839} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141211.831839, "x": 30.207816877979532, "y": 4.901584949107999, "z": null, "yaw": 3.089006265723749, "pitch": null, "roll": null}, "v": 2.2726821952434566, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.365284953367939, "steering_wheel_angle": -0.0031350321006435432, "front_wheel_angle": -0.00014397983251503914, "heading_rate": -0.00012782047034850714, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141211.831839} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24271221000433707, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8351705030016394, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2726821952434566, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.0031350321006435432, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141211.831839} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.46994996070862, "x": 26.207816877979532, "y": -0.09841505089200098, "z": null, "yaw": 3.089006265723749, "pitch": null, "roll": null}, "v": 2.2726821952434566, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.365284953367939, "steering_wheel_angle": -0.0031350321006435432, "front_wheel_angle": -0.00014397983251503914, "heading_rate": -0.00012782047034850714, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141211.851839} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2443510886252504, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8351705030016394, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2707164609603785, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.0031350321006435432, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141211.851839} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.46994996070862, "x": 26.207816877979532, "y": -0.09841505089200098, "z": null, "yaw": 3.089006265723749, "pitch": null, "roll": null}, "v": 2.2726821952434566, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.365284953367939, "steering_wheel_angle": -0.0031350321006435432, "front_wheel_angle": -0.00014397983251503914, "heading_rate": -0.00012782047034850714, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141211.871839} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2443510886252504, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8351705030016394, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2689592385721604, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.0031350321006435432, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141211.871839} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.46994996070862, "x": 26.207816877979532, "y": -0.09841505089200098, "z": null, "yaw": 3.089006265723749, "pitch": null, "roll": null}, "v": 2.2726821952434566, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.365284953367939, "steering_wheel_angle": -0.0031350321006435432, "front_wheel_angle": -0.00014397983251503914, "heading_rate": -0.00012782047034850714, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141211.891839} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2443510886252504, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8351705030016394, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2672053669427763, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.0031350321006435432, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141211.891839} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.46994996070862, "x": 26.207816877979532, "y": -0.09841505089200098, "z": null, "yaw": 3.089006265723749, "pitch": null, "roll": null}, "v": 2.2726821952434566, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.365284953367939, "steering_wheel_angle": -0.0031350321006435432, "front_wheel_angle": -0.00014397983251503914, "heading_rate": -0.00012782047034850714, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141211.901839} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2443510886252504, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8351705030016394, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.265454838452993, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.0031350321006435432, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141211.901839} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.46994996070862, "x": 26.207816877979532, "y": -0.09841505089200098, "z": null, "yaw": 3.089006265723749, "pitch": null, "roll": null}, "v": 2.2726821952434566, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.365284953367939, "steering_wheel_angle": -0.0031350321006435432, "front_wheel_angle": -0.00014397983251503914, "heading_rate": -0.00012782047034850714, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141211.931839} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2443510886252504, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8351705030016394, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2637076455051335, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.0031350321006435432, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141211.931839} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141211.941839, "x": 29.958669255423356, "y": 4.914699514917795, "z": null, "yaw": 3.0890000790902774, "pitch": null, "roll": null}, "v": 2.2628352974910273, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3643460007102644, "steering_wheel_angle": -0.0031350321006435432, "front_wheel_angle": -0.00014397983251503914, "heading_rate": -0.00012726665991921645, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141211.951839} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24753096590046078, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8901107999491452, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.261963780523003, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.0031350321006435432, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141211.951839} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.57994985580444, "x": 25.958669255423356, "y": -0.08530048508220478, "z": null, "yaw": 3.0890000790902774, "pitch": null, "roll": null}, "v": 2.2628352974910273, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3643460007102644, "steering_wheel_angle": -0.0031350321006435432, "front_wheel_angle": -0.00014397983251503914, "heading_rate": -0.00012726665991921645, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141211.971839} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2459451985842825, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8901107999491452, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2606205313611154, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.03783531687164892, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141211.971839} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.57994985580444, "x": 25.958669255423356, "y": -0.08530048508220478, "z": null, "yaw": 3.0890000790902774, "pitch": null, "roll": null}, "v": 2.2628352974910273, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3643460007102644, "steering_wheel_angle": -0.0031350321006435432, "front_wheel_angle": -0.00014397983251503914, "heading_rate": -0.00012726665991921645, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141211.991839} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2459451985842825, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8901107999491452, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2590817124783364, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.03783531687164892, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141211.991839} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.57994985580444, "x": 25.958669255423356, "y": -0.08530048508220478, "z": null, "yaw": 3.0890000790902774, "pitch": null, "roll": null}, "v": 2.2628352974910273, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3643460007102644, "steering_wheel_angle": -0.0031350321006435432, "front_wheel_angle": -0.00014397983251503914, "heading_rate": -0.00012726665991921645, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141212.011839} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2459451985842825, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8901107999491452, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2575458217840634, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.03783531687164892, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141212.011839} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.57994985580444, "x": 25.958669255423356, "y": -0.08530048508220478, "z": null, "yaw": 3.0890000790902774, "pitch": null, "roll": null}, "v": 2.2628352974910273, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3643460007102644, "steering_wheel_angle": -0.0031350321006435432, "front_wheel_angle": -0.00014397983251503914, "heading_rate": -0.00012726665991921645, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141212.031839} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2459451985842825, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8901107999491452, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.256012852763167, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.03783531687164892, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141212.031839} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141212.0518389, "x": 29.710517141260162, "y": 4.92775723605247, "z": null, "yaw": 3.0890600706233684, "pitch": null, "roll": null}, "v": 2.254482798918295, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3635510668520994, "steering_wheel_angle": 0.03783531687164892, "front_wheel_angle": 0.0017384195975182698, "heading_rate": 0.001530953526572068, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141212.0518389} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24199659333660836, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8867447773137775, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.254482798918295, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.03783531687164892, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141212.0518389} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.68994975090027, "x": 25.710517141260162, "y": -0.07224276394753026, "z": null, "yaw": 3.0890600706233684, "pitch": null, "roll": null}, "v": 2.254482798918295, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3635510668520994, "steering_wheel_angle": 0.03783531687164892, "front_wheel_angle": 0.0017384195975182698, "heading_rate": 0.001530953526572068, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141212.0718389} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.243816316069624, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8867447773137775, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2524623127397527, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.03783531687164892, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141212.0718389} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.68994975090027, "x": 25.710517141260162, "y": -0.07224276394753026, "z": null, "yaw": 3.0890600706233684, "pitch": null, "roll": null}, "v": 2.254482798918295, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3635510668520994, "steering_wheel_angle": 0.03783531687164892, "front_wheel_angle": 0.0017384195975182698, "heading_rate": 0.001530953526572068, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141212.0918388} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.243816316069624, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8867447773137775, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2506730233188734, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.03783531687164892, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141212.0918388} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.68994975090027, "x": 25.710517141260162, "y": -0.07224276394753026, "z": null, "yaw": 3.0890600706233684, "pitch": null, "roll": null}, "v": 2.254482798918295, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3635510668520994, "steering_wheel_angle": 0.03783531687164892, "front_wheel_angle": 0.0017384195975182698, "heading_rate": 0.001530953526572068, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141212.1118388} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.243816316069624, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8867447773137775, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.248887132734299, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.03783531687164892, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141212.1118388} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.68994975090027, "x": 25.710517141260162, "y": -0.07224276394753026, "z": null, "yaw": 3.0890600706233684, "pitch": null, "roll": null}, "v": 2.254482798918295, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3635510668520994, "steering_wheel_angle": 0.03783531687164892, "front_wheel_angle": 0.0017384195975182698, "heading_rate": 0.001530953526572068, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141212.1318388} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.243816316069624, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8867447773137775, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.24710463325463, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.03783531687164892, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141212.1318388} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.68994975090027, "x": 25.710517141260162, "y": -0.07224276394753026, "z": null, "yaw": 3.0890600706233684, "pitch": null, "roll": null}, "v": 2.254482798918295, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3635510668520994, "steering_wheel_angle": 0.03783531687164892, "front_wheel_angle": 0.0017384195975182698, "heading_rate": 0.001530953526572068, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141212.1518388} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.243816316069624, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8867447773137775, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.24532551717041, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.03783531687164892, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141212.1518388} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141212.1618388, "x": 29.463378458408314, "y": 4.940743617769425, "z": null, "yaw": 3.0891347684156956, "pitch": null, "roll": null}, "v": 2.2444372254983707, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36259684586694674, "steering_wheel_angle": 0.03783531687164892, "front_wheel_angle": 0.0017384195975182698, "heading_rate": 0.0015241318705980012, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141212.1718388} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24709971091441954, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9429519242436675, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.243549776794053, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.03783531687164892, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141212.1718388} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.799949645996094, "x": 25.463378458408314, "y": -0.05925638223057472, "z": null, "yaw": 3.0891347684156956, "pitch": null, "roll": null}, "v": 2.2444372254983707, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36259684586694674, "steering_wheel_angle": 0.03783531687164892, "front_wheel_angle": 0.0017384195975182698, "heading_rate": 0.0015241318705980012, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141212.1918387} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24546348619113953, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9429519242436675, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.242187634160702, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.11976353617534473, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141212.1918387} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.799949645996094, "x": 25.463378458408314, "y": -0.05925638223057472, "z": null, "yaw": 3.0891347684156956, "pitch": null, "roll": null}, "v": 2.2444372254983707, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36259684586694674, "steering_wheel_angle": 0.03783531687164892, "front_wheel_angle": 0.0017384195975182698, "heading_rate": 0.0015241318705980012, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141212.2118387} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24546348619113953, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9429519242436675, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2406236431875866, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.11976353617534473, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141212.2118387} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.799949645996094, "x": 25.463378458408314, "y": -0.05925638223057472, "z": null, "yaw": 3.0891347684156956, "pitch": null, "roll": null}, "v": 2.2444372254983707, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36259684586694674, "steering_wheel_angle": 0.03783531687164892, "front_wheel_angle": 0.0017384195975182698, "heading_rate": 0.0015241318705980012, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141212.2318387} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24546348619113953, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9429519242436675, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2390626167700605, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.11976353617534473, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141212.2318387} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.799949645996094, "x": 25.463378458408314, "y": -0.05925638223057472, "z": null, "yaw": 3.0891347684156956, "pitch": null, "roll": null}, "v": 2.2444372254983707, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36259684586694674, "steering_wheel_angle": 0.03783531687164892, "front_wheel_angle": 0.0017384195975182698, "heading_rate": 0.0015241318705980012, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141212.2518387} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24546348619113953, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9429519242436675, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.237504548314529, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.11976353617534473, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141212.2518387} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141212.2718387, "x": 29.217251588032983, "y": 4.953647830930132, "z": null, "yaw": 3.0893346531438954, "pitch": null, "roll": null}, "v": 2.2359494312454293, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3617921701531391, "steering_wheel_angle": 0.11976353617534473, "front_wheel_angle": 0.005508703091947813, "heading_rate": 0.00481144771033944, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141212.2718387} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24024794022626214, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9171638631536669, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2359494312454293, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.11976353617534473, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141212.2718387} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.90994954109192, "x": 25.217251588032983, "y": -0.046352169069868054, "z": null, "yaw": 3.0893346531438954, "pitch": null, "roll": null}, "v": 2.2359494312454293, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3617921701531391, "steering_wheel_angle": 0.11976353617534473, "front_wheel_angle": 0.005508703091947813, "heading_rate": 0.00481144771033944, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141212.2918386} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24267022612709413, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9171638631536669, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2337456244553398, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.11976353617534473, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141212.2918386} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.90994954109192, "x": 25.217251588032983, "y": -0.046352169069868054, "z": null, "yaw": 3.0893346531438954, "pitch": null, "roll": null}, "v": 2.2359494312454293, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3617921701531391, "steering_wheel_angle": 0.11976353617534473, "front_wheel_angle": 0.005508703091947813, "heading_rate": 0.00481144771033944, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141212.3118386} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24267022612709413, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9171638631536669, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2318486315172126, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.11976353617534473, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141212.3118386} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.90994954109192, "x": 25.217251588032983, "y": -0.046352169069868054, "z": null, "yaw": 3.0893346531438954, "pitch": null, "roll": null}, "v": 2.2359494312454293, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3617921701531391, "steering_wheel_angle": 0.11976353617534473, "front_wheel_angle": 0.005508703091947813, "heading_rate": 0.00481144771033944, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141212.3318386} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24267022612709413, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9171638631536669, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2299552277531713, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.11976353617534473, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141212.3318386} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.90994954109192, "x": 25.217251588032983, "y": -0.046352169069868054, "z": null, "yaw": 3.0893346531438954, "pitch": null, "roll": null}, "v": 2.2359494312454293, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3617921701531391, "steering_wheel_angle": 0.11976353617534473, "front_wheel_angle": 0.005508703091947813, "heading_rate": 0.00481144771033944, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141212.3518386} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24267022612709413, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9171638631536669, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.228065404939066, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.11976353617534473, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141212.3518386} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.90994954109192, "x": 25.217251588032983, "y": -0.046352169069868054, "z": null, "yaw": 3.0893346531438954, "pitch": null, "roll": null}, "v": 2.2359494312454293, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3617921701531391, "steering_wheel_angle": 0.11976353617534473, "front_wheel_angle": 0.005508703091947813, "heading_rate": 0.00481144771033944, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141212.3718386} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24267022612709413, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9171638631536669, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.226179154874432, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.11976353617534473, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141212.3718386} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141212.3818386, "x": 28.97218101933978, "y": 4.966439982722127, "z": null, "yaw": 3.0895713576242145, "pitch": null, "roll": null}, "v": 2.2252373670669785, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36077868175126077, "steering_wheel_angle": 0.11976353617534473, "front_wheel_angle": 0.005508703091947813, "heading_rate": 0.004788396859571448, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141212.3918386} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24632826456458398, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.968322796956683, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.224296469382409, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.11976353617534473, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141212.3918386} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.019949436187744, "x": 24.97218101933978, "y": -0.033560017277872944, "z": null, "yaw": 3.0895713576242145, "pitch": null, "roll": null}, "v": 2.2252373670669785, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36077868175126077, "steering_wheel_angle": 0.11976353617534473, "front_wheel_angle": 0.005508703091947813, "heading_rate": 0.004788396859571448, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141212.4118385} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24450912242641903, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.968322796956683, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2228743791313694, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.11976353617534473, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141212.4118385} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.019949436187744, "x": 24.97218101933978, "y": -0.033560017277872944, "z": null, "yaw": 3.0895713576242145, "pitch": null, "roll": null}, "v": 2.2252373670669785, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36077868175126077, "steering_wheel_angle": 0.11976353617534473, "front_wheel_angle": 0.005508703091947813, "heading_rate": 0.004788396859571448, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141212.4318385} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24450912242641903, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.968322796956683, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.221227688965131, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.11976353617534473, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141212.4318385} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.019949436187744, "x": 24.97218101933978, "y": -0.033560017277872944, "z": null, "yaw": 3.0895713576242145, "pitch": null, "roll": null}, "v": 2.2252373670669785, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36077868175126077, "steering_wheel_angle": 0.11976353617534473, "front_wheel_angle": 0.005508703091947813, "heading_rate": 0.004788396859571448, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141212.4518385} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24450912242641903, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.968322796956683, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.219584107361418, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.11976353617534473, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141212.4518385} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.019949436187744, "x": 24.97218101933978, "y": -0.033560017277872944, "z": null, "yaw": 3.0895713576242145, "pitch": null, "roll": null}, "v": 2.2252373670669785, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36077868175126077, "steering_wheel_angle": 0.11976353617534473, "front_wheel_angle": 0.005508703091947813, "heading_rate": 0.004788396859571448, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141212.4718385} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24450912242641903, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.968322796956683, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2179436273719637, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.11976353617534473, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141212.4718385} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141212.4918385, "x": 28.72817925775384, "y": 4.979118428452594, "z": null, "yaw": 3.0898080621045336, "pitch": null, "roll": null}, "v": 2.216306242067727, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35993544568967006, "steering_wheel_angle": 0.11976353617534473, "front_wheel_angle": 0.005508703091947813, "heading_rate": 0.004769178338647892, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141212.4918385} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23946640772691247, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9322074135373882, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.216306242067727, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.11976353617534473, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141212.4918385} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.12994933128357, "x": 24.72817925775384, "y": -0.020881571547405997, "z": null, "yaw": 3.0898080621045336, "pitch": null, "roll": null}, "v": 2.216306242067727, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35993544568967006, "steering_wheel_angle": 0.11976353617534473, "front_wheel_angle": 0.005508703091947813, "heading_rate": 0.004769178338647892, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141212.5018384} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24180345505134687, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9322074135373882, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2130573992621856, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.11976353617534473, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141212.5018384} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.12994933128357, "x": 24.72817925775384, "y": -0.020881571547405997, "z": null, "yaw": 3.0898080621045336, "pitch": null, "roll": null}, "v": 2.216306242067727, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35993544568967006, "steering_wheel_angle": 0.11976353617534473, "front_wheel_angle": 0.005508703091947813, "heading_rate": 0.004769178338647892, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141212.5218384} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24180345505134687, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9322074135373882, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.211091176166261, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.11976353617534473, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141212.5218384} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.12994933128357, "x": 24.72817925775384, "y": -0.020881571547405997, "z": null, "yaw": 3.0898080621045336, "pitch": null, "roll": null}, "v": 2.216306242067727, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35993544568967006, "steering_wheel_angle": 0.11976353617534473, "front_wheel_angle": 0.005508703091947813, "heading_rate": 0.004769178338647892, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141212.5518384} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24180345505134687, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9322074135373882, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2091286569337036, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.11976353617534473, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141212.5518384} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.12994933128357, "x": 24.72817925775384, "y": -0.020881571547405997, "z": null, "yaw": 3.0898080621045336, "pitch": null, "roll": null}, "v": 2.216306242067727, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35993544568967006, "steering_wheel_angle": 0.11976353617534473, "front_wheel_angle": 0.005508703091947813, "heading_rate": 0.004769178338647892, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141212.5618384} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24180345505134687, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9322074135373882, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2091286569337036, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.11976353617534473, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141212.5618384} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.12994933128357, "x": 24.72817925775384, "y": -0.020881571547405997, "z": null, "yaw": 3.0898080621045336, "pitch": null, "roll": null}, "v": 2.216306242067727, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35993544568967006, "steering_wheel_angle": 0.11976353617534473, "front_wheel_angle": 0.005508703091947813, "heading_rate": 0.004769178338647892, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141212.5918384} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24180345505134687, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9322074135373882, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2061918042045057, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.11976353617534473, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141212.5918384} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141212.6018384, "x": 28.485279028694254, "y": 4.991681992643615, "z": null, "yaw": 3.0900447665848527, "pitch": null, "roll": null}, "v": 2.205214696015419, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35889045335599473, "steering_wheel_angle": 0.11976353617534473, "front_wheel_angle": 0.005508703091947813, "heading_rate": 0.004745310896427708, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141212.6118383} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2456247005626257, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.98264623760516, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.204238507422568, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.11976353617534473, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141212.6118383} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.239949226379395, "x": 24.485279028694254, "y": -0.008318007356384882, "z": null, "yaw": 3.0900447665848527, "pitch": null, "roll": null}, "v": 2.205214696015419, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35889045335599473, "steering_wheel_angle": 0.11976353617534473, "front_wheel_angle": 0.005508703091947813, "heading_rate": 0.004745310896427708, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141212.6318383} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24372544043068758, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.98264623760516, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2027663158316773, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.16070626938849697, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141212.6318383} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.239949226379395, "x": 24.485279028694254, "y": -0.008318007356384882, "z": null, "yaw": 3.0900447665848527, "pitch": null, "roll": null}, "v": 2.205214696015419, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35889045335599473, "steering_wheel_angle": 0.11976353617534473, "front_wheel_angle": 0.005508703091947813, "heading_rate": 0.004745310896427708, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141212.6518383} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24372544043068758, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.98264623760516, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2010595966161235, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.16070626938849697, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141212.6518383} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.239949226379395, "x": 24.485279028694254, "y": -0.008318007356384882, "z": null, "yaw": 3.0900447665848527, "pitch": null, "roll": null}, "v": 2.205214696015419, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35889045335599473, "steering_wheel_angle": 0.11976353617534473, "front_wheel_angle": 0.005508703091947813, "heading_rate": 0.004745310896427708, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141212.6718383} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24372544043068758, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.98264623760516, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1993560855384833, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.16070626938849697, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141212.6718383} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.239949226379395, "x": 24.485279028694254, "y": -0.008318007356384882, "z": null, "yaw": 3.0900447665848527, "pitch": null, "roll": null}, "v": 2.205214696015419, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35889045335599473, "steering_wheel_angle": 0.11976353617534473, "front_wheel_angle": 0.005508703091947813, "heading_rate": 0.004745310896427708, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141212.6918383} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24372544043068758, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.98264623760516, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1976557754081516, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.16070626938849697, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141212.6918383} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141212.7118382, "x": 28.243486733264056, "y": 5.00412501815469, "z": null, "yaw": 3.09034782106246, "pitch": null, "roll": null}, "v": 2.195958659054575, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35802027727549646, "steering_wheel_angle": 0.16070626938849697, "front_wheel_angle": 0.0073959127725205295, "heading_rate": 0.006344302667215424, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141212.7118382} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2513793329895614, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0924299328211702, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1955896645936677, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.20172941261930688, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141212.7118382} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.34994912147522, "x": 24.243486733264056, "y": 0.004125018154690352, "z": null, "yaw": 3.09034782106246, "pitch": null, "roll": null}, "v": 2.195958659054575, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35802027727549646, "steering_wheel_angle": 0.16070626938849697, "front_wheel_angle": 0.0073959127725205295, "heading_rate": 0.006344302667215424, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141212.7318382} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2476683212634853, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0924299328211702, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1952210166756916, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2427080448943079, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141212.7318382} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.34994912147522, "x": 24.243486733264056, "y": 0.004125018154690352, "z": null, "yaw": 3.09034782106246, "pitch": null, "roll": null}, "v": 2.195958659054575, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35802027727549646, "steering_wheel_angle": 0.16070626938849697, "front_wheel_angle": 0.0073959127725205295, "heading_rate": 0.006344302667215424, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141212.7518382} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2476683212634853, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0924299328211702, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.193421987040263, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2427080448943079, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141212.7518382} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.34994912147522, "x": 24.243486733264056, "y": 0.004125018154690352, "z": null, "yaw": 3.09034782106246, "pitch": null, "roll": null}, "v": 2.195958659054575, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35802027727549646, "steering_wheel_angle": 0.16070626938849697, "front_wheel_angle": 0.0073959127725205295, "heading_rate": 0.006344302667215424, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141212.7718382} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2476683212634853, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0924299328211702, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1928234361243875, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2427080448943079, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141212.7718382} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.34994912147522, "x": 24.243486733264056, "y": 0.004125018154690352, "z": null, "yaw": 3.09034782106246, "pitch": null, "roll": null}, "v": 2.195958659054575, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35802027727549646, "steering_wheel_angle": 0.16070626938849697, "front_wheel_angle": 0.0073959127725205295, "heading_rate": 0.006344302667215424, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141212.7918382} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2476683212634853, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0924299328211702, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1916280191374904, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2427080448943079, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141212.7918382} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.34994912147522, "x": 24.243486733264056, "y": 0.004125018154690352, "z": null, "yaw": 3.09034782106246, "pitch": null, "roll": null}, "v": 2.195958659054575, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35802027727549646, "steering_wheel_angle": 0.16070626938849697, "front_wheel_angle": 0.0073959127725205295, "heading_rate": 0.006344302667215424, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141212.8118382} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2476683212634853, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0924299328211702, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1904348446216493, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2427080448943079, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141212.8118382} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141212.8218381, "x": 28.002531244174328, "y": 5.016435534714611, "z": null, "yaw": 3.0908061256151558, "pitch": null, "roll": null}, "v": 2.189839096797453, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3574459075384995, "steering_wheel_angle": 0.2427080448943079, "front_wheel_angle": 0.011181842082397895, "heading_rate": 0.00956541232796978, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141212.8318381} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24596664415189554, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0882843236102482, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1892439078010355, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2427080448943079, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141212.8318381} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.459949016571045, "x": 24.002531244174328, "y": 0.01643553471461079, "z": null, "yaw": 3.0908061256151558, "pitch": null, "roll": null}, "v": 2.189839096797453, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3574459075384995, "steering_wheel_angle": 0.2427080448943079, "front_wheel_angle": 0.011181842082397895, "heading_rate": 0.00956541232796978, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141212.851838} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24673320546514557, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0882843236102482, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1878425940039894, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2427080448943079, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141212.851838} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.459949016571045, "x": 24.002531244174328, "y": 0.01643553471461079, "z": null, "yaw": 3.0908061256151558, "pitch": null, "roll": null}, "v": 2.189839096797453, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3574459075384995, "steering_wheel_angle": 0.2427080448943079, "front_wheel_angle": 0.011181842082397895, "heading_rate": 0.00956541232796978, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141212.871838} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24673320546514557, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0882843236102482, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1865396820784646, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2427080448943079, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141212.871838} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.459949016571045, "x": 24.002531244174328, "y": 0.01643553471461079, "z": null, "yaw": 3.0908061256151558, "pitch": null, "roll": null}, "v": 2.189839096797453, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3574459075384995, "steering_wheel_angle": 0.2427080448943079, "front_wheel_angle": 0.011181842082397895, "heading_rate": 0.00956541232796978, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141212.891838} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24673320546514557, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0882843236102482, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.185239211637326, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2427080448943079, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141212.891838} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.459949016571045, "x": 24.002531244174328, "y": 0.01643553471461079, "z": null, "yaw": 3.0908061256151558, "pitch": null, "roll": null}, "v": 2.189839096797453, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3574459075384995, "steering_wheel_angle": 0.2427080448943079, "front_wheel_angle": 0.011181842082397895, "heading_rate": 0.00956541232796978, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141212.911838} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24673320546514557, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0882843236102482, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1839411774293827, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2427080448943079, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141212.911838} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141212.931838, "x": 27.76231719025209, "y": 5.028593104879707, "z": null, "yaw": 3.0912866154180882, "pitch": null, "roll": null}, "v": 2.182645574217082, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35677169573734824, "steering_wheel_angle": 0.2427080448943079, "front_wheel_angle": 0.011181842082397895, "heading_rate": 0.009533990380269404, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141212.931838} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2472241353391128, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1154490657679281, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.182645574217082, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2427080448943079, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141212.931838} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.56994891166687, "x": 23.76231719025209, "y": 0.028593104879706566, "z": null, "yaw": 3.0912866154180882, "pitch": null, "roll": null}, "v": 2.182645574217082, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35677169573734824, "steering_wheel_angle": 0.2427080448943079, "front_wheel_angle": 0.011181842082397895, "heading_rate": 0.009533990380269404, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141212.951838} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24693899054802698, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1154490657679281, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.181413734278953, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2836683904336487, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141212.951838} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.56994891166687, "x": 23.76231719025209, "y": 0.028593104879706566, "z": null, "yaw": 3.0912866154180882, "pitch": null, "roll": null}, "v": 2.182645574217082, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35677169573734824, "steering_wheel_angle": 0.2427080448943079, "front_wheel_angle": 0.011181842082397895, "heading_rate": 0.009533990380269404, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141212.971838} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24693899054802698, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1154490657679281, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1801485736984945, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2836683904336487, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141212.971838} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.56994891166687, "x": 23.76231719025209, "y": 0.028593104879706566, "z": null, "yaw": 3.0912866154180882, "pitch": null, "roll": null}, "v": 2.182645574217082, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35677169573734824, "steering_wheel_angle": 0.2427080448943079, "front_wheel_angle": 0.011181842082397895, "heading_rate": 0.009533990380269404, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141212.991838} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24693899054802698, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1154490657679281, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1788857806253463, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2836683904336487, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141212.991838} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.56994891166687, "x": 23.76231719025209, "y": 0.028593104879706566, "z": null, "yaw": 3.0912866154180882, "pitch": null, "roll": null}, "v": 2.182645574217082, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35677169573734824, "steering_wheel_angle": 0.2427080448943079, "front_wheel_angle": 0.011181842082397895, "heading_rate": 0.009533990380269404, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141213.011838} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24693899054802698, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1154490657679281, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1776253499916085, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2836683904336487, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141213.011838} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.56994891166687, "x": 23.76231719025209, "y": 0.028593104879706566, "z": null, "yaw": 3.0912866154180882, "pitch": null, "roll": null}, "v": 2.182645574217082, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35677169573734824, "steering_wheel_angle": 0.2427080448943079, "front_wheel_angle": 0.011181842082397895, "heading_rate": 0.009533990380269404, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141213.031838} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24693899054802698, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1154490657679281, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1763672767424405, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2836683904336487, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141213.031838} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141213.041838, "x": 27.522870856835254, "y": 5.0405892127233995, "z": null, "yaw": 3.091841107458554, "pitch": null, "roll": null}, "v": 2.1757391225609934, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3561253634224745, "steering_wheel_angle": 0.2836683904336487, "front_wheel_angle": 0.013076020114877141, "heading_rate": 0.011113918017534738, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141213.051838} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24766501712172623, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1398352893962005, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1751115558360206, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2836683904336487, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141213.051838} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.679948806762695, "x": 23.522870856835254, "y": 0.04058921272339955, "z": null, "yaw": 3.091841107458554, "pitch": null, "roll": null}, "v": 2.1757391225609934, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3561253634224745, "steering_wheel_angle": 0.2836683904336487, "front_wheel_angle": 0.013076020114877141, "heading_rate": 0.011113918017534738, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141213.071838} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2472700456177164, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1398352893962005, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1739488931425095, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3246119743543146, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141213.071838} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.679948806762695, "x": 23.522870856835254, "y": 0.04058921272339955, "z": null, "yaw": 3.091841107458554, "pitch": null, "roll": null}, "v": 2.1757391225609934, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3561253634224745, "steering_wheel_angle": 0.2836683904336487, "front_wheel_angle": 0.013076020114877141, "heading_rate": 0.011113918017534738, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141213.091838} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2472700456177164, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1398352893962005, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.172739054893575, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3246119743543146, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141213.091838} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.679948806762695, "x": 23.522870856835254, "y": 0.04058921272339955, "z": null, "yaw": 3.091841107458554, "pitch": null, "roll": null}, "v": 2.1757391225609934, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3561253634224745, "steering_wheel_angle": 0.2836683904336487, "front_wheel_angle": 0.013076020114877141, "heading_rate": 0.011113918017534738, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141213.1118379} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2472700456177164, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1398352893962005, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1709285342546814, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3246119743543146, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141213.1118379} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.679948806762695, "x": 23.522870856835254, "y": 0.04058921272339955, "z": null, "yaw": 3.091841107458554, "pitch": null, "roll": null}, "v": 2.1757391225609934, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3561253634224745, "steering_wheel_angle": 0.2836683904336487, "front_wheel_angle": 0.013076020114877141, "heading_rate": 0.011113918017534738, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141213.1218379} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2472700456177164, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1398352893962005, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1709285342546814, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3246119743543146, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141213.1218379} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141213.1518378, "x": 27.284162698728537, "y": 5.052408241641568, "z": null, "yaw": 3.092469650327041, "pitch": null, "roll": null}, "v": 2.1691230832923276, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3555071036693325, "steering_wheel_angle": 0.3246119743543146, "front_wheel_angle": 0.014971486135271123, "heading_rate": 0.012686493265003432, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141213.1518378} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24787770396466163, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1644824614691927, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1691230832923276, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3246119743543146, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141213.1518378} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.78994870185852, "x": 23.284162698728537, "y": 0.052408241641567876, "z": null, "yaw": 3.092469650327041, "pitch": null, "roll": null}, "v": 2.1691230832923276, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3555071036693325, "steering_wheel_angle": 0.3246119743543146, "front_wheel_angle": 0.014971486135271123, "heading_rate": 0.012686493265003432, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141213.1718378} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24754123717398752, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1644824614691927, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1679981796595476, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3246119743543146, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141213.1718378} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.78994870185852, "x": 23.284162698728537, "y": 0.052408241641567876, "z": null, "yaw": 3.092469650327041, "pitch": null, "roll": null}, "v": 2.1691230832923276, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3555071036693325, "steering_wheel_angle": 0.3246119743543146, "front_wheel_angle": 0.014971486135271123, "heading_rate": 0.012686493265003432, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141213.1918378} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24754123717398752, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1644824614691927, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.166833336873607, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3246119743543146, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141213.1918378} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.78994870185852, "x": 23.284162698728537, "y": 0.052408241641567876, "z": null, "yaw": 3.092469650327041, "pitch": null, "roll": null}, "v": 2.1691230832923276, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3555071036693325, "steering_wheel_angle": 0.3246119743543146, "front_wheel_angle": 0.014971486135271123, "heading_rate": 0.012686493265003432, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141213.2118378} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24754123717398752, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1644824614691927, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1656706676593664, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3246119743543146, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141213.2118378} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.78994870185852, "x": 23.284162698728537, "y": 0.052408241641567876, "z": null, "yaw": 3.092469650327041, "pitch": null, "roll": null}, "v": 2.1691230832923276, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3555071036693325, "steering_wheel_angle": 0.3246119743543146, "front_wheel_angle": 0.014971486135271123, "heading_rate": 0.012686493265003432, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141213.2318377} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24754123717398752, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1644824614691927, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.164510167420521, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3246119743543146, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141213.2318377} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.78994870185852, "x": 23.284162698728537, "y": 0.052408241641567876, "z": null, "yaw": 3.092469650327041, "pitch": null, "roll": null}, "v": 2.1691230832923276, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3555071036693325, "steering_wheel_angle": 0.3246119743543146, "front_wheel_angle": 0.014971486135271123, "heading_rate": 0.012686493265003432, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141213.2518377} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24754123717398752, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1644824614691927, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.163351831572363, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3246119743543146, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141213.2518377} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141213.2618377, "x": 27.046159379998016, "y": 5.064039362478506, "z": null, "yaw": 3.0931130044409207, "pitch": null, "roll": null}, "v": 2.162773473865234, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3549145646858126, "steering_wheel_angle": 0.3246119743543146, "front_wheel_angle": 0.014971486135271123, "heading_rate": 0.012649356470944721, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141213.2718377} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2504312933328844, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2211230029292017, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1621956555417503, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3246119743543146, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141213.2718377} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.899948596954346, "x": 23.046159379998016, "y": 0.06403936247850606, "z": null, "yaw": 3.0931130044409207, "pitch": null, "roll": null}, "v": 2.162773473865234, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3549145646858126, "steering_wheel_angle": 0.3246119743543146, "front_wheel_angle": 0.014971486135271123, "heading_rate": 0.012649356470944721, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141213.2918377} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24900992957701298, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2211230029292017, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.161402723379431, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.406551048961355, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141213.2918377} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.899948596954346, "x": 23.046159379998016, "y": 0.06403936247850606, "z": null, "yaw": 3.0931130044409207, "pitch": null, "roll": null}, "v": 2.162773473865234, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3549145646858126, "steering_wheel_angle": 0.3246119743543146, "front_wheel_angle": 0.014971486135271123, "heading_rate": 0.012649356470944721, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141213.3118377} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24900992957701298, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2211230029292017, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1604336814032914, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.406551048961355, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141213.3118377} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.899948596954346, "x": 23.046159379998016, "y": 0.06403936247850606, "z": null, "yaw": 3.0931130044409207, "pitch": null, "roll": null}, "v": 2.162773473865234, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3549145646858126, "steering_wheel_angle": 0.3246119743543146, "front_wheel_angle": 0.014971486135271123, "heading_rate": 0.012649356470944721, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141213.3318377} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24900992957701298, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2211230029292017, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1594664451414687, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.406551048961355, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141213.3318377} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.899948596954346, "x": 23.046159379998016, "y": 0.06403936247850606, "z": null, "yaw": 3.0931130044409207, "pitch": null, "roll": null}, "v": 2.162773473865234, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3549145646858126, "steering_wheel_angle": 0.3246119743543146, "front_wheel_angle": 0.014971486135271123, "heading_rate": 0.012649356470944721, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141213.3518376} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24900992957701298, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2211230029292017, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1580189682868967, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.406551048961355, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141213.3518376} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141213.3718376, "x": 26.808790323435183, "y": 5.075476138875997, "z": null, "yaw": 3.0938825515430746, "pitch": null, "roll": null}, "v": 2.157537374814568, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35442654397794576, "steering_wheel_angle": 0.406551048961355, "front_wheel_angle": 0.01877104289802126, "heading_rate": 0.01582186873011424, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141213.3718376} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24604289201237844, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1926641152276034, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.157537374814568, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.406551048961355, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141213.3718376} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.00994849205017, "x": 22.808790323435183, "y": 0.07547613887599702, "z": null, "yaw": 3.0938825515430746, "pitch": null, "roll": null}, "v": 2.157537374814568, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35442654397794576, "steering_wheel_angle": 0.406551048961355, "front_wheel_angle": 0.01877104289802126, "heading_rate": 0.01582186873011424, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141213.3918376} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24741858520025245, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1926641152276034, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.156204826320743, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.406551048961355, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141213.3918376} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.00994849205017, "x": 22.808790323435183, "y": 0.07547613887599702, "z": null, "yaw": 3.0938825515430746, "pitch": null, "roll": null}, "v": 2.157537374814568, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35442654397794576, "steering_wheel_angle": 0.406551048961355, "front_wheel_angle": 0.01877104289802126, "heading_rate": 0.01582186873011424, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141213.4118376} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24741858520025245, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1926641152276034, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.155046640286617, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.406551048961355, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141213.4118376} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.00994849205017, "x": 22.808790323435183, "y": 0.07547613887599702, "z": null, "yaw": 3.0938825515430746, "pitch": null, "roll": null}, "v": 2.157537374814568, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35442654397794576, "steering_wheel_angle": 0.406551048961355, "front_wheel_angle": 0.01877104289802126, "heading_rate": 0.01582186873011424, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141213.4318376} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24741858520025245, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1926641152276034, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.15389060994668, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.406551048961355, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141213.4318376} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.00994849205017, "x": 22.808790323435183, "y": 0.07547613887599702, "z": null, "yaw": 3.0938825515430746, "pitch": null, "roll": null}, "v": 2.157537374814568, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35442654397794576, "steering_wheel_angle": 0.406551048961355, "front_wheel_angle": 0.01877104289802126, "heading_rate": 0.01582186873011424, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141213.4518375} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24741858520025245, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1926641152276034, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.152736730754295, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.406551048961355, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141213.4518375} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.00994849205017, "x": 22.808790323435183, "y": 0.07547613887599702, "z": null, "yaw": 3.0938825515430746, "pitch": null, "roll": null}, "v": 2.157537374814568, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35442654397794576, "steering_wheel_angle": 0.406551048961355, "front_wheel_angle": 0.01877104289802126, "heading_rate": 0.01582186873011424, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141213.4718375} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24741858520025245, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1926641152276034, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1515849981742665, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.406551048961355, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141213.4718375} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141213.4818375, "x": 26.572061484306275, "y": 5.086692124390007, "z": null, "yaw": 3.0946892145379454, "pitch": null, "roll": null}, "v": 2.1510099354497583, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35381893419652366, "steering_wheel_angle": 0.406551048961355, "front_wheel_angle": 0.01877104289802126, "heading_rate": 0.015774001059324676, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141213.4918375} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24162261765080897, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.116337586604838, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1504354076828087, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.406551048961355, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141213.4918375} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.119948387145996, "x": 22.572061484306275, "y": 0.08669212439000695, "z": null, "yaw": 3.0946892145379454, "pitch": null, "roll": null}, "v": 2.1510099354497583, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35381893419652366, "steering_wheel_angle": 0.406551048961355, "front_wheel_angle": 0.01877104289802126, "heading_rate": 0.015774001059324676, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141213.5118375} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2443363094751861, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.116337586604838, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1485637956912793, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.406551048961355, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141213.5118375} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.119948387145996, "x": 22.572061484306275, "y": 0.08669212439000695, "z": null, "yaw": 3.0946892145379454, "pitch": null, "roll": null}, "v": 2.1510099354497583, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35381893419652366, "steering_wheel_angle": 0.406551048961355, "front_wheel_angle": 0.01877104289802126, "heading_rate": 0.015774001059324676, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141213.5318375} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2443363094751861, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.116337586604838, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.14703471637747, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.406551048961355, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141213.5318375} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.119948387145996, "x": 22.572061484306275, "y": 0.08669212439000695, "z": null, "yaw": 3.0946892145379454, "pitch": null, "roll": null}, "v": 2.1510099354497583, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35381893419652366, "steering_wheel_angle": 0.406551048961355, "front_wheel_angle": 0.01877104289802126, "heading_rate": 0.015774001059324676, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141213.5518374} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2443363094751861, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.116337586604838, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.145508478250408, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.406551048961355, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141213.5518374} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.119948387145996, "x": 22.572061484306275, "y": 0.08669212439000695, "z": null, "yaw": 3.0946892145379454, "pitch": null, "roll": null}, "v": 2.1510099354497583, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35381893419652366, "steering_wheel_angle": 0.406551048961355, "front_wheel_angle": 0.01877104289802126, "heading_rate": 0.015774001059324676, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141213.5718374} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2443363094751861, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.116337586604838, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1439850750995473, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.406551048961355, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141213.5718374} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141213.5918374, "x": 26.33613641666878, "y": 5.097679312195566, "z": null, "yaw": 3.0954958775328163, "pitch": null, "roll": null}, "v": 2.1424645007310676, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35302476640548164, "steering_wheel_angle": 0.406551048961355, "front_wheel_angle": 0.01877104289802126, "heading_rate": 0.01571133482330061, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141213.5918374} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24860422112525005, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1667920199120394, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1424645007310676, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.406551048961355, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141213.5918374} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.22994828224182, "x": 22.33613641666878, "y": 0.09767931219556569, "z": null, "yaw": 3.0954958775328163, "pitch": null, "roll": null}, "v": 2.1424645007310676, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35302476640548164, "steering_wheel_angle": 0.406551048961355, "front_wheel_angle": 0.01877104289802126, "heading_rate": 0.01571133482330061, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141213.6118374} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2465113731766236, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1667920199120394, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1414799902871127, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.406551048961355, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141213.6118374} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.22994828224182, "x": 22.33613641666878, "y": 0.09767931219556569, "z": null, "yaw": 3.0954958775328163, "pitch": null, "roll": null}, "v": 2.1424645007310676, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35302476640548164, "steering_wheel_angle": 0.406551048961355, "front_wheel_angle": 0.01877104289802126, "heading_rate": 0.01571133482330061, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141213.6318374} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2465113731766236, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1667920199120394, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1402358223416127, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.406551048961355, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141213.6318374} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.22994828224182, "x": 22.33613641666878, "y": 0.09767931219556569, "z": null, "yaw": 3.0954958775328163, "pitch": null, "roll": null}, "v": 2.1424645007310676, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35302476640548164, "steering_wheel_angle": 0.406551048961355, "front_wheel_angle": 0.01877104289802126, "heading_rate": 0.01571133482330061, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141213.6518373} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2465113731766236, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1667920199120394, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1389939627723376, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.406551048961355, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141213.6518373} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.22994828224182, "x": 22.33613641666878, "y": 0.09767931219556569, "z": null, "yaw": 3.0954958775328163, "pitch": null, "roll": null}, "v": 2.1424645007310676, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35302476640548164, "steering_wheel_angle": 0.406551048961355, "front_wheel_angle": 0.01877104289802126, "heading_rate": 0.01571133482330061, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141213.6718373} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2465113731766236, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1667920199120394, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.137754406679824, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.406551048961355, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141213.6718373} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.22994828224182, "x": 22.33613641666878, "y": 0.09767931219556569, "z": null, "yaw": 3.0954958775328163, "pitch": null, "roll": null}, "v": 2.1424645007310676, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35302476640548164, "steering_wheel_angle": 0.406551048961355, "front_wheel_angle": 0.01877104289802126, "heading_rate": 0.01571133482330061, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141213.6918373} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2465113731766236, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1667920199120394, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.136517149177129, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.406551048961355, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141213.6918373} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141213.7018373, "x": 26.101028478952294, "y": 5.108438374042524, "z": null, "yaw": 3.096302540527687, "pitch": null, "roll": null}, "v": 2.1358993808732065, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3524156306958058, "steering_wheel_angle": 0.406551048961355, "front_wheel_angle": 0.01877104289802126, "heading_rate": 0.01566319083015311, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141213.7118373} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25008869512324594, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2206242009443313, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1352821853897876, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.406551048961355, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141213.7118373} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.33994817733765, "x": 22.101028478952294, "y": 0.10843837404252366, "z": null, "yaw": 3.096302540527687, "pitch": null, "roll": null}, "v": 2.1358993808732065, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3524156306958058, "steering_wheel_angle": 0.406551048961355, "front_wheel_angle": 0.01877104289802126, "heading_rate": 0.01566319083015311, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141213.7318373} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24833879726806193, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2206242009443313, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.13449646844797, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.406551048961355, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141213.7318373} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.33994817733765, "x": 22.101028478952294, "y": 0.10843837404252366, "z": null, "yaw": 3.096302540527687, "pitch": null, "roll": null}, "v": 2.1358993808732065, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3524156306958058, "steering_wheel_angle": 0.406551048961355, "front_wheel_angle": 0.01877104289802126, "heading_rate": 0.01566319083015311, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141213.7518373} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24833879726806193, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2206242009443313, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.133493571585791, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.406551048961355, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141213.7518373} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.33994817733765, "x": 22.101028478952294, "y": 0.10843837404252366, "z": null, "yaw": 3.096302540527687, "pitch": null, "roll": null}, "v": 2.1358993808732065, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3524156306958058, "steering_wheel_angle": 0.406551048961355, "front_wheel_angle": 0.01877104289802126, "heading_rate": 0.01566319083015311, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141213.7718372} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24833879726806193, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2206242009443313, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1324925327293522, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.406551048961355, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141213.7718372} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.33994817733765, "x": 22.101028478952294, "y": 0.10843837404252366, "z": null, "yaw": 3.096302540527687, "pitch": null, "roll": null}, "v": 2.1358993808732065, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3524156306958058, "steering_wheel_angle": 0.406551048961355, "front_wheel_angle": 0.01877104289802126, "heading_rate": 0.01566319083015311, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141213.7918372} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24833879726806193, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2206242009443313, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1314933480357947, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.406551048961355, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141213.7918372} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141213.8118372, "x": 25.866585039179412, "y": 5.118977511579637, "z": null, "yaw": 3.097109203522558, "pitch": null, "roll": null}, "v": 2.1304960136716034, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3519149333262861, "steering_wheel_angle": 0.406551048961355, "front_wheel_angle": 0.01877104289802126, "heading_rate": 0.01562356631770557, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141213.8118372} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2514939386771739, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2785907800552527, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1304960136716034, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.406551048961355, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141213.8118372} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.44994807243347, "x": 21.866585039179412, "y": 0.11897751157963743, "z": null, "yaw": 3.097109203522558, "pitch": null, "roll": null}, "v": 2.1304960136716034, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3519149333262861, "steering_wheel_angle": 0.406551048961355, "front_wheel_angle": 0.01877104289802126, "heading_rate": 0.01562356631770557, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141213.8318372} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24995334124651383, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2785907800552527, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1298947358810976, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.44751932435006775, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141213.8318372} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.44994807243347, "x": 21.866585039179412, "y": 0.11897751157963743, "z": null, "yaw": 3.097109203522558, "pitch": null, "roll": null}, "v": 2.1304960136716034, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3519149333262861, "steering_wheel_angle": 0.406551048961355, "front_wheel_angle": 0.01877104289802126, "heading_rate": 0.01562356631770557, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141213.8518372} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24995334124651383, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2785907800552527, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1291020856268297, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.44751932435006775, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141213.8518372} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.44994807243347, "x": 21.866585039179412, "y": 0.11897751157963743, "z": null, "yaw": 3.097109203522558, "pitch": null, "roll": null}, "v": 2.1304960136716034, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3519149333262861, "steering_wheel_angle": 0.406551048961355, "front_wheel_angle": 0.01877104289802126, "heading_rate": 0.01562356631770557, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141213.8718371} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24995334124651383, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2785907800552527, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.128310902459525, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.44751932435006775, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141213.8718371} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.44994807243347, "x": 21.866585039179412, "y": 0.11897751157963743, "z": null, "yaw": 3.097109203522558, "pitch": null, "roll": null}, "v": 2.1304960136716034, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3519149333262861, "steering_wheel_angle": 0.406551048961355, "front_wheel_angle": 0.01877104289802126, "heading_rate": 0.01562356631770557, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141213.8918371} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24995334124651383, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2785907800552527, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.127521183413534, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.44751932435006775, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141213.8918371} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.44994807243347, "x": 21.866585039179412, "y": 0.11897751157963743, "z": null, "yaw": 3.097109203522558, "pitch": null, "roll": null}, "v": 2.1304960136716034, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3519149333262861, "steering_wheel_angle": 0.406551048961355, "front_wheel_angle": 0.01877104289802126, "heading_rate": 0.01562356631770557, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141213.911837} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24995334124651383, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2785907800552527, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.126732925530085, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.44751932435006775, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141213.911837} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141213.921837, "x": 25.632657560590623, "y": 5.129297244549677, "z": null, "yaw": 3.097990225338867, "pitch": null, "roll": null}, "v": 2.1263393436015736, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35153015722155845, "steering_wheel_angle": 0.44751932435006775, "front_wheel_angle": 0.02067388779952926, "heading_rate": 0.017174205084978383, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141213.931837} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24868285437764484, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.26729666834654, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.125946125857265, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.44751932435006775, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141213.931837} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.5599479675293, "x": 21.632657560590623, "y": 0.12929724454967673, "z": null, "yaw": 3.097990225338867, "pitch": null, "roll": null}, "v": 2.1263393436015736, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35153015722155845, "steering_wheel_angle": 0.44751932435006775, "front_wheel_angle": 0.02067388779952926, "heading_rate": 0.017174205084978383, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141213.951837} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2492585321376556, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.26729666834654, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.12500204404957, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.44751932435006775, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141213.951837} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.5599479675293, "x": 21.632657560590623, "y": 0.12929724454967673, "z": null, "yaw": 3.097990225338867, "pitch": null, "roll": null}, "v": 2.1263393436015736, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35153015722155845, "steering_wheel_angle": 0.44751932435006775, "front_wheel_angle": 0.02067388779952926, "heading_rate": 0.017174205084978383, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141213.971837} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2492585321376556, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.26729666834654, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.124131634517177, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.44751932435006775, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141213.971837} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.5599479675293, "x": 21.632657560590623, "y": 0.12929724454967673, "z": null, "yaw": 3.097990225338867, "pitch": null, "roll": null}, "v": 2.1263393436015736, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35153015722155845, "steering_wheel_angle": 0.44751932435006775, "front_wheel_angle": 0.02067388779952926, "heading_rate": 0.017174205084978383, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141213.991837} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2492585321376556, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.26729666834654, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.123262834271347, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.44751932435006775, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141213.991837} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.5599479675293, "x": 21.632657560590623, "y": 0.12929724454967673, "z": null, "yaw": 3.097990225338867, "pitch": null, "roll": null}, "v": 2.1263393436015736, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35153015722155845, "steering_wheel_angle": 0.44751932435006775, "front_wheel_angle": 0.02067388779952926, "heading_rate": 0.017174205084978383, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141214.011837} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2492585321376556, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.26729666834654, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.122395640034909, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.44751932435006775, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141214.011837} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141214.031837, "x": 25.399219482437456, "y": 5.139387755493743, "z": null, "yaw": 3.0988786830373196, "pitch": null, "roll": null}, "v": 2.1215300485384243, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35108539989543575, "steering_wheel_angle": 0.44751932435006775, "front_wheel_angle": 0.02067388779952926, "heading_rate": 0.017135360946587564, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141214.031837} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24898745232243533, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2600793408096893, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1215300485384243, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.44751932435006775, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141214.031837} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.66994786262512, "x": 21.399219482437456, "y": 0.13938775549374327, "z": null, "yaw": 3.0988786830373196, "pitch": null, "roll": null}, "v": 2.1215300485384243, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35108539989543575, "steering_wheel_angle": 0.44751932435006775, "front_wheel_angle": 0.02067388779952926, "heading_rate": 0.017135360946587564, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141214.051837} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24908265172382046, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2600793408096893, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1206321872018115, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.44751932435006775, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141214.051837} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.66994786262512, "x": 21.399219482437456, "y": 0.13938775549374327, "z": null, "yaw": 3.0988786830373196, "pitch": null, "roll": null}, "v": 2.1215300485384243, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35108539989543575, "steering_wheel_angle": 0.44751932435006775, "front_wheel_angle": 0.02067388779952926, "heading_rate": 0.017135360946587564, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141214.071837} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24908265172382046, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2600793408096893, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1197478790809767, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.44751932435006775, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141214.071837} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.66994786262512, "x": 21.399219482437456, "y": 0.13938775549374327, "z": null, "yaw": 3.0988786830373196, "pitch": null, "roll": null}, "v": 2.1215300485384243, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35108539989543575, "steering_wheel_angle": 0.44751932435006775, "front_wheel_angle": 0.02067388779952926, "heading_rate": 0.017135360946587564, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141214.091837} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24908265172382046, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2600793408096893, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1188652043956133, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.44751932435006775, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141214.091837} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.66994786262512, "x": 21.399219482437456, "y": 0.13938775549374327, "z": null, "yaw": 3.0988786830373196, "pitch": null, "roll": null}, "v": 2.1215300485384243, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35108539989543575, "steering_wheel_angle": 0.44751932435006775, "front_wheel_angle": 0.02067388779952926, "heading_rate": 0.017135360946587564, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141214.111837} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24908265172382046, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2600793408096893, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1179841598170452, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.44751932435006775, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141214.111837} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.66994786262512, "x": 21.399219482437456, "y": 0.13938775549374327, "z": null, "yaw": 3.0988786830373196, "pitch": null, "roll": null}, "v": 2.1215300485384243, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35108539989543575, "steering_wheel_angle": 0.44751932435006775, "front_wheel_angle": 0.02067388779952926, "heading_rate": 0.017135360946587564, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141214.131837} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24908265172382046, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2600793408096893, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.11710474202447, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.44751932435006775, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141214.131837} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141214.141837, "x": 25.166304023505656, "y": 5.149248361912122, "z": null, "yaw": 3.0997671407357723, "pitch": null, "roll": null}, "v": 2.1166656421373267, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35063601651291254, "steering_wheel_angle": 0.44751932435006775, "front_wheel_angle": 0.02067388779952926, "heading_rate": 0.017096071680083362, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141214.1518369} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2520850972226365, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3159249868926293, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1162269477049365, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.44751932435006775, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141214.1518369} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.77994775772095, "x": 21.166304023505656, "y": 0.14924836191212165, "z": null, "yaw": 3.0997671407357723, "pitch": null, "roll": null}, "v": 2.1166656421373267, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35063601651291254, "steering_wheel_angle": 0.44751932435006775, "front_wheel_angle": 0.02067388779952926, "heading_rate": 0.017096071680083362, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141214.1718369} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25062112180559315, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3159249868926293, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.115725906003977, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.48848561533253104, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141214.1718369} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.77994775772095, "x": 21.166304023505656, "y": 0.14924836191212165, "z": null, "yaw": 3.0997671407357723, "pitch": null, "roll": null}, "v": 2.1166656421373267, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35063601651291254, "steering_wheel_angle": 0.44751932435006775, "front_wheel_angle": 0.02067388779952926, "heading_rate": 0.017096071680083362, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141214.1918368} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25062112180559315, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3159249868926293, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1150428765034075, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.48848561533253104, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141214.1918368} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.77994775772095, "x": 21.166304023505656, "y": 0.14924836191212165, "z": null, "yaw": 3.0997671407357723, "pitch": null, "roll": null}, "v": 2.1166656421373267, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35063601651291254, "steering_wheel_angle": 0.44751932435006775, "front_wheel_angle": 0.02067388779952926, "heading_rate": 0.017096071680083362, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141214.2118368} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25062112180559315, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3159249868926293, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1143611073517383, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.48848561533253104, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141214.2118368} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.77994775772095, "x": 21.166304023505656, "y": 0.14924836191212165, "z": null, "yaw": 3.0997671407357723, "pitch": null, "roll": null}, "v": 2.1166656421373267, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35063601651291254, "steering_wheel_angle": 0.44751932435006775, "front_wheel_angle": 0.02067388779952926, "heading_rate": 0.017096071680083362, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141214.2318368} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25062112180559315, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3159249868926293, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1136805960374936, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.48848561533253104, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141214.2318368} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141214.2518368, "x": 24.93385208711587, "y": 5.158876778024237, "z": null, "yaw": 3.1007225969936574, "pitch": null, "roll": null}, "v": 2.1130013400548595, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35029781363347934, "steering_wheel_angle": 0.48848561533253104, "front_wheel_angle": 0.022578732855351984, "heading_rate": 0.018639453809288876, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141214.2518368} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2518630987589786, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3485115544396817, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1130013400548595, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.48848561533253104, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141214.2518368} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.88994765281677, "x": 20.93385208711587, "y": 0.15887677802423728, "z": null, "yaw": 3.1007225969936574, "pitch": null, "roll": null}, "v": 2.1130013400548595, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35029781363347934, "steering_wheel_angle": 0.48848561533253104, "front_wheel_angle": 0.022578732855351984, "heading_rate": 0.018639453809288876, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141214.2718368} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2512459130153841, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3485115544396817, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1124785124119887, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5294444296817818, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141214.2718368} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.88994765281677, "x": 20.93385208711587, "y": 0.15887677802423728, "z": null, "yaw": 3.1007225969936574, "pitch": null, "roll": null}, "v": 2.1130013400548595, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35029781363347934, "steering_wheel_angle": 0.48848561533253104, "front_wheel_angle": 0.022578732855351984, "heading_rate": 0.018639453809288876, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141214.2918367} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2512459130153841, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3485115544396817, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1118795363283596, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5294444296817818, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141214.2918367} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.88994765281677, "x": 20.93385208711587, "y": 0.15887677802423728, "z": null, "yaw": 3.1007225969936574, "pitch": null, "roll": null}, "v": 2.1130013400548595, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35029781363347934, "steering_wheel_angle": 0.48848561533253104, "front_wheel_angle": 0.022578732855351984, "heading_rate": 0.018639453809288876, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141214.3118367} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2512459130153841, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3485115544396817, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.111281664733213, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5294444296817818, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141214.3118367} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.88994765281677, "x": 20.93385208711587, "y": 0.15887677802423728, "z": null, "yaw": 3.1007225969936574, "pitch": null, "roll": null}, "v": 2.1130013400548595, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35029781363347934, "steering_wheel_angle": 0.48848561533253104, "front_wheel_angle": 0.022578732855351984, "heading_rate": 0.018639453809288876, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141214.3318367} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2512459130153841, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3485115544396817, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1106848954470014, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5294444296817818, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141214.3318367} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.88994765281677, "x": 20.93385208711587, "y": 0.15887677802423728, "z": null, "yaw": 3.1007225969936574, "pitch": null, "roll": null}, "v": 2.1130013400548595, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35029781363347934, "steering_wheel_angle": 0.48848561533253104, "front_wheel_angle": 0.022578732855351984, "heading_rate": 0.018639453809288876, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141214.3518367} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2512459130153841, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3485115544396817, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1100892262949853, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5294444296817818, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141214.3518367} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141214.3618367, "x": 24.7017687683798, "y": 5.1682577321878895, "z": null, "yaw": 3.1017674595071085, "pitch": null, "roll": null}, "v": 2.1097918035910066, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3500018047245483, "steering_wheel_angle": 0.5294444296817818, "front_wheel_angle": 0.024485328878911743, "heading_rate": 0.02018330952040008, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141214.3718367} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2509360725580573, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3396506931284182, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1094946551072224, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5294444296817818, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141214.3718367} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.9999475479126, "x": 20.7017687683798, "y": 0.16825773218788953, "z": null, "yaw": 3.1017674595071085, "pitch": null, "roll": null}, "v": 2.1097918035910066, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3500018047245483, "steering_wheel_angle": 0.5294444296817818, "front_wheel_angle": 0.024485328878911743, "heading_rate": 0.02018330952040008, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141214.3918366} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25106106263568473, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3396506931284182, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.108862467512801, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5294444296817818, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141214.3918366} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.9999475479126, "x": 20.7017687683798, "y": 0.16825773218788953, "z": null, "yaw": 3.1017674595071085, "pitch": null, "roll": null}, "v": 2.1097918035910066, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3500018047245483, "steering_wheel_angle": 0.5294444296817818, "front_wheel_angle": 0.024485328878911743, "heading_rate": 0.02018330952040008, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141214.4118366} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25106106263568473, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3396506931284182, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1082470614468654, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5294444296817818, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141214.4118366} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.9999475479126, "x": 20.7017687683798, "y": 0.16825773218788953, "z": null, "yaw": 3.1017674595071085, "pitch": null, "roll": null}, "v": 2.1097918035910066, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3500018047245483, "steering_wheel_angle": 0.5294444296817818, "front_wheel_angle": 0.024485328878911743, "heading_rate": 0.02018330952040008, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141214.4318366} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25106106263568473, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3396506931284182, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1076327892733135, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5294444296817818, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141214.4318366} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.9999475479126, "x": 20.7017687683798, "y": 0.16825773218788953, "z": null, "yaw": 3.1017674595071085, "pitch": null, "roll": null}, "v": 2.1097918035910066, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3500018047245483, "steering_wheel_angle": 0.5294444296817818, "front_wheel_angle": 0.024485328878911743, "heading_rate": 0.02018330952040008, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141214.4518366} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25106106263568473, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3396506931284182, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.107019648752074, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5294444296817818, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141214.4518366} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141214.4718366, "x": 24.470040665738363, "y": 5.177380248281319, "z": null, "yaw": 3.10281977378924, "pitch": null, "roll": null}, "v": 2.106407637648035, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3496899132418215, "steering_wheel_angle": 0.5294444296817818, "front_wheel_angle": 0.024485328878911743, "heading_rate": 0.020150934918991954, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141214.4718366} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25177105708551395, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3465768884298825, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.106407637648035, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5294444296817818, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141214.4718366} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.10994744300842, "x": 20.470040665738363, "y": 0.17738024828131937, "z": null, "yaw": 3.10281977378924, "pitch": null, "roll": null}, "v": 2.106407637648035, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3496899132418215, "steering_wheel_angle": 0.5294444296817818, "front_wheel_angle": 0.024485328878911743, "heading_rate": 0.020150934918991954, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141214.4918365} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2514092011490056, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3465768884298825, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1058854621582297, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5294444296817818, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141214.4918365} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.10994744300842, "x": 20.470040665738363, "y": 0.17738024828131937, "z": null, "yaw": 3.10281977378924, "pitch": null, "roll": null}, "v": 2.106407637648035, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3496899132418215, "steering_wheel_angle": 0.5294444296817818, "front_wheel_angle": 0.024485328878911743, "heading_rate": 0.020150934918991954, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141214.5118365} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2514092011490056, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3465768884298825, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.104753655070143, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5294444296817818, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141214.5118365} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.10994744300842, "x": 20.470040665738363, "y": 0.17738024828131937, "z": null, "yaw": 3.10281977378924, "pitch": null, "roll": null}, "v": 2.106407637648035, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3496899132418215, "steering_wheel_angle": 0.5294444296817818, "front_wheel_angle": 0.024485328878911743, "heading_rate": 0.020150934918991954, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141214.5318365} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2514092011490056, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3465768884298825, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.104753655070143, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5294444296817818, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141214.5318365} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.10994744300842, "x": 20.470040665738363, "y": 0.17738024828131937, "z": null, "yaw": 3.10281977378924, "pitch": null, "roll": null}, "v": 2.106407637648035, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3496899132418215, "steering_wheel_angle": 0.5294444296817818, "front_wheel_angle": 0.024485328878911743, "heading_rate": 0.020150934918991954, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141214.5518365} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2514092011490056, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3465768884298825, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.103907533093869, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5294444296817818, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141214.5518365} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.10994744300842, "x": 20.470040665738363, "y": 0.17738024828131937, "z": null, "yaw": 3.10281977378924, "pitch": null, "roll": null}, "v": 2.106407637648035, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3496899132418215, "steering_wheel_angle": 0.5294444296817818, "front_wheel_angle": 0.024485328878911743, "heading_rate": 0.020150934918991954, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141214.5718365} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2514092011490056, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3465768884298825, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.103626011708354, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5294444296817818, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141214.5718365} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141214.5818365, "x": 24.238656992441506, "y": 5.186245346465107, "z": null, "yaw": 3.1038720880713715, "pitch": null, "roll": null}, "v": 2.103344749534599, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3494078288306776, "steering_wheel_angle": 0.5294444296817818, "front_wheel_angle": 0.024485328878911743, "heading_rate": 0.020121633819843394, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141214.5918365} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24524482512875095, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.209051469940724, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.103063746318105, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5294444296817818, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141214.5918365} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.21994733810425, "x": 20.238656992441506, "y": 0.18624534646510682, "z": null, "yaw": 3.1038720880713715, "pitch": null, "roll": null}, "v": 2.103344749534599, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3494078288306776, "steering_wheel_angle": 0.5294444296817818, "front_wheel_angle": 0.024485328878911743, "heading_rate": 0.020121633819843394, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141214.6118364} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2481587515912758, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.209051469940724, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.101249651325826, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5294444296817818, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141214.6118364} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.21994733810425, "x": 20.238656992441506, "y": 0.18624534646510682, "z": null, "yaw": 3.1038720880713715, "pitch": null, "roll": null}, "v": 2.103344749534599, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3494078288306776, "steering_wheel_angle": 0.5294444296817818, "front_wheel_angle": 0.024485328878911743, "heading_rate": 0.020121633819843394, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141214.6318364} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2481587515912758, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.209051469940724, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.100767423464898, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5294444296817818, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141214.6318364} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.21994733810425, "x": 20.238656992441506, "y": 0.18624534646510682, "z": null, "yaw": 3.1038720880713715, "pitch": null, "roll": null}, "v": 2.103344749534599, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3494078288306776, "steering_wheel_angle": 0.5294444296817818, "front_wheel_angle": 0.024485328878911743, "heading_rate": 0.020121633819843394, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141214.6518364} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2481587515912758, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.209051469940724, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0993234005449426, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5294444296817818, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141214.6518364} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.21994733810425, "x": 20.238656992441506, "y": 0.18624534646510682, "z": null, "yaw": 3.1038720880713715, "pitch": null, "roll": null}, "v": 2.103344749534599, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3494078288306776, "steering_wheel_angle": 0.5294444296817818, "front_wheel_angle": 0.024485328878911743, "heading_rate": 0.020121633819843394, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141214.6718364} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2481587515912758, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.209051469940724, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0983629312763448, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5294444296817818, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141214.6718364} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141214.6918364, "x": 24.00772549844243, "y": 5.194849784652468, "z": null, "yaw": 3.104924402353503, "pitch": null, "roll": null}, "v": 2.0978833590860257, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.348905313837602, "steering_wheel_angle": 0.5294444296817818, "front_wheel_angle": 0.024485328878911743, "heading_rate": 0.020069387463758546, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141214.6918364} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25177070689708386, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2557266011406165, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0978833590860257, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5294444296817818, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141214.6918364} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.32994723320007, "x": 20.00772549844243, "y": 0.19484978465246794, "z": null, "yaw": 3.104924402353503, "pitch": null, "roll": null}, "v": 2.0978833590860257, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.348905313837602, "steering_wheel_angle": 0.5294444296817818, "front_wheel_angle": 0.024485328878911743, "heading_rate": 0.020069387463758546, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141214.7118363} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2500124404450862, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2557266011406165, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0970140143324403, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5294444296817818, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141214.7118363} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.32994723320007, "x": 20.00772549844243, "y": 0.19484978465246794, "z": null, "yaw": 3.104924402353503, "pitch": null, "roll": null}, "v": 2.0978833590860257, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.348905313837602, "steering_wheel_angle": 0.5294444296817818, "front_wheel_angle": 0.024485328878911743, "heading_rate": 0.020069387463758546, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141214.7318363} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2500124404450862, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2557266011406165, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.096651538075461, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5294444296817818, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141214.7318363} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.32994723320007, "x": 20.00772549844243, "y": 0.19484978465246794, "z": null, "yaw": 3.104924402353503, "pitch": null, "roll": null}, "v": 2.0978833590860257, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.348905313837602, "steering_wheel_angle": 0.5294444296817818, "front_wheel_angle": 0.024485328878911743, "heading_rate": 0.020069387463758546, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141214.7518363} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2500124404450862, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2557266011406165, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.095927584974527, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5294444296817818, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141214.7518363} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.32994723320007, "x": 20.00772549844243, "y": 0.19484978465246794, "z": null, "yaw": 3.104924402353503, "pitch": null, "roll": null}, "v": 2.0978833590860257, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.348905313837602, "steering_wheel_angle": 0.5294444296817818, "front_wheel_angle": 0.024485328878911743, "heading_rate": 0.020069387463758546, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141214.7718363} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2500124404450862, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2557266011406165, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0952049622087214, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5294444296817818, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141214.7718363} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.32994723320007, "x": 20.00772549844243, "y": 0.19484978465246794, "z": null, "yaw": 3.104924402353503, "pitch": null, "roll": null}, "v": 2.0978833590860257, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.348905313837602, "steering_wheel_angle": 0.5294444296817818, "front_wheel_angle": 0.024485328878911743, "heading_rate": 0.020069387463758546, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141214.7918363} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2500124404450862, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2557266011406165, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0944836671246443, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5294444296817818, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141214.7918363} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141214.8018363, "x": 23.777287780330543, "y": 5.203192988086538, "z": null, "yaw": 3.1059767166356345, "pitch": null, "roll": null}, "v": 2.094123516635715, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3485597088610531, "steering_wheel_angle": 0.5294444296817818, "front_wheel_angle": 0.024485328878911743, "heading_rate": 0.02003341895549465, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141214.8118362} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25302347467872194, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.305172788030533, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0937636970749223, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5294444296817818, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141214.8118362} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.4399471282959, "x": 19.777287780330543, "y": 0.2031929880865384, "z": null, "yaw": 3.1059767166356345, "pitch": null, "roll": null}, "v": 2.094123516635715, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3485597088610531, "steering_wheel_angle": 0.5294444296817818, "front_wheel_angle": 0.024485328878911743, "heading_rate": 0.02003341895549465, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141214.8318362} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2515633163160311, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.305172788030533, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.093421255807638, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5294444296817818, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141214.8318362} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.4399471282959, "x": 19.777287780330543, "y": 0.2031929880865384, "z": null, "yaw": 3.1059767166356345, "pitch": null, "roll": null}, "v": 2.094123516635715, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3485597088610531, "steering_wheel_angle": 0.5294444296817818, "front_wheel_angle": 0.024485328878911743, "heading_rate": 0.02003341895549465, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141214.8518362} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2515633163160311, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.305172788030533, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0928970074936, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5294444296817818, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141214.8518362} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.4399471282959, "x": 19.777287780330543, "y": 0.2031929880865384, "z": null, "yaw": 3.1059767166356345, "pitch": null, "roll": null}, "v": 2.094123516635715, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3485597088610531, "steering_wheel_angle": 0.5294444296817818, "front_wheel_angle": 0.024485328878911743, "heading_rate": 0.02003341895549465, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141214.8718362} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2515633163160311, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.305172788030533, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0923737218920837, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5294444296817818, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141214.8718362} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.4399471282959, "x": 19.777287780330543, "y": 0.2031929880865384, "z": null, "yaw": 3.1059767166356345, "pitch": null, "roll": null}, "v": 2.094123516635715, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3485597088610531, "steering_wheel_angle": 0.5294444296817818, "front_wheel_angle": 0.024485328878911743, "heading_rate": 0.02003341895549465, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141214.8918362} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2515633163160311, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.305172788030533, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.091851397125714, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5294444296817818, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141214.8918362} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141214.9118361, "x": 23.547214692129216, "y": 5.211280561967089, "z": null, "yaw": 3.107029030917766, "pitch": null, "roll": null}, "v": 2.0913300313211667, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3483031145651163, "steering_wheel_angle": 0.5294444296817818, "front_wheel_angle": 0.024485328878911743, "heading_rate": 0.020006695096463512, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141214.9118361} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25421416219134807, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3580811623706186, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.091235385312475, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5294444296817818, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141214.9118361} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.549947023391724, "x": 19.547214692129216, "y": 0.21128056196708922, "z": null, "yaw": 3.107029030917766, "pitch": null, "roll": null}, "v": 2.0913300313211667, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3483031145651163, "steering_wheel_angle": 0.5294444296817818, "front_wheel_angle": 0.024485328878911743, "heading_rate": 0.020006695096463512, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141214.9318361} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.252932303949734, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3580811623706186, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0911408262130995, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5294444296817818, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141214.9318361} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.549947023391724, "x": 19.547214692129216, "y": 0.21128056196708922, "z": null, "yaw": 3.107029030917766, "pitch": null, "roll": null}, "v": 2.0913300313211667, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3483031145651163, "steering_wheel_angle": 0.5294444296817818, "front_wheel_angle": 0.024485328878911743, "heading_rate": 0.020006695096463512, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141214.951836} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.252932303949734, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3580811623706186, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.090791809698541, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5294444296817818, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141214.951836} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.549947023391724, "x": 19.547214692129216, "y": 0.21128056196708922, "z": null, "yaw": 3.107029030917766, "pitch": null, "roll": null}, "v": 2.0913300313211667, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3483031145651163, "steering_wheel_angle": 0.5294444296817818, "front_wheel_angle": 0.024485328878911743, "heading_rate": 0.020006695096463512, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141214.971836} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.252932303949734, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3580811623706186, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0904434338067945, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5294444296817818, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141214.971836} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.549947023391724, "x": 19.547214692129216, "y": 0.21128056196708922, "z": null, "yaw": 3.107029030917766, "pitch": null, "roll": null}, "v": 2.0913300313211667, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3483031145651163, "steering_wheel_angle": 0.5294444296817818, "front_wheel_angle": 0.024485328878911743, "heading_rate": 0.020006695096463512, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141214.991836} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.252932303949734, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3580811623706186, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0900956973134677, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5294444296817818, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141214.991836} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.549947023391724, "x": 19.547214692129216, "y": 0.21128056196708922, "z": null, "yaw": 3.107029030917766, "pitch": null, "roll": null}, "v": 2.0913300313211667, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3483031145651163, "steering_wheel_angle": 0.5294444296817818, "front_wheel_angle": 0.024485328878911743, "heading_rate": 0.020006695096463512, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141215.011836} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.252932303949734, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3580811623706186, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0895752887733408, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5294444296817818, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141215.011836} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141215.021836, "x": 23.317382667027484, "y": 5.219117507533914, "z": null, "yaw": 3.1080813451998974, "pitch": null, "roll": null}, "v": 2.0895752887733408, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34814201331318895, "steering_wheel_angle": 0.5294444296817818, "front_wheel_angle": 0.024485328878911743, "heading_rate": 0.01998990836333131, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141215.031836} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2542677163353956, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3890007977372134, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0894021376370673, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5294444296817818, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141215.031836} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.65994691848755, "x": 19.317382667027484, "y": 0.21911750753391424, "z": null, "yaw": 3.1080813451998974, "pitch": null, "roll": null}, "v": 2.0895752887733408, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34814201331318895, "steering_wheel_angle": 0.5294444296817818, "front_wheel_angle": 0.024485328878911743, "heading_rate": 0.01998990836333131, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141215.051836} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2536195309706606, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3890007977372134, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0890932857214906, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141215.051836} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.65994691848755, "x": 19.317382667027484, "y": 0.21911750753391424, "z": null, "yaw": 3.1080813451998974, "pitch": null, "roll": null}, "v": 2.0895752887733408, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34814201331318895, "steering_wheel_angle": 0.5294444296817818, "front_wheel_angle": 0.024485328878911743, "heading_rate": 0.01998990836333131, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141215.071836} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2536195309706606, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3890007977372134, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0889635286886516, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141215.071836} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.65994691848755, "x": 19.317382667027484, "y": 0.21911750753391424, "z": null, "yaw": 3.1080813451998974, "pitch": null, "roll": null}, "v": 2.0895752887733408, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34814201331318895, "steering_wheel_angle": 0.5294444296817818, "front_wheel_angle": 0.024485328878911743, "heading_rate": 0.01998990836333131, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141215.091836} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2536195309706606, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3890007977372134, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0887043717855334, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141215.091836} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.65994691848755, "x": 19.317382667027484, "y": 0.21911750753391424, "z": null, "yaw": 3.1080813451998974, "pitch": null, "roll": null}, "v": 2.0895752887733408, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34814201331318895, "steering_wheel_angle": 0.5294444296817818, "front_wheel_angle": 0.024485328878911743, "heading_rate": 0.01998990836333131, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141215.111836} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2536195309706606, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3890007977372134, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0884456903486197, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141215.111836} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141215.131836, "x": 23.087723396072114, "y": 5.226700999084617, "z": null, "yaw": 3.109200808439919, "pitch": null, "roll": null}, "v": 2.0881874834788348, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34801464383551844, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02153462763739655, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141215.131836} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25399307944112154, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3942841921564229, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0881874834788348, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141215.131836} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.769946813583374, "x": 19.087723396072114, "y": 0.22670099908461694, "z": null, "yaw": 3.109200808439919, "pitch": null, "roll": null}, "v": 2.0881874834788348, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34801464383551844, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02153462763739655, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141215.151836} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2538054947822299, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3942841921564229, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.087859313073001, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141215.151836} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.769946813583374, "x": 19.087723396072114, "y": 0.22670099908461694, "z": null, "yaw": 3.109200808439919, "pitch": null, "roll": null}, "v": 2.0881874834788348, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34801464383551844, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02153462763739655, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141215.171836} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2538054947822299, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3942841921564229, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0877423111892357, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141215.171836} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.769946813583374, "x": 19.087723396072114, "y": 0.22670099908461694, "z": null, "yaw": 3.109200808439919, "pitch": null, "roll": null}, "v": 2.0881874834788348, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34801464383551844, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02153462763739655, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141215.1918359} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2538054947822299, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3942841921564229, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.087508629389267, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141215.1918359} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.769946813583374, "x": 19.087723396072114, "y": 0.22670099908461694, "z": null, "yaw": 3.109200808439919, "pitch": null, "roll": null}, "v": 2.0881874834788348, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34801464383551844, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02153462763739655, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141215.2118359} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2538054947822299, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3942841921564229, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0871589100911265, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141215.2118359} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.769946813583374, "x": 19.087723396072114, "y": 0.22670099908461694, "z": null, "yaw": 3.109200808439919, "pitch": null, "roll": null}, "v": 2.0881874834788348, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34801464383551844, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02153462763739655, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141215.2318358} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2538054947822299, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3942841921564229, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.087042550828373, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141215.2318358} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141215.2418358, "x": 22.85820156319514, "y": 5.234019778600047, "z": null, "yaw": 3.1103351936705828, "pitch": null, "roll": null}, "v": 2.0869262983159516, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3478989286618248, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021521621548106495, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141215.2518358} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2533554009059817, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3716768281001084, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0868101524532228, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141215.2518358} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.8799467086792, "x": 18.85820156319514, "y": 0.23401977860004664, "z": null, "yaw": 3.1103351936705828, "pitch": null, "roll": null}, "v": 2.0869262983159516, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3478989286618248, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021521621548106495, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141215.2718358} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25356091503171985, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3716768281001084, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.086521944345712, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141215.2718358} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.8799467086792, "x": 18.85820156319514, "y": 0.23401977860004664, "z": null, "yaw": 3.1103351936705828, "pitch": null, "roll": null}, "v": 2.0869262983159516, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3478989286618248, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021521621548106495, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141215.2918358} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25356091503171985, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3716768281001084, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0862599422367483, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141215.2918358} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.8799467086792, "x": 18.85820156319514, "y": 0.23401977860004664, "z": null, "yaw": 3.1103351936705828, "pitch": null, "roll": null}, "v": 2.0869262983159516, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3478989286618248, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021521621548106495, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141215.3118358} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25356091503171985, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3716768281001084, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0859984205581212, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141215.3118358} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.8799467086792, "x": 18.85820156319514, "y": 0.23401977860004664, "z": null, "yaw": 3.1103351936705828, "pitch": null, "roll": null}, "v": 2.0869262983159516, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3478989286618248, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021521621548106495, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141215.3318357} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25356091503171985, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3716768281001084, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0857373784015256, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141215.3318357} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141215.3518357, "x": 22.628820857841504, "y": 5.241073598594785, "z": null, "yaw": 3.1114695789012465, "pitch": null, "roll": null}, "v": 2.085476814860473, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3477659761962295, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02150667361516118, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141215.3518357} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25231868253301803, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3270072331665985, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0850615211681798, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141215.3518357} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.989946603775024, "x": 18.628820857841504, "y": 0.2410735985947854, "z": null, "yaw": 3.1114695789012465, "pitch": null, "roll": null}, "v": 2.085476814860473, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3477659761962295, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02150667361516118, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141215.3718357} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2529000923968894, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3270072331665985, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0848904980276957, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141215.3718357} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.989946603775024, "x": 18.628820857841504, "y": 0.2410735985947854, "z": null, "yaw": 3.1114695789012465, "pitch": null, "roll": null}, "v": 2.085476814860473, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3477659761962295, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02150667361516118, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141215.4018357} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2529000923968894, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3270072331665985, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0845489220792732, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141215.4018357} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.989946603775024, "x": 18.628820857841504, "y": 0.2410735985947854, "z": null, "yaw": 3.1114695789012465, "pitch": null, "roll": null}, "v": 2.085476814860473, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3477659761962295, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02150667361516118, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141215.4218357} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2529000923968894, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3270072331665985, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0842079722440006, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141215.4218357} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.989946603775024, "x": 18.628820857841504, "y": 0.2410735985947854, "z": null, "yaw": 3.1114695789012465, "pitch": null, "roll": null}, "v": 2.085476814860473, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3477659761962295, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02150667361516118, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141215.4418356} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2529000923968894, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3270072331665985, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0838676473277267, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141215.4418356} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141215.4618356, "x": 22.399619807244157, "y": 5.247861659576625, "z": null, "yaw": 3.1126039641319103, "pitch": null, "roll": null}, "v": 2.083527946138745, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34758728433034863, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021486575725211815, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141215.4618356} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25534298133764605, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.37590702591437, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.083527946138745, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141215.4618356} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.09994649887085, "x": 18.399619807244157, "y": 0.24786165957662476, "z": null, "yaw": 3.1126039641319103, "pitch": null, "roll": null}, "v": 2.083527946138745, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34758728433034863, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021486575725211815, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141215.4818356} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25416608568340304, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.37590702591437, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.083494088645108, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141215.4818356} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.09994649887085, "x": 18.399619807244157, "y": 0.24786165957662476, "z": null, "yaw": 3.1126039641319103, "pitch": null, "roll": null}, "v": 2.083527946138745, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34758728433034863, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021486575725211815, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141215.5018356} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25416608568340304, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.37590702591437, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.083313248668491, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141215.5018356} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.09994649887085, "x": 18.399619807244157, "y": 0.24786165957662476, "z": null, "yaw": 3.1126039641319103, "pitch": null, "roll": null}, "v": 2.083527946138745, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34758728433034863, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021486575725211815, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141215.5218356} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25416608568340304, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.37590702591437, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.083132740081693, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141215.5218356} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.09994649887085, "x": 18.399619807244157, "y": 0.24786165957662476, "z": null, "yaw": 3.1126039641319103, "pitch": null, "roll": null}, "v": 2.083527946138745, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34758728433034863, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021486575725211815, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141215.5418355} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25416608568340304, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.37590702591437, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.082952562264413, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141215.5418355} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.09994649887085, "x": 18.399619807244157, "y": 0.24786165957662476, "z": null, "yaw": 3.1126039641319103, "pitch": null, "roll": null}, "v": 2.083527946138745, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34758728433034863, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021486575725211815, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141215.5618355} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25416608568340304, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.37590702591437, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0826829143774064, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141215.5618355} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141215.5718355, "x": 22.170560341080915, "y": 5.254385455707843, "z": null, "yaw": 3.113738349362574, "pitch": null, "roll": null}, "v": 2.0826829143774064, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.347509826937266, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021477861256579966, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141215.5818355} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2526594431769382, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3282702105890094, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0825931964632463, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141215.5818355} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.209946393966675, "x": 18.170560341080915, "y": 0.2543854557078431, "z": null, "yaw": 3.113738349362574, "pitch": null, "roll": null}, "v": 2.0826829143774064, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.347509826937266, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021477861256579966, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141215.6018355} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25337099082932624, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3282702105890094, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0822257632330285, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141215.6018355} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.209946393966675, "x": 18.170560341080915, "y": 0.2543854557078431, "z": null, "yaw": 3.113738349362574, "pitch": null, "roll": null}, "v": 2.0826829143774064, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.347509826937266, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021477861256579966, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141215.6218355} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25337099082932624, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3282702105890094, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0819479058745967, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141215.6218355} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.209946393966675, "x": 18.170560341080915, "y": 0.2543854557078431, "z": null, "yaw": 3.113738349362574, "pitch": null, "roll": null}, "v": 2.0826829143774064, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.347509826937266, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021477861256579966, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141215.6418355} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25337099082932624, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3282702105890094, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0816705575417225, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141215.6418355} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.209946393966675, "x": 18.170560341080915, "y": 0.2543854557078431, "z": null, "yaw": 3.113738349362574, "pitch": null, "roll": null}, "v": 2.0826829143774064, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.347509826937266, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021477861256579966, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141215.6618354} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25337099082932624, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3282702105890094, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0813937172711325, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141215.6618354} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141215.6818354, "x": 21.941629862530007, "y": 5.260645687734224, "z": null, "yaw": 3.114872734593238, "pitch": null, "roll": null}, "v": 2.0811173841014874, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34736636486916855, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021461716580005803, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141215.6818354} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25579470293990486, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3792813776258277, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0811173841014874, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141215.6818354} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.3199462890625, "x": 17.941629862530007, "y": 0.2606456877342236, "z": null, "yaw": 3.114872734593238, "pitch": null, "roll": null}, "v": 2.0811173841014874, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34736636486916855, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021461716580005803, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141215.7018354} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25462962329052796, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3792813776258277, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.081144382297715, "gear": 1, "accelerator_pedal_position": 0.25579470293990486, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141215.7018354} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.3199462890625, "x": 17.941629862530007, "y": 0.2606456877342236, "z": null, "yaw": 3.114872734593238, "pitch": null, "roll": null}, "v": 2.0811173841014874, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34736636486916855, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021461716580005803, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141215.7218354} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25462962329052796, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3792813776258277, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0810257628045954, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141215.7218354} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.3199462890625, "x": 17.941629862530007, "y": 0.2606456877342236, "z": null, "yaw": 3.114872734593238, "pitch": null, "roll": null}, "v": 2.0811173841014874, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34736636486916855, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021461716580005803, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141215.7418354} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25462962329052796, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3792813776258277, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.080907360572891, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141215.7418354} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.3199462890625, "x": 17.941629862530007, "y": 0.2606456877342236, "z": null, "yaw": 3.114872734593238, "pitch": null, "roll": null}, "v": 2.0811173841014874, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34736636486916855, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021461716580005803, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141215.7618353} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25462962329052796, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3792813776258277, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0806712062803476, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141215.7618353} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.3199462890625, "x": 17.941629862530007, "y": 0.2606456877342236, "z": null, "yaw": 3.114872734593238, "pitch": null, "roll": null}, "v": 2.0811173841014874, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34736636486916855, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021461716580005803, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141215.7818353} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25462962329052796, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3792813776258277, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0806712062803476, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141215.7818353} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141215.7918353, "x": 21.71280429911106, "y": 5.266643277512339, "z": null, "yaw": 3.1160071198239017, "pitch": null, "roll": null}, "v": 2.080612302866001, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3473200906916737, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02145650788278925, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141215.8118353} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2523138001394436, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.279516417681057, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.080494657876441, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141215.8118353} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.429946184158325, "x": 17.71280429911106, "y": 0.26664327751233863, "z": null, "yaw": 3.1160071198239017, "pitch": null, "roll": null}, "v": 2.080612302866001, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3473200906916737, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02145650788278925, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141215.8318353} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25341304796603503, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.279516417681057, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.080087883035945, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141215.8318353} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.429946184158325, "x": 17.71280429911106, "y": 0.26664327751233863, "z": null, "yaw": 3.1160071198239017, "pitch": null, "roll": null}, "v": 2.080612302866001, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3473200906916737, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02145650788278925, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141215.8518353} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25341304796603503, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.279516417681057, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0798191961439723, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141215.8518353} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.429946184158325, "x": 17.71280429911106, "y": 0.26664327751233863, "z": null, "yaw": 3.1160071198239017, "pitch": null, "roll": null}, "v": 2.080612302866001, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3473200906916737, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02145650788278925, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141215.8718352} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25341304796603503, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.279516417681057, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.079551001248744, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141215.8718352} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.429946184158325, "x": 17.71280429911106, "y": 0.26664327751233863, "z": null, "yaw": 3.1160071198239017, "pitch": null, "roll": null}, "v": 2.080612302866001, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3473200906916737, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02145650788278925, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141215.8918352} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25341304796603503, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.279516417681057, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0792832974205995, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141215.8918352} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141215.9018352, "x": 21.484078721803446, "y": 5.272378623398406, "z": null, "yaw": 3.1171415050545654, "pitch": null, "roll": null}, "v": 2.079149629366673, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34718611328128945, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02144142392628998, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141215.9118352} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2558131957628912, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3217819015773244, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0790160837317373, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141215.9118352} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.53994607925415, "x": 17.484078721803446, "y": 0.2723786233984056, "z": null, "yaw": 3.1171415050545654, "pitch": null, "roll": null}, "v": 2.079149629366673, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34718611328128945, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02144142392628998, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141215.9318352} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25466005986184104, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3217819015773244, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0790492403536307, "gear": 1, "accelerator_pedal_position": 0.2558131957628912, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141215.9318352} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.53994607925415, "x": 17.484078721803446, "y": 0.2723786233984056, "z": null, "yaw": 3.1171415050545654, "pitch": null, "roll": null}, "v": 2.079149629366673, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34718611328128945, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02144142392628998, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141215.9518352} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25466005986184104, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3217819015773244, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0789382602885347, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141215.9518352} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.53994607925415, "x": 17.484078721803446, "y": 0.2723786233984056, "z": null, "yaw": 3.1171415050545654, "pitch": null, "roll": null}, "v": 2.079149629366673, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34718611328128945, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02144142392628998, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141215.9718351} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25466005986184104, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3217819015773244, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.078827483399941, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141215.9718351} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.53994607925415, "x": 17.484078721803446, "y": 0.2723786233984056, "z": null, "yaw": 3.1171415050545654, "pitch": null, "roll": null}, "v": 2.079149629366673, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34718611328128945, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02144142392628998, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141215.991835} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25466005986184104, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3217819015773244, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.078716909310978, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141215.991835} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141216.011835, "x": 21.25546383032741, "y": 5.277851689808573, "z": null, "yaw": 3.1182758902852292, "pitch": null, "roll": null}, "v": 2.078606537645492, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34713637826570043, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021435823242404495, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141216.011835} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2567325099708572, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3664668495388315, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.078606537645492, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141216.011835} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.649945974349976, "x": 17.25546383032741, "y": 0.277851689808573, "z": null, "yaw": 3.1182758902852292, "pitch": null, "roll": null}, "v": 2.078606537645492, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34713637826570043, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021435823242404495, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141216.031835} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25574183913715937, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3664668495388315, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.07875530567975, "gear": 1, "accelerator_pedal_position": 0.2567325099708572, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141216.031835} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.649945974349976, "x": 17.25546383032741, "y": 0.277851689808573, "z": null, "yaw": 3.1182758902852292, "pitch": null, "roll": null}, "v": 2.078606537645492, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34713637826570043, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021435823242404495, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141216.051835} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25574183913715937, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3664668495388315, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.078780024218823, "gear": 1, "accelerator_pedal_position": 0.25574183913715937, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141216.051835} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.649945974349976, "x": 17.25546383032741, "y": 0.277851689808573, "z": null, "yaw": 3.1182758902852292, "pitch": null, "roll": null}, "v": 2.078606537645492, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34713637826570043, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021435823242404495, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141216.071835} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25574183913715937, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3664668495388315, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.078804697506385, "gear": 1, "accelerator_pedal_position": 0.25574183913715937, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141216.071835} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.649945974349976, "x": 17.25546383032741, "y": 0.277851689808573, "z": null, "yaw": 3.1182758902852292, "pitch": null, "roll": null}, "v": 2.078606537645492, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34713637826570043, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021435823242404495, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141216.091835} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25574183913715937, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3664668495388315, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.078829325625033, "gear": 1, "accelerator_pedal_position": 0.25574183913715937, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141216.091835} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.649945974349976, "x": 17.25546383032741, "y": 0.277851689808573, "z": null, "yaw": 3.1182758902852292, "pitch": null, "roll": null}, "v": 2.078606537645492, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34713637826570043, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021435823242404495, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141216.111835} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25574183913715937, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3664668495388315, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0788661832916047, "gear": 1, "accelerator_pedal_position": 0.25574183913715937, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141216.111835} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141216.121835, "x": 21.026857986127983, "y": 5.283065063416142, "z": null, "yaw": 3.119410275515893, "pitch": null, "roll": null}, "v": 2.0788661832916047, "accelerator_pedal_position": 0.25574183913715937, "brake_pedal_position": 0.0, "acceleration": 0.0012263393623316854, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021438500862278644, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141216.121835} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25465265450535735, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2814647029083508, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0788661832916047, "gear": 1, "accelerator_pedal_position": 0.25574183913715937, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141216.121835} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.7599458694458, "x": 17.026857986127983, "y": 0.28306506341614224, "z": null, "yaw": 3.119410275515893, "pitch": null, "roll": null}, "v": 2.0788661832916047, "accelerator_pedal_position": 0.25574183913715937, "brake_pedal_position": 0.0, "acceleration": 0.0012263393623316854, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021438500862278644, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141216.151835} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2551731256932013, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2814647029083508, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0786989046353384, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141216.151835} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.7599458694458, "x": 17.026857986127983, "y": 0.28306506341614224, "z": null, "yaw": 3.119410275515893, "pitch": null, "roll": null}, "v": 2.0788661832916047, "accelerator_pedal_position": 0.25574183913715937, "brake_pedal_position": 0.0, "acceleration": 0.0012263393623316854, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021438500862278644, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141216.171835} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2551731256932013, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2814647029083508, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0786526697943124, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141216.171835} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.7599458694458, "x": 17.026857986127983, "y": 0.28306506341614224, "z": null, "yaw": 3.119410275515893, "pitch": null, "roll": null}, "v": 2.0788661832916047, "accelerator_pedal_position": 0.25574183913715937, "brake_pedal_position": 0.0, "acceleration": 0.0012263393623316854, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021438500862278644, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141216.191835} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2551731256932013, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2814647029083508, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0786065195920402, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141216.191835} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.7599458694458, "x": 17.026857986127983, "y": 0.28306506341614224, "z": null, "yaw": 3.119410275515893, "pitch": null, "roll": null}, "v": 2.0788661832916047, "accelerator_pedal_position": 0.25574183913715937, "brake_pedal_position": 0.0, "acceleration": 0.0012263393623316854, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021438500862278644, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141216.211835} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2551731256932013, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2814647029083508, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0785374526455773, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141216.211835} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141216.231835, "x": 20.798257906718483, "y": 5.28801886252813, "z": null, "yaw": 3.120544660746557, "pitch": null, "roll": null}, "v": 2.0785144724808746, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34712794774716826, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021434873811831765, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141216.231835} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2573536762978856, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3289054128306832, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0785144724808746, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141216.231835} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.869945764541626, "x": 16.798257906718483, "y": 0.2880188625281299, "z": null, "yaw": 3.120544660746557, "pitch": null, "roll": null}, "v": 2.0785144724808746, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34712794774716826, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021434873811831765, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141216.2518349} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25631286444256235, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3289054128306832, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0787890863850733, "gear": 1, "accelerator_pedal_position": 0.25631286444256235, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141216.2518349} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.869945764541626, "x": 16.798257906718483, "y": 0.2880188625281299, "z": null, "yaw": 3.120544660746557, "pitch": null, "roll": null}, "v": 2.0785144724808746, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34712794774716826, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021434873811831765, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141216.2718349} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25631286444256235, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3289054128306832, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0788371094629734, "gear": 1, "accelerator_pedal_position": 0.25631286444256235, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141216.2718349} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.869945764541626, "x": 16.798257906718483, "y": 0.2880188625281299, "z": null, "yaw": 3.120544660746557, "pitch": null, "roll": null}, "v": 2.0785144724808746, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34712794774716826, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021434873811831765, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141216.2918348} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25631286444256235, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3289054128306832, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0789330237253676, "gear": 1, "accelerator_pedal_position": 0.25631286444256235, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141216.2918348} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.869945764541626, "x": 16.798257906718483, "y": 0.2880188625281299, "z": null, "yaw": 3.120544660746557, "pitch": null, "roll": null}, "v": 2.0785144724808746, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34712794774716826, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021434873811831765, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141216.3118348} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25631286444256235, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3289054128306832, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0790287623951276, "gear": 1, "accelerator_pedal_position": 0.25631286444256235, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141216.3118348} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.869945764541626, "x": 16.798257906718483, "y": 0.2880188625281299, "z": null, "yaw": 3.120544660746557, "pitch": null, "roll": null}, "v": 2.0785144724808746, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34712794774716826, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021434873811831765, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141216.3318348} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25631286444256235, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3289054128306832, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.079124325790051, "gear": 1, "accelerator_pedal_position": 0.25631286444256235, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141216.3318348} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141216.3418348, "x": 20.56963073763078, "y": 5.2927137719939115, "z": null, "yaw": 3.1216790459772206, "pitch": null, "roll": null}, "v": 2.079172041858607, "accelerator_pedal_position": 0.25631286444256235, "brake_pedal_position": 0.0, "acceleration": 0.004767236876619341, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021441655057197546, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141216.3518348} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.256254091693329, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2884025089124505, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0792197142273734, "gear": 1, "accelerator_pedal_position": 0.25631286444256235, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141216.3518348} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.97994565963745, "x": 16.56963073763078, "y": 0.29271377199391146, "z": null, "yaw": 3.1216790459772206, "pitch": null, "roll": null}, "v": 2.079172041858607, "accelerator_pedal_position": 0.25631286444256235, "brake_pedal_position": 0.0, "acceleration": 0.004767236876619341, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021441655057197546, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141216.3718348} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2562866667819777, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2884025089124505, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.079307584794315, "gear": 1, "accelerator_pedal_position": 0.256254091693329, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141216.3718348} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.97994565963745, "x": 16.56963073763078, "y": 0.29271377199391146, "z": null, "yaw": 3.1216790459772206, "pitch": null, "roll": null}, "v": 2.079172041858607, "accelerator_pedal_position": 0.25631286444256235, "brake_pedal_position": 0.0, "acceleration": 0.004767236876619341, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021441655057197546, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141216.3918347} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2562866667819777, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2884025089124505, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0793993645026143, "gear": 1, "accelerator_pedal_position": 0.2562866667819777, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141216.3918347} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.97994565963745, "x": 16.56963073763078, "y": 0.29271377199391146, "z": null, "yaw": 3.1216790459772206, "pitch": null, "roll": null}, "v": 2.079172041858607, "accelerator_pedal_position": 0.25631286444256235, "brake_pedal_position": 0.0, "acceleration": 0.004767236876619341, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021441655057197546, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141216.4118347} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2562866667819777, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2884025089124505, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0795367190841594, "gear": 1, "accelerator_pedal_position": 0.2562866667819777, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141216.4118347} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.97994565963745, "x": 16.56963073763078, "y": 0.29271377199391146, "z": null, "yaw": 3.1216790459772206, "pitch": null, "roll": null}, "v": 2.079172041858607, "accelerator_pedal_position": 0.25631286444256235, "brake_pedal_position": 0.0, "acceleration": 0.004767236876619341, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021441655057197546, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141216.4318347} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2562866667819777, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2884025089124505, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.079582420101889, "gear": 1, "accelerator_pedal_position": 0.2562866667819777, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141216.4318347} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141216.4518347, "x": 20.34093978996596, "y": 5.297150465287258, "z": null, "yaw": 3.1228134312078843, "pitch": null, "roll": null}, "v": 2.0796736966009495, "accelerator_pedal_position": 0.2562866667819777, "brake_pedal_position": 0.0, "acceleration": 0.0045575557139744816, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021446828418384866, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141216.4518347} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2557665018668079, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1913935975297756, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0796736966009495, "gear": 1, "accelerator_pedal_position": 0.2562866667819777, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141216.4518347} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.089945554733276, "x": 16.34093978996596, "y": 0.29715046528725786, "z": null, "yaw": 3.1228134312078843, "pitch": null, "roll": null}, "v": 2.0796736966009495, "accelerator_pedal_position": 0.2562866667819777, "brake_pedal_position": 0.0, "acceleration": 0.0045575557139744816, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021446828418384866, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141216.4718347} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2560177002021059, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1913935975297756, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0796998151338992, "gear": 1, "accelerator_pedal_position": 0.2557665018668079, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141216.4718347} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.089945554733276, "x": 16.34093978996596, "y": 0.29715046528725786, "z": null, "yaw": 3.1228134312078843, "pitch": null, "roll": null}, "v": 2.0796736966009495, "accelerator_pedal_position": 0.2562866667819777, "brake_pedal_position": 0.0, "acceleration": 0.0045575557139744816, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021446828418384866, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141216.4918346} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2560177002021059, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1913935975297756, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.079757271254498, "gear": 1, "accelerator_pedal_position": 0.2560177002021059, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141216.4918346} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.089945554733276, "x": 16.34093978996596, "y": 0.29715046528725786, "z": null, "yaw": 3.1228134312078843, "pitch": null, "roll": null}, "v": 2.0796736966009495, "accelerator_pedal_position": 0.2562866667819777, "brake_pedal_position": 0.0, "acceleration": 0.0045575557139744816, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021446828418384866, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141216.5118346} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2560177002021059, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1913935975297756, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0798146221695952, "gear": 1, "accelerator_pedal_position": 0.2560177002021059, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141216.5118346} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.089945554733276, "x": 16.34093978996596, "y": 0.29715046528725786, "z": null, "yaw": 3.1228134312078843, "pitch": null, "roll": null}, "v": 2.0796736966009495, "accelerator_pedal_position": 0.2562866667819777, "brake_pedal_position": 0.0, "acceleration": 0.0045575557139744816, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021446828418384866, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141216.5318346} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2560177002021059, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1913935975297756, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.079871868070515, "gear": 1, "accelerator_pedal_position": 0.2560177002021059, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141216.5318346} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.089945554733276, "x": 16.34093978996596, "y": 0.29715046528725786, "z": null, "yaw": 3.1228134312078843, "pitch": null, "roll": null}, "v": 2.0796736966009495, "accelerator_pedal_position": 0.2562866667819777, "brake_pedal_position": 0.0, "acceleration": 0.0045575557139744816, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021446828418384866, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141216.5518346} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2560177002021059, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1913935975297756, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0799290091482354, "gear": 1, "accelerator_pedal_position": 0.2560177002021059, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141216.5518346} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141216.5618346, "x": 20.112201043588037, "y": 5.30132851811937, "z": null, "yaw": 3.123947816438548, "pitch": null, "roll": null}, "v": 2.079957540437983, "accelerator_pedal_position": 0.2560177002021059, "brake_pedal_position": 0.0, "acceleration": 0.002850515541014398, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021449755584353466, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141216.5718346} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2561401377580317, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1310653329521305, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0799860455933934, "gear": 1, "accelerator_pedal_position": 0.2560177002021059, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141216.5718346} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.1999454498291, "x": 16.112201043588037, "y": 0.30132851811937034, "z": null, "yaw": 3.123947816438548, "pitch": null, "roll": null}, "v": 2.079957540437983, "accelerator_pedal_position": 0.2560177002021059, "brake_pedal_position": 0.0, "acceleration": 0.002850515541014398, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021449755584353466, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141216.5918345} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25608381501174177, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1310653329521305, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0800582752811962, "gear": 1, "accelerator_pedal_position": 0.2561401377580317, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141216.5918345} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.1999454498291, "x": 16.112201043588037, "y": 0.30132851811937034, "z": null, "yaw": 3.123947816438548, "pitch": null, "roll": null}, "v": 2.079957540437983, "accelerator_pedal_position": 0.2560177002021059, "brake_pedal_position": 0.0, "acceleration": 0.002850515541014398, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021449755584353466, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141216.6118345} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25608381501174177, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1310653329521305, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0801233355849114, "gear": 1, "accelerator_pedal_position": 0.25608381501174177, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141216.6118345} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.1999454498291, "x": 16.112201043588037, "y": 0.30132851811937034, "z": null, "yaw": 3.123947816438548, "pitch": null, "roll": null}, "v": 2.079957540437983, "accelerator_pedal_position": 0.2560177002021059, "brake_pedal_position": 0.0, "acceleration": 0.002850515541014398, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021449755584353466, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141216.6318345} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25608381501174177, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1310653329521305, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.080188276749956, "gear": 1, "accelerator_pedal_position": 0.25608381501174177, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141216.6318345} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.1999454498291, "x": 16.112201043588037, "y": 0.30132851811937034, "z": null, "yaw": 3.123947816438548, "pitch": null, "roll": null}, "v": 2.079957540437983, "accelerator_pedal_position": 0.2560177002021059, "brake_pedal_position": 0.0, "acceleration": 0.002850515541014398, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021449755584353466, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141216.6518345} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25608381501174177, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1310653329521305, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0802530989928107, "gear": 1, "accelerator_pedal_position": 0.25608381501174177, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141216.6518345} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141216.6718345, "x": 19.883421207318793, "y": 5.305247714982521, "z": null, "yaw": 3.125082201669212, "pitch": null, "roll": null}, "v": 2.0803178025295694, "accelerator_pedal_position": 0.25608381501174177, "brake_pedal_position": 0.0, "acceleration": 0.0032307321016928903, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021453470820679495, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141216.6718345} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2582463446086156, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1697821872517669, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0803178025295694, "gear": 1, "accelerator_pedal_position": 0.25608381501174177, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141216.6718345} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.30994534492493, "x": 15.883421207318793, "y": 0.3052477149825208, "z": null, "yaw": 3.125082201669212, "pitch": null, "roll": null}, "v": 2.0803178025295694, "accelerator_pedal_position": 0.25608381501174177, "brake_pedal_position": 0.0, "acceleration": 0.0032307321016928903, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021453470820679495, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141216.6918344} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2572190824588121, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1697821872517669, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0806525799594384, "gear": 1, "accelerator_pedal_position": 0.2582463446086156, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141216.6918344} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.30994534492493, "x": 15.883421207318793, "y": 0.3052477149825208, "z": null, "yaw": 3.125082201669212, "pitch": null, "roll": null}, "v": 2.0803178025295694, "accelerator_pedal_position": 0.25608381501174177, "brake_pedal_position": 0.0, "acceleration": 0.0032307321016928903, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021453470820679495, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141216.7118344} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2572190824588121, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1697821872517669, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0808583953339945, "gear": 1, "accelerator_pedal_position": 0.2572190824588121, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141216.7118344} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.30994534492493, "x": 15.883421207318793, "y": 0.3052477149825208, "z": null, "yaw": 3.125082201669212, "pitch": null, "roll": null}, "v": 2.0803178025295694, "accelerator_pedal_position": 0.25608381501174177, "brake_pedal_position": 0.0, "acceleration": 0.0032307321016928903, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021453470820679495, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141216.7318344} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2572190824588121, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1697821872517669, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.081063833761105, "gear": 1, "accelerator_pedal_position": 0.2572190824588121, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141216.7318344} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.30994534492493, "x": 15.883421207318793, "y": 0.3052477149825208, "z": null, "yaw": 3.125082201669212, "pitch": null, "roll": null}, "v": 2.0803178025295694, "accelerator_pedal_position": 0.25608381501174177, "brake_pedal_position": 0.0, "acceleration": 0.0032307321016928903, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021453470820679495, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141216.7518344} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2572190824588121, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1697821872517669, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.081268895914269, "gear": 1, "accelerator_pedal_position": 0.2572190824588121, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141216.7518344} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.30994534492493, "x": 15.883421207318793, "y": 0.3052477149825208, "z": null, "yaw": 3.125082201669212, "pitch": null, "roll": null}, "v": 2.0803178025295694, "accelerator_pedal_position": 0.25608381501174177, "brake_pedal_position": 0.0, "acceleration": 0.0032307321016928903, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021453470820679495, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141216.7718344} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2572190824588121, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1697821872517669, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.081473582465845, "gear": 1, "accelerator_pedal_position": 0.2572190824588121, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141216.7718344} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141216.7818344, "x": 19.654546751860345, "y": 5.3089088208563275, "z": null, "yaw": 3.1262165868998757, "pitch": null, "roll": null}, "v": 2.081575785100837, "accelerator_pedal_position": 0.2572190824588121, "brake_pedal_position": 0.0, "acceleration": 0.010210898621351938, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021466443882945652, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141216.7918344} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25905849105564493, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2110445020643092, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0816778940870506, "gear": 1, "accelerator_pedal_position": 0.2572190824588121, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141216.7918344} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.41994524002075, "x": 15.654546751860345, "y": 0.30890882085632754, "z": null, "yaw": 3.1262165868998757, "pitch": null, "roll": null}, "v": 2.081575785100837, "accelerator_pedal_position": 0.2572190824588121, "brake_pedal_position": 0.0, "acceleration": 0.010210898621351938, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021466443882945652, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141216.8118343} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25819136310204427, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2110445020643092, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.082111652174184, "gear": 1, "accelerator_pedal_position": 0.25905849105564493, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141216.8118343} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.41994524002075, "x": 15.654546751860345, "y": 0.30890882085632754, "z": null, "yaw": 3.1262165868998757, "pitch": null, "roll": null}, "v": 2.081575785100837, "accelerator_pedal_position": 0.2572190824588121, "brake_pedal_position": 0.0, "acceleration": 0.010210898621351938, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021466443882945652, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141216.8318343} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25819136310204427, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2110445020643092, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0824362743070295, "gear": 1, "accelerator_pedal_position": 0.25819136310204427, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141216.8318343} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.41994524002075, "x": 15.654546751860345, "y": 0.30890882085632754, "z": null, "yaw": 3.1262165868998757, "pitch": null, "roll": null}, "v": 2.081575785100837, "accelerator_pedal_position": 0.2572190824588121, "brake_pedal_position": 0.0, "acceleration": 0.010210898621351938, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021466443882945652, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141216.8518343} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25819136310204427, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2110445020643092, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0827603016989795, "gear": 1, "accelerator_pedal_position": 0.25819136310204427, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141216.8518343} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.41994524002075, "x": 15.654546751860345, "y": 0.30890882085632754, "z": null, "yaw": 3.1262165868998757, "pitch": null, "roll": null}, "v": 2.081575785100837, "accelerator_pedal_position": 0.2572190824588121, "brake_pedal_position": 0.0, "acceleration": 0.010210898621351938, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021466443882945652, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141216.8718343} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25819136310204427, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2110445020643092, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0830837353976817, "gear": 1, "accelerator_pedal_position": 0.25819136310204427, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141216.8718343} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141216.8918343, "x": 19.425506253506192, "y": 5.3123126940690595, "z": null, "yaw": 3.1273509721305395, "pitch": null, "roll": null}, "v": 2.0834065764490943, "accelerator_pedal_position": 0.25819136310204427, "brake_pedal_position": 0.0, "acceleration": 0.016119860937408526, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021485324088999187, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141216.8918343} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.259807320964069, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2553601856856436, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0834065764490943, "gear": 1, "accelerator_pedal_position": 0.25819136310204427, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141216.8918343} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.52994513511658, "x": 15.425506253506192, "y": 0.3123126940690595, "z": null, "yaw": 3.1273509721305395, "pitch": null, "roll": null}, "v": 2.0834065764490943, "accelerator_pedal_position": 0.25819136310204427, "brake_pedal_position": 0.0, "acceleration": 0.016119860937408526, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021485324088999187, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141216.9118342} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25905060097207255, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2553601856856436, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.083930728043569, "gear": 1, "accelerator_pedal_position": 0.259807320964069, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141216.9118342} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.52994513511658, "x": 15.425506253506192, "y": 0.3123126940690595, "z": null, "yaw": 3.1273509721305395, "pitch": null, "roll": null}, "v": 2.0834065764490943, "accelerator_pedal_position": 0.25819136310204427, "brake_pedal_position": 0.0, "acceleration": 0.016119860937408526, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021485324088999187, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141216.9318342} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25905060097207255, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2553601856856436, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.084359372398865, "gear": 1, "accelerator_pedal_position": 0.25905060097207255, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141216.9318342} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.52994513511658, "x": 15.425506253506192, "y": 0.3123126940690595, "z": null, "yaw": 3.1273509721305395, "pitch": null, "roll": null}, "v": 2.0834065764490943, "accelerator_pedal_position": 0.25819136310204427, "brake_pedal_position": 0.0, "acceleration": 0.016119860937408526, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021485324088999187, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141216.9518342} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25905060097207255, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2553601856856436, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.084787231108961, "gear": 1, "accelerator_pedal_position": 0.25905060097207255, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141216.9518342} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.52994513511658, "x": 15.425506253506192, "y": 0.3123126940690595, "z": null, "yaw": 3.1273509721305395, "pitch": null, "roll": null}, "v": 2.0834065764490943, "accelerator_pedal_position": 0.25819136310204427, "brake_pedal_position": 0.0, "acceleration": 0.016119860937408526, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021485324088999187, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141216.9718342} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25905060097207255, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2553601856856436, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0852143055406422, "gear": 1, "accelerator_pedal_position": 0.25905060097207255, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141216.9718342} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.52994513511658, "x": 15.425506253506192, "y": 0.3123126940690595, "z": null, "yaw": 3.1273509721305395, "pitch": null, "roll": null}, "v": 2.0834065764490943, "accelerator_pedal_position": 0.25819136310204427, "brake_pedal_position": 0.0, "acceleration": 0.016119860937408526, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021485324088999187, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141216.9918342} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25905060097207255, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2553601856856436, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0858534496508083, "gear": 1, "accelerator_pedal_position": 0.25905060097207255, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141216.9918342} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141217.0018342, "x": 19.196226320270068, "y": 5.315459975015511, "z": null, "yaw": 3.1284853573612033, "pitch": null, "roll": null}, "v": 2.0858534496508083, "accelerator_pedal_position": 0.25905060097207255, "brake_pedal_position": 0.0, "acceleration": 0.021265737458711187, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021510557696465815, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141217.0118341} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2589736588966489, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2264016486176745, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.086481223453076, "gear": 1, "accelerator_pedal_position": 0.2589736588966489, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141217.0118341} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.6399450302124, "x": 15.196226320270068, "y": 0.3154599750155107, "z": null, "yaw": 3.1284853573612033, "pitch": null, "roll": null}, "v": 2.0858534496508083, "accelerator_pedal_position": 0.25905060097207255, "brake_pedal_position": 0.0, "acceleration": 0.021265737458711187, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021510557696465815, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141217.0318341} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2590273921149403, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2264016486176745, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.086481223453076, "gear": 1, "accelerator_pedal_position": 0.2589736588966489, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141217.0318341} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.6399450302124, "x": 15.196226320270068, "y": 0.3154599750155107, "z": null, "yaw": 3.1284853573612033, "pitch": null, "roll": null}, "v": 2.0858534496508083, "accelerator_pedal_position": 0.25905060097207255, "brake_pedal_position": 0.0, "acceleration": 0.021265737458711187, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021510557696465815, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141217.051834} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2590273921149403, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2264016486176745, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0871125369926786, "gear": 1, "accelerator_pedal_position": 0.2590273921149403, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141217.051834} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.6399450302124, "x": 15.196226320270068, "y": 0.3154599750155107, "z": null, "yaw": 3.1284853573612033, "pitch": null, "roll": null}, "v": 2.0858534496508083, "accelerator_pedal_position": 0.25905060097207255, "brake_pedal_position": 0.0, "acceleration": 0.021265737458711187, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021510557696465815, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141217.081834} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2590273921149403, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2264016486176745, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.087532448010919, "gear": 1, "accelerator_pedal_position": 0.2590273921149403, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141217.081834} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.6399450302124, "x": 15.196226320270068, "y": 0.3154599750155107, "z": null, "yaw": 3.1284853573612033, "pitch": null, "roll": null}, "v": 2.0858534496508083, "accelerator_pedal_position": 0.25905060097207255, "brake_pedal_position": 0.0, "acceleration": 0.021265737458711187, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021510557696465815, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141217.091834} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2590273921149403, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2264016486176745, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0877421146219475, "gear": 1, "accelerator_pedal_position": 0.2590273921149403, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141217.091834} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141217.111834, "x": 18.966685230610494, "y": 5.318350408847515, "z": null, "yaw": 3.129619742591867, "pitch": null, "roll": null}, "v": 2.088160870887117, "accelerator_pedal_position": 0.2590273921149403, "brake_pedal_position": 0.0, "acceleration": 0.02090899894698056, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021534353192569328, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141217.121834} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25998507735771015, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.237859252748014, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.088369960876587, "gear": 1, "accelerator_pedal_position": 0.2590273921149403, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141217.121834} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.74994492530823, "x": 14.966685230610494, "y": 0.31835040884751464, "z": null, "yaw": 3.129619742591867, "pitch": null, "roll": null}, "v": 2.088160870887117, "accelerator_pedal_position": 0.2590273921149403, "brake_pedal_position": 0.0, "acceleration": 0.02090899894698056, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021534353192569328, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141217.131834} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.259545164786514, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.237859252748014, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0886387143216565, "gear": 1, "accelerator_pedal_position": 0.25998507735771015, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141217.131834} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.74994492530823, "x": 14.966685230610494, "y": 0.31835040884751464, "z": null, "yaw": 3.129619742591867, "pitch": null, "roll": null}, "v": 2.088160870887117, "accelerator_pedal_position": 0.2590273921149403, "brake_pedal_position": 0.0, "acceleration": 0.02090899894698056, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021534353192569328, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141217.151834} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.259545164786514, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.237859252748014, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0891205176803975, "gear": 1, "accelerator_pedal_position": 0.259545164786514, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141217.151834} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.74994492530823, "x": 14.966685230610494, "y": 0.31835040884751464, "z": null, "yaw": 3.129619742591867, "pitch": null, "roll": null}, "v": 2.088160870887117, "accelerator_pedal_position": 0.2590273921149403, "brake_pedal_position": 0.0, "acceleration": 0.02090899894698056, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021534353192569328, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141217.171834} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.259545164786514, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.237859252748014, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0896014370467415, "gear": 1, "accelerator_pedal_position": 0.259545164786514, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141217.171834} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.74994492530823, "x": 14.966685230610494, "y": 0.31835040884751464, "z": null, "yaw": 3.129619742591867, "pitch": null, "roll": null}, "v": 2.088160870887117, "accelerator_pedal_position": 0.2590273921149403, "brake_pedal_position": 0.0, "acceleration": 0.02090899894698056, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021534353192569328, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141217.191834} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.259545164786514, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.237859252748014, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0900814739501286, "gear": 1, "accelerator_pedal_position": 0.259545164786514, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141217.191834} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.74994492530823, "x": 14.966685230610494, "y": 0.31835040884751464, "z": null, "yaw": 3.129619742591867, "pitch": null, "roll": null}, "v": 2.088160870887117, "accelerator_pedal_position": 0.2590273921149403, "brake_pedal_position": 0.0, "acceleration": 0.02090899894698056, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021534353192569328, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141217.211834} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.259545164786514, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.237859252748014, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.090799878027165, "gear": 1, "accelerator_pedal_position": 0.259545164786514, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141217.211834} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141217.221834, "x": 18.73687095565505, "y": 5.32098354350438, "z": null, "yaw": 3.130754127822531, "pitch": null, "roll": null}, "v": 2.090799878027165, "accelerator_pedal_position": 0.259545164786514, "brake_pedal_position": 0.0, "acceleration": 0.023902844714770166, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02156156819914464, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141217.231834} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2598484391266301, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2209725092341195, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.091296670095651, "gear": 1, "accelerator_pedal_position": 0.2598484391266301, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141217.231834} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.85994482040405, "x": 14.73687095565505, "y": 0.3209835435043802, "z": null, "yaw": 3.130754127822531, "pitch": null, "roll": null}, "v": 2.090799878027165, "accelerator_pedal_position": 0.259545164786514, "brake_pedal_position": 0.0, "acceleration": 0.023902844714770166, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02156156819914464, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141217.251834} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25972247859161746, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2209725092341195, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0918036149473322, "gear": 1, "accelerator_pedal_position": 0.25972247859161746, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141217.251834} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.85994482040405, "x": 14.73687095565505, "y": 0.3209835435043802, "z": null, "yaw": 3.130754127822531, "pitch": null, "roll": null}, "v": 2.090799878027165, "accelerator_pedal_position": 0.259545164786514, "brake_pedal_position": 0.0, "acceleration": 0.023902844714770166, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02156156819914464, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141217.271834} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25972247859161746, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2209725092341195, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.092052803815484, "gear": 1, "accelerator_pedal_position": 0.25972247859161746, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141217.271834} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.85994482040405, "x": 14.73687095565505, "y": 0.3209835435043802, "z": null, "yaw": 3.130754127822531, "pitch": null, "roll": null}, "v": 2.090799878027165, "accelerator_pedal_position": 0.259545164786514, "brake_pedal_position": 0.0, "acceleration": 0.023902844714770166, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02156156819914464, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141217.2918339} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25972247859161746, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2209725092341195, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0927989981020088, "gear": 1, "accelerator_pedal_position": 0.25972247859161746, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141217.2918339} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.85994482040405, "x": 14.73687095565505, "y": 0.3209835435043802, "z": null, "yaw": 3.130754127822531, "pitch": null, "roll": null}, "v": 2.090799878027165, "accelerator_pedal_position": 0.259545164786514, "brake_pedal_position": 0.0, "acceleration": 0.023902844714770166, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02156156819914464, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141217.3118339} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25972247859161746, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2209725092341195, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.093295319337292, "gear": 1, "accelerator_pedal_position": 0.25972247859161746, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141217.3118339} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141217.3318338, "x": 18.50675782962606, "y": 5.32335903341046, "z": null, "yaw": 3.1318885130531946, "pitch": null, "roll": null}, "v": 2.0935431380602036, "accelerator_pedal_position": 0.25972247859161746, "brake_pedal_position": 0.0, "acceleration": 0.024759105585409225, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02158985832337507, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141217.3418338} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26022380128489514, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.20335214319727, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0937907291160576, "gear": 1, "accelerator_pedal_position": 0.25972247859161746, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141217.3418338} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.96994471549988, "x": 14.50675782962606, "y": 0.32335903341046013, "z": null, "yaw": 3.1318885130531946, "pitch": null, "roll": null}, "v": 2.0935431380602036, "accelerator_pedal_position": 0.25972247859161746, "brake_pedal_position": 0.0, "acceleration": 0.024759105585409225, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02158985832337507, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141217.3518338} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2600042723050039, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.20335214319727, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0940694253700722, "gear": 1, "accelerator_pedal_position": 0.26022380128489514, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141217.3518338} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.96994471549988, "x": 14.50675782962606, "y": 0.32335903341046013, "z": null, "yaw": 3.1318885130531946, "pitch": null, "roll": null}, "v": 2.0935431380602036, "accelerator_pedal_position": 0.25972247859161746, "brake_pedal_position": 0.0, "acceleration": 0.024759105585409225, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02158985832337507, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141217.3718338} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2600042723050039, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.20335214319727, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0945986213960937, "gear": 1, "accelerator_pedal_position": 0.2600042723050039, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141217.3718338} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.96994471549988, "x": 14.50675782962606, "y": 0.32335903341046013, "z": null, "yaw": 3.1318885130531946, "pitch": null, "roll": null}, "v": 2.0935431380602036, "accelerator_pedal_position": 0.25972247859161746, "brake_pedal_position": 0.0, "acceleration": 0.024759105585409225, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02158985832337507, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141217.3918338} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2600042723050039, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.20335214319727, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.095126845319635, "gear": 1, "accelerator_pedal_position": 0.2600042723050039, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141217.3918338} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.96994471549988, "x": 14.50675782962606, "y": 0.32335903341046013, "z": null, "yaw": 3.1318885130531946, "pitch": null, "roll": null}, "v": 2.0935431380602036, "accelerator_pedal_position": 0.25972247859161746, "brake_pedal_position": 0.0, "acceleration": 0.024759105585409225, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02158985832337507, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141217.4118338} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2600042723050039, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.20335214319727, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.095917362174302, "gear": 1, "accelerator_pedal_position": 0.2600042723050039, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141217.4118338} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.96994471549988, "x": 14.50675782962606, "y": 0.32335903341046013, "z": null, "yaw": 3.1318885130531946, "pitch": null, "roll": null}, "v": 2.0935431380602036, "accelerator_pedal_position": 0.25972247859161746, "brake_pedal_position": 0.0, "acceleration": 0.024759105585409225, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02158985832337507, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141217.4318337} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2600042723050039, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.20335214319727, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.096180383553371, "gear": 1, "accelerator_pedal_position": 0.2600042723050039, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141217.4318337} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141217.4418337, "x": 18.276332887220452, "y": 5.325476325091725, "z": null, "yaw": 3.1330228982838584, "pitch": null, "roll": null}, "v": 2.0964431631606177, "accelerator_pedal_position": 0.2600042723050039, "brake_pedal_position": 0.0, "acceleration": 0.026253804384614388, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021619765101942905, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141217.4518337} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2607611254409438, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2141706240847554, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.096705701204464, "gear": 1, "accelerator_pedal_position": 0.2600042723050039, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141217.4518337} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.0799446105957, "x": 14.276332887220452, "y": 0.3254763250917252, "z": null, "yaw": 3.1330228982838584, "pitch": null, "roll": null}, "v": 2.0964431631606177, "accelerator_pedal_position": 0.2600042723050039, "brake_pedal_position": 0.0, "acceleration": 0.026253804384614388, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021619765101942905, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141217.4718337} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26042102468513134, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2141706240847554, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0973246165862736, "gear": 1, "accelerator_pedal_position": 0.2607611254409438, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141217.4718337} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.0799446105957, "x": 14.276332887220452, "y": 0.3254763250917252, "z": null, "yaw": 3.1330228982838584, "pitch": null, "roll": null}, "v": 2.0964431631606177, "accelerator_pedal_position": 0.2600042723050039, "brake_pedal_position": 0.0, "acceleration": 0.026253804384614388, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021619765101942905, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141217.4918337} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26042102468513134, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2141706240847554, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0981871470314033, "gear": 1, "accelerator_pedal_position": 0.26042102468513134, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141217.4918337} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.0799446105957, "x": 14.276332887220452, "y": 0.3254763250917252, "z": null, "yaw": 3.1330228982838584, "pitch": null, "roll": null}, "v": 2.0964431631606177, "accelerator_pedal_position": 0.2600042723050039, "brake_pedal_position": 0.0, "acceleration": 0.026253804384614388, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021619765101942905, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141217.5118337} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26042102468513134, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2141706240847554, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.099619417715885, "gear": 1, "accelerator_pedal_position": 0.26042102468513134, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141217.5118337} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141217.5518336, "x": 18.045572344152724, "y": 5.3273349067633395, "z": null, "yaw": 3.134157283514522, "pitch": null, "roll": null}, "v": 2.099619417715885, "accelerator_pedal_position": 0.26042102468513134, "brake_pedal_position": 0.0, "acceleration": 0.028566416403780603, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021652520522454914, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141217.5618336} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2610432469294174, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.214395055860796, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.099905081879923, "gear": 1, "accelerator_pedal_position": 0.26042102468513134, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141217.5618336} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.18994450569153, "x": 14.045572344152724, "y": 0.32733490676333954, "z": null, "yaw": 3.134157283514522, "pitch": null, "roll": null}, "v": 2.099619417715885, "accelerator_pedal_position": 0.26042102468513134, "brake_pedal_position": 0.0, "acceleration": 0.028566416403780603, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021652520522454914, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141217.5918336} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2607692049890809, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.214395055860796, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.101200453812735, "gear": 1, "accelerator_pedal_position": 0.2610432469294174, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141217.5918336} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.18994450569153, "x": 14.045572344152724, "y": 0.32733490676333954, "z": null, "yaw": 3.134157283514522, "pitch": null, "roll": null}, "v": 2.099619417715885, "accelerator_pedal_position": 0.26042102468513134, "brake_pedal_position": 0.0, "acceleration": 0.028566416403780603, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021652520522454914, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141217.6118336} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2607692049890809, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.214395055860796, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1018121137372243, "gear": 1, "accelerator_pedal_position": 0.2607692049890809, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141217.6118336} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.18994450569153, "x": 14.045572344152724, "y": 0.32733490676333954, "z": null, "yaw": 3.134157283514522, "pitch": null, "roll": null}, "v": 2.099619417715885, "accelerator_pedal_position": 0.26042102468513134, "brake_pedal_position": 0.0, "acceleration": 0.028566416403780603, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021652520522454914, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141217.6318336} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2607692049890809, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.214395055860796, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.102117521576028, "gear": 1, "accelerator_pedal_position": 0.2607692049890809, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141217.6318336} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.18994450569153, "x": 14.045572344152724, "y": 0.32733490676333954, "z": null, "yaw": 3.134157283514522, "pitch": null, "roll": null}, "v": 2.099619417715885, "accelerator_pedal_position": 0.26042102468513134, "brake_pedal_position": 0.0, "acceleration": 0.028566416403780603, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021652520522454914, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141217.6518335} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2607692049890809, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.214395055860796, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1030320594812704, "gear": 1, "accelerator_pedal_position": 0.2607692049890809, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141217.6518335} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141217.6618335, "x": 17.814448180246224, "y": 5.328934216011814, "z": null, "yaw": 3.135291668745186, "pitch": null, "roll": null}, "v": 2.1030320594812704, "accelerator_pedal_position": 0.2607692049890809, "brake_pedal_position": 0.0, "acceleration": 0.03042848977563173, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.0216877137080567, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141217.6718335} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26100377283250287, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.17352637115201, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.103640349140896, "gear": 1, "accelerator_pedal_position": 0.2607692049890809, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141217.6718335} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.29994440078735, "x": 13.814448180246224, "y": 0.32893421601181405, "z": null, "yaw": 3.135291668745186, "pitch": null, "roll": null}, "v": 2.1030320594812704, "accelerator_pedal_position": 0.2607692049890809, "brake_pedal_position": 0.0, "acceleration": 0.03042848977563173, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.0216877137080567, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141217.6918335} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2609160017034342, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.17352637115201, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1039587344965036, "gear": 1, "accelerator_pedal_position": 0.26100377283250287, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141217.6918335} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.29994440078735, "x": 13.814448180246224, "y": 0.32893421601181405, "z": null, "yaw": 3.135291668745186, "pitch": null, "roll": null}, "v": 2.1030320594812704, "accelerator_pedal_position": 0.2607692049890809, "brake_pedal_position": 0.0, "acceleration": 0.03042848977563173, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.0216877137080567, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141217.7118335} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2609160017034342, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.17352637115201, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.104583659648383, "gear": 1, "accelerator_pedal_position": 0.2609160017034342, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141217.7118335} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.29994440078735, "x": 13.814448180246224, "y": 0.32893421601181405, "z": null, "yaw": 3.135291668745186, "pitch": null, "roll": null}, "v": 2.1030320594812704, "accelerator_pedal_position": 0.2607692049890809, "brake_pedal_position": 0.0, "acceleration": 0.03042848977563173, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.0216877137080567, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141217.7318335} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2609160017034342, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.17352637115201, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.105207434361231, "gear": 1, "accelerator_pedal_position": 0.2609160017034342, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141217.7318335} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.29994440078735, "x": 13.814448180246224, "y": 0.32893421601181405, "z": null, "yaw": 3.135291668745186, "pitch": null, "roll": null}, "v": 2.1030320594812704, "accelerator_pedal_position": 0.2607692049890809, "brake_pedal_position": 0.0, "acceleration": 0.03042848977563173, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.0216877137080567, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141217.7518334} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2609160017034342, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.17352637115201, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1061409436491063, "gear": 1, "accelerator_pedal_position": 0.2609160017034342, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141217.7518334} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141217.7718334, "x": 17.582947911518108, "y": 5.330273506887867, "z": null, "yaw": 3.1364260539758497, "pitch": null, "roll": null}, "v": 2.1064515403162947, "accelerator_pedal_position": 0.2609160017034342, "brake_pedal_position": 0.0, "acceleration": 0.031031052713640095, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021722977422200213, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141217.7718334} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26136238640134857, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1530310488078317, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1064515403162947, "gear": 1, "accelerator_pedal_position": 0.2609160017034342, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141217.7718334} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.40994429588318, "x": 13.582947911518108, "y": 0.33027350688786683, "z": null, "yaw": 3.1364260539758497, "pitch": null, "roll": null}, "v": 2.1064515403162947, "accelerator_pedal_position": 0.2609160017034342, "brake_pedal_position": 0.0, "acceleration": 0.031031052713640095, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021722977422200213, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141217.7918334} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2611738158054149, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1530310488078317, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1071276478571686, "gear": 1, "accelerator_pedal_position": 0.26136238640134857, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141217.7918334} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.40994429588318, "x": 13.582947911518108, "y": 0.33027350688786683, "z": null, "yaw": 3.1364260539758497, "pitch": null, "roll": null}, "v": 2.1064515403162947, "accelerator_pedal_position": 0.2609160017034342, "brake_pedal_position": 0.0, "acceleration": 0.031031052713640095, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021722977422200213, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141217.8118334} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2611738158054149, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1530310488078317, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1081041503911795, "gear": 1, "accelerator_pedal_position": 0.2611738158054149, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141217.8118334} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.40994429588318, "x": 13.582947911518108, "y": 0.33027350688786683, "z": null, "yaw": 3.1364260539758497, "pitch": null, "roll": null}, "v": 2.1064515403162947, "accelerator_pedal_position": 0.2609160017034342, "brake_pedal_position": 0.0, "acceleration": 0.031031052713640095, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021722977422200213, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141217.8318334} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2611738158054149, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1530310488078317, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.108753653148507, "gear": 1, "accelerator_pedal_position": 0.2611738158054149, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141217.8318334} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.40994429588318, "x": 13.582947911518108, "y": 0.33027350688786683, "z": null, "yaw": 3.1364260539758497, "pitch": null, "roll": null}, "v": 2.1064515403162947, "accelerator_pedal_position": 0.2609160017034342, "brake_pedal_position": 0.0, "acceleration": 0.031031052713640095, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021722977422200213, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141217.8518333} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2611738158054149, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1530310488078317, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1094019591405515, "gear": 1, "accelerator_pedal_position": 0.2611738158054149, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141217.8518333} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.40994429588318, "x": 13.582947911518108, "y": 0.33027350688786683, "z": null, "yaw": 3.1364260539758497, "pitch": null, "roll": null}, "v": 2.1064515403162947, "accelerator_pedal_position": 0.2609160017034342, "brake_pedal_position": 0.0, "acceleration": 0.031031052713640095, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021722977422200213, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141217.8718333} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2611738158054149, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1530310488078317, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1100490704044144, "gear": 1, "accelerator_pedal_position": 0.2611738158054149, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141217.8718333} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141217.8818333, "x": 17.35105949404631, "y": 5.331351983684937, "z": null, "yaw": 3.1375604392065135, "pitch": null, "roll": null}, "v": 2.1100490704044144, "accelerator_pedal_position": 0.2611738158054149, "brake_pedal_position": 0.0, "acceleration": 0.032310824468476884, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021760077285825928, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141217.8918333} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2617795453326069, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1300313747259403, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.110372178649099, "gear": 1, "accelerator_pedal_position": 0.2611738158054149, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141217.8918333} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.519944190979004, "x": 13.35105949404631, "y": 0.3313519836849368, "z": null, "yaw": 3.1375604392065135, "pitch": null, "roll": null}, "v": 2.1100490704044144, "accelerator_pedal_position": 0.2611738158054149, "brake_pedal_position": 0.0, "acceleration": 0.032310824468476884, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021760077285825928, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141217.9118333} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2615163647697152, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1300313747259403, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1114531864635393, "gear": 1, "accelerator_pedal_position": 0.2617795453326069, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141217.9118333} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.519944190979004, "x": 13.35105949404631, "y": 0.3313519836849368, "z": null, "yaw": 3.1375604392065135, "pitch": null, "roll": null}, "v": 2.1100490704044144, "accelerator_pedal_position": 0.2611738158054149, "brake_pedal_position": 0.0, "acceleration": 0.032310824468476884, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021760077285825928, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141217.9318333} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2615163647697152, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1300313747259403, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1121393153986565, "gear": 1, "accelerator_pedal_position": 0.2615163647697152, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141217.9318333} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.519944190979004, "x": 13.35105949404631, "y": 0.3313519836849368, "z": null, "yaw": 3.1375604392065135, "pitch": null, "roll": null}, "v": 2.1100490704044144, "accelerator_pedal_position": 0.2611738158054149, "brake_pedal_position": 0.0, "acceleration": 0.032310824468476884, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021760077285825928, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141217.9518332} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2615163647697152, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1300313747259403, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.112824179155743, "gear": 1, "accelerator_pedal_position": 0.2615163647697152, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141217.9518332} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.519944190979004, "x": 13.35105949404631, "y": 0.3313519836849368, "z": null, "yaw": 3.1375604392065135, "pitch": null, "roll": null}, "v": 2.1100490704044144, "accelerator_pedal_position": 0.2611738158054149, "brake_pedal_position": 0.0, "acceleration": 0.032310824468476884, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021760077285825928, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141217.9718332} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2615163647697152, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1300313747259403, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.11316613726307, "gear": 1, "accelerator_pedal_position": 0.2615163647697152, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141217.9718332} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141217.9918332, "x": 17.11876478067137, "y": 5.332168831693339, "z": null, "yaw": 3.1386948244371773, "pitch": null, "roll": null}, "v": 2.113849107274784, "accelerator_pedal_position": 0.2615163647697152, "brake_pedal_position": 0.0, "acceleration": 0.034101243963716665, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021799265519477945, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141217.9918332} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26206686958495995, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0777775039802158, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.113849107274784, "gear": 1, "accelerator_pedal_position": 0.2615163647697152, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141217.9918332} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.62994408607483, "x": 13.11876478067137, "y": 0.33216883169333933, "z": null, "yaw": 3.1386948244371773, "pitch": null, "roll": null}, "v": 2.113849107274784, "accelerator_pedal_position": 0.2615163647697152, "brake_pedal_position": 0.0, "acceleration": 0.034101243963716665, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021799265519477945, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141218.0118332} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26183142995773667, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0777775039802158, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1145995988165547, "gear": 1, "accelerator_pedal_position": 0.26206686958495995, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141218.0118332} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.62994408607483, "x": 13.11876478067137, "y": 0.33216883169333933, "z": null, "yaw": 3.1386948244371773, "pitch": null, "roll": null}, "v": 2.113849107274784, "accelerator_pedal_position": 0.2615163647697152, "brake_pedal_position": 0.0, "acceleration": 0.034101243963716665, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021799265519477945, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141218.0318332} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26183142995773667, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0777775039802158, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1153192893951145, "gear": 1, "accelerator_pedal_position": 0.26183142995773667, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141218.0318332} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.62994408607483, "x": 13.11876478067137, "y": 0.33216883169333933, "z": null, "yaw": 3.1386948244371773, "pitch": null, "roll": null}, "v": 2.113849107274784, "accelerator_pedal_position": 0.2615163647697152, "brake_pedal_position": 0.0, "acceleration": 0.034101243963716665, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021799265519477945, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141218.0518332} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26183142995773667, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0777775039802158, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.116396336009824, "gear": 1, "accelerator_pedal_position": 0.26183142995773667, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141218.0518332} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.62994408607483, "x": 13.11876478067137, "y": 0.33216883169333933, "z": null, "yaw": 3.1386948244371773, "pitch": null, "roll": null}, "v": 2.113849107274784, "accelerator_pedal_position": 0.2615163647697152, "brake_pedal_position": 0.0, "acceleration": 0.034101243963716665, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021799265519477945, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141218.0718331} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26183142995773667, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0777775039802158, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.11675468886907, "gear": 1, "accelerator_pedal_position": 0.26183142995773667, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141218.0718331} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.62994408607483, "x": 13.11876478067137, "y": 0.33216883169333933, "z": null, "yaw": 3.1386948244371773, "pitch": null, "roll": null}, "v": 2.113849107274784, "accelerator_pedal_position": 0.2615163647697152, "brake_pedal_position": 0.0, "acceleration": 0.034101243963716665, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021799265519477945, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141218.091833} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26183142995773667, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0777775039802158, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1178277633303866, "gear": 1, "accelerator_pedal_position": 0.26183142995773667, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141218.091833} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141218.101833, "x": 16.88604142770298, "y": 5.332723185239747, "z": null, "yaw": 3.139829209667841, "pitch": null, "roll": null}, "v": 2.1178277633303866, "accelerator_pedal_position": 0.26183142995773667, "brake_pedal_position": 0.0, "acceleration": 0.03570310471800492, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02184029578009034, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141218.111833} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26286604983637657, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0986335876163487, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1194477221891987, "gear": 1, "accelerator_pedal_position": 0.26286604983637657, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141218.111833} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.739943981170654, "x": 12.886041427702981, "y": 0.33272318523974675, "z": null, "yaw": 3.139829209667841, "pitch": null, "roll": null}, "v": 2.1178277633303866, "accelerator_pedal_position": 0.26183142995773667, "brake_pedal_position": 0.0, "acceleration": 0.03570310471800492, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02184029578009034, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141218.141833} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26240135797981196, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0986335876163487, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1194477221891987, "gear": 1, "accelerator_pedal_position": 0.26286604983637657, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141218.141833} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.739943981170654, "x": 12.886041427702981, "y": 0.33272318523974675, "z": null, "yaw": 3.139829209667841, "pitch": null, "roll": null}, "v": 2.1178277633303866, "accelerator_pedal_position": 0.26183142995773667, "brake_pedal_position": 0.0, "acceleration": 0.03570310471800492, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02184029578009034, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141218.171833} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26240135797981196, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0986335876163487, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.121428823002595, "gear": 1, "accelerator_pedal_position": 0.26240135797981196, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141218.171833} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.739943981170654, "x": 12.886041427702981, "y": 0.33272318523974675, "z": null, "yaw": 3.139829209667841, "pitch": null, "roll": null}, "v": 2.1178277633303866, "accelerator_pedal_position": 0.26183142995773667, "brake_pedal_position": 0.0, "acceleration": 0.03570310471800492, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02184029578009034, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141218.191833} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26240135797981196, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0986335876163487, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.121428823002595, "gear": 1, "accelerator_pedal_position": 0.26240135797981196, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141218.191833} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141218.211833, "x": 16.652860067733865, "y": 5.333014106753507, "z": null, "yaw": 3.140963594898505, "pitch": null, "roll": null}, "v": 2.122207112014663, "accelerator_pedal_position": 0.26240135797981196, "brake_pedal_position": 0.0, "acceleration": 0.038860501510235346, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02188545822070276, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141218.211833} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26298416342562037, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.032035342659219, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.122207112014663, "gear": 1, "accelerator_pedal_position": 0.26240135797981196, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141218.211833} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.84994387626648, "x": 12.652860067733865, "y": 0.33301410675350684, "z": null, "yaw": 3.140963594898505, "pitch": null, "roll": null}, "v": 2.122207112014663, "accelerator_pedal_position": 0.26240135797981196, "brake_pedal_position": 0.0, "acceleration": 0.038860501510235346, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02188545822070276, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141218.231833} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26273746763072314, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.032035342659219, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1230567797918622, "gear": 1, "accelerator_pedal_position": 0.26298416342562037, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141218.231833} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.84994387626648, "x": 12.652860067733865, "y": 0.33301410675350684, "z": null, "yaw": 3.140963594898505, "pitch": null, "roll": null}, "v": 2.122207112014663, "accelerator_pedal_position": 0.26240135797981196, "brake_pedal_position": 0.0, "acceleration": 0.038860501510235346, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02188545822070276, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141218.251833} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26273746763072314, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.032035342659219, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1238740544256873, "gear": 1, "accelerator_pedal_position": 0.26273746763072314, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141218.251833} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.84994387626648, "x": 12.652860067733865, "y": 0.33301410675350684, "z": null, "yaw": 3.140963594898505, "pitch": null, "roll": null}, "v": 2.122207112014663, "accelerator_pedal_position": 0.26240135797981196, "brake_pedal_position": 0.0, "acceleration": 0.038860501510235346, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02188545822070276, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141218.271833} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26273746763072314, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.032035342659219, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.124689818235226, "gear": 1, "accelerator_pedal_position": 0.26273746763072314, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141218.271833} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.84994387626648, "x": 12.652860067733865, "y": 0.33301410675350684, "z": null, "yaw": 3.140963594898505, "pitch": null, "roll": null}, "v": 2.122207112014663, "accelerator_pedal_position": 0.26240135797981196, "brake_pedal_position": 0.0, "acceleration": 0.038860501510235346, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02188545822070276, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141218.291833} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26273746763072314, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.032035342659219, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.125504073747341, "gear": 1, "accelerator_pedal_position": 0.26273746763072314, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141218.291833} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.84994387626648, "x": 12.652860067733865, "y": 0.33301410675350684, "z": null, "yaw": 3.140963594898505, "pitch": null, "roll": null}, "v": 2.122207112014663, "accelerator_pedal_position": 0.26240135797981196, "brake_pedal_position": 0.0, "acceleration": 0.038860501510235346, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02188545822070276, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141218.311833} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26273746763072314, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.032035342659219, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1271280699707757, "gear": 1, "accelerator_pedal_position": 0.26273746763072314, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141218.311833} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141218.321833, "x": 16.41918971859447, "y": 5.3330405652647235, "z": null, "yaw": 3.1420979801291686, "pitch": null, "roll": null}, "v": 2.126722634477494, "accelerator_pedal_position": 0.26273746763072314, "brake_pedal_position": 0.0, "acceleration": 0.0405435493281559, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021932024966071512, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141218.331833} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26353405660292434, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0269524908970245, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1271280699707757, "gear": 1, "accelerator_pedal_position": 0.26273746763072314, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141218.331833} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.959943771362305, "x": 12.41918971859447, "y": 0.3330405652647235, "z": null, "yaw": 3.1420979801291686, "pitch": null, "roll": null}, "v": 2.126722634477494, "accelerator_pedal_position": 0.26273746763072314, "brake_pedal_position": 0.0, "acceleration": 0.0405435493281559, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021932024966071512, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141218.3518329} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2631865483473491, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0269524908970245, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1284696295697407, "gear": 1, "accelerator_pedal_position": 0.2631865483473491, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141218.3518329} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.959943771362305, "x": 12.41918971859447, "y": 0.3330405652647235, "z": null, "yaw": 3.1420979801291686, "pitch": null, "roll": null}, "v": 2.126722634477494, "accelerator_pedal_position": 0.26273746763072314, "brake_pedal_position": 0.0, "acceleration": 0.0405435493281559, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021932024966071512, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141218.3718328} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2631865483473491, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0269524908970245, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.128901515730265, "gear": 1, "accelerator_pedal_position": 0.2631865483473491, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141218.3718328} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.959943771362305, "x": 12.41918971859447, "y": 0.3330405652647235, "z": null, "yaw": 3.1420979801291686, "pitch": null, "roll": null}, "v": 2.126722634477494, "accelerator_pedal_position": 0.26273746763072314, "brake_pedal_position": 0.0, "acceleration": 0.0405435493281559, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021932024966071512, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141218.3918328} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2631865483473491, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0269524908970245, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.129764088945038, "gear": 1, "accelerator_pedal_position": 0.2631865483473491, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141218.3918328} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.959943771362305, "x": 12.41918971859447, "y": 0.3330405652647235, "z": null, "yaw": 3.1420979801291686, "pitch": null, "roll": null}, "v": 2.126722634477494, "accelerator_pedal_position": 0.26273746763072314, "brake_pedal_position": 0.0, "acceleration": 0.0405435493281559, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021932024966071512, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141218.4118328} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2631865483473491, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0269524908970245, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.130625065569543, "gear": 1, "accelerator_pedal_position": 0.2631865483473491, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141218.4118328} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141218.4318328, "x": 16.18501171315158, "y": 5.332801430401195, "z": null, "yaw": 3.1432323653598324, "pitch": null, "roll": null}, "v": 2.131484448262632, "accelerator_pedal_position": 0.2631865483473491, "brake_pedal_position": 0.0, "acceleration": 0.0429094452259457, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021981131613608124, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141218.4318328} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2640311588709501, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9996851309662608, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.131484448262632, "gear": 1, "accelerator_pedal_position": 0.2631865483473491, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141218.4318328} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.06994366645813, "x": 12.185011713151582, "y": 0.3328014304011946, "z": null, "yaw": 3.1432323653598324, "pitch": null, "roll": null}, "v": 2.131484448262632, "accelerator_pedal_position": 0.2631865483473491, "brake_pedal_position": 0.0, "acceleration": 0.0429094452259457, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021981131613608124, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141218.4518328} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2636625524246144, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9996851309662608, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1324477670930166, "gear": 1, "accelerator_pedal_position": 0.2640311588709501, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141218.4518328} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.06994366645813, "x": 12.185011713151582, "y": 0.3328014304011946, "z": null, "yaw": 3.1432323653598324, "pitch": null, "roll": null}, "v": 2.131484448262632, "accelerator_pedal_position": 0.2631865483473491, "brake_pedal_position": 0.0, "acceleration": 0.0429094452259457, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021981131613608124, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141218.4718328} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2636625524246144, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9996851309662608, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.133363247374135, "gear": 1, "accelerator_pedal_position": 0.2636625524246144, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141218.4718328} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.06994366645813, "x": 12.185011713151582, "y": 0.3328014304011946, "z": null, "yaw": 3.1432323653598324, "pitch": null, "roll": null}, "v": 2.131484448262632, "accelerator_pedal_position": 0.2631865483473491, "brake_pedal_position": 0.0, "acceleration": 0.0429094452259457, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021981131613608124, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141218.4918327} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2636625524246144, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9996851309662608, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.134277031824093, "gear": 1, "accelerator_pedal_position": 0.2636625524246144, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141218.4918327} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.06994366645813, "x": 12.185011713151582, "y": 0.3328014304011946, "z": null, "yaw": 3.1432323653598324, "pitch": null, "roll": null}, "v": 2.131484448262632, "accelerator_pedal_position": 0.2631865483473491, "brake_pedal_position": 0.0, "acceleration": 0.0429094452259457, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021981131613608124, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141218.5118327} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2636625524246144, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9996851309662608, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1360995244571943, "gear": 1, "accelerator_pedal_position": 0.2636625524246144, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141218.5118327} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.06994366645813, "x": 12.185011713151582, "y": 0.3328014304011946, "z": null, "yaw": 3.1432323653598324, "pitch": null, "roll": null}, "v": 2.131484448262632, "accelerator_pedal_position": 0.2631865483473491, "brake_pedal_position": 0.0, "acceleration": 0.0429094452259457, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.021981131613608124, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141218.5318327} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2636625524246144, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9996851309662608, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1360995244571943, "gear": 1, "accelerator_pedal_position": 0.2636625524246144, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141218.5318327} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141218.5418327, "x": 15.950292957260052, "y": 5.332295478398663, "z": null, "yaw": 3.144366750590496, "pitch": null, "roll": null}, "v": 2.1365540921036654, "accelerator_pedal_position": 0.2636625524246144, "brake_pedal_position": 0.0, "acceleration": 0.04541461416380743, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.022033412787226217, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141218.5518327} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26434970083612097, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9723754026245899, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1375049100074053, "gear": 1, "accelerator_pedal_position": 0.26434970083612097, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141218.5518327} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.179943561553955, "x": 11.950292957260052, "y": 0.33229547839866314, "z": null, "yaw": 3.144366750590496, "pitch": null, "roll": null}, "v": 2.1365540921036654, "accelerator_pedal_position": 0.2636625524246144, "brake_pedal_position": 0.0, "acceleration": 0.04541461416380743, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.022033412787226217, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141218.5718327} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2640582857551659, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9723754026245899, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1380011211306287, "gear": 1, "accelerator_pedal_position": 0.26434970083612097, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141218.5718327} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.179943561553955, "x": 11.950292957260052, "y": 0.33229547839866314, "z": null, "yaw": 3.144366750590496, "pitch": null, "roll": null}, "v": 2.1365540921036654, "accelerator_pedal_position": 0.2636625524246144, "brake_pedal_position": 0.0, "acceleration": 0.04541461416380743, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.022033412787226217, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141218.5918326} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2640582857551659, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9723754026245899, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1389557529834806, "gear": 1, "accelerator_pedal_position": 0.2640582857551659, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141218.5918326} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.179943561553955, "x": 11.950292957260052, "y": 0.33229547839866314, "z": null, "yaw": 3.144366750590496, "pitch": null, "roll": null}, "v": 2.1365540921036654, "accelerator_pedal_position": 0.2636625524246144, "brake_pedal_position": 0.0, "acceleration": 0.04541461416380743, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.022033412787226217, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141218.6118326} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2640582857551659, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9723754026245899, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1403843820159407, "gear": 1, "accelerator_pedal_position": 0.2640582857551659, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141218.6118326} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.179943561553955, "x": 11.950292957260052, "y": 0.33229547839866314, "z": null, "yaw": 3.144366750590496, "pitch": null, "roll": null}, "v": 2.1365540921036654, "accelerator_pedal_position": 0.2636625524246144, "brake_pedal_position": 0.0, "acceleration": 0.04541461416380743, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.022033412787226217, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141218.6318326} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2640582857551659, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9723754026245899, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.140859708154353, "gear": 1, "accelerator_pedal_position": 0.2640582857551659, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141218.6318326} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141218.6518326, "x": 15.715010018352551, "y": 5.33152140468811, "z": null, "yaw": 3.14550113582116, "pitch": null, "roll": null}, "v": 2.141809037310132, "accelerator_pedal_position": 0.2640582857551659, "brake_pedal_position": 0.0, "acceleration": 0.04740037458124646, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02208760489840948, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141218.6518326} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26495255951466434, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9654364664687083, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.141809037310132, "gear": 1, "accelerator_pedal_position": 0.2640582857551659, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141218.6518326} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.28994345664978, "x": 11.715010018352551, "y": 0.3315214046881101, "z": null, "yaw": 3.14550113582116, "pitch": null, "roll": null}, "v": 2.141809037310132, "accelerator_pedal_position": 0.2640582857551659, "brake_pedal_position": 0.0, "acceleration": 0.04740037458124646, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02208760489840948, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141218.6718326} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26456386308442814, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9654364664687083, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.142868337058541, "gear": 1, "accelerator_pedal_position": 0.26495255951466434, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141218.6718326} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.28994345664978, "x": 11.715010018352551, "y": 0.3315214046881101, "z": null, "yaw": 3.14550113582116, "pitch": null, "roll": null}, "v": 2.141809037310132, "accelerator_pedal_position": 0.2640582857551659, "brake_pedal_position": 0.0, "acceleration": 0.04740037458124646, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02208760489840948, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141218.6918325} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26456386308442814, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9654364664687083, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1438771060638455, "gear": 1, "accelerator_pedal_position": 0.26456386308442814, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141218.6918325} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.28994345664978, "x": 11.715010018352551, "y": 0.3315214046881101, "z": null, "yaw": 3.14550113582116, "pitch": null, "roll": null}, "v": 2.141809037310132, "accelerator_pedal_position": 0.2640582857551659, "brake_pedal_position": 0.0, "acceleration": 0.04740037458124646, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02208760489840948, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141218.7118325} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26456386308442814, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9654364664687083, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.145386748904723, "gear": 1, "accelerator_pedal_position": 0.26456386308442814, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141218.7118325} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.28994345664978, "x": 11.715010018352551, "y": 0.3315214046881101, "z": null, "yaw": 3.14550113582116, "pitch": null, "roll": null}, "v": 2.141809037310132, "accelerator_pedal_position": 0.2640582857551659, "brake_pedal_position": 0.0, "acceleration": 0.04740037458124646, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02208760489840948, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141218.7318325} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26456386308442814, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9654364664687083, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.14588902854281, "gear": 1, "accelerator_pedal_position": 0.26456386308442814, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141218.7318325} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.28994345664978, "x": 11.715010018352551, "y": 0.3315214046881101, "z": null, "yaw": 3.14550113582116, "pitch": null, "roll": null}, "v": 2.141809037310132, "accelerator_pedal_position": 0.2640582857551659, "brake_pedal_position": 0.0, "acceleration": 0.04740037458124646, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02208760489840948, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141218.7518325} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26456386308442814, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9654364664687083, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.146892188156613, "gear": 1, "accelerator_pedal_position": 0.26456386308442814, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141218.7518325} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141218.7618325, "x": 15.479131439898419, "y": 5.330477787195808, "z": null, "yaw": 3.1466355210518238, "pitch": null, "roll": null}, "v": 2.147393068898555, "accelerator_pedal_position": 0.26456386308442814, "brake_pedal_position": 0.0, "acceleration": 0.05004152090921249, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02214519074351368, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141218.7718325} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2653260349360263, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9131614108228332, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.147893484107647, "gear": 1, "accelerator_pedal_position": 0.26456386308442814, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141218.7718325} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.399943351745605, "x": 11.479131439898419, "y": 0.3304777871958082, "z": null, "yaw": 3.1466355210518238, "pitch": null, "roll": null}, "v": 2.147393068898555, "accelerator_pedal_position": 0.26456386308442814, "brake_pedal_position": 0.0, "acceleration": 0.05004152090921249, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02214519074351368, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141218.7918324} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2650026167102693, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9131614108228332, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1489881466526493, "gear": 1, "accelerator_pedal_position": 0.2653260349360263, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141218.7918324} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.399943351745605, "x": 11.479131439898419, "y": 0.3304777871958082, "z": null, "yaw": 3.1466355210518238, "pitch": null, "roll": null}, "v": 2.147393068898555, "accelerator_pedal_position": 0.26456386308442814, "brake_pedal_position": 0.0, "acceleration": 0.05004152090921249, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02214519074351368, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141218.8118324} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2650026167102693, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9131614108228332, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1500403661530503, "gear": 1, "accelerator_pedal_position": 0.2650026167102693, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141218.8118324} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.399943351745605, "x": 11.479131439898419, "y": 0.3304777871958082, "z": null, "yaw": 3.1466355210518238, "pitch": null, "roll": null}, "v": 2.147393068898555, "accelerator_pedal_position": 0.26456386308442814, "brake_pedal_position": 0.0, "acceleration": 0.05004152090921249, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02214519074351368, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141218.8318324} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2650026167102693, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9131614108228332, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1510906295289365, "gear": 1, "accelerator_pedal_position": 0.2650026167102693, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141218.8318324} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.399943351745605, "x": 11.479131439898419, "y": 0.3304777871958082, "z": null, "yaw": 3.1466355210518238, "pitch": null, "roll": null}, "v": 2.147393068898555, "accelerator_pedal_position": 0.26456386308442814, "brake_pedal_position": 0.0, "acceleration": 0.05004152090921249, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02214519074351368, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141218.8518324} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2650026167102693, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9131614108228332, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.152138939975817, "gear": 1, "accelerator_pedal_position": 0.2650026167102693, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141218.8518324} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141218.8718324, "x": 15.242631672998021, "y": 5.329163130461743, "z": null, "yaw": 3.1477699062824875, "pitch": null, "roll": null}, "v": 2.1531853006857196, "accelerator_pedal_position": 0.2650026167102693, "brake_pedal_position": 0.0, "acceleration": 0.052245020014006605, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02220492367253128, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141218.8718324} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26599117179608234, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8805033088829769, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1531853006857196, "gear": 1, "accelerator_pedal_position": 0.2650026167102693, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141218.8718324} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.50994324684143, "x": 11.242631672998021, "y": 0.32916313046174306, "z": null, "yaw": 3.1477699062824875, "pitch": null, "roll": null}, "v": 2.1531853006857196, "accelerator_pedal_position": 0.2650026167102693, "brake_pedal_position": 0.0, "acceleration": 0.052245020014006605, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02220492367253128, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141218.8918324} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2655614757163166, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8805033088829769, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1543532267269496, "gear": 1, "accelerator_pedal_position": 0.26599117179608234, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141218.8918324} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.50994324684143, "x": 11.242631672998021, "y": 0.32916313046174306, "z": null, "yaw": 3.1477699062824875, "pitch": null, "roll": null}, "v": 2.1531853006857196, "accelerator_pedal_position": 0.2650026167102693, "brake_pedal_position": 0.0, "acceleration": 0.052245020014006605, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02220492367253128, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141218.9118323} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2655614757163166, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8805033088829769, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.155465292532974, "gear": 1, "accelerator_pedal_position": 0.2655614757163166, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141218.9118323} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.50994324684143, "x": 11.242631672998021, "y": 0.32916313046174306, "z": null, "yaw": 3.1477699062824875, "pitch": null, "roll": null}, "v": 2.1531853006857196, "accelerator_pedal_position": 0.2650026167102693, "brake_pedal_position": 0.0, "acceleration": 0.052245020014006605, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02220492367253128, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141218.9318323} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2655614757163166, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8805033088829769, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.156575288553192, "gear": 1, "accelerator_pedal_position": 0.2655614757163166, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141218.9318323} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.50994324684143, "x": 11.242631672998021, "y": 0.32916313046174306, "z": null, "yaw": 3.1477699062824875, "pitch": null, "roll": null}, "v": 2.1531853006857196, "accelerator_pedal_position": 0.2650026167102693, "brake_pedal_position": 0.0, "acceleration": 0.052245020014006605, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02220492367253128, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141218.9518323} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2655614757163166, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8805033088829769, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1576832181472994, "gear": 1, "accelerator_pedal_position": 0.2655614757163166, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141218.9518323} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.50994324684143, "x": 11.242631672998021, "y": 0.32916313046174306, "z": null, "yaw": 3.1477699062824875, "pitch": null, "roll": null}, "v": 2.1531853006857196, "accelerator_pedal_position": 0.2650026167102693, "brake_pedal_position": 0.0, "acceleration": 0.052245020014006605, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02220492367253128, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141218.9718323} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2655614757163166, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8805033088829769, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.158789084671487, "gear": 1, "accelerator_pedal_position": 0.2655614757163166, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141218.9718323} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141218.9818323, "x": 15.005475828441018, "y": 5.327575787248605, "z": null, "yaw": 3.1489042915131513, "pitch": null, "roll": null}, "v": 2.159341245330211, "accelerator_pedal_position": 0.2655614757163166, "brake_pedal_position": 0.0, "acceleration": 0.05516461482262586, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02226840742421755, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141218.9918323} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27003358278471035, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8123926595119273, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1598928914784374, "gear": 1, "accelerator_pedal_position": 0.2655614757163166, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141218.9918323} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.619943141937256, "x": 11.005475828441018, "y": 0.32757578724860537, "z": null, "yaw": 3.1489042915131513, "pitch": null, "roll": null}, "v": 2.159341245330211, "accelerator_pedal_position": 0.2655614757163166, "brake_pedal_position": 0.0, "acceleration": 0.05516461482262586, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02226840742421755, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141219.0118322} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2679476849657011, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8123926595119273, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1615533947680006, "gear": 1, "accelerator_pedal_position": 0.27003358278471035, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141219.0118322} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.619943141937256, "x": 11.005475828441018, "y": 0.32757578724860537, "z": null, "yaw": 3.1489042915131513, "pitch": null, "roll": null}, "v": 2.159341245330211, "accelerator_pedal_position": 0.2655614757163166, "brake_pedal_position": 0.0, "acceleration": 0.05516461482262586, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02226840742421755, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141219.0318322} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2679476849657011, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8123926595119273, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1629501879031703, "gear": 1, "accelerator_pedal_position": 0.2679476849657011, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141219.0318322} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.619943141937256, "x": 11.005475828441018, "y": 0.32757578724860537, "z": null, "yaw": 3.1489042915131513, "pitch": null, "roll": null}, "v": 2.159341245330211, "accelerator_pedal_position": 0.2655614757163166, "brake_pedal_position": 0.0, "acceleration": 0.05516461482262586, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02226840742421755, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141219.0518322} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2679476849657011, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8123926595119273, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.164344377177452, "gear": 1, "accelerator_pedal_position": 0.2679476849657011, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141219.0518322} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.619943141937256, "x": 11.005475828441018, "y": 0.32757578724860537, "z": null, "yaw": 3.1489042915131513, "pitch": null, "roll": null}, "v": 2.159341245330211, "accelerator_pedal_position": 0.2655614757163166, "brake_pedal_position": 0.0, "acceleration": 0.05516461482262586, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02226840742421755, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141219.0718322} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2679476849657011, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8123926595119273, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1657359666677443, "gear": 1, "accelerator_pedal_position": 0.2679476849657011, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141219.0718322} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141219.0918322, "x": 14.767564003852765, "y": 5.3257134684953, "z": null, "yaw": 3.150038676743815, "pitch": null, "roll": null}, "v": 2.167124960447689, "accelerator_pedal_position": 0.2679476849657011, "brake_pedal_position": 0.0, "acceleration": 0.06935247707129327, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02234867771029896, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141219.0918322} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27370284752067686, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7067634055507325, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.167124960447689, "gear": 1, "accelerator_pedal_position": 0.2679476849657011, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141219.0918322} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.72994303703308, "x": 10.767564003852765, "y": 0.3257134684952998, "z": null, "yaw": 3.150038676743815, "pitch": null, "roll": null}, "v": 2.167124960447689, "accelerator_pedal_position": 0.2679476849657011, "brake_pedal_position": 0.0, "acceleration": 0.06935247707129327, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02234867771029896, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141219.1118321} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2710176027195759, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7067634055507325, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1692304220934204, "gear": 1, "accelerator_pedal_position": 0.27370284752067686, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141219.1118321} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.72994303703308, "x": 10.767564003852765, "y": 0.3257134684952998, "z": null, "yaw": 3.150038676743815, "pitch": null, "roll": null}, "v": 2.167124960447689, "accelerator_pedal_position": 0.2679476849657011, "brake_pedal_position": 0.0, "acceleration": 0.06935247707129327, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02234867771029896, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141219.1318321} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2710176027195759, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7067634055507325, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1709964548217866, "gear": 1, "accelerator_pedal_position": 0.2710176027195759, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141219.1318321} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.72994303703308, "x": 10.767564003852765, "y": 0.3257134684952998, "z": null, "yaw": 3.150038676743815, "pitch": null, "roll": null}, "v": 2.167124960447689, "accelerator_pedal_position": 0.2679476849657011, "brake_pedal_position": 0.0, "acceleration": 0.06935247707129327, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02234867771029896, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141219.151832} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2710176027195759, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7067634055507325, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1727591897501153, "gear": 1, "accelerator_pedal_position": 0.2710176027195759, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141219.151832} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.72994303703308, "x": 10.767564003852765, "y": 0.3257134684952998, "z": null, "yaw": 3.150038676743815, "pitch": null, "roll": null}, "v": 2.167124960447689, "accelerator_pedal_position": 0.2679476849657011, "brake_pedal_position": 0.0, "acceleration": 0.06935247707129327, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02234867771029896, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141219.171832} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2710176027195759, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7067634055507325, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1745186317942378, "gear": 1, "accelerator_pedal_position": 0.2710176027195759, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141219.171832} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.72994303703308, "x": 10.767564003852765, "y": 0.3257134684952998, "z": null, "yaw": 3.150038676743815, "pitch": null, "roll": null}, "v": 2.167124960447689, "accelerator_pedal_position": 0.2679476849657011, "brake_pedal_position": 0.0, "acceleration": 0.06935247707129327, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02234867771029896, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141219.191832} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2710176027195759, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7067634055507325, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1762747858677636, "gear": 1, "accelerator_pedal_position": 0.2710176027195759, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141219.191832} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141219.201832, "x": 14.528672499084507, "y": 5.32357244604662, "z": null, "yaw": 3.151173061974479, "pitch": null, "roll": null}, "v": 2.177151631450443, "accelerator_pedal_position": 0.2710176027195759, "brake_pedal_position": 0.0, "acceleration": 0.08760254316155403, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02245207868755569, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141219.211832} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27174571014630433, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7004798854427955, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1780276568820582, "gear": 1, "accelerator_pedal_position": 0.2710176027195759, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141219.211832} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.839942932128906, "x": 10.528672499084507, "y": 0.3235724460466196, "z": null, "yaw": 3.151173061974479, "pitch": null, "roll": null}, "v": 2.177151631450443, "accelerator_pedal_position": 0.2710176027195759, "brake_pedal_position": 0.0, "acceleration": 0.08760254316155403, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02245207868755569, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141219.231832} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2714703765576702, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7004798854427955, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1798682205900555, "gear": 1, "accelerator_pedal_position": 0.27174571014630433, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141219.231832} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.839942932128906, "x": 10.528672499084507, "y": 0.3235724460466196, "z": null, "yaw": 3.151173061974479, "pitch": null, "roll": null}, "v": 2.177151631450443, "accelerator_pedal_position": 0.2710176027195759, "brake_pedal_position": 0.0, "acceleration": 0.08760254316155403, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02245207868755569, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141219.251832} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2714703765576702, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7004798854427955, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1816709402219545, "gear": 1, "accelerator_pedal_position": 0.2714703765576702, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141219.251832} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.839942932128906, "x": 10.528672499084507, "y": 0.3235724460466196, "z": null, "yaw": 3.151173061974479, "pitch": null, "roll": null}, "v": 2.177151631450443, "accelerator_pedal_position": 0.2710176027195759, "brake_pedal_position": 0.0, "acceleration": 0.08760254316155403, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02245207868755569, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141219.271832} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2714703765576702, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7004798854427955, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1834702858631188, "gear": 1, "accelerator_pedal_position": 0.2714703765576702, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141219.271832} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.839942932128906, "x": 10.528672499084507, "y": 0.3235724460466196, "z": null, "yaw": 3.151173061974479, "pitch": null, "roll": null}, "v": 2.177151631450443, "accelerator_pedal_position": 0.2710176027195759, "brake_pedal_position": 0.0, "acceleration": 0.08760254316155403, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02245207868755569, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141219.291832} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2714703765576702, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7004798854427955, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.185266262533896, "gear": 1, "accelerator_pedal_position": 0.2714703765576702, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141219.291832} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141219.311832, "x": 14.288701982613498, "y": 5.3211495098787855, "z": null, "yaw": 3.1523074472051427, "pitch": null, "roll": null}, "v": 2.1870588752525046, "accelerator_pedal_position": 0.2714703765576702, "brake_pedal_position": 0.0, "acceleration": 0.08950464448460593, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.022554248060697835, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141219.311832} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2765619511920488, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6039360399051045, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1870588752525046, "gear": 1, "accelerator_pedal_position": 0.2714703765576702, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141219.311832} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.94994282722473, "x": 10.288701982613498, "y": 0.32114950987878554, "z": null, "yaw": 3.1523074472051427, "pitch": null, "roll": null}, "v": 2.1870588752525046, "accelerator_pedal_position": 0.2714703765576702, "brake_pedal_position": 0.0, "acceleration": 0.08950464448460593, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.022554248060697835, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141219.331832} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27420807525048363, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6039360399051045, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.189484277490839, "gear": 1, "accelerator_pedal_position": 0.2765619511920488, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141219.331832} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.94994282722473, "x": 10.288701982613498, "y": 0.32114950987878554, "z": null, "yaw": 3.1523074472051427, "pitch": null, "roll": null}, "v": 2.1870588752525046, "accelerator_pedal_position": 0.2714703765576702, "brake_pedal_position": 0.0, "acceleration": 0.08950464448460593, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.022554248060697835, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141219.351832} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27420807525048363, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6039360399051045, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1926729197094215, "gear": 1, "accelerator_pedal_position": 0.27420807525048363, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141219.351832} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.94994282722473, "x": 10.288701982613498, "y": 0.32114950987878554, "z": null, "yaw": 3.1523074472051427, "pitch": null, "roll": null}, "v": 2.1870588752525046, "accelerator_pedal_position": 0.2714703765576702, "brake_pedal_position": 0.0, "acceleration": 0.08950464448460593, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.022554248060697835, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141219.371832} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27420807525048363, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6039360399051045, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.193733806499439, "gear": 1, "accelerator_pedal_position": 0.27420807525048363, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141219.371832} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.94994282722473, "x": 10.288701982613498, "y": 0.32114950987878554, "z": null, "yaw": 3.1523074472051427, "pitch": null, "roll": null}, "v": 2.1870588752525046, "accelerator_pedal_position": 0.2714703765576702, "brake_pedal_position": 0.0, "acceleration": 0.08950464448460593, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.022554248060697835, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141219.3918319} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27420807525048363, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6039360399051045, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1958525934149153, "gear": 1, "accelerator_pedal_position": 0.27420807525048363, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141219.3918319} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.94994282722473, "x": 10.288701982613498, "y": 0.32114950987878554, "z": null, "yaw": 3.1523074472051427, "pitch": null, "roll": null}, "v": 2.1870588752525046, "accelerator_pedal_position": 0.2714703765576702, "brake_pedal_position": 0.0, "acceleration": 0.08950464448460593, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.022554248060697835, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141219.4118319} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27420807525048363, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6039360399051045, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2000782404639447, "gear": 1, "accelerator_pedal_position": 0.27420807525048363, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141219.4118319} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141219.4218318, "x": 14.047528152274575, "y": 5.318440789274257, "z": null, "yaw": 3.1534418324358064, "pitch": null, "roll": null}, "v": 2.1990233177748886, "accelerator_pedal_position": 0.27420807525048363, "brake_pedal_position": 0.0, "acceleration": 0.10549226890560137, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02267763248697518, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141219.4318318} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.280573406632424, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.43032183348422826, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2000782404639447, "gear": 1, "accelerator_pedal_position": 0.27420807525048363, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141219.4318318} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.05994272232056, "x": 10.047528152274575, "y": 0.31844078927425734, "z": null, "yaw": 3.1534418324358064, "pitch": null, "roll": null}, "v": 2.1990233177748886, "accelerator_pedal_position": 0.27420807525048363, "brake_pedal_position": 0.0, "acceleration": 0.10549226890560137, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02267763248697518, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141219.4518318} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27762785630552334, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.43032183348422826, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.204245342858481, "gear": 1, "accelerator_pedal_position": 0.27762785630552334, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141219.4518318} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.05994272232056, "x": 10.047528152274575, "y": 0.31844078927425734, "z": null, "yaw": 3.1534418324358064, "pitch": null, "roll": null}, "v": 2.1990233177748886, "accelerator_pedal_position": 0.27420807525048363, "brake_pedal_position": 0.0, "acceleration": 0.10549226890560137, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02267763248697518, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141219.4718318} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27762785630552334, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.43032183348422826, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2055090914529956, "gear": 1, "accelerator_pedal_position": 0.27762785630552334, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141219.4718318} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.05994272232056, "x": 10.047528152274575, "y": 0.31844078927425734, "z": null, "yaw": 3.1534418324358064, "pitch": null, "roll": null}, "v": 2.1990233177748886, "accelerator_pedal_position": 0.27420807525048363, "brake_pedal_position": 0.0, "acceleration": 0.10549226890560137, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02267763248697518, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141219.4918318} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27762785630552334, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.43032183348422826, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.208033021972848, "gear": 1, "accelerator_pedal_position": 0.27762785630552334, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141219.4918318} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.05994272232056, "x": 10.047528152274575, "y": 0.31844078927425734, "z": null, "yaw": 3.1534418324358064, "pitch": null, "roll": null}, "v": 2.1990233177748886, "accelerator_pedal_position": 0.27420807525048363, "brake_pedal_position": 0.0, "acceleration": 0.10549226890560137, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02267763248697518, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141219.5118318} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27762785630552334, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.43032183348422826, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.21181001308197, "gear": 1, "accelerator_pedal_position": 0.27762785630552334, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141219.5118318} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141219.5318317, "x": 13.804948447031702, "y": 5.3154410386112865, "z": null, "yaw": 3.1545762176664702, "pitch": null, "roll": null}, "v": 2.213066638741127, "accelerator_pedal_position": 0.27762785630552334, "brake_pedal_position": 0.0, "acceleration": 0.1255441304973749, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.022822455540553, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141219.5318317} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2765221704022981, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.42504486441589795, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.213066638741127, "gear": 1, "accelerator_pedal_position": 0.27762785630552334, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141219.5318317} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.16994261741638, "x": 9.804948447031702, "y": 0.3154410386112865, "z": null, "yaw": 3.1545762176664702, "pitch": null, "roll": null}, "v": 2.213066638741127, "accelerator_pedal_position": 0.27762785630552334, "brake_pedal_position": 0.0, "acceleration": 0.1255441304973749, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.022822455540553, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141219.5518317} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27714939409828143, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.42504486441589795, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2154381922163675, "gear": 1, "accelerator_pedal_position": 0.2765221704022981, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141219.5518317} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.16994261741638, "x": 9.804948447031702, "y": 0.3154410386112865, "z": null, "yaw": 3.1545762176664702, "pitch": null, "roll": null}, "v": 2.213066638741127, "accelerator_pedal_position": 0.27762785630552334, "brake_pedal_position": 0.0, "acceleration": 0.1255441304973749, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.022822455540553, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141219.5718317} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27714939409828143, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.42504486441589795, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2178836411796583, "gear": 1, "accelerator_pedal_position": 0.27714939409828143, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141219.5718317} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.16994261741638, "x": 9.804948447031702, "y": 0.3154410386112865, "z": null, "yaw": 3.1545762176664702, "pitch": null, "roll": null}, "v": 2.213066638741127, "accelerator_pedal_position": 0.27762785630552334, "brake_pedal_position": 0.0, "acceleration": 0.1255441304973749, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.022822455540553, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141219.5918317} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27714939409828143, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.42504486441589795, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2203244779804985, "gear": 1, "accelerator_pedal_position": 0.27714939409828143, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141219.5918317} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.16994261741638, "x": 9.804948447031702, "y": 0.3154410386112865, "z": null, "yaw": 3.1545762176664702, "pitch": null, "roll": null}, "v": 2.213066638741127, "accelerator_pedal_position": 0.27762785630552334, "brake_pedal_position": 0.0, "acceleration": 0.1255441304973749, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.022822455540553, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141219.6118317} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27714939409828143, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.42504486441589795, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.222760708935563, "gear": 1, "accelerator_pedal_position": 0.27714939409828143, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141219.6118317} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.16994261741638, "x": 9.804948447031702, "y": 0.3154410386112865, "z": null, "yaw": 3.1545762176664702, "pitch": null, "roll": null}, "v": 2.213066638741127, "accelerator_pedal_position": 0.27762785630552334, "brake_pedal_position": 0.0, "acceleration": 0.1255441304973749, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.022822455540553, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141219.6318316} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27714939409828143, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.42504486441589795, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2251923403630895, "gear": 1, "accelerator_pedal_position": 0.27714939409828143, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141219.6318316} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141219.6418316, "x": 13.560868648962792, "y": 5.312145820089073, "z": null, "yaw": 3.155710602897134, "pitch": null, "roll": null}, "v": 2.2264064332288895, "accelerator_pedal_position": 0.27714939409828143, "brake_pedal_position": 0.0, "acceleration": 0.12129453539358459, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.022960023411889335, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141219.6518316} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27619142051739315, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4197421605584052, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2276193785828253, "gear": 1, "accelerator_pedal_position": 0.27714939409828143, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141219.6518316} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.27994251251221, "x": 9.560868648962792, "y": 0.3121458200890732, "z": null, "yaw": 3.155710602897134, "pitch": null, "roll": null}, "v": 2.2264064332288895, "accelerator_pedal_position": 0.27714939409828143, "brake_pedal_position": 0.0, "acceleration": 0.12129453539358459, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.022960023411889335, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141219.6718316} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27674353821713, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4197421605584052, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2299221398441973, "gear": 1, "accelerator_pedal_position": 0.27619142051739315, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141219.6718316} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.27994251251221, "x": 9.560868648962792, "y": 0.3121458200890732, "z": null, "yaw": 3.155710602897134, "pitch": null, "roll": null}, "v": 2.2264064332288895, "accelerator_pedal_position": 0.27714939409828143, "brake_pedal_position": 0.0, "acceleration": 0.12129453539358459, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.022960023411889335, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141219.6918316} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27674353821713, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4197421605584052, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2322895290047016, "gear": 1, "accelerator_pedal_position": 0.27674353821713, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141219.6918316} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.27994251251221, "x": 9.560868648962792, "y": 0.3121458200890732, "z": null, "yaw": 3.155710602897134, "pitch": null, "roll": null}, "v": 2.2264064332288895, "accelerator_pedal_position": 0.27714939409828143, "brake_pedal_position": 0.0, "acceleration": 0.12129453539358459, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.022960023411889335, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141219.7118316} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27674353821713, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4197421605584052, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.234652439577685, "gear": 1, "accelerator_pedal_position": 0.27674353821713, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141219.7118316} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.27994251251221, "x": 9.560868648962792, "y": 0.3121458200890732, "z": null, "yaw": 3.155710602897134, "pitch": null, "roll": null}, "v": 2.2264064332288895, "accelerator_pedal_position": 0.27714939409828143, "brake_pedal_position": 0.0, "acceleration": 0.12129453539358459, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.022960023411889335, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141219.7318316} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27674353821713, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4197421605584052, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.237010877803383, "gear": 1, "accelerator_pedal_position": 0.27674353821713, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141219.7318316} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141219.7518315, "x": 13.315342248238764, "y": 5.30855250008431, "z": null, "yaw": 3.156844988127798, "pitch": null, "roll": null}, "v": 2.239364849922894, "accelerator_pedal_position": 0.27674353821713, "brake_pedal_position": 0.0, "acceleration": 0.11753132205021577, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.023093658289257107, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141219.7518315} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27579454576574575, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.41470029478530357, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.239364849922894, "gear": 1, "accelerator_pedal_position": 0.27674353821713, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141219.7518315} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.38994240760803, "x": 9.315342248238764, "y": 0.3085525000843097, "z": null, "yaw": 3.156844988127798, "pitch": null, "roll": null}, "v": 2.239364849922894, "accelerator_pedal_position": 0.27674353821713, "brake_pedal_position": 0.0, "acceleration": 0.11753132205021577, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.023093658289257107, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141219.7718315} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.276339903516829, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.41470029478530357, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.241595794355565, "gear": 1, "accelerator_pedal_position": 0.27579454576574575, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141219.7718315} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.38994240760803, "x": 9.315342248238764, "y": 0.3085525000843097, "z": null, "yaw": 3.156844988127798, "pitch": null, "roll": null}, "v": 2.239364849922894, "accelerator_pedal_position": 0.27674353821713, "brake_pedal_position": 0.0, "acceleration": 0.11753132205021577, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.023093658289257107, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141219.7918315} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.276339903516829, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.41470029478530357, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2438906473851747, "gear": 1, "accelerator_pedal_position": 0.276339903516829, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141219.7918315} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.38994240760803, "x": 9.315342248238764, "y": 0.3085525000843097, "z": null, "yaw": 3.156844988127798, "pitch": null, "roll": null}, "v": 2.239364849922894, "accelerator_pedal_position": 0.27674353821713, "brake_pedal_position": 0.0, "acceleration": 0.11753132205021577, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.023093658289257107, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141219.8118315} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.276339903516829, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.41470029478530357, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2461811483942205, "gear": 1, "accelerator_pedal_position": 0.276339903516829, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141219.8118315} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.38994240760803, "x": 9.315342248238764, "y": 0.3085525000843097, "z": null, "yaw": 3.156844988127798, "pitch": null, "roll": null}, "v": 2.239364849922894, "accelerator_pedal_position": 0.27674353821713, "brake_pedal_position": 0.0, "acceleration": 0.11753132205021577, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.023093658289257107, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141219.8318315} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.276339903516829, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.41470029478530357, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2484673035384266, "gear": 1, "accelerator_pedal_position": 0.276339903516829, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141219.8318315} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.38994240760803, "x": 9.315342248238764, "y": 0.3085525000843097, "z": null, "yaw": 3.156844988127798, "pitch": null, "roll": null}, "v": 2.239364849922894, "accelerator_pedal_position": 0.27674353821713, "brake_pedal_position": 0.0, "acceleration": 0.11753132205021577, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.023093658289257107, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141219.8518314} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.276339903516829, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.41470029478530357, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2507491189737774, "gear": 1, "accelerator_pedal_position": 0.276339903516829, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141219.8518314} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141219.8618314, "x": 13.068418528326836, "y": 5.304658563562971, "z": null, "yaw": 3.1579793733584616, "pitch": null, "roll": null}, "v": 2.251888401224436, "accelerator_pedal_position": 0.276339903516829, "brake_pedal_position": 0.0, "acceleration": 0.11381996320326809, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.023222808576820006, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141219.8718314} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27775095302863806, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3597152696486949, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2530266008564688, "gear": 1, "accelerator_pedal_position": 0.276339903516829, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141219.8718314} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.49994230270386, "x": 9.068418528326836, "y": 0.3046585635629713, "z": null, "yaw": 3.1579793733584616, "pitch": null, "roll": null}, "v": 2.251888401224436, "accelerator_pedal_position": 0.276339903516829, "brake_pedal_position": 0.0, "acceleration": 0.11381996320326809, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.023222808576820006, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141219.8918314} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2771695875969833, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3597152696486949, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2554760526765585, "gear": 1, "accelerator_pedal_position": 0.27775095302863806, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141219.8918314} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.49994230270386, "x": 9.068418528326836, "y": 0.3046585635629713, "z": null, "yaw": 3.1579793733584616, "pitch": null, "roll": null}, "v": 2.251888401224436, "accelerator_pedal_position": 0.276339903516829, "brake_pedal_position": 0.0, "acceleration": 0.11381996320326809, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.023222808576820006, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141219.9118314} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2771695875969833, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3597152696486949, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2578482118764507, "gear": 1, "accelerator_pedal_position": 0.2771695875969833, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141219.9118314} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.49994230270386, "x": 9.068418528326836, "y": 0.3046585635629713, "z": null, "yaw": 3.1579793733584616, "pitch": null, "roll": null}, "v": 2.251888401224436, "accelerator_pedal_position": 0.276339903516829, "brake_pedal_position": 0.0, "acceleration": 0.11381996320326809, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.023222808576820006, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141219.9318314} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2771695875969833, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3597152696486949, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.26021585923738, "gear": 1, "accelerator_pedal_position": 0.2771695875969833, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141219.9318314} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.49994230270386, "x": 9.068418528326836, "y": 0.3046585635629713, "z": null, "yaw": 3.1579793733584616, "pitch": null, "roll": null}, "v": 2.251888401224436, "accelerator_pedal_position": 0.276339903516829, "brake_pedal_position": 0.0, "acceleration": 0.11381996320326809, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.023222808576820006, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141219.9518313} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2771695875969833, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3597152696486949, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2625790010996134, "gear": 1, "accelerator_pedal_position": 0.2771695875969833, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141219.9518313} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141219.9718313, "x": 12.820092637982544, "y": 5.300460737882382, "z": null, "yaw": 3.1591137585891254, "pitch": null, "roll": null}, "v": 2.2649376438041466, "accelerator_pedal_position": 0.2771695875969833, "brake_pedal_position": 0.0, "acceleration": 0.11776361498772736, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.023357380104581476, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141219.9718313} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2809672268027141, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.27660122116997915, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2649376438041466, "gear": 1, "accelerator_pedal_position": 0.2771695875969833, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141219.9718313} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.60994219779968, "x": 8.820092637982544, "y": 0.30046073788238203, "z": null, "yaw": 3.1591137585891254, "pitch": null, "roll": null}, "v": 2.2649376438041466, "accelerator_pedal_position": 0.2771695875969833, "brake_pedal_position": 0.0, "acceleration": 0.11776361498772736, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.023357380104581476, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141219.9918313} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2792534452746577, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.27660122116997915, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.267766272337909, "gear": 1, "accelerator_pedal_position": 0.2809672268027141, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141219.9918313} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.60994219779968, "x": 8.820092637982544, "y": 0.30046073788238203, "z": null, "yaw": 3.1591137585891254, "pitch": null, "roll": null}, "v": 2.2649376438041466, "accelerator_pedal_position": 0.2771695875969833, "brake_pedal_position": 0.0, "acceleration": 0.11776361498772736, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.023357380104581476, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141220.0118313} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2792534452746577, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.27660122116997915, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.270375389221957, "gear": 1, "accelerator_pedal_position": 0.2792534452746577, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141220.0118313} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.60994219779968, "x": 8.820092637982544, "y": 0.30046073788238203, "z": null, "yaw": 3.1591137585891254, "pitch": null, "roll": null}, "v": 2.2649376438041466, "accelerator_pedal_position": 0.2771695875969833, "brake_pedal_position": 0.0, "acceleration": 0.11776361498772736, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.023357380104581476, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141220.0318313} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2792534452746577, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.27660122116997915, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2729795305746125, "gear": 1, "accelerator_pedal_position": 0.2792534452746577, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141220.0318313} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.60994219779968, "x": 8.820092637982544, "y": 0.30046073788238203, "z": null, "yaw": 3.1591137585891254, "pitch": null, "roll": null}, "v": 2.2649376438041466, "accelerator_pedal_position": 0.2771695875969833, "brake_pedal_position": 0.0, "acceleration": 0.11776361498772736, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.023357380104581476, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141220.0518312} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2792534452746577, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.27660122116997915, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.275578703172784, "gear": 1, "accelerator_pedal_position": 0.2792534452746577, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141220.0518312} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.60994219779968, "x": 8.820092637982544, "y": 0.30046073788238203, "z": null, "yaw": 3.1591137585891254, "pitch": null, "roll": null}, "v": 2.2649376438041466, "accelerator_pedal_position": 0.2771695875969833, "brake_pedal_position": 0.0, "acceleration": 0.11776361498772736, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.023357380104581476, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141220.0718312} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2792534452746577, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.27660122116997915, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2781729137959643, "gear": 1, "accelerator_pedal_position": 0.2792534452746577, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141220.0718312} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141220.0818312, "x": 12.570252611067307, "y": 5.2959538016018115, "z": null, "yaw": 3.160248143819789, "pitch": null, "roll": null}, "v": 2.2794681604862173, "accelerator_pedal_position": 0.2792534452746577, "brake_pedal_position": 0.0, "acceleration": 0.1294008739955953, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.023507227409290954, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141220.0918312} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28537631801488383, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.1629885231482676, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2807621692261733, "gear": 1, "accelerator_pedal_position": 0.2792534452746577, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141220.0918312} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.71994209289551, "x": 8.570252611067307, "y": 0.2959538016018115, "z": null, "yaw": 3.160248143819789, "pitch": null, "roll": null}, "v": 2.2794681604862173, "accelerator_pedal_position": 0.2792534452746577, "brake_pedal_position": 0.0, "acceleration": 0.1294008739955953, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.023507227409290954, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141220.1118312} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2825663277998326, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.1629885231482676, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.284111469326852, "gear": 1, "accelerator_pedal_position": 0.28537631801488383, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141220.1118312} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.71994209289551, "x": 8.570252611067307, "y": 0.2959538016018115, "z": null, "yaw": 3.160248143819789, "pitch": null, "roll": null}, "v": 2.2794681604862173, "accelerator_pedal_position": 0.2792534452746577, "brake_pedal_position": 0.0, "acceleration": 0.1294008739955953, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.023507227409290954, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141220.1318312} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2825663277998326, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.1629885231482676, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2871032835651794, "gear": 1, "accelerator_pedal_position": 0.2825663277998326, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141220.1318312} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.71994209289551, "x": 8.570252611067307, "y": 0.2959538016018115, "z": null, "yaw": 3.160248143819789, "pitch": null, "roll": null}, "v": 2.2794681604862173, "accelerator_pedal_position": 0.2792534452746577, "brake_pedal_position": 0.0, "acceleration": 0.1294008739955953, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.023507227409290954, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141220.1518312} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2825663277998326, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.1629885231482676, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2900893725911273, "gear": 1, "accelerator_pedal_position": 0.2825663277998326, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141220.1518312} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.71994209289551, "x": 8.570252611067307, "y": 0.2959538016018115, "z": null, "yaw": 3.160248143819789, "pitch": null, "roll": null}, "v": 2.2794681604862173, "accelerator_pedal_position": 0.2792534452746577, "brake_pedal_position": 0.0, "acceleration": 0.1294008739955953, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.023507227409290954, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141220.1718311} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2825663277998326, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.1629885231482676, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2930697437956233, "gear": 1, "accelerator_pedal_position": 0.2825663277998326, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141220.1718311} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141220.191831, "x": 12.318725006876091, "y": 5.29113097260285, "z": null, "yaw": 3.161382529050453, "pitch": null, "roll": null}, "v": 2.2960444045759205, "accelerator_pedal_position": 0.2825663277998326, "brake_pedal_position": 0.0, "acceleration": 0.14851912944231366, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.023678171468156622, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141220.191831} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2810599596089761, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.1434364374072395, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2960444045759205, "gear": 1, "accelerator_pedal_position": 0.2825663277998326, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141220.191831} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2810599596089761, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.1434364374072395, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.297435447858415, "gear": 1, "accelerator_pedal_position": 0.2810599596089761, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141220.201831} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.82994198799133, "x": 8.318725006876091, "y": 0.2911309726028497, "z": null, "yaw": 3.161382529050453, "pitch": null, "roll": null}, "v": 2.2960444045759205, "accelerator_pedal_position": 0.2825663277998326, "brake_pedal_position": 0.0, "acceleration": 0.14851912944231366, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.023678171468156622, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141220.221831} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2818982123346516, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.1434364374072395, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3002135318334935, "gear": 1, "accelerator_pedal_position": 0.2810599596089761, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141220.221831} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.82994198799133, "x": 8.318725006876091, "y": 0.2911309726028497, "z": null, "yaw": 3.161382529050453, "pitch": null, "roll": null}, "v": 2.2960444045759205, "accelerator_pedal_position": 0.2825663277998326, "brake_pedal_position": 0.0, "acceleration": 0.14851912944231366, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.023678171468156622, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141220.241831} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2818982123346516, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.1434364374072395, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.303091016260471, "gear": 1, "accelerator_pedal_position": 0.2818982123346516, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141220.241831} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.82994198799133, "x": 8.318725006876091, "y": 0.2911309726028497, "z": null, "yaw": 3.161382529050453, "pitch": null, "roll": null}, "v": 2.2960444045759205, "accelerator_pedal_position": 0.2825663277998326, "brake_pedal_position": 0.0, "acceleration": 0.14851912944231366, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.023678171468156622, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141220.261831} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2818982123346516, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.1434364374072395, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3059629758425078, "gear": 1, "accelerator_pedal_position": 0.2818982123346516, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141220.261831} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.82994198799133, "x": 8.318725006876091, "y": 0.2911309726028497, "z": null, "yaw": 3.161382529050453, "pitch": null, "roll": null}, "v": 2.2960444045759205, "accelerator_pedal_position": 0.2825663277998326, "brake_pedal_position": 0.0, "acceleration": 0.14851912944231366, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.023678171468156622, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141220.281831} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2818982123346516, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.1434364374072395, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3088294178897733, "gear": 1, "accelerator_pedal_position": 0.2818982123346516, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141220.281831} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141220.301831, "x": 12.065434849478747, "y": 5.285986919353856, "z": null, "yaw": 3.1625169142811167, "pitch": null, "roll": null}, "v": 2.311690349717396, "accelerator_pedal_position": 0.2818982123346516, "brake_pedal_position": 0.0, "acceleration": 0.14284018687593736, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02383952173259528, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141220.301831} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2806286958672312, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.12259406089356627, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.311690349717396, "gear": 1, "accelerator_pedal_position": 0.2818982123346516, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141220.301831} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.93994188308716, "x": 8.065434849478747, "y": 0.28598691935385556, "z": null, "yaw": 3.1625169142811167, "pitch": null, "roll": null}, "v": 2.311690349717396, "accelerator_pedal_position": 0.2818982123346516, "brake_pedal_position": 0.0, "acceleration": 0.14284018687593736, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02383952173259528, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141220.321831} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28134775899446307, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.12259406089356627, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.314387165465496, "gear": 1, "accelerator_pedal_position": 0.2806286958672312, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141220.321831} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.93994188308716, "x": 8.065434849478747, "y": 0.28598691935385556, "z": null, "yaw": 3.1625169142811167, "pitch": null, "roll": null}, "v": 2.311690349717396, "accelerator_pedal_position": 0.2818982123346516, "brake_pedal_position": 0.0, "acceleration": 0.14284018687593736, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02383952173259528, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141220.341831} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28134775899446307, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.12259406089356627, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3171686306402792, "gear": 1, "accelerator_pedal_position": 0.28134775899446307, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141220.341831} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.93994188308716, "x": 8.065434849478747, "y": 0.28598691935385556, "z": null, "yaw": 3.1625169142811167, "pitch": null, "roll": null}, "v": 2.311690349717396, "accelerator_pedal_position": 0.2818982123346516, "brake_pedal_position": 0.0, "acceleration": 0.14284018687593736, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02383952173259528, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141220.361831} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28134775899446307, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.12259406089356627, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.319944739655398, "gear": 1, "accelerator_pedal_position": 0.28134775899446307, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141220.361831} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.93994188308716, "x": 8.065434849478747, "y": 0.28598691935385556, "z": null, "yaw": 3.1625169142811167, "pitch": null, "roll": null}, "v": 2.311690349717396, "accelerator_pedal_position": 0.2818982123346516, "brake_pedal_position": 0.0, "acceleration": 0.14284018687593736, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02383952173259528, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141220.381831} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28134775899446307, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.12259406089356627, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.322715499743773, "gear": 1, "accelerator_pedal_position": 0.28134775899446307, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141220.381831} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.93994188308716, "x": 8.065434849478747, "y": 0.28598691935385556, "z": null, "yaw": 3.1625169142811167, "pitch": null, "roll": null}, "v": 2.311690349717396, "accelerator_pedal_position": 0.2818982123346516, "brake_pedal_position": 0.0, "acceleration": 0.14284018687593736, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02383952173259528, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141220.401831} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28134775899446307, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.12259406089356627, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3282410020912607, "gear": 1, "accelerator_pedal_position": 0.28134775899446307, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141220.401831} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141220.411831, "x": 11.810451558608905, "y": 5.280519110917705, "z": null, "yaw": 3.1636512995117805, "pitch": null, "roll": null}, "v": 2.3268616264702158, "accelerator_pedal_position": 0.28134775899446307, "brake_pedal_position": 0.0, "acceleration": 0.1379375621044871, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02399597693512891, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141220.421831} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2808616027216967, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.09203703802985679, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.329619045910987, "gear": 1, "accelerator_pedal_position": 0.28134775899446307, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141220.421831} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.04994177818298, "x": 7.810451558608905, "y": 0.2805191109177052, "z": null, "yaw": 3.1636512995117805, "pitch": null, "roll": null}, "v": 2.3268616264702158, "accelerator_pedal_position": 0.28134775899446307, "brake_pedal_position": 0.0, "acceleration": 0.1379375621044871, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02399597693512891, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141220.4418309} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28120451855776474, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.09203703802985679, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3309653740682306, "gear": 1, "accelerator_pedal_position": 0.2808616027216967, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141220.4418309} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.04994177818298, "x": 7.810451558608905, "y": 0.2805191109177052, "z": null, "yaw": 3.1636512995117805, "pitch": null, "roll": null}, "v": 2.3268616264702158, "accelerator_pedal_position": 0.28134775899446307, "brake_pedal_position": 0.0, "acceleration": 0.1379375621044871, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02399597693512891, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141220.4618309} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28120451855776474, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.09203703802985679, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3377844774199072, "gear": 1, "accelerator_pedal_position": 0.28120451855776474, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141220.4618309} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.04994177818298, "x": 7.810451558608905, "y": 0.2805191109177052, "z": null, "yaw": 3.1636512995117805, "pitch": null, "roll": null}, "v": 2.3268616264702158, "accelerator_pedal_position": 0.28134775899446307, "brake_pedal_position": 0.0, "acceleration": 0.1379375621044871, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02399597693512891, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141220.4918308} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28120451855776474, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.09203703802985679, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3377844774199072, "gear": 1, "accelerator_pedal_position": 0.28120451855776474, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141220.4918308} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141220.5218308, "x": 11.553810664886683, "y": 5.27472448965568, "z": null, "yaw": 3.1647856847424443, "pitch": null, "roll": null}, "v": 2.3418601301590787, "accelerator_pedal_position": 0.28120451855776474, "brake_pedal_position": 0.0, "acceleration": 0.1355921457857886, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.024150650399371545, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141220.5218308} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2808797994883635, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.05936380108234253, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3418601301590787, "gear": 1, "accelerator_pedal_position": 0.28120451855776474, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141220.5218308} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.15994167327881, "x": 7.553810664886683, "y": 0.2747244896556804, "z": null, "yaw": 3.1647856847424443, "pitch": null, "roll": null}, "v": 2.3418601301590787, "accelerator_pedal_position": 0.28120451855776474, "brake_pedal_position": 0.0, "acceleration": 0.1355921457857886, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.024150650399371545, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141220.5418308} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2811449164035127, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.05936380108234253, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3445300896293744, "gear": 1, "accelerator_pedal_position": 0.2808797994883635, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141220.5418308} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.15994167327881, "x": 7.553810664886683, "y": 0.2747244896556804, "z": null, "yaw": 3.1647856847424443, "pitch": null, "roll": null}, "v": 2.3418601301590787, "accelerator_pedal_position": 0.28120451855776474, "brake_pedal_position": 0.0, "acceleration": 0.1355921457857886, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.024150650399371545, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141220.5618308} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2811449164035127, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.05936380108234253, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3485749973393473, "gear": 1, "accelerator_pedal_position": 0.2811449164035127, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141220.5618308} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.15994167327881, "x": 7.553810664886683, "y": 0.2747244896556804, "z": null, "yaw": 3.1647856847424443, "pitch": null, "roll": null}, "v": 2.3418601301590787, "accelerator_pedal_position": 0.28120451855776474, "brake_pedal_position": 0.0, "acceleration": 0.1355921457857886, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.024150650399371545, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141220.5818307} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2811449164035127, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.05936380108234253, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3499206866640843, "gear": 1, "accelerator_pedal_position": 0.2811449164035127, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141220.5818307} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.15994167327881, "x": 7.553810664886683, "y": 0.2747244896556804, "z": null, "yaw": 3.1647856847424443, "pitch": null, "roll": null}, "v": 2.3418601301590787, "accelerator_pedal_position": 0.28120451855776474, "brake_pedal_position": 0.0, "acceleration": 0.1355921457857886, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.024150650399371545, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141220.6018307} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2811449164035127, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.05936380108234253, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.352608150869043, "gear": 1, "accelerator_pedal_position": 0.2811449164035127, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141220.6018307} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.15994167327881, "x": 7.553810664886683, "y": 0.2747244896556804, "z": null, "yaw": 3.1647856847424443, "pitch": null, "roll": null}, "v": 2.3418601301590787, "accelerator_pedal_position": 0.28120451855776474, "brake_pedal_position": 0.0, "acceleration": 0.1355921457857886, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.024150650399371545, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141220.6218307} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2811449164035127, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.05936380108234253, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3552904018429706, "gear": 1, "accelerator_pedal_position": 0.2811449164035127, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141220.6218307} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141220.6318307, "x": 11.295540257086282, "y": 5.268599944079677, "z": null, "yaw": 3.165920069973108, "pitch": null, "roll": null}, "v": 2.3566295746295673, "accelerator_pedal_position": 0.2811449164035127, "brake_pedal_position": 0.0, "acceleration": 0.13378721927028853, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.024302961669120805, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141220.6418307} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28303283318989825, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.006674101027602556, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.35796744682227, "gear": 1, "accelerator_pedal_position": 0.2811449164035127, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141220.6418307} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.269941568374634, "x": 7.295540257086282, "y": 0.2685999440796767, "z": null, "yaw": 3.165920069973108, "pitch": null, "roll": null}, "v": 2.3566295746295673, "accelerator_pedal_position": 0.2811449164035127, "brake_pedal_position": 0.0, "acceleration": 0.13378721927028853, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.024302961669120805, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141220.6618307} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2822429610342952, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.006674101027602556, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.362277542293219, "gear": 1, "accelerator_pedal_position": 0.2822429610342952, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141220.6618307} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2822429610342952, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.006674101027602556, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.362277542293219, "gear": 1, "accelerator_pedal_position": 0.2822429610342952, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141220.6718307} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.269941568374634, "x": 7.295540257086282, "y": 0.2685999440796767, "z": null, "yaw": 3.165920069973108, "pitch": null, "roll": null}, "v": 2.3566295746295673, "accelerator_pedal_position": 0.2811449164035127, "brake_pedal_position": 0.0, "acceleration": 0.13378721927028853, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.024302961669120805, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141220.7018306} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2822429610342952, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.006674101027602556, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3664764877001585, "gear": 1, "accelerator_pedal_position": 0.2822429610342952, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141220.7018306} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.269941568374634, "x": 7.295540257086282, "y": 0.2685999440796767, "z": null, "yaw": 3.165920069973108, "pitch": null, "roll": null}, "v": 2.3566295746295673, "accelerator_pedal_position": 0.2811449164035127, "brake_pedal_position": 0.0, "acceleration": 0.13378721927028853, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.024302961669120805, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141220.7218306} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2822429610342952, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.006674101027602556, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3692689793319994, "gear": 1, "accelerator_pedal_position": 0.2822429610342952, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141220.7218306} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141220.7418306, "x": 11.035618398726836, "y": 5.262141205019475, "z": null, "yaw": 3.167054455203772, "pitch": null, "roll": null}, "v": 2.3720560354344844, "accelerator_pedal_position": 0.2822429610342952, "brake_pedal_position": 0.0, "acceleration": 0.139149206340209, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02446204848092534, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141220.7418306} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2744922856785872, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.03294715508341744, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3720560354344844, "gear": 1, "accelerator_pedal_position": 0.2822429610342952, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141220.7418306} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.37994146347046, "x": 7.035618398726836, "y": 0.2621412050194749, "z": null, "yaw": 3.167054455203772, "pitch": null, "roll": null}, "v": 2.3720560354344844, "accelerator_pedal_position": 0.2822429610342952, "brake_pedal_position": 0.0, "acceleration": 0.139149206340209, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02446204848092534, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141220.7618306} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2782974314152824, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.03294715508341744, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.373869301195643, "gear": 1, "accelerator_pedal_position": 0.2744922856785872, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141220.7618306} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.37994146347046, "x": 7.035618398726836, "y": 0.2621412050194749, "z": null, "yaw": 3.167054455203772, "pitch": null, "roll": null}, "v": 2.3720560354344844, "accelerator_pedal_position": 0.2822429610342952, "brake_pedal_position": 0.0, "acceleration": 0.139149206340209, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02446204848092534, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141220.7818305} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2782974314152824, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.03294715508341744, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3772953465523305, "gear": 1, "accelerator_pedal_position": 0.2782974314152824, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141220.7818305} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.37994146347046, "x": 7.035618398726836, "y": 0.2621412050194749, "z": null, "yaw": 3.167054455203772, "pitch": null, "roll": null}, "v": 2.3720560354344844, "accelerator_pedal_position": 0.2822429610342952, "brake_pedal_position": 0.0, "acceleration": 0.139149206340209, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02446204848092534, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141220.8018305} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2782974314152824, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.03294715508341744, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.380711376958041, "gear": 1, "accelerator_pedal_position": 0.2782974314152824, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141220.8018305} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.37994146347046, "x": 7.035618398726836, "y": 0.2621412050194749, "z": null, "yaw": 3.167054455203772, "pitch": null, "roll": null}, "v": 2.3720560354344844, "accelerator_pedal_position": 0.2822429610342952, "brake_pedal_position": 0.0, "acceleration": 0.139149206340209, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02446204848092534, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141220.8218305} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2782974314152824, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.03294715508341744, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.380711376958041, "gear": 1, "accelerator_pedal_position": 0.2782974314152824, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141220.8218305} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141220.8518305, "x": 10.774197627576832, "y": 5.255348510937485, "z": null, "yaw": 3.1681888404344356, "pitch": null, "roll": null}, "v": 2.384117414696969, "accelerator_pedal_position": 0.2782974314152824, "brake_pedal_position": 0.0, "acceleration": 0.11331291714005293, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.024586432576350677, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141220.8518305} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2690672188127595, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.077218003861708, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3852293530843567, "gear": 1, "accelerator_pedal_position": 0.2690672188127595, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141220.8518305} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.489941358566284, "x": 6.774197627576832, "y": 0.2553485109374849, "z": null, "yaw": 3.1681888404344356, "pitch": null, "roll": null}, "v": 2.384117414696969, "accelerator_pedal_position": 0.2782974314152824, "brake_pedal_position": 0.0, "acceleration": 0.11331291714005293, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.024586432576350677, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141220.8718305} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2735522159367996, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.077218003861708, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3852293530843567, "gear": 1, "accelerator_pedal_position": 0.2690672188127595, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141220.8718305} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.489941358566284, "x": 6.774197627576832, "y": 0.2553485109374849, "z": null, "yaw": 3.1681888404344356, "pitch": null, "roll": null}, "v": 2.384117414696969, "accelerator_pedal_position": 0.2782974314152824, "brake_pedal_position": 0.0, "acceleration": 0.11331291714005293, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.024586432576350677, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141220.8918304} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2735522159367996, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.077218003861708, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3868994705507114, "gear": 1, "accelerator_pedal_position": 0.2735522159367996, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141220.8918304} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.489941358566284, "x": 6.774197627576832, "y": 0.2553485109374849, "z": null, "yaw": 3.1681888404344356, "pitch": null, "roll": null}, "v": 2.384117414696969, "accelerator_pedal_position": 0.2782974314152824, "brake_pedal_position": 0.0, "acceleration": 0.11331291714005293, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.024586432576350677, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141220.9118304} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2735522159367996, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.077218003861708, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3885663252128095, "gear": 1, "accelerator_pedal_position": 0.2735522159367996, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141220.9118304} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.489941358566284, "x": 6.774197627576832, "y": 0.2553485109374849, "z": null, "yaw": 3.1681888404344356, "pitch": null, "roll": null}, "v": 2.384117414696969, "accelerator_pedal_position": 0.2782974314152824, "brake_pedal_position": 0.0, "acceleration": 0.11331291714005293, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.024586432576350677, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141220.9318304} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2735522159367996, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.077218003861708, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.390229922334169, "gear": 1, "accelerator_pedal_position": 0.2735522159367996, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141220.9318304} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.489941358566284, "x": 6.774197627576832, "y": 0.2553485109374849, "z": null, "yaw": 3.1681888404344356, "pitch": null, "roll": null}, "v": 2.384117414696969, "accelerator_pedal_position": 0.2782974314152824, "brake_pedal_position": 0.0, "acceleration": 0.11331291714005293, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.024586432576350677, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141220.9518304} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2735522159367996, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.077218003861708, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3927192216319764, "gear": 1, "accelerator_pedal_position": 0.2735522159367996, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141220.9518304} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141220.9618304, "x": 10.511635536115852, "y": 5.248228140497288, "z": null, "yaw": 3.1693232256650994, "pitch": null, "roll": null}, "v": 2.3927192216319764, "accelerator_pedal_position": 0.2735522159367996, "brake_pedal_position": 0.0, "acceleration": 0.0828143357877274, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.024675139510387824, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141220.9718304} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26530898025206096, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.12010426948811735, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3935473649898538, "gear": 1, "accelerator_pedal_position": 0.2735522159367996, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141220.9718304} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.59994125366211, "x": 6.511635536115852, "y": 0.2482281404972877, "z": null, "yaw": 3.1693232256650994, "pitch": null, "roll": null}, "v": 2.3927192216319764, "accelerator_pedal_position": 0.2735522159367996, "brake_pedal_position": 0.0, "acceleration": 0.0828143357877274, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.024675139510387824, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141220.9918303} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26929840758906276, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.12010426948811735, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3941713208636815, "gear": 1, "accelerator_pedal_position": 0.26530898025206096, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141220.9918303} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.59994125366211, "x": 6.511635536115852, "y": 0.2482281404972877, "z": null, "yaw": 3.1693232256650994, "pitch": null, "roll": null}, "v": 2.3927192216319764, "accelerator_pedal_position": 0.2735522159367996, "brake_pedal_position": 0.0, "acceleration": 0.0828143357877274, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.024675139510387824, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141221.0118303} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26929840758906276, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.12010426948811735, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.39529249020908, "gear": 1, "accelerator_pedal_position": 0.26929840758906276, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141221.0118303} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.59994125366211, "x": 6.511635536115852, "y": 0.2482281404972877, "z": null, "yaw": 3.1693232256650994, "pitch": null, "roll": null}, "v": 2.3927192216319764, "accelerator_pedal_position": 0.2735522159367996, "brake_pedal_position": 0.0, "acceleration": 0.0828143357877274, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.024675139510387824, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141221.0318303} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26929840758906276, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.12010426948811735, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.396411465374071, "gear": 1, "accelerator_pedal_position": 0.26929840758906276, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141221.0318303} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.59994125366211, "x": 6.511635536115852, "y": 0.2482281404972877, "z": null, "yaw": 3.1693232256650994, "pitch": null, "roll": null}, "v": 2.3927192216319764, "accelerator_pedal_position": 0.2735522159367996, "brake_pedal_position": 0.0, "acceleration": 0.0828143357877274, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.024675139510387824, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141221.0518303} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26929840758906276, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.12010426948811735, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3980858223303834, "gear": 1, "accelerator_pedal_position": 0.26929840758906276, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141221.0518303} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141221.0718303, "x": 10.248248958020469, "y": 5.240786431357911, "z": null, "yaw": 3.170457610895763, "pitch": null, "roll": null}, "v": 2.3986428483324085, "accelerator_pedal_position": 0.26929840758906276, "brake_pedal_position": 0.0, "acceleration": 0.05564802987645967, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.024736227461669015, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141221.0718303} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2626615318237807, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.15915419867603509, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3986428483324085, "gear": 1, "accelerator_pedal_position": 0.26929840758906276, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141221.0718303} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.709941148757935, "x": 6.2482489580204685, "y": 0.2407864313579111, "z": null, "yaw": 3.170457610895763, "pitch": null, "roll": null}, "v": 2.3986428483324085, "accelerator_pedal_position": 0.26929840758906276, "brake_pedal_position": 0.0, "acceleration": 0.05564802987645967, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.024736227461669015, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141221.0918303} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2658661412166936, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.15915419867603509, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.398926060653673, "gear": 1, "accelerator_pedal_position": 0.2626615318237807, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141221.0918303} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.709941148757935, "x": 6.2482489580204685, "y": 0.2407864313579111, "z": null, "yaw": 3.170457610895763, "pitch": null, "roll": null}, "v": 2.3986428483324085, "accelerator_pedal_position": 0.26929840758906276, "brake_pedal_position": 0.0, "acceleration": 0.05564802987645967, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.024736227461669015, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141221.1118302} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2658661412166936, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.15915419867603509, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.399609098205477, "gear": 1, "accelerator_pedal_position": 0.2658661412166936, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141221.1118302} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.709941148757935, "x": 6.2482489580204685, "y": 0.2407864313579111, "z": null, "yaw": 3.170457610895763, "pitch": null, "roll": null}, "v": 2.3986428483324085, "accelerator_pedal_position": 0.26929840758906276, "brake_pedal_position": 0.0, "acceleration": 0.05564802987645967, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.024736227461669015, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141221.1318302} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2658661412166936, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.15915419867603509, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.400290797812995, "gear": 1, "accelerator_pedal_position": 0.2658661412166936, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141221.1318302} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.709941148757935, "x": 6.2482489580204685, "y": 0.2407864313579111, "z": null, "yaw": 3.170457610895763, "pitch": null, "roll": null}, "v": 2.3986428483324085, "accelerator_pedal_position": 0.26929840758906276, "brake_pedal_position": 0.0, "acceleration": 0.05564802987645967, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.024736227461669015, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141221.1518302} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2658661412166936, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.15915419867603509, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.400971161911218, "gear": 1, "accelerator_pedal_position": 0.2658661412166936, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141221.1518302} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.709941148757935, "x": 6.2482489580204685, "y": 0.2407864313579111, "z": null, "yaw": 3.170457610895763, "pitch": null, "roll": null}, "v": 2.3986428483324085, "accelerator_pedal_position": 0.26929840758906276, "brake_pedal_position": 0.0, "acceleration": 0.05564802987645967, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.024736227461669015, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141221.1718302} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2658661412166936, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.15915419867603509, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.401650192931459, "gear": 1, "accelerator_pedal_position": 0.2658661412166936, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141221.1718302} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141221.1818302, "x": 9.98436256458767, "y": 5.233031026788205, "z": null, "yaw": 3.171591996126427, "pitch": null, "roll": null}, "v": 2.401989209296116, "accelerator_pedal_position": 0.2658661412166936, "brake_pedal_position": 0.0, "acceleration": 0.033868400523779374, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.024770737120338986, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141221.1918302} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25915786395754903, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.201098482758606, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.402327893301354, "gear": 1, "accelerator_pedal_position": 0.2658661412166936, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141221.1918302} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.81994104385376, "x": 5.98436256458767, "y": 0.23303102678820498, "z": null, "yaw": 3.171591996126427, "pitch": null, "roll": null}, "v": 2.401989209296116, "accelerator_pedal_position": 0.2658661412166936, "brake_pedal_position": 0.0, "acceleration": 0.033868400523779374, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.024770737120338986, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141221.2118301} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26237727108159514, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.201098482758606, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4022865980297943, "gear": 1, "accelerator_pedal_position": 0.26237727108159514, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141221.2118301} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.81994104385376, "x": 5.98436256458767, "y": 0.23303102678820498, "z": null, "yaw": 3.171591996126427, "pitch": null, "roll": null}, "v": 2.401989209296116, "accelerator_pedal_position": 0.2658661412166936, "brake_pedal_position": 0.0, "acceleration": 0.033868400523779374, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.024770737120338986, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141221.2318301} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26237727108159514, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.201098482758606, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4024069360834717, "gear": 1, "accelerator_pedal_position": 0.26237727108159514, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141221.2318301} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.81994104385376, "x": 5.98436256458767, "y": 0.23303102678820498, "z": null, "yaw": 3.171591996126427, "pitch": null, "roll": null}, "v": 2.401989209296116, "accelerator_pedal_position": 0.2658661412166936, "brake_pedal_position": 0.0, "acceleration": 0.033868400523779374, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.024770737120338986, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141221.25183} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26237727108159514, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.201098482758606, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4027672427689253, "gear": 1, "accelerator_pedal_position": 0.26237727108159514, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141221.25183} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.81994104385376, "x": 5.98436256458767, "y": 0.23303102678820498, "z": null, "yaw": 3.171591996126427, "pitch": null, "roll": null}, "v": 2.401989209296116, "accelerator_pedal_position": 0.2658661412166936, "brake_pedal_position": 0.0, "acceleration": 0.033868400523779374, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.024770737120338986, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141221.27183} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26237727108159514, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.201098482758606, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4028871095478483, "gear": 1, "accelerator_pedal_position": 0.26237727108159514, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141221.27183} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141221.29183, "x": 9.720213016083505, "y": 5.224967997435072, "z": null, "yaw": 3.1727263813570907, "pitch": null, "roll": null}, "v": 2.403126490606417, "accelerator_pedal_position": 0.26237727108159514, "brake_pedal_position": 0.0, "acceleration": 0.011951450431105515, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.024782465439625485, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141221.29183} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25718762634108866, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.24114884286966423, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.403126490606417, "gear": 1, "accelerator_pedal_position": 0.26237727108159514, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141221.29183} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.929940938949585, "x": 5.720213016083505, "y": 0.2249679974350718, "z": null, "yaw": 3.1727263813570907, "pitch": null, "roll": null}, "v": 2.403126490606417, "accelerator_pedal_position": 0.26237727108159514, "brake_pedal_position": 0.0, "acceleration": 0.011951450431105515, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.024782465439625485, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141221.31183} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25966738311328114, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.24114884286966423, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4027170148878914, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141221.31183} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.929940938949585, "x": 5.720213016083505, "y": 0.2249679974350718, "z": null, "yaw": 3.1727263813570907, "pitch": null, "roll": null}, "v": 2.403126490606417, "accelerator_pedal_position": 0.26237727108159514, "brake_pedal_position": 0.0, "acceleration": 0.011951450431105515, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.024782465439625485, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141221.33183} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25966738311328114, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.24114884286966423, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.402618159440994, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141221.33183} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.929940938949585, "x": 5.720213016083505, "y": 0.2249679974350718, "z": null, "yaw": 3.1727263813570907, "pitch": null, "roll": null}, "v": 2.403126490606417, "accelerator_pedal_position": 0.26237727108159514, "brake_pedal_position": 0.0, "acceleration": 0.011951450431105515, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.024782465439625485, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141221.35183} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25966738311328114, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.24114884286966423, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.402519497760235, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141221.35183} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.929940938949585, "x": 5.720213016083505, "y": 0.2249679974350718, "z": null, "yaw": 3.1727263813570907, "pitch": null, "roll": null}, "v": 2.403126490606417, "accelerator_pedal_position": 0.26237727108159514, "brake_pedal_position": 0.0, "acceleration": 0.011951450431105515, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.024782465439625485, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141221.37183} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25966738311328114, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.24114884286966423, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4024210294619217, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141221.37183} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.929940938949585, "x": 5.720213016083505, "y": 0.2249679974350718, "z": null, "yaw": 3.1727263813570907, "pitch": null, "roll": null}, "v": 2.403126490606417, "accelerator_pedal_position": 0.26237727108159514, "brake_pedal_position": 0.0, "acceleration": 0.011951450431105515, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.024782465439625485, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141221.39183} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25966738311328114, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.24114884286966423, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.402322754163138, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141221.39183} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141221.40183, "x": 9.45605813397002, "y": 5.216604880414797, "z": null, "yaw": 3.1738607665877545, "pitch": null, "roll": null}, "v": 2.4022736887691196, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37782287319597996, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02477367084136264, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141221.41183} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25417585791243663, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.2830942498474164, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.40222467148174, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141221.41183} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.03994083404541, "x": 5.45605813397002, "y": 0.2166048804147973, "z": null, "yaw": 3.1738607665877545, "pitch": null, "roll": null}, "v": 2.4022736887691196, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37782287319597996, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02477367084136264, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141221.43183} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2567845001201307, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.2830942498474164, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.401440676879737, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141221.43183} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.03994083404541, "x": 5.45605813397002, "y": 0.2166048804147973, "z": null, "yaw": 3.1738607665877545, "pitch": null, "roll": null}, "v": 2.4022736887691196, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37782287319597996, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02477367084136264, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141221.45183} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2567845001201307, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.2830942498474164, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.400984139126745, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141221.45183} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.03994083404541, "x": 5.45605813397002, "y": 0.2166048804147973, "z": null, "yaw": 3.1738607665877545, "pitch": null, "roll": null}, "v": 2.4022736887691196, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37782287319597996, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02477367084136264, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141221.47183} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2567845001201307, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.2830942498474164, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.400528495949665, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141221.47183} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.03994083404541, "x": 5.45605813397002, "y": 0.2166048804147973, "z": null, "yaw": 3.1738607665877545, "pitch": null, "roll": null}, "v": 2.4022736887691196, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37782287319597996, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.02477367084136264, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141221.4918299} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2567845001201307, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.2830942498474164, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.400073745512591, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5704048947509155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141221.4918299} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141221.5118299, "x": 9.19208532500858, "y": 5.207947790568128, "z": null, "yaw": 3.1749951518184183, "pitch": null, "roll": null}, "v": 2.3996198859837023, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3775627502712695, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.024746303253318374, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141221.5118299} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2527339525464829, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.32486098999907936, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.399140130515145, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5306673815013354, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141221.5118299} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.149940729141235, "x": 5.1920853250085806, "y": 0.20794779056812818, "z": null, "yaw": 3.1749951518184183, "pitch": null, "roll": null}, "v": 2.3996198859837023, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3775627502712695, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.024746303253318374, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141221.5318298} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2546429667885447, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.32486098999907936, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.398660845147458, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5306673815013354, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141221.5318298} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.149940729141235, "x": 5.1920853250085806, "y": 0.20794779056812818, "z": null, "yaw": 3.1749951518184183, "pitch": null, "roll": null}, "v": 2.3996198859837023, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3775627502712695, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.024746303253318374, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141221.5518298} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2546429667885447, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.32486098999907936, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3979421925839954, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5306673815013354, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141221.5518298} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.149940729141235, "x": 5.1920853250085806, "y": 0.20794779056812818, "z": null, "yaw": 3.1749951518184183, "pitch": null, "roll": null}, "v": 2.3996198859837023, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3775627502712695, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.024746303253318374, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141221.5718298} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2546429667885447, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.32486098999907936, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3972249473500242, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5306673815013354, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141221.5718298} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.149940729141235, "x": 5.1920853250085806, "y": 0.20794779056812818, "z": null, "yaw": 3.1749951518184183, "pitch": null, "roll": null}, "v": 2.3996198859837023, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3775627502712695, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.024746303253318374, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141221.5918298} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2546429667885447, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.32486098999907936, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.396509106483911, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5306673815013354, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141221.5918298} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.149940729141235, "x": 5.1920853250085806, "y": 0.20794779056812818, "z": null, "yaw": 3.1749951518184183, "pitch": null, "roll": null}, "v": 2.3996198859837023, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3775627502712695, "steering_wheel_angle": 0.5704048947509155, "front_wheel_angle": 0.026394107245100704, "heading_rate": 0.024746303253318374, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141221.6118298} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2546429667885447, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.32486098999907936, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3957946670310286, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5306673815013354, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141221.6118298} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141221.6218297, "x": 8.928498813113169, "y": 5.199011853288432, "z": null, "yaw": 3.176057153419552, "pitch": null, "roll": null}, "v": 2.3954379719131396, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3771531293684903, "steering_wheel_angle": 0.5306673815013354, "front_wheel_angle": 0.024542288522862762, "heading_rate": 0.02296927192836453, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141221.6318297} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.252200145687667, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.36711986677006325, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.395081626043739, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5306673815013354, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141221.6318297} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.25994062423706, "x": 4.928498813113169, "y": 0.1990118532884324, "z": null, "yaw": 3.176057153419552, "pitch": null, "roll": null}, "v": 2.3954379719131396, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3771531293684903, "steering_wheel_angle": 0.5306673815013354, "front_wheel_angle": 0.024542288522862762, "heading_rate": 0.02296927192836453, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141221.6518297} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.253332185184805, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.36711986677006325, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3940647774031683, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4908424164271292, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141221.6518297} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.25994062423706, "x": 4.928498813113169, "y": 0.1990118532884324, "z": null, "yaw": 3.176057153419552, "pitch": null, "roll": null}, "v": 2.3954379719131396, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3771531293684903, "steering_wheel_angle": 0.5306673815013354, "front_wheel_angle": 0.024542288522862762, "heading_rate": 0.02296927192836453, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141221.6718297} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.253332185184805, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.36711986677006325, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3931913541913667, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4908424164271292, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141221.6718297} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.25994062423706, "x": 4.928498813113169, "y": 0.1990118532884324, "z": null, "yaw": 3.176057153419552, "pitch": null, "roll": null}, "v": 2.3954379719131396, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3771531293684903, "steering_wheel_angle": 0.5306673815013354, "front_wheel_angle": 0.024542288522862762, "heading_rate": 0.02296927192836453, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141221.6918297} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.253332185184805, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.36711986677006325, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.392319639750072, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4908424164271292, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141221.6918297} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.25994062423706, "x": 4.928498813113169, "y": 0.1990118532884324, "z": null, "yaw": 3.176057153419552, "pitch": null, "roll": null}, "v": 2.3954379719131396, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3771531293684903, "steering_wheel_angle": 0.5306673815013354, "front_wheel_angle": 0.024542288522862762, "heading_rate": 0.02296927192836453, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141221.7118297} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.253332185184805, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.36711986677006325, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3914496304324295, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4908424164271292, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141221.7118297} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141221.7318296, "x": 8.665405306949323, "y": 5.189820876901877, "z": null, "yaw": 3.177046703906893, "pitch": null, "roll": null}, "v": 2.3905813226004997, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37667785672968856, "steering_wheel_angle": 0.4908424164271292, "front_wheel_angle": 0.02268838286485792, "heading_rate": 0.021190520653507204, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141221.7318296} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2494295005616881, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4083047560082939, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3905813226004997, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4908424164271292, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141221.7318296} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.369940519332886, "x": 4.665405306949323, "y": 0.18982087690187743, "z": null, "yaw": 3.177046703906893, "pitch": null, "roll": null}, "v": 2.3905813226004997, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37667785672968856, "steering_wheel_angle": 0.4908424164271292, "front_wheel_angle": 0.02268838286485792, "heading_rate": 0.021190520653507204, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141221.7518296} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2512517114723947, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4083047560082939, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.388664893388437, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.45093085013899276, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141221.7518296} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.369940519332886, "x": 4.665405306949323, "y": 0.18982087690187743, "z": null, "yaw": 3.177046703906893, "pitch": null, "roll": null}, "v": 2.3905813226004997, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37667785672968856, "steering_wheel_angle": 0.4908424164271292, "front_wheel_angle": 0.02268838286485792, "heading_rate": 0.021190520653507204, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141221.7718296} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2512517114723947, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4083047560082939, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3881032209114768, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.45093085013899276, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141221.7718296} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.369940519332886, "x": 4.665405306949323, "y": 0.18982087690187743, "z": null, "yaw": 3.177046703906893, "pitch": null, "roll": null}, "v": 2.3905813226004997, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37667785672968856, "steering_wheel_angle": 0.4908424164271292, "front_wheel_angle": 0.02268838286485792, "heading_rate": 0.021190520653507204, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141221.7918296} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2512517114723947, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4083047560082939, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.386981522760147, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.45093085013899276, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141221.7918296} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.369940519332886, "x": 4.665405306949323, "y": 0.18982087690187743, "z": null, "yaw": 3.177046703906893, "pitch": null, "roll": null}, "v": 2.3905813226004997, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37667785672968856, "steering_wheel_angle": 0.4908424164271292, "front_wheel_angle": 0.02268838286485792, "heading_rate": 0.021190520653507204, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141221.8118296} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2512517114723947, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4083047560082939, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3858620163502704, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.45093085013899276, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141221.8118296} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.369940519332886, "x": 4.665405306949323, "y": 0.18982087690187743, "z": null, "yaw": 3.177046703906893, "pitch": null, "roll": null}, "v": 2.3905813226004997, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37667785672968856, "steering_wheel_angle": 0.4908424164271292, "front_wheel_angle": 0.02268838286485792, "heading_rate": 0.021190520653507204, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141221.8318295} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2512517114723947, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4083047560082939, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3847446968982213, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.45093085013899276, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141221.8318295} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141221.8418295, "x": 8.40294087898746, "y": 5.180402924026376, "z": null, "yaw": 3.177949230406596, "pitch": null, "roll": null}, "v": 2.3841868557898587, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3760528124227043, "steering_wheel_angle": 0.45093085013899276, "front_wheel_angle": 0.020832436505449584, "heading_rate": 0.019404534275038618, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141221.8518295} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24803963791675127, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4479414704829254, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.383629559632656, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.45093085013899276, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141221.8518295} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.47994041442871, "x": 4.40294087898746, "y": 0.18040292402637625, "z": null, "yaw": 3.177949230406596, "pitch": null, "roll": null}, "v": 2.3841868557898587, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3760528124227043, "steering_wheel_angle": 0.45093085013899276, "front_wheel_angle": 0.020832436505449584, "heading_rate": 0.019404534275038618, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141221.8718295} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24952157506967504, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4479414704829254, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.382115286655852, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.41093405645063097, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141221.8718295} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.47994041442871, "x": 4.40294087898746, "y": 0.18040292402637625, "z": null, "yaw": 3.177949230406596, "pitch": null, "roll": null}, "v": 2.3841868557898587, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3760528124227043, "steering_wheel_angle": 0.45093085013899276, "front_wheel_angle": 0.020832436505449584, "heading_rate": 0.019404534275038618, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141221.8918295} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24952157506967504, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4479414704829254, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3807891213265386, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.41093405645063097, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141221.8918295} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.47994041442871, "x": 4.40294087898746, "y": 0.18040292402637625, "z": null, "yaw": 3.177949230406596, "pitch": null, "roll": null}, "v": 2.3841868557898587, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3760528124227043, "steering_wheel_angle": 0.45093085013899276, "front_wheel_angle": 0.020832436505449584, "heading_rate": 0.019404534275038618, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141221.9118295} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24952157506967504, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4479414704829254, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3794655440026538, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.41093405645063097, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141221.9118295} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.47994041442871, "x": 4.40294087898746, "y": 0.18040292402637625, "z": null, "yaw": 3.177949230406596, "pitch": null, "roll": null}, "v": 2.3841868557898587, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3760528124227043, "steering_wheel_angle": 0.45093085013899276, "front_wheel_angle": 0.020832436505449584, "heading_rate": 0.019404534275038618, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141221.9318295} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24952157506967504, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4479414704829254, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.377485017951142, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.41093405645063097, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141221.9318295} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141221.9518294, "x": 8.141226899749237, "y": 5.17078334293128, "z": null, "yaw": 3.178779160393826, "pitch": null, "roll": null}, "v": 2.376826130382963, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37533433105986064, "steering_wheel_angle": 0.41093405645063097, "front_wheel_angle": 0.01897451977899125, "heading_rate": 0.017618963900373312, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141221.9518294} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2477284133908558, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.48890645458317966, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.376826130382963, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.41093405645063097, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141221.9518294} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.589940309524536, "x": 4.1412268997492365, "y": 0.17078334293127995, "z": null, "yaw": 3.178779160393826, "pitch": null, "roll": null}, "v": 2.376826130382963, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37533433105986064, "steering_wheel_angle": 0.41093405645063097, "front_wheel_angle": 0.01897451977899125, "heading_rate": 0.017618963900373312, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141221.9818294} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2485275588666183, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.48890645458317966, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.374517430955346, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.37085033269064555, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141221.9818294} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.589940309524536, "x": 4.1412268997492365, "y": 0.17078334293127995, "z": null, "yaw": 3.178779160393826, "pitch": null, "roll": null}, "v": 2.376826130382963, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37533433105986064, "steering_wheel_angle": 0.41093405645063097, "front_wheel_angle": 0.01897451977899125, "heading_rate": 0.017618963900373312, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141221.9918294} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2485275588666183, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.48890645458317966, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.373081891822457, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.37085033269064555, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141221.9918294} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.589940309524536, "x": 4.1412268997492365, "y": 0.17078334293127995, "z": null, "yaw": 3.178779160393826, "pitch": null, "roll": null}, "v": 2.376826130382963, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37533433105986064, "steering_wheel_angle": 0.41093405645063097, "front_wheel_angle": 0.01897451977899125, "heading_rate": 0.017618963900373312, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141222.0118294} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2485275588666183, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.48890645458317966, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.37236517153918, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.37085033269064555, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141222.0118294} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.589940309524536, "x": 4.1412268997492365, "y": 0.17078334293127995, "z": null, "yaw": 3.178779160393826, "pitch": null, "roll": null}, "v": 2.376826130382963, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37533433105986064, "steering_wheel_angle": 0.41093405645063097, "front_wheel_angle": 0.01897451977899125, "heading_rate": 0.017618963900373312, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141222.0318294} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2485275588666183, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.48890645458317966, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3709338256172163, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.37085033269064555, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141222.0318294} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.589940309524536, "x": 4.1412268997492365, "y": 0.17078334293127995, "z": null, "yaw": 3.178779160393826, "pitch": null, "roll": null}, "v": 2.376826130382963, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37533433105986064, "steering_wheel_angle": 0.41093405645063097, "front_wheel_angle": 0.01897451977899125, "heading_rate": 0.017618963900373312, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141222.0518293} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2485275588666183, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.48890645458317966, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3687920316124305, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.37085033269064555, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141222.0518293} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141222.0618293, "x": 7.880368301580261, "y": 5.160989449834371, "z": null, "yaw": 3.179521891290963, "pitch": null, "roll": null}, "v": 2.3687920316124305, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.374551358470927, "steering_wheel_angle": 0.37085033269064555, "front_wheel_angle": 0.01711456004740242, "heading_rate": 0.0158378094436366, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141222.0718293} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24715510423139772, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5296361164089388, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3680794904568847, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.37085033269064555, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141222.0718293} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.69994020462036, "x": 3.880368301580261, "y": 0.16098944983437136, "z": null, "yaw": 3.179521891290963, "pitch": null, "roll": null}, "v": 2.3687920316124305, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.374551358470927, "steering_wheel_angle": 0.37085033269064555, "front_wheel_angle": 0.01711456004740242, "heading_rate": 0.0158378094436366, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141222.0918293} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24774899929997482, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5296361164089388, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3664850154182457, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.33067964603932737, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141222.0918293} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.69994020462036, "x": 3.880368301580261, "y": 0.16098944983437136, "z": null, "yaw": 3.179521891290963, "pitch": null, "roll": null}, "v": 2.3687920316124305, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.374551358470927, "steering_wheel_angle": 0.37085033269064555, "front_wheel_angle": 0.01711456004740242, "heading_rate": 0.0158378094436366, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141222.1118293} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24774899929997482, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5296361164089388, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.364967843680889, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.33067964603932737, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141222.1118293} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.69994020462036, "x": 3.880368301580261, "y": 0.16098944983437136, "z": null, "yaw": 3.179521891290963, "pitch": null, "roll": null}, "v": 2.3687920316124305, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.374551358470927, "steering_wheel_angle": 0.37085033269064555, "front_wheel_angle": 0.01711456004740242, "heading_rate": 0.0158378094436366, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141222.1318293} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24774899929997482, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5296361164089388, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3634536231339567, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.33067964603932737, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141222.1318293} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.69994020462036, "x": 3.880368301580261, "y": 0.16098944983437136, "z": null, "yaw": 3.179521891290963, "pitch": null, "roll": null}, "v": 2.3687920316124305, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.374551358470927, "steering_wheel_angle": 0.37085033269064555, "front_wheel_angle": 0.01711456004740242, "heading_rate": 0.0158378094436366, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141222.1518292} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24774899929997482, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5296361164089388, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3619423471201157, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.33067964603932737, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141222.1518292} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141222.1718292, "x": 7.620410244901047, "y": 5.151043926829557, "z": null, "yaw": 3.1801918763289527, "pitch": null, "roll": null}, "v": 2.360434009000328, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37373818755847005, "steering_wheel_angle": 0.33067964603932737, "front_wheel_angle": 0.015252562350377087, "heading_rate": 0.014064632441704817, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141222.1718292} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24477791992105002, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5628905340178035, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.360434009000328, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.33067964603932737, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141222.1718292} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.80994009971619, "x": 3.6204102449010467, "y": 0.1510439268295567, "z": null, "yaw": 3.1801918763289527, "pitch": null, "roll": null}, "v": 2.360434009000328, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37373818755847005, "steering_wheel_angle": 0.33067964603932737, "front_wheel_angle": 0.015252562350377087, "heading_rate": 0.014064632441704817, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141222.1918292} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24613076442206053, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5628905340178035, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3585573977091965, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.29042982993407446, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141222.1918292} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.80994009971619, "x": 3.6204102449010467, "y": 0.1510439268295567, "z": null, "yaw": 3.1801918763289527, "pitch": null, "roll": null}, "v": 2.360434009000328, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37373818755847005, "steering_wheel_angle": 0.33067964603932737, "front_wheel_angle": 0.015252562350377087, "heading_rate": 0.014064632441704817, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141222.2118292} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24613076442206053, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5628905340178035, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3568534554644365, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.29042982993407446, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141222.2118292} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.80994009971619, "x": 3.6204102449010467, "y": 0.1510439268295567, "z": null, "yaw": 3.1801918763289527, "pitch": null, "roll": null}, "v": 2.360434009000328, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37373818755847005, "steering_wheel_angle": 0.33067964603932737, "front_wheel_angle": 0.015252562350377087, "heading_rate": 0.014064632441704817, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141222.2318292} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24613076442206053, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5628905340178035, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3551528222212155, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.29042982993407446, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141222.2318292} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.80994009971619, "x": 3.6204102449010467, "y": 0.1510439268295567, "z": null, "yaw": 3.1801918763289527, "pitch": null, "roll": null}, "v": 2.360434009000328, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37373818755847005, "steering_wheel_angle": 0.33067964603932737, "front_wheel_angle": 0.015252562350377087, "heading_rate": 0.014064632441704817, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141222.2518291} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24613076442206053, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5628905340178035, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3534554903972578, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.29042982993407446, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141222.2518291} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.80994009971619, "x": 3.6204102449010467, "y": 0.1510439268295567, "z": null, "yaw": 3.1801918763289527, "pitch": null, "roll": null}, "v": 2.360434009000328, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37373818755847005, "steering_wheel_angle": 0.33067964603932737, "front_wheel_angle": 0.015252562350377087, "heading_rate": 0.014064632441704817, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141222.2718291} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24613076442206053, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5628905340178035, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3517614524317416, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.29042982993407446, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141222.2718291} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141222.281829, "x": 7.361442683062068, "y": 5.140973519783614, "z": null, "yaw": 3.1807744962652835, "pitch": null, "roll": null}, "v": 2.3509156662889903, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3728138280144796, "steering_wheel_angle": 0.29042982993407446, "front_wheel_angle": 0.013388895745336098, "heading_rate": 0.012296111612967947, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141222.291829} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23738457342901137, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5657976970401424, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.350070700785224, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.29042982993407446, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141222.291829} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.91993999481201, "x": 3.3614426830620676, "y": 0.14097351978361417, "z": null, "yaw": 3.1807744962652835, "pitch": null, "roll": null}, "v": 2.3509156662889903, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3728138280144796, "steering_wheel_angle": 0.29042982993407446, "front_wheel_angle": 0.013388895745336098, "heading_rate": 0.012296111612967947, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141222.311829} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24147900093436186, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5657976970401424, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3472904841888247, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.29042982993407446, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141222.311829} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.91993999481201, "x": 3.3614426830620676, "y": 0.14097351978361417, "z": null, "yaw": 3.1807744962652835, "pitch": null, "roll": null}, "v": 2.3509156662889903, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3728138280144796, "steering_wheel_angle": 0.29042982993407446, "front_wheel_angle": 0.013388895745336098, "heading_rate": 0.012296111612967947, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141222.331829} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24147900093436186, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5657976970401424, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3450272117756765, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.29042982993407446, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141222.331829} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.91993999481201, "x": 3.3614426830620676, "y": 0.14097351978361417, "z": null, "yaw": 3.1807744962652835, "pitch": null, "roll": null}, "v": 2.3509156662889903, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3728138280144796, "steering_wheel_angle": 0.29042982993407446, "front_wheel_angle": 0.013388895745336098, "heading_rate": 0.012296111612967947, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141222.351829} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24147900093436186, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5657976970401424, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3427683239959434, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.29042982993407446, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141222.351829} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.91993999481201, "x": 3.3614426830620676, "y": 0.14097351978361417, "z": null, "yaw": 3.1807744962652835, "pitch": null, "roll": null}, "v": 2.3509156662889903, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3728138280144796, "steering_wheel_angle": 0.29042982993407446, "front_wheel_angle": 0.013388895745336098, "heading_rate": 0.012296111612967947, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141222.371829} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24147900093436186, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5657976970401424, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.340513810315241, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.29042982993407446, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141222.371829} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141222.391829, "x": 7.103679821517962, "y": 5.130801277713829, "z": null, "yaw": 3.1813498347586298, "pitch": null, "roll": null}, "v": 2.3382636602314366, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.371587952459161, "steering_wheel_angle": 0.29042982993407446, "front_wheel_angle": 0.013388895745336098, "heading_rate": 0.01222993719385014, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141222.391829} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24410867728294325, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6119885175500824, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3382636602314366, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.29042982993407446, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141222.391829} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.02993988990784, "x": 3.1036798215179617, "y": 0.13080127771382877, "z": null, "yaw": 3.1813498347586298, "pitch": null, "roll": null}, "v": 2.3382636602314366, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.371587952459161, "steering_wheel_angle": 0.29042982993407446, "front_wheel_angle": 0.013388895745336098, "heading_rate": 0.01222993719385014, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141222.411829} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24276304973577573, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6119885175500824, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3363464138139802, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2500833905013909, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141222.411829} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.02993988990784, "x": 3.1036798215179617, "y": 0.13080127771382877, "z": null, "yaw": 3.1813498347586298, "pitch": null, "roll": null}, "v": 2.3382636602314366, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.371587952459161, "steering_wheel_angle": 0.29042982993407446, "front_wheel_angle": 0.013388895745336098, "heading_rate": 0.01222993719385014, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141222.431829} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24276304973577573, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6119885175500824, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3342647528460767, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2500833905013909, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141222.431829} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.02993988990784, "x": 3.1036798215179617, "y": 0.13080127771382877, "z": null, "yaw": 3.1813498347586298, "pitch": null, "roll": null}, "v": 2.3382636602314366, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.371587952459161, "steering_wheel_angle": 0.29042982993407446, "front_wheel_angle": 0.013388895745336098, "heading_rate": 0.01222993719385014, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141222.451829} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24276304973577573, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6119885175500824, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.332187115685446, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2500833905013909, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141222.451829} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.02993988990784, "x": 3.1036798215179617, "y": 0.13080127771382877, "z": null, "yaw": 3.1813498347586298, "pitch": null, "roll": null}, "v": 2.3382636602314366, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.371587952459161, "steering_wheel_angle": 0.29042982993407446, "front_wheel_angle": 0.013388895745336098, "heading_rate": 0.01222993719385014, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141222.471829} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24276304973577573, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6119885175500824, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.330113492828356, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2500833905013909, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141222.471829} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.02993988990784, "x": 3.1036798215179617, "y": 0.13080127771382877, "z": null, "yaw": 3.1813498347586298, "pitch": null, "roll": null}, "v": 2.3382636602314366, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.371587952459161, "steering_wheel_angle": 0.29042982993407446, "front_wheel_angle": 0.013388895745336098, "heading_rate": 0.01222993719385014, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141222.491829} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24276304973577573, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6119885175500824, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.328043874799441, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2500833905013909, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141222.491829} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141222.501829, "x": 6.847232178986148, "y": 5.120540807024053, "z": null, "yaw": 3.1818522658706305, "pitch": null, "roll": null}, "v": 2.327010564642228, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3705003099116768, "steering_wheel_angle": 0.2500833905013909, "front_wheel_angle": 0.011522756881755665, "heading_rate": 0.010474517099730242, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141222.511829} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24516378009946352, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6609216506354181, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3259782521515975, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2500833905013909, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141222.511829} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.13993978500366, "x": 2.8472321789861477, "y": 0.12054080702405301, "z": null, "yaw": 3.1818522658706305, "pitch": null, "roll": null}, "v": 2.327010564642228, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3705003099116768, "steering_wheel_angle": 0.2500833905013909, "front_wheel_angle": 0.011522756881755665, "heading_rate": 0.010474517099730242, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141222.5318289} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24393770654827895, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6609216506354181, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3242165619666304, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.16915348243796494, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141222.5318289} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.13993978500366, "x": 2.8472321789861477, "y": 0.12054080702405301, "z": null, "yaw": 3.1818522658706305, "pitch": null, "roll": null}, "v": 2.327010564642228, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3705003099116768, "steering_wheel_angle": 0.2500833905013909, "front_wheel_angle": 0.011522756881755665, "heading_rate": 0.010474517099730242, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141222.5518289} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24393770654827895, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6609216506354181, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.322305084689446, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.16915348243796494, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141222.5518289} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.13993978500366, "x": 2.8472321789861477, "y": 0.12054080702405301, "z": null, "yaw": 3.1818522658706305, "pitch": null, "roll": null}, "v": 2.327010564642228, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3705003099116768, "steering_wheel_angle": 0.2500833905013909, "front_wheel_angle": 0.011522756881755665, "heading_rate": 0.010474517099730242, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141222.5718288} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24393770654827895, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6609216506354181, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3203972930900703, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.16915348243796494, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141222.5718288} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.13993978500366, "x": 2.8472321789861477, "y": 0.12054080702405301, "z": null, "yaw": 3.1818522658706305, "pitch": null, "roll": null}, "v": 2.327010564642228, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3705003099116768, "steering_wheel_angle": 0.2500833905013909, "front_wheel_angle": 0.011522756881755665, "heading_rate": 0.010474517099730242, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141222.5918288} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24393770654827895, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6609216506354181, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3184931786066745, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.16915348243796494, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141222.5918288} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141222.6118288, "x": 6.591990091909052, "y": 5.110212657483471, "z": null, "yaw": 3.1822233068444366, "pitch": null, "roll": null}, "v": 2.316592732702349, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36949565552721086, "steering_wheel_angle": 0.16915348243796494, "front_wheel_angle": 0.007785531608634333, "heading_rate": 0.007045418111761972, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141222.6118288} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24640839681045643, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.711806360860535, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.316592732702349, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.16915348243796494, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141222.6118288} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.24993968009949, "x": 2.591990091909052, "y": 0.11021265748347098, "z": null, "yaw": 3.1822233068444366, "pitch": null, "roll": null}, "v": 2.316592732702349, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36949565552721086, "steering_wheel_angle": 0.16915348243796494, "front_wheel_angle": 0.007785531608634333, "heading_rate": 0.007045418111761972, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141222.6318288} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.245155331916071, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.711806360860535, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3150046344208426, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1285674159892015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141222.6318288} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.24993968009949, "x": 2.591990091909052, "y": 0.11021265748347098, "z": null, "yaw": 3.1822233068444366, "pitch": null, "roll": null}, "v": 2.316592732702349, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36949565552721086, "steering_wheel_angle": 0.16915348243796494, "front_wheel_angle": 0.007785531608634333, "heading_rate": 0.007045418111761972, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141222.6518288} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.245155331916071, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.711806360860535, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3132630358929833, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1285674159892015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141222.6518288} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.24993968009949, "x": 2.591990091909052, "y": 0.11021265748347098, "z": null, "yaw": 3.1822233068444366, "pitch": null, "roll": null}, "v": 2.316592732702349, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36949565552721086, "steering_wheel_angle": 0.16915348243796494, "front_wheel_angle": 0.007785531608634333, "heading_rate": 0.007045418111761972, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141222.6718287} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.245155331916071, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.711806360860535, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3115247891630823, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1285674159892015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141222.6718287} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.24993968009949, "x": 2.591990091909052, "y": 0.11021265748347098, "z": null, "yaw": 3.1822233068444366, "pitch": null, "roll": null}, "v": 2.316592732702349, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36949565552721086, "steering_wheel_angle": 0.16915348243796494, "front_wheel_angle": 0.007785531608634333, "heading_rate": 0.007045418111761972, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141222.6918287} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.245155331916071, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.711806360860535, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3097898865724082, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1285674159892015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141222.6918287} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.24993968009949, "x": 2.591990091909052, "y": 0.11021265748347098, "z": null, "yaw": 3.1822233068444366, "pitch": null, "roll": null}, "v": 2.316592732702349, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36949565552721086, "steering_wheel_angle": 0.16915348243796494, "front_wheel_angle": 0.007785531608634333, "heading_rate": 0.007045418111761972, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141222.7118287} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.245155331916071, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.711806360860535, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3080583204839367, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1285674159892015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141222.7118287} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141222.7218287, "x": 6.337839890967324, "y": 5.099849606130977, "z": null, "yaw": 3.182484751138523, "pitch": null, "roll": null}, "v": 2.3071937862473737, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3685911209853536, "steering_wheel_angle": 0.1285674159892015, "front_wheel_angle": 0.005914336075965883, "heading_rate": 0.005330343183738297, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141222.7318287} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24459608173060188, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7433048866989131, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3063300832822744, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1285674159892015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141222.7318287} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.35993957519531, "x": 2.3378398909673237, "y": 0.09984960613097726, "z": null, "yaw": 3.182484751138523, "pitch": null, "roll": null}, "v": 2.3071937862473737, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3685911209853536, "steering_wheel_angle": 0.1285674159892015, "front_wheel_angle": 0.005914336075965883, "heading_rate": 0.005330343183738297, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141222.7518287} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24479347452386152, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7433048866989131, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.304535294693508, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.08790300478450272, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141222.7518287} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.35993957519531, "x": 2.3378398909673237, "y": 0.09984960613097726, "z": null, "yaw": 3.182484751138523, "pitch": null, "roll": null}, "v": 2.3071937862473737, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3685911209853536, "steering_wheel_angle": 0.1285674159892015, "front_wheel_angle": 0.005914336075965883, "heading_rate": 0.005330343183738297, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141222.7718287} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24479347452386152, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7433048866989131, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3027686162661523, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.08790300478450272, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141222.7718287} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.35993957519531, "x": 2.3378398909673237, "y": 0.09984960613097726, "z": null, "yaw": 3.182484751138523, "pitch": null, "roll": null}, "v": 2.3071937862473737, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3685911209853536, "steering_wheel_angle": 0.1285674159892015, "front_wheel_angle": 0.005914336075965883, "heading_rate": 0.005330343183738297, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141222.7918286} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24479347452386152, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7433048866989131, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.301005330499794, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.08790300478450272, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141222.7918286} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.35993957519531, "x": 2.3378398909673237, "y": 0.09984960613097726, "z": null, "yaw": 3.182484751138523, "pitch": null, "roll": null}, "v": 2.3071937862473737, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3685911209853536, "steering_wheel_angle": 0.1285674159892015, "front_wheel_angle": 0.005914336075965883, "heading_rate": 0.005330343183738297, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141222.8118286} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24479347452386152, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7433048866989131, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.297488905939288, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.08790300478450272, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141222.8118286} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141222.8318286, "x": 6.084747188695949, "y": 5.089471143023564, "z": null, "yaw": 3.1826730434623194, "pitch": null, "roll": null}, "v": 2.297488905939288, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36765899802610547, "steering_wheel_angle": 0.08790300478450272, "front_wheel_angle": 0.00404153630816374, "heading_rate": 0.0036271231981098817, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141222.8318286} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2452400218240066, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7793210061944372, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2966119081167684, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.08790300478450272, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141222.8318286} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.46993947029114, "x": 2.0847471886959488, "y": 0.08947114302356418, "z": null, "yaw": 3.1826730434623194, "pitch": null, "roll": null}, "v": 2.297488905939288, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36765899802610547, "steering_wheel_angle": 0.08790300478450272, "front_wheel_angle": 0.00404153630816374, "heading_rate": 0.0036271231981098817, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141222.8618286} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24495636121867487, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7793210061944372, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2949162273559387, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0471550228213084, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141222.8618286} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.46993947029114, "x": 2.0847471886959488, "y": 0.08947114302356418, "z": null, "yaw": 3.1826730434623194, "pitch": null, "roll": null}, "v": 2.297488905939288, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36765899802610547, "steering_wheel_angle": 0.08790300478450272, "front_wheel_angle": 0.00404153630816374, "heading_rate": 0.0036271231981098817, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141222.8818285} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24495636121867487, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7793210061944372, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2931883570048623, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0471550228213084, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141222.8818285} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.46993947029114, "x": 2.0847471886959488, "y": 0.08947114302356418, "z": null, "yaw": 3.1826730434623194, "pitch": null, "roll": null}, "v": 2.297488905939288, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36765899802610547, "steering_wheel_angle": 0.08790300478450272, "front_wheel_angle": 0.00404153630816374, "heading_rate": 0.0036271231981098817, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141222.8918285} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24495636121867487, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7793210061944372, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.291463798167527, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0471550228213084, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141222.8918285} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.46993947029114, "x": 2.0847471886959488, "y": 0.08947114302356418, "z": null, "yaw": 3.1826730434623194, "pitch": null, "roll": null}, "v": 2.297488905939288, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36765899802610547, "steering_wheel_angle": 0.08790300478450272, "front_wheel_angle": 0.00404153630816374, "heading_rate": 0.0036271231981098817, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141222.9118285} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24495636121867487, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7793210061944372, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.289742543308249, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0471550228213084, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141222.9118285} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.46993947029114, "x": 2.0847471886959488, "y": 0.08947114302356418, "z": null, "yaw": 3.1826730434623194, "pitch": null, "roll": null}, "v": 2.297488905939288, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36765899802610547, "steering_wheel_angle": 0.08790300478450272, "front_wheel_angle": 0.00404153630816374, "heading_rate": 0.0036271231981098817, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141222.9318285} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24495636121867487, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7793210061944372, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2888831525212985, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0471550228213084, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141222.9318285} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141222.9418285, "x": 5.832710188516042, "y": 5.079097667280153, "z": null, "yaw": 3.182780798234019, "pitch": null, "roll": null}, "v": 2.2880245849126153, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3667517942572763, "steering_wheel_angle": 0.0471550228213084, "front_wheel_angle": 0.002166897156093097, "heading_rate": 0.0019366881742190452, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141222.9618285} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24550648149142873, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8146638534173425, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2854881943199166, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0471550228213084, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141222.9618285} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.57993936538696, "x": 1.8327101885160424, "y": 0.07909766728015288, "z": null, "yaw": 3.182780798234019, "pitch": null, "roll": null}, "v": 2.2880245849126153, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3667517942572763, "steering_wheel_angle": 0.0471550228213084, "front_wheel_angle": 0.002166897156093097, "heading_rate": 0.0019366881742190452, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141222.9718285} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24517539900424498, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8146638534173425, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.284667259687333, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0471550228213084, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141222.9718285} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.57993936538696, "x": 1.8327101885160424, "y": 0.07909766728015288, "z": null, "yaw": 3.182780798234019, "pitch": null, "roll": null}, "v": 2.2880245849126153, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3667517942572763, "steering_wheel_angle": 0.0471550228213084, "front_wheel_angle": 0.002166897156093097, "heading_rate": 0.0019366881742190452, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141222.9918284} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24517539900424498, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8146638534173425, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2829863809644717, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0471550228213084, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141222.9918284} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.57993936538696, "x": 1.8327101885160424, "y": 0.07909766728015288, "z": null, "yaw": 3.182780798234019, "pitch": null, "roll": null}, "v": 2.2880245849126153, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3667517942572763, "steering_wheel_angle": 0.0471550228213084, "front_wheel_angle": 0.002166897156093097, "heading_rate": 0.0019366881742190452, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141223.0218284} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24517539900424498, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8146638534173425, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.28130871683389, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0471550228213084, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141223.0218284} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.57993936538696, "x": 1.8327101885160424, "y": 0.07909766728015288, "z": null, "yaw": 3.182780798234019, "pitch": null, "roll": null}, "v": 2.2880245849126153, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3667517942572763, "steering_wheel_angle": 0.0471550228213084, "front_wheel_angle": 0.002166897156093097, "heading_rate": 0.0019366881742190452, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141223.0418284} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24517539900424498, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8146638534173425, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2796342600225645, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0471550228213084, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141223.0418284} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141223.0518284, "x": 5.581703381141279, "y": 5.068742678885824, "z": null, "yaw": 3.182873907241926, "pitch": null, "roll": null}, "v": 2.278798232094372, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36586912543068295, "steering_wheel_angle": 0.0471550228213084, "front_wheel_angle": 0.002166897156093097, "heading_rate": 0.0019288785691509477, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141223.0618284} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2420090852813733, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8170956601107231, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.27796300327783, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0471550228213084, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141223.0618284} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.68993926048279, "x": 1.5817033811412786, "y": 0.0687426788858243, "z": null, "yaw": 3.182873907241926, "pitch": null, "roll": null}, "v": 2.278798232094372, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36586912543068295, "steering_wheel_angle": 0.0471550228213084, "front_wheel_angle": 0.002166897156093097, "heading_rate": 0.0019288785691509477, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141223.0818284} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24344960348222114, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8170956601107231, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2758993392216316, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.006321259269364581, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141223.0818284} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.68993926048279, "x": 1.5817033811412786, "y": 0.0687426788858243, "z": null, "yaw": 3.182873907241926, "pitch": null, "roll": null}, "v": 2.278798232094372, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36586912543068295, "steering_wheel_angle": 0.0471550228213084, "front_wheel_angle": 0.002166897156093097, "heading_rate": 0.0019288785691509477, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141223.1018283} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24344960348222114, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8170956601107231, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2740195948447237, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.006321259269364581, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141223.1018283} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.68993926048279, "x": 1.5817033811412786, "y": 0.0687426788858243, "z": null, "yaw": 3.182873907241926, "pitch": null, "roll": null}, "v": 2.278798232094372, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36586912543068295, "steering_wheel_angle": 0.0471550228213084, "front_wheel_angle": 0.002166897156093097, "heading_rate": 0.0019288785691509477, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141223.1118283} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24344960348222114, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8170956601107231, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.273081068753166, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.006321259269364581, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141223.1118283} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.68993926048279, "x": 1.5817033811412786, "y": 0.0687426788858243, "z": null, "yaw": 3.182873907241926, "pitch": null, "roll": null}, "v": 2.278798232094372, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36586912543068295, "steering_wheel_angle": 0.0471550228213084, "front_wheel_angle": 0.002166897156093097, "heading_rate": 0.0019288785691509477, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141223.1318283} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24344960348222114, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8170956601107231, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2702708624764107, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.006321259269364581, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141223.1318283} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141223.1618283, "x": 5.331770603756003, "y": 5.058414688256778, "z": null, "yaw": 3.1829010428198097, "pitch": null, "roll": null}, "v": 2.2684018579952214, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3648765627933228, "steering_wheel_angle": 0.006321259269364581, "front_wheel_angle": 0.0002903229743743502, "heading_rate": 0.0002572535910126992, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141223.1618283} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24650327620701812, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8697708634368834, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2684018579952214, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.006321259269364581, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141223.1618283} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.79993915557861, "x": 1.331770603756003, "y": 0.05841468825677776, "z": null, "yaw": 3.1829010428198097, "pitch": null, "roll": null}, "v": 2.2684018579952214, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3648765627933228, "steering_wheel_angle": 0.006321259269364581, "front_wheel_angle": 0.0002903229743743502, "heading_rate": 0.0002572535910126992, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141223.1818283} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24497352175389864, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8697708634368834, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2669179441374316, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.0345839132357143, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141223.1818283} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.79993915557861, "x": 1.331770603756003, "y": 0.05841468825677776, "z": null, "yaw": 3.1829010428198097, "pitch": null, "roll": null}, "v": 2.2684018579952214, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3648765627933228, "steering_wheel_angle": 0.006321259269364581, "front_wheel_angle": 0.0002903229743743502, "heading_rate": 0.0002572535910126992, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141223.2018282} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24497352175389864, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8697708634368834, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2652457304601388, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.0345839132357143, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141223.2018282} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.79993915557861, "x": 1.331770603756003, "y": 0.05841468825677776, "z": null, "yaw": 3.1829010428198097, "pitch": null, "roll": null}, "v": 2.2684018579952214, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3648765627933228, "steering_wheel_angle": 0.006321259269364581, "front_wheel_angle": 0.0002903229743743502, "heading_rate": 0.0002572535910126992, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141223.2218282} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24497352175389864, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8697708634368834, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2635767029471006, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.0345839132357143, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141223.2218282} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.79993915557861, "x": 1.331770603756003, "y": 0.05841468825677776, "z": null, "yaw": 3.1829010428198097, "pitch": null, "roll": null}, "v": 2.2684018579952214, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3648765627933228, "steering_wheel_angle": 0.006321259269364581, "front_wheel_angle": 0.0002903229743743502, "heading_rate": 0.0002572535910126992, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141223.2318282} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24497352175389864, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8697708634368834, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2627433817562332, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.0345839132357143, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141223.2318282} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.79993915557861, "x": 1.331770603756003, "y": 0.05841468825677776, "z": null, "yaw": 3.1829010428198097, "pitch": null, "roll": null}, "v": 2.2684018579952214, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3648765627933228, "steering_wheel_angle": 0.006321259269364581, "front_wheel_angle": 0.0002903229743743502, "heading_rate": 0.0002572535910126992, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141223.2618282} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24497352175389864, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8697708634368834, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2602481776957912, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.0345839132357143, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141223.2618282} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141223.2718282, "x": 5.082900082845418, "y": 5.048134464172133, "z": null, "yaw": 3.1828401081089908, "pitch": null, "roll": null}, "v": 2.2594180265340844, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.364020599512976, "steering_wheel_angle": -0.0345839132357143, "front_wheel_angle": -0.0015889595579621075, "heading_rate": -0.0014023933164591844, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141223.2818282} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24125177618633126, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8569414974033526, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.258588665648573, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.0345839132357143, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141223.2818282} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.90993905067444, "x": 1.082900082845418, "y": 0.04813446417213285, "z": null, "yaw": 3.1828401081089908, "pitch": null, "roll": null}, "v": 2.2594180265340844, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.364020599512976, "steering_wheel_angle": -0.0345839132357143, "front_wheel_angle": -0.0015889595579621075, "heading_rate": -0.0014023933164591844, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141223.2918282} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24295882058322305, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8569414974033526, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.257527485051335, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.0345839132357143, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141223.2918282} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.90993905067444, "x": 1.082900082845418, "y": 0.04813446417213285, "z": null, "yaw": 3.1828401081089908, "pitch": null, "roll": null}, "v": 2.2594180265340844, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.364020599512976, "steering_wheel_angle": -0.0345839132357143, "front_wheel_angle": -0.0015889595579621075, "heading_rate": -0.0014023933164591844, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141223.3218281} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24295882058322305, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8569414974033526, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.251820188502563, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.0345839132357143, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141223.3218281} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.90993905067444, "x": 1.082900082845418, "y": 0.04813446417213285, "z": null, "yaw": 3.1828401081089908, "pitch": null, "roll": null}, "v": 2.2594180265340844, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.364020599512976, "steering_wheel_angle": -0.0345839132357143, "front_wheel_angle": -0.0015889595579621075, "heading_rate": -0.0014023933164591844, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141223.361828} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24295882058322305, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8569414974033526, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.248978730512579, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.0345839132357143, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141223.361828} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141223.381828, "x": 4.835095668197894, "y": 5.037915059250863, "z": null, "yaw": 3.1827718324455243, "pitch": null, "roll": null}, "v": 2.248978730512579, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3630279898286086, "steering_wheel_angle": -0.0345839132357143, "front_wheel_angle": -0.0015889595579621075, "heading_rate": -0.0013959137722592315, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141223.381828} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24723639459150948, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9203188134545061, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.248978730512579, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.0345839132357143, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141223.381828} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.01993894577026, "x": 0.8350956681978943, "y": 0.037915059250862804, "z": null, "yaw": 3.1827718324455243, "pitch": null, "roll": null}, "v": 2.248978730512579, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3630279898286086, "steering_wheel_angle": -0.0345839132357143, "front_wheel_angle": -0.0015889595579621075, "heading_rate": -0.0013959137722592315, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141223.401828} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2451238261277201, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9203188134545061, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2476233639604657, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.07550298385812422, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141223.401828} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.01993894577026, "x": 0.8350956681978943, "y": 0.037915059250862804, "z": null, "yaw": 3.1827718324455243, "pitch": null, "roll": null}, "v": 2.248978730512579, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3630279898286086, "steering_wheel_angle": -0.0345839132357143, "front_wheel_angle": -0.0015889595579621075, "heading_rate": -0.0013959137722592315, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141223.421828} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2451238261277201, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9203188134545061, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2460066245713413, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.07550298385812422, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141223.421828} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.01993894577026, "x": 0.8350956681978943, "y": 0.037915059250862804, "z": null, "yaw": 3.1827718324455243, "pitch": null, "roll": null}, "v": 2.248978730512579, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3630279898286086, "steering_wheel_angle": -0.0345839132357143, "front_wheel_angle": -0.0015889595579621075, "heading_rate": -0.0013959137722592315, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141223.441828} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2451238261277201, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9203188134545061, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2443929532091627, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.07550298385812422, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141223.441828} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.01993894577026, "x": 0.8350956681978943, "y": 0.037915059250862804, "z": null, "yaw": 3.1827718324455243, "pitch": null, "roll": null}, "v": 2.248978730512579, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3630279898286086, "steering_wheel_angle": -0.0345839132357143, "front_wheel_angle": -0.0015889595579621075, "heading_rate": -0.0013959137722592315, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141223.461828} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2451238261277201, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9203188134545061, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.241978183708433, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.07550298385812422, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141223.461828} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.01993894577026, "x": 0.8350956681978943, "y": 0.037915059250862804, "z": null, "yaw": 3.1827718324455243, "pitch": null, "roll": null}, "v": 2.248978730512579, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3630279898286086, "steering_wheel_angle": -0.0345839132357143, "front_wheel_angle": -0.0015889595579621075, "heading_rate": -0.0013959137722592315, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141223.481828} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2451238261277201, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9203188134545061, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2411747871319387, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.07550298385812422, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141223.481828} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141223.491828, "x": 4.588336023749122, "y": 5.027763045097871, "z": null, "yaw": 3.182630044861556, "pitch": null, "roll": null}, "v": 2.2403721524287077, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3622112814352158, "steering_wheel_angle": -0.07550298385812422, "front_wheel_angle": -0.0034708521224459843, "heading_rate": -0.00303751236946147, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141223.501828} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24527583549081403, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9437203400749963, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2387786658227955, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.11640437385711908, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141223.501828} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.12993884086609, "x": 0.5883360237491218, "y": 0.02776304509787142, "z": null, "yaw": 3.182630044861556, "pitch": null, "roll": null}, "v": 2.2403721524287077, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3622112814352158, "steering_wheel_angle": -0.07550298385812422, "front_wheel_angle": -0.0034708521224459843, "heading_rate": -0.00303751236946147, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141223.521828} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24514122461117155, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9437203400749963, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2379878032166056, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.11640437385711908, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141223.521828} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.12993884086609, "x": 0.5883360237491218, "y": 0.02776304509787142, "z": null, "yaw": 3.182630044861556, "pitch": null, "roll": null}, "v": 2.2403721524287077, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3622112814352158, "steering_wheel_angle": -0.07550298385812422, "front_wheel_angle": -0.0034708521224459843, "heading_rate": -0.00303751236946147, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141223.541828} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24514122461117155, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9437203400749963, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.23639150722613, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.11640437385711908, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141223.541828} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.12993884086609, "x": 0.5883360237491218, "y": 0.02776304509787142, "z": null, "yaw": 3.182630044861556, "pitch": null, "roll": null}, "v": 2.2403721524287077, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3622112814352158, "steering_wheel_angle": -0.07550298385812422, "front_wheel_angle": -0.0034708521224459843, "heading_rate": -0.00303751236946147, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141223.561828} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24514122461117155, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9437203400749963, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.234798234331044, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.11640437385711908, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141223.561828} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.12993884086609, "x": 0.5883360237491218, "y": 0.02776304509787142, "z": null, "yaw": 3.182630044861556, "pitch": null, "roll": null}, "v": 2.2403721524287077, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3622112814352158, "steering_wheel_angle": -0.07550298385812422, "front_wheel_angle": -0.0034708521224459843, "heading_rate": -0.00303751236946147, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141223.5818279} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24514122461117155, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9437203400749963, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.233207977791226, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.11640437385711908, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141223.5818279} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141223.6018279, "x": 4.342539141691169, "y": 5.017693116653759, "z": null, "yaw": 3.1824147018814504, "pitch": null, "roll": null}, "v": 2.231620730885079, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3613823474094145, "steering_wheel_angle": -0.11640437385711908, "front_wheel_angle": -0.0053539567078814895, "heading_rate": -0.0046672324005618375, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141223.6018279} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2467757857445613, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9813973657920879, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.231620730885079, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.11640437385711908, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141223.6018279} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.23993873596191, "x": 0.3425391416911694, "y": 0.017693116653759056, "z": null, "yaw": 3.1824147018814504, "pitch": null, "roll": null}, "v": 2.231620730885079, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3613823474094145, "steering_wheel_angle": -0.11640437385711908, "front_wheel_angle": -0.0053539567078814895, "heading_rate": -0.0046672324005618375, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141223.6218278} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24593426600155782, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9813973657920879, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.230240710389749, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.1573041382163535, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141223.6218278} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.23993873596191, "x": 0.3425391416911694, "y": 0.017693116653759056, "z": null, "yaw": 3.1824147018814504, "pitch": null, "roll": null}, "v": 2.231620730885079, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3613823474094145, "steering_wheel_angle": -0.11640437385711908, "front_wheel_angle": -0.0053539567078814895, "heading_rate": -0.0046672324005618375, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141223.6418278} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24593426600155782, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9813973657920879, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2287581597632844, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.1573041382163535, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141223.6418278} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.23993873596191, "x": 0.3425391416911694, "y": 0.017693116653759056, "z": null, "yaw": 3.1824147018814504, "pitch": null, "roll": null}, "v": 2.231620730885079, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3613823474094145, "steering_wheel_angle": -0.11640437385711908, "front_wheel_angle": -0.0053539567078814895, "heading_rate": -0.0046672324005618375, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141223.6618278} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24593426600155782, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9813973657920879, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2272784122797984, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.1573041382163535, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141223.6618278} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.23993873596191, "x": 0.3425391416911694, "y": 0.017693116653759056, "z": null, "yaw": 3.1824147018814504, "pitch": null, "roll": null}, "v": 2.231620730885079, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3613823474094145, "steering_wheel_angle": -0.11640437385711908, "front_wheel_angle": -0.0053539567078814895, "heading_rate": -0.0046672324005618375, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141223.6818278} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24593426600155782, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9813973657920879, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2258014617637816, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.1573041382163535, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141223.6818278} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.23993873596191, "x": 0.3425391416911694, "y": 0.017693116653759056, "z": null, "yaw": 3.1824147018814504, "pitch": null, "roll": null}, "v": 2.231620730885079, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3613823474094145, "steering_wheel_angle": -0.11640437385711908, "front_wheel_angle": -0.0053539567078814895, "heading_rate": -0.0046672324005618375, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141223.7018278} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24593426600155782, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9813973657920879, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2243273020563614, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.1573041382163535, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141223.7018278} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141223.7118278, "x": 4.097661198252175, "y": 5.00772415706727, "z": null, "yaw": 3.182111008723436, "pitch": null, "roll": null}, "v": 2.223591266835763, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36062314456127087, "steering_wheel_angle": -0.1573041382163535, "front_wheel_angle": -0.007239017606364824, "heading_rate": -0.006287850589149405, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141223.7218277} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24282548225243605, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9564132214486988, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2228559270152477, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.1573041382163535, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141223.7218277} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.34993863105774, "x": 0.09766119825217512, "y": 0.007724157067269921, "z": null, "yaw": 3.182111008723436, "pitch": null, "roll": null}, "v": 2.223591266835763, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36062314456127087, "steering_wheel_angle": -0.1573041382163535, "front_wheel_angle": -0.007239017606364824, "heading_rate": -0.006287850589149405, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141223.7418277} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24424801215039418, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9564132214486988, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.220998916042936, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.1573041382163535, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141223.7418277} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.34993863105774, "x": 0.09766119825217512, "y": 0.007724157067269921, "z": null, "yaw": 3.182111008723436, "pitch": null, "roll": null}, "v": 2.223591266835763, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36062314456127087, "steering_wheel_angle": -0.1573041382163535, "front_wheel_angle": -0.007239017606364824, "heading_rate": -0.006287850589149405, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141223.7618277} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24424801215039418, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9564132214486988, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.21932314284439, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.1573041382163535, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141223.7618277} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.34993863105774, "x": 0.09766119825217512, "y": 0.007724157067269921, "z": null, "yaw": 3.182111008723436, "pitch": null, "roll": null}, "v": 2.223591266835763, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36062314456127087, "steering_wheel_angle": -0.1573041382163535, "front_wheel_angle": -0.007239017606364824, "heading_rate": -0.006287850589149405, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141223.7818277} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24424801215039418, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9564132214486988, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2176505318397144, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.1573041382163535, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141223.7818277} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.34993863105774, "x": 0.09766119825217512, "y": 0.007724157067269921, "z": null, "yaw": 3.182111008723436, "pitch": null, "roll": null}, "v": 2.223591266835763, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36062314456127087, "steering_wheel_angle": -0.1573041382163535, "front_wheel_angle": -0.007239017606364824, "heading_rate": -0.006287850589149405, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141223.8018277} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24424801215039418, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9564132214486988, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2159810759433074, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.1573041382163535, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141223.8018277} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141223.8218277, "x": 3.8537307966580188, "y": 4.997869605335634, "z": null, "yaw": 3.1817999517521662, "pitch": null, "roll": null}, "v": 2.214314768089263, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35974763732624526, "steering_wheel_angle": -0.1573041382163535, "front_wheel_angle": -0.007239017606364824, "heading_rate": -0.006261618592748633, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141223.8218277} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24785866631974657, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0123571034151468, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.214314768089263, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.1573041382163535, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141223.8218277} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.45993852615356, "x": -0.14626920334198124, "y": -0.002130394664366264, "z": null, "yaw": 3.1817999517521662, "pitch": null, "roll": null}, "v": 2.214314768089263, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35974763732624526, "steering_wheel_angle": -0.1573041382163535, "front_wheel_angle": -0.007239017606364824, "heading_rate": -0.006261618592748633, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141223.8418276} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24607260098612105, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0123571034151468, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2131027202629263, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.1573041382163535, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141223.8418276} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.45993852615356, "x": -0.14626920334198124, "y": -0.002130394664366264, "z": null, "yaw": 3.1817999517521662, "pitch": null, "roll": null}, "v": 2.214314768089263, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35974763732624526, "steering_wheel_angle": -0.1573041382163535, "front_wheel_angle": -0.007239017606364824, "heading_rate": -0.006261618592748633, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141223.8618276} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24607260098612105, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0123571034151468, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2116698035512514, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.1573041382163535, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141223.8618276} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.45993852615356, "x": -0.14626920334198124, "y": -0.002130394664366264, "z": null, "yaw": 3.1817999517521662, "pitch": null, "roll": null}, "v": 2.214314768089263, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35974763732624526, "steering_wheel_angle": -0.1573041382163535, "front_wheel_angle": -0.007239017606364824, "heading_rate": -0.006261618592748633, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141223.8818276} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24607260098612105, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0123571034151468, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.210239586344545, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.1573041382163535, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141223.8818276} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.45993852615356, "x": -0.14626920334198124, "y": -0.002130394664366264, "z": null, "yaw": 3.1817999517521662, "pitch": null, "roll": null}, "v": 2.214314768089263, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35974763732624526, "steering_wheel_angle": -0.1573041382163535, "front_wheel_angle": -0.007239017606364824, "heading_rate": -0.006261618592748633, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141223.9018276} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24607260098612105, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0123571034151468, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2088120627393235, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.1573041382163535, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141223.9018276} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.45993852615356, "x": -0.14626920334198124, "y": -0.002130394664366264, "z": null, "yaw": 3.1817999517521662, "pitch": null, "roll": null}, "v": 2.214314768089263, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35974763732624526, "steering_wheel_angle": -0.1573041382163535, "front_wheel_angle": -0.007239017606364824, "heading_rate": -0.006261618592748633, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141223.9218276} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24607260098612105, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0123571034151468, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2073872268478425, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.1573041382163535, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141223.9218276} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141223.9318275, "x": 3.610723978625784, "y": 4.988128081387716, "z": null, "yaw": 3.1814888947808964, "pitch": null, "roll": null}, "v": 2.206675814959126, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3590279722712115, "steering_wheel_angle": -0.1573041382163535, "front_wheel_angle": -0.007239017606364824, "heading_rate": -0.006240017232527351, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141223.9418275} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24913412610485008, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.073045960897292, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2059650727980467, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.1573041382163535, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141223.9418275} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.56993842124939, "x": -0.3892760213742159, "y": -0.011871918612284205, "z": null, "yaw": 3.1814888947808964, "pitch": null, "roll": null}, "v": 2.206675814959126, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3590279722712115, "steering_wheel_angle": -0.1573041382163535, "front_wheel_angle": -0.007239017606364824, "heading_rate": -0.006240017232527351, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141223.9618275} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24762142462179226, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.073045960897292, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.20492810530399, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.23917829234024532, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141223.9618275} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.56993842124939, "x": -0.3892760213742159, "y": -0.011871918612284205, "z": null, "yaw": 3.1814888947808964, "pitch": null, "roll": null}, "v": 2.206675814959126, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3590279722712115, "steering_wheel_angle": -0.1573041382163535, "front_wheel_angle": -0.007239017606364824, "heading_rate": -0.006240017232527351, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141223.9818275} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24762142462179226, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.073045960897292, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2037040898105595, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.23917829234024532, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141223.9818275} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.56993842124939, "x": -0.3892760213742159, "y": -0.011871918612284205, "z": null, "yaw": 3.1814888947808964, "pitch": null, "roll": null}, "v": 2.206675814959126, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3590279722712115, "steering_wheel_angle": -0.1573041382163535, "front_wheel_angle": -0.007239017606364824, "heading_rate": -0.006240017232527351, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141224.0018275} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24762142462179226, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.073045960897292, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2024823763463073, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.23917829234024532, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141224.0018275} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.56993842124939, "x": -0.3892760213742159, "y": -0.011871918612284205, "z": null, "yaw": 3.1814888947808964, "pitch": null, "roll": null}, "v": 2.206675814959126, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3590279722712115, "steering_wheel_angle": -0.1573041382163535, "front_wheel_angle": -0.007239017606364824, "heading_rate": -0.006240017232527351, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141224.0218275} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24762142462179226, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.073045960897292, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2012629599850104, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.23917829234024532, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141224.0218275} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141224.0418274, "x": 3.368511096187571, "y": 4.978504262198694, "z": null, "yaw": 3.1810523297983075, "pitch": null, "roll": null}, "v": 2.2000458358130746, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3584043085874382, "steering_wheel_angle": -0.23917829234024532, "front_wheel_angle": -0.011018707926903485, "heading_rate": -0.009469782661681104, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141224.0418274} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25047496592706664, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1346144238605653, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2000458358130746, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.23917829234024532, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141224.0418274} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.67993831634521, "x": -0.631488903812429, "y": -0.021495737801306092, "z": null, "yaw": 3.1810523297983075, "pitch": null, "roll": null}, "v": 2.2000458358130746, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3584043085874382, "steering_wheel_angle": -0.23917829234024532, "front_wheel_angle": -0.011018707926903485, "heading_rate": -0.009469782661681104, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141224.0618274} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24906861879849762, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1346144238605653, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1991875239639627, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2801187362976194, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141224.0618274} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.67993831634521, "x": -0.631488903812429, "y": -0.021495737801306092, "z": null, "yaw": 3.1810523297983075, "pitch": null, "roll": null}, "v": 2.2000458358130746, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3584043085874382, "steering_wheel_angle": -0.23917829234024532, "front_wheel_angle": -0.011018707926903485, "heading_rate": -0.009469782661681104, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141224.0818274} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24906861879849762, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1346144238605653, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.198155113986911, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2801187362976194, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141224.0818274} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.67993831634521, "x": -0.631488903812429, "y": -0.021495737801306092, "z": null, "yaw": 3.1810523297983075, "pitch": null, "roll": null}, "v": 2.2000458358130746, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3584043085874382, "steering_wheel_angle": -0.23917829234024532, "front_wheel_angle": -0.011018707926903485, "heading_rate": -0.009469782661681104, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141224.1018274} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24906861879849762, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1346144238605653, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.19712464337376, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2801187362976194, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141224.1018274} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.67993831634521, "x": -0.631488903812429, "y": -0.021495737801306092, "z": null, "yaw": 3.1810523297983075, "pitch": null, "roll": null}, "v": 2.2000458358130746, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3584043085874382, "steering_wheel_angle": -0.23917829234024532, "front_wheel_angle": -0.011018707926903485, "heading_rate": -0.009469782661681104, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141224.1218274} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24906861879849762, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1346144238605653, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1960961080569006, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2801187362976194, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141224.1218274} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.67993831634521, "x": -0.631488903812429, "y": -0.021495737801306092, "z": null, "yaw": 3.1810523297983075, "pitch": null, "roll": null}, "v": 2.2000458358130746, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3584043085874382, "steering_wheel_angle": -0.23917829234024532, "front_wheel_angle": -0.011018707926903485, "heading_rate": -0.009469782661681104, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141224.1418273} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24906861879849762, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1346144238605653, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1950695039787544, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2801187362976194, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141224.1418273} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141224.1518273, "x": 3.126958957039773, "y": 4.969027101588983, "z": null, "yaw": 3.1805048914939134, "pitch": null, "roll": null}, "v": 2.1945569248889414, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3578886472102272, "steering_wheel_angle": -0.2801187362976194, "front_wheel_angle": -0.01291178762993792, "heading_rate": -0.011069229575569937, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141224.1618273} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25187725726945315, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2018457974875352, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1933729883835817, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3620192515558905, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141224.1618273} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.78993821144104, "x": -0.8730410429602271, "y": -0.030972898411016914, "z": null, "yaw": 3.1805048914939134, "pitch": null, "roll": null}, "v": 2.1945569248889414, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3578886472102272, "steering_wheel_angle": -0.2801187362976194, "front_wheel_angle": -0.01291178762993792, "heading_rate": -0.011069229575569937, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141224.1818273} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2505005212048994, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2018457974875352, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1933729883835817, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3620192515558905, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141224.1818273} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.78993821144104, "x": -0.8730410429602271, "y": -0.030972898411016914, "z": null, "yaw": 3.1805048914939134, "pitch": null, "roll": null}, "v": 2.1945569248889414, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3578886472102272, "steering_wheel_angle": -0.2801187362976194, "front_wheel_angle": -0.01291178762993792, "heading_rate": -0.011069229575569937, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141224.2018273} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2505005212048994, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2018457974875352, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.192109697579647, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3620192515558905, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141224.2018273} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.78993821144104, "x": -0.8730410429602271, "y": -0.030972898411016914, "z": null, "yaw": 3.1805048914939134, "pitch": null, "roll": null}, "v": 2.1945569248889414, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3578886472102272, "steering_wheel_angle": -0.2801187362976194, "front_wheel_angle": -0.01291178762993792, "heading_rate": -0.011069229575569937, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141224.2218273} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2505005212048994, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2018457974875352, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.191689390813541, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3620192515558905, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141224.2218273} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.78993821144104, "x": -0.8730410429602271, "y": -0.030972898411016914, "z": null, "yaw": 3.1805048914939134, "pitch": null, "roll": null}, "v": 2.1945569248889414, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3578886472102272, "steering_wheel_angle": -0.2801187362976194, "front_wheel_angle": -0.01291178762993792, "heading_rate": -0.011069229575569937, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141224.2418272} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2505005212048994, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2018457974875352, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.190849960098218, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3620192515558905, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141224.2418272} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141224.2618272, "x": 2.885963621291813, "y": 4.959715945485203, "z": null, "yaw": 3.1798240815813528, "pitch": null, "roll": null}, "v": 2.190012103771905, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3574621353352697, "steering_wheel_angle": -0.3620192515558905, "front_wheel_angle": -0.016705049211446013, "heading_rate": -0.014292056015120416, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141224.2618272} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25321460016532943, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2725303750196717, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1897633949288857, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.40298338378388804, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141224.2618272} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.89993810653687, "x": -1.114036378708187, "y": -0.040284054514796885, "z": null, "yaw": 3.1798240815813528, "pitch": null, "roll": null}, "v": 2.190012103771905, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3574621353352697, "steering_wheel_angle": -0.3620192515558905, "front_wheel_angle": -0.016705049211446013, "heading_rate": -0.014292056015120416, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141224.2818272} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2518896848080367, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2725303750196717, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.189514919369177, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.44390265536698303, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141224.2818272} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.89993810653687, "x": -1.114036378708187, "y": -0.040284054514796885, "z": null, "yaw": 3.1798240815813528, "pitch": null, "roll": null}, "v": 2.190012103771905, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3574621353352697, "steering_wheel_angle": -0.3620192515558905, "front_wheel_angle": -0.016705049211446013, "heading_rate": -0.014292056015120416, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141224.3018272} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2518896848080367, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2725303750196717, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.188853130415943, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.44390265536698303, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141224.3018272} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.89993810653687, "x": -1.114036378708187, "y": -0.040284054514796885, "z": null, "yaw": 3.1798240815813528, "pitch": null, "roll": null}, "v": 2.190012103771905, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3574621353352697, "steering_wheel_angle": -0.3620192515558905, "front_wheel_angle": -0.016705049211446013, "heading_rate": -0.014292056015120416, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141224.3218272} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2518896848080367, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2725303750196717, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1881925821369803, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.44390265536698303, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141224.3218272} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.89993810653687, "x": -1.114036378708187, "y": -0.040284054514796885, "z": null, "yaw": 3.1798240815813528, "pitch": null, "roll": null}, "v": 2.190012103771905, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3574621353352697, "steering_wheel_angle": -0.3620192515558905, "front_wheel_angle": -0.016705049211446013, "heading_rate": -0.014292056015120416, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141224.3418272} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2518896848080367, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2725303750196717, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1875332720319145, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.44390265536698303, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141224.3418272} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.89993810653687, "x": -1.114036378708187, "y": -0.040284054514796885, "z": null, "yaw": 3.1798240815813528, "pitch": null, "roll": null}, "v": 2.190012103771905, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3574621353352697, "steering_wheel_angle": -0.3620192515558905, "front_wheel_angle": -0.016705049211446013, "heading_rate": -0.014292056015120416, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141224.3618271} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2518896848080367, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2725303750196717, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1868751976060388, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.44390265536698303, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141224.3618271} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739141224.3718271, "x": 2.645400874364925, "y": 4.950606159832345, "z": null, "yaw": 3.1789651267121632, "pitch": null, "roll": null}, "v": 2.1865466229947477, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3571371924950347, "steering_wheel_angle": -0.44390265536698303, "front_wheel_angle": -0.020505821025946766, "heading_rate": -0.017516882518677706, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141224.381827} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25453107452924234, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1862183563702997, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.44390265536698303, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141224.381827} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.00993800163269, "x": -1.3545991256350751, "y": -0.0493938401676548, "z": null, "yaw": 3.1789651267121632, "pitch": null, "roll": null}, "v": 2.1865466229947477, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3571371924950347, "steering_wheel_angle": -0.44390265536698303, "front_wheel_angle": -0.020505821025946766, "heading_rate": -0.017516882518677706, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141224.401827} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25324851170966844, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.18565003771942, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141224.401827} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.00993800163269, "x": -1.3545991256350751, "y": -0.0493938401676548, "z": null, "yaw": 3.1789651267121632, "pitch": null, "roll": null}, "v": 2.1865466229947477, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3571371924950347, "steering_wheel_angle": -0.44390265536698303, "front_wheel_angle": -0.020505821025946766, "heading_rate": -0.017516882518677706, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141224.421827} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25324851170966844, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1854075380736764, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141224.421827} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.00993800163269, "x": -1.3545991256350751, "y": -0.0493938401676548, "z": null, "yaw": 3.1789651267121632, "pitch": null, "roll": null}, "v": 2.1865466229947477, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3571371924950347, "steering_wheel_angle": -0.44390265536698303, "front_wheel_angle": -0.020505821025946766, "heading_rate": -0.017516882518677706, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739141224.441827} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1846814017247747, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141224.451827} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.164681401724775, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141224.471827} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1446814017247755, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141224.491827} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.124681401724776, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141224.511827} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1046814017247764, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141224.531827} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.084681401724777, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141224.551827} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.064681401724777, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141224.571827} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0446814017247776, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141224.591827} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0146814017247783, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141224.611827} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0046814017247785, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141224.6318269} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9746814017247785, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141224.6518269} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9646814017247785, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141224.6718268} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9446814017247784, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141224.6918268} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9146814017247784, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141224.7118268} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9046814017247784, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141224.7318268} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8846814017247784, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141224.7518268} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8646814017247784, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141224.7718267} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8446814017247783, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141224.7918267} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8246814017247783, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141224.8118267} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8046814017247783, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141224.8318267} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7846814017247783, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141224.8518267} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7646814017247783, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141224.8718266} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7446814017247783, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141224.8918266} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7146814017247782, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141224.9118266} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7046814017247782, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141224.9318266} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6846814017247782, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141224.9518266} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6646814017247782, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141224.9718266} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6446814017247782, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141224.9918265} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6246814017247782, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141225.0118265} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6046814017247781, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141225.0318265} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5846814017247781, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141225.0518265} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.564681401724778, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141225.0718265} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.544681401724778, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141225.0918264} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.524681401724778, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141225.1118264} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.504681401724778, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141225.1318264} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.484681401724778, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141225.1518264} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.464681401724778, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141225.1718264} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.444681401724778, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141225.1918263} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.404681401724778, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141225.2118263} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.404681401724778, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141225.2318263} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.384681401724778, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141225.2518263} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.364681401724778, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141225.2718263} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.344681401724778, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141225.2918262} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3246814017247779, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141225.3118262} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3046814017247779, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141225.3318262} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2846814017247778, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141225.3518262} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2646814017247778, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141225.3718262} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2446814017247778, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141225.3918262} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2246814017247778, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141225.4118261} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2046814017247778, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141225.431826} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1846814017247778, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141225.451826} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1646814017247777, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141225.471826} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1446814017247777, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141225.491826} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1246814017247777, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141225.511826} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1046814017247777, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141225.531826} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0846814017247777, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141225.551826} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0646814017247777, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141225.571826} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0446814017247776, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141225.591826} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0146814017247776, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141225.611826} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0046814017247776, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141225.631826} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9746814017247776, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141225.651826} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9646814017247776, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141225.671826} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9446814017247775, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141225.6918259} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9246814017247775, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141225.7118258} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9046814017247775, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141225.7318258} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8846814017247775, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141225.7518258} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8646814017247775, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141225.7718258} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8446814017247775, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141225.7918258} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8246814017247774, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141225.8118258} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8046814017247774, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141225.8318257} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7846814017247774, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141225.8518257} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7646814017247774, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141225.8718257} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7446814017247774, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141225.8918257} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7146814017247773, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141225.9118257} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7046814017247773, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141225.9318256} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6746814017247773, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141225.9518256} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6646814017247773, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141225.9718256} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6446814017247773, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141225.9918256} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6246814017247773, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141226.0118256} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6046814017247772, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141226.0318255} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5846814017247772, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141226.0518255} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5646814017247772, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141226.0718255} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5446814017247772, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141226.0918255} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5246814017247772, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141226.1118255} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5046814017247772, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141226.1318254} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.48468140172477714, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141226.1518254} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.4646814017247771, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141226.1718254} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.4446814017247771, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141226.1918254} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.4246814017247771, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141226.2118254} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.40468140172477707, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141226.2318254} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.38468140172477705, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141226.2518253} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.36468140172477703, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141226.2718253} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.344681401724777, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141226.2918253} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.324681401724777, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141226.3118253} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.304681401724777, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141226.3318253} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.28468140172477696, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141226.3518252} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.26468140172477694, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141226.3718252} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.24468140172477693, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141226.3918252} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.2246814017247769, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141226.4118252} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.2046814017247769, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141226.4318252} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.18468140172477687, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141226.4518251} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.16468140172477685, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141226.4718251} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.14468140172477684, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141226.491825} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.12468140172477683, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141226.511825} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.10468140172477684, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141226.531825} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.08468140172477685, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141226.551825} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.06468140172477686, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141226.571825} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.04468140172477686, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141226.591825} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.024681401724776855, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141226.611825} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -1.34586889543368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.004681401724776855, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.5257749556326361, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739141226.631825} diff --git a/tuning logs/2025-02-09_16-46-00 (after tuning cte = 0.5 (-50%), decay speed = 1.0 (+250%))/meta.yaml b/tuning logs/2025-02-09_16-46-00 (after tuning cte = 0.5 (-50%), decay speed = 1.0 (+250%))/meta.yaml new file mode 100644 index 000000000..3ff3d3616 --- /dev/null +++ b/tuning logs/2025-02-09_16-46-00 (after tuning cte = 0.5 (-50%), decay speed = 1.0 (+250%))/meta.yaml @@ -0,0 +1,19 @@ +events: +- description: Ctrl+C pressed, switching to recovery mode + time: 1739141225.7197251 + vehicle_time: 1739141224.441827 +- description: Mission execution ended + time: 1739141227.9349117 + vehicle_time: 1739141226.631825 +exit_reason: normal exit +git_branch: A1_control +git_commit_id: a82b3af20db8a1737308910d5367b8987225d2da +pipelines: +- name: drive + time: 1739141160.412679 + vehicle_time: 1739141159.401889 +- name: recovery + time: 1739141225.7228525 + vehicle_time: 1739141224.441827 +start_time: 1739141160.2082536 +start_time_human_readable: '2025-02-09 16:46:00' diff --git a/tuning logs/2025-02-09_16-46-00 (after tuning cte = 0.5 (-50%), decay speed = 1.0 (+250%))/plots/accel.png b/tuning logs/2025-02-09_16-46-00 (after tuning cte = 0.5 (-50%), decay speed = 1.0 (+250%))/plots/accel.png new file mode 100644 index 000000000..f62ddf9a2 Binary files /dev/null and b/tuning logs/2025-02-09_16-46-00 (after tuning cte = 0.5 (-50%), decay speed = 1.0 (+250%))/plots/accel.png differ diff --git a/tuning logs/2025-02-09_16-46-00 (after tuning cte = 0.5 (-50%), decay speed = 1.0 (+250%))/plots/cte.png b/tuning logs/2025-02-09_16-46-00 (after tuning cte = 0.5 (-50%), decay speed = 1.0 (+250%))/plots/cte.png new file mode 100644 index 000000000..b9e9fa3fe Binary files /dev/null and b/tuning logs/2025-02-09_16-46-00 (after tuning cte = 0.5 (-50%), decay speed = 1.0 (+250%))/plots/cte.png differ diff --git a/tuning logs/2025-02-09_16-46-00 (after tuning cte = 0.5 (-50%), decay speed = 1.0 (+250%))/plots/error_v.png b/tuning logs/2025-02-09_16-46-00 (after tuning cte = 0.5 (-50%), decay speed = 1.0 (+250%))/plots/error_v.png new file mode 100644 index 000000000..91590bffa Binary files /dev/null and b/tuning logs/2025-02-09_16-46-00 (after tuning cte = 0.5 (-50%), decay speed = 1.0 (+250%))/plots/error_v.png differ diff --git a/tuning logs/2025-02-09_16-46-00 (after tuning cte = 0.5 (-50%), decay speed = 1.0 (+250%))/plots/error_x.png b/tuning logs/2025-02-09_16-46-00 (after tuning cte = 0.5 (-50%), decay speed = 1.0 (+250%))/plots/error_x.png new file mode 100644 index 000000000..f12e5c851 Binary files /dev/null and b/tuning logs/2025-02-09_16-46-00 (after tuning cte = 0.5 (-50%), decay speed = 1.0 (+250%))/plots/error_x.png differ diff --git a/tuning logs/2025-02-09_16-46-00 (after tuning cte = 0.5 (-50%), decay speed = 1.0 (+250%))/plots/error_y.png b/tuning logs/2025-02-09_16-46-00 (after tuning cte = 0.5 (-50%), decay speed = 1.0 (+250%))/plots/error_y.png new file mode 100644 index 000000000..640e1f6e1 Binary files /dev/null and b/tuning logs/2025-02-09_16-46-00 (after tuning cte = 0.5 (-50%), decay speed = 1.0 (+250%))/plots/error_y.png differ diff --git a/tuning logs/2025-02-09_16-46-00 (after tuning cte = 0.5 (-50%), decay speed = 1.0 (+250%))/plots/front_wheel_angle.png b/tuning logs/2025-02-09_16-46-00 (after tuning cte = 0.5 (-50%), decay speed = 1.0 (+250%))/plots/front_wheel_angle.png new file mode 100644 index 000000000..e116ce13e Binary files /dev/null and b/tuning logs/2025-02-09_16-46-00 (after tuning cte = 0.5 (-50%), decay speed = 1.0 (+250%))/plots/front_wheel_angle.png differ diff --git a/tuning logs/2025-02-09_16-46-00 (after tuning cte = 0.5 (-50%), decay speed = 1.0 (+250%))/plots/v_vs_vd.png b/tuning logs/2025-02-09_16-46-00 (after tuning cte = 0.5 (-50%), decay speed = 1.0 (+250%))/plots/v_vs_vd.png new file mode 100644 index 000000000..3918e47c7 Binary files /dev/null and b/tuning logs/2025-02-09_16-46-00 (after tuning cte = 0.5 (-50%), decay speed = 1.0 (+250%))/plots/v_vs_vd.png differ diff --git a/tuning logs/2025-02-09_16-46-00 (after tuning cte = 0.5 (-50%), decay speed = 1.0 (+250%))/plots/x_vs_xd.png b/tuning logs/2025-02-09_16-46-00 (after tuning cte = 0.5 (-50%), decay speed = 1.0 (+250%))/plots/x_vs_xd.png new file mode 100644 index 000000000..d8350820f Binary files /dev/null and b/tuning logs/2025-02-09_16-46-00 (after tuning cte = 0.5 (-50%), decay speed = 1.0 (+250%))/plots/x_vs_xd.png differ diff --git a/tuning logs/2025-02-09_16-46-00 (after tuning cte = 0.5 (-50%), decay speed = 1.0 (+250%))/plots/y_vs_yd.png b/tuning logs/2025-02-09_16-46-00 (after tuning cte = 0.5 (-50%), decay speed = 1.0 (+250%))/plots/y_vs_yd.png new file mode 100644 index 000000000..3e4b15508 Binary files /dev/null and b/tuning logs/2025-02-09_16-46-00 (after tuning cte = 0.5 (-50%), decay speed = 1.0 (+250%))/plots/y_vs_yd.png differ diff --git a/tuning logs/2025-02-09_16-46-00 (after tuning cte = 0.5 (-50%), decay speed = 1.0 (+250%))/settings.yaml b/tuning logs/2025-02-09_16-46-00 (after tuning cte = 0.5 (-50%), decay speed = 1.0 (+250%))/settings.yaml new file mode 100644 index 000000000..04ab68056 --- /dev/null +++ b/tuning logs/2025-02-09_16-46-00 (after tuning cte = 0.5 (-50%), decay speed = 1.0 (+250%))/settings.yaml @@ -0,0 +1,321 @@ +control: + longitudinal_control: + pid_d: 0.0 + pid_i: 0.1 + pid_p: 1.0 + pure_pursuit: + crosstrack_gain: 0.5 + desired_speed: trajectory + lookahead: 2.0 + lookahead_scale: 3.0 + recovery: + brake_amount: 0.5 + brake_speed: 2.0 +model_predictive_controller: + dt: 0.1 + lookahead: 20 +run: + after: + show_log_folder: true + computation_graph: + components: + - state_estimation: + inputs: [] + outputs: + - vehicle + - roadgraph_update: + inputs: + - vehicle + outputs: + - roadgraph + - obstacle_detection: + inputs: + - vehicle + outputs: + - obstacles + - agent_detection: + inputs: + - vehicle + outputs: + - agents + - lane_detection: + inputs: + - vehicle + - roadgraph + outputs: + - vehicle_lane + - sign_detection: + inputs: + - vehicle + - roadgraph + outputs: + - roadgraph.signs + - environment_detection: + inputs: + - vehicle + outputs: + - environment + - intent_estimation: + inputs: + - vehicle + - roadgraph + - agents + outputs: + - agent_intents + - relations_estimation: + inputs: + - vehicle + - roadgraph + - agents + - obstacles + outputs: + - relations + - predicate_evaluation: + inputs: + - vehicle + - roadgraph + - agents + - obstacles + outputs: + - predicates + - perception_normalization: + inputs: + - all + outputs: [] + - mission_execution: + inputs: [] + outputs: + - mission + - route_planning: + inputs: + - vehicle + - roadgraph + - mission + outputs: + - route + - driving_logic: + inputs: + - all + outputs: + - intent + - motion_planning: + inputs: + - all + outputs: + - trajectory + - trajectory_tracking: + inputs: + - vehicle + - trajectory + outputs: [] + description: Drive the GEM vehicle along a fixed route (currently xyhead_highbay_backlot_p.csv) + drive: + perception: + agent_detection: OmniscientAgentDetector + perception_normalization: StandardPerceptionNormalizer + state_estimation: OmniscientStateEstimator + planning: + motion_planning: + args: + - null + type: RouteToTrajectoryPlanner + route_planning: + args: + - GEMstack/knowledge/routes/xyhead_highbay_backlot_p.csv + type: StaticRoutePlanner + trajectory_tracking: + args: + desired_speed: 2.5 + print: false + type: pure_pursuit.PurePursuitTrajectoryTracker + log: + components: + - state_estimation + - trajectory_tracking + ros_topics: [] + vehicle_interface: true + mission_execution: StandardExecutor + mode: simulation + name: launch/fixed_route.yaml + recovery: + planning: + trajectory_tracking: + print: false + type: recovery.StopTrajectoryTracker + replay: + components: [] + log: null + ros_topics: [] + variants: + log_ros: + log: + ros_topics: + - /game_control/joy + - /front_radar/front_radar/objects + - /front_radar/front_radar/radar_tracks + - /lidar1/velodyne_points + - /novatel/inspva + - /novatel/imu + - /novatel/bestpos + - /zed2/zed_node/depth/camera_info + - /zed2/zed_node/depth/depth_registered + - /zed2/zed_node/rgb/camera_info + - /zed2/zed_node/rgb/image_rect_color + - /zed2/zed_node/imu/data + - /zed2/zed_node/imu/data_raw + - /zed2/zed_node/imu/mag + - /pacmod/as_rx/enable + - /pacmod/as_rx/accel_cmd + - /pacmod/as_rx/brake_cmd + - /pacmod/as_rx/shift_cmd + - /pacmod/as_rx/steer_cmd + - /pacmod/as_rx/turn_cmd + - /pacmod/as_rx/turn_signal_cmd + - /pacmod/as_rx/vehicle_speed_cmd + - /pacmod/as_tx/enable + - /pacmod/as_tx/global_rpt + - /pacmod/as_tx/accel_rpt + - /pacmod/as_tx/brake_rpt + - /pacmod/as_tx/shift_rpt + - /pacmod/as_tx/steer_rpt + - /pacmod/as_tx/turn_rpt + - /pacmod/as_tx/vehicle_speed_rpt + sim: + run: + drive: + perception: + agent_detection: OmniscientAgentDetector + state_estimation: OmniscientStateEstimator + mode: simulation + vehicle_interface: + args: + scene: scenes/xyhead_demo.yaml + type: gem_simulator.GEMDoubleIntegratorSimulationInterface + visualization: + args: + rate: 20 + save_as: null + type: klampt_visualization.KlamptVisualization + vehicle_interface: + args: + scene: scenes/xyhead_demo.yaml + type: gem_simulator.GEMDoubleIntegratorSimulationInterface + visualization: + args: + rate: 20 + save_as: null + type: klampt_visualization.KlamptVisualization +simulator: + dt: 0.01 + gnss_emulator: + dt: 0.1 + real_time_multiplier: 1.0 +variant: sim +vehicle: + calibration: + calibration_date: '2024-03-05' + front_camera: + center_position: + - 1.78 + - 0 + - 1.58 + reference: rear_axle_center + rotation: + - - 0 + - 0 + - 1 + - - -1 + - 0 + - 0 + - - 0 + - -1 + - 0 + gnss_location: + - 1.1 + - 0.1.62 + gnss_yaw: 0.0 + rear_axle_height: 0.33 + reference: rear_axle_center + top_lidar: + position: + - 1.1 + - 0 + - 2.03 + reference: rear_axle_center + rotation: + - - 1 + - 0 + - 0 + - - 0 + - 1 + - 0 + - - 0 + - 0 + - 1 + control_defaults: + accelerator_pedal_speed: 3.0 + brake_pedal_speed: 3.0 + steering_wheel_speed: 4.0 + dynamics: + acceleration_deadband: 0.1 + acceleration_model: kris_v1 + accelerator_active_range: + - 0.2 + - 1.0 + aerodynamic_drag_coefficient: 0.01 + brake_active_range: + - 0 + - 1 + gravity: 9.81 + internal_dry_deceleration: 0.2 + internal_viscous_deceleration: 0.05 + lateral_friction: 1.0 + longitudinal_friction: 1.0 + mass: 300.0 + max_accelerator_acceleration: + - 0.0 + - 5.0 + max_accelerator_acceleration_reverse: 2.5 + max_accelerator_power: + - 0.0 + - 10000.0 + max_accelerator_power_reverse: 10000.0 + max_brake_deceleration: 8.0 + enable_through_joystick: true + geometry: + bounds: + - - -0.35 + - 2.85 + - - -0.85 + - 0.85 + - - 0 + - 2.5 + height: 2.5 + length: 3.2 + max_steering_angle: 11.0 + max_wheel_angle: 0.6108 + min_steering_angle: -11.0 + min_wheel_angle: -0.6108 + urdf_model: /home/acrl/GEMstack/GEMstack/knowledge/vehicle/model/gem_e4.urdf + wheel_radius: 0.33 + wheelbase: 2.56 + width: 1.7 + limits: + max_acceleration: 1.0 + max_accelerator_pedal: 0.5 + max_brake_pedal: 0.5 + max_deceleration: 2.0 + max_reverse_speed: 0.25 + max_speed: 2.5 + max_steering_rate: 2.0 + max_command_rate: 10.0 + max_gear: 1 + name: GEM + num_wiper_settings: 1 + sensors: + ros_topics: + front_camera: /oak/rgb/image_raw + front_depth: /oak/stereo/image_raw + gnss: /septentrio_gnss/insnavgeod + top_lidar: /ouster/points + version: e4 diff --git a/tuning logs/2025-02-13_21-10-39 (fine tuning)/PurePursuitTrajectoryTracker_debug.csv b/tuning logs/2025-02-13_21-10-39 (fine tuning)/PurePursuitTrajectoryTracker_debug.csv new file mode 100644 index 000000000..e39604776 --- /dev/null +++ b/tuning logs/2025-02-13_21-10-39 (fine tuning)/PurePursuitTrajectoryTracker_debug.csv @@ -0,0 +1,3242 @@ +curr pt[0] time,curr pt[0] vehicle time,curr pt[0],curr pt[1] time,curr pt[1] vehicle time,curr pt[1],curr param time,curr param vehicle time,curr param,desired pt[0] time,desired pt[0] vehicle time,desired pt[0],desired pt[1] time,desired pt[1] vehicle time,desired pt[1],desired yaw (rad) time,desired yaw (rad) vehicle time,desired yaw (rad),crosstrack error time,crosstrack error vehicle time,crosstrack error,front wheel angle (rad) time,front wheel angle (rad) vehicle time,front wheel angle (rad),desired speed (m/s) time,desired speed (m/s) vehicle time,desired speed (m/s),feedforward accel (m/s^2) time,feedforward accel (m/s^2) vehicle time,feedforward accel (m/s^2),output accel (m/s^2) time,output accel (m/s^2) vehicle time,output accel (m/s^2),current yaw (rad) time,current yaw (rad) vehicle time,current yaw (rad),current speed (m/s) time,current speed (m/s) vehicle time,current speed (m/s) +1739502639.5794408,0.029999971389770508,0.0,1739502639.5794437,0.029999971389770508,0.0,1739502639.5794468,0.029999971389770508,2e-06,1739502639.5794497,0.029999971389770508,1.9947503416207786,1739502639.579451,0.029999971389770508,-0.06638719928805828,1739502639.579453,0.029999971389770508,-0.03326867705567338,1739502639.579455,0.029999971389770508,-0.06638719928805828,1739502639.5794566,0.029999971389770508,-0.1279158618748393,1739502639.579458,0.029999971389770508,2.370689811361755,1739502639.57946,0.029999971389770508,0.0,1739502639.5794618,0.029999971389770508,2.370689811361755,1739502639.5794635,0.029999971389770508,0.0,1739502639.579465,0.029999971389770508,0.0 +1739502639.5991945,0.04999995231628418,0.0,1739502639.5991986,0.04999995231628418,0.0,1739502639.5992029,0.04999995231628418,2e-06,1739502639.599206,0.04999995231628418,1.9947503416207786,1739502639.5992079,0.04999995231628418,-0.06638719928805828,1739502639.5992103,0.04999995231628418,-0.03326867705567338,1739502639.599213,0.04999995231628418,-0.06638719928805828,1739502639.5992148,0.04999995231628418,-0.1279158618748393,1739502639.5992165,0.04999995231628418,2.370689811361755,1739502639.5992181,0.04999995231628418,0.0,1739502639.5992198,0.04999995231628418,2.370689811361755,1739502639.5992215,0.04999995231628418,0.0,1739502639.5992231,0.04999995231628418,0.0 +1739502639.6183183,0.06999993324279785,0.00047983963609077307,1739502639.6183212,0.06999993324279785,-6.804403263060976e-09,1739502639.618324,0.06999993324279785,1.520160363909227e-06,1739502639.618327,0.06999993324279785,2.05869696822515,1739502639.6183283,0.06999993324279785,-0.06716502371355604,1739502639.61833,0.06999993324279785,-0.03262104377967774,1739502639.6183317,0.06999993324279785,-0.06706948465977582,1739502639.6183329,0.06999993324279785,-0.12139602026825669,1739502639.6183345,0.06999993324279785,2.369396174862239,1739502639.618336,0.06999993324279785,0.0,1739502639.6183374,0.06999993324279785,2.322297716956859,1739502639.6183388,0.06999993324279785,6.283138892165478,1739502639.61834,0.06999993324279785,0.03197591848874033 +1739502639.6381671,0.08999991416931152,0.00047983963609077307,1739502639.6381693,0.08999991416931152,-6.804403263060976e-09,1739502639.6381721,0.08999991416931152,1.520160363909227e-06,1739502639.638175,0.08999991416931152,2.05869696822515,1739502639.6381764,0.08999991416931152,-0.06716502371355604,1739502639.638178,0.08999991416931152,-0.03262104377967774,1739502639.6381795,0.08999991416931152,-0.06706948465977582,1739502639.638181,0.08999991416931152,-0.12139602026825669,1739502639.6381822,0.08999991416931152,2.369396174862239,1739502639.6381836,0.08999991416931152,0.0,1739502639.6381853,0.08999991416931152,2.3374202563734987,1739502639.6381865,0.08999991416931152,6.283138892165478,1739502639.6381881,0.08999991416931152,0.03197591848874033 +1739502639.6776097,0.1099998950958252,0.00047983963609077307,1739502639.6776133,0.1099998950958252,-6.804403263060976e-09,1739502639.6776173,0.1099998950958252,1.520160363909227e-06,1739502639.6776206,0.1099998950958252,2.05869696822515,1739502639.6776223,0.1099998950958252,-0.06716502371355604,1739502639.6776242,0.1099998950958252,-0.03262104377967774,1739502639.677626,0.1099998950958252,-0.06706948465977582,1739502639.6776278,0.1099998950958252,-0.12139602026825669,1739502639.6776292,0.1099998950958252,2.369396174862239,1739502639.6776314,0.1099998950958252,0.0,1739502639.677633,0.1099998950958252,2.3374202563734987,1739502639.6776345,0.1099998950958252,6.283138892165478,1739502639.6776361,0.1099998950958252,0.03197591848874033 +1739502639.7040946,0.14999985694885254,0.00047983963609077307,1739502639.7041,0.14999985694885254,-6.804403263060976e-09,1739502639.704105,0.14999985694885254,1.520160363909227e-06,1739502639.704109,0.14999985694885254,2.05869696822515,1739502639.7041109,0.14999985694885254,-0.06716502371355604,1739502639.7041135,0.14999985694885254,-0.03262104377967774,1739502639.7041175,0.14999985694885254,-0.06706948465977582,1739502639.7041202,0.14999985694885254,-0.12139602026825669,1739502639.704122,0.14999985694885254,2.369396174862239,1739502639.7041247,0.14999985694885254,0.0,1739502639.7041268,0.14999985694885254,2.3374202563734987,1739502639.704129,0.14999985694885254,6.283138892165478,1739502639.7041314,0.14999985694885254,0.03197591848874033 +1739502639.7231534,0.1699998378753662,0.00047983963609077307,1739502639.7231562,0.1699998378753662,-6.804403263060976e-09,1739502639.7231596,0.1699998378753662,1.520160363909227e-06,1739502639.7231624,0.1699998378753662,2.05869696822515,1739502639.7231636,0.1699998378753662,-0.06716502371355604,1739502639.7231655,0.1699998378753662,-0.03262104377967774,1739502639.7231672,0.1699998378753662,-0.06706948465977582,1739502639.7231688,0.1699998378753662,-0.12139602026825669,1739502639.7231703,0.1699998378753662,2.369396174862239,1739502639.723172,0.1699998378753662,0.0,1739502639.7231734,0.1699998378753662,2.3374202563734987,1739502639.7231746,0.1699998378753662,6.283138892165478,1739502639.7231762,0.1699998378753662,0.03197591848874033 +1739502639.8222353,0.19999980926513672,0.009488760476915381,1739502639.82224,0.19999980926513672,-3.58028625679907e-06,1739502639.8222456,0.19999980926513672,0.0,1739502639.822252,0.19999980926513672,2.2781082034004916,1739502639.8222554,0.19999980926513672,-0.06986746817333699,1739502639.8222601,0.19999980926513672,-0.030786042513801123,1739502639.8222644,0.19999980926513672,-0.0680247658429978,1739502639.8222685,0.19999980926513672,-0.1013743189631224,1739502639.8222723,0.19999980926513672,2.3675861149316564,1739502639.8222764,0.19999980926513672,0.0,1739502639.8222804,0.19999980926513672,2.175197469240814,1739502639.8222847,0.19999980926513672,6.282374638252922,1739502639.8222892,0.19999980926513672,0.1416939914738729 +1739502639.8888443,0.2799997329711914,0.009488760476915381,1739502639.888847,0.2799997329711914,-3.58028625679907e-06,1739502639.8888502,0.2799997329711914,0.0,1739502639.888853,0.2799997329711914,2.2781082034004916,1739502639.8888547,0.2799997329711914,-0.06986746817333699,1739502639.8888566,0.2799997329711914,-0.030786042513801123,1739502639.8888578,0.2799997329711914,-0.0680247658429978,1739502639.8888595,0.2799997329711914,-0.1013743189631224,1739502639.8888607,0.2799997329711914,2.3675861149316564,1739502639.8888621,0.2799997329711914,0.0,1739502639.8888636,0.2799997329711914,2.2258921234577835,1739502639.888865,0.2799997329711914,6.282374638252922,1739502639.8888662,0.2799997329711914,0.1416939914738729 +1739502639.907965,0.3099997043609619,0.030547019841669965,1739502639.9079678,0.3099997043609619,-3.691379956194396e-05,1739502639.907971,0.3099997043609619,0.0215519580373643,1739502639.907974,0.3099997043609619,2.518590721821713,1739502639.9079752,0.3099997043609619,-0.073,1739502639.907978,0.3099997043609619,-0.02931708202390329,1739502639.9079828,0.3099997043609619,-0.06672760156828361,1739502639.9079869,0.3099997043609619,-0.08269274153147879,1739502639.9079907,0.3099997043609619,2.370044308683982,1739502639.9079928,0.3099997043609619,0.0,1739502639.9079943,0.3099997043609619,2.070223958273649,1739502639.907996,0.3099997043609619,6.280679216940032,1739502639.9079976,0.3099997043609619,0.2511740168952693 +1739502639.928167,0.3299996852874756,0.030547019841669965,1739502639.9281712,0.3299996852874756,-3.691379956194396e-05,1739502639.9281745,0.3299996852874756,0.0215519580373643,1739502639.9281778,0.3299996852874756,2.518590721821713,1739502639.9281797,0.3299996852874756,-0.073,1739502639.9281816,0.3299996852874756,-0.02931708202390329,1739502639.9281845,0.3299996852874756,-0.06672760156828361,1739502639.928187,0.3299996852874756,-0.08269274153147879,1739502639.9281883,0.3299996852874756,2.370044308683982,1739502639.9281912,0.3299996852874756,0.0,1739502639.9281933,0.3299996852874756,2.1188702917887126,1739502639.9281952,0.3299996852874756,6.280679216940032,1739502639.9281976,0.3299996852874756,0.2511740168952693 +1739502639.9489899,0.34999966621398926,0.030547019841669965,1739502639.9489946,0.34999966621398926,-3.691379956194396e-05,1739502639.9490004,0.34999966621398926,0.0215519580373643,1739502639.9490056,0.34999966621398926,2.518590721821713,1739502639.9490082,0.34999966621398926,-0.073,1739502639.9490116,0.34999966621398926,-0.02931708202390329,1739502639.949014,0.34999966621398926,-0.06672760156828361,1739502639.949017,0.34999966621398926,-0.08269274153147879,1739502639.9490197,0.34999966621398926,2.370044308683982,1739502639.9490228,0.34999966621398926,0.0,1739502639.9490256,0.34999966621398926,2.1188702917887126,1739502639.949028,0.34999966621398926,6.280679216940032,1739502639.9490314,0.34999966621398926,0.2511740168952693 +1739502639.9683585,0.36999964714050293,0.030547019841669965,1739502639.9683614,0.36999964714050293,-3.691379956194396e-05,1739502639.9683654,0.36999964714050293,0.0215519580373643,1739502639.9683683,0.36999964714050293,2.518590721821713,1739502639.96837,0.36999964714050293,-0.073,1739502639.9683716,0.36999964714050293,-0.02931708202390329,1739502639.9683733,0.36999964714050293,-0.06672760156828361,1739502639.968375,0.36999964714050293,-0.08269274153147879,1739502639.9683766,0.36999964714050293,2.370044308683982,1739502639.9683783,0.36999964714050293,0.0,1739502639.9683797,0.36999964714050293,2.1188702917887126,1739502639.9683812,0.36999964714050293,6.280679216940032,1739502639.9683828,0.36999964714050293,0.2511740168952693 +1739502639.9880989,0.3899996280670166,0.030547019841669965,1739502639.9881015,0.3899996280670166,-3.691379956194396e-05,1739502639.9881043,0.3899996280670166,0.0215519580373643,1739502639.9881072,0.3899996280670166,2.518590721821713,1739502639.9881089,0.3899996280670166,-0.073,1739502639.9881105,0.3899996280670166,-0.02931708202390329,1739502639.9881122,0.3899996280670166,-0.06672760156828361,1739502639.9881136,0.3899996280670166,-0.08269274153147879,1739502639.9881148,0.3899996280670166,2.370044308683982,1739502639.9881165,0.3899996280670166,0.0,1739502639.988118,0.3899996280670166,2.1188702917887126,1739502639.9881196,0.3899996280670166,6.280679216940032,1739502639.9881208,0.3899996280670166,0.2511740168952693 +1739502640.0080516,0.4099996089935303,0.06365559344657257,1739502640.0080543,0.4099996089935303,-0.00015719778843248378,1739502640.008057,0.4099996089935303,0.021883043773413324,1739502640.00806,0.4099996089935303,2.738058327968718,1739502640.0080612,0.4099996089935303,-0.07506884463600816,1739502640.008063,0.4099996089935303,-0.02800328587449252,1739502640.0080645,0.4099996089935303,-0.06193778715602109,1739502640.008066,0.4099996089935303,-0.06644337125463601,1739502640.0080674,0.4099996089935303,2.3791433886220754,1739502640.0080688,0.4099996089935303,0.0,1739502640.0080705,0.4099996089935303,1.9727211494889747,1739502640.008072,0.4099996089935303,6.278334493555943,1739502640.0080736,0.4099996089935303,0.36075060221977395 +1739502640.0279503,0.42999958992004395,0.06365559344657257,1739502640.0279531,0.42999958992004395,-0.00015719778843248378,1739502640.0279562,0.42999958992004395,0.021883043773413324,1739502640.0279593,0.42999958992004395,2.738058327968718,1739502640.0279605,0.42999958992004395,-0.07506884463600816,1739502640.0279624,0.42999958992004395,-0.02800328587449252,1739502640.027964,0.42999958992004395,-0.06193778715602109,1739502640.0279658,0.42999958992004395,-0.06644337125463601,1739502640.027967,0.42999958992004395,2.3791433886220754,1739502640.027969,0.42999958992004395,0.0,1739502640.0279703,0.42999958992004395,2.0183927864023015,1739502640.0279717,0.42999958992004395,6.278334493555943,1739502640.0279734,0.42999958992004395,0.36075060221977395 +1739502640.0479147,0.4499995708465576,0.06365559344657257,1739502640.0479176,0.4499995708465576,-0.00015719778843248378,1739502640.0479207,0.4499995708465576,0.021883043773413324,1739502640.0479238,0.4499995708465576,2.738058327968718,1739502640.0479252,0.4499995708465576,-0.07506884463600816,1739502640.0479271,0.4499995708465576,-0.02800328587449252,1739502640.0479286,0.4499995708465576,-0.06193778715602109,1739502640.04793,0.4499995708465576,-0.06644337125463601,1739502640.0479317,0.4499995708465576,2.3791433886220754,1739502640.0479333,0.4499995708465576,0.0,1739502640.047935,0.4499995708465576,2.0183927864023015,1739502640.0479364,0.4499995708465576,6.278334493555943,1739502640.047938,0.4499995708465576,0.36075060221977395 +1739502640.06786,0.4699995517730713,0.06365559344657257,1739502640.0678627,0.4699995517730713,-0.00015719778843248378,1739502640.067866,0.4699995517730713,0.021883043773413324,1739502640.0678692,0.4699995517730713,2.738058327968718,1739502640.0678706,0.4699995517730713,-0.07506884463600816,1739502640.0678728,0.4699995517730713,-0.02800328587449252,1739502640.0678742,0.4699995517730713,-0.06193778715602109,1739502640.0678759,0.4699995517730713,-0.06644337125463601,1739502640.0678773,0.4699995517730713,2.3791433886220754,1739502640.0678794,0.4699995517730713,0.0,1739502640.0678806,0.4699995517730713,2.0183927864023015,1739502640.0678823,0.4699995517730713,6.278334493555943,1739502640.0678837,0.4699995517730713,0.36075060221977395 +1739502640.0878034,0.48999953269958496,0.06365559344657257,1739502640.0878057,0.48999953269958496,-0.00015719778843248378,1739502640.0878086,0.48999953269958496,0.021883043773413324,1739502640.0878115,0.48999953269958496,2.738058327968718,1739502640.087813,0.48999953269958496,-0.07506884463600816,1739502640.0878146,0.48999953269958496,-0.02800328587449252,1739502640.0878162,0.48999953269958496,-0.06193778715602109,1739502640.0878177,0.48999953269958496,-0.06644337125463601,1739502640.0878193,0.48999953269958496,2.3791433886220754,1739502640.0878208,0.48999953269958496,0.0,1739502640.0878222,0.48999953269958496,2.0183927864023015,1739502640.0878236,0.48999953269958496,6.278334493555943,1739502640.087825,0.48999953269958496,0.36075060221977395 +1739502640.10837,0.5099995136260986,0.10882169667425678,1739502640.108373,0.5099995136260986,-0.0004272615560179105,1739502640.1083765,0.5099995136260986,0.022334704805690164,1739502640.1083803,0.5099995136260986,2.957740733492,1739502640.1083822,0.5099995136260986,-0.077,1739502640.1083844,0.5099995136260986,-0.02687135235706951,1739502640.108386,0.5099995136260986,-0.056006179090768306,1739502640.108388,0.5099995136260986,-0.052951494053988635,1739502640.1083894,0.5099995136260986,2.3904599344023905,1739502640.1083915,0.5099995136260986,0.0,1739502640.108393,0.5099995136260986,1.8754046053508828,1739502640.1083949,0.5099995136260986,6.275966870030994,1739502640.1083968,0.5099995136260986,0.47037149317593346 +1739502640.1363766,0.5299994945526123,0.10882169667425678,1739502640.136391,0.5299994945526123,-0.0004272615560179105,1739502640.1364095,0.5299994945526123,0.022334704805690164,1739502640.1364307,0.5299994945526123,2.957740733492,1739502640.136443,0.5299994945526123,-0.077,1739502640.136458,0.5299994945526123,-0.02687135235706951,1739502640.1364715,0.5299994945526123,-0.056006179090768306,1739502640.136485,0.5299994945526123,-0.052951494053988635,1739502640.1364987,0.5299994945526123,2.3904599344023905,1739502640.1365128,0.5299994945526123,0.0,1739502640.1365266,0.5299994945526123,1.920088441226457,1739502640.1365407,0.5299994945526123,6.275966870030994,1739502640.1365545,0.5299994945526123,0.47037149317593346 +1739502640.1559532,0.549999475479126,0.10882169667425678,1739502640.1559675,0.549999475479126,-0.0004272615560179105,1739502640.1559856,0.549999475479126,0.022334704805690164,1739502640.1560068,0.549999475479126,2.957740733492,1739502640.1560187,0.549999475479126,-0.077,1739502640.156034,0.549999475479126,-0.02687135235706951,1739502640.1560476,0.549999475479126,-0.056006179090768306,1739502640.1560612,0.549999475479126,-0.052951494053988635,1739502640.1560748,0.549999475479126,2.3904599344023905,1739502640.1560888,0.549999475479126,0.0,1739502640.1561024,0.549999475479126,1.920088441226457,1739502640.1561165,0.549999475479126,6.275966870030994,1739502640.1561303,0.549999475479126,0.47037149317593346 +1739502640.1753914,0.5699994564056396,0.10882169667425678,1739502640.1753974,0.5699994564056396,-0.0004272615560179105,1739502640.1754055,0.5699994564056396,0.022334704805690164,1739502640.1754148,0.5699994564056396,2.957740733492,1739502640.1754198,0.5699994564056396,-0.077,1739502640.1754262,0.5699994564056396,-0.02687135235706951,1739502640.1754322,0.5699994564056396,-0.056006179090768306,1739502640.1754382,0.5699994564056396,-0.052951494053988635,1739502640.175444,0.5699994564056396,2.3904599344023905,1739502640.17545,0.5699994564056396,0.0,1739502640.175456,0.5699994564056396,1.920088441226457,1739502640.1754618,0.5699994564056396,6.275966870030994,1739502640.175468,0.5699994564056396,0.47037149317593346 +1739502640.194292,0.5899994373321533,0.10882169667425678,1739502640.1942956,0.5899994373321533,-0.0004272615560179105,1739502640.1943002,0.5899994373321533,0.022334704805690164,1739502640.1943054,0.5899994373321533,2.957740733492,1739502640.1943085,0.5899994373321533,-0.077,1739502640.1943128,0.5899994373321533,-0.02687135235706951,1739502640.1943164,0.5899994373321533,-0.056006179090768306,1739502640.19432,0.5899994373321533,-0.052951494053988635,1739502640.1943235,0.5899994373321533,2.3904599344023905,1739502640.194327,0.5899994373321533,0.0,1739502640.1943305,0.5899994373321533,1.920088441226457,1739502640.194334,0.5899994373321533,6.275966870030994,1739502640.1943378,0.5899994373321533,0.47037149317593346 +1739502640.2141337,0.609999418258667,0.10882169667425678,1739502640.2141373,0.609999418258667,-0.0004272615560179105,1739502640.2141418,0.609999418258667,0.022334704805690164,1739502640.2141476,0.609999418258667,2.957740733492,1739502640.2141504,0.609999418258667,-0.077,1739502640.2141542,0.609999418258667,-0.02687135235706951,1739502640.2141578,0.609999418258667,-0.056006179090768306,1739502640.2141614,0.609999418258667,-0.052951494053988635,1739502640.2141647,0.609999418258667,2.3904599344023905,1739502640.2141683,0.609999418258667,0.0,1739502640.214172,0.609999418258667,1.920088441226457,1739502640.2141755,0.609999418258667,6.275966870030994,1739502640.214179,0.609999418258667,0.47037149317593346 +1739502640.2347357,0.6299993991851807,0.16605068655188848,1739502640.2347395,0.6299993991851807,-0.0009043270420709959,1739502640.23475,0.6299993991851807,0.02290699470446648,1739502640.2347555,0.6299993991851807,3.17762407557747,1739502640.2347586,0.6299993991851807,-0.08008663722247125,1739502640.2347627,0.6299993991851807,-0.026286615384780634,1739502640.234766,0.6299993991851807,-0.05030998898661317,1739502640.2347696,0.6299993991851807,-0.04256957009120678,1739502640.2347732,0.6299993991851807,2.4013780034457635,1739502640.2347767,0.6299993991851807,0.0,1739502640.2347803,0.6299993991851807,1.7764492094825028,1739502640.234784,0.6299993991851807,6.273599246506047,1739502640.2347872,0.6299993991851807,0.5800415046128746 +1739502640.2544994,0.6499993801116943,0.16605068655188848,1739502640.2545033,0.6499993801116943,-0.0009043270420709959,1739502640.2545078,0.6499993801116943,0.02290699470446648,1739502640.2545135,0.6499993801116943,3.17762407557747,1739502640.2545164,0.6499993801116943,-0.08008663722247125,1739502640.2545204,0.6499993801116943,-0.026286615384780634,1739502640.254524,0.6499993801116943,-0.05030998898661317,1739502640.2545276,0.6499993801116943,-0.04256957009120678,1739502640.2545311,0.6499993801116943,2.4013780034457635,1739502640.2545347,0.6499993801116943,0.0,1739502640.254538,0.6499993801116943,1.8213364988328888,1739502640.2545416,0.6499993801116943,6.273599246506047,1739502640.2545455,0.6499993801116943,0.5800415046128746 +1739502640.274287,0.669999361038208,0.16605068655188848,1739502640.2742908,0.669999361038208,-0.0009043270420709959,1739502640.274295,0.669999361038208,0.02290699470446648,1739502640.2743,0.669999361038208,3.17762407557747,1739502640.274303,0.669999361038208,-0.08008663722247125,1739502640.2743065,0.669999361038208,-0.026286615384780634,1739502640.2743099,0.669999361038208,-0.05030998898661317,1739502640.2743132,0.669999361038208,-0.04256957009120678,1739502640.2743163,0.669999361038208,2.4013780034457635,1739502640.27432,0.669999361038208,0.0,1739502640.274323,0.669999361038208,1.8213364988328888,1739502640.2743266,0.669999361038208,6.273599246506047,1739502640.27433,0.669999361038208,0.5800415046128746 +1739502640.294291,0.6899993419647217,0.16605068655188848,1739502640.2942934,0.6899993419647217,-0.0009043270420709959,1739502640.2942963,0.6899993419647217,0.02290699470446648,1739502640.2942991,0.6899993419647217,3.17762407557747,1739502640.2943003,0.6899993419647217,-0.08008663722247125,1739502640.2943022,0.6899993419647217,-0.026286615384780634,1739502640.2943034,0.6899993419647217,-0.05030998898661317,1739502640.2943048,0.6899993419647217,-0.04256957009120678,1739502640.294306,0.6899993419647217,2.4013780034457635,1739502640.2943075,0.6899993419647217,0.0,1739502640.2943091,0.6899993419647217,1.8213364988328888,1739502640.2943103,0.6899993419647217,6.273599246506047,1739502640.294312,0.6899993419647217,0.5800415046128746 +1739502640.3135154,0.7099993228912354,0.16605068655188848,1739502640.313518,0.7099993228912354,-0.0009043270420709959,1739502640.313521,0.7099993228912354,0.02290699470446648,1739502640.3135238,0.7099993228912354,3.17762407557747,1739502640.3135252,0.7099993228912354,-0.08008663722247125,1739502640.313527,0.7099993228912354,-0.026286615384780634,1739502640.3135285,0.7099993228912354,-0.05030998898661317,1739502640.3135302,0.7099993228912354,-0.04256957009120678,1739502640.3135314,0.7099993228912354,2.4013780034457635,1739502640.313533,0.7099993228912354,0.0,1739502640.3135345,0.7099993228912354,1.8213364988328888,1739502640.313536,0.7099993228912354,6.273599246506047,1739502640.3135376,0.7099993228912354,0.5800415046128746 +1739502640.333441,0.729999303817749,0.2353344217403004,1739502640.3334439,0.729999303817749,-0.0016454362006603773,1739502640.3334472,0.729999303817749,0.023599832056350602,1739502640.3334506,0.729999303817749,3.397459815032914,1739502640.333452,0.729999303817749,-0.08416954125074805,1739502640.3334541,0.729999303817749,-0.02609174749193811,1739502640.3334558,0.729999303817749,-0.04472006099628646,1739502640.3334575,0.729999303817749,-0.034323438540162184,1739502640.333459,0.729999303817749,2.4121408750736038,1739502640.3334608,0.729999303817749,0.0,1739502640.3334625,0.729999303817749,1.677584920641746,1739502640.3334644,0.729999303817749,6.271231622981098,1739502640.3334658,0.729999303817749,0.6896335567937066 +1739502640.3568933,0.7499992847442627,0.2353344217403004,1739502640.3569028,0.7499992847442627,-0.0016454362006603773,1739502640.3569148,0.7499992847442627,0.023599832056350602,1739502640.3569255,0.7499992847442627,3.397459815032914,1739502640.3569312,0.7499992847442627,-0.08416954125074805,1739502640.3569381,0.7499992847442627,-0.02609174749193811,1739502640.3569438,0.7499992847442627,-0.04472006099628646,1739502640.3569493,0.7499992847442627,-0.034323438540162184,1739502640.3569543,0.7499992847442627,2.4121408750736038,1739502640.3569608,0.7499992847442627,0.0,1739502640.3569658,0.7499992847442627,1.7225073182798971,1739502640.3569717,0.7499992847442627,6.271231622981098,1739502640.3569775,0.7499992847442627,0.6896335567937066 +1739502640.3850803,0.7699992656707764,0.2353344217403004,1739502640.385095,0.7699992656707764,-0.0016454362006603773,1739502640.3851132,0.7699992656707764,0.023599832056350602,1739502640.3851342,0.7699992656707764,3.397459815032914,1739502640.3851469,0.7699992656707764,-0.08416954125074805,1739502640.3851619,0.7699992656707764,-0.02609174749193811,1739502640.3851755,0.7699992656707764,-0.04472006099628646,1739502640.385189,0.7699992656707764,-0.034323438540162184,1739502640.3852026,0.7699992656707764,2.4121408750736038,1739502640.385217,0.7699992656707764,0.0,1739502640.3852313,0.7699992656707764,1.7225073182798971,1739502640.385245,0.7699992656707764,6.271231622981098,1739502640.385259,0.7699992656707764,0.6896335567937066 +1739502640.3975549,0.78999924659729,0.2353344217403004,1739502640.39756,0.78999924659729,-0.0016454362006603773,1739502640.3975656,0.78999924659729,0.023599832056350602,1739502640.3975716,0.78999924659729,3.397459815032914,1739502640.3975747,0.78999924659729,-0.08416954125074805,1739502640.397578,0.78999924659729,-0.02609174749193811,1739502640.397581,0.78999924659729,-0.04472006099628646,1739502640.397584,0.78999924659729,-0.034323438540162184,1739502640.3975866,0.78999924659729,2.4121408750736038,1739502640.3975902,0.78999924659729,0.0,1739502640.397593,0.78999924659729,1.7225073182798971,1739502640.3975961,0.78999924659729,6.271231622981098,1739502640.397599,0.78999924659729,0.6896335567937066 +1739502640.41485,0.8099992275238037,0.2353344217403004,1739502640.414855,0.8099992275238037,-0.0016454362006603773,1739502640.4148607,0.8099992275238037,0.023599832056350602,1739502640.4148676,0.8099992275238037,3.397459815032914,1739502640.4148715,0.8099992275238037,-0.08416954125074805,1739502640.4148762,0.8099992275238037,-0.02609174749193811,1739502640.4148808,0.8099992275238037,-0.04472006099628646,1739502640.414885,0.8099992275238037,-0.034323438540162184,1739502640.4148896,0.8099992275238037,2.4121408750736038,1739502640.414894,0.8099992275238037,0.0,1739502640.4148986,0.8099992275238037,1.7225073182798971,1739502640.4149034,0.8099992275238037,6.271231622981098,1739502640.4149082,0.8099992275238037,0.6896335567937066 +1739502640.434772,0.8299992084503174,0.2353344217403004,1739502640.4347758,0.8299992084503174,-0.0016454362006603773,1739502640.4347808,0.8299992084503174,0.023599832056350602,1739502640.4347866,0.8299992084503174,3.397459815032914,1739502640.4347897,0.8299992084503174,-0.08416954125074805,1739502640.4347937,0.8299992084503174,-0.02609174749193811,1739502640.434797,0.8299992084503174,-0.04472006099628646,1739502640.4348006,0.8299992084503174,-0.034323438540162184,1739502640.4348042,0.8299992084503174,2.4121408750736038,1739502640.434808,0.8299992084503174,0.0,1739502640.4348116,0.8299992084503174,1.7225073182798971,1739502640.4348152,0.8299992084503174,6.271231622981098,1739502640.4348187,0.8299992084503174,0.6896335567937066 +1739502640.4545758,0.849999189376831,0.3166765633221438,1739502640.4545803,0.849999189376831,-0.002707735237910569,1739502640.4545853,0.849999189376831,0.024413253472169036,1739502640.454591,0.849999189376831,3.617526599584563,1739502640.4545944,0.849999189376831,-0.08810172133897894,1739502640.4545984,0.849999189376831,-0.02586453252762726,1739502640.4546022,0.849999189376831,-0.038114355898973114,1739502640.4546058,0.849999189376831,-0.026847018324658536,1739502640.4546092,0.849999189376831,2.4249217289696032,1739502640.4546132,0.849999189376831,0.0,1739502640.4546168,0.849999189376831,1.5816125429031744,1739502640.4546206,0.849999189376831,6.26886399945615,1739502640.4546242,0.849999189376831,0.7992795398931174 +1739502640.4740784,0.8699991703033447,0.3166765633221438,1739502640.4740825,0.8699991703033447,-0.002707735237910569,1739502640.4740882,0.8699991703033447,0.024413253472169036,1739502640.4740937,0.8699991703033447,3.617526599584563,1739502640.4740965,0.8699991703033447,-0.08810172133897894,1739502640.4741008,0.8699991703033447,-0.02586453252762726,1739502640.4741044,0.8699991703033447,-0.038114355898973114,1739502640.4741082,0.8699991703033447,-0.026847018324658536,1739502640.474112,0.8699991703033447,2.4249217289696032,1739502640.4741156,0.8699991703033447,0.0,1739502640.4741194,0.8699991703033447,1.6256421890764858,1739502640.474123,0.8699991703033447,6.26886399945615,1739502640.4741268,0.8699991703033447,0.7992795398931174 +1739502640.502023,0.8899991512298584,0.3166765633221438,1739502640.5020378,0.8899991512298584,-0.002707735237910569,1739502640.5020564,0.8899991512298584,0.024413253472169036,1739502640.5020776,0.8899991512298584,3.617526599584563,1739502640.5020895,0.8899991512298584,-0.08810172133897894,1739502640.5021048,0.8899991512298584,-0.02586453252762726,1739502640.5021186,0.8899991512298584,-0.038114355898973114,1739502640.5021322,0.8899991512298584,-0.026847018324658536,1739502640.502146,0.8899991512298584,2.4249217289696032,1739502640.50216,0.8899991512298584,0.0,1739502640.502174,0.8899991512298584,1.6256421890764858,1739502640.502188,0.8899991512298584,6.26886399945615,1739502640.5022023,0.8899991512298584,0.7992795398931174 +1739502640.5192823,0.9099991321563721,0.3166765633221438,1739502640.5192907,0.9099991321563721,-0.002707735237910569,1739502640.519299,0.9099991321563721,0.024413253472169036,1739502640.5193076,0.9099991321563721,3.617526599584563,1739502640.519312,0.9099991321563721,-0.08810172133897894,1739502640.5193172,0.9099991321563721,-0.02586453252762726,1739502640.5193214,0.9099991321563721,-0.038114355898973114,1739502640.5193253,0.9099991321563721,-0.026847018324658536,1739502640.519329,0.9099991321563721,2.4249217289696032,1739502640.5193338,0.9099991321563721,0.0,1739502640.519338,0.9099991321563721,1.6256421890764858,1739502640.5193422,0.9099991321563721,6.26886399945615,1739502640.5193465,0.9099991321563721,0.7992795398931174 +1739502640.5347235,0.9299991130828857,0.3166765633221438,1739502640.5347276,0.9299991130828857,-0.002707735237910569,1739502640.534732,0.9299991130828857,0.024413253472169036,1739502640.534736,0.9299991130828857,3.617526599584563,1739502640.5347378,0.9299991130828857,-0.08810172133897894,1739502640.5347404,0.9299991130828857,-0.02586453252762726,1739502640.5347428,0.9299991130828857,-0.038114355898973114,1739502640.5347447,0.9299991130828857,-0.026847018324658536,1739502640.5347466,0.9299991130828857,2.4249217289696032,1739502640.534749,0.9299991130828857,0.0,1739502640.5347512,0.9299991130828857,1.6256421890764858,1739502640.5347533,0.9299991130828857,6.26886399945615,1739502640.5347552,0.9299991130828857,0.7992795398931174 +1739502640.555539,0.9499990940093994,0.4100681339427581,1739502640.5555413,0.9499990940093994,-0.0041482056880957074,1739502640.5555441,0.9499990940093994,0.02534716917837518,1739502640.555547,0.9499990940093994,3.837532068798082,1739502640.5555484,0.9499990940093994,-0.09302319255726027,1739502640.55555,0.9499990940093994,-0.025924437836012997,1739502640.5555515,0.9499990940093994,-0.03166455566573931,1739502640.5555532,0.9499990940093994,-0.020686643758999892,1739502640.5555546,0.9499990940093994,2.4374662736468435,1739502640.5555565,0.9499990940093994,0.0,1739502640.5555582,0.9499990940093994,1.4845239615592318,1739502640.5555596,0.9499990940093994,6.266496375931202,1739502640.555561,0.9499990940093994,0.9088428370746009 +1739502640.575119,0.9699990749359131,0.4100681339427581,1739502640.5751214,0.9699990749359131,-0.0041482056880957074,1739502640.5751243,0.9699990749359131,0.02534716917837518,1739502640.5751274,0.9699990749359131,3.837532068798082,1739502640.5751286,0.9699990749359131,-0.09302319255726027,1739502640.5751305,0.9699990749359131,-0.025924437836012997,1739502640.575132,0.9699990749359131,-0.03166455566573931,1739502640.5751333,0.9699990749359131,-0.020686643758999892,1739502640.5751348,0.9699990749359131,2.4374662736468435,1739502640.5751364,0.9699990749359131,0.0,1739502640.575138,0.9699990749359131,1.5286234365722426,1739502640.5751395,0.9699990749359131,6.266496375931202,1739502640.575141,0.9699990749359131,0.9088428370746009 +1739502640.5953233,0.9899990558624268,0.4100681339427581,1739502640.5953262,0.9899990558624268,-0.0041482056880957074,1739502640.5953293,0.9899990558624268,0.02534716917837518,1739502640.5953321,0.9899990558624268,3.837532068798082,1739502640.5953336,0.9899990558624268,-0.09302319255726027,1739502640.5953355,0.9899990558624268,-0.025924437836012997,1739502640.5953367,0.9899990558624268,-0.03166455566573931,1739502640.5953383,0.9899990558624268,-0.020686643758999892,1739502640.5953395,0.9899990558624268,2.4374662736468435,1739502640.595341,0.9899990558624268,0.0,1739502640.5953424,0.9899990558624268,1.5286234365722426,1739502640.5953438,0.9899990558624268,6.266496375931202,1739502640.5953455,0.9899990558624268,0.9088428370746009 +1739502640.6145818,1.0099990367889404,0.4100681339427581,1739502640.614584,1.0099990367889404,-0.0041482056880957074,1739502640.6145866,1.0099990367889404,0.02534716917837518,1739502640.6145897,1.0099990367889404,3.837532068798082,1739502640.614591,1.0099990367889404,-0.09302319255726027,1739502640.6145928,1.0099990367889404,-0.025924437836012997,1739502640.6145942,1.0099990367889404,-0.03166455566573931,1739502640.6145957,1.0099990367889404,-0.020686643758999892,1739502640.6145968,1.0099990367889404,2.4374662736468435,1739502640.6145985,1.0099990367889404,0.0,1739502640.6145997,1.0099990367889404,1.5286234365722426,1739502640.6146011,1.0099990367889404,6.266496375931202,1739502640.6146026,1.0099990367889404,0.9088428370746009 +1739502640.6344874,1.029999017715454,0.4100681339427581,1739502640.6344895,1.029999017715454,-0.0041482056880957074,1739502640.6344926,1.029999017715454,0.02534716917837518,1739502640.6344955,1.029999017715454,3.837532068798082,1739502640.6344967,1.029999017715454,-0.09302319255726027,1739502640.6344986,1.029999017715454,-0.025924437836012997,1739502640.6344998,1.029999017715454,-0.03166455566573931,1739502640.6345015,1.029999017715454,-0.020686643758999892,1739502640.6345026,1.029999017715454,2.4374662736468435,1739502640.634504,1.029999017715454,0.0,1739502640.6345055,1.029999017715454,1.5286234365722426,1739502640.634507,1.029999017715454,6.266496375931202,1739502640.6345086,1.029999017715454,0.9088428370746009 +1739502640.665321,1.0599989891052246,0.5155128223249328,1739502640.6653266,1.0599989891052246,-0.006024001398603929,1739502640.6653323,1.0599989891052246,0.026401616062196927,1739502640.6653385,1.0599989891052246,4.0578073735183535,1739502640.665342,1.0599989891052246,-0.09596058485825128,1739502640.6653469,1.0599989891052246,-0.025383904323323894,1739502640.6653507,1.0599989891052246,-0.022420409104920064,1739502640.6653545,1.0599989891052246,-0.01371363294952331,1739502640.6653578,1.0599989891052246,2.455558928024578,1739502640.665362,1.0599989891052246,0.0,1739502640.6653655,1.0599989891052246,1.3954898514590925,1739502640.665369,1.0599989891052246,6.264128752406254,1739502640.6653728,1.0599989891052246,1.0184648039397393 +1739502640.6937695,1.0799989700317383,0.5155128223249328,1739502640.693774,1.0799989700317383,-0.006024001398603929,1739502640.6937795,1.0799989700317383,0.026401616062196927,1739502640.6937854,1.0799989700317383,4.0578073735183535,1739502640.6937885,1.0799989700317383,-0.09596058485825128,1739502640.6937923,1.0799989700317383,-0.025383904323323894,1739502640.693796,1.0799989700317383,-0.022420409104920064,1739502640.6937995,1.0799989700317383,-0.01371363294952331,1739502640.6938028,1.0799989700317383,2.455558928024578,1739502640.6938066,1.0799989700317383,0.0,1739502640.69381,1.0799989700317383,1.4370941240848387,1739502640.6938136,1.0799989700317383,6.264128752406254,1739502640.6938174,1.0799989700317383,1.0184648039397393 +1739502640.6997993,1.099998950958252,0.5155128223249328,1739502640.6998043,1.099998950958252,-0.006024001398603929,1739502640.6998112,1.099998950958252,0.026401616062196927,1739502640.699819,1.099998950958252,4.0578073735183535,1739502640.6998234,1.099998950958252,-0.09596058485825128,1739502640.6998284,1.099998950958252,-0.025383904323323894,1739502640.6998305,1.099998950958252,-0.022420409104920064,1739502640.6998534,1.099998950958252,-0.01371363294952331,1739502640.699855,1.099998950958252,2.455558928024578,1739502640.6998587,1.099998950958252,0.0,1739502640.6998658,1.099998950958252,1.4370941240848387,1739502640.6998703,1.099998950958252,6.264128752406254,1739502640.6998754,1.099998950958252,1.0184648039397393 +1739502640.7195532,1.1199989318847656,0.5155128223249328,1739502640.7195568,1.1199989318847656,-0.006024001398603929,1739502640.7195604,1.1199989318847656,0.026401616062196927,1739502640.7195635,1.1199989318847656,4.0578073735183535,1739502640.7195654,1.1199989318847656,-0.09596058485825128,1739502640.7195675,1.1199989318847656,-0.025383904323323894,1739502640.7195694,1.1199989318847656,-0.022420409104920064,1739502640.719571,1.1199989318847656,-0.01371363294952331,1739502640.7195728,1.1199989318847656,2.455558928024578,1739502640.7195745,1.1199989318847656,0.0,1739502640.7195761,1.1199989318847656,1.4370941240848387,1739502640.7195776,1.1199989318847656,6.264128752406254,1739502640.7195795,1.1199989318847656,1.0184648039397393 +1739502640.7412546,1.1399989128112793,0.5155128223249328,1739502640.7412622,1.1399989128112793,-0.006024001398603929,1739502640.741271,1.1399989128112793,0.026401616062196927,1739502640.741279,1.1399989128112793,4.0578073735183535,1739502640.7412827,1.1399989128112793,-0.09596058485825128,1739502640.7412882,1.1399989128112793,-0.025383904323323894,1739502640.7412922,1.1399989128112793,-0.022420409104920064,1739502640.7412963,1.1399989128112793,-0.01371363294952331,1739502640.7413,1.1399989128112793,2.455558928024578,1739502640.7413049,1.1399989128112793,0.0,1739502640.7413087,1.1399989128112793,1.4370941240848387,1739502640.741313,1.1399989128112793,6.264128752406254,1739502640.7413173,1.1399989128112793,1.0184648039397393 +1739502640.7623806,1.159998893737793,0.5155128223249328,1739502640.762388,1.159998893737793,-0.006024001398603929,1739502640.7623968,1.159998893737793,0.026401616062196927,1739502640.7624054,1.159998893737793,4.0578073735183535,1739502640.7624094,1.159998893737793,-0.09596058485825128,1739502640.7624152,1.159998893737793,-0.025383904323323894,1739502640.7624192,1.159998893737793,-0.022420409104920064,1739502640.7624235,1.159998893737793,-0.01371363294952331,1739502640.7624273,1.159998893737793,2.455558928024578,1739502640.762432,1.159998893737793,0.0,1739502640.7624362,1.159998893737793,1.4370941240848387,1739502640.7624407,1.159998893737793,6.264128752406254,1739502640.7624452,1.159998893737793,1.0184648039397393 +1739502640.7894094,1.1799988746643066,0.6330084566019529,1739502640.7894175,1.1799988746643066,-0.008388629592535501,1739502640.789426,1.1799988746643066,0.02757657240496713,1739502640.7894342,1.1799988746643066,4.278170138816449,1739502640.789438,1.1799988746643066,-0.09952495456837804,1739502640.789443,1.1799988746643066,-0.024996790339990207,1739502640.7894478,1.1799988746643066,-0.013291131241874572,1739502640.7894518,1.1799988746643066,-0.007677454177262558,1739502640.7894557,1.1799988746643066,2.473558561288127,1739502640.7894602,1.1799988746643066,0.0,1739502640.7894642,1.1799988746643066,1.3038427011648865,1739502640.7894688,1.1799988746643066,6.2618336249659325,1739502640.789473,1.1799988746643066,1.1280747631587245 +1739502640.8133814,1.2099988460540771,0.6330084566019529,1739502640.8133948,1.2099988460540771,-0.008388629592535501,1739502640.813412,1.2099988460540771,0.02757657240496713,1739502640.8134277,1.2099988460540771,4.278170138816449,1739502640.8134363,1.2099988460540771,-0.09952495456837804,1739502640.8134484,1.2099988460540771,-0.024996790339990207,1739502640.8134606,1.2099988460540771,-0.013291131241874572,1739502640.8134735,1.2099988460540771,-0.007677454177262558,1739502640.8134828,1.2099988460540771,2.473558561288127,1739502640.8134875,1.2099988460540771,0.0,1739502640.8134913,1.2099988460540771,1.3454837981294023,1739502640.813496,1.2099988460540771,6.2618336249659325,1739502640.8135002,1.2099988460540771,1.1280747631587245 +1739502640.835117,1.2299988269805908,0.6330084566019529,1739502640.835128,1.2299988269805908,-0.008388629592535501,1739502640.8351417,1.2299988269805908,0.02757657240496713,1739502640.8351574,1.2299988269805908,4.278170138816449,1739502640.835167,1.2299988269805908,-0.09952495456837804,1739502640.835181,1.2299988269805908,-0.024996790339990207,1739502640.8351943,1.2299988269805908,-0.013291131241874572,1739502640.835205,1.2299988269805908,-0.007677454177262558,1739502640.835215,1.2299988269805908,2.473558561288127,1739502640.8352258,1.2299988269805908,0.0,1739502640.835236,1.2299988269805908,1.3454837981294023,1739502640.8352466,1.2299988269805908,6.2618336249659325,1739502640.8352568,1.2299988269805908,1.1280747631587245 +1739502640.854858,1.2499988079071045,0.6330084566019529,1739502640.854865,1.2499988079071045,-0.008388629592535501,1739502640.8548746,1.2499988079071045,0.02757657240496713,1739502640.854883,1.2499988079071045,4.278170138816449,1739502640.8548877,1.2499988079071045,-0.09952495456837804,1739502640.854893,1.2499988079071045,-0.024996790339990207,1739502640.8548977,1.2499988079071045,-0.013291131241874572,1739502640.8549018,1.2499988079071045,-0.007677454177262558,1739502640.8549056,1.2499988079071045,2.473558561288127,1739502640.8549101,1.2499988079071045,0.0,1739502640.8549142,1.2499988079071045,1.3454837981294023,1739502640.8549192,1.2499988079071045,6.2618336249659325,1739502640.854923,1.2499988079071045,1.1280747631587245 +1739502640.8747249,1.2699987888336182,0.6330084566019529,1739502640.8747323,1.2699987888336182,-0.008388629592535501,1739502640.8747408,1.2699987888336182,0.02757657240496713,1739502640.874749,1.2699987888336182,4.278170138816449,1739502640.8747528,1.2699987888336182,-0.09952495456837804,1739502640.8747582,1.2699987888336182,-0.024996790339990207,1739502640.8747625,1.2699987888336182,-0.013291131241874572,1739502640.8747666,1.2699987888336182,-0.007677454177262558,1739502640.8747706,1.2699987888336182,2.473558561288127,1739502640.8747756,1.2699987888336182,0.0,1739502640.8747797,1.2699987888336182,1.3454837981294023,1739502640.874784,1.2699987888336182,6.2618336249659325,1739502640.874788,1.2699987888336182,1.1280747631587245 +1739502640.8945048,1.2899987697601318,0.7625444461948137,1739502640.894512,1.2899987697601318,-0.011284503608371743,1739502640.89452,1.2899987697601318,0.028871932300895735,1739502640.894528,1.2899987697601318,4.498478494353831,1739502640.8945317,1.2899987697601318,-0.10276618876341846,1739502640.894537,1.2899987697601318,-0.024482072237631287,1739502640.894541,1.2899987697601318,-0.003796239992356659,1739502640.894545,1.2899987697601318,-0.0020876422536527765,1739502640.894549,1.2899987697601318,2.4924190375032937,1739502640.8945537,1.2899987697601318,0.0,1739502640.894558,1.2899987697601318,1.2136150749875065,1739502640.894562,1.2899987697601318,6.259719072741353,1739502640.8945668,1.2899987697601318,1.237594959515217 +1739502640.9148214,1.3099987506866455,0.7625444461948137,1739502640.9148293,1.3099987506866455,-0.011284503608371743,1739502640.9148383,1.3099987506866455,0.028871932300895735,1739502640.9148467,1.3099987506866455,4.498478494353831,1739502640.9148521,1.3099987506866455,-0.10276618876341846,1739502640.9148586,1.3099987506866455,-0.024482072237631287,1739502640.914863,1.3099987506866455,-0.003796239992356659,1739502640.9148674,1.3099987506866455,-0.0020876422536527765,1739502640.9148715,1.3099987506866455,2.4924190375032937,1739502640.9148765,1.3099987506866455,0.0,1739502640.9148805,1.3099987506866455,1.2548240779880768,1739502640.914885,1.3099987506866455,6.259719072741353,1739502640.9148898,1.3099987506866455,1.237594959515217 +1739502640.9547343,1.3499987125396729,0.7625444461948137,1739502640.954738,1.3499987125396729,-0.011284503608371743,1739502640.9547422,1.3499987125396729,0.028871932300895735,1739502640.9547465,1.3499987125396729,4.498478494353831,1739502640.9547484,1.3499987125396729,-0.10276618876341846,1739502640.9547508,1.3499987125396729,-0.024482072237631287,1739502640.954753,1.3499987125396729,-0.003796239992356659,1739502640.954755,1.3499987125396729,-0.0020876422536527765,1739502640.9547572,1.3499987125396729,2.4924190375032937,1739502640.9547594,1.3499987125396729,0.0,1739502640.9547615,1.3499987125396729,1.2548240779880768,1739502640.9547634,1.3499987125396729,6.259719072741353,1739502640.9547656,1.3499987125396729,1.237594959515217 +1739502640.9748285,1.3699986934661865,0.7625444461948137,1739502640.9748309,1.3699986934661865,-0.011284503608371743,1739502640.974834,1.3699986934661865,0.028871932300895735,1739502640.9748368,1.3699986934661865,4.498478494353831,1739502640.974838,1.3699986934661865,-0.10276618876341846,1739502640.97484,1.3699986934661865,-0.024482072237631287,1739502640.9748414,1.3699986934661865,-0.003796239992356659,1739502640.9748428,1.3699986934661865,-0.0020876422536527765,1739502640.9748442,1.3699986934661865,2.4924190375032937,1739502640.974846,1.3699986934661865,0.0,1739502640.9748473,1.3699986934661865,1.2548240779880768,1739502640.9748487,1.3699986934661865,6.259719072741353,1739502640.97485,1.3699986934661865,1.237594959515217 +1739502640.9951413,1.3899986743927002,0.9041174697190657,1739502640.9951444,1.3899986743927002,-0.014731825254432174,1739502640.9951475,1.3899986743927002,0.030287662536138252,1739502640.9951503,1.3899986743927002,4.718890758243079,1739502640.9951518,1.3899986743927002,-0.10530649184882504,1739502640.9951537,1.3899986743927002,-0.02373867211054338,1739502640.9951549,1.3899986743927002,0.005957619212993994,1739502640.9951568,1.3899986743927002,0.0031423284542696586,1739502640.995158,1.3899986743927002,2.4881131110986328,1739502640.9951596,1.3899986743927002,0.0,1739502640.995161,1.3899986743927002,1.08927955105566,1739502640.995163,1.3899986743927002,6.257885351441234,1739502640.9951644,1.3899986743927002,1.347100861457992 +1739502641.0138514,1.4099986553192139,0.9041174697190657,1739502641.0138538,1.4099986553192139,-0.014731825254432174,1739502641.0138562,1.4099986553192139,0.030287662536138252,1739502641.0138588,1.4099986553192139,4.718890758243079,1739502641.01386,1.4099986553192139,-0.10530649184882504,1739502641.0138617,1.4099986553192139,-0.02373867211054338,1739502641.013863,1.4099986553192139,0.005957619212993994,1739502641.0138645,1.4099986553192139,0.0031423284542696586,1739502641.0138657,1.4099986553192139,2.4881131110986328,1739502641.0138674,1.4099986553192139,0.0,1739502641.0138683,1.4099986553192139,1.1410122496406407,1739502641.0138698,1.4099986553192139,6.257885351441234,1739502641.0138714,1.4099986553192139,1.347100861457992 +1739502641.0339303,1.4299986362457275,0.9041174697190657,1739502641.0339324,1.4299986362457275,-0.014731825254432174,1739502641.0339355,1.4299986362457275,0.030287662536138252,1739502641.0339382,1.4299986362457275,4.718890758243079,1739502641.0339396,1.4299986362457275,-0.10530649184882504,1739502641.0339413,1.4299986362457275,-0.02373867211054338,1739502641.0339427,1.4299986362457275,0.005957619212993994,1739502641.0339441,1.4299986362457275,0.0031423284542696586,1739502641.0339458,1.4299986362457275,2.4881131110986328,1739502641.0339477,1.4299986362457275,0.0,1739502641.033949,1.4299986362457275,1.1410122496406407,1739502641.0339506,1.4299986362457275,6.257885351441234,1739502641.033952,1.4299986362457275,1.347100861457992 +1739502641.0538464,1.4499986171722412,0.9041174697190657,1739502641.0538487,1.4499986171722412,-0.014731825254432174,1739502641.0538516,1.4499986171722412,0.030287662536138252,1739502641.0538547,1.4499986171722412,4.718890758243079,1739502641.0538564,1.4499986171722412,-0.10530649184882504,1739502641.0538578,1.4499986171722412,-0.02373867211054338,1739502641.0538595,1.4499986171722412,0.005957619212993994,1739502641.0538611,1.4499986171722412,0.0031423284542696586,1739502641.0538623,1.4499986171722412,2.4881131110986328,1739502641.0538645,1.4499986171722412,0.0,1739502641.0538657,1.4499986171722412,1.1410122496406407,1739502641.0538676,1.4499986171722412,6.257885351441234,1739502641.0538688,1.4499986171722412,1.347100861457992 +1739502641.0780823,1.4699985980987549,0.9041174697190657,1739502641.0780928,1.4699985980987549,-0.014731825254432174,1739502641.078105,1.4699985980987549,0.030287662536138252,1739502641.0781167,1.4699985980987549,4.718890758243079,1739502641.0781221,1.4699985980987549,-0.10530649184882504,1739502641.078129,1.4699985980987549,-0.02373867211054338,1739502641.0781345,1.4699985980987549,0.005957619212993994,1739502641.0781403,1.4699985980987549,0.0031423284542696586,1739502641.0781455,1.4699985980987549,2.4881131110986328,1739502641.0781522,1.4699985980987549,0.0,1739502641.078158,1.4699985980987549,1.1410122496406407,1739502641.0781639,1.4699985980987549,6.257885351441234,1739502641.0781698,1.4699985980987549,1.347100861457992 +1739502641.1015806,1.4899985790252686,0.9041174697190657,1739502641.1015952,1.4899985790252686,-0.014731825254432174,1739502641.1016135,1.4899985790252686,0.030287662536138252,1739502641.101635,1.4899985790252686,4.718890758243079,1739502641.1016467,1.4899985790252686,-0.10530649184882504,1739502641.1016617,1.4899985790252686,-0.02373867211054338,1739502641.1016755,1.4899985790252686,0.005957619212993994,1739502641.1016889,1.4899985790252686,0.0031423284542696586,1739502641.1017025,1.4899985790252686,2.4881131110986328,1739502641.1017165,1.4899985790252686,0.0,1739502641.1017303,1.4899985790252686,1.1410122496406407,1739502641.1017444,1.4899985790252686,6.257885351441234,1739502641.1017585,1.4899985790252686,1.347100861457992 +1739502641.120495,1.5099985599517822,1.057733673796732,1739502641.120505,1.5099985599517822,-0.018733655665641002,1739502641.1205168,1.5099985599517822,0.2371771832263732,1739502641.120528,1.5099985599517822,5.144887836913158,1739502641.1205335,1.5099985599517822,-0.11077973771494862,1739502641.1205406,1.5099985599517822,-0.022517018338008673,1739502641.1205466,1.5099985599517822,0.017902479370068874,1739502641.1205518,1.5099985599517822,0.008226423477328253,1739502641.120557,1.5099985599517822,2.464450220596629,1739502641.1205637,1.5099985599517822,0.0,1739502641.120569,1.5099985599517822,0.9472131207234842,1739502641.120575,1.5099985599517822,6.256289203143346,1739502641.1205807,1.5099985599517822,1.4566748323788168 +1739502641.1419575,1.529998540878296,1.057733673796732,1739502641.141965,1.529998540878296,-0.018733655665641002,1739502641.141977,1.529998540878296,0.2371771832263732,1739502641.1419866,1.529998540878296,5.144887836913158,1739502641.1419911,1.529998540878296,-0.11077973771494862,1739502641.1419976,1.529998540878296,-0.022517018338008673,1739502641.1420033,1.529998540878296,0.017902479370068874,1739502641.1420085,1.529998540878296,0.008226423477328253,1739502641.1420143,1.529998540878296,2.464450220596629,1739502641.14202,1.529998540878296,0.0,1739502641.1420255,1.529998540878296,1.0077753882178124,1739502641.1420312,1.529998540878296,6.256289203143346,1739502641.1420367,1.529998540878296,1.4566748323788168 +1739502641.158897,1.5599985122680664,1.057733673796732,1739502641.1589003,1.5599985122680664,-0.018733655665641002,1739502641.158904,1.5599985122680664,0.2371771832263732,1739502641.1589074,1.5599985122680664,5.144887836913158,1739502641.158909,1.5599985122680664,-0.11077973771494862,1739502641.1589112,1.5599985122680664,-0.022517018338008673,1739502641.1589131,1.5599985122680664,0.017902479370068874,1739502641.1589148,1.5599985122680664,0.008226423477328253,1739502641.1589167,1.5599985122680664,2.464450220596629,1739502641.1589184,1.5599985122680664,0.0,1739502641.15892,1.5599985122680664,1.0077753882178124,1739502641.1589217,1.5599985122680664,6.256289203143346,1739502641.1589239,1.5599985122680664,1.4566748323788168 +1739502641.1777298,1.57999849319458,1.057733673796732,1739502641.1777332,1.57999849319458,-0.018733655665641002,1739502641.177758,1.57999849319458,0.2371771832263732,1739502641.177761,1.57999849319458,5.144887836913158,1739502641.1777625,1.57999849319458,-0.11077973771494862,1739502641.1777642,1.57999849319458,-0.022517018338008673,1739502641.1777656,1.57999849319458,0.017902479370068874,1739502641.1777673,1.57999849319458,0.008226423477328253,1739502641.1777685,1.57999849319458,2.464450220596629,1739502641.1777701,1.57999849319458,0.0,1739502641.1777718,1.57999849319458,1.0077753882178124,1739502641.1777732,1.57999849319458,6.256289203143346,1739502641.177775,1.57999849319458,1.4566748323788168 +1739502641.199941,1.5999984741210938,1.057733673796732,1739502641.1999502,1.5999984741210938,-0.018733655665641002,1739502641.1999593,1.5999984741210938,0.2371771832263732,1739502641.1999662,1.5999984741210938,5.144887836913158,1739502641.1999698,1.5999984741210938,-0.11077973771494862,1739502641.1999755,1.5999984741210938,-0.022517018338008673,1739502641.1999848,1.5999984741210938,0.017902479370068874,1739502641.199994,1.5999984741210938,0.008226423477328253,1739502641.2000022,1.5999984741210938,2.464450220596629,1739502641.2000105,1.5999984741210938,0.0,1739502641.200015,1.5999984741210938,1.0077753882178124,1739502641.2000203,1.5999984741210938,6.256289203143346,1739502641.2000246,1.5999984741210938,1.4566748323788168 +1739502641.2194567,1.6199984550476074,1.2232570224346127,1739502641.2194657,1.6199984550476074,-0.023297337112818894,1739502641.2194726,1.6199984550476074,0.23850137001547628,1739502641.2194786,1.6199984550476074,5.362005910222087,1739502641.2194822,1.6199984550476074,-0.11319797823148008,1739502641.2194865,1.6199984550476074,-0.02171827965964367,1739502641.2194893,1.6199984550476074,0.027235237172512652,1739502641.2194936,1.6199984550476074,0.012205258041634514,1739502641.2194967,1.6199984550476074,2.446118645792294,1739502641.2195003,1.6199984550476074,0.0,1739502641.2195039,1.6199984550476074,0.8241603876901622,1739502641.2195072,1.6199984550476074,6.254887983614709,1739502641.2195106,1.6199984550476074,1.5645785328161617 +1739502641.2387338,1.639998435974121,1.2232570224346127,1739502641.2387385,1.639998435974121,-0.023297337112818894,1739502641.2387435,1.639998435974121,0.23850137001547628,1739502641.2387488,1.639998435974121,5.362005910222087,1739502641.238751,1.639998435974121,-0.11319797823148008,1739502641.2387538,1.639998435974121,-0.02171827965964367,1739502641.2387567,1.639998435974121,0.027235237172512652,1739502641.2387593,1.639998435974121,0.012205258041634514,1739502641.2387612,1.639998435974121,2.446118645792294,1739502641.2387645,1.639998435974121,0.0,1739502641.2387671,1.639998435974121,0.8815401129761324,1739502641.2387693,1.639998435974121,6.254887983614709,1739502641.2387722,1.639998435974121,1.5645785328161617 +1739502641.2580733,1.6599984169006348,1.2232570224346127,1739502641.2580774,1.6599984169006348,-0.023297337112818894,1739502641.2580822,1.6599984169006348,0.23850137001547628,1739502641.2580862,1.6599984169006348,5.362005910222087,1739502641.258088,1.6599984169006348,-0.11319797823148008,1739502641.2580907,1.6599984169006348,-0.02171827965964367,1739502641.2580926,1.6599984169006348,0.027235237172512652,1739502641.2580945,1.6599984169006348,0.012205258041634514,1739502641.2580965,1.6599984169006348,2.446118645792294,1739502641.2580986,1.6599984169006348,0.0,1739502641.2581005,1.6599984169006348,0.8815401129761324,1739502641.258103,1.6599984169006348,6.254887983614709,1739502641.2581048,1.6599984169006348,1.5645785328161617 +1739502641.2776577,1.6799983978271484,1.2232570224346127,1739502641.277664,1.6799983978271484,-0.023297337112818894,1739502641.2776704,1.6799983978271484,0.23850137001547628,1739502641.2776766,1.6799983978271484,5.362005910222087,1739502641.2776806,1.6799983978271484,-0.11319797823148008,1739502641.2776854,1.6799983978271484,-0.02171827965964367,1739502641.27769,1.6799983978271484,0.027235237172512652,1739502641.2776942,1.6799983978271484,0.012205258041634514,1739502641.2776976,1.6799983978271484,2.446118645792294,1739502641.2777011,1.6799983978271484,0.0,1739502641.2777052,1.6799983978271484,0.8815401129761324,1739502641.2777088,1.6799983978271484,6.254887983614709,1739502641.2777126,1.6799983978271484,1.5645785328161617 +1739502641.297352,1.699998378753662,1.2232570224346127,1739502641.2973554,1.699998378753662,-0.023297337112818894,1739502641.29736,1.699998378753662,0.23850137001547628,1739502641.2973647,1.699998378753662,5.362005910222087,1739502641.2973673,1.699998378753662,-0.11319797823148008,1739502641.2973707,1.699998378753662,-0.02171827965964367,1739502641.2973735,1.699998378753662,0.027235237172512652,1739502641.2973762,1.699998378753662,0.012205258041634514,1739502641.2973785,1.699998378753662,2.446118645792294,1739502641.2973814,1.699998378753662,0.0,1739502641.297384,1.699998378753662,0.8815401129761324,1739502641.2973866,1.699998378753662,6.254887983614709,1739502641.2973895,1.699998378753662,1.5645785328161617 +1739502641.3176162,1.7199983596801758,1.4001356780696703,1739502641.3176186,1.7199983596801758,-0.028404985312024067,1739502641.3176217,1.7199983596801758,0.731228953788296,1739502641.3176248,1.7199983596801758,6.047714517682896,1739502641.317626,1.7199983596801758,-0.12151260674766835,1739502641.317628,1.7199983596801758,-0.020030895995679324,1739502641.3176298,1.7199983596801758,0.04406556359172311,1739502641.317631,1.7199983596801758,0.01566133595438605,1739502641.3176322,1.7199983596801758,2.413404197735044,1739502641.3176339,1.7199983596801758,0.0,1739502641.317635,1.7199983596801758,0.6935587115788099,1739502641.3176365,1.7199983596801758,6.253674769223807,1739502641.3176382,1.7199983596801758,1.6611012597038548 +1739502641.337591,1.7399983406066895,1.4001356780696703,1739502641.3375936,1.7399983406066895,-0.028404985312024067,1739502641.3375967,1.7399983406066895,0.731228953788296,1739502641.3375993,1.7399983406066895,6.047714517682896,1739502641.3376005,1.7399983406066895,-0.12151260674766835,1739502641.3376024,1.7399983406066895,-0.020030895995679324,1739502641.3376038,1.7399983406066895,0.04406556359172311,1739502641.3376052,1.7399983406066895,0.01566133595438605,1739502641.3376067,1.7399983406066895,2.413404197735044,1739502641.337608,1.7399983406066895,0.0,1739502641.3376095,1.7399983406066895,0.7523029380311894,1739502641.337611,1.7399983406066895,6.253674769223807,1739502641.3376126,1.7399983406066895,1.6611012597038548 +1739502641.3576992,1.7599983215332031,1.4001356780696703,1739502641.3577015,1.7599983215332031,-0.028404985312024067,1739502641.3577046,1.7599983215332031,0.731228953788296,1739502641.3577073,1.7599983215332031,6.047714517682896,1739502641.3577085,1.7599983215332031,-0.12151260674766835,1739502641.3577106,1.7599983215332031,-0.020030895995679324,1739502641.3577118,1.7599983215332031,0.04406556359172311,1739502641.3577132,1.7599983215332031,0.01566133595438605,1739502641.3577144,1.7599983215332031,2.413404197735044,1739502641.357716,1.7599983215332031,0.0,1739502641.3577175,1.7599983215332031,0.7523029380311894,1739502641.3577187,1.7599983215332031,6.253674769223807,1739502641.3577204,1.7599983215332031,1.6611012597038548 +1739502641.377292,1.7799983024597168,1.4001356780696703,1739502641.3772948,1.7799983024597168,-0.028404985312024067,1739502641.3772979,1.7799983024597168,0.731228953788296,1739502641.377301,1.7799983024597168,6.047714517682896,1739502641.3773022,1.7799983024597168,-0.12151260674766835,1739502641.377304,1.7799983024597168,-0.020030895995679324,1739502641.3773057,1.7799983024597168,0.04406556359172311,1739502641.3773072,1.7799983024597168,0.01566133595438605,1739502641.3773086,1.7799983024597168,2.413404197735044,1739502641.3773103,1.7799983024597168,0.0,1739502641.3773115,1.7799983024597168,0.7523029380311894,1739502641.3773131,1.7799983024597168,6.253674769223807,1739502641.3773146,1.7799983024597168,1.6611012597038548 +1739502641.3976717,1.7999982833862305,1.4001356780696703,1739502641.3976753,1.7999982833862305,-0.028404985312024067,1739502641.397679,1.7999982833862305,0.731228953788296,1739502641.3976827,1.7999982833862305,6.047714517682896,1739502641.3976846,1.7999982833862305,-0.12151260674766835,1739502641.3976867,1.7999982833862305,-0.020030895995679324,1739502641.3976886,1.7999982833862305,0.04406556359172311,1739502641.3976903,1.7999982833862305,0.01566133595438605,1739502641.397692,1.7999982833862305,2.413404197735044,1739502641.3976939,1.7999982833862305,0.0,1739502641.3976958,1.7999982833862305,0.7523029380311894,1739502641.3976974,1.7999982833862305,6.253674769223807,1739502641.3976994,1.7999982833862305,1.6611012597038548 +1739502641.4181209,1.8199982643127441,1.4001356780696703,1739502641.418125,1.8199982643127441,-0.028404985312024067,1739502641.4181297,1.8199982643127441,0.731228953788296,1739502641.418134,1.8199982643127441,6.047714517682896,1739502641.418136,1.8199982643127441,-0.12151260674766835,1739502641.4181383,1.8199982643127441,-0.020030895995679324,1739502641.4181404,1.8199982643127441,0.04406556359172311,1739502641.4181426,1.8199982643127441,0.01566133595438605,1739502641.4181442,1.8199982643127441,2.413404197735044,1739502641.4181466,1.8199982643127441,0.0,1739502641.4181483,1.8199982643127441,0.7523029380311894,1739502641.4181504,1.8199982643127441,6.253674769223807,1739502641.4181523,1.8199982643127441,1.6611012597038548 +1739502641.4382026,1.8399982452392578,1.5867888943064967,1739502641.4382062,1.8399982452392578,-0.03400556592972315,1739502641.4382105,1.8399982452392578,0.7334687923831379,1739502641.4382145,1.8399982452392578,6.212431688643482,1739502641.4382164,1.8399982452392578,-0.123,1739502641.438219,1.8399982452392578,-0.01923699255213611,1739502641.438221,1.8399982452392578,0.05233777000085461,1739502641.4382231,1.8399982452392578,0.018778714182049204,1739502641.4382248,1.8399982452392578,2.3974855865083176,1739502641.4382274,1.8399982452392578,0.0,1739502641.4382293,1.8399982452392578,0.6109781677791652,1739502641.4382312,1.8399982452392578,6.252635464781707,1739502641.4382336,1.8399982452392578,1.742343399069207 +1739502641.4583714,1.8599982261657715,1.5867888943064967,1739502641.4583755,1.8599982261657715,-0.03400556592972315,1739502641.4583802,1.8599982261657715,0.7334687923831379,1739502641.4583852,1.8599982261657715,6.212431688643482,1739502641.4583871,1.8599982261657715,-0.123,1739502641.4583895,1.8599982261657715,-0.01923699255213611,1739502641.4583917,1.8599982261657715,0.05233777000085461,1739502641.4583938,1.8599982261657715,0.018778714182049204,1739502641.4583957,1.8599982261657715,2.3974855865083176,1739502641.4583986,1.8599982261657715,0.0,1739502641.4584002,1.8599982261657715,0.6551421874391106,1739502641.4584026,1.8599982261657715,6.252635464781707,1739502641.4584045,1.8599982261657715,1.742343399069207 +1739502641.4784095,1.8799982070922852,1.5867888943064967,1739502641.478413,1.8799982070922852,-0.03400556592972315,1739502641.4784179,1.8799982070922852,0.7334687923831379,1739502641.478422,1.8799982070922852,6.212431688643482,1739502641.478424,1.8799982070922852,-0.123,1739502641.478427,1.8799982070922852,-0.01923699255213611,1739502641.478429,1.8799982070922852,0.05233777000085461,1739502641.4784312,1.8799982070922852,0.018778714182049204,1739502641.4784336,1.8799982070922852,2.3974855865083176,1739502641.478436,1.8799982070922852,0.0,1739502641.4784384,1.8799982070922852,0.6551421874391106,1739502641.4784408,1.8799982070922852,6.252635464781707,1739502641.4784427,1.8799982070922852,1.742343399069207 +1739502641.4980927,1.8999981880187988,1.5867888943064967,1739502641.4980965,1.8999981880187988,-0.03400556592972315,1739502641.498101,1.8999981880187988,0.7334687923831379,1739502641.498105,1.8999981880187988,6.212431688643482,1739502641.4981074,1.8999981880187988,-0.123,1739502641.49811,1.8999981880187988,-0.01923699255213611,1739502641.4981122,1.8999981880187988,0.05233777000085461,1739502641.4981143,1.8999981880187988,0.018778714182049204,1739502641.4981163,1.8999981880187988,2.3974855865083176,1739502641.4981186,1.8999981880187988,0.0,1739502641.4981208,1.8999981880187988,0.6551421874391106,1739502641.4981227,1.8999981880187988,6.252635464781707,1739502641.4981253,1.8999981880187988,1.742343399069207 +1739502641.5181863,1.9199981689453125,1.5867888943064967,1739502641.51819,1.9199981689453125,-0.03400556592972315,1739502641.5181944,1.9199981689453125,0.7334687923831379,1739502641.5181985,1.9199981689453125,6.212431688643482,1739502641.5182006,1.9199981689453125,-0.123,1739502641.5182028,1.9199981689453125,-0.01923699255213611,1739502641.5182052,1.9199981689453125,0.05233777000085461,1739502641.5182073,1.9199981689453125,0.018778714182049204,1739502641.518209,1.9199981689453125,2.3974855865083176,1739502641.5182118,1.9199981689453125,0.0,1739502641.518214,1.9199981689453125,0.6551421874391106,1739502641.518216,1.9199981689453125,6.252635464781707,1739502641.5182178,1.9199981689453125,1.742343399069207 +1739502641.5389984,1.9399981498718262,1.7819622468259055,1739502641.5390062,1.9399981498718262,-0.04005261744435895,1739502641.5390139,1.9399981498718262,1.0380001494086928,1739502641.5390227,1.9399981498718262,6.660508475842497,1739502641.5390272,1.9399981498718262,-0.125,1739502641.539034,1.9399981498718262,-0.01741067830035398,1739502641.5390394,1.9399981498718262,0.0684701826073158,1739502641.5390449,1.9399981498718262,0.022087285988851978,1739502641.5390503,1.9399981498718262,2.3667426151869067,1739502641.5390558,1.9399981498718262,0.0,1739502641.5390613,1.9399981498718262,0.5060209963558256,1739502641.5390668,1.9399981498718262,6.251741339254254,1739502641.5390723,1.9399981498718262,1.8141212160639495 +1739502641.558917,1.9599981307983398,1.7819622468259055,1739502641.5589225,1.9599981307983398,-0.04005261744435895,1739502641.5589294,1.9599981307983398,1.0380001494086928,1739502641.5589373,1.9599981307983398,6.660508475842497,1739502641.5589416,1.9599981307983398,-0.125,1739502641.5589473,1.9599981307983398,-0.01741067830035398,1739502641.5589786,1.9599981307983398,0.0684701826073158,1739502641.558984,1.9599981307983398,0.022087285988851978,1739502641.5589888,1.9599981307983398,2.3667426151869067,1739502641.5589943,1.9599981307983398,0.0,1739502641.5589993,1.9599981307983398,0.5526213991229572,1739502641.5590043,1.9599981307983398,6.251741339254254,1739502641.5590098,1.9599981307983398,1.8141212160639495 +1739502641.5780814,1.9799981117248535,1.7819622468259055,1739502641.5780857,1.9799981117248535,-0.04005261744435895,1739502641.5780914,1.9799981117248535,1.0380001494086928,1739502641.5780964,1.9799981117248535,6.660508475842497,1739502641.5780993,1.9799981117248535,-0.125,1739502641.578103,1.9799981117248535,-0.01741067830035398,1739502641.5781066,1.9799981117248535,0.0684701826073158,1739502641.5781102,1.9799981117248535,0.022087285988851978,1739502641.5781136,1.9799981117248535,2.3667426151869067,1739502641.5781171,1.9799981117248535,0.0,1739502641.5781205,1.9799981117248535,0.5526213991229572,1739502641.578124,1.9799981117248535,6.251741339254254,1739502641.5781274,1.9799981117248535,1.8141212160639495 +1739502641.5975454,1.9999980926513672,1.7819622468259055,1739502641.5975485,1.9999980926513672,-0.04005261744435895,1739502641.597553,1.9999980926513672,1.0380001494086928,1739502641.5975578,1.9999980926513672,6.660508475842497,1739502641.5975604,1.9999980926513672,-0.125,1739502641.597564,1.9999980926513672,-0.01741067830035398,1739502641.5975673,1.9999980926513672,0.0684701826073158,1739502641.5975704,1.9999980926513672,0.022087285988851978,1739502641.5975733,1.9999980926513672,2.3667426151869067,1739502641.5975773,1.9999980926513672,0.0,1739502641.597581,1.9999980926513672,0.5526213991229572,1739502641.5975838,1.9999980926513672,6.251741339254254,1739502641.5975869,1.9999980926513672,1.8141212160639495 +1739502641.618693,2.019998073577881,1.7819622468259055,1739502641.618697,2.019998073577881,-0.04005261744435895,1739502641.6187015,2.019998073577881,1.0380001494086928,1739502641.618707,2.019998073577881,6.660508475842497,1739502641.6187098,2.019998073577881,-0.125,1739502641.6187134,2.019998073577881,-0.01741067830035398,1739502641.6187167,2.019998073577881,0.0684701826073158,1739502641.6187198,2.019998073577881,0.022087285988851978,1739502641.6187232,2.019998073577881,2.3667426151869067,1739502641.6187265,2.019998073577881,0.0,1739502641.6187298,2.019998073577881,0.5526213991229572,1739502641.6187332,2.019998073577881,6.251741339254254,1739502641.6187363,2.019998073577881,1.8141212160639495 +1739502641.6379106,2.0399980545043945,1.7819622468259055,1739502641.6379144,2.0399980545043945,-0.04005261744435895,1739502641.6379192,2.0399980545043945,1.0380001494086928,1739502641.6379244,2.0399980545043945,6.660508475842497,1739502641.6379275,2.0399980545043945,-0.125,1739502641.637931,2.0399980545043945,-0.01741067830035398,1739502641.6379344,2.0399980545043945,0.0684701826073158,1739502641.6379375,2.0399980545043945,0.022087285988851978,1739502641.637941,2.0399980545043945,2.3667426151869067,1739502641.6379445,2.0399980545043945,0.0,1739502641.6379478,2.0399980545043945,0.5526213991229572,1739502641.6379514,2.0399980545043945,6.251741339254254,1739502641.6379552,2.0399980545043945,1.8141212160639495 +1739502641.657716,2.059998035430908,1.9843566375051767,1739502641.6577196,2.059998035430908,-0.04648733142190942,1739502641.6577244,2.059998035430908,1.0406312764875234,1739502641.6577296,2.059998035430908,6.782341344534461,1739502641.6577322,2.059998035430908,-0.12525532496540798,1739502641.6577358,2.059998035430908,-0.016415416707095287,1739502641.6577399,2.059998035430908,0.07556656657383842,1739502641.6577432,2.059998035430908,0.025202634533404333,1739502641.6577463,2.059998035430908,2.3533444311571627,1739502641.6577501,2.059998035430908,0.0,1739502641.6577532,2.059998035430908,0.4464403364567495,1739502641.6577566,2.059998035430908,6.251021714256675,1739502641.6577601,2.059998035430908,1.8737224908616685 +1739502641.6775732,2.079998016357422,1.9843566375051767,1739502641.6775773,2.079998016357422,-0.04648733142190942,1739502641.6775818,2.079998016357422,1.0406312764875234,1739502641.6775873,2.079998016357422,6.782341344534461,1739502641.6775904,2.079998016357422,-0.12525532496540798,1739502641.6775942,2.079998016357422,-0.016415416707095287,1739502641.677598,2.079998016357422,0.07556656657383842,1739502641.6776016,2.079998016357422,0.025202634533404333,1739502641.677605,2.079998016357422,2.3533444311571627,1739502641.6776085,2.079998016357422,0.0,1739502641.677612,2.079998016357422,0.4796219402954942,1739502641.6776154,2.079998016357422,6.251021714256675,1739502641.677619,2.079998016357422,1.8737224908616685 +1739502641.6978672,2.0999979972839355,1.9843566375051767,1739502641.6978714,2.0999979972839355,-0.04648733142190942,1739502641.697876,2.0999979972839355,1.0406312764875234,1739502641.697881,2.0999979972839355,6.782341344534461,1739502641.697884,2.0999979972839355,-0.12525532496540798,1739502641.6978884,2.0999979972839355,-0.016415416707095287,1739502641.6978915,2.0999979972839355,0.07556656657383842,1739502641.697895,2.0999979972839355,0.025202634533404333,1739502641.6978989,2.0999979972839355,2.3533444311571627,1739502641.6979024,2.0999979972839355,0.0,1739502641.6979058,2.0999979972839355,0.4796219402954942,1739502641.6979094,2.0999979972839355,6.251021714256675,1739502641.6979127,2.0999979972839355,1.8737224908616685 +1739502641.7175357,2.119997978210449,1.9843566375051767,1739502641.7175395,2.119997978210449,-0.04648733142190942,1739502641.7175446,2.119997978210449,1.0406312764875234,1739502641.71755,2.119997978210449,6.782341344534461,1739502641.717553,2.119997978210449,-0.12525532496540798,1739502641.717557,2.119997978210449,-0.016415416707095287,1739502641.717561,2.119997978210449,0.07556656657383842,1739502641.7175655,2.119997978210449,0.025202634533404333,1739502641.7175689,2.119997978210449,2.3533444311571627,1739502641.717573,2.119997978210449,0.0,1739502641.7175763,2.119997978210449,0.4796219402954942,1739502641.7175798,2.119997978210449,6.251021714256675,1739502641.7175834,2.119997978210449,1.8737224908616685 +1739502641.7386713,2.139997959136963,1.9843566375051767,1739502641.7386756,2.139997959136963,-0.04648733142190942,1739502641.7386806,2.139997959136963,1.0406312764875234,1739502641.7386856,2.139997959136963,6.782341344534461,1739502641.7386885,2.139997959136963,-0.12525532496540798,1739502641.7386923,2.139997959136963,-0.016415416707095287,1739502641.7386956,2.139997959136963,0.07556656657383842,1739502641.7386987,2.139997959136963,0.025202634533404333,1739502641.738702,2.139997959136963,2.3533444311571627,1739502641.7387056,2.139997959136963,0.0,1739502641.738709,2.139997959136963,0.4796219402954942,1739502641.7387125,2.139997959136963,6.251021714256675,1739502641.7387161,2.139997959136963,1.8737224908616685 +1739502641.7579775,2.1599979400634766,2.1929984760120886,1739502641.757982,2.1599979400634766,-0.0532618823806601,1739502641.7579873,2.1599979400634766,1.3758485241070102,1739502641.7579925,2.1599979400634766,7.222625225854546,1739502641.7579954,2.1599979400634766,-0.1282141111470747,1739502641.7579992,2.1599979400634766,-0.014901042347882218,1739502641.758003,2.1599979400634766,0.09000926096939052,1739502641.7580063,2.1599979400634766,0.027319230460840747,1739502641.7580097,2.1599979400634766,2.326310004355574,1739502641.7580132,2.1599979400634766,0.0,1739502641.7580168,2.1599979400634766,0.36387586368069386,1739502641.7580204,2.1599979400634766,6.250389483321406,1739502641.7580237,2.1599979400634766,1.926263468017414 +1739502641.7775526,2.1799979209899902,2.1929984760120886,1739502641.7775824,2.1799979209899902,-0.0532618823806601,1739502641.777594,2.1799979209899902,1.3758485241070102,1739502641.7776058,2.1799979209899902,7.222625225854546,1739502641.7776098,2.1799979209899902,-0.1282141111470747,1739502641.7776148,2.1799979209899902,-0.014901042347882218,1739502641.777641,2.1799979209899902,0.09000926096939052,1739502641.7776456,2.1799979209899902,0.027319230460840747,1739502641.7776544,2.1799979209899902,2.326310004355574,1739502641.77766,2.1799979209899902,0.0,1739502641.7776635,2.1799979209899902,0.40004653633816,1739502641.7776673,2.1799979209899902,6.250389483321406,1739502641.7776716,2.1799979209899902,1.926263468017414 +1739502641.7981205,2.199997901916504,2.1929984760120886,1739502641.7981248,2.199997901916504,-0.0532618823806601,1739502641.7981296,2.199997901916504,1.3758485241070102,1739502641.7981353,2.199997901916504,7.222625225854546,1739502641.7981384,2.199997901916504,-0.1282141111470747,1739502641.7981424,2.199997901916504,-0.014901042347882218,1739502641.7981462,2.199997901916504,0.09000926096939052,1739502641.7981503,2.199997901916504,0.027319230460840747,1739502641.7981544,2.199997901916504,2.326310004355574,1739502641.7981584,2.199997901916504,0.0,1739502641.798162,2.199997901916504,0.40004653633816,1739502641.7981658,2.199997901916504,6.250389483321406,1739502641.7981694,2.199997901916504,1.926263468017414 +1739502641.8173776,2.2199978828430176,2.1929984760120886,1739502641.8173804,2.2199978828430176,-0.0532618823806601,1739502641.8173838,2.2199978828430176,1.3758485241070102,1739502641.8173862,2.2199978828430176,7.222625225854546,1739502641.8173878,2.2199978828430176,-0.1282141111470747,1739502641.8173892,2.2199978828430176,-0.014901042347882218,1739502641.817391,2.2199978828430176,0.09000926096939052,1739502641.817392,2.2199978828430176,0.027319230460840747,1739502641.8173938,2.2199978828430176,2.326310004355574,1739502641.8173952,2.2199978828430176,0.0,1739502641.8173966,2.2199978828430176,0.40004653633816,1739502641.817398,2.2199978828430176,6.250389483321406,1739502641.8173995,2.2199978828430176,1.926263468017414 +1739502641.8382213,2.2399978637695312,2.1929984760120886,1739502641.8382258,2.2399978637695312,-0.0532618823806601,1739502641.8382308,2.2399978637695312,1.3758485241070102,1739502641.838236,2.2399978637695312,7.222625225854546,1739502641.8382394,2.2399978637695312,-0.1282141111470747,1739502641.8382435,2.2399978637695312,-0.014901042347882218,1739502641.8382468,2.2399978637695312,0.09000926096939052,1739502641.8382504,2.2399978637695312,0.027319230460840747,1739502641.8382537,2.2399978637695312,2.326310004355574,1739502641.8382576,2.2399978637695312,0.0,1739502641.838261,2.2399978637695312,0.40004653633816,1739502641.8382645,2.2399978637695312,6.250389483321406,1739502641.838268,2.2399978637695312,1.926263468017414 +1739502641.858709,2.259997844696045,2.1929984760120886,1739502641.8587132,2.259997844696045,-0.0532618823806601,1739502641.8587186,2.259997844696045,1.3758485241070102,1739502641.858724,2.259997844696045,7.222625225854546,1739502641.858727,2.259997844696045,-0.1282141111470747,1739502641.8587356,2.259997844696045,-0.014901042347882218,1739502641.858739,2.259997844696045,0.09000926096939052,1739502641.8587425,2.259997844696045,0.027319230460840747,1739502641.8587458,2.259997844696045,2.326310004355574,1739502641.8587496,2.259997844696045,0.0,1739502641.8587532,2.259997844696045,0.40004653633816,1739502641.858757,2.259997844696045,6.250389483321406,1739502641.8587604,2.259997844696045,1.926263468017414 +1739502641.87882,2.2799978256225586,2.406896542279541,1739502641.878824,2.2799978256225586,-0.060333302990514426,1739502641.8788288,2.2799978256225586,1.6398371053586764,1739502641.878834,2.2799978256225586,7.572790814464956,1739502641.8788366,2.2799978256225586,-0.13,1739502641.8788407,2.2799978256225586,-0.013485075456160378,1739502641.878844,2.2799978256225586,0.10257380497732795,1739502641.8788471,2.2799978256225586,0.029513021271564646,1739502641.8788507,2.2799978256225586,2.303043911843407,1739502641.8788548,2.2799978256225586,0.0,1739502641.878858,2.2799978256225586,0.3035243016083874,1739502641.8788617,2.2799978256225586,6.2498447695709025,1739502641.8788655,2.2799978256225586,1.969356392105419 +1739502641.8977647,2.2999978065490723,2.406896542279541,1739502641.8977695,2.2999978065490723,-0.060333302990514426,1739502641.897775,2.2999978065490723,1.6398371053586764,1739502641.8977807,2.2999978065490723,7.572790814464956,1739502641.897784,2.2999978065490723,-0.13,1739502641.8977885,2.2999978065490723,-0.013485075456160378,1739502641.897792,2.2999978065490723,0.10257380497732795,1739502641.897796,2.2999978065490723,0.029513021271564646,1739502641.8977995,2.2999978065490723,2.303043911843407,1739502641.8978035,2.2999978065490723,0.0,1739502641.8978074,2.2999978065490723,0.33368751973798827,1739502641.8978114,2.2999978065490723,6.2498447695709025,1739502641.8978157,2.2999978065490723,1.969356392105419 +1739502641.9173145,2.319997787475586,2.406896542279541,1739502641.917317,2.319997787475586,-0.060333302990514426,1739502641.91732,2.319997787475586,1.6398371053586764,1739502641.9173224,2.319997787475586,7.572790814464956,1739502641.9173238,2.319997787475586,-0.13,1739502641.9173253,2.319997787475586,-0.013485075456160378,1739502641.917327,2.319997787475586,0.10257380497732795,1739502641.9173281,2.319997787475586,0.029513021271564646,1739502641.9173293,2.319997787475586,2.303043911843407,1739502641.917331,2.319997787475586,0.0,1739502641.9173322,2.319997787475586,0.33368751973798827,1739502641.9173336,2.319997787475586,6.2498447695709025,1739502641.917335,2.319997787475586,1.969356392105419 +1739502641.9376972,2.3399977684020996,2.406896542279541,1739502641.9377,2.3399977684020996,-0.060333302990514426,1739502641.9377038,2.3399977684020996,1.6398371053586764,1739502641.9377072,2.3399977684020996,7.572790814464956,1739502641.937709,2.3399977684020996,-0.13,1739502641.9377115,2.3399977684020996,-0.013485075456160378,1739502641.9377131,2.3399977684020996,0.10257380497732795,1739502641.9377146,2.3399977684020996,0.029513021271564646,1739502641.9377162,2.3399977684020996,2.303043911843407,1739502641.9377182,2.3399977684020996,0.0,1739502641.93772,2.3399977684020996,0.33368751973798827,1739502641.937722,2.3399977684020996,6.2498447695709025,1739502641.9377236,2.3399977684020996,1.969356392105419 +1739502641.9578269,2.3599977493286133,2.406896542279541,1739502641.9578297,2.3599977493286133,-0.060333302990514426,1739502641.9578333,2.3599977493286133,1.6398371053586764,1739502641.9578369,2.3599977493286133,7.572790814464956,1739502641.9578385,2.3599977493286133,-0.13,1739502641.957841,2.3599977493286133,-0.013485075456160378,1739502641.9578424,2.3599977493286133,0.10257380497732795,1739502641.9578443,2.3599977493286133,0.029513021271564646,1739502641.957846,2.3599977493286133,2.303043911843407,1739502641.957848,2.3599977493286133,0.0,1739502641.9578497,2.3599977493286133,0.33368751973798827,1739502641.9578524,2.3599977493286133,6.2498447695709025,1739502641.9578543,2.3599977493286133,1.969356392105419 +1739502641.9794347,2.379997730255127,2.625244380468361,1739502641.9794402,2.379997730255127,-0.06766007926476458,1739502641.9794471,2.379997730255127,2.2289482181887315,1739502641.9794538,2.379997730255127,8.235009545887785,1739502641.979456,2.379997730255127,-0.134,1739502641.9794593,2.379997730255127,-0.011825241611083158,1739502641.9794621,2.379997730255127,0.12301280528761413,1739502641.9794657,2.379997730255127,0.03001559498541677,1739502641.9794686,2.379997730255127,2.265692581391648,1739502641.9794724,2.379997730255127,0.0,1739502641.9794753,2.379997730255127,0.22617634161584885,1739502641.9794796,2.379997730255127,6.249431507155699,1739502641.979483,2.379997730255127,2.005918974584547 +1739502641.999192,2.3999977111816406,2.625244380468361,1739502641.9991972,2.3999977111816406,-0.06766007926476458,1739502641.999204,2.3999977111816406,2.2289482181887315,1739502641.999209,2.3999977111816406,8.235009545887785,1739502641.9992115,2.3999977111816406,-0.134,1739502641.9992151,2.3999977111816406,-0.011825241611083158,1739502641.999219,2.3999977111816406,0.12301280528761413,1739502641.9992218,2.3999977111816406,0.03001559498541677,1739502641.9992247,2.3999977111816406,2.265692581391648,1739502641.9992273,2.3999977111816406,0.0,1739502641.9992309,2.3999977111816406,0.25977360680710104,1739502641.9992354,2.3999977111816406,6.249431507155699,1739502641.9992383,2.3999977111816406,2.005918974584547 +1739502642.018279,2.4199976921081543,2.625244380468361,1739502642.0182836,2.4199976921081543,-0.06766007926476458,1739502642.0182881,2.4199976921081543,2.2289482181887315,1739502642.0182922,2.4199976921081543,8.235009545887785,1739502642.018294,2.4199976921081543,-0.134,1739502642.0182965,2.4199976921081543,-0.011825241611083158,1739502642.0182984,2.4199976921081543,0.12301280528761413,1739502642.0183008,2.4199976921081543,0.03001559498541677,1739502642.0183024,2.4199976921081543,2.265692581391648,1739502642.018305,2.4199976921081543,0.0,1739502642.018307,2.4199976921081543,0.25977360680710104,1739502642.018309,2.4199976921081543,6.249431507155699,1739502642.018311,2.4199976921081543,2.005918974584547 +1739502642.038551,2.439997673034668,2.625244380468361,1739502642.0385575,2.439997673034668,-0.06766007926476458,1739502642.0385656,2.439997673034668,2.2289482181887315,1739502642.0385728,2.439997673034668,8.235009545887785,1739502642.038577,2.439997673034668,-0.134,1739502642.0385826,2.439997673034668,-0.011825241611083158,1739502642.0385878,2.439997673034668,0.12301280528761413,1739502642.0385933,2.439997673034668,0.03001559498541677,1739502642.038598,2.439997673034668,2.265692581391648,1739502642.0386035,2.439997673034668,0.0,1739502642.0386083,2.439997673034668,0.25977360680710104,1739502642.0386138,2.439997673034668,6.249431507155699,1739502642.0386186,2.439997673034668,2.005918974584547 +1739502642.059271,2.4599976539611816,2.625244380468361,1739502642.0592763,2.4599976539611816,-0.06766007926476458,1739502642.0592847,2.4599976539611816,2.2289482181887315,1739502642.0592902,2.4599976539611816,8.235009545887785,1739502642.0592933,2.4599976539611816,-0.134,1739502642.0592973,2.4599976539611816,-0.011825241611083158,1739502642.0593002,2.4599976539611816,0.12301280528761413,1739502642.0593038,2.4599976539611816,0.03001559498541677,1739502642.0593061,2.4599976539611816,2.265692581391648,1739502642.0593102,2.4599976539611816,0.0,1739502642.0593128,2.4599976539611816,0.25977360680710104,1739502642.059316,2.4599976539611816,6.249431507155699,1739502642.0593197,2.4599976539611816,2.005918974584547 +1739502642.0791233,2.4799976348876953,2.625244380468361,1739502642.0791287,2.4799976348876953,-0.06766007926476458,1739502642.079136,2.4799976348876953,2.2289482181887315,1739502642.0791438,2.4799976348876953,8.235009545887785,1739502642.0791478,2.4799976348876953,-0.134,1739502642.0791533,2.4799976348876953,-0.011825241611083158,1739502642.079158,2.4799976348876953,0.12301280528761413,1739502642.0791626,2.4799976348876953,0.03001559498541677,1739502642.0791671,2.4799976348876953,2.265692581391648,1739502642.0791724,2.4799976348876953,0.0,1739502642.0791774,2.4799976348876953,0.25977360680710104,1739502642.0791824,2.4799976348876953,6.249431507155699,1739502642.0791872,2.4799976348876953,2.005918974584547 +1739502642.0986555,2.499997615814209,2.8471290213236937,1739502642.098661,2.499997615814209,-0.07519051146022626,1739502642.098666,2.499997615814209,2.6679107539493265,1739502642.0986717,2.499997615814209,8.729524158516725,1739502642.0986745,2.499997615814209,-0.13576909583506344,1739502642.0986779,2.499997615814209,-0.010297921433491425,1739502642.0986805,2.499997615814209,0.1401870764524467,1739502642.098685,2.499997615814209,0.031109940932051987,1739502642.0986893,2.499997615814209,2.2347761595251194,1739502642.098693,2.499997615814209,0.0,1739502642.0986955,2.499997615814209,0.17439662854238774,1739502642.0986981,2.499997615814209,6.249054761261585,1739502642.0987008,2.499997615814209,2.0336992077820257 +1739502642.118117,2.5199975967407227,2.8471290213236937,1739502642.118126,2.5199975967407227,-0.07519051146022626,1739502642.1181343,2.5199975967407227,2.6679107539493265,1739502642.1181388,2.5199975967407227,8.729524158516725,1739502642.1181407,2.5199975967407227,-0.13576909583506344,1739502642.1181438,2.5199975967407227,-0.010297921433491425,1739502642.1181457,2.5199975967407227,0.1401870764524467,1739502642.1181476,2.5199975967407227,0.031109940932051987,1739502642.1181493,2.5199975967407227,2.2347761595251194,1739502642.118152,2.5199975967407227,0.0,1739502642.1181538,2.5199975967407227,0.2010769517430937,1739502642.118156,2.5199975967407227,6.249054761261585,1739502642.118158,2.5199975967407227,2.0336992077820257 +1739502642.138277,2.5399975776672363,2.8471290213236937,1739502642.1382828,2.5399975776672363,-0.07519051146022626,1739502642.1382916,2.5399975776672363,2.6679107539493265,1739502642.1383016,2.5399975776672363,8.729524158516725,1739502642.138306,2.5399975776672363,-0.13576909583506344,1739502642.1383135,2.5399975776672363,-0.010297921433491425,1739502642.1383216,2.5399975776672363,0.1401870764524467,1739502642.1383276,2.5399975776672363,0.031109940932051987,1739502642.1383338,2.5399975776672363,2.2347761595251194,1739502642.1383388,2.5399975776672363,0.0,1739502642.138346,2.5399975776672363,0.2010769517430937,1739502642.1383536,2.5399975776672363,6.249054761261585,1739502642.1383593,2.5399975776672363,2.0336992077820257 +1739502642.1590302,2.55999755859375,2.8471290213236937,1739502642.159036,2.55999755859375,-0.07519051146022626,1739502642.1590426,2.55999755859375,2.6679107539493265,1739502642.1590486,2.55999755859375,8.729524158516725,1739502642.1590512,2.55999755859375,-0.13576909583506344,1739502642.1590555,2.55999755859375,-0.010297921433491425,1739502642.1590586,2.55999755859375,0.1401870764524467,1739502642.159062,2.55999755859375,0.031109940932051987,1739502642.1590645,2.55999755859375,2.2347761595251194,1739502642.1590703,2.55999755859375,0.0,1739502642.1590755,2.55999755859375,0.2010769517430937,1739502642.1590786,2.55999755859375,6.249054761261585,1739502642.1590817,2.55999755859375,2.0336992077820257 +1739502642.1800742,2.5799975395202637,2.8471290213236937,1739502642.180083,2.5799975395202637,-0.07519051146022626,1739502642.1800938,2.5799975395202637,2.6679107539493265,1739502642.1801045,2.5799975395202637,8.729524158516725,1739502642.1801105,2.5799975395202637,-0.13576909583506344,1739502642.1801178,2.5799975395202637,-0.010297921433491425,1739502642.1801217,2.5799975395202637,0.1401870764524467,1739502642.180124,2.5799975395202637,0.031109940932051987,1739502642.1801264,2.5799975395202637,2.2347761595251194,1739502642.1801288,2.5799975395202637,0.0,1739502642.180131,2.5799975395202637,0.2010769517430937,1739502642.1801333,2.5799975395202637,6.249054761261585,1739502642.1801357,2.5799975395202637,2.0336992077820257 +1739502642.19931,2.5999975204467773,3.071817351510738,1739502642.199316,2.5999975204467773,-0.08290082304367452,1739502642.199323,2.5999975204467773,2.5949566058880973,1739502642.1993299,2.5999975204467773,8.700662446149138,1739502642.1993332,2.5999975204467773,-0.13549681552970885,1739502642.1993377,2.5999975204467773,-0.009343739426761486,1739502642.1993413,2.5999975204467773,0.14163297347471748,1739502642.1993449,2.5999975204467773,0.03432654775068447,1739502642.1993484,2.5999975204467773,2.2321926490536197,1739502642.1993527,2.5999975204467773,0.0,1739502642.199357,2.5999975204467773,0.1652528157400034,1739502642.199361,2.5999975204467773,6.248678015367473,1739502642.199365,2.5999975204467773,2.055744783472604 +1739502642.2186303,2.619997501373291,3.071817351510738,1739502642.2186363,2.619997501373291,-0.08290082304367452,1739502642.2186437,2.619997501373291,2.5949566058880973,1739502642.2186525,2.619997501373291,8.700662446149138,1739502642.2186568,2.619997501373291,-0.13549681552970885,1739502642.2186627,2.619997501373291,-0.009343739426761486,1739502642.218668,2.619997501373291,0.14163297347471748,1739502642.2186732,2.619997501373291,0.03432654775068447,1739502642.2186785,2.619997501373291,2.2321926490536197,1739502642.2186842,2.619997501373291,0.0,1739502642.2186892,2.619997501373291,0.17644786558101577,1739502642.218695,2.619997501373291,6.248678015367473,1739502642.2187006,2.619997501373291,2.055744783472604 +1739502642.2381313,2.6399974822998047,3.071817351510738,1739502642.2381356,2.6399974822998047,-0.08290082304367452,1739502642.2381423,2.6399974822998047,2.5949566058880973,1739502642.2381477,2.6399974822998047,8.700662446149138,1739502642.2381496,2.6399974822998047,-0.13549681552970885,1739502642.2381525,2.6399974822998047,-0.009343739426761486,1739502642.2381546,2.6399974822998047,0.14163297347471748,1739502642.2381573,2.6399974822998047,0.03432654775068447,1739502642.2381594,2.6399974822998047,2.2321926490536197,1739502642.2381618,2.6399974822998047,0.0,1739502642.238164,2.6399974822998047,0.17644786558101577,1739502642.2381666,2.6399974822998047,6.248678015367473,1739502642.2381692,2.6399974822998047,2.055744783472604 +1739502642.257706,2.6599974632263184,3.071817351510738,1739502642.25771,2.6599974632263184,-0.08290082304367452,1739502642.2577152,2.6599974632263184,2.5949566058880973,1739502642.2577205,2.6599974632263184,8.700662446149138,1739502642.2577224,2.6599974632263184,-0.13549681552970885,1739502642.2577271,2.6599974632263184,-0.009343739426761486,1739502642.257732,2.6599974632263184,0.14163297347471748,1739502642.2577357,2.6599974632263184,0.03432654775068447,1739502642.2577405,2.6599974632263184,2.2321926490536197,1739502642.2577438,2.6599974632263184,0.0,1739502642.257749,2.6599974632263184,0.17644786558101577,1739502642.2577517,2.6599974632263184,6.248678015367473,1739502642.2577538,2.6599974632263184,2.055744783472604 +1739502642.2774138,2.679997444152832,3.071817351510738,1739502642.2774165,2.679997444152832,-0.08290082304367452,1739502642.2774198,2.679997444152832,2.5949566058880973,1739502642.2774231,2.679997444152832,8.700662446149138,1739502642.2774246,2.679997444152832,-0.13549681552970885,1739502642.2774265,2.679997444152832,-0.009343739426761486,1739502642.2774282,2.679997444152832,0.14163297347471748,1739502642.2774298,2.679997444152832,0.03432654775068447,1739502642.2774312,2.679997444152832,2.2321926490536197,1739502642.2774332,2.679997444152832,0.0,1739502642.2774346,2.679997444152832,0.17644786558101577,1739502642.2774365,2.679997444152832,6.248678015367473,1739502642.2774382,2.679997444152832,2.055744783472604 +1739502642.2975032,2.6999974250793457,3.071817351510738,1739502642.297508,2.6999974250793457,-0.08290082304367452,1739502642.297514,2.6999974250793457,2.5949566058880973,1739502642.2975209,2.6999974250793457,8.700662446149138,1739502642.2975247,2.6999974250793457,-0.13549681552970885,1739502642.2975297,2.6999974250793457,-0.009343739426761486,1739502642.2975345,2.6999974250793457,0.14163297347471748,1739502642.2975388,2.6999974250793457,0.03432654775068447,1739502642.297543,2.6999974250793457,2.2321926490536197,1739502642.2975478,2.6999974250793457,0.0,1739502642.2975523,2.6999974250793457,0.17644786558101577,1739502642.2975566,2.6999974250793457,6.248678015367473,1739502642.2975612,2.6999974250793457,2.055744783472604 +1739502642.3179634,2.7199974060058594,3.298759796063872,1739502642.317969,2.7199974060058594,-0.09076179914124971,1739502642.317974,2.7199974060058594,2.6228862485203286,1739502642.3179812,2.7199974060058594,8.766787710735594,1739502642.3179848,2.7199974060058594,-0.136,1739502642.3179886,2.7199974060058594,-0.008273031791304127,1739502642.3179936,2.7199974060058594,0.1447369313893771,1739502642.3179982,2.7199974060058594,0.03717296326576365,1739502642.318,2.7199974060058594,2.226656619707051,1739502642.3180022,2.7199974060058594,0.0,1739502642.3180053,2.7199974060058594,0.14061508827931524,1739502642.31801,2.7199974060058594,6.248440412834193,1739502642.318014,2.7199974060058594,2.0748437811791374 +1739502642.338179,2.739997386932373,3.298759796063872,1739502642.3381834,2.739997386932373,-0.09076179914124971,1739502642.3381898,2.739997386932373,2.6228862485203286,1739502642.3381965,2.739997386932373,8.766787710735594,1739502642.3381999,2.739997386932373,-0.136,1739502642.3382044,2.739997386932373,-0.008273031791304127,1739502642.3382082,2.739997386932373,0.1447369313893771,1739502642.338212,2.739997386932373,0.03717296326576365,1739502642.3382163,2.739997386932373,2.226656619707051,1739502642.3382204,2.739997386932373,0.0,1739502642.3382246,2.739997386932373,0.15181283852791383,1739502642.3382287,2.739997386932373,6.248440412834193,1739502642.3382328,2.739997386932373,2.0748437811791374 +1739502642.3583665,2.7599973678588867,3.298759796063872,1739502642.3583727,2.7599973678588867,-0.09076179914124971,1739502642.3583791,2.7599973678588867,2.6228862485203286,1739502642.3583858,2.7599973678588867,8.766787710735594,1739502642.3583908,2.7599973678588867,-0.136,1739502642.358396,2.7599973678588867,-0.008273031791304127,1739502642.3584003,2.7599973678588867,0.1447369313893771,1739502642.3584042,2.7599973678588867,0.03717296326576365,1739502642.358408,2.7599973678588867,2.226656619707051,1739502642.3584123,2.7599973678588867,0.0,1739502642.3584163,2.7599973678588867,0.15181283852791383,1739502642.3584201,2.7599973678588867,6.248440412834193,1739502642.3584244,2.7599973678588867,2.0748437811791374 +1739502642.378401,2.7799973487854004,3.298759796063872,1739502642.3784068,2.7799973487854004,-0.09076179914124971,1739502642.3784125,2.7799973487854004,2.6228862485203286,1739502642.3784187,2.7799973487854004,8.766787710735594,1739502642.378422,2.7799973487854004,-0.136,1739502642.3784263,2.7799973487854004,-0.008273031791304127,1739502642.3784304,2.7799973487854004,0.1447369313893771,1739502642.3784344,2.7799973487854004,0.03717296326576365,1739502642.3784382,2.7799973487854004,2.226656619707051,1739502642.3784428,2.7799973487854004,0.0,1739502642.3784468,2.7799973487854004,0.15181283852791383,1739502642.378451,2.7799973487854004,6.248440412834193,1739502642.3784554,2.7799973487854004,2.0748437811791374 +1739502642.3974247,2.799997329711914,3.298759796063872,1739502642.397427,2.799997329711914,-0.09076179914124971,1739502642.3974304,2.799997329711914,2.6228862485203286,1739502642.3974338,2.799997329711914,8.766787710735594,1739502642.3974354,2.799997329711914,-0.136,1739502642.3974373,2.799997329711914,-0.008273031791304127,1739502642.397439,2.799997329711914,0.1447369313893771,1739502642.3974404,2.799997329711914,0.03717296326576365,1739502642.397442,2.799997329711914,2.226656619707051,1739502642.3974438,2.799997329711914,0.0,1739502642.3974454,2.799997329711914,0.15181283852791383,1739502642.3974469,2.799997329711914,6.248440412834193,1739502642.3974488,2.799997329711914,2.0748437811791374 +1739502642.4178526,2.8199973106384277,3.527690424979127,1739502642.417857,2.8199973106384277,-0.09873186824256219,1739502642.4178624,2.8199973106384277,3.2871393388811057,1739502642.4178686,2.8199973106384277,9.464286082569544,1739502642.4178717,2.8199973106384277,-0.1386322785423106,1739502642.4178762,2.8199973106384277,-0.006720991593349242,1739502642.4178803,2.8199973106384277,0.16688819913508746,1739502642.417884,2.8199973106384277,0.03636394730018068,1739502642.417888,2.8199973106384277,2.1875455733544604,1739502642.417892,2.8199973106384277,0.0,1739502642.417896,2.8199973106384277,0.07073821198376691,1739502642.4178998,2.8199973106384277,6.248349478909339,1739502642.417904,2.8199973106384277,2.091471523964178 +1739502642.4381104,2.8399972915649414,3.527690424979127,1739502642.4381144,2.8399972915649414,-0.09873186824256219,1739502642.4381182,2.8399972915649414,3.2871393388811057,1739502642.4381218,2.8399972915649414,9.464286082569544,1739502642.4381235,2.8399972915649414,-0.1386322785423106,1739502642.4381258,2.8399972915649414,-0.006720991593349242,1739502642.4381275,2.8399972915649414,0.16688819913508746,1739502642.4381292,2.8399972915649414,0.03636394730018068,1739502642.4381306,2.8399972915649414,2.1875455733544604,1739502642.4381328,2.8399972915649414,0.0,1739502642.4381342,2.8399972915649414,0.0960740493902823,1739502642.438136,2.8399972915649414,6.248349478909339,1739502642.4381375,2.8399972915649414,2.091471523964178 +1739502642.4577942,2.859997272491455,3.527690424979127,1739502642.4577973,2.859997272491455,-0.09873186824256219,1739502642.4578006,2.859997272491455,3.2871393388811057,1739502642.4578037,2.859997272491455,9.464286082569544,1739502642.4578054,2.859997272491455,-0.1386322785423106,1739502642.4578075,2.859997272491455,-0.006720991593349242,1739502642.4578092,2.859997272491455,0.16688819913508746,1739502642.4578106,2.859997272491455,0.03636394730018068,1739502642.457812,2.859997272491455,2.1875455733544604,1739502642.4578137,2.859997272491455,0.0,1739502642.4578156,2.859997272491455,0.0960740493902823,1739502642.4578176,2.859997272491455,6.248349478909339,1739502642.4578195,2.859997272491455,2.091471523964178 +1739502642.4775162,2.8799972534179688,3.527690424979127,1739502642.4775188,2.8799972534179688,-0.09873186824256219,1739502642.477522,2.8799972534179688,3.2871393388811057,1739502642.477525,2.8799972534179688,9.464286082569544,1739502642.4775264,2.8799972534179688,-0.1386322785423106,1739502642.4775286,2.8799972534179688,-0.006720991593349242,1739502642.47753,2.8799972534179688,0.16688819913508746,1739502642.4775317,2.8799972534179688,0.03636394730018068,1739502642.4775329,2.8799972534179688,2.1875455733544604,1739502642.4775352,2.8799972534179688,0.0,1739502642.4775367,2.8799972534179688,0.0960740493902823,1739502642.4775386,2.8799972534179688,6.248349478909339,1739502642.47754,2.8799972534179688,2.091471523964178 +1739502642.4977021,2.8999972343444824,3.527690424979127,1739502642.497705,2.8999972343444824,-0.09873186824256219,1739502642.4977086,2.8999972343444824,3.2871393388811057,1739502642.4977117,2.8999972343444824,9.464286082569544,1739502642.497713,2.8999972343444824,-0.1386322785423106,1739502642.497715,2.8999972343444824,-0.006720991593349242,1739502642.4977167,2.8999972343444824,0.16688819913508746,1739502642.4977183,2.8999972343444824,0.03636394730018068,1739502642.4977198,2.8999972343444824,2.1875455733544604,1739502642.4977217,2.8999972343444824,0.0,1739502642.497723,2.8999972343444824,0.0960740493902823,1739502642.4977248,2.8999972343444824,6.248349478909339,1739502642.4977264,2.8999972343444824,2.091471523964178 +1739502642.5174901,2.919997215270996,3.527690424979127,1739502642.5174928,2.919997215270996,-0.09873186824256219,1739502642.5174966,2.919997215270996,3.2871393388811057,1739502642.5175,2.919997215270996,9.464286082569544,1739502642.5175014,2.919997215270996,-0.1386322785423106,1739502642.517504,2.919997215270996,-0.006720991593349242,1739502642.517506,2.919997215270996,0.16688819913508746,1739502642.5175073,2.919997215270996,0.03636394730018068,1739502642.5175087,2.919997215270996,2.1875455733544604,1739502642.517511,2.919997215270996,0.0,1739502642.5175128,2.919997215270996,0.0960740493902823,1739502642.5175142,2.919997215270996,6.248349478909339,1739502642.5175164,2.919997215270996,2.091471523964178 +1739502642.5377643,2.9399971961975098,3.758091227316167,1739502642.5377698,2.9399971961975098,-0.10676701352363693,1739502642.537775,2.9399971961975098,3.3074306797773274,1739502642.5377784,2.9399971961975098,9.504610518949184,1739502642.53778,2.9399971961975098,-0.13900560109127694,1739502642.5377817,2.9399971961975098,-0.005610048051648453,1739502642.5377839,2.9399971961975098,0.1682369104101732,1739502642.5377853,2.9399971961975098,0.03912320962592891,1739502642.5377867,2.9399971961975098,2.185186552334981,1739502642.5377884,2.9399971961975098,0.0,1739502642.53779,2.9399971961975098,0.07807195995790508,1739502642.5377915,2.9399971961975098,6.248295221020758,1739502642.5377934,2.9399971961975098,2.1014889357409903 +1739502642.5577612,2.9599971771240234,3.758091227316167,1739502642.5577638,2.9599971771240234,-0.10676701352363693,1739502642.5577674,2.9599971771240234,3.3074306797773274,1739502642.5577705,2.9599971771240234,9.504610518949184,1739502642.557772,2.9599971771240234,-0.13900560109127694,1739502642.557774,2.9599971771240234,-0.005610048051648453,1739502642.5577755,2.9599971771240234,0.1682369104101732,1739502642.5577772,2.9599971771240234,0.03912320962592891,1739502642.5577784,2.9599971771240234,2.185186552334981,1739502642.5577805,2.9599971771240234,0.0,1739502642.557782,2.9599971771240234,0.08369761659399089,1739502642.5577838,2.9599971771240234,6.248295221020758,1739502642.5577853,2.9599971771240234,2.1014889357409903 +1739502642.5777705,2.979997158050537,3.758091227316167,1739502642.5777736,2.979997158050537,-0.10676701352363693,1739502642.5777798,2.979997158050537,3.3074306797773274,1739502642.5777874,2.979997158050537,9.504610518949184,1739502642.5777917,2.979997158050537,-0.13900560109127694,1739502642.577796,2.979997158050537,-0.005610048051648453,1739502642.5777977,2.979997158050537,0.1682369104101732,1739502642.5777993,2.979997158050537,0.03912320962592891,1739502642.577801,2.979997158050537,2.185186552334981,1739502642.5778024,2.979997158050537,0.0,1739502642.577804,2.979997158050537,0.08369761659399089,1739502642.5778058,2.979997158050537,6.248295221020758,1739502642.5778074,2.979997158050537,2.1014889357409903 +1739502642.597618,2.999997138977051,3.758091227316167,1739502642.597621,2.999997138977051,-0.10676701352363693,1739502642.597624,2.999997138977051,3.3074306797773274,1739502642.5976272,2.999997138977051,9.504610518949184,1739502642.5976286,2.999997138977051,-0.13900560109127694,1739502642.597631,2.999997138977051,-0.005610048051648453,1739502642.5976324,2.999997138977051,0.1682369104101732,1739502642.597636,2.999997138977051,0.03912320962592891,1739502642.597641,2.999997138977051,2.185186552334981,1739502642.597646,2.999997138977051,0.0,1739502642.597651,2.999997138977051,0.08369761659399089,1739502642.5976553,2.999997138977051,6.248295221020758,1739502642.5976567,2.999997138977051,2.1014889357409903 +1739502642.6177452,3.0199971199035645,3.758091227316167,1739502642.6177478,3.0199971199035645,-0.10676701352363693,1739502642.6177511,3.0199971199035645,3.3074306797773274,1739502642.6177542,3.0199971199035645,9.504610518949184,1739502642.6177557,3.0199971199035645,-0.13900560109127694,1739502642.6177578,3.0199971199035645,-0.005610048051648453,1739502642.6177592,3.0199971199035645,0.1682369104101732,1739502642.6177611,3.0199971199035645,0.03912320962592891,1739502642.6177626,3.0199971199035645,2.185186552334981,1739502642.6177642,3.0199971199035645,0.0,1739502642.617766,3.0199971199035645,0.08369761659399089,1739502642.6177673,3.0199971199035645,6.248295221020758,1739502642.617769,3.0199971199035645,2.1014889357409903 +1739502642.638052,3.039997100830078,3.989574984388282,1739502642.638055,3.039997100830078,-0.11484692510284766,1739502642.6380582,3.039997100830078,3.3278174102228317,1739502642.6380613,3.039997100830078,9.543328285022039,1739502642.638063,3.039997100830078,-0.13936080995433064,1739502642.6380649,3.039997100830078,-0.004413902513627268,1739502642.638067,3.039997100830078,0.1691669635253729,1739502642.6380684,3.039997100830078,0.04211789032864445,1739502642.6380699,3.039997100830078,2.1835612853955584,1739502642.6380715,3.039997100830078,0.0,1739502642.6380732,3.039997100830078,0.06800074001023133,1739502642.6380749,3.039997100830078,6.248307054577268,1739502642.6380763,3.039997100830078,2.110655268236752 +1739502642.65793,3.059997081756592,3.989574984388282,1739502642.6579328,3.059997081756592,-0.11484692510284766,1739502642.657936,3.059997081756592,3.3278174102228317,1739502642.6579392,3.059997081756592,9.543328285022039,1739502642.6579406,3.059997081756592,-0.13936080995433064,1739502642.6579428,3.059997081756592,-0.004413902513627268,1739502642.6579442,3.059997081756592,0.1691669635253729,1739502642.6579459,3.059997081756592,0.04211789032864445,1739502642.6579473,3.059997081756592,2.1835612853955584,1739502642.6579492,3.059997081756592,0.0,1739502642.6579506,3.059997081756592,0.07290601715880651,1739502642.6579525,3.059997081756592,6.248307054577268,1739502642.657954,3.059997081756592,2.110655268236752 +1739502642.6778219,3.0799970626831055,3.989574984388282,1739502642.6778247,3.0799970626831055,-0.11484692510284766,1739502642.677828,3.0799970626831055,3.3278174102228317,1739502642.6778312,3.0799970626831055,9.543328285022039,1739502642.6778324,3.0799970626831055,-0.13936080995433064,1739502642.6778343,3.0799970626831055,-0.004413902513627268,1739502642.6778357,3.0799970626831055,0.1691669635253729,1739502642.6778374,3.0799970626831055,0.04211789032864445,1739502642.6778388,3.0799970626831055,2.1835612853955584,1739502642.677841,3.0799970626831055,0.0,1739502642.6778424,3.0799970626831055,0.07290601715880651,1739502642.677844,3.0799970626831055,6.248307054577268,1739502642.6778455,3.0799970626831055,2.110655268236752 +1739502642.6977174,3.099997043609619,3.989574984388282,1739502642.69772,3.099997043609619,-0.11484692510284766,1739502642.6977234,3.099997043609619,3.3278174102228317,1739502642.6977262,3.099997043609619,9.543328285022039,1739502642.697728,3.099997043609619,-0.13936080995433064,1739502642.6977298,3.099997043609619,-0.004413902513627268,1739502642.6977313,3.099997043609619,0.1691669635253729,1739502642.6977332,3.099997043609619,0.04211789032864445,1739502642.6977344,3.099997043609619,2.1835612853955584,1739502642.6977365,3.099997043609619,0.0,1739502642.697738,3.099997043609619,0.07290601715880651,1739502642.6977396,3.099997043609619,6.248307054577268,1739502642.697741,3.099997043609619,2.110655268236752 +1739502642.717907,3.119997024536133,3.989574984388282,1739502642.7179098,3.119997024536133,-0.11484692510284766,1739502642.7179132,3.119997024536133,3.3278174102228317,1739502642.7179163,3.119997024536133,9.543328285022039,1739502642.7179174,3.119997024536133,-0.13936080995433064,1739502642.7179196,3.119997024536133,-0.004413902513627268,1739502642.717921,3.119997024536133,0.1691669635253729,1739502642.7179224,3.119997024536133,0.04211789032864445,1739502642.7179239,3.119997024536133,2.1835612853955584,1739502642.7179255,3.119997024536133,0.0,1739502642.717927,3.119997024536133,0.07290601715880651,1739502642.717929,3.119997024536133,6.248307054577268,1739502642.7179306,3.119997024536133,2.110655268236752 +1739502642.7377791,3.1399970054626465,3.989574984388282,1739502642.737783,3.1399970054626465,-0.11484692510284766,1739502642.7377865,3.1399970054626465,3.3278174102228317,1739502642.7377903,3.1399970054626465,9.543328285022039,1739502642.7377923,3.1399970054626465,-0.13936080995433064,1739502642.7377944,3.1399970054626465,-0.004413902513627268,1739502642.7377963,3.1399970054626465,0.1691669635253729,1739502642.7377982,3.1399970054626465,0.04211789032864445,1739502642.7378004,3.1399970054626465,2.1835612853955584,1739502642.737803,3.1399970054626465,0.0,1739502642.7378056,3.1399970054626465,0.07290601715880651,1739502642.737808,3.1399970054626465,6.248307054577268,1739502642.73781,3.1399970054626465,2.110655268236752 +1739502642.7578895,3.15999698638916,4.221996556602605,1739502642.7578924,3.15999698638916,-0.12294685641402303,1739502642.7578957,3.15999698638916,3.3482867084403147,1739502642.7578988,3.15999698638916,9.579567096348208,1739502642.7579,3.15999698638916,-0.13969327611328633,1739502642.7579021,3.15999698638916,-0.003125738622783602,1739502642.7579038,3.15999698638916,0.1695526378867835,1739502642.7579052,3.15999698638916,0.045362045723926055,1739502642.7579067,3.15999698638916,2.1828876744352166,1739502642.7579088,3.15999698638916,0.0,1739502642.7579103,3.15999698638916,0.06045636976022529,1739502642.757912,3.15999698638916,6.248407138913457,1739502642.7579136,3.15999698638916,2.1185407873121127 +1739502642.777518,3.179996967315674,4.221996556602605,1739502642.777521,3.179996967315674,-0.12294685641402303,1739502642.7775242,3.179996967315674,3.3482867084403147,1739502642.777527,3.179996967315674,9.579567096348208,1739502642.7775285,3.179996967315674,-0.13969327611328633,1739502642.7775307,3.179996967315674,-0.003125738622783602,1739502642.777532,3.179996967315674,0.1695526378867835,1739502642.7775338,3.179996967315674,0.045362045723926055,1739502642.7775352,3.179996967315674,2.1828876744352166,1739502642.777537,3.179996967315674,0.0,1739502642.7775388,3.179996967315674,0.06434688712310388,1739502642.7775404,3.179996967315674,6.248407138913457,1739502642.777542,3.179996967315674,2.1185407873121127 +1739502642.7977316,3.1999969482421875,4.221996556602605,1739502642.7977345,3.1999969482421875,-0.12294685641402303,1739502642.7977378,3.1999969482421875,3.3482867084403147,1739502642.7977407,3.1999969482421875,9.579567096348208,1739502642.7977424,3.1999969482421875,-0.13969327611328633,1739502642.797744,3.1999969482421875,-0.003125738622783602,1739502642.7977457,3.1999969482421875,0.1695526378867835,1739502642.7977471,3.1999969482421875,0.045362045723926055,1739502642.7977488,3.1999969482421875,2.1828876744352166,1739502642.7977505,3.1999969482421875,0.0,1739502642.7977521,3.1999969482421875,0.06434688712310388,1739502642.7977538,3.1999969482421875,6.248407138913457,1739502642.7977555,3.1999969482421875,2.1185407873121127 +1739502642.8179286,3.219996929168701,4.221996556602605,1739502642.8179314,3.219996929168701,-0.12294685641402303,1739502642.817935,3.219996929168701,3.3482867084403147,1739502642.817938,3.219996929168701,9.579567096348208,1739502642.81794,3.219996929168701,-0.13969327611328633,1739502642.817942,3.219996929168701,-0.003125738622783602,1739502642.8179436,3.219996929168701,0.1695526378867835,1739502642.817945,3.219996929168701,0.045362045723926055,1739502642.8179467,3.219996929168701,2.1828876744352166,1739502642.8179483,3.219996929168701,0.0,1739502642.81795,3.219996929168701,0.06434688712310388,1739502642.8179514,3.219996929168701,6.248407138913457,1739502642.8179533,3.219996929168701,2.1185407873121127 +1739502642.8376415,3.239996910095215,4.221996556602605,1739502642.8376443,3.239996910095215,-0.12294685641402303,1739502642.8376477,3.239996910095215,3.3482867084403147,1739502642.8376508,3.239996910095215,9.579567096348208,1739502642.837652,3.239996910095215,-0.13969327611328633,1739502642.837654,3.239996910095215,-0.003125738622783602,1739502642.8376555,3.239996910095215,0.1695526378867835,1739502642.8376575,3.239996910095215,0.045362045723926055,1739502642.837659,3.239996910095215,2.1828876744352166,1739502642.837661,3.239996910095215,0.0,1739502642.8376625,3.239996910095215,0.06434688712310388,1739502642.837664,3.239996910095215,6.248407138913457,1739502642.8376658,3.239996910095215,2.1185407873121127 +1739502642.8579195,3.2599968910217285,4.455249790099751,1739502642.8579223,3.2599968910217285,-0.13104081377911925,1739502642.8579257,3.2599968910217285,3.693490903828139,1739502642.857929,3.2599968910217285,9.938845801720971,1739502642.8579302,3.2599968910217285,-0.142,1739502642.8579323,3.2599968910217285,-0.001998537384367376,1739502642.857934,3.2599968910217285,0.178442854022669,1739502642.8579357,3.2599968910217285,0.04557160619134478,1739502642.857937,3.2599968910217285,2.1674176777100014,1739502642.8579388,3.2599968910217285,0.0,1739502642.8579402,3.2599968910217285,0.031596433999177,1739502642.857942,3.2599968910217285,6.248639878083607,1739502642.8579438,3.2599968910217285,2.125586720399321 +1739502642.8775604,3.279996871948242,4.455249790099751,1739502642.8775628,3.279996871948242,-0.13104081377911925,1739502642.877566,3.279996871948242,3.693490903828139,1739502642.8775692,3.279996871948242,9.938845801720971,1739502642.877571,3.279996871948242,-0.142,1739502642.8775728,3.279996871948242,-0.001998537384367376,1739502642.877575,3.279996871948242,0.178442854022669,1739502642.8775764,3.279996871948242,0.04557160619134478,1739502642.8775778,3.279996871948242,2.1674176777100014,1739502642.8775797,3.279996871948242,0.0,1739502642.8775811,3.279996871948242,0.04183095731068054,1739502642.8775828,3.279996871948242,6.248639878083607,1739502642.8775845,3.279996871948242,2.125586720399321 +1739502642.8976028,3.299996852874756,4.455249790099751,1739502642.8976057,3.299996852874756,-0.13104081377911925,1739502642.8976095,3.299996852874756,3.693490903828139,1739502642.8976126,3.299996852874756,9.938845801720971,1739502642.897614,3.299996852874756,-0.142,1739502642.897616,3.299996852874756,-0.001998537384367376,1739502642.8976176,3.299996852874756,0.178442854022669,1739502642.8976192,3.299996852874756,0.04557160619134478,1739502642.8976204,3.299996852874756,2.1674176777100014,1739502642.8976223,3.299996852874756,0.0,1739502642.897624,3.299996852874756,0.04183095731068054,1739502642.8976257,3.299996852874756,6.248639878083607,1739502642.897627,3.299996852874756,2.125586720399321 +1739502642.9178066,3.3199968338012695,4.455249790099751,1739502642.9178092,3.3199968338012695,-0.13104081377911925,1739502642.9178126,3.3199968338012695,3.693490903828139,1739502642.9178154,3.3199968338012695,9.938845801720971,1739502642.917817,3.3199968338012695,-0.142,1739502642.917819,3.3199968338012695,-0.001998537384367376,1739502642.9178207,3.3199968338012695,0.178442854022669,1739502642.9178224,3.3199968338012695,0.04557160619134478,1739502642.9178238,3.3199968338012695,2.1674176777100014,1739502642.9178257,3.3199968338012695,0.0,1739502642.9178274,3.3199968338012695,0.04183095731068054,1739502642.917829,3.3199968338012695,6.248639878083607,1739502642.9178307,3.3199968338012695,2.125586720399321 +1739502642.9387057,3.339996814727783,4.455249790099751,1739502642.9387102,3.339996814727783,-0.13104081377911925,1739502642.938716,3.339996814727783,3.693490903828139,1739502642.9387205,3.339996814727783,9.938845801720971,1739502642.9387226,3.339996814727783,-0.142,1739502642.938729,3.339996814727783,-0.001998537384367376,1739502642.9387348,3.339996814727783,0.178442854022669,1739502642.9387372,3.339996814727783,0.04557160619134478,1739502642.9387393,3.339996814727783,2.1674176777100014,1739502642.938742,3.339996814727783,0.0,1739502642.9387443,3.339996814727783,0.04183095731068054,1739502642.9387467,3.339996814727783,6.248639878083607,1739502642.9387488,3.339996814727783,2.125586720399321 +1739502642.9589264,3.359996795654297,4.455249790099751,1739502642.9589307,3.359996795654297,-0.13104081377911925,1739502642.9589362,3.359996795654297,3.693490903828139,1739502642.9589415,3.359996795654297,9.938845801720971,1739502642.958944,3.359996795654297,-0.142,1739502642.9589472,3.359996795654297,-0.001998537384367376,1739502642.9589496,3.359996795654297,0.178442854022669,1739502642.9589522,3.359996795654297,0.04557160619134478,1739502642.9589546,3.359996795654297,2.1674176777100014,1739502642.958958,3.359996795654297,0.0,1739502642.9589603,3.359996795654297,0.04183095731068054,1739502642.958963,3.359996795654297,6.248639878083607,1739502642.9589655,3.359996795654297,2.125586720399321 +1739502642.9794328,3.3799967765808105,4.689135754434787,1739502642.9794369,3.3799967765808105,-0.13909501459392803,1739502642.9794426,3.3799967765808105,3.8774285516088263,1739502642.979448,3.3799967765808105,10.1315346317157,1739502642.9794507,3.3799967765808105,-0.14274122392468816,1739502642.9794538,3.3799967765808105,-0.0006699635339934382,1739502642.9794562,3.3799967765808105,0.18286218711264307,1739502642.9794588,3.3799967765808105,0.04740979113870869,1739502642.9794612,3.3799967765808105,2.1597683750739027,1739502642.979464,3.3799967765808105,0.0,1739502642.9794662,3.3799967765808105,0.024337747285449556,1739502642.9794688,3.3799967765808105,6.248909469819413,1739502642.9794714,3.3799967765808105,2.1299639960713654 +1739502642.998606,3.399996757507324,4.689135754434787,1739502642.9986103,3.399996757507324,-0.13909501459392803,1739502642.9986143,3.399996757507324,3.8774285516088263,1739502642.9986186,3.399996757507324,10.1315346317157,1739502642.998621,3.399996757507324,-0.14274122392468816,1739502642.9986234,3.399996757507324,-0.0006699635339934382,1739502642.998626,3.399996757507324,0.18286218711264307,1739502642.9986281,3.399996757507324,0.04740979113870869,1739502642.99863,3.399996757507324,2.1597683750739027,1739502642.9986324,3.399996757507324,0.0,1739502642.9986348,3.399996757507324,0.029804379002537296,1739502642.998637,3.399996757507324,6.248909469819413,1739502642.998639,3.399996757507324,2.1299639960713654 +1739502643.018744,3.419996738433838,4.689135754434787,1739502643.0187469,3.419996738433838,-0.13909501459392803,1739502643.0187507,3.419996738433838,3.8774285516088263,1739502643.018754,3.419996738433838,10.1315346317157,1739502643.018756,3.419996738433838,-0.14274122392468816,1739502643.0187578,3.419996738433838,-0.0006699635339934382,1739502643.0187597,3.419996738433838,0.18286218711264307,1739502643.0187614,3.419996738433838,0.04740979113870869,1739502643.018763,3.419996738433838,2.1597683750739027,1739502643.018765,3.419996738433838,0.0,1739502643.0187666,3.419996738433838,0.029804379002537296,1739502643.0187683,3.419996738433838,6.248909469819413,1739502643.0187705,3.419996738433838,2.1299639960713654 +1739502643.0374484,3.4399967193603516,4.689135754434787,1739502643.0374506,3.4399967193603516,-0.13909501459392803,1739502643.0374537,3.4399967193603516,3.8774285516088263,1739502643.0374563,3.4399967193603516,10.1315346317157,1739502643.037458,3.4399967193603516,-0.14274122392468816,1739502643.0374596,3.4399967193603516,-0.0006699635339934382,1739502643.037461,3.4399967193603516,0.18286218711264307,1739502643.0374622,3.4399967193603516,0.04740979113870869,1739502643.0374637,3.4399967193603516,2.1597683750739027,1739502643.0374653,3.4399967193603516,0.0,1739502643.0374668,3.4399967193603516,0.029804379002537296,1739502643.0374682,3.4399967193603516,6.248909469819413,1739502643.0374699,3.4399967193603516,2.1299639960713654 +1739502643.0575235,3.4599967002868652,4.689135754434787,1739502643.0575264,3.4599967002868652,-0.13909501459392803,1739502643.057529,3.4599967002868652,3.8774285516088263,1739502643.0575318,3.4599967002868652,10.1315346317157,1739502643.0575333,3.4599967002868652,-0.14274122392468816,1739502643.057535,3.4599967002868652,-0.0006699635339934382,1739502643.0575364,3.4599967002868652,0.18286218711264307,1739502643.0575376,3.4599967002868652,0.04740979113870869,1739502643.0575387,3.4599967002868652,2.1597683750739027,1739502643.0575404,3.4599967002868652,0.0,1739502643.0575418,3.4599967002868652,0.029804379002537296,1739502643.0575433,3.4599967002868652,6.248909469819413,1739502643.0575447,3.4599967002868652,2.1299639960713654 +1739502643.077805,3.479996681213379,4.923461037747035,1739502643.0778077,3.479996681213379,-0.14709543259579494,1739502643.0778112,3.479996681213379,4.143385316942074,1739502643.0778139,3.479996681213379,10.404028843315174,1739502643.0778153,3.479996681213379,-0.14343244415042047,1739502643.0778167,3.479996681213379,0.0006683591974227649,1739502643.0778184,3.479996681213379,0.1896347054588148,1739502643.0778198,3.479996681213379,0.04848304915578315,1739502643.0778215,3.479996681213379,2.1480983610203226,1739502643.077823,3.479996681213379,0.0,1739502643.0778244,3.479996681213379,0.008073430293049707,1739502643.0778258,3.479996681213379,6.249245477918026,1739502643.077827,3.479996681213379,2.13323400480308 +1739502643.0977933,3.4999966621398926,4.923461037747035,1739502643.0977955,3.4999966621398926,-0.14709543259579494,1739502643.0977986,3.4999966621398926,4.143385316942074,1739502643.0978012,3.4999966621398926,10.404028843315174,1739502643.0978024,3.4999966621398926,-0.14343244415042047,1739502643.097804,3.4999966621398926,0.0006683591974227649,1739502643.0978055,3.4999966621398926,0.1896347054588148,1739502643.097807,3.4999966621398926,0.04848304915578315,1739502643.0978084,3.4999966621398926,2.1480983610203226,1739502643.09781,3.4999966621398926,0.0,1739502643.0978112,3.4999966621398926,0.01486435621724258,1739502643.0978127,3.4999966621398926,6.249245477918026,1739502643.097814,3.4999966621398926,2.13323400480308 +1739502643.117623,3.5199966430664062,4.923461037747035,1739502643.1176257,3.5199966430664062,-0.14709543259579494,1739502643.1176293,3.5199966430664062,4.143385316942074,1739502643.1176317,3.5199966430664062,10.404028843315174,1739502643.1176333,3.5199966430664062,-0.14343244415042047,1739502643.117635,3.5199966430664062,0.0006683591974227649,1739502643.1176367,3.5199966430664062,0.1896347054588148,1739502643.117638,3.5199966430664062,0.04848304915578315,1739502643.117639,3.5199966430664062,2.1480983610203226,1739502643.117641,3.5199966430664062,0.0,1739502643.1176422,3.5199966430664062,0.01486435621724258,1739502643.1176438,3.5199966430664062,6.249245477918026,1739502643.117645,3.5199966430664062,2.13323400480308 +1739502643.137884,3.53999662399292,4.923461037747035,1739502643.1378865,3.53999662399292,-0.14709543259579494,1739502643.1378899,3.53999662399292,4.143385316942074,1739502643.137893,3.53999662399292,10.404028843315174,1739502643.1378944,3.53999662399292,-0.14343244415042047,1739502643.1378963,3.53999662399292,0.0006683591974227649,1739502643.1378977,3.53999662399292,0.1896347054588148,1739502643.137899,3.53999662399292,0.04848304915578315,1739502643.1379006,3.53999662399292,2.1480983610203226,1739502643.1379023,3.53999662399292,0.0,1739502643.137904,3.53999662399292,0.01486435621724258,1739502643.1379054,3.53999662399292,6.249245477918026,1739502643.137907,3.53999662399292,2.13323400480308 +1739502643.1579657,3.5599966049194336,4.923461037747035,1739502643.1579683,3.5599966049194336,-0.14709543259579494,1739502643.1579719,3.5599966049194336,4.143385316942074,1739502643.1579752,3.5599966049194336,10.404028843315174,1739502643.1579769,3.5599966049194336,-0.14343244415042047,1739502643.1579788,3.5599966049194336,0.0006683591974227649,1739502643.1579807,3.5599966049194336,0.1896347054588148,1739502643.157982,3.5599966049194336,0.04848304915578315,1739502643.1579838,3.5599966049194336,2.1480983610203226,1739502643.1579854,3.5599966049194336,0.0,1739502643.157987,3.5599966049194336,0.01486435621724258,1739502643.1579888,3.5599966049194336,6.249245477918026,1739502643.1579907,3.5599966049194336,2.13323400480308 +1739502643.1776283,3.5799965858459473,4.923461037747035,1739502643.1776311,3.5799965858459473,-0.14709543259579494,1739502643.1776347,3.5799965858459473,4.143385316942074,1739502643.177638,3.5799965858459473,10.404028843315174,1739502643.17764,3.5799965858459473,-0.14343244415042047,1739502643.1776419,3.5799965858459473,0.0006683591974227649,1739502643.1776438,3.5799965858459473,0.1896347054588148,1739502643.1776452,3.5799965858459473,0.04848304915578315,1739502643.1776469,3.5799965858459473,2.1480983610203226,1739502643.1776488,3.5799965858459473,0.0,1739502643.1776505,3.5799965858459473,0.01486435621724258,1739502643.177652,3.5799965858459473,6.249245477918026,1739502643.1776538,3.5799965858459473,2.13323400480308 +1739502643.2014318,3.599996566772461,5.158051780258839,1739502643.2014344,3.599996566772461,-0.15501591405488746,1739502643.2014372,3.599996566772461,4.491186427131467,1739502643.2014399,3.599996566772461,10.75480945101561,1739502643.201441,3.599996566772461,-0.145,1739502643.2014427,3.599996566772461,0.0017895903220510254,1739502643.2014441,3.599996566772461,0.19755172379586913,1739502643.2014453,3.599996566772461,0.04843172243728691,1739502643.2014468,3.599996566772461,2.1345361280450064,1739502643.201448,3.599996566772461,0.0,1739502643.2014492,3.599996566772461,-0.007034020101487708,1739502643.2014506,3.599996566772461,6.249670089963592,1739502643.201452,3.599996566772461,2.1347269010601084 +1739502643.2174978,3.6199965476989746,5.158051780258839,1739502643.2175002,3.6199965476989746,-0.15501591405488746,1739502643.2175033,3.6199965476989746,4.491186427131467,1739502643.217506,3.6199965476989746,10.75480945101561,1739502643.2175076,3.6199965476989746,-0.145,1739502643.2175093,3.6199965476989746,0.0017895903220510254,1739502643.2175114,3.6199965476989746,0.19755172379586913,1739502643.2175128,3.6199965476989746,0.04843172243728691,1739502643.2175143,3.6199965476989746,2.1345361280450064,1739502643.2175157,3.6199965476989746,0.0,1739502643.2175171,3.6199965476989746,-0.00019077301510206368,1739502643.2175183,3.6199965476989746,6.249670089963592,1739502643.2175198,3.6199965476989746,2.1347269010601084 +1739502643.237533,3.6399965286254883,5.158051780258839,1739502643.2375374,3.6399965286254883,-0.15501591405488746,1739502643.2375412,3.6399965286254883,4.491186427131467,1739502643.237545,3.6399965286254883,10.75480945101561,1739502643.2375472,3.6399965286254883,-0.145,1739502643.2375495,3.6399965286254883,0.0017895903220510254,1739502643.2375515,3.6399965286254883,0.19755172379586913,1739502643.2375531,3.6399965286254883,0.04843172243728691,1739502643.2375553,3.6399965286254883,2.1345361280450064,1739502643.2375576,3.6399965286254883,0.0,1739502643.2375598,3.6399965286254883,-0.00019077301510206368,1739502643.237562,3.6399965286254883,6.249670089963592,1739502643.2375636,3.6399965286254883,2.1347269010601084 +1739502643.2575812,3.659996509552002,5.158051780258839,1739502643.2575846,3.659996509552002,-0.15501591405488746,1739502643.257588,3.659996509552002,4.491186427131467,1739502643.2575912,3.659996509552002,10.75480945101561,1739502643.2575932,3.659996509552002,-0.145,1739502643.257595,3.659996509552002,0.0017895903220510254,1739502643.257597,3.659996509552002,0.19755172379586913,1739502643.2575986,3.659996509552002,0.04843172243728691,1739502643.2576,3.659996509552002,2.1345361280450064,1739502643.2576017,3.659996509552002,0.0,1739502643.257604,3.659996509552002,-0.00019077301510206368,1739502643.2576056,3.659996509552002,6.249670089963592,1739502643.2576072,3.659996509552002,2.1347269010601084 +1739502643.2779958,3.6799964904785156,5.158051780258839,1739502643.2779994,3.6799964904785156,-0.15501591405488746,1739502643.278003,3.6799964904785156,4.491186427131467,1739502643.2780066,3.6799964904785156,10.75480945101561,1739502643.2780082,3.6799964904785156,-0.145,1739502643.2780108,3.6799964904785156,0.0017895903220510254,1739502643.2780128,3.6799964904785156,0.19755172379586913,1739502643.2780144,3.6799964904785156,0.04843172243728691,1739502643.2780163,3.6799964904785156,2.1345361280450064,1739502643.2780182,3.6799964904785156,0.0,1739502643.2780204,3.6799964904785156,-0.00019077301510206368,1739502643.2780223,3.6799964904785156,6.249670089963592,1739502643.2780242,3.6799964904785156,2.1347269010601084 +1739502643.2981179,3.6999964714050293,5.392743621505659,1739502643.2981215,3.6999964714050293,-0.16283847281764618,1739502643.2981255,3.6999964714050293,4.512324337961206,1739502643.298129,3.6999964714050293,10.775929586554103,1739502643.298131,3.6999964714050293,-0.145,1739502643.2981336,3.6999964714050293,0.003313726785576202,1739502643.2981353,3.6999964714050293,0.19588935556959902,1739502643.2981377,3.6999964714050293,0.0519093005932185,1739502643.2981393,3.6999964714050293,2.1373767245029334,1739502643.2981417,3.6999964714050293,0.0,1739502643.2981434,3.6999964714050293,0.003953932370734765,1739502643.2981453,3.6999964714050293,6.25010208648468,1739502643.2981474,3.6999964714050293,2.134718013414486 +1739502643.3178625,3.719996452331543,5.392743621505659,1739502643.3178656,3.719996452331543,-0.16283847281764618,1739502643.31787,3.719996452331543,4.512324337961206,1739502643.3178735,3.719996452331543,10.775929586554103,1739502643.3178751,3.719996452331543,-0.145,1739502643.3178775,3.719996452331543,0.003313726785576202,1739502643.31788,3.719996452331543,0.19588935556959902,1739502643.3178816,3.719996452331543,0.0519093005932185,1739502643.3178835,3.719996452331543,2.1373767245029334,1739502643.3178854,3.719996452331543,0.0,1739502643.3178875,3.719996452331543,0.0026587110884475074,1739502643.3178895,3.719996452331543,6.25010208648468,1739502643.3178918,3.719996452331543,2.134718013414486 +1739502643.3379843,3.7399964332580566,5.392743621505659,1739502643.3379877,3.7399964332580566,-0.16283847281764618,1739502643.337992,3.7399964332580566,4.512324337961206,1739502643.3379955,3.7399964332580566,10.775929586554103,1739502643.3379977,3.7399964332580566,-0.145,1739502643.3379998,3.7399964332580566,0.003313726785576202,1739502643.3380017,3.7399964332580566,0.19588935556959902,1739502643.3380036,3.7399964332580566,0.0519093005932185,1739502643.3380053,3.7399964332580566,2.1373767245029334,1739502643.3380075,3.7399964332580566,0.0,1739502643.3380094,3.7399964332580566,0.0026587110884475074,1739502643.3380115,3.7399964332580566,6.25010208648468,1739502643.3380132,3.7399964332580566,2.134718013414486 +1739502643.358039,3.7599964141845703,5.392743621505659,1739502643.358042,3.7599964141845703,-0.16283847281764618,1739502643.3580463,3.7599964141845703,4.512324337961206,1739502643.3580499,3.7599964141845703,10.775929586554103,1739502643.3580515,3.7599964141845703,-0.145,1739502643.358054,3.7599964141845703,0.003313726785576202,1739502643.3580556,3.7599964141845703,0.19588935556959902,1739502643.3580575,3.7599964141845703,0.0519093005932185,1739502643.3580592,3.7599964141845703,2.1373767245029334,1739502643.3580618,3.7599964141845703,0.0,1739502643.3580637,3.7599964141845703,0.0026587110884475074,1739502643.3580654,3.7599964141845703,6.25010208648468,1739502643.3580675,3.7599964141845703,2.134718013414486 +1739502643.3781676,3.779996395111084,5.392743621505659,1739502643.3781712,3.779996395111084,-0.16283847281764618,1739502643.3781755,3.779996395111084,4.512324337961206,1739502643.3781793,3.779996395111084,10.775929586554103,1739502643.3781812,3.779996395111084,-0.145,1739502643.3781831,3.779996395111084,0.003313726785576202,1739502643.3781853,3.779996395111084,0.19588935556959902,1739502643.378187,3.779996395111084,0.0519093005932185,1739502643.3781888,3.779996395111084,2.1373767245029334,1739502643.378191,3.779996395111084,0.0,1739502643.378193,3.779996395111084,0.0026587110884475074,1739502643.378195,3.779996395111084,6.25010208648468,1739502643.3781967,3.779996395111084,2.134718013414486 +1739502643.4015186,3.7999963760375977,5.392743621505659,1739502643.4015276,3.7999963760375977,-0.16283847281764618,1739502643.4015381,3.7999963760375977,4.512324337961206,1739502643.4015477,3.7999963760375977,10.775929586554103,1739502643.401553,3.7999963760375977,-0.145,1739502643.4015589,3.7999963760375977,0.003313726785576202,1739502643.4015641,3.7999963760375977,0.19588935556959902,1739502643.4015691,3.7999963760375977,0.0519093005932185,1739502643.401574,3.7999963760375977,2.1373767245029334,1739502643.4015796,3.7999963760375977,0.0,1739502643.4015844,3.7999963760375977,0.0026587110884475074,1739502643.4015899,3.7999963760375977,6.25010208648468,1739502643.401595,3.7999963760375977,2.134718013414486 +1739502643.4432404,3.839996337890625,5.6274528862152255,1739502643.443249,3.839996337890625,-0.17055299312879857,1739502643.4432595,3.839996337890625,5.068968004451558,1739502643.4432695,3.839996337890625,11.333179309307496,1739502643.4432743,3.839996337890625,-0.14751512891268015,1739502643.4432802,3.839996337890625,0.00403765223129331,1739502643.4432852,3.839996337890625,0.20886951341453175,1739502643.44329,3.839996337890625,0.049268377392816906,1739502643.4432948,3.839996337890625,2.1152967736021338,1739502643.443301,3.839996337890625,0.0,1739502643.4433057,3.839996337890625,-0.029918367126446948,1739502643.4433112,3.839996337890625,6.250608079478647,1739502643.4433162,3.839996337890625,2.1350347971116728 +1739502643.4639943,3.8599963188171387,5.6274528862152255,1739502643.4640007,3.8599963188171387,-0.17055299312879857,1739502643.4640083,3.8599963188171387,5.068968004451558,1739502643.4640174,3.8599963188171387,11.333179309307496,1739502643.4640222,3.8599963188171387,-0.14751512891268015,1739502643.4640286,3.8599963188171387,0.00403765223129331,1739502643.4640343,3.8599963188171387,0.20886951341453175,1739502643.4640403,3.8599963188171387,0.049268377392816906,1739502643.4640458,3.8599963188171387,2.1152967736021338,1739502643.4640517,3.8599963188171387,0.0,1739502643.4640574,3.8599963188171387,-0.019738023509539016,1739502643.4640636,3.8599963188171387,6.250608079478647,1739502643.4640694,3.8599963188171387,2.1350347971116728 +1739502643.4799662,3.8799962997436523,5.6274528862152255,1739502643.4799705,3.8799962997436523,-0.17055299312879857,1739502643.479976,3.8799962997436523,5.068968004451558,1739502643.479982,3.8799962997436523,11.333179309307496,1739502643.479985,3.8799962997436523,-0.14751512891268015,1739502643.4799888,3.8799962997436523,0.00403765223129331,1739502643.4799926,3.8799962997436523,0.20886951341453175,1739502643.4799962,3.8799962997436523,0.049268377392816906,1739502643.4800003,3.8799962997436523,2.1152967736021338,1739502643.4800043,3.8799962997436523,0.0,1739502643.4800081,3.8799962997436523,-0.019738023509539016,1739502643.4800117,3.8799962997436523,6.250608079478647,1739502643.4800155,3.8799962997436523,2.1350347971116728 +1739502643.497479,3.899996280670166,5.6274528862152255,1739502643.4974809,3.899996280670166,-0.17055299312879857,1739502643.4974837,3.899996280670166,5.068968004451558,1739502643.4974868,3.899996280670166,11.333179309307496,1739502643.497488,3.899996280670166,-0.14751512891268015,1739502643.49749,3.899996280670166,0.00403765223129331,1739502643.4974911,3.899996280670166,0.20886951341453175,1739502643.4974926,3.899996280670166,0.049268377392816906,1739502643.4974937,3.899996280670166,2.1152967736021338,1739502643.4974954,3.899996280670166,0.0,1739502643.4974966,3.899996280670166,-0.019738023509539016,1739502643.4974978,3.899996280670166,6.250608079478647,1739502643.4974992,3.899996280670166,2.1350347971116728 +1739502643.5180306,3.9199962615966797,5.862122618578281,1739502643.5180328,3.9199962615966797,-0.1781457764691714,1739502643.5180357,3.9199962615966797,5.077893047064695,1739502643.5180383,3.9199962615966797,11.338707953056579,1739502643.5180395,3.9199962615966797,-0.14756493651402322,1739502643.5180414,3.9199962615966797,0.0055838666348390475,1739502643.5180426,3.9199962615966797,0.20613536297343077,1739502643.518044,3.9199962615966797,0.05277590123347228,1739502643.5180452,3.9199962615966797,2.119928669160405,1739502643.5180466,3.9199962615966797,0.0,1739502643.518048,3.9199962615966797,-0.01053077303713721,1739502643.5180492,3.9199962615966797,6.2511214721199035,1739502643.518051,3.9199962615966797,2.1333367098566516 +1739502643.5378747,3.9399962425231934,5.862122618578281,1739502643.5378773,3.9399962425231934,-0.1781457764691714,1739502643.5378804,3.9399962425231934,5.077893047064695,1739502643.5378833,3.9399962425231934,11.338707953056579,1739502643.5378847,3.9399962425231934,-0.14756493651402322,1739502643.5378864,3.9399962425231934,0.0055838666348390475,1739502643.5378878,3.9399962425231934,0.20613536297343077,1739502643.537889,3.9399962425231934,0.05277590123347228,1739502643.5378902,3.9399962425231934,2.119928669160405,1739502643.537892,3.9399962425231934,0.0,1739502643.5378933,3.9399962425231934,-0.01340804069624646,1739502643.537895,3.9399962425231934,6.2511214721199035,1739502643.5378964,3.9399962425231934,2.1333367098566516 +1739502643.5578482,3.959996223449707,5.862122618578281,1739502643.557851,3.959996223449707,-0.1781457764691714,1739502643.5578542,3.959996223449707,5.077893047064695,1739502643.557857,3.959996223449707,11.338707953056579,1739502643.5578582,3.959996223449707,-0.14756493651402322,1739502643.55786,3.959996223449707,0.0055838666348390475,1739502643.5578613,3.959996223449707,0.20613536297343077,1739502643.5578628,3.959996223449707,0.05277590123347228,1739502643.5578642,3.959996223449707,2.119928669160405,1739502643.5578656,3.959996223449707,0.0,1739502643.557867,3.959996223449707,-0.01340804069624646,1739502643.5578687,3.959996223449707,6.2511214721199035,1739502643.5578704,3.959996223449707,2.1333367098566516 +1739502643.5789716,3.9799962043762207,5.862122618578281,1739502643.578975,3.9799962043762207,-0.1781457764691714,1739502643.5789793,3.9799962043762207,5.077893047064695,1739502643.5789845,3.9799962043762207,11.338707953056579,1739502643.5789874,3.9799962043762207,-0.14756493651402322,1739502643.5789912,3.9799962043762207,0.0055838666348390475,1739502643.5789945,3.9799962043762207,0.20613536297343077,1739502643.5789979,3.9799962043762207,0.05277590123347228,1739502643.5790012,3.9799962043762207,2.119928669160405,1739502643.5790045,3.9799962043762207,0.0,1739502643.5790076,3.9799962043762207,-0.01340804069624646,1739502643.5790114,3.9799962043762207,6.2511214721199035,1739502643.5790145,3.9799962043762207,2.1333367098566516 +1739502643.5990732,3.9999961853027344,5.862122618578281,1739502643.5990767,3.9999961853027344,-0.1781457764691714,1739502643.5990813,3.9999961853027344,5.077893047064695,1739502643.5990863,3.9999961853027344,11.338707953056579,1739502643.5990894,3.9999961853027344,-0.14756493651402322,1739502643.599093,3.9999961853027344,0.0055838666348390475,1739502643.5990963,3.9999961853027344,0.20613536297343077,1739502643.5990996,3.9999961853027344,0.05277590123347228,1739502643.599103,3.9999961853027344,2.119928669160405,1739502643.5991066,3.9999961853027344,0.0,1739502643.59911,3.9999961853027344,-0.01340804069624646,1739502643.5991132,3.9999961853027344,6.2511214721199035,1739502643.5991166,3.9999961853027344,2.1333367098566516 +1739502643.617751,4.019996166229248,5.862122618578281,1739502643.6177535,4.019996166229248,-0.1781457764691714,1739502643.6177566,4.019996166229248,5.077893047064695,1739502643.6177595,4.019996166229248,11.338707953056579,1739502643.6177611,4.019996166229248,-0.14756493651402322,1739502643.6177628,4.019996166229248,0.0055838666348390475,1739502643.6177647,4.019996166229248,0.20613536297343077,1739502643.617766,4.019996166229248,0.05277590123347228,1739502643.617767,4.019996166229248,2.119928669160405,1739502643.617769,4.019996166229248,0.0,1739502643.6177702,4.019996166229248,-0.01340804069624646,1739502643.6177719,4.019996166229248,6.2511214721199035,1739502643.6177733,4.019996166229248,2.1333367098566516 +1739502643.6375551,4.039996147155762,6.096602949372915,1739502643.6375573,4.039996147155762,-0.1856048169332487,1739502643.6375604,4.039996147155762,5.507272192333409,1739502643.637563,4.039996147155762,11.765254351208286,1739502643.6375644,4.039996147155762,-0.15039512813578826,1739502643.6375659,4.039996147155762,0.0062112191265072695,1739502643.6375673,4.039996147155762,0.2135915523756114,1739502643.6375687,4.039996147155762,0.05104193470271706,1739502643.6375701,4.039996147155762,2.1073210367596316,1739502643.637572,4.039996147155762,0.0,1739502643.6375735,4.039996147155762,-0.02969401318698855,1739502643.6375747,4.039996147155762,6.251708902344365,1739502643.637576,4.039996147155762,2.1319256802064124 +1739502643.6574633,4.059996128082275,6.096602949372915,1739502643.657466,4.059996128082275,-0.1856048169332487,1739502643.6574686,4.059996128082275,5.507272192333409,1739502643.6574714,4.059996128082275,11.765254351208286,1739502643.657473,4.059996128082275,-0.15039512813578826,1739502643.6574745,4.059996128082275,0.0062112191265072695,1739502643.657476,4.059996128082275,0.2135915523756114,1739502643.6574774,4.059996128082275,0.05104193470271706,1739502643.6574786,4.059996128082275,2.1073210367596316,1739502643.65748,4.059996128082275,0.0,1739502643.6574814,4.059996128082275,-0.024604643446780816,1739502643.6574829,4.059996128082275,6.251708902344365,1739502643.657484,4.059996128082275,2.1319256802064124 +1739502643.6773717,4.079996109008789,6.096602949372915,1739502643.677374,4.079996109008789,-0.1856048169332487,1739502643.677377,4.079996109008789,5.507272192333409,1739502643.6773798,4.079996109008789,11.765254351208286,1739502643.677381,4.079996109008789,-0.15039512813578826,1739502643.677383,4.079996109008789,0.0062112191265072695,1739502643.6773846,4.079996109008789,0.2135915523756114,1739502643.677386,4.079996109008789,0.05104193470271706,1739502643.6773872,4.079996109008789,2.1073210367596316,1739502643.6773891,4.079996109008789,0.0,1739502643.6773903,4.079996109008789,-0.024604643446780816,1739502643.6773918,4.079996109008789,6.251708902344365,1739502643.6773937,4.079996109008789,2.1319256802064124 +1739502643.6974964,4.099996089935303,6.096602949372915,1739502643.6974986,4.099996089935303,-0.1856048169332487,1739502643.6975017,4.099996089935303,5.507272192333409,1739502643.6975045,4.099996089935303,11.765254351208286,1739502643.697506,4.099996089935303,-0.15039512813578826,1739502643.6975079,4.099996089935303,0.0062112191265072695,1739502643.697509,4.099996089935303,0.2135915523756114,1739502643.6975107,4.099996089935303,0.05104193470271706,1739502643.697512,4.099996089935303,2.1073210367596316,1739502643.6975138,4.099996089935303,0.0,1739502643.697515,4.099996089935303,-0.024604643446780816,1739502643.6975162,4.099996089935303,6.251708902344365,1739502643.6975179,4.099996089935303,2.1319256802064124 +1739502643.717533,4.119996070861816,6.096602949372915,1739502643.7175355,4.119996070861816,-0.1856048169332487,1739502643.7175386,4.119996070861816,5.507272192333409,1739502643.7175415,4.119996070861816,11.765254351208286,1739502643.7175431,4.119996070861816,-0.15039512813578826,1739502643.717545,4.119996070861816,0.0062112191265072695,1739502643.7175462,4.119996070861816,0.2135915523756114,1739502643.717548,4.119996070861816,0.05104193470271706,1739502643.7175493,4.119996070861816,2.1073210367596316,1739502643.7175508,4.119996070861816,0.0,1739502643.7175522,4.119996070861816,-0.024604643446780816,1739502643.7175536,4.119996070861816,6.251708902344365,1739502643.717555,4.119996070861816,2.1319256802064124 +1739502643.7374725,4.13999605178833,6.330868366519734,1739502643.7374752,4.13999605178833,-0.19291769837837514,1739502643.7374778,4.13999605178833,5.529542032725248,1739502643.7374806,4.13999605178833,11.782157974331335,1739502643.7374823,4.13999605178833,-0.15054605334224408,1739502643.737484,4.13999605178833,0.007772618005392996,1739502643.7374856,4.13999605178833,0.2106690723267555,1739502643.7374868,4.13999605178833,0.054436423776429516,1739502643.7374883,4.13999605178833,2.112253683686806,1739502643.73749,4.13999605178833,0.0,1739502643.7374911,4.13999605178833,-0.013527667517710994,1739502643.737493,4.13999605178833,6.252303736327147,1739502643.7374945,4.13999605178833,2.1292429084519253 +1739502643.762174,4.159996032714844,6.330868366519734,1739502643.7621827,4.159996032714844,-0.19291769837837514,1739502643.762193,4.159996032714844,5.529542032725248,1739502643.762203,4.159996032714844,11.782157974331335,1739502643.7622077,4.159996032714844,-0.15054605334224408,1739502643.7622142,4.159996032714844,0.007772618005392996,1739502643.7622192,4.159996032714844,0.2106690723267555,1739502643.7622244,4.159996032714844,0.054436423776429516,1739502643.7622287,4.159996032714844,2.112253683686806,1739502643.7622344,4.159996032714844,0.0,1739502643.7622392,4.159996032714844,-0.016989224765119104,1739502643.7622445,4.159996032714844,6.252303736327147,1739502643.7622492,4.159996032714844,2.1292429084519253 +1739502643.781538,4.179996013641357,6.330868366519734,1739502643.7815468,4.179996013641357,-0.19291769837837514,1739502643.7815576,4.179996013641357,5.529542032725248,1739502643.7815678,4.179996013641357,11.782157974331335,1739502643.7815728,4.179996013641357,-0.15054605334224408,1739502643.7815793,4.179996013641357,0.007772618005392996,1739502643.7815845,4.179996013641357,0.2106690723267555,1739502643.7815895,4.179996013641357,0.054436423776429516,1739502643.7815943,4.179996013641357,2.112253683686806,1739502643.7815998,4.179996013641357,0.0,1739502643.7816045,4.179996013641357,-0.016989224765119104,1739502643.7816098,4.179996013641357,6.252303736327147,1739502643.7816148,4.179996013641357,2.1292429084519253 +1739502643.8042774,4.199995994567871,6.330868366519734,1739502643.8042836,4.199995994567871,-0.19291769837837514,1739502643.8042908,4.199995994567871,5.529542032725248,1739502643.8042974,4.199995994567871,11.782157974331335,1739502643.8043008,4.199995994567871,-0.15054605334224408,1739502643.804305,4.199995994567871,0.007772618005392996,1739502643.8043087,4.199995994567871,0.2106690723267555,1739502643.8043122,4.199995994567871,0.054436423776429516,1739502643.8043156,4.199995994567871,2.112253683686806,1739502643.8043194,4.199995994567871,0.0,1739502643.804323,4.199995994567871,-0.016989224765119104,1739502643.8043268,4.199995994567871,6.252303736327147,1739502643.8043303,4.199995994567871,2.1292429084519253 +1739502643.8202677,4.209995985031128,6.330868366519734,1739502643.820274,4.209995985031128,-0.19291769837837514,1739502643.8202798,4.209995985031128,5.529542032725248,1739502643.8202856,4.209995985031128,11.782157974331335,1739502643.8202882,4.209995985031128,-0.15054605334224408,1739502643.8202918,4.209995985031128,0.007772618005392996,1739502643.8202946,4.209995985031128,0.2106690723267555,1739502643.8202977,4.209995985031128,0.054436423776429516,1739502643.8203003,4.209995985031128,2.112253683686806,1739502643.8203032,4.209995985031128,0.0,1739502643.8203058,4.209995985031128,-0.016989224765119104,1739502643.8203092,4.209995985031128,6.252303736327147,1739502643.820312,4.209995985031128,2.1292429084519253 +1739502643.8403826,4.239995956420898,6.330868366519734,1739502643.8403866,4.239995956420898,-0.19291769837837514,1739502643.8403916,4.239995956420898,5.529542032725248,1739502643.8403978,4.239995956420898,11.782157974331335,1739502643.8404014,4.239995956420898,-0.15054605334224408,1739502643.8404057,4.239995956420898,0.007772618005392996,1739502643.8404095,4.239995956420898,0.2106690723267555,1739502643.8404138,4.239995956420898,0.054436423776429516,1739502643.8404176,4.239995956420898,2.112253683686806,1739502643.8404217,4.239995956420898,0.0,1739502643.8404257,4.239995956420898,-0.016989224765119104,1739502643.8404298,4.239995956420898,6.252303736327147,1739502643.8404338,4.239995956420898,2.1292429084519253 +1739502643.8593216,4.259995937347412,6.564888981594651,1739502643.8593242,4.259995937347412,-0.2000764957973855,1739502643.8593273,4.259995937347412,5.7265333452068425,1739502643.8593307,4.259995937347412,11.975564132555624,1739502643.8593323,4.259995937347412,-0.151,1739502643.8593345,4.259995937347412,0.009070060324304317,1739502643.859336,4.259995937347412,0.2124999188064242,1739502643.8593378,4.259995937347412,0.05573543161848481,1739502643.859339,4.259995937347412,2.10916217849129,1739502643.859341,4.259995937347412,0.0,1739502643.8593426,4.259995937347412,-0.01888004906747827,1739502643.8593442,4.259995937347412,6.252972684245004,1739502643.8593457,4.259995937347412,2.127451344576868 +1739502643.8904026,4.279995918273926,6.564888981594651,1739502643.890412,4.279995918273926,-0.2000764957973855,1739502643.890423,4.279995918273926,5.7265333452068425,1739502643.8904335,4.279995918273926,11.975564132555624,1739502643.8904383,4.279995918273926,-0.151,1739502643.8904445,4.279995918273926,0.009070060324304317,1739502643.8904498,4.279995918273926,0.2124999188064242,1739502643.8904545,4.279995918273926,0.05573543161848481,1739502643.8904593,4.279995918273926,2.10916217849129,1739502643.8904655,4.279995918273926,0.0,1739502643.89047,4.279995918273926,-0.018289166085577957,1739502643.8904755,4.279995918273926,6.252972684245004,1739502643.8904808,4.279995918273926,2.127451344576868 +1739502643.9029617,4.2999958992004395,6.564888981594651,1739502643.9029703,4.2999958992004395,-0.2000764957973855,1739502643.9029806,4.2999958992004395,5.7265333452068425,1739502643.9029906,4.2999958992004395,11.975564132555624,1739502643.9029953,4.2999958992004395,-0.151,1739502643.9030015,4.2999958992004395,0.009070060324304317,1739502643.9030066,4.2999958992004395,0.2124999188064242,1739502643.9030113,4.2999958992004395,0.05573543161848481,1739502643.9030159,4.2999958992004395,2.10916217849129,1739502643.9030216,4.2999958992004395,0.0,1739502643.903027,4.2999958992004395,-0.018289166085577957,1739502643.903032,4.2999958992004395,6.252972684245004,1739502643.903037,4.2999958992004395,2.127451344576868 +1739502643.926654,4.309995889663696,6.564888981594651,1739502643.926663,4.309995889663696,-0.2000764957973855,1739502643.9266737,4.309995889663696,5.7265333452068425,1739502643.9266837,4.309995889663696,11.975564132555624,1739502643.9266882,4.309995889663696,-0.151,1739502643.9266946,4.309995889663696,0.009070060324304317,1739502643.9266996,4.309995889663696,0.2124999188064242,1739502643.9267044,4.309995889663696,0.05573543161848481,1739502643.9267092,4.309995889663696,2.10916217849129,1739502643.926715,4.309995889663696,0.0,1739502643.9267197,4.309995889663696,-0.018289166085577957,1739502643.926725,4.309995889663696,6.252972684245004,1739502643.92673,4.309995889663696,2.127451344576868 +1739502643.9466875,4.339995861053467,6.564888981594651,1739502643.9466994,4.339995861053467,-0.2000764957973855,1739502643.9467142,4.339995861053467,5.7265333452068425,1739502643.9467251,4.339995861053467,11.975564132555624,1739502643.9467287,4.339995861053467,-0.151,1739502643.9467332,4.339995861053467,0.009070060324304317,1739502643.9467368,4.339995861053467,0.2124999188064242,1739502643.946741,4.339995861053467,0.05573543161848481,1739502643.9467516,4.339995861053467,2.10916217849129,1739502643.9467578,4.339995861053467,0.0,1739502643.9467657,4.339995861053467,-0.018289166085577957,1739502643.946777,4.339995861053467,6.252972684245004,1739502643.9467847,4.339995861053467,2.127451344576868 +1739502643.9639776,4.3599958419799805,6.798704179917509,1739502643.9639802,4.3599958419799805,-0.20707088054905665,1739502643.963984,4.3599958419799805,5.976758364221622,1739502643.9639878,4.3599958419799805,12.221782383505456,1739502643.9639895,4.3599958419799805,-0.1524550993317131,1739502643.9639919,4.3599958419799805,0.010070652277695,1739502643.9639935,4.3599958419799805,0.21474613872115492,1739502643.9639955,4.3599958419799805,0.05606608581929086,1739502643.9639971,4.3599958419799805,2.1053754681529595,1739502643.9639995,4.3599958419799805,0.0,1739502643.9640012,4.3599958419799805,-0.02088841375768698,1739502643.9640033,4.3599958419799805,6.253649043556369,1739502643.9640052,4.3599958419799805,2.1254516164805497 +1739502643.982575,4.379995822906494,6.798704179917509,1739502643.9825773,4.379995822906494,-0.20707088054905665,1739502643.9825802,4.379995822906494,5.976758364221622,1739502643.9825828,4.379995822906494,12.221782383505456,1739502643.9825842,4.379995822906494,-0.1524550993317131,1739502643.982586,4.379995822906494,0.010070652277695,1739502643.9825873,4.379995822906494,0.21474613872115492,1739502643.982589,4.379995822906494,0.05606608581929086,1739502643.9825902,4.379995822906494,2.1053754681529595,1739502643.9825916,4.379995822906494,0.0,1739502643.982593,4.379995822906494,-0.020076148327590193,1739502643.9825945,4.379995822906494,6.253649043556369,1739502643.9825962,4.379995822906494,2.1254516164805497 +1739502644.0024278,4.399995803833008,6.798704179917509,1739502644.0024302,4.399995803833008,-0.20707088054905665,1739502644.002433,4.399995803833008,5.976758364221622,1739502644.0024357,4.399995803833008,12.221782383505456,1739502644.0024369,4.399995803833008,-0.1524550993317131,1739502644.0024383,4.399995803833008,0.010070652277695,1739502644.0024397,4.399995803833008,0.21474613872115492,1739502644.0024412,4.399995803833008,0.05606608581929086,1739502644.0024426,4.399995803833008,2.1053754681529595,1739502644.002444,4.399995803833008,0.0,1739502644.0024452,4.399995803833008,-0.020076148327590193,1739502644.002447,4.399995803833008,6.253649043556369,1739502644.002448,4.399995803833008,2.1254516164805497 +1739502644.0226343,4.4199957847595215,6.798704179917509,1739502644.022637,4.4199957847595215,-0.20707088054905665,1739502644.02264,4.4199957847595215,5.976758364221622,1739502644.0226424,4.4199957847595215,12.221782383505456,1739502644.0226438,4.4199957847595215,-0.1524550993317131,1739502644.0226455,4.4199957847595215,0.010070652277695,1739502644.0226471,4.4199957847595215,0.21474613872115492,1739502644.0226483,4.4199957847595215,0.05606608581929086,1739502644.0226495,4.4199957847595215,2.1053754681529595,1739502644.0226512,4.4199957847595215,0.0,1739502644.0226526,4.4199957847595215,-0.020076148327590193,1739502644.022654,4.4199957847595215,6.253649043556369,1739502644.022656,4.4199957847595215,2.1254516164805497 +1739502644.0425336,4.439995765686035,6.798704179917509,1739502644.0425363,4.439995765686035,-0.20707088054905665,1739502644.0425394,4.439995765686035,5.976758364221622,1739502644.0425417,4.439995765686035,12.221782383505456,1739502644.0425434,4.439995765686035,-0.1524550993317131,1739502644.042545,4.439995765686035,0.010070652277695,1739502644.0425467,4.439995765686035,0.21474613872115492,1739502644.042548,4.439995765686035,0.05606608581929086,1739502644.0425491,4.439995765686035,2.1053754681529595,1739502644.0425508,4.439995765686035,0.0,1739502644.042552,4.439995765686035,-0.020076148327590193,1739502644.0425537,4.439995765686035,6.253649043556369,1739502644.042555,4.439995765686035,2.1254516164805497 +1739502644.062708,4.459995746612549,6.798704179917509,1739502644.062711,4.459995746612549,-0.20707088054905665,1739502644.0627139,4.459995746612549,5.976758364221622,1739502644.0627167,4.459995746612549,12.221782383505456,1739502644.062718,4.459995746612549,-0.1524550993317131,1739502644.0627196,4.459995746612549,0.010070652277695,1739502644.062721,4.459995746612549,0.21474613872115492,1739502644.0627224,4.459995746612549,0.05606608581929086,1739502644.0627239,4.459995746612549,2.1053754681529595,1739502644.0627258,4.459995746612549,0.0,1739502644.0627272,4.459995746612549,-0.020076148327590193,1739502644.0627284,4.459995746612549,6.253649043556369,1739502644.06273,4.459995746612549,2.1254516164805497 +1739502644.0826836,4.4799957275390625,7.032292593177704,1739502644.082686,4.4799957275390625,-0.21389326060200275,1739502644.0826888,4.4799957275390625,6.208885022174687,1739502644.0826914,4.4799957275390625,12.449477714234202,1739502644.0826929,4.4799957275390625,-0.153,1739502644.0826948,4.4799957275390625,0.011240283416738182,1739502644.082696,4.4799957275390625,0.21678404450841865,1739502644.0826972,4.4799957275390625,0.056719782553635245,1739502644.0826986,4.4799957275390625,2.101945819152504,1739502644.0827,4.4799957275390625,0.0,1739502644.0827012,4.4799957275390625,-0.021843937146623613,1739502644.0827029,4.4799957275390625,6.254399592491855,1739502644.0827043,4.4799957275390625,2.1232373219309753 +1739502644.1028476,4.499995708465576,7.032292593177704,1739502644.1028495,4.499995708465576,-0.21389326060200275,1739502644.1028526,4.499995708465576,6.208885022174687,1739502644.1028554,4.499995708465576,12.449477714234202,1739502644.1028566,4.499995708465576,-0.153,1739502644.1028585,4.499995708465576,0.011240283416738182,1739502644.1028597,4.499995708465576,0.21678404450841865,1739502644.1028612,4.499995708465576,0.056719782553635245,1739502644.1028621,4.499995708465576,2.101945819152504,1739502644.1028636,4.499995708465576,0.0,1739502644.102865,4.499995708465576,-0.02129150277847147,1739502644.1028664,4.499995708465576,6.254399592491855,1739502644.1028676,4.499995708465576,2.1232373219309753 +1739502644.1225054,4.51999568939209,7.032292593177704,1739502644.1225078,4.51999568939209,-0.21389326060200275,1739502644.1225107,4.51999568939209,6.208885022174687,1739502644.1225133,4.51999568939209,12.449477714234202,1739502644.1225147,4.51999568939209,-0.153,1739502644.1225164,4.51999568939209,0.011240283416738182,1739502644.1225178,4.51999568939209,0.21678404450841865,1739502644.122519,4.51999568939209,0.056719782553635245,1739502644.1225202,4.51999568939209,2.101945819152504,1739502644.1225219,4.51999568939209,0.0,1739502644.1225233,4.51999568939209,-0.02129150277847147,1739502644.1225247,4.51999568939209,6.254399592491855,1739502644.122526,4.51999568939209,2.1232373219309753 +1739502644.142945,4.5399956703186035,7.032292593177704,1739502644.142947,4.5399956703186035,-0.21389326060200275,1739502644.1429498,4.5399956703186035,6.208885022174687,1739502644.1429524,4.5399956703186035,12.449477714234202,1739502644.1429536,4.5399956703186035,-0.153,1739502644.1429553,4.5399956703186035,0.011240283416738182,1739502644.1429565,4.5399956703186035,0.21678404450841865,1739502644.142958,4.5399956703186035,0.056719782553635245,1739502644.142959,4.5399956703186035,2.101945819152504,1739502644.1429605,4.5399956703186035,0.0,1739502644.142962,4.5399956703186035,-0.02129150277847147,1739502644.1429632,4.5399956703186035,6.254399592491855,1739502644.1429648,4.5399956703186035,2.1232373219309753 +1739502644.1638436,4.559995651245117,7.032292593177704,1739502644.1638474,4.559995651245117,-0.21389326060200275,1739502644.1638522,4.559995651245117,6.208885022174687,1739502644.163858,4.559995651245117,12.449477714234202,1739502644.163861,4.559995651245117,-0.153,1739502644.163865,4.559995651245117,0.011240283416738182,1739502644.1638687,4.559995651245117,0.21678404450841865,1739502644.1638725,4.559995651245117,0.056719782553635245,1739502644.163876,4.559995651245117,2.101945819152504,1739502644.1638799,4.559995651245117,0.0,1739502644.1638834,4.559995651245117,-0.02129150277847147,1739502644.163887,4.559995651245117,6.254399592491855,1739502644.1638906,4.559995651245117,2.1232373219309753 +1739502644.1839767,4.579995632171631,7.2656379834310965,1739502644.18398,4.579995632171631,-0.22053168588505034,1739502644.1839852,4.579995632171631,6.408571955940202,1739502644.1839905,4.579995632171631,12.644503086290456,1739502644.1839936,4.579995632171631,-0.15432885663324736,1739502644.1839976,4.579995632171631,0.012307333491577834,1739502644.1840012,4.579995632171631,0.21691455984368258,1739502644.1840048,4.579995632171631,0.05756380992177493,1739502644.1840084,4.579995632171631,2.101726361679095,1739502644.184012,4.579995632171631,0.0,1739502644.1840155,4.579995632171631,-0.018224297420048476,1739502644.1840196,4.579995632171631,6.255157560389752,1739502644.1840231,4.579995632171631,2.1209091614020936 +1739502644.211412,4.5999956130981445,7.2656379834310965,1739502644.2114248,4.5999956130981445,-0.22053168588505034,1739502644.2114415,4.5999956130981445,6.408571955940202,1739502644.211461,4.5999956130981445,12.644503086290456,1739502644.2114718,4.5999956130981445,-0.15432885663324736,1739502644.211486,4.5999956130981445,0.012307333491577834,1739502644.2114987,4.5999956130981445,0.21691455984368258,1739502644.2115114,4.5999956130981445,0.05756380992177493,1739502644.2115238,4.5999956130981445,2.101726361679095,1739502644.211537,4.5999956130981445,0.0,1739502644.2115498,4.5999956130981445,-0.019182799722998745,1739502644.2115624,4.5999956130981445,6.255157560389752,1739502644.2115753,4.5999956130981445,2.1209091614020936 +1739502644.2277067,4.619995594024658,7.2656379834310965,1739502644.227711,4.619995594024658,-0.22053168588505034,1739502644.2277172,4.619995594024658,6.408571955940202,1739502644.2277243,4.619995594024658,12.644503086290456,1739502644.2277281,4.619995594024658,-0.15432885663324736,1739502644.2277336,4.619995594024658,0.012307333491577834,1739502644.2277381,4.619995594024658,0.21691455984368258,1739502644.2277427,4.619995594024658,0.05756380992177493,1739502644.2277474,4.619995594024658,2.101726361679095,1739502644.2277522,4.619995594024658,0.0,1739502644.2277567,4.619995594024658,-0.019182799722998745,1739502644.2277615,4.619995594024658,6.255157560389752,1739502644.2277663,4.619995594024658,2.1209091614020936 +1739502644.2442465,4.639995574951172,7.2656379834310965,1739502644.24425,4.639995574951172,-0.22053168588505034,1739502644.2442544,4.639995574951172,6.408571955940202,1739502644.2442594,4.639995574951172,12.644503086290456,1739502644.244262,4.639995574951172,-0.15432885663324736,1739502644.2442656,4.639995574951172,0.012307333491577834,1739502644.2442687,4.639995574951172,0.21691455984368258,1739502644.2442718,4.639995574951172,0.05756380992177493,1739502644.2442749,4.639995574951172,2.101726361679095,1739502644.244278,4.639995574951172,0.0,1739502644.2442813,4.639995574951172,-0.019182799722998745,1739502644.2442844,4.639995574951172,6.255157560389752,1739502644.2442877,4.639995574951172,2.1209091614020936 +1739502644.2642074,4.6599955558776855,7.2656379834310965,1739502644.2642107,4.6599955558776855,-0.22053168588505034,1739502644.2642148,4.6599955558776855,6.408571955940202,1739502644.2642193,4.6599955558776855,12.644503086290456,1739502644.264222,4.6599955558776855,-0.15432885663324736,1739502644.2642255,4.6599955558776855,0.012307333491577834,1739502644.2642286,4.6599955558776855,0.21691455984368258,1739502644.2642317,4.6599955558776855,0.05756380992177493,1739502644.2642345,4.6599955558776855,2.101726361679095,1739502644.2642379,4.6599955558776855,0.0,1739502644.264241,4.6599955558776855,-0.019182799722998745,1739502644.264244,4.6599955558776855,6.255157560389752,1739502644.264247,4.6599955558776855,2.1209091614020936 +1739502644.2839303,4.679995536804199,7.2656379834310965,1739502644.2839336,4.679995536804199,-0.22053168588505034,1739502644.283938,4.679995536804199,6.408571955940202,1739502644.2839432,4.679995536804199,12.644503086290456,1739502644.2839458,4.679995536804199,-0.15432885663324736,1739502644.2839494,4.679995536804199,0.012307333491577834,1739502644.2839527,4.679995536804199,0.21691455984368258,1739502644.283956,4.679995536804199,0.05756380992177493,1739502644.2839592,4.679995536804199,2.101726361679095,1739502644.2839622,4.679995536804199,0.0,1739502644.2839656,4.679995536804199,-0.019182799722998745,1739502644.283969,4.679995536804199,6.255157560389752,1739502644.2839723,4.679995536804199,2.1209091614020936 +1739502644.3037806,4.699995517730713,7.498745235178198,1739502644.3037837,4.699995517730713,-0.22698650765050665,1739502644.3037882,4.699995517730713,6.941762970837709,1739502644.303793,4.699995517730713,13.173519302650336,1739502644.3037953,4.699995517730713,-0.157,1739502644.3037992,4.699995517730713,0.01233229002734548,1739502644.303802,4.699995517730713,0.22469114192905285,1739502644.303805,4.699995517730713,0.05357199287665603,1739502644.3038082,4.699995517730713,2.0886915521692133,1739502644.3038113,4.699995517730713,0.0,1739502644.3038144,4.699995517730713,-0.035115060773246325,1739502644.3038175,4.699995517730713,6.255915528287648,1739502644.3038206,4.699995517730713,2.1188277780998788 +1739502644.3238275,4.719995498657227,7.498745235178198,1739502644.3238313,4.719995498657227,-0.22698650765050665,1739502644.3238354,4.719995498657227,6.941762970837709,1739502644.3238401,4.719995498657227,13.173519302650336,1739502644.3238428,4.719995498657227,-0.157,1739502644.323846,4.719995498657227,0.01233229002734548,1739502644.3238494,4.719995498657227,0.22469114192905285,1739502644.3238525,4.719995498657227,0.05357199287665603,1739502644.3238556,4.719995498657227,2.0886915521692133,1739502644.3238587,4.719995498657227,0.0,1739502644.3238618,4.719995498657227,-0.03013622593066545,1739502644.3238652,4.719995498657227,6.255915528287648,1739502644.3238683,4.719995498657227,2.1188277780998788 +1739502644.3441956,4.73999547958374,7.498745235178198,1739502644.3441987,4.73999547958374,-0.22698650765050665,1739502644.344203,4.73999547958374,6.941762970837709,1739502644.3442082,4.73999547958374,13.173519302650336,1739502644.3442106,4.73999547958374,-0.157,1739502644.3442144,4.73999547958374,0.01233229002734548,1739502644.3442175,4.73999547958374,0.22469114192905285,1739502644.3442209,4.73999547958374,0.05357199287665603,1739502644.3442242,4.73999547958374,2.0886915521692133,1739502644.3442273,4.73999547958374,0.0,1739502644.3442307,4.73999547958374,-0.03013622593066545,1739502644.344234,4.73999547958374,6.255915528287648,1739502644.3442373,4.73999547958374,2.1188277780998788 +1739502644.363713,4.759995460510254,7.498745235178198,1739502644.3637164,4.759995460510254,-0.22698650765050665,1739502644.3637207,4.759995460510254,6.941762970837709,1739502644.363726,4.759995460510254,13.173519302650336,1739502644.3637285,4.759995460510254,-0.157,1739502644.3637323,4.759995460510254,0.01233229002734548,1739502644.3637354,4.759995460510254,0.22469114192905285,1739502644.3637385,4.759995460510254,0.05357199287665603,1739502644.3637419,4.759995460510254,2.0886915521692133,1739502644.3637452,4.759995460510254,0.0,1739502644.3637483,4.759995460510254,-0.03013622593066545,1739502644.3637516,4.759995460510254,6.255915528287648,1739502644.363755,4.759995460510254,2.1188277780998788 +1739502644.383596,4.779995441436768,7.498745235178198,1739502644.3835993,4.779995441436768,-0.22698650765050665,1739502644.3836038,4.779995441436768,6.941762970837709,1739502644.3836088,4.779995441436768,13.173519302650336,1739502644.3836114,4.779995441436768,-0.157,1739502644.383615,4.779995441436768,0.01233229002734548,1739502644.3836184,4.779995441436768,0.22469114192905285,1739502644.3836217,4.779995441436768,0.05357199287665603,1739502644.3836248,4.779995441436768,2.0886915521692133,1739502644.3836281,4.779995441436768,0.0,1739502644.3836315,4.779995441436768,-0.03013622593066545,1739502644.3836348,4.779995441436768,6.255915528287648,1739502644.383638,4.779995441436768,2.1188277780998788 +1739502644.4113104,4.799995422363281,7.731569238083926,1739502644.411323,4.799995422363281,-0.23325689011528006,1739502644.41134,4.799995422363281,6.955738681394517,1739502644.41136,4.799995422363281,13.18091884371748,1739502644.411371,4.799995422363281,-0.157,1739502644.411385,4.799995422363281,0.01399284658570403,1739502644.411398,4.799995422363281,0.22068529515644425,1739502644.4114103,4.799995422363281,0.057056859965651685,1739502644.4114232,4.799995422363281,2.095395871672702,1739502644.4114363,4.799995422363281,0.0,1739502644.4114492,4.799995422363281,-0.015601815419695318,1739502644.4114618,4.799995422363281,6.256673496185545,1739502644.411475,4.799995422363281,2.1155396933550468 +1739502644.4278605,4.809995412826538,7.731569238083926,1739502644.4278662,4.809995412826538,-0.23325689011528006,1739502644.4278736,4.809995412826538,6.955738681394517,1739502644.4278817,4.809995412826538,13.18091884371748,1739502644.4278862,4.809995412826538,-0.157,1739502644.4278924,4.809995412826538,0.01399284658570403,1739502644.427898,4.809995412826538,0.22068529515644425,1739502644.4279034,4.809995412826538,0.057056859965651685,1739502644.427909,4.809995412826538,2.095395871672702,1739502644.4279144,4.809995412826538,0.0,1739502644.4279199,4.809995412826538,-0.020143821682344853,1739502644.4279253,4.809995412826538,6.256673496185545,1739502644.4279308,4.809995412826538,2.1155396933550468 +1739502644.444393,4.839995384216309,7.731569238083926,1739502644.444396,4.839995384216309,-0.23325689011528006,1739502644.4443994,4.839995384216309,6.955738681394517,1739502644.4444022,4.839995384216309,13.18091884371748,1739502644.4444034,4.839995384216309,-0.157,1739502644.4444053,4.839995384216309,0.01399284658570403,1739502644.4444067,4.839995384216309,0.22068529515644425,1739502644.4444087,4.839995384216309,0.057056859965651685,1739502644.4444098,4.839995384216309,2.095395871672702,1739502644.4444113,4.839995384216309,0.0,1739502644.4444127,4.839995384216309,-0.020143821682344853,1739502644.4444141,4.839995384216309,6.256673496185545,1739502644.4444158,4.839995384216309,2.1155396933550468 +1739502644.4640129,4.859995365142822,7.731569238083926,1739502644.464016,4.859995365142822,-0.23325689011528006,1739502644.4640193,4.859995365142822,6.955738681394517,1739502644.4640222,4.859995365142822,13.18091884371748,1739502644.464024,4.859995365142822,-0.157,1739502644.4640262,4.859995365142822,0.01399284658570403,1739502644.4640281,4.859995365142822,0.22068529515644425,1739502644.4640298,4.859995365142822,0.057056859965651685,1739502644.4640312,4.859995365142822,2.095395871672702,1739502644.4640334,4.859995365142822,0.0,1739502644.4640348,4.859995365142822,-0.020143821682344853,1739502644.4640365,4.859995365142822,6.256673496185545,1739502644.464038,4.859995365142822,2.1155396933550468 +1739502644.484164,4.879995346069336,7.731569238083926,1739502644.4841664,4.879995346069336,-0.23325689011528006,1739502644.484169,4.879995346069336,6.955738681394517,1739502644.4841716,4.879995346069336,13.18091884371748,1739502644.4841728,4.879995346069336,-0.157,1739502644.4841745,4.879995346069336,0.01399284658570403,1739502644.484176,4.879995346069336,0.22068529515644425,1739502644.484177,4.879995346069336,0.057056859965651685,1739502644.4841785,4.879995346069336,2.095395871672702,1739502644.48418,4.879995346069336,0.0,1739502644.4841812,4.879995346069336,-0.020143821682344853,1739502644.4841826,4.879995346069336,6.256673496185545,1739502644.4841838,4.879995346069336,2.1155396933550468 +1739502644.5043588,4.89999532699585,7.731569238083926,1739502644.5043616,4.89999532699585,-0.23325689011528006,1739502644.5043662,4.89999532699585,6.955738681394517,1739502644.504371,4.89999532699585,13.18091884371748,1739502644.5043738,4.89999532699585,-0.157,1739502644.5043774,4.89999532699585,0.01399284658570403,1739502644.5043805,4.89999532699585,0.22068529515644425,1739502644.5043838,4.89999532699585,0.057056859965651685,1739502644.5043871,4.89999532699585,2.095395871672702,1739502644.5043905,4.89999532699585,0.0,1739502644.5043938,4.89999532699585,-0.020143821682344853,1739502644.504397,4.89999532699585,6.256673496185545,1739502644.5044,4.89999532699585,2.1155396933550468 +1739502644.5240657,4.919995307922363,7.964093006505637,1739502644.5240679,4.919995307922363,-0.23934280888091575,1739502644.5240705,4.919995307922363,7.283932910823044,1739502644.524073,4.919995307922363,13.50478488064978,1739502644.5240743,4.919995307922363,-0.159,1739502644.5240757,4.919995307922363,0.014499484962345252,1739502644.524077,4.919995307922363,0.22299450205148594,1739502644.5240784,4.919995307922363,0.05576812467874796,1739502644.5240796,4.919995307922363,2.091528482937101,1739502644.5240812,4.919995307922363,0.0,1739502644.5240824,4.919995307922363,-0.022626394581131064,1739502644.5240839,4.919995307922363,6.257431464083442,1739502644.5240855,4.919995307922363,2.113379072978704 +1739502644.5455108,4.939995288848877,7.964093006505637,1739502644.5455136,4.939995288848877,-0.23934280888091575,1739502644.5455182,4.939995288848877,7.283932910823044,1739502644.5455232,4.939995288848877,13.50478488064978,1739502644.5455258,4.939995288848877,-0.159,1739502644.5455294,4.939995288848877,0.014499484962345252,1739502644.5455327,4.939995288848877,0.22299450205148594,1739502644.545536,4.939995288848877,0.05576812467874796,1739502644.5455391,4.939995288848877,2.091528482937101,1739502644.5455425,4.939995288848877,0.0,1739502644.5455458,4.939995288848877,-0.02185059004160328,1739502644.5455492,4.939995288848877,6.257431464083442,1739502644.5455525,4.939995288848877,2.113379072978704 +1739502644.5643494,4.959995269775391,7.964093006505637,1739502644.5643523,4.959995269775391,-0.23934280888091575,1739502644.5643556,4.959995269775391,7.283932910823044,1739502644.564359,4.959995269775391,13.50478488064978,1739502644.5643604,4.959995269775391,-0.159,1739502644.5643625,4.959995269775391,0.014499484962345252,1739502644.564364,4.959995269775391,0.22299450205148594,1739502644.5643656,4.959995269775391,0.05576812467874796,1739502644.564367,4.959995269775391,2.091528482937101,1739502644.564369,4.959995269775391,0.0,1739502644.5643704,4.959995269775391,-0.02185059004160328,1739502644.564372,4.959995269775391,6.257431464083442,1739502644.5643735,4.959995269775391,2.113379072978704 +1739502644.5846045,4.979995250701904,7.964093006505637,1739502644.584609,4.979995250701904,-0.23934280888091575,1739502644.584615,4.979995250701904,7.283932910823044,1739502644.584622,4.979995250701904,13.50478488064978,1739502644.5846257,4.979995250701904,-0.159,1739502644.5846305,4.979995250701904,0.014499484962345252,1739502644.584635,4.979995250701904,0.22299450205148594,1739502644.5846395,4.979995250701904,0.05576812467874796,1739502644.5846438,4.979995250701904,2.091528482937101,1739502644.5846481,4.979995250701904,0.0,1739502644.584653,4.979995250701904,-0.02185059004160328,1739502644.5846572,4.979995250701904,6.257431464083442,1739502644.5846617,4.979995250701904,2.113379072978704 +1739502644.604714,4.999995231628418,7.964093006505637,1739502644.6047168,4.999995231628418,-0.23934280888091575,1739502644.6047204,4.999995231628418,7.283932910823044,1739502644.604724,4.999995231628418,13.50478488064978,1739502644.6047258,4.999995231628418,-0.159,1739502644.6047277,4.999995231628418,0.014499484962345252,1739502644.6047297,4.999995231628418,0.22299450205148594,1739502644.6047313,4.999995231628418,0.05576812467874796,1739502644.604733,4.999995231628418,2.091528482937101,1739502644.604735,4.999995231628418,0.0,1739502644.6047368,4.999995231628418,-0.02185059004160328,1739502644.6047385,4.999995231628418,6.257431464083442,1739502644.6047404,4.999995231628418,2.113379072978704 +1739502644.625246,5.019995212554932,8.196370433155991,1739502644.6252494,5.019995212554932,-0.24524610559101578,1739502644.625254,5.019995212554932,7.30739883421144,1739502644.6252575,5.019995212554932,13.523472769899588,1739502644.6252592,5.019995212554932,-0.159,1739502644.6252618,5.019995212554932,0.016188645490771484,1739502644.625264,5.019995212554932,0.21936088379263605,1739502644.6252654,5.019995212554932,0.059342775736297676,1739502644.6252675,5.019995212554932,2.0976171811191833,1739502644.6252697,5.019995212554932,0.0,1739502644.6252713,5.019995212554932,-0.009519364182787652,1739502644.6252732,5.019995212554932,6.258189431981339,1739502644.6252756,5.019995212554932,2.1109900559094092 +1739502644.6446164,5.039995193481445,8.196370433155991,1739502644.6446192,5.039995193481445,-0.24524610559101578,1739502644.6446228,5.039995193481445,7.30739883421144,1739502644.6446264,5.039995193481445,13.523472769899588,1739502644.644628,5.039995193481445,-0.159,1739502644.64463,5.039995193481445,0.016188645490771484,1739502644.6446319,5.039995193481445,0.21936088379263605,1739502644.6446338,5.039995193481445,0.059342775736297676,1739502644.6446354,5.039995193481445,2.0976171811191833,1739502644.6446373,5.039995193481445,0.0,1739502644.644639,5.039995193481445,-0.013372874790225975,1739502644.644641,5.039995193481445,6.258189431981339,1739502644.6446428,5.039995193481445,2.1109900559094092 +1739502644.6646316,5.059995174407959,8.196370433155991,1739502644.664636,5.059995174407959,-0.24524610559101578,1739502644.664642,5.059995174407959,7.30739883421144,1739502644.664649,5.059995174407959,13.523472769899588,1739502644.6646526,5.059995174407959,-0.159,1739502644.6646574,5.059995174407959,0.016188645490771484,1739502644.6646621,5.059995174407959,0.21936088379263605,1739502644.6646664,5.059995174407959,0.059342775736297676,1739502644.6646807,5.059995174407959,2.0976171811191833,1739502644.6646833,5.059995174407959,0.0,1739502644.664685,5.059995174407959,-0.013372874790225975,1739502644.664687,5.059995174407959,6.258189431981339,1739502644.6646886,5.059995174407959,2.1109900559094092 +1739502644.6846297,5.079995155334473,8.196370433155991,1739502644.6846342,5.079995155334473,-0.24524610559101578,1739502644.68464,5.079995155334473,7.30739883421144,1739502644.6846468,5.079995155334473,13.523472769899588,1739502644.6846507,5.079995155334473,-0.159,1739502644.6846557,5.079995155334473,0.016188645490771484,1739502644.68466,5.079995155334473,0.21936088379263605,1739502644.6846645,5.079995155334473,0.059342775736297676,1739502644.684669,5.079995155334473,2.0976171811191833,1739502644.6846836,5.079995155334473,0.0,1739502644.6846855,5.079995155334473,-0.013372874790225975,1739502644.6846874,5.079995155334473,6.258189431981339,1739502644.684689,5.079995155334473,2.1109900559094092 +1739502644.7045672,5.099995136260986,8.196370433155991,1739502644.70457,5.099995136260986,-0.24524610559101578,1739502644.7045736,5.099995136260986,7.30739883421144,1739502644.7045772,5.099995136260986,13.523472769899588,1739502644.704579,5.099995136260986,-0.159,1739502644.704581,5.099995136260986,0.016188645490771484,1739502644.7045832,5.099995136260986,0.21936088379263605,1739502644.704585,5.099995136260986,0.059342775736297676,1739502644.7045865,5.099995136260986,2.0976171811191833,1739502644.7045887,5.099995136260986,0.0,1739502644.70459,5.099995136260986,-0.013372874790225975,1739502644.7045922,5.099995136260986,6.258189431981339,1739502644.704594,5.099995136260986,2.1109900559094092 +1739502644.725649,5.1199951171875,8.196370433155991,1739502644.7256525,5.1199951171875,-0.24524610559101578,1739502644.7256563,5.1199951171875,7.30739883421144,1739502644.7256594,5.1199951171875,13.523472769899588,1739502644.7256613,5.1199951171875,-0.159,1739502644.7256632,5.1199951171875,0.016188645490771484,1739502644.725665,5.1199951171875,0.21936088379263605,1739502644.7256668,5.1199951171875,0.059342775736297676,1739502644.7256684,5.1199951171875,2.0976171811191833,1739502644.7256703,5.1199951171875,0.0,1739502644.7256722,5.1199951171875,-0.013372874790225975,1739502644.725674,5.1199951171875,6.258189431981339,1739502644.725676,5.1199951171875,2.1109900559094092 +1739502644.7458823,5.139995098114014,8.428442919754117,1739502644.7458854,5.139995098114014,-0.25096111235751195,1739502644.7458892,5.139995098114014,7.69748865695159,1739502644.745893,5.139995098114014,13.910782457875488,1739502644.7458947,5.139995098114014,-0.16,1739502644.745897,5.139995098114014,0.01659013755268527,1739502644.7458985,5.139995098114014,0.22339455727393673,1739502644.7459006,5.139995098114014,0.05705977276026293,1739502644.745902,5.139995098114014,2.0908592085274997,1739502644.7459042,5.139995098114014,0.0,1739502644.7459056,5.139995098114014,-0.021183957199021036,1739502644.7459075,5.139995098114014,6.259021738184658,1739502644.7459095,5.139995098114014,2.109602200873351 +1739502644.765435,5.159995079040527,8.428442919754117,1739502644.7654378,5.159995079040527,-0.25096111235751195,1739502644.7654414,5.159995079040527,7.69748865695159,1739502644.7654448,5.159995079040527,13.910782457875488,1739502644.7654467,5.159995079040527,-0.16,1739502644.7654488,5.159995079040527,0.01659013755268527,1739502644.7654505,5.159995079040527,0.22339455727393673,1739502644.7654524,5.159995079040527,0.05705977276026293,1739502644.7654538,5.159995079040527,2.0908592085274997,1739502644.765456,5.159995079040527,0.0,1739502644.7654576,5.159995079040527,-0.018742992345851306,1739502644.7654595,5.159995079040527,6.259021738184658,1739502644.7654612,5.159995079040527,2.109602200873351 +1739502644.7853045,5.179995059967041,8.428442919754117,1739502644.7853076,5.179995059967041,-0.25096111235751195,1739502644.7853115,5.179995059967041,7.69748865695159,1739502644.7853148,5.179995059967041,13.910782457875488,1739502644.7853167,5.179995059967041,-0.16,1739502644.7853189,5.179995059967041,0.01659013755268527,1739502644.7853208,5.179995059967041,0.22339455727393673,1739502644.7853222,5.179995059967041,0.05705977276026293,1739502644.785324,5.179995059967041,2.0908592085274997,1739502644.785326,5.179995059967041,0.0,1739502644.7853277,5.179995059967041,-0.018742992345851306,1739502644.7853296,5.179995059967041,6.259021738184658,1739502644.7853317,5.179995059967041,2.109602200873351 +1739502644.8053737,5.199995040893555,8.428442919754117,1739502644.8053768,5.199995040893555,-0.25096111235751195,1739502644.8053806,5.199995040893555,7.69748865695159,1739502644.8053844,5.199995040893555,13.910782457875488,1739502644.8053863,5.199995040893555,-0.16,1739502644.8053882,5.199995040893555,0.01659013755268527,1739502644.8053901,5.199995040893555,0.22339455727393673,1739502644.8053918,5.199995040893555,0.05705977276026293,1739502644.8053935,5.199995040893555,2.0908592085274997,1739502644.8053954,5.199995040893555,0.0,1739502644.8053973,5.199995040893555,-0.018742992345851306,1739502644.805399,5.199995040893555,6.259021738184658,1739502644.805401,5.199995040893555,2.109602200873351 +1739502644.8265033,5.219995021820068,8.428442919754117,1739502644.8265076,5.219995021820068,-0.25096111235751195,1739502644.826514,5.219995021820068,7.69748865695159,1739502644.826521,5.219995021820068,13.910782457875488,1739502644.8265245,5.219995021820068,-0.16,1739502644.8265295,5.219995021820068,0.01659013755268527,1739502644.8265338,5.219995021820068,0.22339455727393673,1739502644.8265383,5.219995021820068,0.05705977276026293,1739502644.8265426,5.219995021820068,2.0908592085274997,1739502644.8265471,5.219995021820068,0.0,1739502644.8265514,5.219995021820068,-0.018742992345851306,1739502644.8265562,5.219995021820068,6.259021738184658,1739502644.8265607,5.219995021820068,2.109602200873351 +1739502644.8467653,5.239995002746582,8.660332101796328,1739502644.8467696,5.239995002746582,-0.25647692627286833,1739502644.8467755,5.239995002746582,8.091849450626789,1739502644.8467824,5.239995002746582,14.301042759350198,1739502644.8467863,5.239995002746582,-0.162,1739502644.8467915,5.239995002746582,0.016747551658780183,1739502644.8467958,5.239995002746582,0.22600227218898358,1739502644.8468003,5.239995002746582,0.054530154695777475,1739502644.8468046,5.239995002746582,2.0865018633986856,1739502644.8468094,5.239995002746582,0.0,1739502644.8468137,5.239995002746582,-0.022104637244850223,1739502644.8468182,5.239995002746582,6.25986147821852,1739502644.846823,5.239995002746582,2.1075559859238275 +1739502644.8726451,5.259994983673096,8.660332101796328,1739502644.8726528,5.259994983673096,-0.25647692627286833,1739502644.8726623,5.259994983673096,8.091849450626789,1739502644.8726885,5.259994983673096,14.301042759350198,1739502644.8726962,5.259994983673096,-0.162,1739502644.8727047,5.259994983673096,0.016747551658780183,1739502644.872712,5.259994983673096,0.22600227218898358,1739502644.8727193,5.259994983673096,0.054530154695777475,1739502644.8727262,5.259994983673096,2.0865018633986856,1739502644.8727336,5.259994983673096,0.0,1739502644.8727407,5.259994983673096,-0.02105412252514194,1739502644.8727484,5.259994983673096,6.25986147821852,1739502644.8727555,5.259994983673096,2.1075559859238275 +1739502644.886667,5.279994964599609,8.660332101796328,1739502644.8866718,5.279994964599609,-0.25647692627286833,1739502644.8866785,5.279994964599609,8.091849450626789,1739502644.8866858,5.279994964599609,14.301042759350198,1739502644.8866901,5.279994964599609,-0.162,1739502644.8866954,5.279994964599609,0.016747551658780183,1739502644.8867,5.279994964599609,0.22600227218898358,1739502644.886705,5.279994964599609,0.054530154695777475,1739502644.8867097,5.279994964599609,2.0865018633986856,1739502644.8867147,5.279994964599609,0.0,1739502644.8867195,5.279994964599609,-0.02105412252514194,1739502644.8867242,5.279994964599609,6.25986147821852,1739502644.8867292,5.279994964599609,2.1075559859238275 +1739502644.9058268,5.299994945526123,8.660332101796328,1739502644.9058304,5.299994945526123,-0.25647692627286833,1739502644.9058344,5.299994945526123,8.091849450626789,1739502644.9058394,5.299994945526123,14.301042759350198,1739502644.9058418,5.299994945526123,-0.162,1739502644.9058452,5.299994945526123,0.016747551658780183,1739502644.9058483,5.299994945526123,0.22600227218898358,1739502644.9058514,5.299994945526123,0.054530154695777475,1739502644.9058545,5.299994945526123,2.0865018633986856,1739502644.9058578,5.299994945526123,0.0,1739502644.905861,5.299994945526123,-0.02105412252514194,1739502644.905864,5.299994945526123,6.25986147821852,1739502644.9058673,5.299994945526123,2.1075559859238275 +1739502644.9264066,5.319994926452637,8.660332101796328,1739502644.9264097,5.319994926452637,-0.25647692627286833,1739502644.9264143,5.319994926452637,8.091849450626789,1739502644.926419,5.319994926452637,14.301042759350198,1739502644.9264214,5.319994926452637,-0.162,1739502644.926425,5.319994926452637,0.016747551658780183,1739502644.926428,5.319994926452637,0.22600227218898358,1739502644.9264312,5.319994926452637,0.054530154695777475,1739502644.9264343,5.319994926452637,2.0865018633986856,1739502644.9264376,5.319994926452637,0.0,1739502644.9264407,5.319994926452637,-0.02105412252514194,1739502644.9264438,5.319994926452637,6.25986147821852,1739502644.926447,5.319994926452637,2.1075559859238275 +1739502644.9456553,5.33999490737915,8.660332101796328,1739502644.9456587,5.33999490737915,-0.25647692627286833,1739502644.9456632,5.33999490737915,8.091849450626789,1739502644.9456685,5.33999490737915,14.301042759350198,1739502644.945671,5.33999490737915,-0.162,1739502644.945675,5.33999490737915,0.016747551658780183,1739502644.9456782,5.33999490737915,0.22600227218898358,1739502644.9456816,5.33999490737915,0.054530154695777475,1739502644.945685,5.33999490737915,2.0865018633986856,1739502644.9456882,5.33999490737915,0.0,1739502644.9456916,5.33999490737915,-0.02105412252514194,1739502644.945695,5.33999490737915,6.25986147821852,1739502644.9456985,5.33999490737915,2.1075559859238275 +1739502644.9658186,5.359994888305664,8.891983971707562,1739502644.965822,5.359994888305664,-0.2617924637860307,1739502644.9658265,5.359994888305664,8.11571490876516,1739502644.965832,5.359994888305664,14.320235079813838,1739502644.9658349,5.359994888305664,-0.162,1739502644.9658387,5.359994888305664,0.018381836406777013,1739502644.9658422,5.359994888305664,0.22180623813934572,1739502644.9658456,5.359994888305664,0.05778493778169059,1739502644.965849,5.359994888305664,2.0935176585075137,1739502644.9658525,5.359994888305664,0.0,1739502644.965856,5.359994888305664,-0.007450680003807038,1739502644.9658594,5.359994888305664,6.260701218252381,1739502644.965863,5.359994888305664,2.105219417086462 +1739502644.9862227,5.379994869232178,8.891983971707562,1739502644.986226,5.379994869232178,-0.2617924637860307,1739502644.986231,5.379994869232178,8.11571490876516,1739502644.986236,5.379994869232178,14.320235079813838,1739502644.986239,5.379994869232178,-0.162,1739502644.986243,5.379994869232178,0.018381836406777013,1739502644.9862466,5.379994869232178,0.22180623813934572,1739502644.98625,5.379994869232178,0.05778493778169059,1739502644.9862533,5.379994869232178,2.0935176585075137,1739502644.9862566,5.379994869232178,0.0,1739502644.9862602,5.379994869232178,-0.011701758578948507,1739502644.9862638,5.379994869232178,6.260701218252381,1739502644.986267,5.379994869232178,2.105219417086462 +1739502645.0133398,5.399994850158691,8.891983971707562,1739502645.013347,5.399994850158691,-0.2617924637860307,1739502645.0133557,5.399994850158691,8.11571490876516,1739502645.0133665,5.399994850158691,14.320235079813838,1739502645.0133724,5.399994850158691,-0.162,1739502645.0133798,5.399994850158691,0.018381836406777013,1739502645.0133865,5.399994850158691,0.22180623813934572,1739502645.0133932,5.399994850158691,0.05778493778169059,1739502645.0133998,5.399994850158691,2.0935176585075137,1739502645.0134068,5.399994850158691,0.0,1739502645.0134137,5.399994850158691,-0.011701758578948507,1739502645.0134206,5.399994850158691,6.260701218252381,1739502645.0134273,5.399994850158691,2.105219417086462 +1739502645.0265703,5.419994831085205,8.891983971707562,1739502645.026575,5.419994831085205,-0.2617924637860307,1739502645.0265813,5.419994831085205,8.11571490876516,1739502645.0265884,5.419994831085205,14.320235079813838,1739502645.0265923,5.419994831085205,-0.162,1739502645.0265973,5.419994831085205,0.018381836406777013,1739502645.0266023,5.419994831085205,0.22180623813934572,1739502645.0266068,5.419994831085205,0.05778493778169059,1739502645.026611,5.419994831085205,2.0935176585075137,1739502645.026616,5.419994831085205,0.0,1739502645.0266206,5.419994831085205,-0.011701758578948507,1739502645.0266254,5.419994831085205,6.260701218252381,1739502645.0266302,5.419994831085205,2.105219417086462 +1739502645.0459998,5.439994812011719,8.891983971707562,1739502645.046003,5.439994812011719,-0.2617924637860307,1739502645.0460076,5.439994812011719,8.11571490876516,1739502645.0460122,5.439994812011719,14.320235079813838,1739502645.0460148,5.439994812011719,-0.162,1739502645.0460184,5.439994812011719,0.018381836406777013,1739502645.0460215,5.439994812011719,0.22180623813934572,1739502645.0460246,5.439994812011719,0.05778493778169059,1739502645.0460274,5.439994812011719,2.0935176585075137,1739502645.0460308,5.439994812011719,0.0,1739502645.0460339,5.439994812011719,-0.011701758578948507,1739502645.0460372,5.439994812011719,6.260701218252381,1739502645.0460403,5.439994812011719,2.105219417086462 +1739502645.0685174,5.459994792938232,9.123435475612741,1739502645.0685232,5.459994792938232,-0.26690893757825407,1739502645.068531,5.459994792938232,8.421010255346957,1739502645.0685399,5.459994792938232,14.622955140256037,1739502645.0685449,5.459994792938232,-0.16210186233763532,1739502645.068551,5.459994792938232,0.019055189573895803,1739502645.0685568,5.459994792938232,0.22380675479346285,1739502645.0685625,5.459994792938232,0.05680352467774418,1739502645.068568,5.459994792938232,2.090169844611838,1739502645.068574,5.459994792938232,0.0,1739502645.06858,5.459994792938232,-0.014698641950024096,1739502645.0685856,5.459994792938232,6.261540958286242,1739502645.0685916,5.459994792938232,2.1039319598943664 +1739502645.086151,5.479994773864746,9.123435475612741,1739502645.0861554,5.479994773864746,-0.26690893757825407,1739502645.0861607,5.479994773864746,8.421010255346957,1739502645.086166,5.479994773864746,14.622955140256037,1739502645.0861692,5.479994773864746,-0.16210186233763532,1739502645.0861735,5.479994773864746,0.019055189573895803,1739502645.0861773,5.479994773864746,0.22380675479346285,1739502645.086181,5.479994773864746,0.05680352467774418,1739502645.0861845,5.479994773864746,2.090169844611838,1739502645.086188,5.479994773864746,0.0,1739502645.086192,5.479994773864746,-0.013762115282528242,1739502645.0861955,5.479994773864746,6.261540958286242,1739502645.0861995,5.479994773864746,2.1039319598943664 +1739502645.1059213,5.49999475479126,9.123435475612741,1739502645.1059244,5.49999475479126,-0.26690893757825407,1739502645.1059282,5.49999475479126,8.421010255346957,1739502645.105933,5.49999475479126,14.622955140256037,1739502645.1059356,5.49999475479126,-0.16210186233763532,1739502645.105939,5.49999475479126,0.019055189573895803,1739502645.1059422,5.49999475479126,0.22380675479346285,1739502645.1059453,5.49999475479126,0.05680352467774418,1739502645.1059482,5.49999475479126,2.090169844611838,1739502645.1059515,5.49999475479126,0.0,1739502645.1059544,5.49999475479126,-0.013762115282528242,1739502645.1059577,5.49999475479126,6.261540958286242,1739502645.1059606,5.49999475479126,2.1039319598943664 +1739502645.1260774,5.519994735717773,9.123435475612741,1739502645.1260805,5.519994735717773,-0.26690893757825407,1739502645.1260846,5.519994735717773,8.421010255346957,1739502645.1260893,5.519994735717773,14.622955140256037,1739502645.126092,5.519994735717773,-0.16210186233763532,1739502645.1260953,5.519994735717773,0.019055189573895803,1739502645.1260984,5.519994735717773,0.22380675479346285,1739502645.1261015,5.519994735717773,0.05680352467774418,1739502645.1261046,5.519994735717773,2.090169844611838,1739502645.1261077,5.519994735717773,0.0,1739502645.1261108,5.519994735717773,-0.013762115282528242,1739502645.126114,5.519994735717773,6.261540958286242,1739502645.1261168,5.519994735717773,2.1039319598943664 +1739502645.1457443,5.539994716644287,9.123435475612741,1739502645.1457474,5.539994716644287,-0.26690893757825407,1739502645.1457515,5.539994716644287,8.421010255346957,1739502645.1457562,5.539994716644287,14.622955140256037,1739502645.1457586,5.539994716644287,-0.16210186233763532,1739502645.1457622,5.539994716644287,0.019055189573895803,1739502645.1457653,5.539994716644287,0.22380675479346285,1739502645.1457684,5.539994716644287,0.05680352467774418,1739502645.1457713,5.539994716644287,2.090169844611838,1739502645.1457744,5.539994716644287,0.0,1739502645.1457775,5.539994716644287,-0.013762115282528242,1739502645.1457806,5.539994716644287,6.261540958286242,1739502645.145784,5.539994716644287,2.1039319598943664 +1739502645.1657982,5.559994697570801,9.123435475612741,1739502645.1658015,5.559994697570801,-0.26690893757825407,1739502645.165806,5.559994697570801,8.421010255346957,1739502645.1658113,5.559994697570801,14.622955140256037,1739502645.165814,5.559994697570801,-0.16210186233763532,1739502645.1658177,5.559994697570801,0.019055189573895803,1739502645.165821,5.559994697570801,0.22380675479346285,1739502645.1658244,5.559994697570801,0.05680352467774418,1739502645.1658275,5.559994697570801,2.090169844611838,1739502645.165831,5.559994697570801,0.0,1739502645.1658344,5.559994697570801,-0.013762115282528242,1739502645.1658378,5.559994697570801,6.261540958286242,1739502645.1658413,5.559994697570801,2.1039319598943664 +1739502645.1861846,5.5799946784973145,9.354738432921286,1739502645.1861887,5.5799946784973145,-0.27182780404831774,1739502645.186195,5.5799946784973145,8.728832484960531,1739502645.1862009,5.5799946784973145,14.927720668771697,1739502645.1862042,5.5799946784973145,-0.16358017972844954,1739502645.1862085,5.5799946784973145,0.019421202091202537,1739502645.1862123,5.5799946784973145,0.2241595504190188,1739502645.1862159,5.5799946784973145,0.0554025755651565,1739502645.1862197,5.5799946784973145,2.0895800056305203,1739502645.1862235,5.5799946784973145,0.0,1739502645.1862278,5.5799946784973145,-0.012401225545035617,1739502645.1862316,5.5799946784973145,6.262380698320103,1739502645.1862354,5.5799946784973145,2.1024065094973565 +1739502645.2056,5.599994659423828,9.354738432921286,1739502645.2056031,5.599994659423828,-0.27182780404831774,1739502645.2056077,5.599994659423828,8.728832484960531,1739502645.2056127,5.599994659423828,14.927720668771697,1739502645.2056153,5.599994659423828,-0.16358017972844954,1739502645.205619,5.599994659423828,0.019421202091202537,1739502645.2056224,5.599994659423828,0.2241595504190188,1739502645.2056258,5.599994659423828,0.0554025755651565,1739502645.205629,5.599994659423828,2.0895800056305203,1739502645.2056324,5.599994659423828,0.0,1739502645.2056358,5.599994659423828,-0.012826503866836259,1739502645.2056391,5.599994659423828,6.262380698320103,1739502645.2056427,5.599994659423828,2.1024065094973565 +1739502645.226915,5.619994640350342,9.354738432921286,1739502645.2269182,5.619994640350342,-0.27182780404831774,1739502645.2269225,5.619994640350342,8.728832484960531,1739502645.2269273,5.619994640350342,14.927720668771697,1739502645.2269301,5.619994640350342,-0.16358017972844954,1739502645.2269337,5.619994640350342,0.019421202091202537,1739502645.2269368,5.619994640350342,0.2241595504190188,1739502645.2269402,5.619994640350342,0.0554025755651565,1739502645.2269435,5.619994640350342,2.0895800056305203,1739502645.2269468,5.619994640350342,0.0,1739502645.2269502,5.619994640350342,-0.012826503866836259,1739502645.2269535,5.619994640350342,6.262380698320103,1739502645.2269568,5.619994640350342,2.1024065094973565 +1739502645.2456312,5.6399946212768555,9.354738432921286,1739502645.2456346,5.6399946212768555,-0.27182780404831774,1739502645.2456388,5.6399946212768555,8.728832484960531,1739502645.245644,5.6399946212768555,14.927720668771697,1739502645.245647,5.6399946212768555,-0.16358017972844954,1739502645.2456508,5.6399946212768555,0.019421202091202537,1739502645.245654,5.6399946212768555,0.2241595504190188,1739502645.2456574,5.6399946212768555,0.0554025755651565,1739502645.2456603,5.6399946212768555,2.0895800056305203,1739502645.245664,5.6399946212768555,0.0,1739502645.2456672,5.6399946212768555,-0.012826503866836259,1739502645.2456706,5.6399946212768555,6.262380698320103,1739502645.2456741,5.6399946212768555,2.1024065094973565 +1739502645.265676,5.659994602203369,9.354738432921286,1739502645.2656791,5.659994602203369,-0.27182780404831774,1739502645.2656834,5.659994602203369,8.728832484960531,1739502645.2656884,5.659994602203369,14.927720668771697,1739502645.265691,5.659994602203369,-0.16358017972844954,1739502645.2656946,5.659994602203369,0.019421202091202537,1739502645.265698,5.659994602203369,0.2241595504190188,1739502645.265701,5.659994602203369,0.0554025755651565,1739502645.2657044,5.659994602203369,2.0895800056305203,1739502645.2657077,5.659994602203369,0.0,1739502645.2657108,5.659994602203369,-0.012826503866836259,1739502645.2657142,5.659994602203369,6.262380698320103,1739502645.2657175,5.659994602203369,2.1024065094973565 +1739502645.2857907,5.679994583129883,9.585884505922996,1739502645.2857938,5.679994583129883,-0.2765491463508507,1739502645.285798,5.679994583129883,8.753338690041014,1739502645.2858033,5.679994583129883,14.949418293664692,1739502645.2858062,5.679994583129883,-0.16376885472751906,1739502645.2858098,5.679994583129883,0.021024137958186633,1739502645.285813,5.679994583129883,0.2198329503808182,1739502645.285816,5.679994583129883,0.05865494673137937,1739502645.2858193,5.679994583129883,2.0968251586947235,1739502645.2858226,5.679994583129883,0.0,1739502645.2858257,5.679994583129883,-0.00024608847734599194,1739502645.285829,5.679994583129883,6.263220438353964,1739502645.2858324,5.679994583129883,2.1010026295589004 +1739502645.3123095,5.6999945640563965,9.585884505922996,1739502645.3123186,5.6999945640563965,-0.2765491463508507,1739502645.3123302,5.6999945640563965,8.753338690041014,1739502645.312358,5.6999945640563965,14.949418293664692,1739502645.312364,5.6999945640563965,-0.16376885472751906,1739502645.3123715,5.6999945640563965,0.021024137958186633,1739502645.3123782,5.6999945640563965,0.2198329503808182,1739502645.3123848,5.6999945640563965,0.05865494673137937,1739502645.3123915,5.6999945640563965,2.0968251586947235,1739502645.3123984,5.6999945640563965,0.0,1739502645.312405,5.6999945640563965,-0.004177470864176858,1739502645.3124118,5.6999945640563965,6.263220438353964,1739502645.3124187,5.6999945640563965,2.1010026295589004 +1739502645.326541,5.71999454498291,9.585884505922996,1739502645.3265457,5.71999454498291,-0.2765491463508507,1739502645.326552,5.71999454498291,8.753338690041014,1739502645.326559,5.71999454498291,14.949418293664692,1739502645.326563,5.71999454498291,-0.16376885472751906,1739502645.3265681,5.71999454498291,0.021024137958186633,1739502645.326573,5.71999454498291,0.2198329503808182,1739502645.3265774,5.71999454498291,0.05865494673137937,1739502645.326582,5.71999454498291,2.0968251586947235,1739502645.3265867,5.71999454498291,0.0,1739502645.3265913,5.71999454498291,-0.004177470864176858,1739502645.3265958,5.71999454498291,6.263220438353964,1739502645.3266008,5.71999454498291,2.1010026295589004 +1739502645.3458211,5.739994525909424,9.585884505922996,1739502645.3458245,5.739994525909424,-0.2765491463508507,1739502645.3458285,5.739994525909424,8.753338690041014,1739502645.3458333,5.739994525909424,14.949418293664692,1739502645.3458364,5.739994525909424,-0.16376885472751906,1739502645.3458395,5.739994525909424,0.021024137958186633,1739502645.3458426,5.739994525909424,0.2198329503808182,1739502645.3458457,5.739994525909424,0.05865494673137937,1739502645.3458488,5.739994525909424,2.0968251586947235,1739502645.3458521,5.739994525909424,0.0,1739502645.3458552,5.739994525909424,-0.004177470864176858,1739502645.3458583,5.739994525909424,6.263220438353964,1739502645.3458614,5.739994525909424,2.1010026295589004 +1739502645.3658442,5.7599945068359375,9.585884505922996,1739502645.3658476,5.7599945068359375,-0.2765491463508507,1739502645.3658516,5.7599945068359375,8.753338690041014,1739502645.3658562,5.7599945068359375,14.949418293664692,1739502645.3658588,5.7599945068359375,-0.16376885472751906,1739502645.3658624,5.7599945068359375,0.021024137958186633,1739502645.3658655,5.7599945068359375,0.2198329503808182,1739502645.3658686,5.7599945068359375,0.05865494673137937,1739502645.3658717,5.7599945068359375,2.0968251586947235,1739502645.365875,5.7599945068359375,0.0,1739502645.365878,5.7599945068359375,-0.004177470864176858,1739502645.3658814,5.7599945068359375,6.263220438353964,1739502645.3658843,5.7599945068359375,2.1010026295589004 +1739502645.3862984,5.779994487762451,9.585884505922996,1739502645.386302,5.779994487762451,-0.2765491463508507,1739502645.3863063,5.779994487762451,8.753338690041014,1739502645.3863115,5.779994487762451,14.949418293664692,1739502645.3863142,5.779994487762451,-0.16376885472751906,1739502645.3863177,5.779994487762451,0.021024137958186633,1739502645.3863208,5.779994487762451,0.2198329503808182,1739502645.3863242,5.779994487762451,0.05865494673137937,1739502645.3863275,5.779994487762451,2.0968251586947235,1739502645.3863308,5.779994487762451,0.0,1739502645.386334,5.779994487762451,-0.004177470864176858,1739502645.3863373,5.779994487762451,6.263220438353964,1739502645.3863406,5.779994487762451,2.1010026295589004 +1739502645.4057653,5.799994468688965,9.816935004920976,1739502645.4057686,5.799994468688965,-0.2810744288529632,1739502645.4057732,5.799994468688965,9.159426824247415,1739502645.4057782,5.799994468688965,15.35474648208205,1739502645.4057808,5.799994468688965,-0.164,1739502645.4057846,5.799994468688965,0.021137771179428277,1739502645.4057877,5.799994468688965,0.22295791961705516,1739502645.405791,5.799994468688965,0.05580378234093149,1739502645.4057941,5.799994468688965,2.091589694395672,1739502645.4057977,5.799994468688965,0.0,1739502645.405801,5.799994468688965,-0.011240736801565133,1739502645.4058044,5.799994468688965,6.264060178387825,1739502645.4058077,5.799994468688965,2.100623159144603 +1739502645.425818,5.8199944496154785,9.816935004920976,1739502645.425821,5.8199944496154785,-0.2810744288529632,1739502645.4258256,5.8199944496154785,9.159426824247415,1739502645.4258306,5.8199944496154785,15.35474648208205,1739502645.4258335,5.8199944496154785,-0.164,1739502645.425837,5.8199944496154785,0.021137771179428277,1739502645.4258404,5.8199944496154785,0.22295791961705516,1739502645.4258437,5.8199944496154785,0.05580378234093149,1739502645.4258468,5.8199944496154785,2.091589694395672,1739502645.4258502,5.8199944496154785,0.0,1739502645.4258535,5.8199944496154785,-0.009033464748930964,1739502645.4258568,5.8199944496154785,6.264060178387825,1739502645.4258602,5.8199944496154785,2.100623159144603 +1739502645.4455426,5.839994430541992,9.816935004920976,1739502645.445546,5.839994430541992,-0.2810744288529632,1739502645.4455504,5.839994430541992,9.159426824247415,1739502645.4455552,5.839994430541992,15.35474648208205,1739502645.445558,5.839994430541992,-0.164,1739502645.4455616,5.839994430541992,0.021137771179428277,1739502645.445565,5.839994430541992,0.22295791961705516,1739502645.4455683,5.839994430541992,0.05580378234093149,1739502645.4455714,5.839994430541992,2.091589694395672,1739502645.4455748,5.839994430541992,0.0,1739502645.4455776,5.839994430541992,-0.009033464748930964,1739502645.445581,5.839994430541992,6.264060178387825,1739502645.4455843,5.839994430541992,2.100623159144603 +1739502645.4657302,5.859994411468506,9.816935004920976,1739502645.4657335,5.859994411468506,-0.2810744288529632,1739502645.465738,5.859994411468506,9.159426824247415,1739502645.465743,5.859994411468506,15.35474648208205,1739502645.4657457,5.859994411468506,-0.164,1739502645.4657493,5.859994411468506,0.021137771179428277,1739502645.4657526,5.859994411468506,0.22295791961705516,1739502645.465756,5.859994411468506,0.05580378234093149,1739502645.4657593,5.859994411468506,2.091589694395672,1739502645.4657626,5.859994411468506,0.0,1739502645.4657657,5.859994411468506,-0.009033464748930964,1739502645.465769,5.859994411468506,6.264060178387825,1739502645.4657724,5.859994411468506,2.100623159144603 +1739502645.486086,5.8799943923950195,9.816935004920976,1739502645.4860892,5.8799943923950195,-0.2810744288529632,1739502645.4860935,5.8799943923950195,9.159426824247415,1739502645.4860985,5.8799943923950195,15.35474648208205,1739502645.4861012,5.8799943923950195,-0.164,1739502645.4861047,5.8799943923950195,0.021137771179428277,1739502645.486108,5.8799943923950195,0.22295791961705516,1739502645.4861112,5.8799943923950195,0.05580378234093149,1739502645.4861147,5.8799943923950195,2.091589694395672,1739502645.486118,5.8799943923950195,0.0,1739502645.4861212,5.8799943923950195,-0.009033464748930964,1739502645.4861245,5.8799943923950195,6.264060178387825,1739502645.486128,5.8799943923950195,2.100623159144603 +1739502645.505708,5.899994373321533,10.047914550342588,1739502645.5057113,5.899994373321533,-0.2854042922963833,1739502645.505716,5.899994373321533,9.18414596547097,1739502645.505721,5.899994373321533,15.377496697515772,1739502645.505724,5.899994373321533,-0.164,1739502645.5057278,5.899994373321533,0.022775387765174696,1739502645.505731,5.899994373321533,0.21883204765434777,1739502645.5057344,5.899994373321533,0.05912951054724509,1739502645.5057378,5.899994373321533,2.0985048054848168,1739502645.5057411,5.899994373321533,0.0,1739502645.5057445,5.899994373321533,0.002456828106807249,1739502645.5057478,5.899994373321533,6.264899918421686,1739502645.5057511,5.899994373321533,2.0996386962496865 +1739502645.5263433,5.919994354248047,10.047914550342588,1739502645.5263467,5.919994354248047,-0.2854042922963833,1739502645.5263512,5.919994354248047,9.18414596547097,1739502645.5263562,5.919994354248047,15.377496697515772,1739502645.5263588,5.919994354248047,-0.164,1739502645.5263624,5.919994354248047,0.022775387765174696,1739502645.5263658,5.919994354248047,0.21883204765434777,1739502645.526369,5.919994354248047,0.05912951054724509,1739502645.5263722,5.919994354248047,2.0985048054848168,1739502645.5263755,5.919994354248047,0.0,1739502645.5263789,5.919994354248047,-0.0011338907648696939,1739502645.526382,5.919994354248047,6.264899918421686,1739502645.5263853,5.919994354248047,2.0996386962496865 +1739502645.545865,5.9399943351745605,10.047914550342588,1739502645.545868,5.9399943351745605,-0.2854042922963833,1739502645.5458724,5.9399943351745605,9.18414596547097,1739502645.5458775,5.9399943351745605,15.377496697515772,1739502645.54588,5.9399943351745605,-0.164,1739502645.5458841,5.9399943351745605,0.022775387765174696,1739502645.5458872,5.9399943351745605,0.21883204765434777,1739502645.5458906,5.9399943351745605,0.05912951054724509,1739502645.5458937,5.9399943351745605,2.0985048054848168,1739502645.545897,5.9399943351745605,0.0,1739502645.5459003,5.9399943351745605,-0.0011338907648696939,1739502645.5459037,5.9399943351745605,6.264899918421686,1739502645.545907,5.9399943351745605,2.0996386962496865 +1739502645.565556,5.959994316101074,10.047914550342588,1739502645.5655594,5.959994316101074,-0.2854042922963833,1739502645.5655637,5.959994316101074,9.18414596547097,1739502645.5655684,5.959994316101074,15.377496697515772,1739502645.5655713,5.959994316101074,-0.164,1739502645.565575,5.959994316101074,0.022775387765174696,1739502645.565578,5.959994316101074,0.21883204765434777,1739502645.5655813,5.959994316101074,0.05912951054724509,1739502645.5655844,5.959994316101074,2.0985048054848168,1739502645.5655878,5.959994316101074,0.0,1739502645.565591,5.959994316101074,-0.0011338907648696939,1739502645.5655944,5.959994316101074,6.264899918421686,1739502645.5655978,5.959994316101074,2.0996386962496865 +1739502645.5870214,5.979994297027588,10.047914550342588,1739502645.5870245,5.979994297027588,-0.2854042922963833,1739502645.5870285,5.979994297027588,9.18414596547097,1739502645.587033,5.979994297027588,15.377496697515772,1739502645.5870357,5.979994297027588,-0.164,1739502645.5870392,5.979994297027588,0.022775387765174696,1739502645.5870423,5.979994297027588,0.21883204765434777,1739502645.5870454,5.979994297027588,0.05912951054724509,1739502645.5870485,5.979994297027588,2.0985048054848168,1739502645.5870516,5.979994297027588,0.0,1739502645.5870545,5.979994297027588,-0.0011338907648696939,1739502645.5870576,5.979994297027588,6.264899918421686,1739502645.5870607,5.979994297027588,2.0996386962496865 +1739502645.6055565,5.999994277954102,10.047914550342588,1739502645.6055598,5.999994277954102,-0.2854042922963833,1739502645.605564,5.999994277954102,9.18414596547097,1739502645.6055691,5.999994277954102,15.377496697515772,1739502645.6055715,5.999994277954102,-0.164,1739502645.6055753,5.999994277954102,0.022775387765174696,1739502645.6055784,5.999994277954102,0.21883204765434777,1739502645.6055818,5.999994277954102,0.05912951054724509,1739502645.6055849,5.999994277954102,2.0985048054848168,1739502645.6055882,5.999994277954102,0.0,1739502645.6055915,5.999994277954102,-0.0011338907648696939,1739502645.6055949,5.999994277954102,6.264899918421686,1739502645.6055982,5.999994277954102,2.0996386962496865 +1739502645.6260269,6.019994258880615,10.278838361300004,1739502645.62603,6.019994258880615,-0.28953912270570115,1739502645.6260345,6.019994258880615,9.855704607756383,1739502645.6260397,6.019994258880615,16.048946703844283,1739502645.6260424,6.019994258880615,-0.165,1739502645.6260462,6.019994258880615,0.021580147542341284,1739502645.6260495,6.019994258880615,0.2251783485695709,1739502645.6260529,6.019994258880615,0.051912781051368775,1739502645.6260562,6.019994258880615,2.0878776112871105,1739502645.6260595,6.019994258880615,0.0,1739502645.6260629,6.019994258880615,-0.016514589982476898,1739502645.6260662,6.019994258880615,6.265739658455548,1739502645.6260695,6.019994258880615,2.0995857296127167 +1739502645.6455433,6.039994239807129,10.278838361300004,1739502645.6455464,6.039994239807129,-0.28953912270570115,1739502645.645551,6.039994239807129,9.855704607756383,1739502645.6455557,6.039994239807129,16.048946703844283,1739502645.6455586,6.039994239807129,-0.165,1739502645.6455622,6.039994239807129,0.021580147542341284,1739502645.6455655,6.039994239807129,0.2251783485695709,1739502645.6455686,6.039994239807129,0.051912781051368775,1739502645.645572,6.039994239807129,2.0878776112871105,1739502645.6455753,6.039994239807129,0.0,1739502645.6455781,6.039994239807129,-0.011708118325606254,1739502645.6455815,6.039994239807129,6.265739658455548,1739502645.6455848,6.039994239807129,2.0995857296127167 +1739502645.6656587,6.059994220733643,10.278838361300004,1739502645.665662,6.059994220733643,-0.28953912270570115,1739502645.6656663,6.059994220733643,9.855704607756383,1739502645.6656713,6.059994220733643,16.048946703844283,1739502645.665674,6.059994220733643,-0.165,1739502645.6656775,6.059994220733643,0.021580147542341284,1739502645.665681,6.059994220733643,0.2251783485695709,1739502645.665684,6.059994220733643,0.051912781051368775,1739502645.6656873,6.059994220733643,2.0878776112871105,1739502645.6656907,6.059994220733643,0.0,1739502645.6656938,6.059994220733643,-0.011708118325606254,1739502645.665697,6.059994220733643,6.265739658455548,1739502645.6657007,6.059994220733643,2.0995857296127167 +1739502645.6864533,6.079994201660156,10.278838361300004,1739502645.6864567,6.079994201660156,-0.28953912270570115,1739502645.686461,6.079994201660156,9.855704607756383,1739502645.6864657,6.079994201660156,16.048946703844283,1739502645.6864686,6.079994201660156,-0.165,1739502645.6864722,6.079994201660156,0.021580147542341284,1739502645.6864755,6.079994201660156,0.2251783485695709,1739502645.6864789,6.079994201660156,0.051912781051368775,1739502645.686482,6.079994201660156,2.0878776112871105,1739502645.6864853,6.079994201660156,0.0,1739502645.6864884,6.079994201660156,-0.011708118325606254,1739502645.6864917,6.079994201660156,6.265739658455548,1739502645.686495,6.079994201660156,2.0995857296127167 +1739502645.7055073,6.09999418258667,10.278838361300004,1739502645.7055106,6.09999418258667,-0.28953912270570115,1739502645.7055151,6.09999418258667,9.855704607756383,1739502645.7055202,6.09999418258667,16.048946703844283,1739502645.705523,6.09999418258667,-0.165,1739502645.7055268,6.09999418258667,0.021580147542341284,1739502645.7055302,6.09999418258667,0.2251783485695709,1739502645.7055335,6.09999418258667,0.051912781051368775,1739502645.7055368,6.09999418258667,2.0878776112871105,1739502645.7055402,6.09999418258667,0.0,1739502645.7055435,6.09999418258667,-0.011708118325606254,1739502645.7055469,6.09999418258667,6.265739658455548,1739502645.7055502,6.09999418258667,2.0995857296127167 +1739502645.7255147,6.119994163513184,10.509697345387606,1739502645.725518,6.119994163513184,-0.29347888112742027,1739502645.7255228,6.119994163513184,9.86586634281466,1739502645.7255278,6.119994163513184,16.05656334969359,1739502645.7255306,6.119994163513184,-0.165,1739502645.7255344,6.119994163513184,0.023158286534796187,1739502645.7255378,6.119994163513184,0.22056768420096903,1739502645.7255409,6.119994163513184,0.055020701189988794,1739502645.7255442,6.119994163513184,2.095593034156397,1739502645.7255476,6.119994163513184,0.0,1739502645.725551,6.119994163513184,0.0013652928051552712,1739502645.7255545,6.119994163513184,6.266579398489409,1739502645.725558,6.119994163513184,2.09831318500823 +1739502645.7455547,6.139994144439697,10.509697345387606,1739502645.745558,6.139994144439697,-0.29347888112742027,1739502645.7455626,6.139994144439697,9.86586634281466,1739502645.7455678,6.139994144439697,16.05656334969359,1739502645.7455707,6.139994144439697,-0.165,1739502645.7455745,6.139994144439697,0.023158286534796187,1739502645.7455778,6.139994144439697,0.22056768420096903,1739502645.7455812,6.139994144439697,0.055020701189988794,1739502645.7455845,6.139994144439697,2.095593034156397,1739502645.7455878,6.139994144439697,0.0,1739502645.745591,6.139994144439697,-0.002720150851833303,1739502645.7455947,6.139994144439697,6.266579398489409,1739502645.7455978,6.139994144439697,2.09831318500823 +1739502645.7655547,6.159994125366211,10.509697345387606,1739502645.765558,6.159994125366211,-0.29347888112742027,1739502645.7655623,6.159994125366211,9.86586634281466,1739502645.7655675,6.159994125366211,16.05656334969359,1739502645.7655704,6.159994125366211,-0.165,1739502645.7655742,6.159994125366211,0.023158286534796187,1739502645.7655776,6.159994125366211,0.22056768420096903,1739502645.7655807,6.159994125366211,0.055020701189988794,1739502645.7655838,6.159994125366211,2.095593034156397,1739502645.765587,6.159994125366211,0.0,1739502645.7655904,6.159994125366211,-0.002720150851833303,1739502645.765594,6.159994125366211,6.266579398489409,1739502645.7655976,6.159994125366211,2.09831318500823 +1739502645.7841582,6.179994106292725,10.509697345387606,1739502645.7841601,6.179994106292725,-0.29347888112742027,1739502645.7841628,6.179994106292725,9.86586634281466,1739502645.7841656,6.179994106292725,16.05656334969359,1739502645.7841668,6.179994106292725,-0.165,1739502645.7841685,6.179994106292725,0.023158286534796187,1739502645.7841697,6.179994106292725,0.22056768420096903,1739502645.7841713,6.179994106292725,0.055020701189988794,1739502645.7841725,6.179994106292725,2.095593034156397,1739502645.784174,6.179994106292725,0.0,1739502645.7841754,6.179994106292725,-0.002720150851833303,1739502645.7841766,6.179994106292725,6.266579398489409,1739502645.784178,6.179994106292725,2.09831318500823 +1739502645.8045745,6.199994087219238,10.509697345387606,1739502645.8045769,6.199994087219238,-0.29347888112742027,1739502645.8045802,6.199994087219238,9.86586634281466,1739502645.8045828,6.199994087219238,16.05656334969359,1739502645.8045843,6.199994087219238,-0.165,1739502645.804586,6.199994087219238,0.023158286534796187,1739502645.8045874,6.199994087219238,0.22056768420096903,1739502645.8045888,6.199994087219238,0.055020701189988794,1739502645.80459,6.199994087219238,2.095593034156397,1739502645.8045917,6.199994087219238,0.0,1739502645.8045928,6.199994087219238,-0.002720150851833303,1739502645.8045945,6.199994087219238,6.266579398489409,1739502645.804596,6.199994087219238,2.09831318500823 +1739502645.824352,6.219994068145752,10.509697345387606,1739502645.8243544,6.219994068145752,-0.29347888112742027,1739502645.8243573,6.219994068145752,9.86586634281466,1739502645.8243601,6.219994068145752,16.05656334969359,1739502645.8243616,6.219994068145752,-0.165,1739502645.8243635,6.219994068145752,0.023158286534796187,1739502645.8243651,6.219994068145752,0.22056768420096903,1739502645.8243666,6.219994068145752,0.055020701189988794,1739502645.8243678,6.219994068145752,2.095593034156397,1739502645.8243694,6.219994068145752,0.0,1739502645.8243709,6.219994068145752,-0.002720150851833303,1739502645.8243725,6.219994068145752,6.266579398489409,1739502645.824374,6.219994068145752,2.09831318500823 +1739502645.853683,6.239994049072266,10.740474224886462,1739502645.8536913,6.239994049072266,-0.2972233837763083,1739502645.8537016,6.239994049072266,9.87602427001526,1739502645.8537118,6.239994049072266,16.06628758347474,1739502645.8537169,6.239994049072266,-0.165,1739502645.853723,6.239994049072266,0.024821791254170895,1739502645.8537283,6.239994049072266,0.21617114361342524,1739502645.8537328,6.239994049072266,0.05848768349539213,1739502645.8537374,6.239994049072266,2.1029766994418604,1739502645.853743,6.239994049072266,0.0,1739502645.8537476,6.239994049072266,0.00833514261772014,1739502645.8537529,6.239994049072266,6.26741913852327,1739502645.8537579,6.239994049072266,2.098096338298507 +1739502645.8728514,6.259994029998779,10.740474224886462,1739502645.8728604,6.259994029998779,-0.2972233837763083,1739502645.872872,6.259994029998779,9.87602427001526,1739502645.8728857,6.259994029998779,16.06628758347474,1739502645.872893,6.259994029998779,-0.165,1739502645.872903,6.259994029998779,0.024821791254170895,1739502645.872912,6.259994029998779,0.21617114361342524,1739502645.8729205,6.259994029998779,0.05848768349539213,1739502645.8729293,6.259994029998779,2.1029766994418604,1739502645.8729384,6.259994029998779,0.0,1739502645.8729472,6.259994029998779,0.00488036114335344,1739502645.8729563,6.259994029998779,6.26741913852327,1739502645.872965,6.259994029998779,2.098096338298507 +1739502645.8874848,6.279994010925293,10.740474224886462,1739502645.887489,6.279994010925293,-0.2972233837763083,1739502645.8874955,6.279994010925293,9.87602427001526,1739502645.8875027,6.279994010925293,16.06628758347474,1739502645.8875065,6.279994010925293,-0.165,1739502645.8875115,6.279994010925293,0.024821791254170895,1739502645.8875163,6.279994010925293,0.21617114361342524,1739502645.8875208,6.279994010925293,0.05848768349539213,1739502645.8875253,6.279994010925293,2.1029766994418604,1739502645.88753,6.279994010925293,0.0,1739502645.8875349,6.279994010925293,0.00488036114335344,1739502645.8875394,6.279994010925293,6.26741913852327,1739502645.8875444,6.279994010925293,2.098096338298507 +1739502645.9054158,6.299993991851807,10.740474224886462,1739502645.9054196,6.299993991851807,-0.2972233837763083,1739502645.9054236,6.299993991851807,9.87602427001526,1739502645.9054284,6.299993991851807,16.06628758347474,1739502645.9054313,6.299993991851807,-0.165,1739502645.9054348,6.299993991851807,0.024821791254170895,1739502645.905438,6.299993991851807,0.21617114361342524,1739502645.9054413,6.299993991851807,0.05848768349539213,1739502645.9054444,6.299993991851807,2.1029766994418604,1739502645.9054477,6.299993991851807,0.0,1739502645.9054508,6.299993991851807,0.00488036114335344,1739502645.9054542,6.299993991851807,6.26741913852327,1739502645.9054575,6.299993991851807,2.098096338298507 +1739502645.9257736,6.31999397277832,10.740474224886462,1739502645.9257767,6.31999397277832,-0.2972233837763083,1739502645.9257808,6.31999397277832,9.87602427001526,1739502645.9257855,6.31999397277832,16.06628758347474,1739502645.9257882,6.31999397277832,-0.165,1739502645.9257915,6.31999397277832,0.024821791254170895,1739502645.9257946,6.31999397277832,0.21617114361342524,1739502645.9257977,6.31999397277832,0.05848768349539213,1739502645.9258008,6.31999397277832,2.1029766994418604,1739502645.9258037,6.31999397277832,0.0,1739502645.9258068,6.31999397277832,0.00488036114335344,1739502645.9258099,6.31999397277832,6.26741913852327,1739502645.9258132,6.31999397277832,2.098096338298507 +1739502645.9452832,6.339993953704834,10.971262572664498,1739502645.9452868,6.339993953704834,-0.3007742156717983,1739502645.9452913,6.339993953704834,10.157316200114577,1739502645.9452956,6.339993953704834,16.348635161442548,1739502645.945298,6.339993953704834,-0.165,1739502645.9453008,6.339993953704834,0.0252438103369,1739502645.9453032,6.339993953704834,0.2160210784955972,1739502645.9453056,6.339993953704834,0.057330725229717355,1739502645.9453082,6.339993953704834,2.1032291813540014,1739502645.945311,6.339993953704834,0.0,1739502645.9453135,6.339993953704834,0.004479863537299374,1739502645.9453158,6.339993953704834,6.2682588785571305,1739502645.9453182,6.339993953704834,2.0986241622327517 +1739502645.9653323,6.359993934631348,10.971262572664498,1739502645.9653356,6.359993934631348,-0.3007742156717983,1739502645.9653401,6.359993934631348,10.157316200114577,1739502645.9653454,6.359993934631348,16.348635161442548,1739502645.965348,6.359993934631348,-0.165,1739502645.9653523,6.359993934631348,0.0252438103369,1739502645.9653556,6.359993934631348,0.2160210784955972,1739502645.9653587,6.359993934631348,0.057330725229717355,1739502645.9653625,6.359993934631348,2.1032291813540014,1739502645.9653656,6.359993934631348,0.0,1739502645.9653697,6.359993934631348,0.004605019121249665,1739502645.965373,6.359993934631348,6.2682588785571305,1739502645.9653766,6.359993934631348,2.0986241622327517 +1739502645.9852462,6.379993915557861,10.971262572664498,1739502645.9852502,6.379993915557861,-0.3007742156717983,1739502645.9852555,6.379993915557861,10.157316200114577,1739502645.9852607,6.379993915557861,16.348635161442548,1739502645.9852633,6.379993915557861,-0.165,1739502645.9852667,6.379993915557861,0.0252438103369,1739502645.9852705,6.379993915557861,0.2160210784955972,1739502645.9852734,6.379993915557861,0.057330725229717355,1739502645.985276,6.379993915557861,2.1032291813540014,1739502645.985279,6.379993915557861,0.0,1739502645.9852815,6.379993915557861,0.004605019121249665,1739502645.9852843,6.379993915557861,6.2682588785571305,1739502645.9852872,6.379993915557861,2.0986241622327517 +1739502646.0052378,6.399993896484375,10.971262572664498,1739502646.0052416,6.399993896484375,-0.3007742156717983,1739502646.005246,6.399993896484375,10.157316200114577,1739502646.0052505,6.399993896484375,16.348635161442548,1739502646.0052528,6.399993896484375,-0.165,1739502646.005256,6.399993896484375,0.0252438103369,1739502646.005259,6.399993896484375,0.2160210784955972,1739502646.0052617,6.399993896484375,0.057330725229717355,1739502646.0052638,6.399993896484375,2.1032291813540014,1739502646.005267,6.399993896484375,0.0,1739502646.0052695,6.399993896484375,0.004605019121249665,1739502646.0052722,6.399993896484375,6.2682588785571305,1739502646.0052745,6.399993896484375,2.0986241622327517 +1739502646.025458,6.419993877410889,10.971262572664498,1739502646.0254624,6.419993877410889,-0.3007742156717983,1739502646.0254674,6.419993877410889,10.157316200114577,1739502646.0254724,6.419993877410889,16.348635161442548,1739502646.0254753,6.419993877410889,-0.165,1739502646.0254803,6.419993877410889,0.0252438103369,1739502646.0254836,6.419993877410889,0.2160210784955972,1739502646.025487,6.419993877410889,0.057330725229717355,1739502646.0254912,6.419993877410889,2.1032291813540014,1739502646.0254948,6.419993877410889,0.0,1739502646.0254986,6.419993877410889,0.004605019121249665,1739502646.0255027,6.419993877410889,6.2682588785571305,1739502646.0255058,6.419993877410889,2.0986241622327517 +1739502646.0469933,6.439993858337402,10.971262572664498,1739502646.046997,6.439993858337402,-0.3007742156717983,1739502646.0470016,6.439993858337402,10.157316200114577,1739502646.047007,6.439993858337402,16.348635161442548,1739502646.0470097,6.439993858337402,-0.165,1739502646.0470133,6.439993858337402,0.0252438103369,1739502646.0470169,6.439993858337402,0.2160210784955972,1739502646.04702,6.439993858337402,0.057330725229717355,1739502646.0470233,6.439993858337402,2.1032291813540014,1739502646.0470269,6.439993858337402,0.0,1739502646.0470302,6.439993858337402,0.004605019121249665,1739502646.0470335,6.439993858337402,6.2682588785571305,1739502646.047037,6.439993858337402,2.0986241622327517 +1739502646.065927,6.459993839263916,11.202111824689917,1739502646.0659316,6.459993839263916,-0.30413208834202177,1739502646.0659368,6.459993839263916,10.951756370467594,1739502646.0659428,6.459993839263916,17.14407882713519,1739502646.0659456,6.459993839263916,-0.165,1739502646.0659497,6.459993839263916,0.023410878813315043,1739502646.0659533,6.459993839263916,0.22281815478849573,1739502646.065956,6.459993839263916,0.048436810441810085,1739502646.0659604,6.459993839263916,2.0918235720106173,1739502646.065964,6.459993839263916,0.0,1739502646.0659673,6.459993839263916,-0.012714778059650027,1739502646.06597,6.459993839263916,6.269098618590992,1739502646.0659738,6.459993839263916,2.099125909902564 +1739502646.0853326,6.47999382019043,11.202111824689917,1739502646.085335,6.47999382019043,-0.30413208834202177,1739502646.085338,6.47999382019043,10.951756370467594,1739502646.085341,6.47999382019043,17.14407882713519,1739502646.0853422,6.47999382019043,-0.165,1739502646.085344,6.47999382019043,0.023410878813315043,1739502646.0853453,6.47999382019043,0.22281815478849573,1739502646.0853467,6.47999382019043,0.048436810441810085,1739502646.085348,6.47999382019043,2.0918235720106173,1739502646.0853496,6.47999382019043,0.0,1739502646.0853517,6.47999382019043,-0.007302337891946564,1739502646.085353,6.47999382019043,6.269098618590992,1739502646.0853543,6.47999382019043,2.099125909902564 +1739502646.1045532,6.499993801116943,11.202111824689917,1739502646.1045554,6.499993801116943,-0.30413208834202177,1739502646.1045578,6.499993801116943,10.951756370467594,1739502646.1045604,6.499993801116943,17.14407882713519,1739502646.1045616,6.499993801116943,-0.165,1739502646.1045632,6.499993801116943,0.023410878813315043,1739502646.1045644,6.499993801116943,0.22281815478849573,1739502646.1045659,6.499993801116943,0.048436810441810085,1739502646.104567,6.499993801116943,2.0918235720106173,1739502646.1045682,6.499993801116943,0.0,1739502646.1045697,6.499993801116943,-0.007302337891946564,1739502646.1045709,6.499993801116943,6.269098618590992,1739502646.104572,6.499993801116943,2.099125909902564 +1739502646.1340716,6.519993782043457,11.202111824689917,1739502646.13408,6.519993782043457,-0.30413208834202177,1739502646.1340907,6.519993782043457,10.951756370467594,1739502646.134101,6.519993782043457,17.14407882713519,1739502646.134106,6.519993782043457,-0.165,1739502646.134112,6.519993782043457,0.023410878813315043,1739502646.1341171,6.519993782043457,0.22281815478849573,1739502646.134122,6.519993782043457,0.048436810441810085,1739502646.1341264,6.519993782043457,2.0918235720106173,1739502646.1341324,6.519993782043457,0.0,1739502646.1341374,6.519993782043457,-0.007302337891946564,1739502646.1341424,6.519993782043457,6.269098618590992,1739502646.1341472,6.519993782043457,2.099125909902564 +1739502646.149042,6.539993762969971,11.202111824689917,1739502646.14905,6.539993762969971,-0.30413208834202177,1739502646.14906,6.539993762969971,10.951756370467594,1739502646.14907,6.539993762969971,17.14407882713519,1739502646.149075,6.539993762969971,-0.165,1739502646.1490817,6.539993762969971,0.023410878813315043,1739502646.149087,6.539993762969971,0.22281815478849573,1739502646.149092,6.539993762969971,0.048436810441810085,1739502646.1490965,6.539993762969971,2.0918235720106173,1739502646.149102,6.539993762969971,0.0,1739502646.1491072,6.539993762969971,-0.007302337891946564,1739502646.149112,6.539993762969971,6.269098618590992,1739502646.1491175,6.539993762969971,2.099125909902564 +1739502646.1667006,6.559993743896484,11.432956577504482,1739502646.166706,6.559993743896484,-0.3072960176579409,1739502646.1667132,6.559993743896484,10.956838118958832,1739502646.1667202,6.559993743896484,17.147581669458113,1739502646.1667237,6.559993743896484,-0.165,1739502646.1667278,6.559993743896484,0.024895179862315965,1739502646.1667314,6.559993743896484,0.21798266326018018,1739502646.1667347,6.559993743896484,0.05122668867629963,1739502646.166738,6.559993743896484,2.0999312398526593,1739502646.1667418,6.559993743896484,0.0,1739502646.1667452,6.559993743896484,0.005638932766598502,1739502646.166749,6.559993743896484,6.269938358624853,1739502646.1667523,6.559993743896484,2.0983364568184073 +1739502646.1860118,6.579993724822998,11.432956577504482,1739502646.1860166,6.579993724822998,-0.3072960176579409,1739502646.1860223,6.579993724822998,10.956838118958832,1739502646.1860278,6.579993724822998,17.147581669458113,1739502646.1860304,6.579993724822998,-0.165,1739502646.1860335,6.579993724822998,0.024895179862315965,1739502646.186036,6.579993724822998,0.21798266326018018,1739502646.1860387,6.579993724822998,0.05122668867629963,1739502646.1860414,6.579993724822998,2.0999312398526593,1739502646.1860442,6.579993724822998,0.0,1739502646.186047,6.579993724822998,0.0015947830342519786,1739502646.1860497,6.579993724822998,6.269938358624853,1739502646.1860523,6.579993724822998,2.0983364568184073 +1739502646.2050176,6.599993705749512,11.432956577504482,1739502646.2050204,6.599993705749512,-0.3072960176579409,1739502646.2050235,6.599993705749512,10.956838118958832,1739502646.2050266,6.599993705749512,17.147581669458113,1739502646.205028,6.599993705749512,-0.165,1739502646.2050302,6.599993705749512,0.024895179862315965,1739502646.2050316,6.599993705749512,0.21798266326018018,1739502646.205033,6.599993705749512,0.05122668867629963,1739502646.2050345,6.599993705749512,2.0999312398526593,1739502646.2050364,6.599993705749512,0.0,1739502646.2050376,6.599993705749512,0.0015947830342519786,1739502646.2050393,6.599993705749512,6.269938358624853,1739502646.205041,6.599993705749512,2.0983364568184073 +1739502646.2254817,6.619993686676025,11.432956577504482,1739502646.2254844,6.619993686676025,-0.3072960176579409,1739502646.225487,6.619993686676025,10.956838118958832,1739502646.2254899,6.619993686676025,17.147581669458113,1739502646.2254915,6.619993686676025,-0.165,1739502646.225493,6.619993686676025,0.024895179862315965,1739502646.2254944,6.619993686676025,0.21798266326018018,1739502646.2254956,6.619993686676025,0.05122668867629963,1739502646.2254968,6.619993686676025,2.0999312398526593,1739502646.2254984,6.619993686676025,0.0,1739502646.2254996,6.619993686676025,0.0015947830342519786,1739502646.2255008,6.619993686676025,6.269938358624853,1739502646.2255023,6.619993686676025,2.0983364568184073 +1739502646.2443786,6.639993667602539,11.432956577504482,1739502646.244381,6.639993667602539,-0.3072960176579409,1739502646.2443836,6.639993667602539,10.956838118958832,1739502646.244386,6.639993667602539,17.147581669458113,1739502646.2443874,6.639993667602539,-0.165,1739502646.2443888,6.639993667602539,0.024895179862315965,1739502646.2443898,6.639993667602539,0.21798266326018018,1739502646.2443912,6.639993667602539,0.05122668867629963,1739502646.2443924,6.639993667602539,2.0999312398526593,1739502646.244394,6.639993667602539,0.0,1739502646.2443953,6.639993667602539,0.0015947830342519786,1739502646.2443964,6.639993667602539,6.269938358624853,1739502646.2443979,6.639993667602539,2.0983364568184073 +1739502646.265296,6.659993648529053,11.432956577504482,1739502646.2652981,6.659993648529053,-0.3072960176579409,1739502646.2653012,6.659993648529053,10.956838118958832,1739502646.265304,6.659993648529053,17.147581669458113,1739502646.2653053,6.659993648529053,-0.165,1739502646.265307,6.659993648529053,0.024895179862315965,1739502646.2653081,6.659993648529053,0.21798266326018018,1739502646.2653093,6.659993648529053,0.05122668867629963,1739502646.2653105,6.659993648529053,2.0999312398526593,1739502646.265312,6.659993648529053,0.0,1739502646.2653134,6.659993648529053,0.0015947830342519786,1739502646.2653146,6.659993648529053,6.269938358624853,1739502646.2653158,6.659993648529053,2.0983364568184073 +1739502646.2855175,6.679993629455566,11.6637708791411,1739502646.2855198,6.679993629455566,-0.3102656630963958,1739502646.285523,6.679993629455566,10.961919003240276,1739502646.2855258,6.679993629455566,17.153172155248367,1739502646.285527,6.679993629455566,-0.165,1739502646.285529,6.679993629455566,0.026456759274806355,1739502646.28553,6.679993629455566,0.21336088111341187,1739502646.2855313,6.679993629455566,0.05433435850776251,1739502646.2855327,6.679993629455566,2.107709951365824,1739502646.2855344,6.679993629455566,0.0,1739502646.2855356,6.679993629455566,0.012538656490342436,1739502646.2855368,6.679993629455566,6.270778098658714,1739502646.285538,6.679993629455566,2.0985912575728123 +1739502646.304876,6.69999361038208,11.6637708791411,1739502646.3048782,6.69999361038208,-0.3102656630963958,1739502646.304881,6.69999361038208,10.961919003240276,1739502646.3048837,6.69999361038208,17.153172155248367,1739502646.304885,6.69999361038208,-0.165,1739502646.3048866,6.69999361038208,0.026456759274806355,1739502646.304888,6.69999361038208,0.21336088111341187,1739502646.3048894,6.69999361038208,0.05433435850776251,1739502646.3048904,6.69999361038208,2.107709951365824,1739502646.304892,6.69999361038208,0.0,1739502646.3048933,6.69999361038208,0.00911869379301189,1739502646.304895,6.69999361038208,6.270778098658714,1739502646.3048964,6.69999361038208,2.0985912575728123 +1739502646.3244843,6.719993591308594,11.6637708791411,1739502646.3244865,6.719993591308594,-0.3102656630963958,1739502646.324489,6.719993591308594,10.961919003240276,1739502646.324492,6.719993591308594,17.153172155248367,1739502646.3244934,6.719993591308594,-0.165,1739502646.324495,6.719993591308594,0.026456759274806355,1739502646.3244963,6.719993591308594,0.21336088111341187,1739502646.324498,6.719993591308594,0.05433435850776251,1739502646.3244994,6.719993591308594,2.107709951365824,1739502646.324501,6.719993591308594,0.0,1739502646.3245022,6.719993591308594,0.00911869379301189,1739502646.3245037,6.719993591308594,6.270778098658714,1739502646.3245049,6.719993591308594,2.0985912575728123 +1739502646.3511877,6.729993581771851,11.6637708791411,1739502646.351196,6.729993581771851,-0.3102656630963958,1739502646.3512123,6.729993581771851,10.961919003240276,1739502646.351237,6.729993581771851,17.153172155248367,1739502646.3512468,6.729993581771851,-0.165,1739502646.3512576,6.729993581771851,0.026456759274806355,1739502646.3512661,6.729993581771851,0.21336088111341187,1739502646.3512733,6.729993581771851,0.05433435850776251,1739502646.3512807,6.729993581771851,2.107709951365824,1739502646.3512895,6.729993581771851,0.0,1739502646.3512974,6.729993581771851,0.00911869379301189,1739502646.351305,6.729993581771851,6.270778098658714,1739502646.3513129,6.729993581771851,2.0985912575728123 +1739502646.3712587,6.749993562698364,11.6637708791411,1739502646.3712673,6.749993562698364,-0.3102656630963958,1739502646.3712778,6.749993562698364,10.961919003240276,1739502646.3712876,6.749993562698364,17.153172155248367,1739502646.3712926,6.749993562698364,-0.165,1739502646.3712988,6.749993562698364,0.026456759274806355,1739502646.3713043,6.749993562698364,0.21336088111341187,1739502646.371309,6.749993562698364,0.05433435850776251,1739502646.3713138,6.749993562698364,2.107709951365824,1739502646.3713195,6.749993562698364,0.0,1739502646.3713243,6.749993562698364,0.00911869379301189,1739502646.3713295,6.749993562698364,6.270778098658714,1739502646.3713343,6.749993562698364,2.0985912575728123 +1739502646.3926625,6.769993543624878,11.6637708791411,1739502646.392669,6.769993543624878,-0.3102656630963958,1739502646.3927064,6.769993543624878,10.961919003240276,1739502646.392723,6.769993543624878,17.153172155248367,1739502646.3927276,6.769993543624878,-0.165,1739502646.3927321,6.769993543624878,0.026456759274806355,1739502646.392736,6.769993543624878,0.21336088111341187,1739502646.3927398,6.769993543624878,0.05433435850776251,1739502646.3927433,6.769993543624878,2.107709951365824,1739502646.3927472,6.769993543624878,0.0,1739502646.3927505,6.769993543624878,0.00911869379301189,1739502646.392754,6.769993543624878,6.270778098658714,1739502646.3927577,6.769993543624878,2.0985912575728123 +1739502646.410238,6.799993515014648,11.894647508316831,1739502646.4102426,6.799993515014648,-0.31304219791911336,1739502646.4102485,6.799993515014648,10.967001065616964,1739502646.410254,6.799993515014648,17.16023729818609,1739502646.4102566,6.799993515014648,-0.165,1739502646.41026,6.799993515014648,0.028107622399320607,1739502646.4102628,6.799993515014648,0.2089404791600302,1739502646.4102654,6.799993515014648,0.057821961913635506,1739502646.4102678,6.799993515014648,2.1151766861210137,1739502646.410271,6.799993515014648,0.0,1739502646.4102736,6.799993515014648,0.018537161290368323,1739502646.4102764,6.799993515014648,6.271617838692576,1739502646.4102788,6.799993515014648,2.0995827978533295 +1739502646.4279451,6.819993495941162,11.894647508316831,1739502646.4279487,6.819993495941162,-0.31304219791911336,1739502646.4279535,6.819993495941162,10.967001065616964,1739502646.4279578,6.819993495941162,17.16023729818609,1739502646.4279602,6.819993495941162,-0.165,1739502646.4279625,6.819993495941162,0.028107622399320607,1739502646.4279652,6.819993495941162,0.2089404791600302,1739502646.4279673,6.819993495941162,0.057821961913635506,1739502646.4279692,6.819993495941162,2.1151766861210137,1739502646.4279718,6.819993495941162,0.0,1739502646.427974,6.819993495941162,0.015593888267684264,1739502646.427976,6.819993495941162,6.271617838692576,1739502646.4279783,6.819993495941162,2.0995827978533295 +1739502646.4491525,6.839993476867676,11.894647508316831,1739502646.4491556,6.839993476867676,-0.31304219791911336,1739502646.4491594,6.839993476867676,10.967001065616964,1739502646.4491627,6.839993476867676,17.16023729818609,1739502646.4491646,6.839993476867676,-0.165,1739502646.4491668,6.839993476867676,0.028107622399320607,1739502646.4491687,6.839993476867676,0.2089404791600302,1739502646.4491704,6.839993476867676,0.057821961913635506,1739502646.449172,6.839993476867676,2.1151766861210137,1739502646.449174,6.839993476867676,0.0,1739502646.4491758,6.839993476867676,0.015593888267684264,1739502646.4491777,6.839993476867676,6.271617838692576,1739502646.44918,6.839993476867676,2.0995827978533295 +1739502646.469381,6.8599934577941895,11.894647508316831,1739502646.4693856,6.8599934577941895,-0.31304219791911336,1739502646.4693918,6.8599934577941895,10.967001065616964,1739502646.469399,6.8599934577941895,17.16023729818609,1739502646.469403,6.8599934577941895,-0.165,1739502646.4694083,6.8599934577941895,0.028107622399320607,1739502646.4694128,6.8599934577941895,0.2089404791600302,1739502646.4694176,6.8599934577941895,0.057821961913635506,1739502646.469422,6.8599934577941895,2.1151766861210137,1739502646.4694266,6.8599934577941895,0.0,1739502646.4694314,6.8599934577941895,0.015593888267684264,1739502646.469436,6.8599934577941895,6.271617838692576,1739502646.4694407,6.8599934577941895,2.0995827978533295 +1739502646.488205,6.879993438720703,11.894647508316831,1739502646.488208,6.879993438720703,-0.31304219791911336,1739502646.4882116,6.879993438720703,10.967001065616964,1739502646.4882152,6.879993438720703,17.16023729818609,1739502646.488217,6.879993438720703,-0.165,1739502646.488219,6.879993438720703,0.028107622399320607,1739502646.488221,6.879993438720703,0.2089404791600302,1739502646.4882228,6.879993438720703,0.057821961913635506,1739502646.4882245,6.879993438720703,2.1151766861210137,1739502646.4882267,6.879993438720703,0.0,1739502646.4882283,6.879993438720703,0.015593888267684264,1739502646.4882302,6.879993438720703,6.271617838692576,1739502646.488232,6.879993438720703,2.0995827978533295 +1739502646.507698,6.899993419647217,12.125664660577549,1739502646.5077012,6.899993419647217,-0.3156263971482751,1739502646.5077047,6.899993419647217,11.376337372735234,1739502646.5077088,6.899993419647217,17.572840872976563,1739502646.5077105,6.899993419647217,-0.164,1739502646.5077128,6.899993419647217,0.0278285937229107,1739502646.5077145,6.899993419647217,0.21005237874370375,1739502646.5077164,6.899993419647217,0.054320296896996446,1739502646.507718,6.899993419647217,2.1132960314233338,1739502646.5077202,6.899993419647217,0.0,1739502646.507722,6.899993419647217,0.010479138616779312,1739502646.5077238,6.899993419647217,6.272457578726437,1739502646.5077255,6.899993419647217,2.10121853249268 +1739502646.5287697,6.9199934005737305,12.125664660577549,1739502646.5287726,6.9199934005737305,-0.3156263971482751,1739502646.528776,6.9199934005737305,11.376337372735234,1739502646.528779,6.9199934005737305,17.572840872976563,1739502646.5287805,6.9199934005737305,-0.164,1739502646.5287824,6.9199934005737305,0.0278285937229107,1739502646.528784,6.9199934005737305,0.21005237874370375,1739502646.5287857,6.9199934005737305,0.054320296896996446,1739502646.528787,6.9199934005737305,2.1132960314233338,1739502646.5287888,6.9199934005737305,0.0,1739502646.5287902,6.9199934005737305,0.012077498930653796,1739502646.5287921,6.9199934005737305,6.272457578726437,1739502646.5287936,6.9199934005737305,2.10121853249268 +1739502646.5485883,6.939993381500244,12.125664660577549,1739502646.5485919,6.939993381500244,-0.3156263971482751,1739502646.5485964,6.939993381500244,11.376337372735234,1739502646.5486019,6.939993381500244,17.572840872976563,1739502646.548605,6.939993381500244,-0.164,1739502646.5486088,6.939993381500244,0.0278285937229107,1739502646.5486124,6.939993381500244,0.21005237874370375,1739502646.5486157,6.939993381500244,0.054320296896996446,1739502646.5486193,6.939993381500244,2.1132960314233338,1739502646.5486226,6.939993381500244,0.0,1739502646.5486262,6.939993381500244,0.012077498930653796,1739502646.5486298,6.939993381500244,6.272457578726437,1739502646.5486333,6.939993381500244,2.10121853249268 +1739502646.5673058,6.959993362426758,12.125664660577549,1739502646.5673082,6.959993362426758,-0.3156263971482751,1739502646.567311,6.959993362426758,11.376337372735234,1739502646.567314,6.959993362426758,17.572840872976563,1739502646.567315,6.959993362426758,-0.164,1739502646.567317,6.959993362426758,0.0278285937229107,1739502646.5673182,6.959993362426758,0.21005237874370375,1739502646.5673199,6.959993362426758,0.054320296896996446,1739502646.567321,6.959993362426758,2.1132960314233338,1739502646.5673227,6.959993362426758,0.0,1739502646.567324,6.959993362426758,0.012077498930653796,1739502646.5673254,6.959993362426758,6.272457578726437,1739502646.5673268,6.959993362426758,2.10121853249268 +1739502646.5879498,6.9799933433532715,12.125664660577549,1739502646.5879521,6.9799933433532715,-0.3156263971482751,1739502646.5879555,6.9799933433532715,11.376337372735234,1739502646.5879583,6.9799933433532715,17.572840872976563,1739502646.5879595,6.9799933433532715,-0.164,1739502646.5879614,6.9799933433532715,0.0278285937229107,1739502646.5879629,6.9799933433532715,0.21005237874370375,1739502646.587964,6.9799933433532715,0.054320296896996446,1739502646.5879655,6.9799933433532715,2.1132960314233338,1739502646.587967,6.9799933433532715,0.0,1739502646.5879686,6.9799933433532715,0.012077498930653796,1739502646.5879698,6.9799933433532715,6.272457578726437,1739502646.5879712,6.9799933433532715,2.10121853249268 +1739502646.6077409,6.999993324279785,12.356853206070472,1739502646.607743,6.999993324279785,-0.31801835578835913,1739502646.6077464,6.999993324279785,11.50165405086277,1739502646.6077492,6.999993324279785,17.70080430248516,1739502646.6077507,6.999993324279785,-0.16367391342449444,1739502646.607752,6.999993324279785,0.028874056723481843,1739502646.6077535,6.999993324279785,0.20717696261414167,1739502646.607755,6.999993324279785,0.055662891645641754,1739502646.6077564,6.999993324279785,2.1181629113955345,1739502646.6077578,6.999993324279785,0.0,1739502646.6077595,6.999993324279785,0.017230692085238294,1739502646.6077607,6.999993324279785,6.273297318760298,1739502646.607762,6.999993324279785,2.1025425932269473 +1739502646.6275277,7.019993305206299,12.356853206070472,1739502646.62753,7.019993305206299,-0.31801835578835913,1739502646.6275327,7.019993305206299,11.50165405086277,1739502646.6275356,7.019993305206299,17.70080430248516,1739502646.627537,7.019993305206299,-0.16367391342449444,1739502646.6275384,7.019993305206299,0.028874056723481843,1739502646.6275399,7.019993305206299,0.20717696261414167,1739502646.6275413,7.019993305206299,0.055662891645641754,1739502646.6275425,7.019993305206299,2.1181629113955345,1739502646.6275442,7.019993305206299,0.0,1739502646.6275454,7.019993305206299,0.015620318168587222,1739502646.6275468,7.019993305206299,6.273297318760298,1739502646.6275482,7.019993305206299,2.1025425932269473 +1739502646.6477141,7.0399932861328125,12.356853206070472,1739502646.6477168,7.0399932861328125,-0.31801835578835913,1739502646.64772,7.0399932861328125,11.50165405086277,1739502646.6477234,7.0399932861328125,17.70080430248516,1739502646.6477249,7.0399932861328125,-0.16367391342449444,1739502646.6477268,7.0399932861328125,0.028874056723481843,1739502646.6477284,7.0399932861328125,0.20717696261414167,1739502646.6477299,7.0399932861328125,0.055662891645641754,1739502646.6477313,7.0399932861328125,2.1181629113955345,1739502646.6477332,7.0399932861328125,0.0,1739502646.6477346,7.0399932861328125,0.015620318168587222,1739502646.647736,7.0399932861328125,6.273297318760298,1739502646.6477373,7.0399932861328125,2.1025425932269473 +1739502646.6719131,7.059993267059326,12.356853206070472,1739502646.671922,7.059993267059326,-0.31801835578835913,1739502646.6719325,7.059993267059326,11.50165405086277,1739502646.671943,7.059993267059326,17.70080430248516,1739502646.6719477,7.059993267059326,-0.16367391342449444,1739502646.671954,7.059993267059326,0.028874056723481843,1739502646.6719587,7.059993267059326,0.20717696261414167,1739502646.6719635,7.059993267059326,0.055662891645641754,1739502646.671968,7.059993267059326,2.1181629113955345,1739502646.671974,7.059993267059326,0.0,1739502646.6719787,7.059993267059326,0.015620318168587222,1739502646.671984,7.059993267059326,6.273297318760298,1739502646.6719887,7.059993267059326,2.1025425932269473 +1739502646.6974444,7.069993257522583,12.356853206070472,1739502646.6974528,7.069993257522583,-0.31801835578835913,1739502646.6974638,7.069993257522583,11.50165405086277,1739502646.6974747,7.069993257522583,17.70080430248516,1739502646.6974797,7.069993257522583,-0.16367391342449444,1739502646.6974862,7.069993257522583,0.028874056723481843,1739502646.6974912,7.069993257522583,0.20717696261414167,1739502646.6974957,7.069993257522583,0.055662891645641754,1739502646.697501,7.069993257522583,2.1181629113955345,1739502646.6975067,7.069993257522583,0.0,1739502646.6975114,7.069993257522583,0.015620318168587222,1739502646.6975164,7.069993257522583,6.273297318760298,1739502646.6975217,7.069993257522583,2.1025425932269473 +1739502646.7160501,7.0999932289123535,12.356853206070472,1739502646.7160592,7.0999932289123535,-0.31801835578835913,1739502646.7160695,7.0999932289123535,11.50165405086277,1739502646.716079,7.0999932289123535,17.70080430248516,1739502646.7160838,7.0999932289123535,-0.16367391342449444,1739502646.71609,7.0999932289123535,0.028874056723481843,1739502646.7160947,7.0999932289123535,0.20717696261414167,1739502646.7160997,7.0999932289123535,0.055662891645641754,1739502646.7161043,7.0999932289123535,2.1181629113955345,1739502646.71611,7.0999932289123535,0.0,1739502646.7161152,7.0999932289123535,0.015620318168587222,1739502646.7161205,7.0999932289123535,6.273297318760298,1739502646.7161255,7.0999932289123535,2.1025425932269473 +1739502646.7352211,7.119993209838867,12.588211153110645,1739502646.7352269,7.119993209838867,-0.3202177641781869,1739502646.7352343,7.119993209838867,11.82416530452078,1739502646.7352414,7.119993209838867,18.026775403432783,1739502646.7352448,7.119993209838867,-0.15988707660945364,1739502646.735249,7.119993209838867,0.029471797542037804,1739502646.7352526,7.119993209838867,0.2095329331426326,1739502646.735256,7.119993209838867,0.0543525828013183,1739502646.735259,7.119993209838867,2.1141744077800144,1739502646.7352636,7.119993209838867,0.0,1739502646.735267,7.119993209838867,0.007284638436019611,1739502646.7352705,7.119993209838867,6.274137058794159,1739502646.735274,7.119993209838867,2.104284867719661 +1739502646.7547808,7.139993190765381,12.588211153110645,1739502646.7547867,7.139993190765381,-0.3202177641781869,1739502646.7547946,7.139993190765381,11.82416530452078,1739502646.7548018,7.139993190765381,18.026775403432783,1739502646.7548053,7.139993190765381,-0.15988707660945364,1739502646.7548096,7.139993190765381,0.029471797542037804,1739502646.7548132,7.139993190765381,0.2095329331426326,1739502646.7548165,7.139993190765381,0.0543525828013183,1739502646.7548199,7.139993190765381,2.1141744077800144,1739502646.754824,7.139993190765381,0.0,1739502646.7548273,7.139993190765381,0.009889540060353585,1739502646.754831,7.139993190765381,6.274137058794159,1739502646.7548344,7.139993190765381,2.104284867719661 +1739502646.7740047,7.1599931716918945,12.588211153110645,1739502646.7740085,7.1599931716918945,-0.3202177641781869,1739502646.7740135,7.1599931716918945,11.82416530452078,1739502646.774018,7.1599931716918945,18.026775403432783,1739502646.7740202,7.1599931716918945,-0.15988707660945364,1739502646.7740228,7.1599931716918945,0.029471797542037804,1739502646.7740252,7.1599931716918945,0.2095329331426326,1739502646.7740273,7.1599931716918945,0.0543525828013183,1739502646.7740293,7.1599931716918945,2.1141744077800144,1739502646.7740316,7.1599931716918945,0.0,1739502646.7740335,7.1599931716918945,0.009889540060353585,1739502646.774036,7.1599931716918945,6.274137058794159,1739502646.7740383,7.1599931716918945,2.104284867719661 +1739502646.7926183,7.179993152618408,12.588211153110645,1739502646.792621,7.179993152618408,-0.3202177641781869,1739502646.7926245,7.179993152618408,11.82416530452078,1739502646.792627,7.179993152618408,18.026775403432783,1739502646.7926288,7.179993152618408,-0.15988707660945364,1739502646.7926304,7.179993152618408,0.029471797542037804,1739502646.7926323,7.179993152618408,0.2095329331426326,1739502646.7926338,7.179993152618408,0.0543525828013183,1739502646.7926352,7.179993152618408,2.1141744077800144,1739502646.7926369,7.179993152618408,0.0,1739502646.7926385,7.179993152618408,0.009889540060353585,1739502646.79264,7.179993152618408,6.274137058794159,1739502646.7926419,7.179993152618408,2.104284867719661 +1739502646.8127246,7.199993133544922,12.588211153110645,1739502646.8127272,7.199993133544922,-0.3202177641781869,1739502646.8127303,7.199993133544922,11.82416530452078,1739502646.8127332,7.199993133544922,18.026775403432783,1739502646.8127344,7.199993133544922,-0.15988707660945364,1739502646.8127365,7.199993133544922,0.029471797542037804,1739502646.8127377,7.199993133544922,0.2095329331426326,1739502646.8127394,7.199993133544922,0.0543525828013183,1739502646.8127406,7.199993133544922,2.1141744077800144,1739502646.8127422,7.199993133544922,0.0,1739502646.8127437,7.199993133544922,0.009889540060353585,1739502646.8127453,7.199993133544922,6.274137058794159,1739502646.8127468,7.199993133544922,2.104284867719661 +1739502646.8337286,7.2199931144714355,12.81972916386827,1739502646.8337312,7.2199931144714355,-0.32222426838813956,1739502646.8337338,7.2199931144714355,12.23101745395152,1739502646.8337367,7.2199931144714355,18.43570226335801,1739502646.833738,7.2199931144714355,-0.15108829561069984,1739502646.8337398,7.2199931144714355,0.03046364832558692,1739502646.833741,7.2199931144714355,0.21722845167729607,1739502646.8337424,7.2199931144714355,0.05284207578673544,1739502646.8337436,7.2199931144714355,2.101198656145714,1739502646.8337452,7.2199931144714355,0.0,1739502646.8337464,7.2199931144714355,-0.010564439730098948,1739502646.8337476,7.2199931144714355,6.27497679882802,1739502646.8337493,7.2199931144714355,2.105371223000458 +1739502646.8521674,7.239993095397949,12.81972916386827,1739502646.8521695,7.239993095397949,-0.32222426838813956,1739502646.8521724,7.239993095397949,12.23101745395152,1739502646.852175,7.239993095397949,18.43570226335801,1739502646.8521764,7.239993095397949,-0.15108829561069984,1739502646.8521779,7.239993095397949,0.03046364832558692,1739502646.8521795,7.239993095397949,0.21722845167729607,1739502646.852181,7.239993095397949,0.05284207578673544,1739502646.852182,7.239993095397949,2.101198656145714,1739502646.8521836,7.239993095397949,0.0,1739502646.8521848,7.239993095397949,-0.0041725668547440975,1739502646.8521862,7.239993095397949,6.27497679882802,1739502646.8521876,7.239993095397949,2.105371223000458 +1739502646.8758228,7.259993076324463,12.81972916386827,1739502646.8758314,7.259993076324463,-0.32222426838813956,1739502646.8758419,7.259993076324463,12.23101745395152,1739502646.8758516,7.259993076324463,18.43570226335801,1739502646.8758564,7.259993076324463,-0.15108829561069984,1739502646.8758626,7.259993076324463,0.03046364832558692,1739502646.8758676,7.259993076324463,0.21722845167729607,1739502646.8758724,7.259993076324463,0.05284207578673544,1739502646.8758771,7.259993076324463,2.101198656145714,1739502646.8758821,7.259993076324463,0.0,1739502646.8758872,7.259993076324463,-0.0041725668547440975,1739502646.875892,7.259993076324463,6.27497679882802,1739502646.8758976,7.259993076324463,2.105371223000458 +1739502646.8962688,7.279993057250977,12.81972916386827,1739502646.8962812,7.279993057250977,-0.32222426838813956,1739502646.8962944,7.279993057250977,12.23101745395152,1739502646.8963068,7.279993057250977,18.43570226335801,1739502646.8963127,7.279993057250977,-0.15108829561069984,1739502646.8963203,7.279993057250977,0.03046364832558692,1739502646.8963265,7.279993057250977,0.21722845167729607,1739502646.8963325,7.279993057250977,0.05284207578673544,1739502646.896338,7.279993057250977,2.101198656145714,1739502646.896345,7.279993057250977,0.0,1739502646.8963513,7.279993057250977,-0.0041725668547440975,1739502646.8963578,7.279993057250977,6.27497679882802,1739502646.8963642,7.279993057250977,2.105371223000458 +1739502646.9179351,7.29999303817749,12.81972916386827,1739502646.9179435,7.29999303817749,-0.32222426838813956,1739502646.9179537,7.29999303817749,12.23101745395152,1739502646.9179637,7.29999303817749,18.43570226335801,1739502646.9179688,7.29999303817749,-0.15108829561069984,1739502646.9179747,7.29999303817749,0.03046364832558692,1739502646.9179797,7.29999303817749,0.21722845167729607,1739502646.9179845,7.29999303817749,0.05284207578673544,1739502646.917989,7.29999303817749,2.101198656145714,1739502646.9179945,7.29999303817749,0.0,1739502646.9179993,7.29999303817749,-0.0041725668547440975,1739502646.918007,7.29999303817749,6.27497679882802,1739502646.9180121,7.29999303817749,2.105371223000458 +1739502646.950003,7.319993019104004,12.81972916386827,1739502646.9500122,7.319993019104004,-0.32222426838813956,1739502646.9500232,7.319993019104004,12.23101745395152,1739502646.9500332,7.319993019104004,18.43570226335801,1739502646.9500377,7.319993019104004,-0.15108829561069984,1739502646.9500444,7.319993019104004,0.03046364832558692,1739502646.9500492,7.319993019104004,0.21722845167729607,1739502646.9500542,7.319993019104004,0.05284207578673544,1739502646.9500587,7.319993019104004,2.101198656145714,1739502646.9500644,7.319993019104004,0.0,1739502646.9500692,7.319993019104004,-0.0041725668547440975,1739502646.9500747,7.319993019104004,6.27497679882802,1739502646.9500794,7.319993019104004,2.105371223000458 +1739502646.9673853,7.349992990493774,13.051277916417405,1739502646.9673944,7.349992990493774,-0.32403659726563827,1739502646.9674056,7.349992990493774,12.277099280366551,1739502646.9674158,7.349992990493774,18.480610657379803,1739502646.9674206,7.349992990493774,-0.1503398223770033,1739502646.9674268,7.349992990493774,0.031981379593748485,1739502646.967432,7.349992990493774,0.21369919218079064,1739502646.9674368,7.349992990493774,0.055613106567178924,1739502646.9674413,7.349992990493774,2.1071395792718857,1739502646.967447,7.349992990493774,0.0,1739502646.9674525,7.349992990493774,0.005317648192992995,1739502646.9674578,7.349992990493774,6.275816538861881,1739502646.9674633,7.349992990493774,2.104787625225771 +1739502646.9953523,7.369992971420288,13.051277916417405,1739502646.9953654,7.369992971420288,-0.32403659726563827,1739502646.9953814,7.369992971420288,12.277099280366551,1739502646.995396,7.369992971420288,18.480610657379803,1739502646.9954033,7.369992971420288,-0.1503398223770033,1739502646.9954133,7.369992971420288,0.031981379593748485,1739502646.995422,7.369992971420288,0.21369919218079064,1739502646.9954307,7.369992971420288,0.055613106567178924,1739502646.9954395,7.369992971420288,2.1071395792718857,1739502646.9954486,7.369992971420288,0.0,1739502646.9954572,7.369992971420288,0.002351954046114546,1739502646.9954662,7.369992971420288,6.275816538861881,1739502646.9954753,7.369992971420288,2.104787625225771 +1739502647.009616,7.389992952346802,13.051277916417405,1739502647.0096195,7.389992952346802,-0.32403659726563827,1739502647.0096233,7.389992952346802,12.277099280366551,1739502647.009627,7.389992952346802,18.480610657379803,1739502647.009629,7.389992952346802,-0.1503398223770033,1739502647.0096312,7.389992952346802,0.031981379593748485,1739502647.009633,7.389992952346802,0.21369919218079064,1739502647.0096347,7.389992952346802,0.055613106567178924,1739502647.0096366,7.389992952346802,2.1071395792718857,1739502647.0096385,7.389992952346802,0.0,1739502647.0096405,7.389992952346802,0.002351954046114546,1739502647.0096426,7.389992952346802,6.275816538861881,1739502647.0096445,7.389992952346802,2.104787625225771 +1739502647.0282295,7.409992933273315,13.051277916417405,1739502647.028232,7.409992933273315,-0.32403659726563827,1739502647.028235,7.409992933273315,12.277099280366551,1739502647.0282376,7.409992933273315,18.480610657379803,1739502647.028239,7.409992933273315,-0.1503398223770033,1739502647.0282407,7.409992933273315,0.031981379593748485,1739502647.028242,7.409992933273315,0.21369919218079064,1739502647.0282438,7.409992933273315,0.055613106567178924,1739502647.0282452,7.409992933273315,2.1071395792718857,1739502647.0282469,7.409992933273315,0.0,1739502647.028248,7.409992933273315,0.002351954046114546,1739502647.0282493,7.409992933273315,6.275816538861881,1739502647.0282507,7.409992933273315,2.104787625225771 +1739502647.0487344,7.429992914199829,13.051277916417405,1739502647.0487373,7.429992914199829,-0.32403659726563827,1739502647.0487404,7.429992914199829,12.277099280366551,1739502647.048743,7.429992914199829,18.480610657379803,1739502647.0487442,7.429992914199829,-0.1503398223770033,1739502647.0487456,7.429992914199829,0.031981379593748485,1739502647.0487652,7.429992914199829,0.21369919218079064,1739502647.0487664,7.429992914199829,0.055613106567178924,1739502647.0487678,7.429992914199829,2.1071395792718857,1739502647.0487692,7.429992914199829,0.0,1739502647.048771,7.429992914199829,0.002351954046114546,1739502647.048772,7.429992914199829,6.275816538861881,1739502647.0487735,7.429992914199829,2.104787625225771 +1739502647.0686114,7.449992895126343,13.28280398584204,1739502647.0686135,7.449992895126343,-0.32565431018180746,1739502647.0686164,7.449992895126343,12.688960607886452,1739502647.068619,7.449992895126343,18.892765764692122,1739502647.0686204,7.449992895126343,-0.14225585588269696,1739502647.068622,7.449992895126343,0.03267993052023883,1739502647.0686233,7.449992895126343,0.22002188423683777,1739502647.0686247,7.449992895126343,0.05362868289763702,1739502647.068626,7.449992895126343,2.0965082536348603,1739502647.0686276,7.449992895126343,0.0,1739502647.068629,7.449992895126343,-0.013385462096254387,1739502647.0686302,7.449992895126343,6.276656278895742,1739502647.0686316,7.449992895126343,2.104975769962168 +1739502647.089679,7.4699928760528564,13.28280398584204,1739502647.0896819,7.4699928760528564,-0.32565431018180746,1739502647.0896857,7.4699928760528564,12.688960607886452,1739502647.0896883,7.4699928760528564,18.892765764692122,1739502647.0896902,7.4699928760528564,-0.14225585588269696,1739502647.0896916,7.4699928760528564,0.03267993052023883,1739502647.0896928,7.4699928760528564,0.22002188423683777,1739502647.0896945,7.4699928760528564,0.05362868289763702,1739502647.089696,7.4699928760528564,2.0965082536348603,1739502647.0896978,7.4699928760528564,0.0,1739502647.0896993,7.4699928760528564,-0.008467516327307578,1739502647.089701,7.4699928760528564,6.276656278895742,1739502647.0897026,7.4699928760528564,2.104975769962168 +1739502647.109543,7.48999285697937,13.28280398584204,1739502647.109547,7.48999285697937,-0.32565431018180746,1739502647.1095517,7.48999285697937,12.688960607886452,1739502647.1095567,7.48999285697937,18.892765764692122,1739502647.1095598,7.48999285697937,-0.14225585588269696,1739502647.1095636,7.48999285697937,0.03267993052023883,1739502647.109567,7.48999285697937,0.22002188423683777,1739502647.1095705,7.48999285697937,0.05362868289763702,1739502647.1095738,7.48999285697937,2.0965082536348603,1739502647.1095774,7.48999285697937,0.0,1739502647.1095808,7.48999285697937,-0.008467516327307578,1739502647.1095843,7.48999285697937,6.276656278895742,1739502647.109588,7.48999285697937,2.104975769962168 +1739502647.1281416,7.509992837905884,13.28280398584204,1739502647.1281435,7.509992837905884,-0.32565431018180746,1739502647.1281464,7.509992837905884,12.688960607886452,1739502647.1281495,7.509992837905884,18.892765764692122,1739502647.128151,7.509992837905884,-0.14225585588269696,1739502647.1281528,7.509992837905884,0.03267993052023883,1739502647.128154,7.509992837905884,0.22002188423683777,1739502647.1281557,7.509992837905884,0.05362868289763702,1739502647.128157,7.509992837905884,2.0965082536348603,1739502647.1281588,7.509992837905884,0.0,1739502647.12816,7.509992837905884,-0.008467516327307578,1739502647.1281612,7.509992837905884,6.276656278895742,1739502647.1281629,7.509992837905884,2.104975769962168 +1739502647.148187,7.5299928188323975,13.28280398584204,1739502647.1481898,7.5299928188323975,-0.32565431018180746,1739502647.1481924,7.5299928188323975,12.688960607886452,1739502647.148195,7.5299928188323975,18.892765764692122,1739502647.1481965,7.5299928188323975,-0.14225585588269696,1739502647.1481981,7.5299928188323975,0.03267993052023883,1739502647.1481993,7.5299928188323975,0.22002188423683777,1739502647.148201,7.5299928188323975,0.05362868289763702,1739502647.148202,7.5299928188323975,2.0965082536348603,1739502647.148204,7.5299928188323975,0.0,1739502647.1482053,7.5299928188323975,-0.008467516327307578,1739502647.148207,7.5299928188323975,6.276656278895742,1739502647.1482081,7.5299928188323975,2.104975769962168 +1739502647.1682055,7.549992799758911,13.51430292254529,1739502647.1682086,7.549992799758911,-0.327077435525025,1739502647.1682115,7.549992799758911,12.714658412985855,1739502647.1682143,7.549992799758911,18.916620695082585,1739502647.1682155,7.549992799758911,-0.1416594826229354,1739502647.1682172,7.549992799758911,0.03430845888836994,1739502647.1682186,7.549992799758911,0.21615012932526323,1739502647.1682198,7.549992799758911,0.05680587610406679,1739502647.1682212,7.549992799758911,2.103012053785726,1739502647.1682227,7.549992799758911,0.0,1739502647.1682243,7.549992799758911,0.0023274116239102153,1739502647.1682255,7.549992799758911,6.277496018929604,1739502647.1682267,7.549992799758911,2.104058059358356 +1739502647.188831,7.569992780685425,13.51430292254529,1739502647.1888342,7.569992780685425,-0.327077435525025,1739502647.188838,7.569992780685425,12.714658412985855,1739502647.1888409,7.569992780685425,18.916620695082585,1739502647.1888425,7.569992780685425,-0.1416594826229354,1739502647.1888444,7.569992780685425,0.03430845888836994,1739502647.188846,7.569992780685425,0.21615012932526323,1739502647.1888475,7.569992780685425,0.05680587610406679,1739502647.188849,7.569992780685425,2.103012053785726,1739502647.1888504,7.569992780685425,0.0,1739502647.188852,7.569992780685425,-0.0010460055726300155,1739502647.1888537,7.569992780685425,6.277496018929604,1739502647.1888556,7.569992780685425,2.104058059358356 +1739502647.216932,7.599992752075195,13.51430292254529,1739502647.2169404,7.599992752075195,-0.327077435525025,1739502647.2169502,7.599992752075195,12.714658412985855,1739502647.2169607,7.599992752075195,18.916620695082585,1739502647.2169654,7.599992752075195,-0.1416594826229354,1739502647.2169719,7.599992752075195,0.03430845888836994,1739502647.2169766,7.599992752075195,0.21615012932526323,1739502647.2169812,7.599992752075195,0.05680587610406679,1739502647.216986,7.599992752075195,2.103012053785726,1739502647.2169917,7.599992752075195,0.0,1739502647.2169967,7.599992752075195,-0.0010460055726300155,1739502647.2170017,7.599992752075195,6.277496018929604,1739502647.217007,7.599992752075195,2.104058059358356 +1739502647.237715,7.609992742538452,13.51430292254529,1739502647.2377234,7.609992742538452,-0.327077435525025,1739502647.237734,7.609992742538452,12.714658412985855,1739502647.237744,7.609992742538452,18.916620695082585,1739502647.237749,7.609992742538452,-0.1416594826229354,1739502647.2377555,7.609992742538452,0.03430845888836994,1739502647.2377608,7.609992742538452,0.21615012932526323,1739502647.2377658,7.609992742538452,0.05680587610406679,1739502647.2377706,7.609992742538452,2.103012053785726,1739502647.237776,7.609992742538452,0.0,1739502647.237781,7.609992742538452,-0.0010460055726300155,1739502647.237786,7.609992742538452,6.277496018929604,1739502647.2377913,7.609992742538452,2.104058059358356 +1739502647.2602363,7.639992713928223,13.51430292254529,1739502647.260245,7.639992713928223,-0.327077435525025,1739502647.2602563,7.639992713928223,12.714658412985855,1739502647.2602665,7.639992713928223,18.916620695082585,1739502647.2602713,7.639992713928223,-0.1416594826229354,1739502647.2602777,7.639992713928223,0.03430845888836994,1739502647.2602832,7.639992713928223,0.21615012932526323,1739502647.2602885,7.639992713928223,0.05680587610406679,1739502647.260293,7.639992713928223,2.103012053785726,1739502647.2602987,7.639992713928223,0.0,1739502647.260304,7.639992713928223,-0.0010460055726300155,1739502647.2603092,7.639992713928223,6.277496018929604,1739502647.2603147,7.639992713928223,2.104058059358356 +1739502647.279501,7.659992694854736,13.745746689569607,1739502647.2795093,7.659992694854736,-0.32830585579390004,1739502647.2795198,7.659992694854736,12.936822403958931,1739502647.27953,7.659992694854736,19.138635003697292,1739502647.279535,7.659992694854736,-0.13716323250654947,1739502647.2795413,7.659992694854736,0.035428629737673446,1739502647.2795463,7.659992694854736,0.2172933450261816,1739502647.279551,7.659992694854736,0.05730159869742748,1739502647.2795558,7.659992694854736,2.1010895759231936,1739502647.2795618,7.659992694854736,0.0,1739502647.2795665,7.659992694854736,-0.0037730260155186763,1739502647.279572,7.659992694854736,6.278335758963465,1739502647.279577,7.659992694854736,2.1040104074915673 +1739502647.2996824,7.67999267578125,13.745746689569607,1739502647.29969,7.67999267578125,-0.32830585579390004,1739502647.2997005,7.67999267578125,12.936822403958931,1739502647.2997108,7.67999267578125,19.138635003697292,1739502647.2997158,7.67999267578125,-0.13716323250654947,1739502647.299722,7.67999267578125,0.035428629737673446,1739502647.299727,7.67999267578125,0.2172933450261816,1739502647.2997317,7.67999267578125,0.05730159869742748,1739502647.2997363,7.67999267578125,2.1010895759231936,1739502647.299742,7.67999267578125,0.0,1739502647.2997468,7.67999267578125,-0.0029208315683737496,1739502647.299752,7.67999267578125,6.278335758963465,1739502647.2997572,7.67999267578125,2.1040104074915673 +1739502647.3257318,7.699992656707764,13.745746689569607,1739502647.325742,7.699992656707764,-0.32830585579390004,1739502647.3257527,7.699992656707764,12.936822403958931,1739502647.3257642,7.699992656707764,19.138635003697292,1739502647.3257697,7.699992656707764,-0.13716323250654947,1739502647.3257773,7.699992656707764,0.035428629737673446,1739502647.3257837,7.699992656707764,0.2172933450261816,1739502647.3257895,7.699992656707764,0.05730159869742748,1739502647.3257954,7.699992656707764,2.1010895759231936,1739502647.325802,7.699992656707764,0.0,1739502647.325809,7.699992656707764,-0.0029208315683737496,1739502647.3258152,7.699992656707764,6.278335758963465,1739502647.3258219,7.699992656707764,2.1040104074915673 +1739502647.354194,7.729992628097534,13.745746689569607,1739502647.3541982,7.729992628097534,-0.32830585579390004,1739502647.354204,7.729992628097534,12.936822403958931,1739502647.354209,7.729992628097534,19.138635003697292,1739502647.3542116,7.729992628097534,-0.13716323250654947,1739502647.354215,7.729992628097534,0.035428629737673446,1739502647.3542175,7.729992628097534,0.2172933450261816,1739502647.3542206,7.729992628097534,0.05730159869742748,1739502647.3542228,7.729992628097534,2.1010895759231936,1739502647.3542259,7.729992628097534,0.0,1739502647.3542285,7.729992628097534,-0.0029208315683737496,1739502647.3542314,7.729992628097534,6.278335758963465,1739502647.3542337,7.729992628097534,2.1040104074915673 +1739502647.3748627,7.759992599487305,13.745746689569607,1739502647.3748662,7.759992599487305,-0.32830585579390004,1739502647.3748705,7.759992599487305,12.936822403958931,1739502647.3748744,7.759992599487305,19.138635003697292,1739502647.3748763,7.759992599487305,-0.13716323250654947,1739502647.3748786,7.759992599487305,0.035428629737673446,1739502647.3748806,7.759992599487305,0.2172933450261816,1739502647.3748822,7.759992599487305,0.05730159869742748,1739502647.3748841,7.759992599487305,2.1010895759231936,1739502647.3748865,7.759992599487305,0.0,1739502647.3748882,7.759992599487305,-0.0029208315683737496,1739502647.37489,7.759992599487305,6.278335758963465,1739502647.374892,7.759992599487305,2.1040104074915673 +1739502647.3940675,7.779992580413818,13.977167884735906,1739502647.3940706,7.779992580413818,-0.32933981997671324,1739502647.3940747,7.779992580413818,13.159872694999684,1739502647.3940783,7.779992580413818,19.360999554471785,1739502647.39408,7.779992580413818,-0.135,1739502647.394082,7.779992580413818,0.03608126893478386,1739502647.3940837,7.779992580413818,0.21592633205666625,1739502647.3940856,7.779992580413818,0.057130215964347475,1739502647.3940873,7.779992580413818,2.1033886061760496,1739502647.3940892,7.779992580413818,0.0,1739502647.394091,7.779992580413818,0.0009129761086154602,1739502647.394093,7.779992580413818,6.279175498997326,1739502647.394095,7.779992580413818,2.1036736957520064 +1739502647.4138517,7.799992561340332,13.977167884735906,1739502647.4138553,7.799992561340332,-0.32933981997671324,1739502647.4138591,7.799992561340332,13.159872694999684,1739502647.4138627,7.799992561340332,19.360999554471785,1739502647.4138644,7.799992561340332,-0.135,1739502647.4138668,7.799992561340332,0.03608126893478386,1739502647.413869,7.799992561340332,0.21592633205666625,1739502647.4138706,7.799992561340332,0.057130215964347475,1739502647.4138725,7.799992561340332,2.1033886061760496,1739502647.4138744,7.799992561340332,0.0,1739502647.4138765,7.799992561340332,-0.0002850895759567429,1739502647.4138784,7.799992561340332,6.279175498997326,1739502647.4138803,7.799992561340332,2.1036736957520064 +1739502647.4340024,7.819992542266846,13.977167884735906,1739502647.4340062,7.819992542266846,-0.32933981997671324,1739502647.4340105,7.819992542266846,13.159872694999684,1739502647.4340146,7.819992542266846,19.360999554471785,1739502647.4340162,7.819992542266846,-0.135,1739502647.4340189,7.819992542266846,0.03608126893478386,1739502647.4340208,7.819992542266846,0.21592633205666625,1739502647.4340231,7.819992542266846,0.057130215964347475,1739502647.434025,7.819992542266846,2.1033886061760496,1739502647.434027,7.819992542266846,0.0,1739502647.4340289,7.819992542266846,-0.0002850895759567429,1739502647.4340308,7.819992542266846,6.279175498997326,1739502647.4340327,7.819992542266846,2.1036736957520064 +1739502647.453857,7.839992523193359,13.977167884735906,1739502647.4538596,7.839992523193359,-0.32933981997671324,1739502647.4538624,7.839992523193359,13.159872694999684,1739502647.4538653,7.839992523193359,19.360999554471785,1739502647.4538665,7.839992523193359,-0.135,1739502647.4538684,7.839992523193359,0.03608126893478386,1739502647.4538698,7.839992523193359,0.21592633205666625,1739502647.453871,7.839992523193359,0.057130215964347475,1739502647.4538727,7.839992523193359,2.1033886061760496,1739502647.453874,7.839992523193359,0.0,1739502647.4538755,7.839992523193359,-0.0002850895759567429,1739502647.453877,7.839992523193359,6.279175498997326,1739502647.4538786,7.839992523193359,2.1036736957520064 +1739502647.47379,7.859992504119873,13.977167884735906,1739502647.473792,7.859992504119873,-0.32933981997671324,1739502647.4737947,7.859992504119873,13.159872694999684,1739502647.4737973,7.859992504119873,19.360999554471785,1739502647.4737988,7.859992504119873,-0.135,1739502647.4738,7.859992504119873,0.03608126893478386,1739502647.4738011,7.859992504119873,0.21592633205666625,1739502647.4738026,7.859992504119873,0.057130215964347475,1739502647.4738038,7.859992504119873,2.1033886061760496,1739502647.4738054,7.859992504119873,0.0,1739502647.4738064,7.859992504119873,-0.0002850895759567429,1739502647.4738076,7.859992504119873,6.279175498997326,1739502647.473809,7.859992504119873,2.1036736957520064 +1739502647.4935489,7.879992485046387,14.208568333558958,1739502647.4935517,7.879992485046387,-0.3301793696639832,1739502647.4935544,7.879992485046387,13.483313544662195,1739502647.4935575,7.879992485046387,19.684364112717045,1739502647.493559,7.879992485046387,-0.1330816520196584,1739502647.4935608,7.879992485046387,0.035978818823874,1739502647.4935622,7.879992485046387,0.2144553440078064,1739502647.4935637,7.879992485046387,0.054852055061995586,1739502647.4935648,7.879992485046387,2.1058653107728103,1739502647.4935665,7.879992485046387,0.0,1739502647.493568,7.879992485046387,0.0033657545566339623,1739502647.4935696,7.879992485046387,6.280015239031187,1739502647.4935708,7.879992485046387,2.1036404457556364 +1739502647.5133889,7.8999924659729,14.208568333558958,1739502647.5133908,7.8999924659729,-0.3301793696639832,1739502647.5133932,7.8999924659729,13.483313544662195,1739502647.5133958,7.8999924659729,19.684364112717045,1739502647.513397,7.8999924659729,-0.1330816520196584,1739502647.5133984,7.8999924659729,0.035978818823874,1739502647.5133998,7.8999924659729,0.2144553440078064,1739502647.513401,7.8999924659729,0.054852055061995586,1739502647.5134022,7.8999924659729,2.1058653107728103,1739502647.5134037,7.8999924659729,0.0,1739502647.5134046,7.8999924659729,0.0022248650171738937,1739502647.513406,7.8999924659729,6.280015239031187,1739502647.5134072,7.8999924659729,2.1036404457556364 +1739502647.53335,7.919992446899414,14.208568333558958,1739502647.533352,7.919992446899414,-0.3301793696639832,1739502647.5333548,7.919992446899414,13.483313544662195,1739502647.5333574,7.919992446899414,19.684364112717045,1739502647.5333586,7.919992446899414,-0.1330816520196584,1739502647.5333602,7.919992446899414,0.035978818823874,1739502647.5333614,7.919992446899414,0.2144553440078064,1739502647.533363,7.919992446899414,0.054852055061995586,1739502647.5333643,7.919992446899414,2.1058653107728103,1739502647.533366,7.919992446899414,0.0,1739502647.5333674,7.919992446899414,0.0022248650171738937,1739502647.5333686,7.919992446899414,6.280015239031187,1739502647.53337,7.919992446899414,2.1036404457556364 +1739502647.5532742,7.939992427825928,14.208568333558958,1739502647.553276,7.939992427825928,-0.3301793696639832,1739502647.553279,7.939992427825928,13.483313544662195,1739502647.5532815,7.939992427825928,19.684364112717045,1739502647.5532827,7.939992427825928,-0.1330816520196584,1739502647.5532846,7.939992427825928,0.035978818823874,1739502647.5532858,7.939992427825928,0.2144553440078064,1739502647.5532873,7.939992427825928,0.054852055061995586,1739502647.5532885,7.939992427825928,2.1058653107728103,1739502647.5532897,7.939992427825928,0.0,1739502647.553291,7.939992427825928,0.0022248650171738937,1739502647.5532923,7.939992427825928,6.280015239031187,1739502647.5532935,7.939992427825928,2.1036404457556364 +1739502647.5731146,7.959992408752441,14.208568333558958,1739502647.573117,7.959992408752441,-0.3301793696639832,1739502647.5731194,7.959992408752441,13.483313544662195,1739502647.5731223,7.959992408752441,19.684364112717045,1739502647.5731237,7.959992408752441,-0.1330816520196584,1739502647.5731251,7.959992408752441,0.035978818823874,1739502647.5731263,7.959992408752441,0.2144553440078064,1739502647.5731277,7.959992408752441,0.054852055061995586,1739502647.573129,7.959992408752441,2.1058653107728103,1739502647.5731306,7.959992408752441,0.0,1739502647.5731318,7.959992408752441,0.0022248650171738937,1739502647.573133,7.959992408752441,6.280015239031187,1739502647.5731347,7.959992408752441,2.1036404457556364 +1739502647.59343,7.979992389678955,14.208568333558958,1739502647.5934331,7.979992389678955,-0.3301793696639832,1739502647.5934362,7.979992389678955,13.483313544662195,1739502647.5934389,7.979992389678955,19.684364112717045,1739502647.5934403,7.979992389678955,-0.1330816520196584,1739502647.593442,7.979992389678955,0.035978818823874,1739502647.5934434,7.979992389678955,0.2144553440078064,1739502647.5934448,7.979992389678955,0.054852055061995586,1739502647.5934458,7.979992389678955,2.1058653107728103,1739502647.5934477,7.979992389678955,0.0,1739502647.5934489,7.979992389678955,0.0022248650171738937,1739502647.5934503,7.979992389678955,6.280015239031187,1739502647.5934515,7.979992389678955,2.1036404457556364 +1739502647.6133323,7.999992370605469,14.43998223845049,1739502647.6133342,7.999992370605469,-0.33082463651332006,1739502647.613337,7.999992370605469,13.809209993712091,1739502647.6133397,7.999992370605469,20.010784410196816,1739502647.6133409,7.999992370605469,-0.131,1739502647.6133428,7.999992370605469,0.03585462103522739,1739502647.613344,7.999992370605469,0.21280587911870036,1739502647.6133456,7.999992370605469,0.052590397165771186,1739502647.6133466,7.999992370605469,2.1086459857326485,1739502647.613348,7.999992370605469,0.0,1739502647.6133494,7.999992370605469,0.0058822397973677856,1739502647.6133509,7.999992370605469,6.280854979065048,1739502647.6133525,7.999992370605469,2.103906676303455 +1739502647.6333323,8.019992351531982,14.43998223845049,1739502647.6333346,8.019992351531982,-0.33082463651332006,1739502647.633337,8.019992351531982,13.809209993712091,1739502647.63334,8.019992351531982,20.010784410196816,1739502647.633341,8.019992351531982,-0.131,1739502647.633343,8.019992351531982,0.03585462103522739,1739502647.6333442,8.019992351531982,0.21280587911870036,1739502647.6333458,8.019992351531982,0.052590397165771186,1739502647.633347,8.019992351531982,2.1086459857326485,1739502647.6333487,8.019992351531982,0.0,1739502647.63335,8.019992351531982,0.00473930942919365,1739502647.633351,8.019992351531982,6.280854979065048,1739502647.6333525,8.019992351531982,2.103906676303455 +1739502647.6532967,8.039992332458496,14.43998223845049,1739502647.6532986,8.039992332458496,-0.33082463651332006,1739502647.6533015,8.039992332458496,13.809209993712091,1739502647.653304,8.039992332458496,20.010784410196816,1739502647.6533055,8.039992332458496,-0.131,1739502647.6533077,8.039992332458496,0.03585462103522739,1739502647.6533089,8.039992332458496,0.21280587911870036,1739502647.6533103,8.039992332458496,0.052590397165771186,1739502647.6533115,8.039992332458496,2.1086459857326485,1739502647.653313,8.039992332458496,0.0,1739502647.6533144,8.039992332458496,0.00473930942919365,1739502647.6533155,8.039992332458496,6.280854979065048,1739502647.6533172,8.039992332458496,2.103906676303455 +1739502647.6732855,8.05999231338501,14.43998223845049,1739502647.6732876,8.05999231338501,-0.33082463651332006,1739502647.6732905,8.05999231338501,13.809209993712091,1739502647.6732936,8.05999231338501,20.010784410196816,1739502647.6732948,8.05999231338501,-0.131,1739502647.6732967,8.05999231338501,0.03585462103522739,1739502647.6732981,8.05999231338501,0.21280587911870036,1739502647.6732998,8.05999231338501,0.052590397165771186,1739502647.673301,8.05999231338501,2.1086459857326485,1739502647.6733024,8.05999231338501,0.0,1739502647.673304,8.05999231338501,0.00473930942919365,1739502647.6733055,8.05999231338501,6.280854979065048,1739502647.6733072,8.05999231338501,2.103906676303455 +1739502647.693611,8.079992294311523,14.43998223845049,1739502647.6936135,8.079992294311523,-0.33082463651332006,1739502647.693617,8.079992294311523,13.809209993712091,1739502647.6936202,8.079992294311523,20.010784410196816,1739502647.6936219,8.079992294311523,-0.131,1739502647.6936238,8.079992294311523,0.03585462103522739,1739502647.6936257,8.079992294311523,0.21280587911870036,1739502647.693627,8.079992294311523,0.052590397165771186,1739502647.6936288,8.079992294311523,2.1086459857326485,1739502647.6936305,8.079992294311523,0.0,1739502647.693632,8.079992294311523,0.00473930942919365,1739502647.6936338,8.079992294311523,6.280854979065048,1739502647.6936357,8.079992294311523,2.103906676303455 +1739502647.7134705,8.099992275238037,14.671436928797736,1739502647.7134733,8.099992275238037,-0.33127565214739096,1739502647.713477,8.099992275238037,13.835364824736965,1739502647.71348,8.099992275238037,20.037972149227382,1739502647.7134817,8.099992275238037,-0.131,1739502647.7134836,8.099992275238037,0.037302047709496355,1739502647.7134852,8.099992275238037,0.20827472012781748,1739502647.713487,8.099992275238037,0.05545694003291201,1739502647.7134883,8.099992275238037,2.11630354456766,1739502647.7134902,8.099992275238037,0.0,1739502647.7134917,8.099992275238037,0.015126374098842318,1739502647.7134936,8.099992275238037,6.281694719098909,1739502647.713495,8.099992275238037,2.1044231303063 +1739502647.7333891,8.11999225616455,14.671436928797736,1739502647.7333915,8.11999225616455,-0.33127565214739096,1739502647.7333949,8.11999225616455,13.835364824736965,1739502647.7333984,8.11999225616455,20.037972149227382,1739502647.7334,8.11999225616455,-0.131,1739502647.733402,8.11999225616455,0.037302047709496355,1739502647.733404,8.11999225616455,0.20827472012781748,1739502647.7334054,8.11999225616455,0.05545694003291201,1739502647.7334068,8.11999225616455,2.11630354456766,1739502647.7334087,8.11999225616455,0.0,1739502647.7334101,8.11999225616455,0.011880414261359995,1739502647.7334118,8.11999225616455,6.281694719098909,1739502647.7334135,8.11999225616455,2.1044231303063 +1739502647.753446,8.139992237091064,14.671436928797736,1739502647.753449,8.139992237091064,-0.33127565214739096,1739502647.7534523,8.139992237091064,13.835364824736965,1739502647.7534554,8.139992237091064,20.037972149227382,1739502647.7534568,8.139992237091064,-0.131,1739502647.7534587,8.139992237091064,0.037302047709496355,1739502647.7534604,8.139992237091064,0.20827472012781748,1739502647.753462,8.139992237091064,0.05545694003291201,1739502647.7534635,8.139992237091064,2.11630354456766,1739502647.7534654,8.139992237091064,0.0,1739502647.7534668,8.139992237091064,0.011880414261359995,1739502647.7534685,8.139992237091064,6.281694719098909,1739502647.75347,8.139992237091064,2.1044231303063 +1739502647.7733994,8.159992218017578,14.671436928797736,1739502647.7734017,8.159992218017578,-0.33127565214739096,1739502647.773405,8.159992218017578,13.835364824736965,1739502647.7734082,8.159992218017578,20.037972149227382,1739502647.7734098,8.159992218017578,-0.131,1739502647.7734118,8.159992218017578,0.037302047709496355,1739502647.7734134,8.159992218017578,0.20827472012781748,1739502647.7734149,8.159992218017578,0.05545694003291201,1739502647.7734165,8.159992218017578,2.11630354456766,1739502647.7734182,8.159992218017578,0.0,1739502647.7734199,8.159992218017578,0.011880414261359995,1739502647.7734213,8.159992218017578,6.281694719098909,1739502647.773423,8.159992218017578,2.1044231303063 +1739502647.7934287,8.179992198944092,14.671436928797736,1739502647.7934313,8.179992198944092,-0.33127565214739096,1739502647.7934346,8.179992198944092,13.835364824736965,1739502647.7934377,8.179992198944092,20.037972149227382,1739502647.7934394,8.179992198944092,-0.131,1739502647.7934418,8.179992198944092,0.037302047709496355,1739502647.7934434,8.179992198944092,0.20827472012781748,1739502647.793445,8.179992198944092,0.05545694003291201,1739502647.7934463,8.179992198944092,2.11630354456766,1739502647.7934482,8.179992198944092,0.0,1739502647.7934496,8.179992198944092,0.011880414261359995,1739502647.7934515,8.179992198944092,6.281694719098909,1739502647.7934532,8.179992198944092,2.1044231303063 +1739502647.8133576,8.199992179870605,14.671436928797736,1739502647.8133602,8.199992179870605,-0.33127565214739096,1739502647.8133636,8.199992179870605,13.835364824736965,1739502647.813367,8.199992179870605,20.037972149227382,1739502647.8133683,8.199992179870605,-0.131,1739502647.8133705,8.199992179870605,0.037302047709496355,1739502647.813372,8.199992179870605,0.20827472012781748,1739502647.8133733,8.199992179870605,0.05545694003291201,1739502647.813375,8.199992179870605,2.11630354456766,1739502647.8133774,8.199992179870605,0.0,1739502647.8133788,8.199992179870605,0.011880414261359995,1739502647.8133802,8.199992179870605,6.281694719098909,1739502647.8133821,8.199992179870605,2.1044231303063 +1739502647.8334408,8.21999216079712,14.902994629275767,1739502647.8334434,8.21999216079712,-0.33153241354556684,1739502647.833447,8.21999216079712,14.264076197394687,1739502647.83345,8.21999216079712,20.469407446651097,1739502647.8334517,8.21999216079712,-0.129,1739502647.8334537,8.21999216079712,0.036368684292866695,1739502647.8334553,8.21999216079712,0.20615525930305734,1739502647.833457,8.21999216079712,0.05102562983853716,1739502647.8334584,8.21999216079712,2.1198949263892795,1739502647.8334603,8.21999216079712,0.0,1739502647.833462,8.21999216079712,0.015118501151973128,1739502647.8334637,8.21999216079712,6.282534459132771,1739502647.833465,8.21999216079712,2.105788328054078 +1739502647.8534353,8.239992141723633,14.902994629275767,1739502647.853438,8.239992141723633,-0.33153241354556684,1739502647.8534412,8.239992141723633,14.264076197394687,1739502647.8534446,8.239992141723633,20.469407446651097,1739502647.8534462,8.239992141723633,-0.129,1739502647.8534482,8.239992141723633,0.036368684292866695,1739502647.8534498,8.239992141723633,0.20615525930305734,1739502647.8534513,8.239992141723633,0.05102562983853716,1739502647.8534527,8.239992141723633,2.1198949263892795,1739502647.8534546,8.239992141723633,0.0,1739502647.853456,8.239992141723633,0.014106598335201337,1739502647.853458,8.239992141723633,6.282534459132771,1739502647.8534594,8.239992141723633,2.105788328054078 +1739502647.8739035,8.259992122650146,14.902994629275767,1739502647.8739069,8.259992122650146,-0.33153241354556684,1739502647.8739104,8.259992122650146,14.264076197394687,1739502647.8739145,8.259992122650146,20.469407446651097,1739502647.8739161,8.259992122650146,-0.129,1739502647.8739185,8.259992122650146,0.036368684292866695,1739502647.8739202,8.259992122650146,0.20615525930305734,1739502647.873922,8.259992122650146,0.05102562983853716,1739502647.8739235,8.259992122650146,2.1198949263892795,1739502647.8739257,8.259992122650146,0.0,1739502647.8739274,8.259992122650146,0.014106598335201337,1739502647.8739297,8.259992122650146,6.282534459132771,1739502647.8739314,8.259992122650146,2.105788328054078 +1739502647.8936174,8.27999210357666,14.902994629275767,1739502647.8936203,8.27999210357666,-0.33153241354556684,1739502647.893624,8.27999210357666,14.264076197394687,1739502647.8936274,8.27999210357666,20.469407446651097,1739502647.893629,8.27999210357666,-0.129,1739502647.8936312,8.27999210357666,0.036368684292866695,1739502647.8936327,8.27999210357666,0.20615525930305734,1739502647.8936346,8.27999210357666,0.05102562983853716,1739502647.893636,8.27999210357666,2.1198949263892795,1739502647.8936381,8.27999210357666,0.0,1739502647.89364,8.27999210357666,0.014106598335201337,1739502647.8936417,8.27999210357666,6.282534459132771,1739502647.8936436,8.27999210357666,2.105788328054078 +1739502647.9135902,8.299992084503174,14.902994629275767,1739502647.9135933,8.299992084503174,-0.33153241354556684,1739502647.9135973,8.299992084503174,14.264076197394687,1739502647.9136007,8.299992084503174,20.469407446651097,1739502647.9136026,8.299992084503174,-0.129,1739502647.913605,8.299992084503174,0.036368684292866695,1739502647.9136066,8.299992084503174,0.20615525930305734,1739502647.9136086,8.299992084503174,0.05102562983853716,1739502647.9136102,8.299992084503174,2.1198949263892795,1739502647.9136124,8.299992084503174,0.0,1739502647.9136138,8.299992084503174,0.014106598335201337,1739502647.9136157,8.299992084503174,6.282534459132771,1739502647.9136174,8.299992084503174,2.105788328054078 +1739502647.933788,8.319992065429688,15.134708074566767,1739502647.9337916,8.319992065429688,-0.3315947668949466,1739502647.933796,8.319992065429688,14.290491592511207,1739502647.9337997,8.319992065429688,20.498905590841467,1739502647.9338014,8.319992065429688,-0.129,1739502647.9338036,8.319992065429688,0.03775001206423186,1739502647.9338055,8.319992065429688,0.20158150935890923,1739502647.9338074,8.319992065429688,0.05372011388960295,1739502647.9338088,8.319992065429688,2.127665830028334,1739502647.933811,8.319992065429688,0.0,1739502647.9338124,8.319992065429688,0.023167734275093763,1739502647.9338143,8.319992065429688,0.00018889198704552008,1739502647.933816,8.319992065429688,2.1073297025910027 +1739502647.9536054,8.339992046356201,15.134708074566767,1739502647.9536104,8.339992046356201,-0.3315947668949466,1739502647.9536154,8.339992046356201,14.290491592511207,1739502647.95362,8.339992046356201,20.498905590841467,1739502647.9536223,8.339992046356201,-0.129,1739502647.9536252,8.339992046356201,0.03775001206423186,1739502647.9536276,8.339992046356201,0.20158150935890923,1739502647.9536302,8.339992046356201,0.05372011388960295,1739502647.9536324,8.339992046356201,2.127665830028334,1739502647.9536345,8.339992046356201,0.0,1739502647.953637,8.339992046356201,0.020336127437331264,1739502647.9536393,8.339992046356201,0.00018889198704552008,1739502647.9536414,8.339992046356201,2.1073297025910027 +1739502647.973616,8.359992027282715,15.134708074566767,1739502647.9736187,8.359992027282715,-0.3315947668949466,1739502647.9736223,8.359992027282715,14.290491592511207,1739502647.9736261,8.359992027282715,20.498905590841467,1739502647.9736278,8.359992027282715,-0.129,1739502647.9736302,8.359992027282715,0.03775001206423186,1739502647.973632,8.359992027282715,0.20158150935890923,1739502647.9736338,8.359992027282715,0.05372011388960295,1739502647.9736357,8.359992027282715,2.127665830028334,1739502647.9736373,8.359992027282715,0.0,1739502647.973639,8.359992027282715,0.020336127437331264,1739502647.973641,8.359992027282715,0.00018889198704552008,1739502647.9736428,8.359992027282715,2.1073297025910027 +1739502647.9937298,8.379992008209229,15.134708074566767,1739502647.9937332,8.379992008209229,-0.3315947668949466,1739502647.993737,8.379992008209229,14.290491592511207,1739502647.9937403,8.379992008209229,20.498905590841467,1739502647.993742,8.379992008209229,-0.129,1739502647.9937441,8.379992008209229,0.03775001206423186,1739502647.9937458,8.379992008209229,0.20158150935890923,1739502647.9937477,8.379992008209229,0.05372011388960295,1739502647.9937491,8.379992008209229,2.127665830028334,1739502647.9937515,8.379992008209229,0.0,1739502647.9937534,8.379992008209229,0.020336127437331264,1739502647.993755,8.379992008209229,0.00018889198704552008,1739502647.993757,8.379992008209229,2.1073297025910027 +1739502648.0135887,8.399991989135742,15.134708074566767,1739502648.0135915,8.399991989135742,-0.3315947668949466,1739502648.0135953,8.399991989135742,14.290491592511207,1739502648.0135992,8.399991989135742,20.498905590841467,1739502648.013601,8.399991989135742,-0.129,1739502648.013603,8.399991989135742,0.03775001206423186,1739502648.0136049,8.399991989135742,0.20158150935890923,1739502648.0136065,8.399991989135742,0.05372011388960295,1739502648.0136082,8.399991989135742,2.127665830028334,1739502648.0136101,8.399991989135742,0.0,1739502648.013612,8.399991989135742,0.020336127437331264,1739502648.013614,8.399991989135742,0.00018889198704552008,1739502648.0136156,8.399991989135742,2.1073297025910027 +1739502648.0337517,8.419991970062256,15.134708074566767,1739502648.0337553,8.419991970062256,-0.3315947668949466,1739502648.0337596,8.419991970062256,14.290491592511207,1739502648.0337632,8.419991970062256,20.498905590841467,1739502648.0337648,8.419991970062256,-0.129,1739502648.033767,8.419991970062256,0.03775001206423186,1739502648.033769,8.419991970062256,0.20158150935890923,1739502648.0337708,8.419991970062256,0.05372011388960295,1739502648.0337722,8.419991970062256,2.127665830028334,1739502648.0337744,8.419991970062256,0.0,1739502648.033776,8.419991970062256,0.020336127437331264,1739502648.033778,8.419991970062256,0.00018889198704552008,1739502648.0337799,8.419991970062256,2.1073297025910027 +1739502648.0534499,8.43999195098877,15.3666311963349,1739502648.0534525,8.43999195098877,-0.3314624160970876,1739502648.0534558,8.43999195098877,14.718883599438227,1739502648.053459,8.43999195098877,20.931858128073326,1739502648.0534601,8.43999195098877,-0.12774706452398912,1739502648.0534623,8.43999195098877,0.03658870323191038,1739502648.0534637,8.43999195098877,0.19799067418306202,1739502648.0534654,8.43999195098877,0.049025270852730854,1739502648.0534668,8.43999195098877,2.1337866952703246,1739502648.0534687,8.43999195098877,0.0,1739502648.05347,8.43999195098877,0.02591872203484396,1739502648.0534718,8.43999195098877,0.0010286320209066762,1739502648.0534732,8.43999195098877,2.1096125351910273 +1739502648.0734313,8.459991931915283,15.3666311963349,1739502648.073434,8.459991931915283,-0.3314624160970876,1739502648.0734372,8.459991931915283,14.718883599438227,1739502648.0734403,8.459991931915283,20.931858128073326,1739502648.073442,8.459991931915283,-0.12774706452398912,1739502648.073444,8.459991931915283,0.03658870323191038,1739502648.0734456,8.459991931915283,0.19799067418306202,1739502648.0734472,8.459991931915283,0.049025270852730854,1739502648.0734484,8.459991931915283,2.1337866952703246,1739502648.0734506,8.459991931915283,0.0,1739502648.073452,8.459991931915283,0.02417416007929729,1739502648.073454,8.459991931915283,0.0010286320209066762,1739502648.0734553,8.459991931915283,2.1096125351910273 +1739502648.0935516,8.479991912841797,15.3666311963349,1739502648.093555,8.479991912841797,-0.3314624160970876,1739502648.0935585,8.479991912841797,14.718883599438227,1739502648.0935614,8.479991912841797,20.931858128073326,1739502648.0935626,8.479991912841797,-0.12774706452398912,1739502648.0935647,8.479991912841797,0.03658870323191038,1739502648.0935662,8.479991912841797,0.19799067418306202,1739502648.0935678,8.479991912841797,0.049025270852730854,1739502648.0935693,8.479991912841797,2.1337866952703246,1739502648.0935712,8.479991912841797,0.0,1739502648.0935726,8.479991912841797,0.02417416007929729,1739502648.0935748,8.479991912841797,0.0010286320209066762,1739502648.0935767,8.479991912841797,2.1096125351910273 +1739502648.113419,8.49999189376831,15.3666311963349,1739502648.1134217,8.49999189376831,-0.3314624160970876,1739502648.1134245,8.49999189376831,14.718883599438227,1739502648.1134276,8.49999189376831,20.931858128073326,1739502648.113429,8.49999189376831,-0.12774706452398912,1739502648.1134312,8.49999189376831,0.03658870323191038,1739502648.113433,8.49999189376831,0.19799067418306202,1739502648.1134343,8.49999189376831,0.049025270852730854,1739502648.113436,8.49999189376831,2.1337866952703246,1739502648.1134377,8.49999189376831,0.0,1739502648.1134393,8.49999189376831,0.02417416007929729,1739502648.1134408,8.49999189376831,0.0010286320209066762,1739502648.1134427,8.49999189376831,2.1096125351910273 +1739502648.1336672,8.519991874694824,15.3666311963349,1739502648.1336703,8.519991874694824,-0.3314624160970876,1739502648.1336737,8.519991874694824,14.718883599438227,1739502648.133677,8.519991874694824,20.931858128073326,1739502648.1336787,8.519991874694824,-0.12774706452398912,1739502648.1336806,8.519991874694824,0.03658870323191038,1739502648.1336825,8.519991874694824,0.19799067418306202,1739502648.133684,8.519991874694824,0.049025270852730854,1739502648.1336854,8.519991874694824,2.1337866952703246,1739502648.133687,8.519991874694824,0.0,1739502648.1336887,8.519991874694824,0.02417416007929729,1739502648.1336904,8.519991874694824,0.0010286320209066762,1739502648.1336923,8.519991874694824,2.1096125351910273 +1739502648.1534438,8.539991855621338,15.598819852072186,1739502648.1534464,8.539991855621338,-0.3311349324384123,1739502648.1534498,8.539991855621338,14.951939730631413,1739502648.1534529,8.539991855621338,21.170194072788068,1739502648.1534543,8.539991855621338,-0.127,1739502648.1534564,8.539991855621338,0.03662357766454231,1739502648.1534579,8.539991855621338,0.193725182295535,1739502648.1534595,8.539991855621338,0.047863355590919525,1739502648.1534607,8.539991855621338,2.1410804526485703,1739502648.1534624,8.539991855621338,0.0,1739502648.153464,8.539991855621338,0.03094117267530242,1739502648.1534655,8.539991855621338,0.0018683720547678334,1739502648.1534672,8.539991855621338,2.11225397279602 +1739502648.1734095,8.559991836547852,15.598819852072186,1739502648.173412,8.559991836547852,-0.3311349324384123,1739502648.1734152,8.559991836547852,14.951939730631413,1739502648.1734183,8.559991836547852,21.170194072788068,1739502648.1734197,8.559991836547852,-0.127,1739502648.1734216,8.559991836547852,0.03662357766454231,1739502648.173423,8.559991836547852,0.193725182295535,1739502648.1734247,8.559991836547852,0.047863355590919525,1739502648.1734262,8.559991836547852,2.1410804526485703,1739502648.173428,8.559991836547852,0.0,1739502648.1734293,8.559991836547852,0.028826479852550158,1739502648.1734312,8.559991836547852,0.0018683720547678334,1739502648.1734326,8.559991836547852,2.11225397279602 +1739502648.1935277,8.579991817474365,15.598819852072186,1739502648.1935308,8.579991817474365,-0.3311349324384123,1739502648.1935341,8.579991817474365,14.951939730631413,1739502648.1935372,8.579991817474365,21.170194072788068,1739502648.193539,8.579991817474365,-0.127,1739502648.1935408,8.579991817474365,0.03662357766454231,1739502648.1935425,8.579991817474365,0.193725182295535,1739502648.1935441,8.579991817474365,0.047863355590919525,1739502648.1935456,8.579991817474365,2.1410804526485703,1739502648.1935475,8.579991817474365,0.0,1739502648.1935492,8.579991817474365,0.028826479852550158,1739502648.1935506,8.579991817474365,0.0018683720547678334,1739502648.1935525,8.579991817474365,2.11225397279602 +1739502648.21338,8.599991798400879,15.598819852072186,1739502648.2133827,8.599991798400879,-0.3311349324384123,1739502648.2133858,8.599991798400879,14.951939730631413,1739502648.2133892,8.599991798400879,21.170194072788068,1739502648.2133906,8.599991798400879,-0.127,1739502648.2133927,8.599991798400879,0.03662357766454231,1739502648.2133944,8.599991798400879,0.193725182295535,1739502648.213396,8.599991798400879,0.047863355590919525,1739502648.2133973,8.599991798400879,2.1410804526485703,1739502648.213399,8.599991798400879,0.0,1739502648.2134006,8.599991798400879,0.028826479852550158,1739502648.2134023,8.599991798400879,0.0018683720547678334,1739502648.2134037,8.599991798400879,2.11225397279602 +1739502648.2335467,8.619991779327393,15.598819852072186,1739502648.2335496,8.619991779327393,-0.3311349324384123,1739502648.2335532,8.619991779327393,14.951939730631413,1739502648.233556,8.619991779327393,21.170194072788068,1739502648.2335577,8.619991779327393,-0.127,1739502648.2335598,8.619991779327393,0.03662357766454231,1739502648.2335613,8.619991779327393,0.193725182295535,1739502648.2335627,8.619991779327393,0.047863355590919525,1739502648.2335641,8.619991779327393,2.1410804526485703,1739502648.2335663,8.619991779327393,0.0,1739502648.2335677,8.619991779327393,0.028826479852550158,1739502648.2335694,8.619991779327393,0.0018683720547678334,1739502648.233571,8.619991779327393,2.11225397279602 +1739502648.253409,8.639991760253906,15.598819852072186,1739502648.2534113,8.639991760253906,-0.3311349324384123,1739502648.2534146,8.639991760253906,14.951939730631413,1739502648.2534177,8.639991760253906,21.170194072788068,1739502648.253419,8.639991760253906,-0.127,1739502648.253421,8.639991760253906,0.03662357766454231,1739502648.2534225,8.639991760253906,0.193725182295535,1739502648.2534242,8.639991760253906,0.047863355590919525,1739502648.2534254,8.639991760253906,2.1410804526485703,1739502648.2534273,8.639991760253906,0.0,1739502648.2534287,8.639991760253906,0.028826479852550158,1739502648.2534304,8.639991760253906,0.0018683720547678334,1739502648.2534318,8.639991760253906,2.11225397279602 +1739502648.2735016,8.65999174118042,15.831329303447621,1739502648.2735045,8.65999174118042,-0.3306117442033729,1739502648.2735078,8.65999174118042,14.97867779435135,1739502648.273511,8.65999174118042,21.203328635505027,1739502648.2735124,8.65999174118042,-0.127,1739502648.2735143,8.65999174118042,0.03788427979556988,1739502648.273516,8.65999174118042,0.18906303902359334,1739502648.2735176,8.65999174118042,0.05023794881371051,1739502648.2735188,8.65999174118042,2.149080982281873,1739502648.2735207,8.65999174118042,0.0,1739502648.273522,8.65999174118042,0.035811616675797575,1739502648.2735238,8.65999174118042,0.0027081120886289904,1739502648.2735252,8.65999174118042,2.1154522222945324 +1739502648.2933815,8.679991722106934,15.831329303447621,1739502648.2933838,8.679991722106934,-0.3306117442033729,1739502648.2933872,8.679991722106934,14.97867779435135,1739502648.2933903,8.679991722106934,21.203328635505027,1739502648.293392,8.679991722106934,-0.127,1739502648.2933936,8.679991722106934,0.03788427979556988,1739502648.2933953,8.679991722106934,0.18906303902359334,1739502648.2933967,8.679991722106934,0.05023794881371051,1739502648.293398,8.679991722106934,2.149080982281873,1739502648.2933998,8.679991722106934,0.0,1739502648.2934012,8.679991722106934,0.033628759987340384,1739502648.293403,8.679991722106934,0.0027081120886289904,1739502648.2934046,8.679991722106934,2.1154522222945324 +1739502648.3134208,8.699991703033447,15.831329303447621,1739502648.3134239,8.699991703033447,-0.3306117442033729,1739502648.3134272,8.699991703033447,14.97867779435135,1739502648.3134305,8.699991703033447,21.203328635505027,1739502648.313432,8.699991703033447,-0.127,1739502648.3134341,8.699991703033447,0.03788427979556988,1739502648.3134356,8.699991703033447,0.18906303902359334,1739502648.3134375,8.699991703033447,0.05023794881371051,1739502648.313439,8.699991703033447,2.149080982281873,1739502648.3134408,8.699991703033447,0.0,1739502648.3134422,8.699991703033447,0.033628759987340384,1739502648.3134441,8.699991703033447,0.0027081120886289904,1739502648.3134458,8.699991703033447,2.1154522222945324 +1739502648.3332846,8.719991683959961,15.831329303447621,1739502648.3332872,8.719991683959961,-0.3306117442033729,1739502648.33329,8.719991683959961,14.97867779435135,1739502648.3332925,8.719991683959961,21.203328635505027,1739502648.3332942,8.719991683959961,-0.127,1739502648.3332956,8.719991683959961,0.03788427979556988,1739502648.3332973,8.719991683959961,0.18906303902359334,1739502648.3332984,8.719991683959961,0.05023794881371051,1739502648.3332999,8.719991683959961,2.149080982281873,1739502648.3333015,8.719991683959961,0.0,1739502648.3333027,8.719991683959961,0.033628759987340384,1739502648.3333044,8.719991683959961,0.0027081120886289904,1739502648.3333056,8.719991683959961,2.1154522222945324 +1739502648.3532665,8.739991664886475,15.831329303447621,1739502648.3532686,8.739991664886475,-0.3306117442033729,1739502648.3532715,8.739991664886475,14.97867779435135,1739502648.3532743,8.739991664886475,21.203328635505027,1739502648.3532755,8.739991664886475,-0.127,1739502648.3532774,8.739991664886475,0.03788427979556988,1739502648.3532789,8.739991664886475,0.18906303902359334,1739502648.3532803,8.739991664886475,0.05023794881371051,1739502648.3532815,8.739991664886475,2.149080982281873,1739502648.3532832,8.739991664886475,0.0,1739502648.3532844,8.739991664886475,0.033628759987340384,1739502648.3532858,8.739991664886475,0.0027081120886289904,1739502648.3532872,8.739991664886475,2.1154522222945324 +1739502648.3733964,8.759991645812988,16.064210997905523,1739502648.3733988,8.759991645812988,-0.3298921529563037,1739502648.3734016,8.759991645812988,15.596616587220048,1739502648.3734045,8.759991645812988,21.828609118798653,1739502648.3734057,8.759991645812988,-0.125,1739502648.3734076,8.759991645812988,0.03552945628146186,1739502648.3734088,8.759991645812988,0.18443967423882898,1739502648.37341,8.759991645812988,0.042572595932455035,1739502648.3734114,8.759991645812988,2.1570444887478786,1739502648.3734133,8.759991645812988,0.0,1739502648.3734145,8.759991645812988,0.03986667160889012,1739502648.373416,8.759991645812988,0.0035478521224901476,1739502648.3734174,8.759991645812988,2.1191271657988153 +1739502648.393486,8.779991626739502,16.064210997905523,1739502648.3934886,8.779991626739502,-0.3298921529563037,1739502648.3934915,8.779991626739502,15.596616587220048,1739502648.3934944,8.779991626739502,21.828609118798653,1739502648.3934956,8.779991626739502,-0.125,1739502648.393497,8.779991626739502,0.03552945628146186,1739502648.3934987,8.779991626739502,0.18443967423882898,1739502648.3935,8.779991626739502,0.042572595932455035,1739502648.3935015,8.779991626739502,2.1570444887478786,1739502648.393503,8.779991626739502,0.0,1739502648.3935041,8.779991626739502,0.03791732294906325,1739502648.3935058,8.779991626739502,0.0035478521224901476,1739502648.3935072,8.779991626739502,2.1191271657988153 +1739502648.4132805,8.799991607666016,16.064210997905523,1739502648.4132829,8.799991607666016,-0.3298921529563037,1739502648.4132857,8.799991607666016,15.596616587220048,1739502648.4132884,8.799991607666016,21.828609118798653,1739502648.41329,8.799991607666016,-0.125,1739502648.4132915,8.799991607666016,0.03552945628146186,1739502648.413293,8.799991607666016,0.18443967423882898,1739502648.413294,8.799991607666016,0.042572595932455035,1739502648.4132955,8.799991607666016,2.1570444887478786,1739502648.4132972,8.799991607666016,0.0,1739502648.4132984,8.799991607666016,0.03791732294906325,1739502648.4133,8.799991607666016,0.0035478521224901476,1739502648.4133015,8.799991607666016,2.1191271657988153 +1739502648.4335065,8.81999158859253,16.064210997905523,1739502648.433509,8.81999158859253,-0.3298921529563037,1739502648.4335117,8.81999158859253,15.596616587220048,1739502648.4335146,8.81999158859253,21.828609118798653,1739502648.4335158,8.81999158859253,-0.125,1739502648.4335172,8.81999158859253,0.03552945628146186,1739502648.433519,8.81999158859253,0.18443967423882898,1739502648.4335203,8.81999158859253,0.042572595932455035,1739502648.4335215,8.81999158859253,2.1570444887478786,1739502648.4335232,8.81999158859253,0.0,1739502648.4335241,8.81999158859253,0.03791732294906325,1739502648.4335258,8.81999158859253,0.0035478521224901476,1739502648.4335275,8.81999158859253,2.1191271657988153 +1739502648.4533565,8.839991569519043,16.064210997905523,1739502648.4533591,8.839991569519043,-0.3298921529563037,1739502648.4533627,8.839991569519043,15.596616587220048,1739502648.4533658,8.839991569519043,21.828609118798653,1739502648.453367,8.839991569519043,-0.125,1739502648.453369,8.839991569519043,0.03552945628146186,1739502648.45337,8.839991569519043,0.18443967423882898,1739502648.4533718,8.839991569519043,0.042572595932455035,1739502648.4533727,8.839991569519043,2.1570444887478786,1739502648.4533744,8.839991569519043,0.0,1739502648.453376,8.839991569519043,0.03791732294906325,1739502648.4533775,8.839991569519043,0.0035478521224901476,1739502648.453379,8.839991569519043,2.1191271657988153 +1739502648.4734483,8.859991550445557,16.064210997905523,1739502648.4734507,8.859991550445557,-0.3298921529563037,1739502648.4734535,8.859991550445557,15.596616587220048,1739502648.4734564,8.859991550445557,21.828609118798653,1739502648.4734576,8.859991550445557,-0.125,1739502648.4734595,8.859991550445557,0.03552945628146186,1739502648.473461,8.859991550445557,0.18443967423882898,1739502648.4734623,8.859991550445557,0.042572595932455035,1739502648.4734635,8.859991550445557,2.1570444887478786,1739502648.4734652,8.859991550445557,0.0,1739502648.4734664,8.859991550445557,0.03791732294906325,1739502648.4734676,8.859991550445557,0.0035478521224901476,1739502648.4734693,8.859991550445557,2.1191271657988153 +1739502648.4934576,8.87999153137207,16.2975248353152,1739502648.4934602,8.87999153137207,-0.328975297434285,1739502648.493463,8.87999153137207,15.639778730285318,1739502648.4934657,8.87999153137207,21.880151244848854,1739502648.493467,8.87999153137207,-0.12480033393939141,1739502648.4934688,8.87999153137207,0.03655698704755603,1739502648.4934702,8.87999153137207,0.17967878895890965,1739502648.4934719,8.87999153137207,0.04421492849139795,1739502648.493473,8.87999153137207,2.1652757070356143,1739502648.4934745,8.87999153137207,0.0,1739502648.4934762,8.87999153137207,0.04379497547214489,1739502648.4934776,8.87999153137207,0.004387592156351304,1739502648.4934793,8.87999153137207,2.123317499181211 +1739502648.52271,8.899991512298584,16.2975248353152,1739502648.5227191,8.899991512298584,-0.328975297434285,1739502648.5227299,8.899991512298584,15.639778730285318,1739502648.5227394,8.899991512298584,21.880151244848854,1739502648.5227442,8.899991512298584,-0.12480033393939141,1739502648.5227504,8.899991512298584,0.03655698704755603,1739502648.5227554,8.899991512298584,0.17967878895890965,1739502648.52276,8.899991512298584,0.04421492849139795,1739502648.5227644,8.899991512298584,2.1652757070356143,1739502648.52277,8.899991512298584,0.0,1739502648.5227747,8.899991512298584,0.041958207854403184,1739502648.52278,8.899991512298584,0.004387592156351304,1739502648.522785,8.899991512298584,2.123317499181211 +1739502648.563303,8.939991474151611,16.2975248353152,1739502648.5633094,8.939991474151611,-0.328975297434285,1739502648.563316,8.939991474151611,15.639778730285318,1739502648.5633216,8.939991474151611,21.880151244848854,1739502648.5633242,8.939991474151611,-0.12480033393939141,1739502648.5633278,8.939991474151611,0.03655698704755603,1739502648.5633314,8.939991474151611,0.17967878895890965,1739502648.563334,8.939991474151611,0.04421492849139795,1739502648.5633364,8.939991474151611,2.1652757070356143,1739502648.56334,8.939991474151611,0.0,1739502648.5633426,8.939991474151611,0.041958207854403184,1739502648.5633457,8.939991474151611,0.004387592156351304,1739502648.563349,8.939991474151611,2.123317499181211 +1739502648.5804315,8.959991455078125,16.2975248353152,1739502648.5804374,8.959991455078125,-0.328975297434285,1739502648.5804446,8.959991455078125,15.639778730285318,1739502648.5804522,8.959991455078125,21.880151244848854,1739502648.5804572,8.959991455078125,-0.12480033393939141,1739502648.5804644,8.959991455078125,0.03655698704755603,1739502648.5804706,8.959991455078125,0.17967878895890965,1739502648.580477,8.959991455078125,0.04421492849139795,1739502648.580482,8.959991455078125,2.1652757070356143,1739502648.580486,8.959991455078125,0.0,1739502648.5804904,8.959991455078125,0.041958207854403184,1739502648.5804944,8.959991455078125,0.004387592156351304,1739502648.5804987,8.959991455078125,2.123317499181211 +1739502648.600592,8.979991436004639,16.531315927187865,1739502648.6005964,8.979991436004639,-0.3278602357413485,1739502648.6006014,8.979991436004639,15.774074010691326,1739502648.6006067,8.979991436004639,22.02361716529274,1739502648.60061,8.979991436004639,-0.124,1739502648.6006157,8.979991436004639,0.03710042192523559,1739502648.6006193,8.979991436004639,0.17514749819707767,1739502648.6006227,8.979991436004639,0.044527329456923934,1739502648.600626,8.979991436004639,2.1731391460825575,1739502648.6006298,8.979991436004639,0.0,1739502648.6006331,8.979991436004639,0.046724389070108535,1739502648.600637,8.979991436004639,0.0052273321902124616,1739502648.6006405,8.979991436004639,2.127904189618905 +1739502648.6191697,8.999991416931152,16.531315927187865,1739502648.6191735,8.999991416931152,-0.3278602357413485,1739502648.6191778,8.999991416931152,15.774074010691326,1739502648.619182,8.999991416931152,22.02361716529274,1739502648.619184,8.999991416931152,-0.124,1739502648.6191869,8.999991416931152,0.03710042192523559,1739502648.6191897,8.999991416931152,0.17514749819707767,1739502648.6191921,8.999991416931152,0.044527329456923934,1739502648.619194,8.999991416931152,2.1731391460825575,1739502648.6191967,8.999991416931152,0.0,1739502648.619199,8.999991416931152,0.0452349564636525,1739502648.619201,8.999991416931152,0.0052273321902124616,1739502648.6192033,8.999991416931152,2.127904189618905 +1739502648.639216,9.019991397857666,16.531315927187865,1739502648.6392183,9.019991397857666,-0.3278602357413485,1739502648.6392214,9.019991397857666,15.774074010691326,1739502648.6392245,9.019991397857666,22.02361716529274,1739502648.639226,9.019991397857666,-0.124,1739502648.6392283,9.019991397857666,0.03710042192523559,1739502648.6392298,9.019991397857666,0.17514749819707767,1739502648.6392312,9.019991397857666,0.044527329456923934,1739502648.6392324,9.019991397857666,2.1731391460825575,1739502648.639234,9.019991397857666,0.0,1739502648.6392353,9.019991397857666,0.0452349564636525,1739502648.6392367,9.019991397857666,0.0052273321902124616,1739502648.639238,9.019991397857666,2.127904189618905 +1739502648.6597111,9.03999137878418,16.531315927187865,1739502648.6597145,9.03999137878418,-0.3278602357413485,1739502648.6597192,9.03999137878418,15.774074010691326,1739502648.659725,9.03999137878418,22.02361716529274,1739502648.6597278,9.03999137878418,-0.124,1739502648.6597316,9.03999137878418,0.03710042192523559,1739502648.6597352,9.03999137878418,0.17514749819707767,1739502648.6597388,9.03999137878418,0.044527329456923934,1739502648.659742,9.03999137878418,2.1731391460825575,1739502648.6597457,9.03999137878418,0.0,1739502648.6597493,9.03999137878418,0.0452349564636525,1739502648.6597528,9.03999137878418,0.0052273321902124616,1739502648.6597562,9.03999137878418,2.127904189618905 +1739502648.6795387,9.059991359710693,16.531315927187865,1739502648.6795423,9.059991359710693,-0.3278602357413485,1739502648.6795468,9.059991359710693,15.774074010691326,1739502648.6795523,9.059991359710693,22.02361716529274,1739502648.6795552,9.059991359710693,-0.124,1739502648.679559,9.059991359710693,0.03710042192523559,1739502648.6795628,9.059991359710693,0.17514749819707767,1739502648.6795661,9.059991359710693,0.044527329456923934,1739502648.6795695,9.059991359710693,2.1731391460825575,1739502648.6795728,9.059991359710693,0.0,1739502648.6795764,9.059991359710693,0.0452349564636525,1739502648.67958,9.059991359710693,0.0052273321902124616,1739502648.6795833,9.059991359710693,2.127904189618905 +1739502648.7002532,9.079991340637207,16.531315927187865,1739502648.700257,9.079991340637207,-0.3278602357413485,1739502648.7002623,9.079991340637207,15.774074010691326,1739502648.7002676,9.079991340637207,22.02361716529274,1739502648.7002704,9.079991340637207,-0.124,1739502648.700274,9.079991340637207,0.03710042192523559,1739502648.7002773,9.079991340637207,0.17514749819707767,1739502648.7002807,9.079991340637207,0.044527329456923934,1739502648.7002838,9.079991340637207,2.1731391460825575,1739502648.7002873,9.079991340637207,0.0,1739502648.7002904,9.079991340637207,0.0452349564636525,1739502648.7002943,9.079991340637207,0.0052273321902124616,1739502648.7002974,9.079991340637207,2.127904189618905 +1739502648.7182207,9.09999132156372,16.76563261632459,1739502648.718223,9.09999132156372,-0.326545894117066,1739502648.718226,9.09999132156372,15.904780379247509,1739502648.7182288,9.09999132156372,22.164288336033852,1739502648.71823,9.09999132156372,-0.124,1739502648.7182314,9.09999132156372,0.037500250260539596,1739502648.7182329,9.09999132156372,0.16978833311337133,1739502648.718234,9.09999132156372,0.044673997723277674,1739502648.7182355,9.09999132156372,2.18247611627332,1739502648.7182372,9.09999132156372,0.0,1739502648.7182384,9.09999132156372,0.051568877039744575,1739502648.71824,9.09999132156372,0.006067072224073619,1739502648.7182417,9.09999132156372,2.1328865907113683 +1739502648.7380915,9.119991302490234,16.76563261632459,1739502648.7380939,9.119991302490234,-0.326545894117066,1739502648.7380965,9.119991302490234,15.904780379247509,1739502648.7380986,9.119991302490234,22.164288336033852,1739502648.7381,9.119991302490234,-0.124,1739502648.7381015,9.119991302490234,0.037500250260539596,1739502648.7381027,9.119991302490234,0.16978833311337133,1739502648.738104,9.119991302490234,0.044673997723277674,1739502648.7381053,9.119991302490234,2.18247611627332,1739502648.7381067,9.119991302490234,0.0,1739502648.738108,9.119991302490234,0.04958952556195184,1739502648.738109,9.119991302490234,0.006067072224073619,1739502648.7381108,9.119991302490234,2.1328865907113683 +1739502648.758157,9.139991283416748,16.76563261632459,1739502648.7581594,9.139991283416748,-0.326545894117066,1739502648.7581623,9.139991283416748,15.904780379247509,1739502648.7581646,9.139991283416748,22.164288336033852,1739502648.7581663,9.139991283416748,-0.124,1739502648.7581682,9.139991283416748,0.037500250260539596,1739502648.7581697,9.139991283416748,0.16978833311337133,1739502648.758171,9.139991283416748,0.044673997723277674,1739502648.7581723,9.139991283416748,2.18247611627332,1739502648.7581737,9.139991283416748,0.0,1739502648.758175,9.139991283416748,0.04958952556195184,1739502648.7581766,9.139991283416748,0.006067072224073619,1739502648.7581778,9.139991283416748,2.1328865907113683 +1739502648.7780929,9.159991264343262,16.76563261632459,1739502648.7780948,9.159991264343262,-0.326545894117066,1739502648.7780976,9.159991264343262,15.904780379247509,1739502648.7781003,9.159991264343262,22.164288336033852,1739502648.7781014,9.159991264343262,-0.124,1739502648.7781034,9.159991264343262,0.037500250260539596,1739502648.7781045,9.159991264343262,0.16978833311337133,1739502648.778106,9.159991264343262,0.044673997723277674,1739502648.7781072,9.159991264343262,2.18247611627332,1739502648.7781086,9.159991264343262,0.0,1739502648.77811,9.159991264343262,0.04958952556195184,1739502648.7781112,9.159991264343262,0.006067072224073619,1739502648.7781124,9.159991264343262,2.1328865907113683 +1739502648.798185,9.179991245269775,16.76563261632459,1739502648.7981875,9.179991245269775,-0.326545894117066,1739502648.7981904,9.179991245269775,15.904780379247509,1739502648.798193,9.179991245269775,22.164288336033852,1739502648.7981944,9.179991245269775,-0.124,1739502648.798196,9.179991245269775,0.037500250260539596,1739502648.7981977,9.179991245269775,0.16978833311337133,1739502648.798199,9.179991245269775,0.044673997723277674,1739502648.7982001,9.179991245269775,2.18247611627332,1739502648.7982018,9.179991245269775,0.0,1739502648.7982032,9.179991245269775,0.04958952556195184,1739502648.7982044,9.179991245269775,0.006067072224073619,1739502648.7982056,9.179991245269775,2.1328865907113683 +1739502648.8181663,9.199991226196289,17.000515792780938,1739502648.8181684,9.199991226196289,-0.32503112340723117,1739502648.818171,9.199991226196289,16.11537984765894,1739502648.8181736,9.199991226196289,22.385729515020287,1739502648.8181753,9.199991226196289,-0.12383146735755864,1739502648.818177,9.199991226196289,0.03734412927429915,1739502648.8181784,9.199991226196289,0.1640004926225866,1739502648.8181796,9.199991226196289,0.04336750437571474,1739502648.8181808,9.199991226196289,2.192605006846808,1739502648.8181827,9.199991226196289,0.0,1739502648.818184,9.199991226196289,0.056437080687229885,1739502648.8181853,9.199991226196289,0.006906812257934776,1739502648.8181865,9.199991226196289,2.1383077885392305 +1739502648.838196,9.219991207122803,17.000515792780938,1739502648.838198,9.219991207122803,-0.32503112340723117,1739502648.838201,9.219991207122803,16.11537984765894,1739502648.8382037,9.219991207122803,22.385729515020287,1739502648.8382049,9.219991207122803,-0.12383146735755864,1739502648.8382068,9.219991207122803,0.03734412927429915,1739502648.8382082,9.219991207122803,0.1640004926225866,1739502648.8382094,9.219991207122803,0.04336750437571474,1739502648.8382106,9.219991207122803,2.192605006846808,1739502648.838212,9.219991207122803,0.0,1739502648.8382134,9.219991207122803,0.05429721830757739,1739502648.8382149,9.219991207122803,0.006906812257934776,1739502648.8382165,9.219991207122803,2.1383077885392305 +1739502648.858158,9.239991188049316,17.000515792780938,1739502648.85816,9.239991188049316,-0.32503112340723117,1739502648.8581629,9.239991188049316,16.11537984765894,1739502648.8581657,9.239991188049316,22.385729515020287,1739502648.858167,9.239991188049316,-0.12383146735755864,1739502648.8581686,9.239991188049316,0.03734412927429915,1739502648.85817,9.239991188049316,0.1640004926225866,1739502648.8581715,9.239991188049316,0.04336750437571474,1739502648.8581727,9.239991188049316,2.192605006846808,1739502648.8581746,9.239991188049316,0.0,1739502648.8581758,9.239991188049316,0.05429721830757739,1739502648.858177,9.239991188049316,0.006906812257934776,1739502648.8581784,9.239991188049316,2.1383077885392305 +1739502648.8782184,9.25999116897583,17.000515792780938,1739502648.8782206,9.25999116897583,-0.32503112340723117,1739502648.8782234,9.25999116897583,16.11537984765894,1739502648.8782258,9.25999116897583,22.385729515020287,1739502648.8782272,9.25999116897583,-0.12383146735755864,1739502648.8782287,9.25999116897583,0.03734412927429915,1739502648.87823,9.25999116897583,0.1640004926225866,1739502648.8782315,9.25999116897583,0.04336750437571474,1739502648.8782327,9.25999116897583,2.192605006846808,1739502648.8782341,9.25999116897583,0.0,1739502648.8782353,9.25999116897583,0.05429721830757739,1739502648.8782368,9.25999116897583,0.006906812257934776,1739502648.8782382,9.25999116897583,2.1383077885392305 +1739502648.9057703,9.279991149902344,17.000515792780938,1739502648.9057827,9.279991149902344,-0.32503112340723117,1739502648.9058,9.279991149902344,16.11537984765894,1739502648.90582,9.279991149902344,22.385729515020287,1739502648.9058306,9.279991149902344,-0.12383146735755864,1739502648.905845,9.279991149902344,0.03734412927429915,1739502648.9058576,9.279991149902344,0.1640004926225866,1739502648.9058702,9.279991149902344,0.04336750437571474,1739502648.9058826,9.279991149902344,2.192605006846808,1739502648.9058955,9.279991149902344,0.0,1739502648.905908,9.279991149902344,0.05429721830757739,1739502648.9059212,9.279991149902344,0.006906812257934776,1739502648.905934,9.279991149902344,2.1383077885392305 +1739502648.925946,9.299991130828857,17.000515792780938,1739502648.9259553,9.299991130828857,-0.32503112340723117,1739502648.9259675,9.299991130828857,16.11537984765894,1739502648.9259813,9.299991130828857,22.385729515020287,1739502648.925989,9.299991130828857,-0.12383146735755864,1739502648.925999,9.299991130828857,0.03734412927429915,1739502648.9260075,9.299991130828857,0.1640004926225866,1739502648.9260163,9.299991130828857,0.04336750437571474,1739502648.926025,9.299991130828857,2.192605006846808,1739502648.926034,9.299991130828857,0.0,1739502648.9260426,9.299991130828857,0.05429721830757739,1739502648.9260516,9.299991130828857,0.006906812257934776,1739502648.9260612,9.299991130828857,2.1383077885392305 +1739502648.9406605,9.319991111755371,17.23602524136425,1739502648.940665,9.319991111755371,-0.32331453387254605,1739502648.9406807,9.319991111755371,16.372177316377147,1739502648.9406893,9.319991111755371,22.65449429677763,1739502648.9406936,9.319991111755371,-0.12191218785235301,1739502648.9406989,9.319991111755371,0.03715250002525894,1739502648.9407034,9.319991111755371,0.15942226899393913,1739502648.9407082,9.319991111755371,0.04164180245632709,1739502648.9407127,9.319991111755371,2.20065031999077,1739502648.9407175,9.319991111755371,0.0,1739502648.9407222,9.319991111755371,0.05729043418758249,1739502648.9407268,9.319991111755371,0.007746552291795933,1739502648.9407313,9.319991111755371,2.1442952663789723 +1739502648.960358,9.339991092681885,17.23602524136425,1739502648.9603617,9.339991092681885,-0.32331453387254605,1739502648.960366,9.339991092681885,16.372177316377147,1739502648.9603713,9.339991092681885,22.65449429677763,1739502648.960374,9.339991092681885,-0.12191218785235301,1739502648.9603777,9.339991092681885,0.03715250002525894,1739502648.960381,9.339991092681885,0.15942226899393913,1739502648.960384,9.339991092681885,0.04164180245632709,1739502648.9603872,9.339991092681885,2.20065031999077,1739502648.9603906,9.339991092681885,0.0,1739502648.960394,9.339991092681885,0.0563550536117976,1739502648.9603972,9.339991092681885,0.007746552291795933,1739502648.9604006,9.339991092681885,2.1442952663789723 +1739502648.9783869,9.359991073608398,17.23602524136425,1739502648.9783893,9.359991073608398,-0.32331453387254605,1739502648.978392,9.359991073608398,16.372177316377147,1739502648.9783943,9.359991073608398,22.65449429677763,1739502648.9783957,9.359991073608398,-0.12191218785235301,1739502648.9783971,9.359991073608398,0.03715250002525894,1739502648.9783986,9.359991073608398,0.15942226899393913,1739502648.9784002,9.359991073608398,0.04164180245632709,1739502648.9784012,9.359991073608398,2.20065031999077,1739502648.9784029,9.359991073608398,0.0,1739502648.978404,9.359991073608398,0.0563550536117976,1739502648.9784055,9.359991073608398,0.007746552291795933,1739502648.978407,9.359991073608398,2.1442952663789723 +1739502648.9988844,9.379991054534912,17.23602524136425,1739502648.9988866,9.379991054534912,-0.32331453387254605,1739502648.9988894,9.379991054534912,16.372177316377147,1739502648.9988923,9.379991054534912,22.65449429677763,1739502648.9988933,9.379991054534912,-0.12191218785235301,1739502648.9988952,9.379991054534912,0.03715250002525894,1739502648.9988966,9.379991054534912,0.15942226899393913,1739502648.998898,9.379991054534912,0.04164180245632709,1739502648.9988992,9.379991054534912,2.20065031999077,1739502648.9989007,9.379991054534912,0.0,1739502648.998902,9.379991054534912,0.0563550536117976,1739502648.9989033,9.379991054534912,0.007746552291795933,1739502648.998905,9.379991054534912,2.1442952663789723 +1739502649.0263739,9.399991035461426,17.23602524136425,1739502649.0263827,9.399991035461426,-0.32331453387254605,1739502649.0263934,9.399991035461426,16.372177316377147,1739502649.026404,9.399991035461426,22.65449429677763,1739502649.0264087,9.399991035461426,-0.12191218785235301,1739502649.0264153,9.399991035461426,0.03715250002525894,1739502649.0264206,9.399991035461426,0.15942226899393913,1739502649.0264263,9.399991035461426,0.04164180245632709,1739502649.0264416,9.399991035461426,2.20065031999077,1739502649.0264573,9.399991035461426,0.0,1739502649.0264657,9.399991035461426,0.0563550536117976,1739502649.026478,9.399991035461426,0.007746552291795933,1739502649.026493,9.399991035461426,2.1442952663789723 +1739502649.048539,9.429991006851196,17.47219798369533,1739502649.0485427,9.429991006851196,-0.3213947727784241,1739502649.0485468,9.429991006851196,16.605548527229885,1739502649.0485506,9.429991006851196,22.900189452250707,1739502649.0485525,9.429991006851196,-0.121,1739502649.048555,9.429991006851196,0.036902011101122754,1739502649.0485568,9.429991006851196,0.15378163700835906,1739502649.0485585,9.429991006851196,0.04002856992896764,1739502649.0485606,9.429991006851196,2.210603206196326,1739502649.0485625,9.429991006851196,0.0,1739502649.0485644,9.429991006851196,0.06186761767216422,1739502649.0485663,9.429991006851196,0.00858629232565709,1739502649.048568,9.429991006851196,2.1504582659225018 +1739502649.0687244,9.44999098777771,17.47219798369533,1739502649.0687268,9.44999098777771,-0.3213947727784241,1739502649.0687304,9.44999098777771,16.605548527229885,1739502649.068733,9.44999098777771,22.900189452250707,1739502649.0687344,9.44999098777771,-0.121,1739502649.068736,9.44999098777771,0.036902011101122754,1739502649.0687616,9.44999098777771,0.15378163700835906,1739502649.0687628,9.44999098777771,0.04002856992896764,1739502649.0687642,9.44999098777771,2.210603206196326,1739502649.0687656,9.44999098777771,0.0,1739502649.068767,9.44999098777771,0.06014494027382433,1739502649.0687685,9.44999098777771,0.00858629232565709,1739502649.06877,9.44999098777771,2.1504582659225018 +1739502649.090777,9.469990968704224,17.47219798369533,1739502649.090781,9.469990968704224,-0.3213947727784241,1739502649.0907855,9.469990968704224,16.605548527229885,1739502649.090791,9.469990968704224,22.900189452250707,1739502649.0907936,9.469990968704224,-0.121,1739502649.090798,9.469990968704224,0.036902011101122754,1739502649.0908194,9.469990968704224,0.15378163700835906,1739502649.0908227,9.469990968704224,0.04002856992896764,1739502649.0908263,9.469990968704224,2.210603206196326,1739502649.0908296,9.469990968704224,0.0,1739502649.090833,9.469990968704224,0.06014494027382433,1739502649.0908365,9.469990968704224,0.00858629232565709,1739502649.09084,9.469990968704224,2.1504582659225018 +1739502649.1095407,9.489990949630737,17.47219798369533,1739502649.1095445,9.489990949630737,-0.3213947727784241,1739502649.109549,9.489990949630737,16.605548527229885,1739502649.1095538,9.489990949630737,22.900189452250707,1739502649.1095567,9.489990949630737,-0.121,1739502649.1095603,9.489990949630737,0.036902011101122754,1739502649.1095636,9.489990949630737,0.15378163700835906,1739502649.109567,9.489990949630737,0.04002856992896764,1739502649.1095703,9.489990949630737,2.210603206196326,1739502649.1095736,9.489990949630737,0.0,1739502649.109577,9.489990949630737,0.06014494027382433,1739502649.1095803,9.489990949630737,0.00858629232565709,1739502649.1095836,9.489990949630737,2.1504582659225018 +1739502649.129565,9.509990930557251,17.47219798369533,1739502649.1295714,9.509990930557251,-0.3213947727784241,1739502649.1295767,9.509990930557251,16.605548527229885,1739502649.1295831,9.509990930557251,22.900189452250707,1739502649.1295872,9.509990930557251,-0.121,1739502649.1295924,9.509990930557251,0.036902011101122754,1739502649.1295965,9.509990930557251,0.15378163700835906,1739502649.1296008,9.509990930557251,0.04002856992896764,1739502649.1296048,9.509990930557251,2.210603206196326,1739502649.1296084,9.509990930557251,0.0,1739502649.1296124,9.509990930557251,0.06014494027382433,1739502649.1296165,9.509990930557251,0.00858629232565709,1739502649.1296206,9.509990930557251,2.1504582659225018 +1739502649.1496406,9.529990911483765,17.70906730956616,1739502649.1496441,9.529990911483765,-0.31927042312120335,1739502649.1496484,9.529990911483765,16.903044074807163,1739502649.1496532,9.529990911483765,23.210834524041204,1739502649.149656,9.529990911483765,-0.12,1739502649.1496596,9.529990911483765,0.03620352276430119,1739502649.149663,9.529990911483765,0.1474025027465181,1739502649.1496665,9.529990911483765,0.03734821635069992,1739502649.1496696,9.529990911483765,2.221913429143492,1739502649.1496732,9.529990911483765,0.0,1739502649.1496766,9.529990911483765,0.06703078344003381,1739502649.14968,9.529990911483765,0.009426032359518248,1739502649.1496832,9.529990911483765,2.1570344731037467 +1739502649.1682904,9.549990892410278,17.70906730956616,1739502649.1682932,9.549990892410278,-0.31927042312120335,1739502649.1682959,9.549990892410278,16.903044074807163,1739502649.1682987,9.549990892410278,23.210834524041204,1739502649.1683,9.549990892410278,-0.12,1739502649.1683018,9.549990892410278,0.03620352276430119,1739502649.1683033,9.549990892410278,0.1474025027465181,1739502649.168305,9.549990892410278,0.03734821635069992,1739502649.1683059,9.549990892410278,2.221913429143492,1739502649.168308,9.549990892410278,0.0,1739502649.168309,9.549990892410278,0.06487895603974536,1739502649.1683106,9.549990892410278,0.009426032359518248,1739502649.1683118,9.549990892410278,2.1570344731037467 +1739502649.1886618,9.569990873336792,17.70906730956616,1739502649.1886647,9.569990873336792,-0.31927042312120335,1739502649.1886675,9.569990873336792,16.903044074807163,1739502649.1886811,9.569990873336792,23.210834524041204,1739502649.1886847,9.569990873336792,-0.12,1739502649.1886868,9.569990873336792,0.03620352276430119,1739502649.1886883,9.569990873336792,0.1474025027465181,1739502649.18869,9.569990873336792,0.03734821635069992,1739502649.1886911,9.569990873336792,2.221913429143492,1739502649.1886928,9.569990873336792,0.0,1739502649.188694,9.569990873336792,0.06487895603974536,1739502649.1886957,9.569990873336792,0.009426032359518248,1739502649.1886969,9.569990873336792,2.1570344731037467 +1739502649.2087286,9.589990854263306,17.70906730956616,1739502649.208731,9.589990854263306,-0.31927042312120335,1739502649.2087343,9.589990854263306,16.903044074807163,1739502649.2087371,9.589990854263306,23.210834524041204,1739502649.2087386,9.589990854263306,-0.12,1739502649.20874,9.589990854263306,0.03620352276430119,1739502649.2087417,9.589990854263306,0.1474025027465181,1739502649.2087429,9.589990854263306,0.03734821635069992,1739502649.2087443,9.589990854263306,2.221913429143492,1739502649.2087457,9.589990854263306,0.0,1739502649.2087471,9.589990854263306,0.06487895603974536,1739502649.2087488,9.589990854263306,0.009426032359518248,1739502649.2087502,9.589990854263306,2.1570344731037467 +1739502649.229136,9.60999083518982,17.70906730956616,1739502649.2291389,9.60999083518982,-0.31927042312120335,1739502649.229142,9.60999083518982,16.903044074807163,1739502649.2291453,9.60999083518982,23.210834524041204,1739502649.229147,9.60999083518982,-0.12,1739502649.2291486,9.60999083518982,0.03620352276430119,1739502649.2291505,9.60999083518982,0.1474025027465181,1739502649.229152,9.60999083518982,0.03734821635069992,1739502649.2291536,9.60999083518982,2.221913429143492,1739502649.2291553,9.60999083518982,0.0,1739502649.229157,9.60999083518982,0.06487895603974536,1739502649.2291584,9.60999083518982,0.009426032359518248,1739502649.2291603,9.60999083518982,2.1570344731037467 +1739502649.248302,9.629990816116333,17.70906730956616,1739502649.2483046,9.629990816116333,-0.31927042312120335,1739502649.2483077,9.629990816116333,16.903044074807163,1739502649.2483108,9.629990816116333,23.210834524041204,1739502649.2483122,9.629990816116333,-0.12,1739502649.2483141,9.629990816116333,0.03620352276430119,1739502649.2483158,9.629990816116333,0.1474025027465181,1739502649.2483175,9.629990816116333,0.03734821635069992,1739502649.2483187,9.629990816116333,2.221913429143492,1739502649.2483206,9.629990816116333,0.0,1739502649.248322,9.629990816116333,0.06487895603974536,1739502649.2483237,9.629990816116333,0.009426032359518248,1739502649.248325,9.629990816116333,2.1570344731037467 +1739502649.2686515,9.649990797042847,17.946689576017263,1739502649.268654,9.649990797042847,-0.3169397583136062,1739502649.2686572,9.649990797042847,17.179385043531553,1739502649.2686605,9.649990797042847,23.50146379369435,1739502649.268662,9.649990797042847,-0.119,1739502649.2686641,9.649990797042847,0.03561909691219017,1739502649.2686656,9.649990797042847,0.14090628212692993,1739502649.2686672,9.649990797042847,0.03502578725411877,1739502649.2686687,9.649990797042847,2.2334907184030963,1739502649.2686808,9.649990797042847,0.0,1739502649.2686844,9.649990797042847,0.07132420350019908,1739502649.268686,9.649990797042847,0.010265772393379405,1739502649.2686877,9.649990797042847,2.164180656054863 +1739502649.2884061,9.66999077796936,17.946689576017263,1739502649.2884085,9.66999077796936,-0.3169397583136062,1739502649.2884119,9.66999077796936,17.179385043531553,1739502649.288415,9.66999077796936,23.50146379369435,1739502649.2884166,9.66999077796936,-0.119,1739502649.2884185,9.66999077796936,0.03561909691219017,1739502649.2884202,9.66999077796936,0.14090628212692993,1739502649.2884219,9.66999077796936,0.03502578725411877,1739502649.288423,9.66999077796936,2.2334907184030963,1739502649.2884252,9.66999077796936,0.0,1739502649.2884266,9.66999077796936,0.06931006234823345,1739502649.2884283,9.66999077796936,0.010265772393379405,1739502649.2884297,9.66999077796936,2.164180656054863 +1739502649.308241,9.689990758895874,17.946689576017263,1739502649.3082442,9.689990758895874,-0.3169397583136062,1739502649.3082478,9.689990758895874,17.179385043531553,1739502649.3082511,9.689990758895874,23.50146379369435,1739502649.3082526,9.689990758895874,-0.119,1739502649.3082547,9.689990758895874,0.03561909691219017,1739502649.3082566,9.689990758895874,0.14090628212692993,1739502649.308258,9.689990758895874,0.03502578725411877,1739502649.3082595,9.689990758895874,2.2334907184030963,1739502649.3082614,9.689990758895874,0.0,1739502649.3082628,9.689990758895874,0.06931006234823345,1739502649.3082647,9.689990758895874,0.010265772393379405,1739502649.3082662,9.689990758895874,2.164180656054863 +1739502649.3282976,9.709990739822388,17.946689576017263,1739502649.3283007,9.709990739822388,-0.3169397583136062,1739502649.3283043,9.709990739822388,17.179385043531553,1739502649.3283076,9.709990739822388,23.50146379369435,1739502649.3283098,9.709990739822388,-0.119,1739502649.328312,9.709990739822388,0.03561909691219017,1739502649.3283134,9.709990739822388,0.14090628212692993,1739502649.328315,9.709990739822388,0.03502578725411877,1739502649.3283167,9.709990739822388,2.2334907184030963,1739502649.3283188,9.709990739822388,0.0,1739502649.3283203,9.709990739822388,0.06931006234823345,1739502649.328322,9.709990739822388,0.010265772393379405,1739502649.3283236,9.709990739822388,2.164180656054863 +1739502649.3485837,9.729990720748901,17.946689576017263,1739502649.3485863,9.729990720748901,-0.3169397583136062,1739502649.3485897,9.729990720748901,17.179385043531553,1739502649.348593,9.729990720748901,23.50146379369435,1739502649.3485944,9.729990720748901,-0.119,1739502649.3485963,9.729990720748901,0.03561909691219017,1739502649.348598,9.729990720748901,0.14090628212692993,1739502649.3485994,9.729990720748901,0.03502578725411877,1739502649.3486009,9.729990720748901,2.2334907184030963,1739502649.3486025,9.729990720748901,0.0,1739502649.3486042,9.729990720748901,0.06931006234823345,1739502649.348606,9.729990720748901,0.010265772393379405,1739502649.3486078,9.729990720748901,2.164180656054863 +1739502649.368371,9.749990701675415,18.185114401325777,1739502649.3683743,9.749990701675415,-0.31440098253542104,1739502649.368378,9.749990701675415,17.41655106410047,1739502649.3683813,9.749990701675415,23.75378088587902,1739502649.3683827,9.749990701675415,-0.11773348873269089,1739502649.3683848,9.749990701675415,0.03530213009431217,1739502649.3683863,9.749990701675415,0.13481374254005413,1739502649.3683884,9.749990701675415,0.033345231411683114,1739502649.3683896,9.749990701675415,2.244403395661785,1739502649.3683918,9.749990701675415,0.0,1739502649.3683932,9.749990701675415,0.0741603673194695,1739502649.368395,9.749990701675415,0.011105512427240562,1739502649.3683965,9.749990701675415,2.171758749639611 +1739502649.3887508,9.769990682601929,18.185114401325777,1739502649.3887534,9.769990682601929,-0.31440098253542104,1739502649.3887568,9.769990682601929,17.41655106410047,1739502649.38876,9.769990682601929,23.75378088587902,1739502649.3887613,9.769990682601929,-0.11773348873269089,1739502649.3887637,9.769990682601929,0.03530213009431217,1739502649.388765,9.769990682601929,0.13481374254005413,1739502649.3887668,9.769990682601929,0.033345231411683114,1739502649.3887682,9.769990682601929,2.244403395661785,1739502649.38877,9.769990682601929,0.0,1739502649.3887715,9.769990682601929,0.07264464602217391,1739502649.3887734,9.769990682601929,0.011105512427240562,1739502649.3887749,9.769990682601929,2.171758749639611 +1739502649.415644,9.789990663528442,18.185114401325777,1739502649.4156525,9.789990663528442,-0.31440098253542104,1739502649.4156632,9.789990663528442,17.41655106410047,1739502649.415674,9.789990663528442,23.75378088587902,1739502649.415679,9.789990663528442,-0.11773348873269089,1739502649.4156852,9.789990663528442,0.03530213009431217,1739502649.41569,9.789990663528442,0.13481374254005413,1739502649.4156945,9.789990663528442,0.033345231411683114,1739502649.415699,9.789990663528442,2.244403395661785,1739502649.4157045,9.789990663528442,0.0,1739502649.4157095,9.789990663528442,0.07264464602217391,1739502649.4157145,9.789990663528442,0.011105512427240562,1739502649.4157197,9.789990663528442,2.171758749639611 +1739502649.4360926,9.809990644454956,18.185114401325777,1739502649.4361057,9.809990644454956,-0.31440098253542104,1739502649.4361227,9.809990644454956,17.41655106410047,1739502649.4361424,9.809990644454956,23.75378088587902,1739502649.4361534,9.809990644454956,-0.11773348873269089,1739502649.4361675,9.809990644454956,0.03530213009431217,1739502649.43618,9.809990644454956,0.13481374254005413,1739502649.4361928,9.809990644454956,0.033345231411683114,1739502649.4362054,9.809990644454956,2.244403395661785,1739502649.4362183,9.809990644454956,0.0,1739502649.4362311,9.809990644454956,0.07264464602217391,1739502649.436244,9.809990644454956,0.011105512427240562,1739502649.436257,9.809990644454956,2.171758749639611 +1739502649.4596076,9.839990615844727,18.185114401325777,1739502649.4596143,9.839990615844727,-0.31440098253542104,1739502649.4596236,9.839990615844727,17.41655106410047,1739502649.459634,9.839990615844727,23.75378088587902,1739502649.4596398,9.839990615844727,-0.11773348873269089,1739502649.4596474,9.839990615844727,0.03530213009431217,1739502649.4596543,9.839990615844727,0.13481374254005413,1739502649.459661,9.839990615844727,0.033345231411683114,1739502649.4596677,9.839990615844727,2.244403395661785,1739502649.4596746,9.839990615844727,0.0,1739502649.4596813,9.839990615844727,0.07264464602217391,1739502649.4596882,9.839990615844727,0.011105512427240562,1739502649.4596949,9.839990615844727,2.171758749639611 +1739502649.4772632,9.85999059677124,18.424393363773532,1739502649.4772673,9.85999059677124,-0.3116521524436626,1739502649.477272,9.85999059677124,17.548861981669305,1739502649.4772775,9.85999059677124,23.902056241694744,1739502649.4772806,9.85999059677124,-0.117,1739502649.4772844,9.85999059677124,0.03552067450985021,1739502649.477288,9.85999059677124,0.12920775533143383,1739502649.4772916,9.85999059677124,0.03302885977744354,1739502649.477295,9.85999059677124,2.254491678047158,1739502649.4772987,9.85999059677124,0.0,1739502649.4773023,9.85999059677124,0.07570584323383328,1739502649.477306,9.85999059677124,0.01194525246110172,1739502649.4773097,9.85999059677124,2.1797424595691806 +1739502649.496779,9.879990577697754,18.424393363773532,1739502649.4967828,9.879990577697754,-0.3116521524436626,1739502649.4967875,9.879990577697754,17.548861981669305,1739502649.4967923,9.879990577697754,23.902056241694744,1739502649.4967952,9.879990577697754,-0.117,1739502649.4967988,9.879990577697754,0.03552067450985021,1739502649.496802,9.879990577697754,0.12920775533143383,1739502649.4968054,9.879990577697754,0.03302885977744354,1739502649.4968085,9.879990577697754,2.254491678047158,1739502649.4968119,9.879990577697754,0.0,1739502649.496815,9.879990577697754,0.07474921847797766,1739502649.496818,9.879990577697754,0.01194525246110172,1739502649.4968214,9.879990577697754,2.1797424595691806 +1739502649.5196214,9.899990558624268,18.424393363773532,1739502649.5196285,9.899990558624268,-0.3116521524436626,1739502649.519638,9.899990558624268,17.548861981669305,1739502649.5196493,9.899990558624268,23.902056241694744,1739502649.5196555,9.899990558624268,-0.117,1739502649.5196633,9.899990558624268,0.03552067450985021,1739502649.5196707,9.899990558624268,0.12920775533143383,1739502649.519678,9.899990558624268,0.03302885977744354,1739502649.5196853,9.899990558624268,2.254491678047158,1739502649.519693,9.899990558624268,0.0,1739502649.5197003,9.899990558624268,0.07474921847797766,1739502649.5197077,9.899990558624268,0.01194525246110172,1739502649.5197148,9.899990558624268,2.1797424595691806 +1739502649.5378625,9.919990539550781,18.424393363773532,1739502649.5378664,9.919990539550781,-0.3116521524436626,1739502649.5378711,9.919990539550781,17.548861981669305,1739502649.5378768,9.919990539550781,23.902056241694744,1739502649.5378797,9.919990539550781,-0.117,1739502649.537884,9.919990539550781,0.03552067450985021,1739502649.5378876,9.919990539550781,0.12920775533143383,1739502649.5378914,9.919990539550781,0.03302885977744354,1739502649.537895,9.919990539550781,2.254491678047158,1739502649.5378988,9.919990539550781,0.0,1739502649.5379024,9.919990539550781,0.07474921847797766,1739502649.5379062,9.919990539550781,0.01194525246110172,1739502649.5379097,9.919990539550781,2.1797424595691806 +1739502649.555763,9.939990520477295,18.424393363773532,1739502649.5557663,9.939990520477295,-0.3116521524436626,1739502649.5557706,9.939990520477295,17.548861981669305,1739502649.5557756,9.939990520477295,23.902056241694744,1739502649.5557783,9.939990520477295,-0.117,1739502649.5557818,9.939990520477295,0.03552067450985021,1739502649.5557852,9.939990520477295,0.12920775533143383,1739502649.5557885,9.939990520477295,0.03302885977744354,1739502649.5557916,9.939990520477295,2.254491678047158,1739502649.555795,9.939990520477295,0.0,1739502649.5557983,9.939990520477295,0.07474921847797766,1739502649.5558016,9.939990520477295,0.01194525246110172,1739502649.555805,9.939990520477295,2.1797424595691806 +1739502649.5762033,9.959990501403809,18.424393363773532,1739502649.5762064,9.959990501403809,-0.3116521524436626,1739502649.5762105,9.959990501403809,17.548861981669305,1739502649.5762153,9.959990501403809,23.902056241694744,1739502649.576218,9.959990501403809,-0.117,1739502649.5762212,9.959990501403809,0.03552067450985021,1739502649.5762243,9.959990501403809,0.12920775533143383,1739502649.5762274,9.959990501403809,0.03302885977744354,1739502649.5762303,9.959990501403809,2.254491678047158,1739502649.5762334,9.959990501403809,0.0,1739502649.5762365,9.959990501403809,0.07474921847797766,1739502649.5762398,9.959990501403809,0.01194525246110172,1739502649.576243,9.959990501403809,2.1797424595691806 +1739502649.596105,9.979990482330322,18.66455855678383,1739502649.596108,9.979990482330322,-0.3086914349488854,1739502649.5961108,9.979990482330322,17.80814317171334,1739502649.5961134,9.979990482330322,24.177743401064358,1739502649.5961149,9.979990482330322,-0.117,1739502649.5961165,9.979990482330322,0.03475563568412437,1739502649.596118,9.979990482330322,0.12119166195607603,1739502649.5961194,9.979990482330322,0.030583634503862964,1739502649.5961206,9.979990482330322,2.2689959078884865,1739502649.596122,9.979990482330322,0.0,1739502649.5961235,9.979990482330322,0.08391466874191737,1739502649.596125,9.979990482330322,0.012784992494962876,1739502649.5961277,9.979990482330322,2.1879454442319695 +1739502649.6155643,9.999990463256836,18.66455855678383,1739502649.6155665,9.999990463256836,-0.3086914349488854,1739502649.615569,9.999990463256836,17.80814317171334,1739502649.615572,9.999990463256836,24.177743401064358,1739502649.6155732,9.999990463256836,-0.117,1739502649.615575,9.999990463256836,0.03475563568412437,1739502649.6155763,9.999990463256836,0.12119166195607603,1739502649.6155777,9.999990463256836,0.030583634503862964,1739502649.615579,9.999990463256836,2.2689959078884865,1739502649.6155803,9.999990463256836,0.0,1739502649.6155818,9.999990463256836,0.08105046365651702,1739502649.6155832,9.999990463256836,0.012784992494962876,1739502649.6155846,9.999990463256836,2.1879454442319695 +1739502649.635594,10.01999044418335,18.66455855678383,1739502649.635597,10.01999044418335,-0.3086914349488854,1739502649.6356003,10.01999044418335,17.80814317171334,1739502649.635603,10.01999044418335,24.177743401064358,1739502649.6356044,10.01999044418335,-0.117,1739502649.6356065,10.01999044418335,0.03475563568412437,1739502649.635608,10.01999044418335,0.12119166195607603,1739502649.6356094,10.01999044418335,0.030583634503862964,1739502649.6356106,10.01999044418335,2.2689959078884865,1739502649.6356125,10.01999044418335,0.0,1739502649.635614,10.01999044418335,0.08105046365651702,1739502649.6356156,10.01999044418335,0.012784992494962876,1739502649.635617,10.01999044418335,2.1879454442319695 +1739502649.655471,10.039990425109863,18.66455855678383,1739502649.6554735,10.039990425109863,-0.3086914349488854,1739502649.6554763,10.039990425109863,17.80814317171334,1739502649.655479,10.039990425109863,24.177743401064358,1739502649.6554806,10.039990425109863,-0.117,1739502649.6554823,10.039990425109863,0.03475563568412437,1739502649.6554837,10.039990425109863,0.12119166195607603,1739502649.6554852,10.039990425109863,0.030583634503862964,1739502649.6554863,10.039990425109863,2.2689959078884865,1739502649.655488,10.039990425109863,0.0,1739502649.6554892,10.039990425109863,0.08105046365651702,1739502649.6554909,10.039990425109863,0.012784992494962876,1739502649.655492,10.039990425109863,2.1879454442319695 +1739502649.6752975,10.059990406036377,18.66455855678383,1739502649.6753,10.059990406036377,-0.3086914349488854,1739502649.6753027,10.059990406036377,17.80814317171334,1739502649.6753054,10.059990406036377,24.177743401064358,1739502649.6753068,10.059990406036377,-0.117,1739502649.6753085,10.059990406036377,0.03475563568412437,1739502649.67531,10.059990406036377,0.12119166195607603,1739502649.6753113,10.059990406036377,0.030583634503862964,1739502649.6753123,10.059990406036377,2.2689959078884865,1739502649.675314,10.059990406036377,0.0,1739502649.6753151,10.059990406036377,0.08105046365651702,1739502649.6753168,10.059990406036377,0.012784992494962876,1739502649.675318,10.059990406036377,2.1879454442319695 +1739502649.6957378,10.07999038696289,18.90565398542263,1739502649.6957407,10.07999038696289,-0.30551675414854795,1739502649.695744,10.07999038696289,18.131946140306823,1739502649.6957474,10.07999038696289,24.519257627701712,1739502649.6957488,10.07999038696289,-0.11452636075039259,1739502649.695751,10.07999038696289,0.034009659943140924,1739502649.6957524,10.07999038696289,0.11449118473487227,1739502649.6957543,10.07999038696289,0.027869864567734888,1739502649.6957557,10.07999038696289,2.281191248845433,1739502649.6957576,10.07999038696289,0.0,1739502649.6957593,10.07999038696289,0.08590093882792349,1739502649.695761,10.07999038696289,0.013624732528824034,1739502649.6957626,10.07999038696289,2.196806084502393 +1739502649.7167768,10.099990367889404,18.90565398542263,1739502649.7167928,10.099990367889404,-0.30551675414854795,1739502649.716799,10.099990367889404,18.131946140306823,1739502649.7168176,10.099990367889404,24.519257627701712,1739502649.716826,10.099990367889404,-0.11452636075039259,1739502649.7168312,10.099990367889404,0.034009659943140924,1739502649.7168357,10.099990367889404,0.11449118473487227,1739502649.716838,10.099990367889404,0.027869864567734888,1739502649.7168393,10.099990367889404,2.281191248845433,1739502649.7168412,10.099990367889404,0.0,1739502649.7168427,10.099990367889404,0.08438516434303978,1739502649.7168446,10.099990367889404,0.013624732528824034,1739502649.7168462,10.099990367889404,2.196806084502393 +1739502649.735878,10.119990348815918,18.90565398542263,1739502649.7358801,10.119990348815918,-0.30551675414854795,1739502649.735883,10.119990348815918,18.131946140306823,1739502649.7358856,10.119990348815918,24.519257627701712,1739502649.7358868,10.119990348815918,-0.11452636075039259,1739502649.7358885,10.119990348815918,0.034009659943140924,1739502649.73589,10.119990348815918,0.11449118473487227,1739502649.735891,10.119990348815918,0.027869864567734888,1739502649.7358923,10.119990348815918,2.281191248845433,1739502649.7358937,10.119990348815918,0.0,1739502649.7358954,10.119990348815918,0.08438516434303978,1739502649.7358966,10.119990348815918,0.013624732528824034,1739502649.7358978,10.119990348815918,2.196806084502393 +1739502649.7577293,10.139990329742432,18.90565398542263,1739502649.7577362,10.139990329742432,-0.30551675414854795,1739502649.757744,10.139990329742432,18.131946140306823,1739502649.7577515,10.139990329742432,24.519257627701712,1739502649.7577553,10.139990329742432,-0.11452636075039259,1739502649.7577603,10.139990329742432,0.034009659943140924,1739502649.757764,10.139990329742432,0.11449118473487227,1739502649.757768,10.139990329742432,0.027869864567734888,1739502649.7577715,10.139990329742432,2.281191248845433,1739502649.7577758,10.139990329742432,0.0,1739502649.7577794,10.139990329742432,0.08438516434303978,1739502649.7577834,10.139990329742432,0.013624732528824034,1739502649.7577875,10.139990329742432,2.196806084502393 +1739502649.7786663,10.159990310668945,18.90565398542263,1739502649.7786725,10.159990310668945,-0.30551675414854795,1739502649.77868,10.159990310668945,18.131946140306823,1739502649.7786875,10.159990310668945,24.519257627701712,1739502649.7786913,10.159990310668945,-0.11452636075039259,1739502649.7786956,10.159990310668945,0.034009659943140924,1739502649.7786996,10.159990310668945,0.11449118473487227,1739502649.7787032,10.159990310668945,0.027869864567734888,1739502649.7787066,10.159990310668945,2.281191248845433,1739502649.7787106,10.159990310668945,0.0,1739502649.7787144,10.159990310668945,0.08438516434303978,1739502649.7787182,10.159990310668945,0.013624732528824034,1739502649.7787218,10.159990310668945,2.196806084502393 +1739502649.8002417,10.169990301132202,18.90565398542263,1739502649.8002496,10.169990301132202,-0.30551675414854795,1739502649.8002605,10.169990301132202,18.131946140306823,1739502649.8002737,10.169990301132202,24.519257627701712,1739502649.800282,10.169990301132202,-0.11452636075039259,1739502649.800289,10.169990301132202,0.034009659943140924,1739502649.8002932,10.169990301132202,0.11449118473487227,1739502649.8002975,10.169990301132202,0.027869864567734888,1739502649.8003016,10.169990301132202,2.281191248845433,1739502649.800306,10.169990301132202,0.0,1739502649.8003104,10.169990301132202,0.08438516434303978,1739502649.8003147,10.169990301132202,0.013624732528824034,1739502649.8003192,10.169990301132202,2.196806084502393 +1739502649.8173885,10.199990272521973,19.147744578853096,1739502649.817393,10.199990272521973,-0.3021256360977782,1739502649.8173988,10.199990272521973,18.47875913777556,1739502649.817405,10.199990272521973,24.884606309131488,1739502649.8174078,10.199990272521973,-0.114,1739502649.8174112,10.199990272521973,0.03278068309649638,1739502649.8174138,10.199990272521973,0.10512817095303835,1739502649.8174164,10.199990272521973,0.02450502440160241,1739502649.817419,10.199990272521973,2.298342463560086,1739502649.8174224,10.199990272521973,0.0,1739502649.8174253,10.199990272521973,0.0958503356332191,1739502649.8174279,10.199990272521973,0.014464472562685191,1739502649.8174307,10.199990272521973,2.2060749963041597 +1739502649.8383417,10.219990253448486,19.147744578853096,1739502649.8383467,10.219990253448486,-0.3021256360977782,1739502649.8383527,10.219990253448486,18.47875913777556,1739502649.8383586,10.219990253448486,24.884606309131488,1739502649.838361,10.219990253448486,-0.114,1739502649.8383646,10.219990253448486,0.03278068309649638,1739502649.8383675,10.219990253448486,0.10512817095303835,1739502649.8383703,10.219990253448486,0.02450502440160241,1739502649.8383732,10.219990253448486,2.298342463560086,1739502649.8383763,10.219990253448486,0.0,1739502649.8383787,10.219990253448486,0.0922674672559265,1739502649.8383818,10.219990253448486,0.014464472562685191,1739502649.8383849,10.219990253448486,2.2060749963041597 +1739502649.8569722,10.239990234375,19.147744578853096,1739502649.856976,10.239990234375,-0.3021256360977782,1739502649.8569803,10.239990234375,18.47875913777556,1739502649.8569841,10.239990234375,24.884606309131488,1739502649.8569858,10.239990234375,-0.114,1739502649.8569887,10.239990234375,0.03278068309649638,1739502649.8569908,10.239990234375,0.10512817095303835,1739502649.8569927,10.239990234375,0.02450502440160241,1739502649.8569949,10.239990234375,2.298342463560086,1739502649.856997,10.239990234375,0.0,1739502649.8569992,10.239990234375,0.0922674672559265,1739502649.8570013,10.239990234375,0.014464472562685191,1739502649.8570032,10.239990234375,2.2060749963041597 +1739502649.8760037,10.259990215301514,19.147744578853096,1739502649.876006,10.259990215301514,-0.3021256360977782,1739502649.876009,10.259990215301514,18.47875913777556,1739502649.8760116,10.259990215301514,24.884606309131488,1739502649.8760128,10.259990215301514,-0.114,1739502649.8760147,10.259990215301514,0.03278068309649638,1739502649.876016,10.259990215301514,0.10512817095303835,1739502649.876017,10.259990215301514,0.02450502440160241,1739502649.8760185,10.259990215301514,2.298342463560086,1739502649.8760197,10.259990215301514,0.0,1739502649.876021,10.259990215301514,0.0922674672559265,1739502649.8760226,10.259990215301514,0.014464472562685191,1739502649.8760238,10.259990215301514,2.2060749963041597 +1739502649.8963404,10.279990196228027,19.147744578853096,1739502649.896343,10.279990196228027,-0.3021256360977782,1739502649.8963459,10.279990196228027,18.47875913777556,1739502649.8963485,10.279990196228027,24.884606309131488,1739502649.8963497,10.279990196228027,-0.114,1739502649.8963516,10.279990196228027,0.03278068309649638,1739502649.8963528,10.279990196228027,0.10512817095303835,1739502649.896354,10.279990196228027,0.02450502440160241,1739502649.8963552,10.279990196228027,2.298342463560086,1739502649.8963566,10.279990196228027,0.0,1739502649.8963578,10.279990196228027,0.0922674672559265,1739502649.8963592,10.279990196228027,0.014464472562685191,1739502649.8963604,10.279990196228027,2.2060749963041597 +1739502649.916037,10.299990177154541,19.390889414743697,1739502649.9160392,10.299990177154541,-0.2985155232670609,1739502649.916042,10.299990177154541,18.613556403817512,1739502649.9160442,10.299990177154541,25.039573002785524,1739502649.9160457,10.299990177154541,-0.113304284530199,1739502649.916047,10.299990177154541,0.03277664723553212,1739502649.9160483,10.299990177154541,0.09874426926201947,1739502649.9160497,10.299990177154541,0.023741213162283604,1739502649.916051,10.299990177154541,2.310110401998376,1739502649.9160526,10.299990177154541,0.0,1739502649.9160535,10.299990177154541,0.0947137379482898,1739502649.916055,10.299990177154541,0.015304212596546348,1739502649.9160564,10.299990177154541,2.2161611241426686 +1739502649.9376156,10.319990158081055,19.390889414743697,1739502649.937618,10.319990158081055,-0.2985155232670609,1739502649.9376204,10.319990158081055,18.613556403817512,1739502649.9376233,10.319990158081055,25.039573002785524,1739502649.937625,10.319990158081055,-0.113304284530199,1739502649.9376264,10.319990158081055,0.03277664723553212,1739502649.9376276,10.319990158081055,0.09874426926201947,1739502649.937629,10.319990158081055,0.023741213162283604,1739502649.9376302,10.319990158081055,2.310110401998376,1739502649.9376318,10.319990158081055,0.0,1739502649.937633,10.319990158081055,0.09394927785570717,1739502649.9376342,10.319990158081055,0.015304212596546348,1739502649.9376357,10.319990158081055,2.2161611241426686 +1739502649.957347,10.339990139007568,19.390889414743697,1739502649.957349,10.339990139007568,-0.2985155232670609,1739502649.9573517,10.339990139007568,18.613556403817512,1739502649.9573545,10.339990139007568,25.039573002785524,1739502649.9573555,10.339990139007568,-0.113304284530199,1739502649.9573574,10.339990139007568,0.03277664723553212,1739502649.9573586,10.339990139007568,0.09874426926201947,1739502649.9573598,10.339990139007568,0.023741213162283604,1739502649.957361,10.339990139007568,2.310110401998376,1739502649.9573624,10.339990139007568,0.0,1739502649.9573636,10.339990139007568,0.09394927785570717,1739502649.957365,10.339990139007568,0.015304212596546348,1739502649.9573665,10.339990139007568,2.2161611241426686 +1739502649.9759574,10.359990119934082,19.390889414743697,1739502649.9759598,10.359990119934082,-0.2985155232670609,1739502649.9759626,10.359990119934082,18.613556403817512,1739502649.9759655,10.359990119934082,25.039573002785524,1739502649.9759667,10.359990119934082,-0.113304284530199,1739502649.9759686,10.359990119934082,0.03277664723553212,1739502649.97597,10.359990119934082,0.09874426926201947,1739502649.9759712,10.359990119934082,0.023741213162283604,1739502649.9759727,10.359990119934082,2.310110401998376,1739502649.975974,10.359990119934082,0.0,1739502649.9759755,10.359990119934082,0.09394927785570717,1739502649.975977,10.359990119934082,0.015304212596546348,1739502649.9759781,10.359990119934082,2.2161611241426686 +1739502649.9959676,10.379990100860596,19.390889414743697,1739502649.99597,10.379990100860596,-0.2985155232670609,1739502649.9959729,10.379990100860596,18.613556403817512,1739502649.9959755,10.379990100860596,25.039573002785524,1739502649.9959767,10.379990100860596,-0.113304284530199,1739502649.9959784,10.379990100860596,0.03277664723553212,1739502649.9959798,10.379990100860596,0.09874426926201947,1739502649.995981,10.379990100860596,0.023741213162283604,1739502649.9959822,10.379990100860596,2.310110401998376,1739502649.9959836,10.379990100860596,0.0,1739502649.9959848,10.379990100860596,0.09394927785570717,1739502649.9959862,10.379990100860596,0.015304212596546348,1739502649.9959874,10.379990100860596,2.2161611241426686 +1739502650.0159106,10.39999008178711,19.390889414743697,1739502650.0159128,10.39999008178711,-0.2985155232670609,1739502650.0159156,10.39999008178711,18.613556403817512,1739502650.015918,10.39999008178711,25.039573002785524,1739502650.0159194,10.39999008178711,-0.113304284530199,1739502650.0159209,10.39999008178711,0.03277664723553212,1739502650.015922,10.39999008178711,0.09874426926201947,1739502650.0159237,10.39999008178711,0.023741213162283604,1739502650.0159247,10.39999008178711,2.310110401998376,1739502650.0159264,10.39999008178711,0.0,1739502650.0159276,10.39999008178711,0.09394927785570717,1739502650.015929,10.39999008178711,0.015304212596546348,1739502650.0159304,10.39999008178711,2.2161611241426686 +1739502650.0359356,10.419990062713623,19.63515378414241,1739502650.0359378,10.419990062713623,-0.29468362078968724,1739502650.035941,10.419990062713623,19.382224832344857,1739502650.0359435,10.419990062713623,25.82883295570972,1739502650.035945,10.419990062713623,-0.113,1739502650.0359468,10.419990062713623,0.029325305966770535,1739502650.035948,10.419990062713623,0.08167382561880875,1739502650.0359492,10.419990062713623,0.01633687098393416,1739502650.0359507,10.419990062713623,2.3418744866921877,1739502650.035952,10.419990062713623,0.0,1739502650.0359535,10.419990062713623,0.1251684091470225,1739502650.035955,10.419990062713623,0.016143952630407493,1739502650.0359561,10.419990062713623,2.2264620624702234 +1739502650.055877,10.439990043640137,19.63515378414241,1739502650.055879,10.439990043640137,-0.29468362078968724,1739502650.0558817,10.439990043640137,19.382224832344857,1739502650.0558846,10.439990043640137,25.82883295570972,1739502650.055886,10.439990043640137,-0.113,1739502650.0558877,10.439990043640137,0.029325305966770535,1739502650.055889,10.439990043640137,0.08167382561880875,1739502650.0558903,10.439990043640137,0.01633687098393416,1739502650.0558918,10.439990043640137,2.3418744866921877,1739502650.0558932,10.439990043640137,0.0,1739502650.0558946,10.439990043640137,0.1154124242219643,1739502650.0558958,10.439990043640137,0.016143952630407493,1739502650.055897,10.439990043640137,2.2264620624702234 +1739502650.078777,10.45999002456665,19.63515378414241,1739502650.0787852,10.45999002456665,-0.29468362078968724,1739502650.0787952,10.45999002456665,19.382224832344857,1739502650.0788052,10.45999002456665,25.82883295570972,1739502650.0788097,10.45999002456665,-0.113,1739502650.078816,10.45999002456665,0.029325305966770535,1739502650.078821,10.45999002456665,0.08167382561880875,1739502650.0788257,10.45999002456665,0.01633687098393416,1739502650.0788302,10.45999002456665,2.3418744866921877,1739502650.0788357,10.45999002456665,0.0,1739502650.0788403,10.45999002456665,0.1154124242219643,1739502650.0788457,10.45999002456665,0.016143952630407493,1739502650.0788512,10.45999002456665,2.2264620624702234 +1739502650.0994198,10.479990005493164,19.63515378414241,1739502650.0994287,10.479990005493164,-0.29468362078968724,1739502650.0994394,10.479990005493164,19.382224832344857,1739502650.0994496,10.479990005493164,25.82883295570972,1739502650.0994549,10.479990005493164,-0.113,1739502650.0994613,10.479990005493164,0.029325305966770535,1739502650.0994666,10.479990005493164,0.08167382561880875,1739502650.0994716,10.479990005493164,0.01633687098393416,1739502650.0994763,10.479990005493164,2.3418744866921877,1739502650.099482,10.479990005493164,0.0,1739502650.0994873,10.479990005493164,0.1154124242219643,1739502650.0994923,10.479990005493164,0.016143952630407493,1739502650.0994978,10.479990005493164,2.2264620624702234 +1739502650.1228666,10.499989986419678,19.63515378414241,1739502650.1228738,10.499989986419678,-0.29468362078968724,1739502650.1228817,10.499989986419678,19.382224832344857,1739502650.1228888,10.499989986419678,25.82883295570972,1739502650.1228921,10.499989986419678,-0.113,1739502650.1228964,10.499989986419678,0.029325305966770535,1739502650.1229,10.499989986419678,0.08167382561880875,1739502650.1229033,10.499989986419678,0.01633687098393416,1739502650.1229067,10.499989986419678,2.3418744866921877,1739502650.1229107,10.499989986419678,0.0,1739502650.122914,10.499989986419678,0.1154124242219643,1739502650.1229181,10.499989986419678,0.016143952630407493,1739502650.122922,10.499989986419678,2.2264620624702234 +1739502650.1462939,10.519989967346191,19.880658231328745,1739502650.146299,10.519989967346191,-0.29062603297262424,1739502650.1463048,10.519989967346191,19.411439861560034,1739502650.1463103,10.519989967346191,25.883261570945447,1739502650.146313,10.519989967346191,-0.113,1739502650.1463163,10.519989967346191,0.029582866577266817,1739502650.1463192,10.519989967346191,0.07565894646976323,1739502650.1463218,10.519989967346191,0.016112313974982487,1739502650.1463242,10.519989967346191,2.353170516212839,1739502650.1463275,10.519989967346191,0.0,1739502650.14633,10.519989967346191,0.11350585857794684,1739502650.146333,10.519989967346191,0.01698369266426863,1739502650.1463358,10.519989967346191,2.2390688554804985 +1739502650.1659904,10.549989938735962,19.880658231328745,1739502650.1659944,10.549989938735962,-0.29062603297262424,1739502650.1659994,10.549989938735962,19.411439861560034,1739502650.166004,10.549989938735962,25.883261570945447,1739502650.166006,10.549989938735962,-0.113,1739502650.166009,10.549989938735962,0.029582866577266817,1739502650.1660109,10.549989938735962,0.07565894646976323,1739502650.1660132,10.549989938735962,0.016112313974982487,1739502650.1660151,10.549989938735962,2.353170516212839,1739502650.1660178,10.549989938735962,0.0,1739502650.16602,10.549989938735962,0.11410166073234063,1739502650.166022,10.549989938735962,0.01698369266426863,1739502650.1660244,10.549989938735962,2.2390688554804985 +1739502650.1855135,10.569989919662476,19.880658231328745,1739502650.1855178,10.569989919662476,-0.29062603297262424,1739502650.1855235,10.569989919662476,19.411439861560034,1739502650.18553,10.569989919662476,25.883261570945447,1739502650.1855333,10.569989919662476,-0.113,1739502650.1855378,10.569989919662476,0.029582866577266817,1739502650.1855416,10.569989919662476,0.07565894646976323,1739502650.1855457,10.569989919662476,0.016112313974982487,1739502650.1855497,10.569989919662476,2.353170516212839,1739502650.185554,10.569989919662476,0.0,1739502650.1855578,10.569989919662476,0.11410166073234063,1739502650.185562,10.569989919662476,0.01698369266426863,1739502650.1855662,10.569989919662476,2.2390688554804985 +1739502650.2051442,10.58998990058899,19.880658231328745,1739502650.205147,10.58998990058899,-0.29062603297262424,1739502650.2051513,10.58998990058899,19.411439861560034,1739502650.205155,10.58998990058899,25.883261570945447,1739502650.2051566,10.58998990058899,-0.113,1739502650.2051587,10.58998990058899,0.029582866577266817,1739502650.2051601,10.58998990058899,0.07565894646976323,1739502650.205162,10.58998990058899,0.016112313974982487,1739502650.2051635,10.58998990058899,2.353170516212839,1739502650.205166,10.58998990058899,0.0,1739502650.2051675,10.58998990058899,0.11410166073234063,1739502650.2051694,10.58998990058899,0.01698369266426863,1739502650.205171,10.58998990058899,2.2390688554804985 +1739502650.224493,10.609989881515503,19.880658231328745,1739502650.2244961,10.609989881515503,-0.29062603297262424,1739502650.2244997,10.609989881515503,19.411439861560034,1739502650.2245033,10.609989881515503,25.883261570945447,1739502650.224505,10.609989881515503,-0.113,1739502650.2245069,10.609989881515503,0.029582866577266817,1739502650.2245088,10.609989881515503,0.07565894646976323,1739502650.2245104,10.609989881515503,0.016112313974982487,1739502650.2245119,10.609989881515503,2.353170516212839,1739502650.2245138,10.609989881515503,0.0,1739502650.2245154,10.609989881515503,0.11410166073234063,1739502650.2245169,10.609989881515503,0.01698369266426863,1739502650.2245185,10.609989881515503,2.2390688554804985 +1739502650.2452815,10.629989862442017,20.127542741543518,1739502650.2452846,10.629989862442017,-0.2863382601996527,1739502650.2452884,10.629989862442017,19.44081911827559,1739502650.245292,10.629989862442017,25.937589025491313,1739502650.2452936,10.629989862442017,-0.113,1739502650.2452958,10.629989862442017,0.029825383619450075,1739502650.2452974,10.629989862442017,0.06976124213181809,1739502650.245299,10.629989862442017,0.01585717469055172,1739502650.2453005,10.629989862442017,2.36429939266608,1739502650.2453024,10.629989862442017,0.0,1739502650.245304,10.629989862442017,0.11214497293187184,1739502650.2453055,10.629989862442017,0.01782343269812977,1739502650.2453074,10.629989862442017,2.2515429543956538 +1739502650.2645304,10.64998984336853,20.127542741543518,1739502650.264534,10.64998984336853,-0.2863382601996527,1739502650.2645376,10.64998984336853,19.44081911827559,1739502650.264541,10.64998984336853,25.937589025491313,1739502650.2645428,10.64998984336853,-0.113,1739502650.2645447,10.64998984336853,0.029825383619450075,1739502650.2645464,10.64998984336853,0.06976124213181809,1739502650.264548,10.64998984336853,0.01585717469055172,1739502650.2645497,10.64998984336853,2.36429939266608,1739502650.2645514,10.64998984336853,0.0,1739502650.2645533,10.64998984336853,0.11275643827042625,1739502650.264555,10.64998984336853,0.01782343269812977,1739502650.2645566,10.64998984336853,2.2515429543956538 +1739502650.284646,10.669989824295044,20.127542741543518,1739502650.2846491,10.669989824295044,-0.2863382601996527,1739502650.2846527,10.669989824295044,19.44081911827559,1739502650.284656,10.669989824295044,25.937589025491313,1739502650.2846577,10.669989824295044,-0.113,1739502650.2846596,10.669989824295044,0.029825383619450075,1739502650.2846615,10.669989824295044,0.06976124213181809,1739502650.284663,10.669989824295044,0.01585717469055172,1739502650.2846646,10.669989824295044,2.36429939266608,1739502650.2846663,10.669989824295044,0.0,1739502650.284668,10.669989824295044,0.11275643827042625,1739502650.2846696,10.669989824295044,0.01782343269812977,1739502650.284683,10.669989824295044,2.2515429543956538 +1739502650.3062046,10.689989805221558,20.127542741543518,1739502650.3062074,10.689989805221558,-0.2863382601996527,1739502650.3062108,10.689989805221558,19.44081911827559,1739502650.306214,10.689989805221558,25.937589025491313,1739502650.306216,10.689989805221558,-0.113,1739502650.3062177,10.689989805221558,0.029825383619450075,1739502650.3062196,10.689989805221558,0.06976124213181809,1739502650.306221,10.689989805221558,0.01585717469055172,1739502650.3062227,10.689989805221558,2.36429939266608,1739502650.3062243,10.689989805221558,0.0,1739502650.306226,10.689989805221558,0.11275643827042625,1739502650.3062274,10.689989805221558,0.01782343269812977,1739502650.3062294,10.689989805221558,2.2515429543956538 +1739502650.326856,10.709989786148071,20.127542741543518,1739502650.3268602,10.709989786148071,-0.2863382601996527,1739502650.3268664,10.709989786148071,19.44081911827559,1739502650.3268728,10.709989786148071,25.937589025491313,1739502650.3268766,10.709989786148071,-0.113,1739502650.3268816,10.709989786148071,0.029825383619450075,1739502650.3268857,10.709989786148071,0.06976124213181809,1739502650.3268895,10.709989786148071,0.01585717469055172,1739502650.3268936,10.709989786148071,2.36429939266608,1739502650.3268976,10.709989786148071,0.0,1739502650.3269017,10.709989786148071,0.11275643827042625,1739502650.326906,10.709989786148071,0.01782343269812977,1739502650.32691,10.709989786148071,2.2515429543956538 +1739502650.3457959,10.729989767074585,20.127542741543518,1739502650.3457994,10.729989767074585,-0.2863382601996527,1739502650.3458037,10.729989767074585,19.44081911827559,1739502650.345807,10.729989767074585,25.937589025491313,1739502650.345809,10.729989767074585,-0.113,1739502650.345811,10.729989767074585,0.029825383619450075,1739502650.3458128,10.729989767074585,0.06976124213181809,1739502650.3458145,10.729989767074585,0.01585717469055172,1739502650.3458161,10.729989767074585,2.36429939266608,1739502650.3458185,10.729989767074585,0.0,1739502650.3458207,10.729989767074585,0.11275643827042625,1739502650.3458228,10.729989767074585,0.01782343269812977,1739502650.3458247,10.729989767074585,2.2515429543956538 +1739502650.3669438,10.749989748001099,20.375788551839143,1739502650.3669462,10.749989748001099,-0.28181831870070884,1739502650.3669496,10.749989748001099,19.995454773791042,1739502650.366953,10.749989748001099,26.516877593199755,1739502650.3669546,10.749989748001099,-0.11032689960905201,1739502650.3669565,10.749989748001099,0.027917990008161316,1739502650.3669581,10.749989748001099,0.056856001375021635,1739502650.3669596,10.749989748001099,0.011569272540760008,1739502650.3669612,10.749989748001099,2.3888353138229794,1739502650.366963,10.749989748001099,0.0,1739502650.3669643,10.749989748001099,0.13050720335135102,1739502650.366966,10.749989748001099,0.018663172731990908,1739502650.3669674,10.749989748001099,2.263875228196391 +1739502650.3854697,10.769989728927612,20.375788551839143,1739502650.385474,10.769989728927612,-0.28181831870070884,1739502650.3854775,10.769989728927612,19.995454773791042,1739502650.3854809,10.769989728927612,26.516877593199755,1739502650.3854825,10.769989728927612,-0.11032689960905201,1739502650.3854845,10.769989728927612,0.027917990008161316,1739502650.3854861,10.769989728927612,0.056856001375021635,1739502650.3854878,10.769989728927612,0.011569272540760008,1739502650.3854895,10.769989728927612,2.3888353138229794,1739502650.3854914,10.769989728927612,0.0,1739502650.3854933,10.769989728927612,0.12496008562658822,1739502650.385495,10.769989728927612,0.018663172731990908,1739502650.385497,10.769989728927612,2.263875228196391 +1739502650.4054167,10.789989709854126,20.375788551839143,1739502650.405421,10.789989709854126,-0.28181831870070884,1739502650.4054263,10.789989709854126,19.995454773791042,1739502650.4054315,10.789989709854126,26.516877593199755,1739502650.4054346,10.789989709854126,-0.11032689960905201,1739502650.4054384,10.789989709854126,0.027917990008161316,1739502650.405442,10.789989709854126,0.056856001375021635,1739502650.4054456,10.789989709854126,0.011569272540760008,1739502650.4054492,10.789989709854126,2.3888353138229794,1739502650.4054527,10.789989709854126,0.0,1739502650.4054563,10.789989709854126,0.12496008562658822,1739502650.40546,10.789989709854126,0.018663172731990908,1739502650.4054637,10.789989709854126,2.263875228196391 +1739502650.4291272,10.80998969078064,20.375788551839143,1739502650.4291363,10.80998969078064,-0.28181831870070884,1739502650.4291441,10.80998969078064,19.995454773791042,1739502650.4291508,10.80998969078064,26.516877593199755,1739502650.4291546,10.80998969078064,-0.11032689960905201,1739502650.4291594,10.80998969078064,0.027917990008161316,1739502650.4291642,10.80998969078064,0.056856001375021635,1739502650.429168,10.80998969078064,0.011569272540760008,1739502650.4291735,10.80998969078064,2.3888353138229794,1739502650.4291768,10.80998969078064,0.0,1739502650.4291818,10.80998969078064,0.12496008562658822,1739502650.429185,10.80998969078064,0.018663172731990908,1739502650.4291902,10.80998969078064,2.263875228196391 +1739502650.4660597,10.829989671707153,20.375788551839143,1739502650.4660654,10.829989671707153,-0.28181831870070884,1739502650.466071,10.829989671707153,19.995454773791042,1739502650.4660769,10.829989671707153,26.516877593199755,1739502650.4660802,10.829989671707153,-0.11032689960905201,1739502650.466085,10.829989671707153,0.027917990008161316,1739502650.4660888,10.829989671707153,0.056856001375021635,1739502650.4660926,10.829989671707153,0.011569272540760008,1739502650.466096,10.829989671707153,2.3888353138229794,1739502650.4661002,10.829989671707153,0.0,1739502650.4661038,10.829989671707153,0.12496008562658822,1739502650.4661078,10.829989671707153,0.018663172731990908,1739502650.466112,10.829989671707153,2.263875228196391 +1739502650.4757292,10.859989643096924,20.625450928566682,1739502650.4757338,10.859989643096924,-0.2770628506720332,1739502650.4757395,10.859989643096924,20.02516459662162,1739502650.475745,10.859989643096924,26.573900845442335,1739502650.475748,10.859989643096924,-0.10983007442729809,1739502650.4757524,10.859989643096924,0.028106269766632663,1739502650.4757557,10.859989643096924,0.051196227124608036,1739502650.4757593,10.859989643096924,0.011103156311173224,1739502650.4757626,10.859989643096924,2.399676052634227,1739502650.4757662,10.859989643096924,0.0,1739502650.4757695,10.859989643096924,0.12086254136111625,1739502650.4757729,10.859989643096924,0.019502912765852046,1739502650.4757767,10.859989643096924,2.2775330278506005 +1739502650.5182474,10.899989604949951,20.625450928566682,1739502650.5182514,10.899989604949951,-0.2770628506720332,1739502650.518256,10.899989604949951,20.02516459662162,1739502650.5182607,10.899989604949951,26.573900845442335,1739502650.5182633,10.899989604949951,-0.10983007442729809,1739502650.5182664,10.899989604949951,0.028106269766632663,1739502650.5182686,10.899989604949951,0.051196227124608036,1739502650.5182712,10.899989604949951,0.011103156311173224,1739502650.5182736,10.899989604949951,2.399676052634227,1739502650.5182765,10.899989604949951,0.0,1739502650.5182786,10.899989604949951,0.1221430247836266,1739502650.518281,10.899989604949951,0.019502912765852046,1739502650.5182838,10.899989604949951,2.2775330278506005 +1739502650.5324616,10.909989595413208,20.625450928566682,1739502650.5324664,10.909989595413208,-0.2770628506720332,1739502650.5324717,10.909989595413208,20.02516459662162,1739502650.5324771,10.909989595413208,26.573900845442335,1739502650.5324805,10.909989595413208,-0.10983007442729809,1739502650.5324843,10.909989595413208,0.028106269766632663,1739502650.5324876,10.909989595413208,0.051196227124608036,1739502650.532491,10.909989595413208,0.011103156311173224,1739502650.5324945,10.909989595413208,2.399676052634227,1739502650.5324981,10.909989595413208,0.0,1739502650.5325015,10.909989595413208,0.1221430247836266,1739502650.5325055,10.909989595413208,0.019502912765852046,1739502650.5325093,10.909989595413208,2.2775330278506005 +1739502650.5526133,10.929989576339722,20.625450928566682,1739502650.5526178,10.929989576339722,-0.2770628506720332,1739502650.552623,10.929989576339722,20.02516459662162,1739502650.552629,10.929989576339722,26.573900845442335,1739502650.5526323,10.929989576339722,-0.10983007442729809,1739502650.5526364,10.929989576339722,0.028106269766632663,1739502650.55264,10.929989576339722,0.051196227124608036,1739502650.5526433,10.929989576339722,0.011103156311173224,1739502650.5526469,10.929989576339722,2.399676052634227,1739502650.5526505,10.929989576339722,0.0,1739502650.5526543,10.929989576339722,0.1221430247836266,1739502650.5526578,10.929989576339722,0.019502912765852046,1739502650.5526614,10.929989576339722,2.2775330278506005 +1739502650.5725684,10.949989557266235,20.625450928566682,1739502650.5725727,10.949989557266235,-0.2770628506720332,1739502650.572578,10.949989557266235,20.02516459662162,1739502650.572584,10.949989557266235,26.573900845442335,1739502650.5725873,10.949989557266235,-0.10983007442729809,1739502650.5725915,10.949989557266235,0.028106269766632663,1739502650.5725951,10.949989557266235,0.051196227124608036,1739502650.5725987,10.949989557266235,0.011103156311173224,1739502650.572602,10.949989557266235,2.399676052634227,1739502650.5726058,10.949989557266235,0.0,1739502650.5726094,10.949989557266235,0.1221430247836266,1739502650.572613,10.949989557266235,0.019502912765852046,1739502650.5726168,10.949989557266235,2.2775330278506005 +1739502650.5927565,10.969989538192749,20.87659743430749,1739502650.592763,10.969989538192749,-0.2720681396318998,1739502650.5927699,10.969989538192749,20.055051030804776,1739502650.5927763,10.969989538192749,26.630457034223646,1739502650.5927796,10.969989538192749,-0.1093702680144419,1739502650.592784,10.969989538192749,0.028268769497933225,1739502650.5927875,10.969989538192749,0.04562351333098947,1739502650.592791,10.969989538192749,0.010575052331152987,1739502650.5927944,10.969989538192749,2.4103981015104337,1739502650.5927985,10.969989538192749,0.0,1739502650.5928018,10.969989538192749,0.118341186598505,1739502650.5928056,10.969989538192749,0.020342652799713184,1739502650.5928094,10.969989538192749,2.2908688397001153 +1739502650.6122756,10.989989519119263,20.87659743430749,1739502650.6122808,10.989989519119263,-0.2720681396318998,1739502650.6122859,10.989989519119263,20.055051030804776,1739502650.6122916,10.989989519119263,26.630457034223646,1739502650.6122947,10.989989519119263,-0.1093702680144419,1739502650.6122997,10.989989519119263,0.028268769497933225,1739502650.6123033,10.989989519119263,0.04562351333098947,1739502650.6123068,10.989989519119263,0.010575052331152987,1739502650.6123102,10.989989519119263,2.4103981015104337,1739502650.6123142,10.989989519119263,0.0,1739502650.6123183,10.989989519119263,0.11952926181031831,1739502650.612322,10.989989519119263,0.020342652799713184,1739502650.6123254,10.989989519119263,2.2908688397001153 +1739502650.633454,11.009989500045776,20.87659743430749,1739502650.633459,11.009989500045776,-0.2720681396318998,1739502650.6334667,11.009989500045776,20.055051030804776,1739502650.6334722,11.009989500045776,26.630457034223646,1739502650.6334755,11.009989500045776,-0.1093702680144419,1739502650.6334798,11.009989500045776,0.028268769497933225,1739502650.633484,11.009989500045776,0.04562351333098947,1739502650.6334882,11.009989500045776,0.010575052331152987,1739502650.6334918,11.009989500045776,2.4103981015104337,1739502650.6334956,11.009989500045776,0.0,1739502650.6334991,11.009989500045776,0.11952926181031831,1739502650.6335034,11.009989500045776,0.020342652799713184,1739502650.6335082,11.009989500045776,2.2908688397001153 +1739502650.6524687,11.02998948097229,20.87659743430749,1739502650.6524727,11.02998948097229,-0.2720681396318998,1739502650.6524775,11.02998948097229,20.055051030804776,1739502650.6524832,11.02998948097229,26.630457034223646,1739502650.652486,11.02998948097229,-0.1093702680144419,1739502650.6524897,11.02998948097229,0.028268769497933225,1739502650.6524932,11.02998948097229,0.04562351333098947,1739502650.6524966,11.02998948097229,0.010575052331152987,1739502650.6524997,11.02998948097229,2.4103981015104337,1739502650.652503,11.02998948097229,0.0,1739502650.6525068,11.02998948097229,0.11952926181031831,1739502650.6525104,11.02998948097229,0.020342652799713184,1739502650.652514,11.02998948097229,2.2908688397001153 +1739502650.6735601,11.049989461898804,20.87659743430749,1739502650.6735637,11.049989461898804,-0.2720681396318998,1739502650.673568,11.049989461898804,20.055051030804776,1739502650.6735735,11.049989461898804,26.630457034223646,1739502650.673576,11.049989461898804,-0.1093702680144419,1739502650.6735797,11.049989461898804,0.028268769497933225,1739502650.6735833,11.049989461898804,0.04562351333098947,1739502650.6735864,11.049989461898804,0.010575052331152987,1739502650.6735897,11.049989461898804,2.4103981015104337,1739502650.6735933,11.049989461898804,0.0,1739502650.6735966,11.049989461898804,0.11952926181031831,1739502650.6736002,11.049989461898804,0.020342652799713184,1739502650.6736035,11.049989461898804,2.2908688397001153 +1739502650.6912222,11.069989442825317,21.1291935858373,1739502650.6912248,11.069989442825317,-0.26683239845520035,1739502650.6912277,11.069989442825317,20.20511974877661,1739502650.6912303,11.069989442825317,26.806657804513254,1739502650.6912313,11.069989442825317,-0.10693774142672151,1739502650.691233,11.069989442825317,0.028155598543519518,1739502650.6912344,11.069989442825317,0.039605502410531006,1739502650.6912355,11.069989442825317,0.009428924930683903,1739502650.6912365,11.069989442825317,2.422030722816374,1739502650.6912382,11.069989442825317,0.0,1739502650.6912394,11.069989442825317,0.11743120518288443,1739502650.6912408,11.069989442825317,0.021182392833574322,1739502650.691242,11.069989442825317,2.3039438745075436 +1739502650.7116797,11.089989423751831,21.1291935858373,1739502650.7116826,11.089989423751831,-0.26683239845520035,1739502650.711686,11.089989423751831,20.20511974877661,1739502650.7116885,11.089989423751831,26.806657804513254,1739502650.7116897,11.089989423751831,-0.10693774142672151,1739502650.7116916,11.089989423751831,0.028155598543519518,1739502650.7116928,11.089989423751831,0.039605502410531006,1739502650.711694,11.089989423751831,0.009428924930683903,1739502650.7116954,11.089989423751831,2.422030722816374,1739502650.7116969,11.089989423751831,0.0,1739502650.7116983,11.089989423751831,0.11808684830883065,1739502650.7116995,11.089989423751831,0.021182392833574322,1739502650.7117012,11.089989423751831,2.3039438745075436 +1739502650.730735,11.109989404678345,21.1291935858373,1739502650.7307374,11.109989404678345,-0.26683239845520035,1739502650.7307403,11.109989404678345,20.20511974877661,1739502650.7307427,11.109989404678345,26.806657804513254,1739502650.7307441,11.109989404678345,-0.10693774142672151,1739502650.7307458,11.109989404678345,0.028155598543519518,1739502650.7307472,11.109989404678345,0.039605502410531006,1739502650.7307484,11.109989404678345,0.009428924930683903,1739502650.7307496,11.109989404678345,2.422030722816374,1739502650.7307513,11.109989404678345,0.0,1739502650.7307525,11.109989404678345,0.11808684830883065,1739502650.7307541,11.109989404678345,0.021182392833574322,1739502650.7307553,11.109989404678345,2.3039438745075436 +1739502650.7508538,11.129989385604858,21.1291935858373,1739502650.7508562,11.129989385604858,-0.26683239845520035,1739502650.750859,11.129989385604858,20.20511974877661,1739502650.7508621,11.129989385604858,26.806657804513254,1739502650.7508633,11.129989385604858,-0.10693774142672151,1739502650.750865,11.129989385604858,0.028155598543519518,1739502650.7508664,11.129989385604858,0.039605502410531006,1739502650.7508676,11.129989385604858,0.009428924930683903,1739502650.750869,11.129989385604858,2.422030722816374,1739502650.7508705,11.129989385604858,0.0,1739502650.750872,11.129989385604858,0.11808684830883065,1739502650.7508733,11.129989385604858,0.021182392833574322,1739502650.7508745,11.129989385604858,2.3039438745075436 +1739502650.7708187,11.149989366531372,21.1291935858373,1739502650.7708216,11.149989366531372,-0.26683239845520035,1739502650.7708247,11.149989366531372,20.20511974877661,1739502650.7708275,11.149989366531372,26.806657804513254,1739502650.770829,11.149989366531372,-0.10693774142672151,1739502650.7708309,11.149989366531372,0.028155598543519518,1739502650.7708323,11.149989366531372,0.039605502410531006,1739502650.7708337,11.149989366531372,0.009428924930683903,1739502650.770835,11.149989366531372,2.422030722816374,1739502650.7708366,11.149989366531372,0.0,1739502650.7708378,11.149989366531372,0.11808684830883065,1739502650.7708392,11.149989366531372,0.021182392833574322,1739502650.770841,11.149989366531372,2.3039438745075436 +1739502650.7912114,11.169989347457886,21.1291935858373,1739502650.7912138,11.169989347457886,-0.26683239845520035,1739502650.791217,11.169989347457886,20.20511974877661,1739502650.79122,11.169989347457886,26.806657804513254,1739502650.7912219,11.169989347457886,-0.10693774142672151,1739502650.7912235,11.169989347457886,0.028155598543519518,1739502650.7912252,11.169989347457886,0.039605502410531006,1739502650.7912264,11.169989347457886,0.009428924930683903,1739502650.7912276,11.169989347457886,2.422030722816374,1739502650.7912292,11.169989347457886,0.0,1739502650.7912304,11.169989347457886,0.11808684830883065,1739502650.7912323,11.169989347457886,0.021182392833574322,1739502650.7912335,11.169989347457886,2.3039438745075436 +1739502650.810886,11.1899893283844,21.383214697320167,1739502650.8108888,11.1899893283844,-0.2613537157082444,1739502650.810892,11.1899893283844,20.539191170530167,1739502650.810895,11.1899893283844,27.166525003227324,1739502650.8108962,11.1899893283844,-0.10301334838708302,1739502650.8108978,11.1899893283844,0.027372008881869473,1739502650.8108993,11.1899893283844,0.03095143960119451,1739502650.8109007,11.1899893283844,0.0071017085684173635,1739502650.8109016,11.1899893283844,2.4388572274589406,1739502650.8109035,11.1899893283844,0.0,1739502650.8109047,11.1899893283844,0.12377735126613194,1739502650.8109062,11.1899893283844,0.02202213286743546,1739502650.8109074,11.1899893283844,2.3168581595328988 +1739502650.830833,11.209989309310913,21.383214697320167,1739502650.8308358,11.209989309310913,-0.2613537157082444,1739502650.8308387,11.209989309310913,20.539191170530167,1739502650.8308415,11.209989309310913,27.166525003227324,1739502650.830843,11.209989309310913,-0.10301334838708302,1739502650.8308444,11.209989309310913,0.027372008881869473,1739502650.8308456,11.209989309310913,0.03095143960119451,1739502650.8308473,11.209989309310913,0.0071017085684173635,1739502650.8308485,11.209989309310913,2.4388572274589406,1739502650.8308501,11.209989309310913,0.0,1739502650.8308513,11.209989309310913,0.12199906792604187,1739502650.8308525,11.209989309310913,0.02202213286743546,1739502650.8308547,11.209989309310913,2.3168581595328988 +1739502650.8522534,11.229989290237427,21.383214697320167,1739502650.852257,11.229989290237427,-0.2613537157082444,1739502650.8522618,11.229989290237427,20.539191170530167,1739502650.852267,11.229989290237427,27.166525003227324,1739502650.85227,11.229989290237427,-0.10301334838708302,1739502650.8522735,11.229989290237427,0.027372008881869473,1739502650.852277,11.229989290237427,0.03095143960119451,1739502650.8522804,11.229989290237427,0.0071017085684173635,1739502650.8522837,11.229989290237427,2.4388572274589406,1739502650.8522873,11.229989290237427,0.0,1739502650.8522906,11.229989290237427,0.12199906792604187,1739502650.852294,11.229989290237427,0.02202213286743546,1739502650.8522975,11.229989290237427,2.3168581595328988 +1739502650.8722546,11.24998927116394,21.383214697320167,1739502650.8722591,11.24998927116394,-0.2613537157082444,1739502650.872264,11.24998927116394,20.539191170530167,1739502650.8722696,11.24998927116394,27.166525003227324,1739502650.8722725,11.24998927116394,-0.10301334838708302,1739502650.8722763,11.24998927116394,0.027372008881869473,1739502650.8722801,11.24998927116394,0.03095143960119451,1739502650.8722835,11.24998927116394,0.0071017085684173635,1739502650.8722868,11.24998927116394,2.4388572274589406,1739502650.8722904,11.24998927116394,0.0,1739502650.8722937,11.24998927116394,0.12199906792604187,1739502650.8722973,11.24998927116394,0.02202213286743546,1739502650.8723009,11.24998927116394,2.3168581595328988 +1739502650.8924582,11.269989252090454,21.383214697320167,1739502650.892462,11.269989252090454,-0.2613537157082444,1739502650.8924673,11.269989252090454,20.539191170530167,1739502650.8924723,11.269989252090454,27.166525003227324,1739502650.8924751,11.269989252090454,-0.10301334838708302,1739502650.892479,11.269989252090454,0.027372008881869473,1739502650.8924823,11.269989252090454,0.03095143960119451,1739502650.8924856,11.269989252090454,0.0071017085684173635,1739502650.892489,11.269989252090454,2.4388572274589406,1739502650.8924923,11.269989252090454,0.0,1739502650.8924959,11.269989252090454,0.12199906792604187,1739502650.8924992,11.269989252090454,0.02202213286743546,1739502650.8925028,11.269989252090454,2.3168581595328988 +1739502650.9108293,11.289989233016968,21.638671898580018,1739502650.9108315,11.289989233016968,-0.25562943539525396,1739502650.910834,11.289989233016968,20.890148804871746,1739502650.910837,11.289989233016968,27.544137438443165,1739502650.9108384,11.289989233016968,-0.099,1739502650.9108398,11.289989233016968,0.026516575602032258,1739502650.9108417,11.289989233016968,0.021590262734296498,1739502650.910843,11.289989233016968,0.004751219604896879,1739502650.910844,11.289989233016968,2.457190248324032,1739502650.9108458,11.289989233016968,0.0,1739502650.9108467,11.289989233016968,0.1292622149657221,1739502650.9108481,11.289989233016968,0.022861872901296598,1739502650.9108498,11.289989233016968,2.3301977682963644 +1739502650.9308589,11.309989213943481,21.638671898580018,1739502650.9308615,11.309989213943481,-0.25562943539525396,1739502650.9308648,11.309989213943481,20.890148804871746,1739502650.9308677,11.309989213943481,27.544137438443165,1739502650.9308693,11.309989213943481,-0.099,1739502650.9308708,11.309989213943481,0.026516575602032258,1739502650.9308722,11.309989213943481,0.021590262734296498,1739502650.9308739,11.309989213943481,0.004751219604896879,1739502650.930875,11.309989213943481,2.457190248324032,1739502650.930877,11.309989213943481,0.0,1739502650.9308782,11.309989213943481,0.12699248002766783,1739502650.9308798,11.309989213943481,0.022861872901296598,1739502650.930881,11.309989213943481,2.3301977682963644 +1739502650.9516969,11.329989194869995,21.638671898580018,1739502650.9517012,11.329989194869995,-0.25562943539525396,1739502650.951706,11.329989194869995,20.890148804871746,1739502650.9517112,11.329989194869995,27.544137438443165,1739502650.951714,11.329989194869995,-0.099,1739502650.9517179,11.329989194869995,0.026516575602032258,1739502650.9517212,11.329989194869995,0.021590262734296498,1739502650.9517248,11.329989194869995,0.004751219604896879,1739502650.951728,11.329989194869995,2.457190248324032,1739502650.9517317,11.329989194869995,0.0,1739502650.951735,11.329989194869995,0.12699248002766783,1739502650.9517386,11.329989194869995,0.022861872901296598,1739502650.9517422,11.329989194869995,2.3301977682963644 +1739502650.9729111,11.349989175796509,21.638671898580018,1739502650.9729137,11.349989175796509,-0.25562943539525396,1739502650.9729168,11.349989175796509,20.890148804871746,1739502650.9729195,11.349989175796509,27.544137438443165,1739502650.972921,11.349989175796509,-0.099,1739502650.9729226,11.349989175796509,0.026516575602032258,1739502650.9729242,11.349989175796509,0.021590262734296498,1739502650.9729254,11.349989175796509,0.004751219604896879,1739502650.9729266,11.349989175796509,2.457190248324032,1739502650.9729285,11.349989175796509,0.0,1739502650.9729297,11.349989175796509,0.12699248002766783,1739502650.9729314,11.349989175796509,0.022861872901296598,1739502650.9729328,11.349989175796509,2.3301977682963644 +1739502650.9929175,11.369989156723022,21.638671898580018,1739502650.9929204,11.369989156723022,-0.25562943539525396,1739502650.9929235,11.369989156723022,20.890148804871746,1739502650.9929261,11.369989156723022,27.544137438443165,1739502650.9929278,11.369989156723022,-0.099,1739502650.9929292,11.369989156723022,0.026516575602032258,1739502650.9929307,11.369989156723022,0.021590262734296498,1739502650.992932,11.369989156723022,0.004751219604896879,1739502650.9929338,11.369989156723022,2.457190248324032,1739502650.9929354,11.369989156723022,0.0,1739502650.9929366,11.369989156723022,0.12699248002766783,1739502650.9929383,11.369989156723022,0.022861872901296598,1739502650.9929395,11.369989156723022,2.3301977682963644 +1739502651.012698,11.389989137649536,21.638671898580018,1739502651.012702,11.389989137649536,-0.25562943539525396,1739502651.0127082,11.389989137649536,20.890148804871746,1739502651.012714,11.389989137649536,27.544137438443165,1739502651.0127172,11.389989137649536,-0.099,1739502651.0127213,11.389989137649536,0.026516575602032258,1739502651.0127246,11.389989137649536,0.021590262734296498,1739502651.0127282,11.389989137649536,0.004751219604896879,1739502651.0127316,11.389989137649536,2.457190248324032,1739502651.0127351,11.389989137649536,0.0,1739502651.0127385,11.389989137649536,0.12699248002766783,1739502651.012742,11.389989137649536,0.022861872901296598,1739502651.0127454,11.389989137649536,2.3301977682963644 +1739502651.0319798,11.40998911857605,21.895624948068637,1739502651.0319834,11.40998911857605,-0.2496557461988358,1739502651.0319877,11.40998911857605,21.134841222151692,1739502651.031992,11.40998911857605,27.816710146491594,1739502651.0319943,11.40998911857605,-0.09646812769932367,1739502651.0319974,11.40998911857605,0.02586577443987509,1739502651.032,11.40998911857605,0.01281846243184968,1739502651.0320022,11.40998911857605,0.002806104342610208,1739502651.0320046,11.40998911857605,2.474494077338036,1739502651.0320072,11.40998911857605,0.0,1739502651.0320098,11.40998911857605,0.13187541570401973,1739502651.032012,11.40998911857605,0.023701612935157736,1739502651.0320146,11.40998911857605,2.3441445800333462 +1739502651.0524242,11.429989099502563,21.895624948068637,1739502651.0524275,11.429989099502563,-0.2496557461988358,1739502651.0524318,11.429989099502563,21.134841222151692,1739502651.052436,11.429989099502563,27.816710146491594,1739502651.0524385,11.429989099502563,-0.09646812769932367,1739502651.0524414,11.429989099502563,0.02586577443987509,1739502651.052444,11.429989099502563,0.01281846243184968,1739502651.0524466,11.429989099502563,0.002806104342610208,1739502651.052449,11.429989099502563,2.474494077338036,1739502651.0524516,11.429989099502563,0.0,1739502651.0524542,11.429989099502563,0.1303494973046897,1739502651.0524566,11.429989099502563,0.023701612935157736,1739502651.0524592,11.429989099502563,2.3441445800333462 +1739502651.0731058,11.449989080429077,21.895624948068637,1739502651.0731103,11.449989080429077,-0.2496557461988358,1739502651.0731163,11.449989080429077,21.134841222151692,1739502651.0731218,11.449989080429077,27.816710146491594,1739502651.0731256,11.449989080429077,-0.09646812769932367,1739502651.0731297,11.449989080429077,0.02586577443987509,1739502651.0731335,11.449989080429077,0.01281846243184968,1739502651.0731366,11.449989080429077,0.002806104342610208,1739502651.0731394,11.449989080429077,2.474494077338036,1739502651.073144,11.449989080429077,0.0,1739502651.073148,11.449989080429077,0.1303494973046897,1739502651.0731506,11.449989080429077,0.023701612935157736,1739502651.0731542,11.449989080429077,2.3441445800333462 +1739502651.0927248,11.46998906135559,21.895624948068637,1739502651.0927289,11.46998906135559,-0.2496557461988358,1739502651.0927346,11.46998906135559,21.134841222151692,1739502651.0927408,11.46998906135559,27.816710146491594,1739502651.092744,11.46998906135559,-0.09646812769932367,1739502651.092748,11.46998906135559,0.02586577443987509,1739502651.0927527,11.46998906135559,0.01281846243184968,1739502651.0927558,11.46998906135559,0.002806104342610208,1739502651.09276,11.46998906135559,2.474494077338036,1739502651.092764,11.46998906135559,0.0,1739502651.0927675,11.46998906135559,0.1303494973046897,1739502651.0927715,11.46998906135559,0.023701612935157736,1739502651.0927749,11.46998906135559,2.3441445800333462 +1739502651.1116788,11.489989042282104,21.895624948068637,1739502651.1116812,11.489989042282104,-0.2496557461988358,1739502651.111684,11.489989042282104,21.134841222151692,1739502651.1116867,11.489989042282104,27.816710146491594,1739502651.111688,11.489989042282104,-0.09646812769932367,1739502651.1116896,11.489989042282104,0.02586577443987509,1739502651.111691,11.489989042282104,0.01281846243184968,1739502651.1116922,11.489989042282104,0.002806104342610208,1739502651.1116936,11.489989042282104,2.474494077338036,1739502651.111695,11.489989042282104,0.0,1739502651.1116965,11.489989042282104,0.1303494973046897,1739502651.1116977,11.489989042282104,0.023701612935157736,1739502651.111699,11.489989042282104,2.3441445800333462 +1739502651.1310074,11.509989023208618,22.15411859962384,1739502651.13101,11.509989023208618,-0.24342904974543256,1739502651.1310132,11.509989023208618,21.411668548118183,1739502651.131016,11.509989023208618,28.12202224804098,1739502651.1310172,11.509989023208618,-0.09306099746896958,1739502651.1310186,11.509989023208618,0.025190796152971456,1739502651.1310203,11.509989023208618,0.003877044149438408,1739502651.1310215,11.509989023208618,0.0008354928305452005,1739502651.131023,11.509989023208618,2.492257924455256,1739502651.1310246,11.509989023208618,0.0,1739502651.131026,11.509989023208618,0.1354565008374714,1739502651.1310275,11.509989023208618,0.024541352969018874,1739502651.131029,11.509989023208618,2.3583973632681583 +1739502651.151003,11.529989004135132,22.15411859962384,1739502651.1510053,11.529989004135132,-0.24342904974543256,1739502651.151008,11.529989004135132,21.411668548118183,1739502651.1510108,11.529989004135132,28.12202224804098,1739502651.1510122,11.529989004135132,-0.09306099746896958,1739502651.1510136,11.529989004135132,0.025190796152971456,1739502651.1510153,11.529989004135132,0.003877044149438408,1739502651.1510165,11.529989004135132,0.0008354928305452005,1739502651.1510177,11.529989004135132,2.492257924455256,1739502651.1510193,11.529989004135132,0.0,1739502651.1510205,11.529989004135132,0.13386056118709755,1739502651.1510217,11.529989004135132,0.024541352969018874,1739502651.1510231,11.529989004135132,2.3583973632681583 +1739502651.170843,11.549988985061646,22.15411859962384,1739502651.1708455,11.549988985061646,-0.24342904974543256,1739502651.170849,11.549988985061646,21.411668548118183,1739502651.170852,11.549988985061646,28.12202224804098,1739502651.1708536,11.549988985061646,-0.09306099746896958,1739502651.1708553,11.549988985061646,0.025190796152971456,1739502651.1708567,11.549988985061646,0.003877044149438408,1739502651.170858,11.549988985061646,0.0008354928305452005,1739502651.1708596,11.549988985061646,2.492257924455256,1739502651.170861,11.549988985061646,0.0,1739502651.1708624,11.549988985061646,0.13386056118709755,1739502651.1708639,11.549988985061646,0.024541352969018874,1739502651.1708653,11.549988985061646,2.3583973632681583 +1739502651.1924162,11.56998896598816,22.15411859962384,1739502651.19242,11.56998896598816,-0.24342904974543256,1739502651.1924248,11.56998896598816,21.411668548118183,1739502651.1924298,11.56998896598816,28.12202224804098,1739502651.1924326,11.56998896598816,-0.09306099746896958,1739502651.1924365,11.56998896598816,0.025190796152971456,1739502651.1924398,11.56998896598816,0.003877044149438408,1739502651.1924431,11.56998896598816,0.0008354928305452005,1739502651.1924465,11.56998896598816,2.492257924455256,1739502651.19245,11.56998896598816,0.0,1739502651.1924531,11.56998896598816,0.13386056118709755,1739502651.1924567,11.56998896598816,0.024541352969018874,1739502651.1924603,11.56998896598816,2.3583973632681583 +1739502651.2109153,11.589988946914673,22.15411859962384,1739502651.210918,11.589988946914673,-0.24342904974543256,1739502651.2109208,11.589988946914673,21.411668548118183,1739502651.2109232,11.589988946914673,28.12202224804098,1739502651.2109246,11.589988946914673,-0.09306099746896958,1739502651.2109263,11.589988946914673,0.025190796152971456,1739502651.2109277,11.589988946914673,0.003877044149438408,1739502651.210929,11.589988946914673,0.0008354928305452005,1739502651.21093,11.589988946914673,2.492257924455256,1739502651.2109318,11.589988946914673,0.0,1739502651.210933,11.589988946914673,0.13386056118709755,1739502651.2109342,11.589988946914673,0.024541352969018874,1739502651.2109356,11.589988946914673,2.3583973632681583 +1739502651.2321844,11.609988927841187,22.15411859962384,1739502651.2321877,11.609988927841187,-0.24342904974543256,1739502651.232192,11.609988927841187,21.411668548118183,1739502651.232197,11.609988927841187,28.12202224804098,1739502651.2322,11.609988927841187,-0.09306099746896958,1739502651.2322037,11.609988927841187,0.025190796152971456,1739502651.232207,11.609988927841187,0.003877044149438408,1739502651.2322102,11.609988927841187,0.0008354928305452005,1739502651.2322135,11.609988927841187,2.492257924455256,1739502651.2322168,11.609988927841187,0.0,1739502651.2322202,11.609988927841187,0.13386056118709755,1739502651.2322237,11.609988927841187,0.024541352969018874,1739502651.232227,11.609988927841187,2.3583973632681583 +1739502651.25234,11.6299889087677,22.414198612209045,1739502651.252344,11.6299889087677,-0.23694560724358915,1739502651.252349,11.6299889087677,21.82405926401551,1739502651.252354,11.6299889087677,28.563757224174793,1739502651.2523568,11.6299889087677,-0.08864425020996103,1739502651.2523608,11.6299889087677,0.024111099216442864,1739502651.2523637,11.6299889087677,-0.007812169800446219,1739502651.252367,11.6299889087677,-0.0015855957172596523,1739502651.2523704,11.6299889087677,2.4844243828430583,1739502651.2523737,11.6299889087677,0.0,1739502651.2523773,11.6299889087677,0.10110647180466138,1739502651.2523806,11.6299889087677,0.025381093002880013,1739502651.2523842,11.6299889087677,2.373082251395364 +1739502651.2707767,11.649988889694214,22.414198612209045,1739502651.270779,11.649988889694214,-0.23694560724358915,1739502651.2707818,11.649988889694214,21.82405926401551,1739502651.2707841,11.649988889694214,28.563757224174793,1739502651.2707858,11.649988889694214,-0.08864425020996103,1739502651.2707872,11.649988889694214,0.024111099216442864,1739502651.2707887,11.649988889694214,-0.007812169800446219,1739502651.27079,11.649988889694214,-0.0015855957172596523,1739502651.2707915,11.649988889694214,2.4844243828430583,1739502651.270793,11.649988889694214,0.0,1739502651.2707942,11.649988889694214,0.11134213144769411,1739502651.2707956,11.649988889694214,0.025381093002880013,1739502651.270797,11.649988889694214,2.373082251395364 +1739502651.2919126,11.669988870620728,22.414198612209045,1739502651.291916,11.669988870620728,-0.23694560724358915,1739502651.2919204,11.669988870620728,21.82405926401551,1739502651.2919252,11.669988870620728,28.563757224174793,1739502651.291928,11.669988870620728,-0.08864425020996103,1739502651.2919316,11.669988870620728,0.024111099216442864,1739502651.291935,11.669988870620728,-0.007812169800446219,1739502651.291938,11.669988870620728,-0.0015855957172596523,1739502651.2919414,11.669988870620728,2.4844243828430583,1739502651.291945,11.669988870620728,0.0,1739502651.291948,11.669988870620728,0.11134213144769411,1739502651.2919514,11.669988870620728,0.025381093002880013,1739502651.2919548,11.669988870620728,2.373082251395364 +1739502651.3107903,11.689988851547241,22.414198612209045,1739502651.3107927,11.689988851547241,-0.23694560724358915,1739502651.3107955,11.689988851547241,21.82405926401551,1739502651.3107984,11.689988851547241,28.563757224174793,1739502651.3108,11.689988851547241,-0.08864425020996103,1739502651.3108017,11.689988851547241,0.024111099216442864,1739502651.310803,11.689988851547241,-0.007812169800446219,1739502651.3108041,11.689988851547241,-0.0015855957172596523,1739502651.3108056,11.689988851547241,2.4844243828430583,1739502651.310807,11.689988851547241,0.0,1739502651.3108084,11.689988851547241,0.11134213144769411,1739502651.3108096,11.689988851547241,0.025381093002880013,1739502651.3108108,11.689988851547241,2.373082251395364 +1739502651.3307664,11.709988832473755,22.414198612209045,1739502651.3307683,11.709988832473755,-0.23694560724358915,1739502651.3307712,11.709988832473755,21.82405926401551,1739502651.3307738,11.709988832473755,28.563757224174793,1739502651.3307753,11.709988832473755,-0.08864425020996103,1739502651.3307772,11.709988832473755,0.024111099216442864,1739502651.3307784,11.709988832473755,-0.007812169800446219,1739502651.3307796,11.709988832473755,-0.0015855957172596523,1739502651.3307807,11.709988832473755,2.4844243828430583,1739502651.3307822,11.709988832473755,0.0,1739502651.3307836,11.709988832473755,0.11134213144769411,1739502651.3307848,11.709988832473755,0.025381093002880013,1739502651.330786,11.709988832473755,2.373082251395364 +1739502651.3521314,11.729988813400269,22.675765076082964,1739502651.3521347,11.729988813400269,-0.23020534102783063,1739502651.352139,11.729988813400269,21.849692777475155,1739502651.3521442,11.729988813400269,28.613776887001112,1739502651.3521469,11.729988813400269,-0.08823758628454381,1739502651.3521507,11.729988813400269,0.023903743985297758,1739502651.352154,11.729988813400269,-0.013762821617782865,1739502651.3521574,11.729988813400269,-0.002995975570183642,1739502651.3521607,11.729988813400269,2.47262533436278,1739502651.3521643,11.729988813400269,0.0,1739502651.352168,11.729988813400269,0.0764432851158919,1739502651.3521721,11.729988813400269,0.02622083303674115,1739502651.3521762,11.729988813400269,2.385276152617737 +1739502651.3707635,11.749988794326782,22.675765076082964,1739502651.370766,11.749988794326782,-0.23020534102783063,1739502651.3707683,11.749988794326782,21.849692777475155,1739502651.3707712,11.749988794326782,28.613776887001112,1739502651.3707724,11.749988794326782,-0.08823758628454381,1739502651.370774,11.749988794326782,0.023903743985297758,1739502651.3707755,11.749988794326782,-0.013762821617782865,1739502651.370777,11.749988794326782,-0.002995975570183642,1739502651.370778,11.749988794326782,2.47262533436278,1739502651.3707798,11.749988794326782,0.0,1739502651.370781,11.749988794326782,0.08734918174504314,1739502651.3707821,11.749988794326782,0.02622083303674115,1739502651.3707838,11.749988794326782,2.385276152617737 +1739502651.3923016,11.769988775253296,22.675765076082964,1739502651.392305,11.769988775253296,-0.23020534102783063,1739502651.3923097,11.769988775253296,21.849692777475155,1739502651.392315,11.769988775253296,28.613776887001112,1739502651.3923178,11.769988775253296,-0.08823758628454381,1739502651.3923218,11.769988775253296,0.023903743985297758,1739502651.3923252,11.769988775253296,-0.013762821617782865,1739502651.3923285,11.769988775253296,-0.002995975570183642,1739502651.3923318,11.769988775253296,2.47262533436278,1739502651.3923354,11.769988775253296,0.0,1739502651.392339,11.769988775253296,0.08734918174504314,1739502651.3923423,11.769988775253296,0.02622083303674115,1739502651.3923461,11.769988775253296,2.385276152617737 +1739502651.4109635,11.78998875617981,22.675765076082964,1739502651.4109666,11.78998875617981,-0.23020534102783063,1739502651.41097,11.78998875617981,21.849692777475155,1739502651.4109726,11.78998875617981,28.613776887001112,1739502651.410974,11.78998875617981,-0.08823758628454381,1739502651.4109757,11.78998875617981,0.023903743985297758,1739502651.4109774,11.78998875617981,-0.013762821617782865,1739502651.4109788,11.78998875617981,-0.002995975570183642,1739502651.4109797,11.78998875617981,2.47262533436278,1739502651.4109814,11.78998875617981,0.0,1739502651.4109828,11.78998875617981,0.08734918174504314,1739502651.4109845,11.78998875617981,0.02622083303674115,1739502651.4109857,11.78998875617981,2.385276152617737 +1739502651.4309435,11.809988737106323,22.675765076082964,1739502651.4309468,11.809988737106323,-0.23020534102783063,1739502651.4309504,11.809988737106323,21.849692777475155,1739502651.4309533,11.809988737106323,28.613776887001112,1739502651.4309547,11.809988737106323,-0.08823758628454381,1739502651.4309566,11.809988737106323,0.023903743985297758,1739502651.430958,11.809988737106323,-0.013762821617782865,1739502651.4309595,11.809988737106323,-0.002995975570183642,1739502651.430961,11.809988737106323,2.47262533436278,1739502651.430963,11.809988737106323,0.0,1739502651.4309642,11.809988737106323,0.08734918174504314,1739502651.4309654,11.809988737106323,0.02622083303674115,1739502651.430967,11.809988737106323,2.385276152617737 +1739502651.450977,11.829988718032837,22.675765076082964,1739502651.4509802,11.829988718032837,-0.23020534102783063,1739502651.4509835,11.829988718032837,21.849692777475155,1739502651.4509861,11.829988718032837,28.613776887001112,1739502651.450988,11.829988718032837,-0.08823758628454381,1739502651.4509897,11.829988718032837,0.023903743985297758,1739502651.4509914,11.829988718032837,-0.013762821617782865,1739502651.4509928,11.829988718032837,-0.002995975570183642,1739502651.4509945,11.829988718032837,2.47262533436278,1739502651.4509964,11.829988718032837,0.0,1739502651.450998,11.829988718032837,0.08734918174504314,1739502651.4509995,11.829988718032837,0.02622083303674115,1739502651.4510014,11.829988718032837,2.385276152617737 +1739502651.470941,11.84998869895935,22.938510823365796,1739502651.470944,11.84998869895935,-0.22321391737107632,1739502651.4709473,11.84998869895935,22.11907105591039,1739502651.4709504,11.84998869895935,28.901825189049955,1739502651.4709518,11.84998869895935,-0.08497876539680405,1739502651.4709532,11.84998869895935,0.023176775700999356,1739502651.4709547,11.84998869895935,-0.023166468228535166,1739502651.4709563,11.84998869895935,-0.005000482720860932,1739502651.4709575,11.84998869895935,2.45409377159194,1739502651.4709594,11.84998869895935,0.0,1739502651.470961,11.84998869895935,0.04680074570495025,1739502651.4709628,11.84998869895935,0.02706057307060229,1739502651.4709642,11.84998869895935,2.394621631316447 +1739502651.491166,11.869988679885864,22.938510823365796,1739502651.4911685,11.869988679885864,-0.22321391737107632,1739502651.4911714,11.869988679885864,22.11907105591039,1739502651.4911742,11.869988679885864,28.901825189049955,1739502651.4911754,11.869988679885864,-0.08497876539680405,1739502651.4911773,11.869988679885864,0.023176775700999356,1739502651.4911788,11.869988679885864,-0.023166468228535166,1739502651.4911802,11.869988679885864,-0.005000482720860932,1739502651.4911816,11.869988679885864,2.45409377159194,1739502651.491183,11.869988679885864,0.0,1739502651.4911845,11.869988679885864,0.05947214027549297,1739502651.4911857,11.869988679885864,0.02706057307060229,1739502651.491187,11.869988679885864,2.394621631316447 +1739502651.5110164,11.889988660812378,22.938510823365796,1739502651.511019,11.889988660812378,-0.22321391737107632,1739502651.511022,11.889988660812378,22.11907105591039,1739502651.511025,11.889988660812378,28.901825189049955,1739502651.5110261,11.889988660812378,-0.08497876539680405,1739502651.5110278,11.889988660812378,0.023176775700999356,1739502651.5110292,11.889988660812378,-0.023166468228535166,1739502651.5110304,11.889988660812378,-0.005000482720860932,1739502651.5110319,11.889988660812378,2.45409377159194,1739502651.5110333,11.889988660812378,0.0,1739502651.5110347,11.889988660812378,0.05947214027549297,1739502651.5110364,11.889988660812378,0.02706057307060229,1739502651.5110376,11.889988660812378,2.394621631316447 +1739502651.53117,11.909988641738892,22.938510823365796,1739502651.5311728,11.909988641738892,-0.22321391737107632,1739502651.531176,11.909988641738892,22.11907105591039,1739502651.5311792,11.909988641738892,28.901825189049955,1739502651.5311809,11.909988641738892,-0.08497876539680405,1739502651.5311825,11.909988641738892,0.023176775700999356,1739502651.531184,11.909988641738892,-0.023166468228535166,1739502651.5311854,11.909988641738892,-0.005000482720860932,1739502651.5311873,11.909988641738892,2.45409377159194,1739502651.531189,11.909988641738892,0.0,1739502651.5311902,11.909988641738892,0.05947214027549297,1739502651.5311918,11.909988641738892,0.02706057307060229,1739502651.5311935,11.909988641738892,2.394621631316447 +1739502651.5514576,11.929988622665405,22.938510823365796,1739502651.55146,11.929988622665405,-0.22321391737107632,1739502651.5514631,11.929988622665405,22.11907105591039,1739502651.5514662,11.929988622665405,28.901825189049955,1739502651.5514677,11.929988622665405,-0.08497876539680405,1739502651.5514696,11.929988622665405,0.023176775700999356,1739502651.551471,11.929988622665405,-0.023166468228535166,1739502651.5514727,11.929988622665405,-0.005000482720860932,1739502651.5514739,11.929988622665405,2.45409377159194,1739502651.5514758,11.929988622665405,0.0,1739502651.551477,11.929988622665405,0.05947214027549297,1739502651.5514786,11.929988622665405,0.02706057307060229,1739502651.55148,11.929988622665405,2.394621631316447 +1739502651.571066,11.949988603591919,23.20215141180437,1739502651.5710688,11.949988603591919,-0.21597715491761527,1739502651.571072,11.949988603591919,22.36636384828833,1739502651.571075,11.949988603591919,29.16216345747928,1739502651.5710766,11.949988603591919,-0.08345792032227176,1739502651.5710783,11.949988603591919,0.02223106289634112,1739502651.5710802,11.949988603591919,-0.03379696976097072,1739502651.5710816,11.949988603591919,-0.007303469088007369,1739502651.5710833,11.949988603591919,2.4333116684390266,1739502651.5710852,11.949988603591919,0.0,1739502651.571087,11.949988603591919,0.01975172944463971,1739502651.5710883,11.949988603591919,0.027900313104463427,1739502651.5710902,11.949988603591919,2.4011473024713865 +1739502651.5915797,11.969988584518433,23.20215141180437,1739502651.591583,11.969988584518433,-0.21597715491761527,1739502651.591587,11.969988584518433,22.36636384828833,1739502651.5915904,11.969988584518433,29.16216345747928,1739502651.5915916,11.969988584518433,-0.08345792032227176,1739502651.5915937,11.969988584518433,0.02223106289634112,1739502651.5915952,11.969988584518433,-0.03379696976097072,1739502651.5915968,11.969988584518433,-0.007303469088007369,1739502651.5915983,11.969988584518433,2.4333116684390266,1739502651.5916004,11.969988584518433,0.0,1739502651.5916018,11.969988584518433,0.03216436596764005,1739502651.5916035,11.969988584518433,0.027900313104463427,1739502651.591605,11.969988584518433,2.4011473024713865 +1739502651.610995,11.989988565444946,23.20215141180437,1739502651.6109986,11.989988565444946,-0.21597715491761527,1739502651.611002,11.989988565444946,22.36636384828833,1739502651.6110048,11.989988565444946,29.16216345747928,1739502651.6110065,11.989988565444946,-0.08345792032227176,1739502651.6110084,11.989988565444946,0.02223106289634112,1739502651.6110098,11.989988565444946,-0.03379696976097072,1739502651.6110113,11.989988565444946,-0.007303469088007369,1739502651.6110127,11.989988565444946,2.4333116684390266,1739502651.6110148,11.989988565444946,0.0,1739502651.6110165,11.989988565444946,0.03216436596764005,1739502651.611018,11.989988565444946,0.027900313104463427,1739502651.6110196,11.989988565444946,2.4011473024713865 +1739502651.6318567,12.00998854637146,23.20215141180437,1739502651.63186,12.00998854637146,-0.21597715491761527,1739502651.631864,12.00998854637146,22.36636384828833,1739502651.631868,12.00998854637146,29.16216345747928,1739502651.6318698,12.00998854637146,-0.08345792032227176,1739502651.631872,12.00998854637146,0.02223106289634112,1739502651.6318738,12.00998854637146,-0.03379696976097072,1739502651.6318755,12.00998854637146,-0.007303469088007369,1739502651.6318774,12.00998854637146,2.4333116684390266,1739502651.6318793,12.00998854637146,0.0,1739502651.631881,12.00998854637146,0.03216436596764005,1739502651.631883,12.00998854637146,0.027900313104463427,1739502651.6318848,12.00998854637146,2.4011473024713865 +1739502651.650931,12.029988527297974,23.20215141180437,1739502651.650933,12.029988527297974,-0.21597715491761527,1739502651.650936,12.029988527297974,22.36636384828833,1739502651.6509385,12.029988527297974,29.16216345747928,1739502651.65094,12.029988527297974,-0.08345792032227176,1739502651.6509416,12.029988527297974,0.02223106289634112,1739502651.650943,12.029988527297974,-0.03379696976097072,1739502651.6509445,12.029988527297974,-0.007303469088007369,1739502651.6509454,12.029988527297974,2.4333116684390266,1739502651.6509473,12.029988527297974,0.0,1739502651.6509485,12.029988527297974,0.03216436596764005,1739502651.6509502,12.029988527297974,0.027900313104463427,1739502651.6509514,12.029988527297974,2.4011473024713865 +1739502651.6708374,12.049988508224487,23.20215141180437,1739502651.6708405,12.049988508224487,-0.21597715491761527,1739502651.6708434,12.049988508224487,22.36636384828833,1739502651.6708462,12.049988508224487,29.16216345747928,1739502651.6708474,12.049988508224487,-0.08345792032227176,1739502651.6708493,12.049988508224487,0.02223106289634112,1739502651.6708508,12.049988508224487,-0.03379696976097072,1739502651.6708524,12.049988508224487,-0.007303469088007369,1739502651.6708536,12.049988508224487,2.4333116684390266,1739502651.6708555,12.049988508224487,0.0,1739502651.6708567,12.049988508224487,0.03216436596764005,1739502651.6708581,12.049988508224487,0.027900313104463427,1739502651.6708598,12.049988508224487,2.4011473024713865 +1739502651.691167,12.069988489151001,23.466324817989975,1739502651.6911695,12.069988489151001,-0.20850378090392585,1739502651.6911724,12.069988489151001,22.637801150215118,1739502651.6911752,12.069988489151001,29.440142754540528,1739502651.6911767,12.069988489151001,-0.08143214371216229,1739502651.6911783,12.069988489151001,0.021268220461435998,1739502651.6911795,12.069988489151001,-0.04464504967373992,1739502651.6911807,12.069988489151001,-0.009603568084252587,1739502651.6911821,12.069988489151001,2.412285629718621,1739502651.6911836,12.069988489151001,0.0,1739502651.691185,12.069988489151001,-0.0031823725389381,1739502651.6911864,12.069988489151001,0.028740053138324565,1739502651.6911876,12.069988489151001,2.4044221392320213 +1739502651.7111645,12.089988470077515,23.466324817989975,1739502651.7111676,12.089988470077515,-0.20850378090392585,1739502651.711171,12.089988470077515,22.637801150215118,1739502651.7111738,12.089988470077515,29.440142754540528,1739502651.7111752,12.089988470077515,-0.08143214371216229,1739502651.711177,12.089988470077515,0.021268220461435998,1739502651.7111793,12.089988470077515,-0.04464504967373992,1739502651.7111804,12.089988470077515,-0.009603568084252587,1739502651.711182,12.089988470077515,2.412285629718621,1739502651.7111838,12.089988470077515,0.0,1739502651.7111852,12.089988470077515,0.007863490486599733,1739502651.7111871,12.089988470077515,0.028740053138324565,1739502651.7111888,12.089988470077515,2.4044221392320213 +1739502651.7309096,12.109988451004028,23.466324817989975,1739502651.7309124,12.109988451004028,-0.20850378090392585,1739502651.7309158,12.109988451004028,22.637801150215118,1739502651.7309186,12.109988451004028,29.440142754540528,1739502651.7309198,12.109988451004028,-0.08143214371216229,1739502651.730922,12.109988451004028,0.021268220461435998,1739502651.7309232,12.109988451004028,-0.04464504967373992,1739502651.7309248,12.109988451004028,-0.009603568084252587,1739502651.730926,12.109988451004028,2.412285629718621,1739502651.7309277,12.109988451004028,0.0,1739502651.730929,12.109988451004028,0.007863490486599733,1739502651.7309303,12.109988451004028,0.028740053138324565,1739502651.730932,12.109988451004028,2.4044221392320213 +1739502651.7511704,12.129988431930542,23.466324817989975,1739502651.7511723,12.129988431930542,-0.20850378090392585,1739502651.7511752,12.129988431930542,22.637801150215118,1739502651.751178,12.129988431930542,29.440142754540528,1739502651.7511795,12.129988431930542,-0.08143214371216229,1739502651.7511811,12.129988431930542,0.021268220461435998,1739502651.7511826,12.129988431930542,-0.04464504967373992,1739502651.7511842,12.129988431930542,-0.009603568084252587,1739502651.7511854,12.129988431930542,2.412285629718621,1739502651.7511868,12.129988431930542,0.0,1739502651.7511883,12.129988431930542,0.007863490486599733,1739502651.7511897,12.129988431930542,0.028740053138324565,1739502651.7511911,12.129988431930542,2.4044221392320213 +1739502651.7708952,12.149988412857056,23.466324817989975,1739502651.7708976,12.149988412857056,-0.20850378090392585,1739502651.7709005,12.149988412857056,22.637801150215118,1739502651.7709033,12.149988412857056,29.440142754540528,1739502651.7709045,12.149988412857056,-0.08143214371216229,1739502651.7709064,12.149988412857056,0.021268220461435998,1739502651.7709076,12.149988412857056,-0.04464504967373992,1739502651.770909,12.149988412857056,-0.009603568084252587,1739502651.7709105,12.149988412857056,2.412285629718621,1739502651.7709122,12.149988412857056,0.0,1739502651.7709136,12.149988412857056,0.007863490486599733,1739502651.770915,12.149988412857056,0.028740053138324565,1739502651.7709165,12.149988412857056,2.4044221392320213 +1739502651.7922258,12.16998839378357,23.73074736810815,1739502651.7922294,12.16998839378357,-0.20080114935879134,1739502651.7922342,12.16998839378357,22.927932912064186,1739502651.7922397,12.16998839378357,29.732022567241053,1739502651.7922425,12.16998839378357,-0.07899147860632456,1739502651.7922463,12.16998839378357,0.02029451126909797,1739502651.79225,12.16998839378357,-0.05573420844304537,1739502651.7922535,12.16998839378357,-0.011879955622349277,1739502651.7922568,12.16998839378357,2.3909800989375047,1739502651.7922604,12.16998839378357,0.0,1739502651.792264,12.16998839378357,-0.024405113084563695,1739502651.7922673,12.16998839378357,0.029579793172185703,1739502651.792271,12.16998839378357,2.40530126679453 +1739502651.8108995,12.189988374710083,23.73074736810815,1739502651.8109024,12.189988374710083,-0.20080114935879134,1739502651.810905,12.189988374710083,22.927932912064186,1739502651.8109078,12.189988374710083,29.732022567241053,1739502651.8109093,12.189988374710083,-0.07899147860632456,1739502651.810911,12.189988374710083,0.02029451126909797,1739502651.8109124,12.189988374710083,-0.05573420844304537,1739502651.8109138,12.189988374710083,-0.011879955622349277,1739502651.810915,12.189988374710083,2.3909800989375047,1739502651.8109167,12.189988374710083,0.0,1739502651.8109179,12.189988374710083,-0.014321167857025419,1739502651.8109198,12.189988374710083,0.029579793172185703,1739502651.8109212,12.189988374710083,2.40530126679453 +1739502651.830837,12.209988355636597,23.73074736810815,1739502651.8308394,12.209988355636597,-0.20080114935879134,1739502651.830842,12.209988355636597,22.927932912064186,1739502651.8308449,12.209988355636597,29.732022567241053,1739502651.8308463,12.209988355636597,-0.07899147860632456,1739502651.8308477,12.209988355636597,0.02029451126909797,1739502651.830849,12.209988355636597,-0.05573420844304537,1739502651.8308506,12.209988355636597,-0.011879955622349277,1739502651.8308516,12.209988355636597,2.3909800989375047,1739502651.8308532,12.209988355636597,0.0,1739502651.8308547,12.209988355636597,-0.014321167857025419,1739502651.830856,12.209988355636597,0.029579793172185703,1739502651.8308575,12.209988355636597,2.40530126679453 +1739502651.8509202,12.22998833656311,23.73074736810815,1739502651.8509226,12.22998833656311,-0.20080114935879134,1739502651.8509257,12.22998833656311,22.927932912064186,1739502651.850928,12.22998833656311,29.732022567241053,1739502651.8509297,12.22998833656311,-0.07899147860632456,1739502651.8509316,12.22998833656311,0.02029451126909797,1739502651.850933,12.22998833656311,-0.05573420844304537,1739502651.8509345,12.22998833656311,-0.011879955622349277,1739502651.8509357,12.22998833656311,2.3909800989375047,1739502651.8509376,12.22998833656311,0.0,1739502651.850939,12.22998833656311,-0.014321167857025419,1739502651.850941,12.22998833656311,0.029579793172185703,1739502651.8509424,12.22998833656311,2.40530126679453 +1739502651.8708146,12.249988317489624,23.73074736810815,1739502651.8708165,12.249988317489624,-0.20080114935879134,1739502651.8708196,12.249988317489624,22.927932912064186,1739502651.8708224,12.249988317489624,29.732022567241053,1739502651.8708236,12.249988317489624,-0.07899147860632456,1739502651.8708253,12.249988317489624,0.02029451126909797,1739502651.8708267,12.249988317489624,-0.05573420844304537,1739502651.870828,12.249988317489624,-0.011879955622349277,1739502651.8708293,12.249988317489624,2.3909800989375047,1739502651.8708313,12.249988317489624,0.0,1739502651.8708327,12.249988317489624,-0.014321167857025419,1739502651.870834,12.249988317489624,0.029579793172185703,1739502651.8708355,12.249988317489624,2.40530126679453 +1739502651.8910573,12.269988298416138,23.73074736810815,1739502651.8910623,12.269988298416138,-0.20080114935879134,1739502651.8910663,12.269988298416138,22.927932912064186,1739502651.8910694,12.269988298416138,29.732022567241053,1739502651.8910718,12.269988298416138,-0.07899147860632456,1739502651.8910744,12.269988298416138,0.02029451126909797,1739502651.8910763,12.269988298416138,-0.05573420844304537,1739502651.8910787,12.269988298416138,-0.011879955622349277,1739502651.8910806,12.269988298416138,2.3909800989375047,1739502651.8910828,12.269988298416138,0.0,1739502651.8910842,12.269988298416138,-0.014321167857025419,1739502651.891087,12.269988298416138,0.029579793172185703,1739502651.8910887,12.269988298416138,2.40530126679453 +1739502651.9109921,12.289988279342651,23.995114181233742,1739502651.9109948,12.289988279342651,-0.1928779669273437,1739502651.910998,12.289988279342651,23.219885541265203,1739502651.9110012,12.289988279342651,30.020431700412974,1739502651.9110024,12.289988279342651,-0.07687181448405152,1739502651.9110043,12.289988279342651,0.019250740138009405,1739502651.9110057,12.289988279342651,-0.06730659667815676,1739502651.9110072,12.289988279342651,-0.014232944670858852,1739502651.9110086,12.289988279342651,2.3689467676400353,1739502651.9110103,12.289988279342651,0.0,1739502651.9110117,12.289988279342651,-0.043798848466585105,1739502651.9110131,12.289988279342651,0.03041953320604684,1739502651.9110148,12.289988279342651,2.4035338348764186 +1739502651.93145,12.309988260269165,23.995114181233742,1739502651.9314535,12.309988260269165,-0.1928779669273437,1739502651.931458,12.309988260269165,23.219885541265203,1739502651.9314618,12.309988260269165,30.020431700412974,1739502651.9314637,12.309988260269165,-0.07687181448405152,1739502651.931466,12.309988260269165,0.019250740138009405,1739502651.9314678,12.309988260269165,-0.06730659667815676,1739502651.9314702,12.309988260269165,-0.014232944670858852,1739502651.9314718,12.309988260269165,2.3689467676400353,1739502651.931474,12.309988260269165,0.0,1739502651.9314756,12.309988260269165,-0.03458706723638327,1739502651.9314778,12.309988260269165,0.03041953320604684,1739502651.9314797,12.309988260269165,2.4035338348764186 +1739502651.9517484,12.329988241195679,23.995114181233742,1739502651.9517512,12.329988241195679,-0.1928779669273437,1739502651.951755,12.329988241195679,23.219885541265203,1739502651.9517586,12.329988241195679,30.020431700412974,1739502651.9517603,12.329988241195679,-0.07687181448405152,1739502651.9517624,12.329988241195679,0.019250740138009405,1739502651.951764,12.329988241195679,-0.06730659667815676,1739502651.9517663,12.329988241195679,-0.014232944670858852,1739502651.951768,12.329988241195679,2.3689467676400353,1739502651.95177,12.329988241195679,0.0,1739502651.9517717,12.329988241195679,-0.03458706723638327,1739502651.951774,12.329988241195679,0.03041953320604684,1739502651.9517758,12.329988241195679,2.4035338348764186 +1739502651.971372,12.349988222122192,23.995114181233742,1739502651.9713755,12.349988222122192,-0.1928779669273437,1739502651.97138,12.349988222122192,23.219885541265203,1739502651.971384,12.349988222122192,30.020431700412974,1739502651.9713862,12.349988222122192,-0.07687181448405152,1739502651.9713886,12.349988222122192,0.019250740138009405,1739502651.971391,12.349988222122192,-0.06730659667815676,1739502651.9713933,12.349988222122192,-0.014232944670858852,1739502651.971395,12.349988222122192,2.3689467676400353,1739502651.9713974,12.349988222122192,0.0,1739502651.9713993,12.349988222122192,-0.03458706723638327,1739502651.9714015,12.349988222122192,0.03041953320604684,1739502651.9714034,12.349988222122192,2.4035338348764186 +1739502651.991733,12.369988203048706,23.995114181233742,1739502651.9917357,12.369988203048706,-0.1928779669273437,1739502651.9917397,12.369988203048706,23.219885541265203,1739502651.9917436,12.369988203048706,30.020431700412974,1739502651.991745,12.369988203048706,-0.07687181448405152,1739502651.9917474,12.369988203048706,0.019250740138009405,1739502651.991749,12.369988203048706,-0.06730659667815676,1739502651.991751,12.369988203048706,-0.014232944670858852,1739502651.9917526,12.369988203048706,2.3689467676400353,1739502651.9917548,12.369988203048706,0.0,1739502651.9917564,12.369988203048706,-0.03458706723638327,1739502651.9917583,12.369988203048706,0.03041953320604684,1739502651.9917605,12.369988203048706,2.4035338348764186 +1739502652.011367,12.38998818397522,24.259192655593292,1739502652.011371,12.38998818397522,-0.18474148063680662,1739502652.0113752,12.38998818397522,23.4690224512405,1739502652.011379,12.38998818397522,30.262032051805036,1739502652.0113807,12.38998818397522,-0.07553754578315097,1739502652.0113833,12.38998818397522,0.018190040246546343,1739502652.0113857,12.38998818397522,-0.07846325387234612,1739502652.0113873,12.38998818397522,-0.016717290319434783,1739502652.0113893,12.38998818397522,2.347897222800345,1739502652.0113914,12.38998818397522,0.0,1739502652.0113935,12.38998818397522,-0.05972635551785761,1739502652.011397,12.38998818397522,0.03125927323990798,1739502652.0113986,12.38998818397522,2.3997675455794254 +1739502652.0313206,12.409988164901733,24.259192655593292,1739502652.0313241,12.409988164901733,-0.18474148063680662,1739502652.0313294,12.409988164901733,23.4690224512405,1739502652.031333,12.409988164901733,30.262032051805036,1739502652.0313349,12.409988164901733,-0.07553754578315097,1739502652.0313373,12.409988164901733,0.018190040246546343,1739502652.031339,12.409988164901733,-0.07846325387234612,1739502652.0313408,12.409988164901733,-0.016717290319434783,1739502652.0313427,12.409988164901733,2.347897222800345,1739502652.0313454,12.409988164901733,0.0,1739502652.0313473,12.409988164901733,-0.051870322779080436,1739502652.0313497,12.409988164901733,0.03125927323990798,1739502652.0313518,12.409988164901733,2.3997675455794254 +1739502652.0517817,12.429988145828247,24.259192655593292,1739502652.0517848,12.429988145828247,-0.18474148063680662,1739502652.0517888,12.429988145828247,23.4690224512405,1739502652.0517926,12.429988145828247,30.262032051805036,1739502652.0517945,12.429988145828247,-0.07553754578315097,1739502652.0517964,12.429988145828247,0.018190040246546343,1739502652.0517983,12.429988145828247,-0.07846325387234612,1739502652.0518,12.429988145828247,-0.016717290319434783,1739502652.051802,12.429988145828247,2.347897222800345,1739502652.0518038,12.429988145828247,0.0,1739502652.0518057,12.429988145828247,-0.051870322779080436,1739502652.0518074,12.429988145828247,0.03125927323990798,1739502652.0518093,12.429988145828247,2.3997675455794254 +1739502652.071322,12.44998812675476,24.259192655593292,1739502652.071327,12.44998812675476,-0.18474148063680662,1739502652.0713315,12.44998812675476,23.4690224512405,1739502652.0713353,12.44998812675476,30.262032051805036,1739502652.0713375,12.44998812675476,-0.07553754578315097,1739502652.0713398,12.44998812675476,0.018190040246546343,1739502652.0713415,12.44998812675476,-0.07846325387234612,1739502652.0713437,12.44998812675476,-0.016717290319434783,1739502652.0713453,12.44998812675476,2.347897222800345,1739502652.0713477,12.44998812675476,0.0,1739502652.0713496,12.44998812675476,-0.051870322779080436,1739502652.0713518,12.44998812675476,0.03125927323990798,1739502652.071354,12.44998812675476,2.3997675455794254 +1739502652.091394,12.469988107681274,24.259192655593292,1739502652.0913973,12.469988107681274,-0.18474148063680662,1739502652.091401,12.469988107681274,23.4690224512405,1739502652.0914052,12.469988107681274,30.262032051805036,1739502652.0914068,12.469988107681274,-0.07553754578315097,1739502652.091409,12.469988107681274,0.018190040246546343,1739502652.0914106,12.469988107681274,-0.07846325387234612,1739502652.0914125,12.469988107681274,-0.016717290319434783,1739502652.0914142,12.469988107681274,2.347897222800345,1739502652.0914164,12.469988107681274,0.0,1739502652.0914178,12.469988107681274,-0.051870322779080436,1739502652.09142,12.469988107681274,0.03125927323990798,1739502652.0914218,12.469988107681274,2.3997675455794254 +1739502652.1186428,12.489988088607788,24.259192655593292,1739502652.1186507,12.489988088607788,-0.18474148063680662,1739502652.1186612,12.489988088607788,23.4690224512405,1739502652.1186714,12.489988088607788,30.262032051805036,1739502652.118676,12.489988088607788,-0.07553754578315097,1739502652.1186821,12.489988088607788,0.018190040246546343,1739502652.1186872,12.489988088607788,-0.07846325387234612,1739502652.1186922,12.489988088607788,-0.016717290319434783,1739502652.1186967,12.489988088607788,2.347897222800345,1739502652.1187027,12.489988088607788,0.0,1739502652.1187074,12.489988088607788,-0.051870322779080436,1739502652.118713,12.489988088607788,0.03125927323990798,1739502652.1187181,12.489988088607788,2.3997675455794254 +1739502652.1374974,12.509988069534302,24.522735786790708,1739502652.137506,12.509988069534302,-0.17639997978524047,1739502652.1375167,12.509988069534302,23.86725905378269,1739502652.1375275,12.509988069534302,30.648597108576272,1739502652.1375327,12.509988069534302,-0.07416703665650919,1739502652.1375391,12.509988069534302,0.016687196825817416,1739502652.1375444,12.509988069534302,-0.09442005877365015,1739502652.1375494,12.509988069534302,-0.019318091617260544,1739502652.137554,12.509988069534302,2.3181157636661216,1739502652.1375594,12.509988069534302,0.0,1739502652.1375642,12.509988069534302,-0.08670367597166961,1739502652.137569,12.509988069534302,0.032099013273769156,1739502652.1375742,12.509988069534302,2.393934009628063 +1739502652.1591818,12.519988059997559,24.522735786790708,1739502652.1591878,12.519988059997559,-0.17639997978524047,1739502652.1591954,12.519988059997559,23.86725905378269,1739502652.1592026,12.519988059997559,30.648597108576272,1739502652.1592062,12.519988059997559,-0.07416703665650919,1739502652.1592104,12.519988059997559,0.016687196825817416,1739502652.159214,12.519988059997559,-0.09442005877365015,1739502652.1592171,12.519988059997559,-0.019318091617260544,1739502652.1592205,12.519988059997559,2.3181157636661216,1739502652.1592247,12.519988059997559,0.0,1739502652.159228,12.519988059997559,-0.07581824596194142,1739502652.159232,12.519988059997559,0.032099013273769156,1739502652.1592355,12.519988059997559,2.393934009628063 +1739502652.1789067,12.549988031387329,24.522735786790708,1739502652.178914,12.549988031387329,-0.17639997978524047,1739502652.1789238,12.549988031387329,23.86725905378269,1739502652.1789343,12.549988031387329,30.648597108576272,1739502652.1789398,12.549988031387329,-0.07416703665650919,1739502652.1789477,12.549988031387329,0.016687196825817416,1739502652.1789541,12.549988031387329,-0.09442005877365015,1739502652.1789608,12.549988031387329,-0.019318091617260544,1739502652.1789675,12.549988031387329,2.3181157636661216,1739502652.1789744,12.549988031387329,0.0,1739502652.1789813,12.549988031387329,-0.07581824596194142,1739502652.178988,12.549988031387329,0.032099013273769156,1739502652.178995,12.549988031387329,2.393934009628063 +1739502652.1977797,12.569988012313843,24.522735786790708,1739502652.1977844,12.569988012313843,-0.17639997978524047,1739502652.1977906,12.569988012313843,23.86725905378269,1739502652.1977975,12.569988012313843,30.648597108576272,1739502652.1978018,12.569988012313843,-0.07416703665650919,1739502652.1978068,12.569988012313843,0.016687196825817416,1739502652.1978114,12.569988012313843,-0.09442005877365015,1739502652.1978161,12.569988012313843,-0.019318091617260544,1739502652.1978204,12.569988012313843,2.3181157636661216,1739502652.1978252,12.569988012313843,0.0,1739502652.19783,12.569988012313843,-0.07581824596194142,1739502652.1978345,12.569988012313843,0.032099013273769156,1739502652.1978393,12.569988012313843,2.393934009628063 +1739502652.2158928,12.589987993240356,24.522735786790708,1739502652.2158961,12.589987993240356,-0.17639997978524047,1739502652.2159004,12.589987993240356,23.86725905378269,1739502652.2159054,12.589987993240356,30.648597108576272,1739502652.215908,12.589987993240356,-0.07416703665650919,1739502652.2159116,12.589987993240356,0.016687196825817416,1739502652.215915,12.589987993240356,-0.09442005877365015,1739502652.2159183,12.589987993240356,-0.019318091617260544,1739502652.2159214,12.589987993240356,2.3181157636661216,1739502652.2159247,12.589987993240356,0.0,1739502652.215928,12.589987993240356,-0.07581824596194142,1739502652.2159314,12.589987993240356,0.032099013273769156,1739502652.215935,12.589987993240356,2.393934009628063 +1739502652.2358372,12.60998797416687,24.78551244520974,1739502652.2358391,12.60998797416687,-0.16786186908413914,1739502652.2358418,12.60998797416687,23.873828470243165,1739502652.2358441,12.60998797416687,30.638405578619167,1739502652.235845,12.60998797416687,-0.07422124692223846,1739502652.2358468,12.60998797416687,0.0159976667188906,1739502652.235848,12.60998797416687,-0.09916231534897227,1739502652.235849,12.60998797416687,-0.02222529798159087,1739502652.2358503,12.60998797416687,2.309337945083424,1739502652.2358515,12.60998797416687,0.0,1739502652.2358527,12.60998797416687,-0.07639609818695269,1739502652.2358541,12.60998797416687,0.03293875330763033,1739502652.2358553,12.60998797416687,2.385553464331664 +1739502652.255528,12.629987955093384,24.78551244520974,1739502652.255531,12.629987955093384,-0.16786186908413914,1739502652.2555351,12.629987955093384,23.873828470243165,1739502652.2555397,12.629987955093384,30.638405578619167,1739502652.2555423,12.629987955093384,-0.07422124692223846,1739502652.2555456,12.629987955093384,0.0159976667188906,1739502652.2555487,12.629987955093384,-0.09916231534897227,1739502652.2555518,12.629987955093384,-0.02222529798159087,1739502652.255555,12.629987955093384,2.309337945083424,1739502652.2555578,12.629987955093384,0.0,1739502652.2555609,12.629987955093384,-0.07621551924823988,1739502652.2555642,12.629987955093384,0.03293875330763033,1739502652.2555676,12.629987955093384,2.385553464331664 +1739502652.2752795,12.649987936019897,24.78551244520974,1739502652.2752826,12.649987936019897,-0.16786186908413914,1739502652.2752867,12.649987936019897,23.873828470243165,1739502652.2752917,12.649987936019897,30.638405578619167,1739502652.2752943,12.649987936019897,-0.07422124692223846,1739502652.2752979,12.649987936019897,0.0159976667188906,1739502652.275301,12.649987936019897,-0.09916231534897227,1739502652.2753038,12.649987936019897,-0.02222529798159087,1739502652.275307,12.649987936019897,2.309337945083424,1739502652.27531,12.649987936019897,0.0,1739502652.2753131,12.649987936019897,-0.07621551924823988,1739502652.2753162,12.649987936019897,0.03293875330763033,1739502652.2753193,12.649987936019897,2.385553464331664 +1739502652.2961743,12.669987916946411,24.78551244520974,1739502652.2961779,12.669987916946411,-0.16786186908413914,1739502652.2961822,12.669987916946411,23.873828470243165,1739502652.2961874,12.669987916946411,30.638405578619167,1739502652.29619,12.669987916946411,-0.07422124692223846,1739502652.2961938,12.669987916946411,0.0159976667188906,1739502652.296197,12.669987916946411,-0.09916231534897227,1739502652.2962003,12.669987916946411,-0.02222529798159087,1739502652.2962034,12.669987916946411,2.309337945083424,1739502652.2962065,12.669987916946411,0.0,1739502652.2962098,12.669987916946411,-0.07621551924823988,1739502652.2962132,12.669987916946411,0.03293875330763033,1739502652.2962165,12.669987916946411,2.385553464331664 +1739502652.3161886,12.689987897872925,24.78551244520974,1739502652.316192,12.689987897872925,-0.16786186908413914,1739502652.3161964,12.689987897872925,23.873828470243165,1739502652.3162012,12.689987897872925,30.638405578619167,1739502652.316204,12.689987897872925,-0.07422124692223846,1739502652.3162076,12.689987897872925,0.0159976667188906,1739502652.3162112,12.689987897872925,-0.09916231534897227,1739502652.3162146,12.689987897872925,-0.02222529798159087,1739502652.3162177,12.689987897872925,2.309337945083424,1739502652.316221,12.689987897872925,0.0,1739502652.316224,12.689987897872925,-0.07621551924823988,1739502652.3162274,12.689987897872925,0.03293875330763033,1739502652.3162308,12.689987897872925,2.385553464331664 +1739502652.335724,12.709987878799438,24.78551244520974,1739502652.3357275,12.709987878799438,-0.16786186908413914,1739502652.3357315,12.709987878799438,23.873828470243165,1739502652.3357363,12.709987878799438,30.638405578619167,1739502652.335739,12.709987878799438,-0.07422124692223846,1739502652.3357425,12.709987878799438,0.0159976667188906,1739502652.3357456,12.709987878799438,-0.09916231534897227,1739502652.3357487,12.709987878799438,-0.02222529798159087,1739502652.3357518,12.709987878799438,2.309337945083424,1739502652.3357546,12.709987878799438,0.0,1739502652.3357577,12.709987878799438,-0.07621551924823988,1739502652.335761,12.709987878799438,0.03293875330763033,1739502652.3357642,12.709987878799438,2.385553464331664 +1739502652.3568347,12.729987859725952,25.047361193182127,1739502652.356838,12.729987859725952,-0.15914001208320538,1739502652.3568423,12.729987859725952,24.21492308587432,1739502652.3568473,12.729987859725952,30.9628282583658,1739502652.35685,12.729987859725952,-0.07257906673822588,1739502652.3568535,12.729987859725952,0.014631941471124149,1739502652.3568568,12.729987859725952,-0.11287917235651103,1739502652.3568602,12.729987859725952,-0.024768180518475864,1739502652.3568633,12.729987859725952,2.2841349934029607,1739502652.3568666,12.729987859725952,0.0,1739502652.35687,12.729987859725952,-0.10075417649219721,1739502652.3568733,12.729987859725952,0.033713095542334405,1739502652.3568766,12.729987859725952,2.3772208344786687 +1739502652.3745084,12.749987840652466,25.047361193182127,1739502652.3745103,12.749987840652466,-0.15914001208320538,1739502652.3745131,12.749987840652466,24.21492308587432,1739502652.3745158,12.749987840652466,30.9628282583658,1739502652.3745167,12.749987840652466,-0.07257906673822588,1739502652.3745186,12.749987840652466,0.014631941471124149,1739502652.3745198,12.749987840652466,-0.11287917235651103,1739502652.3745213,12.749987840652466,-0.024768180518475864,1739502652.3745224,12.749987840652466,2.2841349934029607,1739502652.3745239,12.749987840652466,0.0,1739502652.374525,12.749987840652466,-0.09308584107570805,1739502652.3745265,12.749987840652466,0.033713095542334405,1739502652.3745277,12.749987840652466,2.3772208344786687 +1739502652.394679,12.76998782157898,25.047361193182127,1739502652.394681,12.76998782157898,-0.15914001208320538,1739502652.3946838,12.76998782157898,24.21492308587432,1739502652.3946867,12.76998782157898,30.9628282583658,1739502652.394688,12.76998782157898,-0.07257906673822588,1739502652.3946896,12.76998782157898,0.014631941471124149,1739502652.3946908,12.76998782157898,-0.11287917235651103,1739502652.3946924,12.76998782157898,-0.024768180518475864,1739502652.3946934,12.76998782157898,2.2841349934029607,1739502652.3946948,12.76998782157898,0.0,1739502652.3946965,12.76998782157898,-0.09308584107570805,1739502652.3946977,12.76998782157898,0.033713095542334405,1739502652.394699,12.76998782157898,2.3772208344786687 +1739502652.4144633,12.789987802505493,25.047361193182127,1739502652.4144654,12.789987802505493,-0.15914001208320538,1739502652.4144683,12.789987802505493,24.21492308587432,1739502652.414471,12.789987802505493,30.9628282583658,1739502652.414472,12.789987802505493,-0.07257906673822588,1739502652.4144738,12.789987802505493,0.014631941471124149,1739502652.4144752,12.789987802505493,-0.11287917235651103,1739502652.4144766,12.789987802505493,-0.024768180518475864,1739502652.4144778,12.789987802505493,2.2841349934029607,1739502652.4144793,12.789987802505493,0.0,1739502652.4144807,12.789987802505493,-0.09308584107570805,1739502652.4144819,12.789987802505493,0.033713095542334405,1739502652.4144835,12.789987802505493,2.3772208344786687 +1739502652.4344885,12.809987783432007,25.047361193182127,1739502652.4344907,12.809987783432007,-0.15914001208320538,1739502652.4344935,12.809987783432007,24.21492308587432,1739502652.434496,12.809987783432007,30.9628282583658,1739502652.4344974,12.809987783432007,-0.07257906673822588,1739502652.4344988,12.809987783432007,0.014631941471124149,1739502652.4345,12.809987783432007,-0.11287917235651103,1739502652.4345014,12.809987783432007,-0.024768180518475864,1739502652.4345026,12.809987783432007,2.2841349934029607,1739502652.4345043,12.809987783432007,0.0,1739502652.4345055,12.809987783432007,-0.09308584107570805,1739502652.4345067,12.809987783432007,0.033713095542334405,1739502652.4345083,12.809987783432007,2.3772208344786687 +1739502652.4579587,12.82998776435852,25.308198643252975,1739502652.457967,12.82998776435852,-0.15026396700620026,1739502652.4579775,12.82998776435852,24.679379254372506,1739502652.4579873,12.82998776435852,31.406944842509752,1739502652.4579926,12.82998776435852,-0.07330039683636946,1739502652.4579983,12.82998776435852,0.012618902717094338,1739502652.4580035,12.82998776435852,-0.13252772479667574,1739502652.458008,12.82998776435852,-0.027359341695156407,1739502652.4580126,12.82998776435852,2.2485117480119046,1739502652.4580188,12.82998776435852,0.0,1739502652.458024,12.82998776435852,-0.1301136124979259,1739502652.458029,12.82998776435852,0.034349205762641145,1739502652.4580345,12.82998776435852,2.3670541743537266 +1739502652.480795,12.849987745285034,25.308198643252975,1739502652.4808006,12.849987745285034,-0.15026396700620026,1739502652.4808083,12.849987745285034,24.679379254372506,1739502652.4808156,12.849987745285034,31.406944842509752,1739502652.480819,12.849987745285034,-0.07330039683636946,1739502652.4808233,12.849987745285034,0.012618902717094338,1739502652.4808269,12.849987745285034,-0.13252772479667574,1739502652.4808302,12.849987745285034,-0.027359341695156407,1739502652.4808333,12.849987745285034,2.2485117480119046,1739502652.480837,12.849987745285034,0.0,1739502652.4808404,12.849987745285034,-0.118542426341822,1739502652.480844,12.849987745285034,0.034349205762641145,1739502652.4808476,12.849987745285034,2.3670541743537266 +1739502652.4959416,12.869987726211548,25.308198643252975,1739502652.4959466,12.869987726211548,-0.15026396700620026,1739502652.495953,12.869987726211548,24.679379254372506,1739502652.4959602,12.869987726211548,31.406944842509752,1739502652.495964,12.869987726211548,-0.07330039683636946,1739502652.4959693,12.869987726211548,0.012618902717094338,1739502652.4959738,12.869987726211548,-0.13252772479667574,1739502652.4959786,12.869987726211548,-0.027359341695156407,1739502652.495983,12.869987726211548,2.2485117480119046,1739502652.4959877,12.869987726211548,0.0,1739502652.4959924,12.869987726211548,-0.118542426341822,1739502652.4959972,12.869987726211548,0.034349205762641145,1739502652.4960017,12.869987726211548,2.3670541743537266 +1739502652.5149074,12.889987707138062,25.308198643252975,1739502652.51491,12.889987707138062,-0.15026396700620026,1739502652.5149133,12.889987707138062,24.679379254372506,1739502652.5149164,12.889987707138062,31.406944842509752,1739502652.5149179,12.889987707138062,-0.07330039683636946,1739502652.51492,12.889987707138062,0.012618902717094338,1739502652.5149214,12.889987707138062,-0.13252772479667574,1739502652.514923,12.889987707138062,-0.027359341695156407,1739502652.5149243,12.889987707138062,2.2485117480119046,1739502652.5149264,12.889987707138062,0.0,1739502652.5149276,12.889987707138062,-0.118542426341822,1739502652.5149293,12.889987707138062,0.034349205762641145,1739502652.514931,12.889987707138062,2.3670541743537266 +1739502652.5346406,12.909987688064575,25.308198643252975,1739502652.5346432,12.909987688064575,-0.15026396700620026,1739502652.5346465,12.909987688064575,24.679379254372506,1739502652.5346496,12.909987688064575,31.406944842509752,1739502652.534651,12.909987688064575,-0.07330039683636946,1739502652.534653,12.909987688064575,0.012618902717094338,1739502652.5346544,12.909987688064575,-0.13252772479667574,1739502652.5346563,12.909987688064575,-0.027359341695156407,1739502652.5346575,12.909987688064575,2.2485117480119046,1739502652.5346594,12.909987688064575,0.0,1739502652.5346608,12.909987688064575,-0.118542426341822,1739502652.5346627,12.909987688064575,0.034349205762641145,1739502652.534664,12.909987688064575,2.3670541743537266 +1739502652.5546677,12.929987668991089,25.308198643252975,1739502652.5546703,12.929987668991089,-0.15026396700620026,1739502652.554674,12.929987668991089,24.679379254372506,1739502652.5546772,12.929987668991089,31.406944842509752,1739502652.5546787,12.929987668991089,-0.07330039683636946,1739502652.554681,12.929987668991089,0.012618902717094338,1739502652.5546827,12.929987668991089,-0.13252772479667574,1739502652.5546842,12.929987668991089,-0.027359341695156407,1739502652.5546856,12.929987668991089,2.2485117480119046,1739502652.5546877,12.929987668991089,0.0,1739502652.5546892,12.929987668991089,-0.118542426341822,1739502652.5546908,12.929987668991089,0.034349205762641145,1739502652.5546923,12.929987668991089,2.3670541743537266 +1739502652.5747056,12.949987649917603,25.567747256830724,1739502652.5747082,12.949987649917603,-0.14128214098499292,1739502652.5747116,12.949987649917603,24.71130373384257,1739502652.5747147,12.949987649917603,31.41245763361113,1739502652.574716,12.949987649917603,-0.07334918259832855,1739502652.5747182,12.949987649917603,0.011622457769642451,1739502652.5747197,12.949987649917603,-0.13590754134131292,1739502652.5747213,12.949987649917603,-0.030549570335803466,1739502652.5747225,12.949987649917603,2.2424403140785847,1739502652.5747244,12.949987649917603,0.0,1739502652.574726,12.949987649917603,-0.10816525623822101,1739502652.574728,12.949987649917603,0.03487606685398633,1739502652.5747294,12.949987649917603,2.353848438100371 +1739502652.594683,12.969987630844116,25.567747256830724,1739502652.5946858,12.969987630844116,-0.14128214098499292,1739502652.5946891,12.969987630844116,24.71130373384257,1739502652.594692,12.969987630844116,31.41245763361113,1739502652.5946937,12.969987630844116,-0.07334918259832855,1739502652.5946956,12.969987630844116,0.011622457769642451,1739502652.5946972,12.969987630844116,-0.13590754134131292,1739502652.5946987,12.969987630844116,-0.030549570335803466,1739502652.5947003,12.969987630844116,2.2424403140785847,1739502652.594702,12.969987630844116,0.0,1739502652.5947037,12.969987630844116,-0.11140812402178613,1739502652.594705,12.969987630844116,0.03487606685398633,1739502652.5947068,12.969987630844116,2.353848438100371 +1739502652.6146486,12.98998761177063,25.567747256830724,1739502652.6146512,12.98998761177063,-0.14128214098499292,1739502652.6146545,12.98998761177063,24.71130373384257,1739502652.6146576,12.98998761177063,31.41245763361113,1739502652.614659,12.98998761177063,-0.07334918259832855,1739502652.6146612,12.98998761177063,0.011622457769642451,1739502652.6146626,12.98998761177063,-0.13590754134131292,1739502652.614664,12.98998761177063,-0.030549570335803466,1739502652.6146655,12.98998761177063,2.2424403140785847,1739502652.6146672,12.98998761177063,0.0,1739502652.6146688,12.98998761177063,-0.11140812402178613,1739502652.6146703,12.98998761177063,0.03487606685398633,1739502652.6146722,12.98998761177063,2.353848438100371 +1739502652.6347492,13.009987592697144,25.567747256830724,1739502652.6347518,13.009987592697144,-0.14128214098499292,1739502652.6347554,13.009987592697144,24.71130373384257,1739502652.6347585,13.009987592697144,31.41245763361113,1739502652.6347597,13.009987592697144,-0.07334918259832855,1739502652.6347618,13.009987592697144,0.011622457769642451,1739502652.6347635,13.009987592697144,-0.13590754134131292,1739502652.6347651,13.009987592697144,-0.030549570335803466,1739502652.6347666,13.009987592697144,2.2424403140785847,1739502652.6347685,13.009987592697144,0.0,1739502652.63477,13.009987592697144,-0.11140812402178613,1739502652.6347718,13.009987592697144,0.03487606685398633,1739502652.6347733,13.009987592697144,2.353848438100371 +1739502652.6546688,13.029987573623657,25.567747256830724,1739502652.6546714,13.029987573623657,-0.14128214098499292,1739502652.6546748,13.029987573623657,24.71130373384257,1739502652.6546779,13.029987573623657,31.41245763361113,1739502652.6546793,13.029987573623657,-0.07334918259832855,1739502652.6546814,13.029987573623657,0.011622457769642451,1739502652.6546829,13.029987573623657,-0.13590754134131292,1739502652.6546843,13.029987573623657,-0.030549570335803466,1739502652.654686,13.029987573623657,2.2424403140785847,1739502652.6546876,13.029987573623657,0.0,1739502652.6546893,13.029987573623657,-0.11140812402178613,1739502652.6546907,13.029987573623657,0.03487606685398633,1739502652.6546926,13.029987573623657,2.353848438100371 +1739502652.6747193,13.049987554550171,25.825900456715573,1739502652.6747217,13.049987554550171,-0.132225098328826,1739502652.6747253,13.049987554550171,24.959675577428406,1739502652.6747284,13.049987554550171,31.63644642096389,1739502652.67473,13.049987554550171,-0.07445109269376037,1739502652.674732,13.049987554550171,0.009942628835825383,1739502652.6747336,13.049987554550171,-0.147166372047341,1739502652.6747353,13.049987554550171,-0.033471483964961996,1739502652.6747367,13.049987554550171,2.2223331983676315,1739502652.6747386,13.049987554550171,0.0,1739502652.67474,13.049987554550171,-0.12292502782771383,1739502652.6747417,13.049987554550171,0.03527154545501697,1739502652.6747434,13.049987554550171,2.341659191396282 +1739502652.6946728,13.069987535476685,25.825900456715573,1739502652.6946754,13.069987535476685,-0.132225098328826,1739502652.6946788,13.069987535476685,24.959675577428406,1739502652.694682,13.069987535476685,31.63644642096389,1739502652.6946833,13.069987535476685,-0.07445109269376037,1739502652.6946855,13.069987535476685,0.009942628835825383,1739502652.6946871,13.069987535476685,-0.147166372047341,1739502652.6946888,13.069987535476685,-0.033471483964961996,1739502652.6946902,13.069987535476685,2.2223331983676315,1739502652.6946921,13.069987535476685,0.0,1739502652.6946936,13.069987535476685,-0.11932599302865032,1739502652.6946955,13.069987535476685,0.03527154545501697,1739502652.694697,13.069987535476685,2.341659191396282 +1739502652.714617,13.089987516403198,25.825900456715573,1739502652.7146199,13.089987516403198,-0.132225098328826,1739502652.714623,13.089987516403198,24.959675577428406,1739502652.714626,13.089987516403198,31.63644642096389,1739502652.7146277,13.089987516403198,-0.07445109269376037,1739502652.71463,13.089987516403198,0.009942628835825383,1739502652.7146313,13.089987516403198,-0.147166372047341,1739502652.714633,13.089987516403198,-0.033471483964961996,1739502652.7146344,13.089987516403198,2.2223331983676315,1739502652.7146363,13.089987516403198,0.0,1739502652.7146378,13.089987516403198,-0.11932599302865032,1739502652.7146394,13.089987516403198,0.03527154545501697,1739502652.7146409,13.089987516403198,2.341659191396282 +1739502652.73466,13.109987497329712,25.825900456715573,1739502652.7346623,13.109987497329712,-0.132225098328826,1739502652.7346656,13.109987497329712,24.959675577428406,1739502652.7346685,13.109987497329712,31.63644642096389,1739502652.7346704,13.109987497329712,-0.07445109269376037,1739502652.7346723,13.109987497329712,0.009942628835825383,1739502652.734674,13.109987497329712,-0.147166372047341,1739502652.7346754,13.109987497329712,-0.033471483964961996,1739502652.7346773,13.109987497329712,2.2223331983676315,1739502652.734679,13.109987497329712,0.0,1739502652.7346804,13.109987497329712,-0.11932599302865032,1739502652.734682,13.109987497329712,0.03527154545501697,1739502652.7346838,13.109987497329712,2.341659191396282 +1739502652.7547462,13.129987478256226,25.825900456715573,1739502652.7547493,13.129987478256226,-0.132225098328826,1739502652.7547524,13.129987478256226,24.959675577428406,1739502652.7547555,13.129987478256226,31.63644642096389,1739502652.7547572,13.129987478256226,-0.07445109269376037,1739502652.754759,13.129987478256226,0.009942628835825383,1739502652.754761,13.129987478256226,-0.147166372047341,1739502652.7547631,13.129987478256226,-0.033471483964961996,1739502652.7547646,13.129987478256226,2.2223331983676315,1739502652.7547662,13.129987478256226,0.0,1739502652.7547681,13.129987478256226,-0.11932599302865032,1739502652.7547696,13.129987478256226,0.03527154545501697,1739502652.7547717,13.129987478256226,2.341659191396282 +1739502652.774661,13.14998745918274,25.825900456715573,1739502652.7746637,13.14998745918274,-0.132225098328826,1739502652.7746673,13.14998745918274,24.959675577428406,1739502652.7746704,13.14998745918274,31.63644642096389,1739502652.774672,13.14998745918274,-0.07445109269376037,1739502652.7746742,13.14998745918274,0.009942628835825383,1739502652.7746756,13.14998745918274,-0.147166372047341,1739502652.7746773,13.14998745918274,-0.033471483964961996,1739502652.7746787,13.14998745918274,2.2223331983676315,1739502652.7746806,13.14998745918274,0.0,1739502652.774682,13.14998745918274,-0.11932599302865032,1739502652.7746837,13.14998745918274,0.03527154545501697,1739502652.7746854,13.14998745918274,2.341659191396282 +1739502652.7947423,13.169987440109253,26.082660758141525,1739502652.7947454,13.169987440109253,-0.12313078299786362,1739502652.7947488,13.169987440109253,25.737898497038366,1739502652.7947516,13.169987440109253,32.38837715284461,1739502652.7947533,13.169987440109253,-0.08,1739502652.7947552,13.169987440109253,0.006839843039829524,1739502652.794757,13.169987440109253,-0.181064165478598,1739502652.7947586,13.169987440109253,-0.034969133518466616,1739502652.79476,13.169987440109253,2.162877258684191,1739502652.794762,13.169987440109253,0.0,1739502652.7947636,13.169987440109253,-0.1867035703357825,1739502652.7947652,13.169987440109253,0.035557407832536796,1739502652.794767,13.169987440109253,2.3285253223064286 +1739502652.814701,13.189987421035767,26.082660758141525,1739502652.8147037,13.189987421035767,-0.12313078299786362,1739502652.814707,13.189987421035767,25.737898497038366,1739502652.81471,13.189987421035767,32.38837715284461,1739502652.8147116,13.189987421035767,-0.08,1739502652.8147137,13.189987421035767,0.006839843039829524,1739502652.8147154,13.189987421035767,-0.181064165478598,1739502652.8147168,13.189987421035767,-0.034969133518466616,1739502652.8147185,13.189987421035767,2.162877258684191,1739502652.8147202,13.189987421035767,0.0,1739502652.8147218,13.189987421035767,-0.16564806362223772,1739502652.8147233,13.189987421035767,0.035557407832536796,1739502652.8147252,13.189987421035767,2.3285253223064286 +1739502652.8346443,13.20998740196228,26.082660758141525,1739502652.8346467,13.20998740196228,-0.12313078299786362,1739502652.83465,13.20998740196228,25.737898497038366,1739502652.8346534,13.20998740196228,32.38837715284461,1739502652.834655,13.20998740196228,-0.08,1739502652.834657,13.20998740196228,0.006839843039829524,1739502652.8346586,13.20998740196228,-0.181064165478598,1739502652.8346605,13.20998740196228,-0.034969133518466616,1739502652.834662,13.20998740196228,2.162877258684191,1739502652.8346639,13.20998740196228,0.0,1739502652.8346655,13.20998740196228,-0.16564806362223772,1739502652.8346672,13.20998740196228,0.035557407832536796,1739502652.8346689,13.20998740196228,2.3285253223064286 +1739502652.8563607,13.229987382888794,26.082660758141525,1739502652.8563647,13.229987382888794,-0.12313078299786362,1739502652.8563702,13.229987382888794,25.737898497038366,1739502652.8563766,13.229987382888794,32.38837715284461,1739502652.8563802,13.229987382888794,-0.08,1739502652.8563845,13.229987382888794,0.006839843039829524,1739502652.8563883,13.229987382888794,-0.181064165478598,1739502652.8563924,13.229987382888794,-0.034969133518466616,1739502652.8563962,13.229987382888794,2.162877258684191,1739502652.8564005,13.229987382888794,0.0,1739502652.8564045,13.229987382888794,-0.16564806362223772,1739502652.8564084,13.229987382888794,0.035557407832536796,1739502652.8564126,13.229987382888794,2.3285253223064286 +1739502652.8746316,13.249987363815308,26.082660758141525,1739502652.8746343,13.249987363815308,-0.12313078299786362,1739502652.8746376,13.249987363815308,25.737898497038366,1739502652.874641,13.249987363815308,32.38837715284461,1739502652.8746424,13.249987363815308,-0.08,1739502652.8746445,13.249987363815308,0.006839843039829524,1739502652.874646,13.249987363815308,-0.181064165478598,1739502652.874648,13.249987363815308,-0.034969133518466616,1739502652.8746493,13.249987363815308,2.162877258684191,1739502652.8746512,13.249987363815308,0.0,1739502652.8746526,13.249987363815308,-0.16564806362223772,1739502652.8746545,13.249987363815308,0.035557407832536796,1739502652.8746562,13.249987363815308,2.3285253223064286 +1739502652.895066,13.269987344741821,26.337739563265007,1739502652.8950686,13.269987344741821,-0.11403083155021321,1739502652.895072,13.269987344741821,25.87853971737554,1739502652.8950756,13.269987344741821,32.492858405916834,1739502652.8950772,13.269987344741821,-0.08,1739502652.8950791,13.269987344741821,0.005528810356204809,1739502652.8950808,13.269987344741821,-0.1861131864352999,1739502652.8950822,13.269987344741821,-0.03772500546154687,1739502652.8950837,13.269987344741821,2.1541585488330033,1739502652.8950856,13.269987344741821,0.0,1739502652.895087,13.269987344741821,-0.1520316613369029,1739502652.8950887,13.269987344741821,0.0357700968551492,1739502652.89509,13.269987344741821,2.310445338673953 +1739502652.9146526,13.289987325668335,26.337739563265007,1739502652.9146552,13.289987325668335,-0.11403083155021321,1739502652.9146585,13.289987325668335,25.87853971737554,1739502652.914662,13.289987325668335,32.492858405916834,1739502652.9146633,13.289987325668335,-0.08,1739502652.9146655,13.289987325668335,0.005528810356204809,1739502652.914667,13.289987325668335,-0.1861131864352999,1739502652.9146686,13.289987325668335,-0.03772500546154687,1739502652.91467,13.289987325668335,2.1541585488330033,1739502652.914672,13.289987325668335,0.0,1739502652.9146733,13.289987325668335,-0.15628678984094968,1739502652.914675,13.289987325668335,0.0357700968551492,1739502652.9146764,13.289987325668335,2.310445338673953 +1739502652.934668,13.309987306594849,26.337739563265007,1739502652.9346707,13.309987306594849,-0.11403083155021321,1739502652.934674,13.309987306594849,25.87853971737554,1739502652.9346774,13.309987306594849,32.492858405916834,1739502652.9346788,13.309987306594849,-0.08,1739502652.9346805,13.309987306594849,0.005528810356204809,1739502652.9346824,13.309987306594849,-0.1861131864352999,1739502652.9346838,13.309987306594849,-0.03772500546154687,1739502652.9346855,13.309987306594849,2.1541585488330033,1739502652.9346871,13.309987306594849,0.0,1739502652.934689,13.309987306594849,-0.15628678984094968,1739502652.9346905,13.309987306594849,0.0357700968551492,1739502652.9346921,13.309987306594849,2.310445338673953 +1739502652.954798,13.329987287521362,26.337739563265007,1739502652.954801,13.329987287521362,-0.11403083155021321,1739502652.9548047,13.329987287521362,25.87853971737554,1739502652.9548078,13.329987287521362,32.492858405916834,1739502652.9548094,13.329987287521362,-0.08,1739502652.9548116,13.329987287521362,0.005528810356204809,1739502652.9548132,13.329987287521362,-0.1861131864352999,1739502652.9548147,13.329987287521362,-0.03772500546154687,1739502652.9548163,13.329987287521362,2.1541585488330033,1739502652.954818,13.329987287521362,0.0,1739502652.9548197,13.329987287521362,-0.15628678984094968,1739502652.9548213,13.329987287521362,0.0357700968551492,1739502652.954823,13.329987287521362,2.310445338673953 +1739502652.9746723,13.349987268447876,26.337739563265007,1739502652.9746752,13.349987268447876,-0.11403083155021321,1739502652.9746783,13.349987268447876,25.87853971737554,1739502652.9746816,13.349987268447876,32.492858405916834,1739502652.974683,13.349987268447876,-0.08,1739502652.974685,13.349987268447876,0.005528810356204809,1739502652.9746866,13.349987268447876,-0.1861131864352999,1739502652.9746883,13.349987268447876,-0.03772500546154687,1739502652.9746895,13.349987268447876,2.1541585488330033,1739502652.9746916,13.349987268447876,0.0,1739502652.974693,13.349987268447876,-0.15628678984094968,1739502652.9746947,13.349987268447876,0.0357700968551492,1739502652.9746962,13.349987268447876,2.310445338673953 +1739502652.9946864,13.36998724937439,26.337739563265007,1739502652.9946892,13.36998724937439,-0.11403083155021321,1739502652.9946926,13.36998724937439,25.87853971737554,1739502652.994696,13.36998724937439,32.492858405916834,1739502652.9946976,13.36998724937439,-0.08,1739502652.9946995,13.36998724937439,0.005528810356204809,1739502652.9947014,13.36998724937439,-0.1861131864352999,1739502652.9947028,13.36998724937439,-0.03772500546154687,1739502652.9947045,13.36998724937439,2.1541585488330033,1739502652.9947062,13.36998724937439,0.0,1739502652.9947078,13.36998724937439,-0.15628678984094968,1739502652.9947095,13.36998724937439,0.0357700968551492,1739502652.994711,13.36998724937439,2.310445338673953 +1739502653.014709,13.389987230300903,26.59087714125104,1739502653.0147116,13.389987230300903,-0.1049630820664289,1739502653.014715,13.389987230300903,26.133375926867398,1739502653.014718,13.389987230300903,32.71364384147076,1739502653.0147195,13.389987230300903,-0.07956611959667939,1739502653.0147216,13.389987230300903,0.0041479314921879454,1739502653.014723,13.389987230300903,-0.19394433203782818,1739502653.0147245,13.389987230300903,-0.0397292189311968,1739502653.0147262,13.389987230300903,2.1407051117683333,1739502653.0147283,13.389987230300903,0.0,1739502653.0147295,13.389987230300903,-0.1510920058536716,1739502653.0147312,13.389987230300903,0.03582888876619402,1739502653.0147328,13.389987230300903,2.2934204886823943 +1739502653.0346684,13.409987211227417,26.59087714125104,1739502653.0346713,13.409987211227417,-0.1049630820664289,1739502653.0346746,13.409987211227417,26.133375926867398,1739502653.034678,13.409987211227417,32.71364384147076,1739502653.03468,13.409987211227417,-0.07956611959667939,1739502653.0346818,13.409987211227417,0.0041479314921879454,1739502653.0346835,13.409987211227417,-0.19394433203782818,1739502653.0346851,13.409987211227417,-0.0397292189311968,1739502653.0346866,13.409987211227417,2.1407051117683333,1739502653.0346885,13.409987211227417,0.0,1739502653.0346901,13.409987211227417,-0.152715376914061,1739502653.0346916,13.409987211227417,0.03582888876619402,1739502653.0346935,13.409987211227417,2.2934204886823943 +1739502653.0547385,13.42998719215393,26.59087714125104,1739502653.0547416,13.42998719215393,-0.1049630820664289,1739502653.0547447,13.42998719215393,26.133375926867398,1739502653.0547478,13.42998719215393,32.71364384147076,1739502653.0547497,13.42998719215393,-0.07956611959667939,1739502653.0547516,13.42998719215393,0.0041479314921879454,1739502653.0547533,13.42998719215393,-0.19394433203782818,1739502653.054755,13.42998719215393,-0.0397292189311968,1739502653.0547564,13.42998719215393,2.1407051117683333,1739502653.0547585,13.42998719215393,0.0,1739502653.0547602,13.42998719215393,-0.152715376914061,1739502653.0547616,13.42998719215393,0.03582888876619402,1739502653.0547636,13.42998719215393,2.2934204886823943 +1739502653.0746465,13.449987173080444,26.59087714125104,1739502653.074649,13.449987173080444,-0.1049630820664289,1739502653.0746524,13.449987173080444,26.133375926867398,1739502653.0746555,13.449987173080444,32.71364384147076,1739502653.074657,13.449987173080444,-0.07956611959667939,1739502653.074659,13.449987173080444,0.0041479314921879454,1739502653.0746605,13.449987173080444,-0.19394433203782818,1739502653.0746624,13.449987173080444,-0.0397292189311968,1739502653.0746636,13.449987173080444,2.1407051117683333,1739502653.0746655,13.449987173080444,0.0,1739502653.074667,13.449987173080444,-0.152715376914061,1739502653.074669,13.449987173080444,0.03582888876619402,1739502653.0746703,13.449987173080444,2.2934204886823943 +1739502653.0947342,13.469987154006958,26.59087714125104,1739502653.0947368,13.469987154006958,-0.1049630820664289,1739502653.0947402,13.469987154006958,26.133375926867398,1739502653.0947437,13.469987154006958,32.71364384147076,1739502653.0947454,13.469987154006958,-0.07956611959667939,1739502653.0947473,13.469987154006958,0.0041479314921879454,1739502653.0947492,13.469987154006958,-0.19394433203782818,1739502653.0947506,13.469987154006958,-0.0397292189311968,1739502653.0947523,13.469987154006958,2.1407051117683333,1739502653.094754,13.469987154006958,0.0,1739502653.0947556,13.469987154006958,-0.152715376914061,1739502653.0947573,13.469987154006958,0.03582888876619402,1739502653.094759,13.469987154006958,2.2934204886823943 +1739502653.1574044,13.499987125396729,26.84215538640039,1739502653.157406,13.499987125396729,-0.09595803557975824,1739502653.1574087,13.499987125396729,26.702796377567104,1739502653.1574113,13.499987125396729,33.249648784605604,1739502653.1574128,13.499987125396729,-0.07827501066135434,1739502653.1574144,13.499987125396729,0.0027597344120929286,1739502653.1574156,13.499987125396729,-0.21166533050356465,1739502653.157417,13.499987125396729,-0.0395918770507865,1739502653.1574183,13.499987125396729,2.1105708743778044,1739502653.1574197,13.499987125396729,0.0,1739502653.157421,13.499987125396729,-0.17224814507010122,1739502653.1574223,13.499987125396729,0.03579964976111607,1739502653.1574242,13.499987125396729,2.2767150253970527 +1739502653.1632495,13.499987125396729,26.84215538640039,1739502653.1632516,13.499987125396729,-0.09595803557975824,1739502653.1632543,13.499987125396729,26.702796377567104,1739502653.163257,13.499987125396729,33.249648784605604,1739502653.163258,13.499987125396729,-0.07827501066135434,1739502653.16326,13.499987125396729,0.0027597344120929286,1739502653.1632612,13.499987125396729,-0.21166533050356465,1739502653.1632624,13.499987125396729,-0.0395918770507865,1739502653.1632636,13.499987125396729,2.1105708743778044,1739502653.163265,13.499987125396729,0.0,1739502653.1632664,13.499987125396729,-0.1661441510192483,1739502653.1632676,13.499987125396729,0.03579964976111607,1739502653.1632688,13.499987125396729,2.2767150253970527 +1739502653.183915,13.519987106323242,26.84215538640039,1739502653.1839178,13.519987106323242,-0.09595803557975824,1739502653.1839206,13.519987106323242,26.702796377567104,1739502653.1839235,13.519987106323242,33.249648784605604,1739502653.1839247,13.519987106323242,-0.07827501066135434,1739502653.1839266,13.519987106323242,0.0027597344120929286,1739502653.183928,13.519987106323242,-0.21166533050356465,1739502653.1839297,13.519987106323242,-0.0395918770507865,1739502653.1839309,13.519987106323242,2.1105708743778044,1739502653.1839323,13.519987106323242,0.0,1739502653.1839337,13.519987106323242,-0.1661441510192483,1739502653.1839352,13.519987106323242,0.03579964976111607,1739502653.1839368,13.519987106323242,2.2767150253970527 +1739502653.2035115,13.539987087249756,26.84215538640039,1739502653.2035136,13.539987087249756,-0.09595803557975824,1739502653.2035165,13.539987087249756,26.702796377567104,1739502653.2035186,13.539987087249756,33.249648784605604,1739502653.2035203,13.539987087249756,-0.07827501066135434,1739502653.2035217,13.539987087249756,0.0027597344120929286,1739502653.2035232,13.539987087249756,-0.21166533050356465,1739502653.2035244,13.539987087249756,-0.0395918770507865,1739502653.2035263,13.539987087249756,2.1105708743778044,1739502653.2035277,13.539987087249756,0.0,1739502653.203529,13.539987087249756,-0.1661441510192483,1739502653.2035303,13.539987087249756,0.03579964976111607,1739502653.2035315,13.539987087249756,2.2767150253970527 +1739502653.223483,13.55998706817627,26.84215538640039,1739502653.2234852,13.55998706817627,-0.09595803557975824,1739502653.223488,13.55998706817627,26.702796377567104,1739502653.2234907,13.55998706817627,33.249648784605604,1739502653.2234921,13.55998706817627,-0.07827501066135434,1739502653.2234938,13.55998706817627,0.0027597344120929286,1739502653.2234955,13.55998706817627,-0.21166533050356465,1739502653.223497,13.55998706817627,-0.0395918770507865,1739502653.2234979,13.55998706817627,2.1105708743778044,1739502653.2234995,13.55998706817627,0.0,1739502653.2235007,13.55998706817627,-0.1661441510192483,1739502653.2235024,13.55998706817627,0.03579964976111607,1739502653.2235036,13.55998706817627,2.2767150253970527 +1739502653.2437978,13.579987049102783,26.84215538640039,1739502653.2438006,13.579987049102783,-0.09595803557975824,1739502653.2438037,13.579987049102783,26.702796377567104,1739502653.2438068,13.579987049102783,33.249648784605604,1739502653.243808,13.579987049102783,-0.07827501066135434,1739502653.2438097,13.579987049102783,0.0027597344120929286,1739502653.2438111,13.579987049102783,-0.21166533050356465,1739502653.2438123,13.579987049102783,-0.0395918770507865,1739502653.2438135,13.579987049102783,2.1105708743778044,1739502653.2438157,13.579987049102783,0.0,1739502653.2438169,13.579987049102783,-0.1661441510192483,1739502653.2438183,13.579987049102783,0.03579964976111607,1739502653.2438195,13.579987049102783,2.2767150253970527 +1739502653.2638428,13.599987030029297,27.091538107593223,1739502653.2638457,13.599987030029297,-0.08703138271189115,1739502653.263849,13.599987030029297,26.932610926479597,1739502653.2638521,13.599987030029297,33.44337083815359,1739502653.2638535,13.599987030029297,-0.0769816802274261,1739502653.2638552,13.599987030029297,0.0015821723469523776,1739502653.263857,13.599987030029297,-0.2170227766308363,1739502653.2638583,13.599987030029297,-0.041308544625035484,1739502653.2638597,13.599987030029297,2.101544415895574,1739502653.2638614,13.599987030029297,0.0,1739502653.2638628,13.599987030029297,-0.15303344695573226,1739502653.2638643,13.599987030029297,0.03575573467855233,1739502653.263866,13.599987030029297,2.2586749605574217 +1739502653.2837448,13.61998701095581,27.091538107593223,1739502653.2837474,13.61998701095581,-0.08703138271189115,1739502653.28375,13.61998701095581,26.932610926479597,1739502653.283753,13.61998701095581,33.44337083815359,1739502653.2837546,13.61998701095581,-0.0769816802274261,1739502653.283756,13.61998701095581,0.0015821723469523776,1739502653.2837572,13.61998701095581,-0.2170227766308363,1739502653.2837586,13.61998701095581,-0.041308544625035484,1739502653.2837598,13.61998701095581,2.101544415895574,1739502653.2837615,13.61998701095581,0.0,1739502653.2837625,13.61998701095581,-0.15713054466184762,1739502653.283764,13.61998701095581,0.03575573467855233,1739502653.2837653,13.61998701095581,2.2586749605574217 +1739502653.303691,13.639986991882324,27.091538107593223,1739502653.3036938,13.639986991882324,-0.08703138271189115,1739502653.303697,13.639986991882324,26.932610926479597,1739502653.3037002,13.639986991882324,33.44337083815359,1739502653.3037014,13.639986991882324,-0.0769816802274261,1739502653.3037033,13.639986991882324,0.0015821723469523776,1739502653.3037047,13.639986991882324,-0.2170227766308363,1739502653.303707,13.639986991882324,-0.041308544625035484,1739502653.303708,13.639986991882324,2.101544415895574,1739502653.3037097,13.639986991882324,0.0,1739502653.303711,13.639986991882324,-0.15713054466184762,1739502653.3037126,13.639986991882324,0.03575573467855233,1739502653.3037138,13.639986991882324,2.2586749605574217 +1739502653.3238661,13.659986972808838,27.091538107593223,1739502653.3238685,13.659986972808838,-0.08703138271189115,1739502653.3238711,13.659986972808838,26.932610926479597,1739502653.3238738,13.659986972808838,33.44337083815359,1739502653.3238752,13.659986972808838,-0.0769816802274261,1739502653.3238769,13.659986972808838,0.0015821723469523776,1739502653.323878,13.659986972808838,-0.2170227766308363,1739502653.323898,13.659986972808838,-0.041308544625035484,1739502653.323899,13.659986972808838,2.101544415895574,1739502653.3239007,13.659986972808838,0.0,1739502653.323902,13.659986972808838,-0.15713054466184762,1739502653.3239036,13.659986972808838,0.03575573467855233,1739502653.3239048,13.659986972808838,2.2586749605574217 +1739502653.3436747,13.679986953735352,27.091538107593223,1739502653.343677,13.679986953735352,-0.08703138271189115,1739502653.3436797,13.679986953735352,26.932610926479597,1739502653.3436825,13.679986953735352,33.44337083815359,1739502653.343684,13.679986953735352,-0.0769816802274261,1739502653.3436854,13.679986953735352,0.0015821723469523776,1739502653.3436868,13.679986953735352,-0.2170227766308363,1739502653.3436882,13.679986953735352,-0.041308544625035484,1739502653.3436894,13.679986953735352,2.101544415895574,1739502653.3436913,13.679986953735352,0.0,1739502653.3436925,13.679986953735352,-0.15713054466184762,1739502653.3436937,13.679986953735352,0.03575573467855233,1739502653.3436952,13.679986953735352,2.2586749605574217 +1739502653.3652112,13.699986934661865,27.091538107593223,1739502653.3652134,13.699986934661865,-0.08703138271189115,1739502653.3652163,13.699986934661865,26.932610926479597,1739502653.3652189,13.699986934661865,33.44337083815359,1739502653.36522,13.699986934661865,-0.0769816802274261,1739502653.3652217,13.699986934661865,0.0015821723469523776,1739502653.365223,13.699986934661865,-0.2170227766308363,1739502653.3652241,13.699986934661865,-0.041308544625035484,1739502653.3652256,13.699986934661865,2.101544415895574,1739502653.365227,13.699986934661865,0.0,1739502653.3652282,13.699986934661865,-0.15713054466184762,1739502653.3652296,13.699986934661865,0.03575573467855233,1739502653.3652308,13.699986934661865,2.2586749605574217 +1739502653.3845348,13.719986915588379,27.338980532388167,1739502653.3845384,13.719986915588379,-0.07819249580107446,1739502653.3845432,13.719986915588379,26.938805825986382,1739502653.3845484,13.719986915588379,33.41532941330041,1739502653.3845513,13.719986915588379,-0.0775482352599908,1739502653.384555,13.719986915588379,0.00010602757532459335,1739502653.3845751,13.719986915588379,-0.21586148894962323,1739502653.3845785,13.719986915588379,-0.04489712746772427,1739502653.384582,13.719986915588379,2.1034977212082033,1739502653.3845856,13.719986915588379,0.0,1739502653.384589,13.719986915588379,-0.12938575419842546,1739502653.3845925,13.719986915588379,0.035638371293744635,1739502653.3845959,13.719986915588379,2.241553728111109 +1739502653.4042873,13.739986896514893,27.338980532388167,1739502653.4042897,13.739986896514893,-0.07819249580107446,1739502653.4042928,13.739986896514893,26.938805825986382,1739502653.4042957,13.739986896514893,33.41532941330041,1739502653.4042969,13.739986896514893,-0.0775482352599908,1739502653.4042988,13.739986896514893,0.00010602757532459335,1739502653.4043,13.739986896514893,-0.21586148894962323,1739502653.404302,13.739986896514893,-0.04489712746772427,1739502653.404303,13.739986896514893,2.1034977212082033,1739502653.4043047,13.739986896514893,0.0,1739502653.404306,13.739986896514893,-0.13805600690290554,1739502653.4043074,13.739986896514893,0.035638371293744635,1739502653.4043088,13.739986896514893,2.241553728111109 +1739502653.425098,13.759986877441406,27.338980532388167,1739502653.4251003,13.759986877441406,-0.07819249580107446,1739502653.4251034,13.759986877441406,26.938805825986382,1739502653.4251058,13.759986877441406,33.41532941330041,1739502653.4251075,13.759986877441406,-0.0775482352599908,1739502653.425109,13.759986877441406,0.00010602757532459335,1739502653.4251106,13.759986877441406,-0.21586148894962323,1739502653.4251118,13.759986877441406,-0.04489712746772427,1739502653.4251132,13.759986877441406,2.1034977212082033,1739502653.4251149,13.759986877441406,0.0,1739502653.4251163,13.759986877441406,-0.13805600690290554,1739502653.425118,13.759986877441406,0.035638371293744635,1739502653.4251192,13.759986877441406,2.241553728111109 +1739502653.4440963,13.77998685836792,27.338980532388167,1739502653.4440985,13.77998685836792,-0.07819249580107446,1739502653.4441016,13.77998685836792,26.938805825986382,1739502653.4441047,13.77998685836792,33.41532941330041,1739502653.444106,13.77998685836792,-0.0775482352599908,1739502653.4441075,13.77998685836792,0.00010602757532459335,1739502653.4441092,13.77998685836792,-0.21586148894962323,1739502653.4441106,13.77998685836792,-0.04489712746772427,1739502653.4441118,13.77998685836792,2.1034977212082033,1739502653.4441135,13.77998685836792,0.0,1739502653.444115,13.77998685836792,-0.13805600690290554,1739502653.444116,13.77998685836792,0.035638371293744635,1739502653.444118,13.77998685836792,2.241553728111109 +1739502653.46544,13.799986839294434,27.338980532388167,1739502653.4654436,13.799986839294434,-0.07819249580107446,1739502653.4654481,13.799986839294434,26.938805825986382,1739502653.4654534,13.799986839294434,33.41532941330041,1739502653.465456,13.799986839294434,-0.0775482352599908,1739502653.46546,13.799986839294434,0.00010602757532459335,1739502653.4654634,13.799986839294434,-0.21586148894962323,1739502653.4654667,13.799986839294434,-0.04489712746772427,1739502653.4654698,13.799986839294434,2.1034977212082033,1739502653.4654732,13.799986839294434,0.0,1739502653.4654768,13.799986839294434,-0.13805600690290554,1739502653.46548,13.799986839294434,0.035638371293744635,1739502653.4654834,13.799986839294434,2.241553728111109 +1739502653.4851837,13.819986820220947,27.58463638556982,1739502653.4851878,13.819986820220947,-0.06945845389741212,1739502653.4851925,13.819986820220947,26.944955956357823,1739502653.4851978,13.819986820220947,33.39125405853483,1739502653.4852006,13.819986820220947,-0.078,1739502653.4852042,13.819986820220947,-0.0014710009204667563,1739502653.4852078,13.819986820220947,-0.21398101191474916,1739502653.4852111,13.819986820220947,-0.04873610828009341,1739502653.4852145,13.819986820220947,2.1066645660086274,1739502653.485218,13.819986820220947,0.0,1739502653.4852219,13.819986820220947,-0.1114638580857869,1739502653.4852252,13.819986820220947,0.035388536495359654,1739502653.4852293,13.819986820220947,2.2264384760482585 +1739502653.5051298,13.839986801147461,27.58463638556982,1739502653.5051322,13.839986801147461,-0.06945845389741212,1739502653.505135,13.839986801147461,26.944955956357823,1739502653.5051377,13.839986801147461,33.39125405853483,1739502653.5051389,13.839986801147461,-0.078,1739502653.5051405,13.839986801147461,-0.0014710009204667563,1739502653.5051417,13.839986801147461,-0.21398101191474916,1739502653.5051434,13.839986801147461,-0.04873610828009341,1739502653.5051446,13.839986801147461,2.1066645660086274,1739502653.505146,13.839986801147461,0.0,1739502653.5051477,13.839986801147461,-0.11977391003963112,1739502653.5051494,13.839986801147461,0.035388536495359654,1739502653.505151,13.839986801147461,2.2264384760482585 +1739502653.5363617,13.859986782073975,27.58463638556982,1739502653.5363712,13.859986782073975,-0.06945845389741212,1739502653.5363815,13.859986782073975,26.944955956357823,1739502653.536392,13.859986782073975,33.39125405853483,1739502653.5363965,13.859986782073975,-0.078,1739502653.536403,13.859986782073975,-0.0014710009204667563,1739502653.536408,13.859986782073975,-0.21398101191474916,1739502653.5364134,13.859986782073975,-0.04873610828009341,1739502653.536418,13.859986782073975,2.1066645660086274,1739502653.5364237,13.859986782073975,0.0,1739502653.5364287,13.859986782073975,-0.11977391003963112,1739502653.5364342,13.859986782073975,0.035388536495359654,1739502653.5364392,13.859986782073975,2.2264384760482585 +1739502653.5676618,13.889986753463745,27.58463638556982,1739502653.5676715,13.889986753463745,-0.06945845389741212,1739502653.567682,13.889986753463745,26.944955956357823,1739502653.5676913,13.889986753463745,33.39125405853483,1739502653.5676966,13.889986753463745,-0.078,1739502653.5677025,13.889986753463745,-0.0014710009204667563,1739502653.567708,13.889986753463745,-0.21398101191474916,1739502653.567712,13.889986753463745,-0.04873610828009341,1739502653.567717,13.889986753463745,2.1066645660086274,1739502653.5677223,13.889986753463745,0.0,1739502653.567726,13.889986753463745,-0.11977391003963112,1739502653.5677443,13.889986753463745,0.035388536495359654,1739502653.567749,13.889986753463745,2.2264384760482585 +1739502653.5860994,13.919986724853516,27.58463638556982,1739502653.5861034,13.919986724853516,-0.06945845389741212,1739502653.5861096,13.919986724853516,26.944955956357823,1739502653.5861151,13.919986724853516,33.39125405853483,1739502653.5861177,13.919986724853516,-0.078,1739502653.5861206,13.919986724853516,-0.0014710009204667563,1739502653.5861235,13.919986724853516,-0.21398101191474916,1739502653.586126,13.919986724853516,-0.04873610828009341,1739502653.5861287,13.919986724853516,2.1066645660086274,1739502653.5861316,13.919986724853516,0.0,1739502653.5861342,13.919986724853516,-0.11977391003963112,1739502653.586137,13.919986724853516,0.035388536495359654,1739502653.58614,13.919986724853516,2.2264384760482585 +1739502653.606137,13.93998670578003,27.828752100396937,1739502653.6061423,13.93998670578003,-0.06086101963447188,1739502653.606148,13.93998670578003,26.951067446662766,1739502653.6061535,13.93998670578003,33.37146880274068,1739502653.606156,13.93998670578003,-0.078,1739502653.6061594,13.93998670578003,-0.003092152578172945,1739502653.6061625,13.93998670578003,-0.21087199992571623,1739502653.606165,13.93998670578003,-0.0527091399412929,1739502653.6061676,13.93998670578003,2.11191080386473,1739502653.6061707,13.93998670578003,0.0,1739502653.6061733,13.93998670578003,-0.0933090135624392,1739502653.606176,13.93998670578003,0.03496173063127122,1739502653.6061785,13.93998670578003,2.2134901029987133 +1739502653.6285744,13.959986686706543,27.828752100396937,1739502653.6285799,13.959986686706543,-0.06086101963447188,1739502653.6285858,13.959986686706543,26.951067446662766,1739502653.628591,13.959986686706543,33.37146880274068,1739502653.6285937,13.959986686706543,-0.078,1739502653.6285973,13.959986686706543,-0.003092152578172945,1739502653.6286001,13.959986686706543,-0.21087199992571623,1739502653.6286027,13.959986686706543,-0.0527091399412929,1739502653.628605,13.959986686706543,2.11191080386473,1739502653.628608,13.959986686706543,0.0,1739502653.6286106,13.959986686706543,-0.10157929913398345,1739502653.6286137,13.959986686706543,0.03496173063127122,1739502653.628616,13.959986686706543,2.2134901029987133 +1739502653.6513562,13.979986667633057,27.828752100396937,1739502653.6513636,13.979986667633057,-0.06086101963447188,1739502653.651373,13.979986667633057,26.951067446662766,1739502653.6513834,13.979986667633057,33.37146880274068,1739502653.6513891,13.979986667633057,-0.078,1739502653.6513968,13.979986667633057,-0.003092152578172945,1739502653.6514034,13.979986667633057,-0.21087199992571623,1739502653.65141,13.979986667633057,-0.0527091399412929,1739502653.651417,13.979986667633057,2.11191080386473,1739502653.6514242,13.979986667633057,0.0,1739502653.651431,13.979986667633057,-0.10157929913398345,1739502653.6514378,13.979986667633057,0.03496173063127122,1739502653.6514447,13.979986667633057,2.2134901029987133 +1739502653.6722684,14.009986639022827,27.828752100396937,1739502653.6722739,14.009986639022827,-0.06086101963447188,1739502653.672281,14.009986639022827,26.951067446662766,1739502653.6722898,14.009986639022827,33.37146880274068,1739502653.6722944,14.009986639022827,-0.078,1739502653.6723008,14.009986639022827,-0.003092152578172945,1739502653.6723065,14.009986639022827,-0.21087199992571623,1739502653.6723118,14.009986639022827,-0.0527091399412929,1739502653.6723173,14.009986639022827,2.11191080386473,1739502653.6723287,14.009986639022827,0.0,1739502653.6723342,14.009986639022827,-0.10157929913398345,1739502653.6723397,14.009986639022827,0.03496173063127122,1739502653.6723454,14.009986639022827,2.2134901029987133 +1739502653.7028935,14.02998661994934,27.828752100396937,1739502653.7028995,14.02998661994934,-0.06086101963447188,1739502653.702906,14.02998661994934,26.951067446662766,1739502653.7029126,14.02998661994934,33.37146880274068,1739502653.7029157,14.02998661994934,-0.078,1739502653.7029202,14.02998661994934,-0.003092152578172945,1739502653.7029235,14.02998661994934,-0.21087199992571623,1739502653.7029274,14.02998661994934,-0.0527091399412929,1739502653.7029312,14.02998661994934,2.11191080386473,1739502653.7029347,14.02998661994934,0.0,1739502653.7029388,14.02998661994934,-0.10157929913398345,1739502653.7029426,14.02998661994934,0.03496173063127122,1739502653.702946,14.02998661994934,2.2134901029987133 +1739502653.7287996,14.059986591339111,28.071529645677103,1739502653.7288046,14.059986591339111,-0.05242963851159299,1739502653.7288098,14.059986591339111,27.39349089888209,1739502653.7288153,14.059986591339111,33.791622474544724,1739502653.7288182,14.059986591339111,-0.075,1739502653.7288227,14.059986591339111,-0.00394578287964203,1739502653.728826,14.059986591339111,-0.2192155208178151,1739502653.7288296,14.059986591339111,-0.05144901026064902,1739502653.728833,14.059986591339111,2.097861128002033,1739502653.7288375,14.059986591339111,0.0,1739502653.7288413,14.059986591339111,-0.1058329546633094,1739502653.7288444,14.059986591339111,0.034387075665919024,1739502653.7288473,14.059986591339111,2.202364814440892 +1739502653.743098,14.069986581802368,28.071529645677103,1739502653.743103,14.069986581802368,-0.05242963851159299,1739502653.74311,14.069986581802368,27.39349089888209,1739502653.743115,14.069986581802368,33.791622474544724,1739502653.7431176,14.069986581802368,-0.075,1739502653.7431211,14.069986581802368,-0.00394578287964203,1739502653.7431245,14.069986581802368,-0.2192155208178151,1739502653.7431276,14.069986581802368,-0.05144901026064902,1739502653.7431307,14.069986581802368,2.097861128002033,1739502653.7431338,14.069986581802368,0.0,1739502653.7431374,14.069986581802368,-0.10450368643885888,1739502653.74314,14.069986581802368,0.034387075665919024,1739502653.743143,14.069986581802368,2.202364814440892 +1739502653.7625158,14.089986562728882,28.071529645677103,1739502653.7625194,14.089986562728882,-0.05242963851159299,1739502653.7625246,14.089986562728882,27.39349089888209,1739502653.7625277,14.089986562728882,33.791622474544724,1739502653.7625291,14.089986562728882,-0.075,1739502653.7625318,14.089986562728882,-0.00394578287964203,1739502653.7625334,14.089986562728882,-0.2192155208178151,1739502653.7625353,14.089986562728882,-0.05144901026064902,1739502653.7625372,14.089986562728882,2.097861128002033,1739502653.7625403,14.089986562728882,0.0,1739502653.762542,14.089986562728882,-0.10450368643885888,1739502653.7625442,14.089986562728882,0.034387075665919024,1739502653.762546,14.089986562728882,2.202364814440892 +1739502653.7850034,14.109986543655396,28.071529645677103,1739502653.7850103,14.109986543655396,-0.05242963851159299,1739502653.7850187,14.109986543655396,27.39349089888209,1739502653.7850277,14.109986543655396,33.791622474544724,1739502653.7850335,14.109986543655396,-0.075,1739502653.78504,14.109986543655396,-0.00394578287964203,1739502653.7850454,14.109986543655396,-0.2192155208178151,1739502653.7850509,14.109986543655396,-0.05144901026064902,1739502653.7850564,14.109986543655396,2.097861128002033,1739502653.7850618,14.109986543655396,0.0,1739502653.7850676,14.109986543655396,-0.10450368643885888,1739502653.785073,14.109986543655396,0.034387075665919024,1739502653.7850788,14.109986543655396,2.202364814440892 +1739502653.8021147,14.12998652458191,28.071529645677103,1739502653.8021183,14.12998652458191,-0.05242963851159299,1739502653.8021214,14.12998652458191,27.39349089888209,1739502653.8021245,14.12998652458191,33.791622474544724,1739502653.8021262,14.12998652458191,-0.075,1739502653.8021278,14.12998652458191,-0.00394578287964203,1739502653.8021297,14.12998652458191,-0.2192155208178151,1739502653.802131,14.12998652458191,-0.05144901026064902,1739502653.8021324,14.12998652458191,2.097861128002033,1739502653.8021343,14.12998652458191,0.0,1739502653.8021357,14.12998652458191,-0.10450368643885888,1739502653.8021376,14.12998652458191,0.034387075665919024,1739502653.802139,14.12998652458191,2.202364814440892 +1739502653.821706,14.149986505508423,28.313082490564447,1739502653.8217084,14.149986505508423,-0.04418723745595354,1739502653.8217113,14.149986505508423,27.855598683712042,1739502653.821714,14.149986505508423,34.23096492622931,1739502653.821715,14.149986505508423,-0.07184326507248501,1739502653.8217173,14.149986505508423,-0.004673263888998503,1739502653.8217185,14.149986505508423,-0.22748136556305648,1739502653.82172,14.149986505508423,-0.04987981952846195,1739502653.821721,14.149986505508423,2.0840344186541366,1739502653.8217225,14.149986505508423,0.0,1739502653.821724,14.149986505508423,-0.10806834920564193,1739502653.8217254,14.149986505508423,0.033775444886139885,1739502653.8217268,14.149986505508423,2.190988810014791 +1739502653.8415868,14.169986486434937,28.313082490564447,1739502653.8415897,14.169986486434937,-0.04418723745595354,1739502653.8415926,14.169986486434937,27.855598683712042,1739502653.8415952,14.169986486434937,34.23096492622931,1739502653.8415966,14.169986486434937,-0.07184326507248501,1739502653.8415985,14.169986486434937,-0.004673263888998503,1739502653.8415997,14.169986486434937,-0.22748136556305648,1739502653.8416014,14.169986486434937,-0.04987981952846195,1739502653.8416026,14.169986486434937,2.0840344186541366,1739502653.8416045,14.169986486434937,0.0,1739502653.8416057,14.169986486434937,-0.10695439136065454,1739502653.8416069,14.169986486434937,0.033775444886139885,1739502653.8416085,14.169986486434937,2.190988810014791 +1739502653.861584,14.18998646736145,28.313082490564447,1739502653.861586,14.18998646736145,-0.04418723745595354,1739502653.8615892,14.18998646736145,27.855598683712042,1739502653.8615918,14.18998646736145,34.23096492622931,1739502653.861593,14.18998646736145,-0.07184326507248501,1739502653.861595,14.18998646736145,-0.004673263888998503,1739502653.861596,14.18998646736145,-0.22748136556305648,1739502653.8615975,14.18998646736145,-0.04987981952846195,1739502653.8615987,14.18998646736145,2.0840344186541366,1739502653.8616002,14.18998646736145,0.0,1739502653.8616016,14.18998646736145,-0.10695439136065454,1739502653.8616028,14.18998646736145,0.033775444886139885,1739502653.8616042,14.18998646736145,2.190988810014791 +1739502653.8815098,14.209986448287964,28.313082490564447,1739502653.881512,14.209986448287964,-0.04418723745595354,1739502653.8815308,14.209986448287964,27.855598683712042,1739502653.8815334,14.209986448287964,34.23096492622931,1739502653.8815346,14.209986448287964,-0.07184326507248501,1739502653.8815362,14.209986448287964,-0.004673263888998503,1739502653.8815374,14.209986448287964,-0.22748136556305648,1739502653.8815627,14.209986448287964,-0.04987981952846195,1739502653.8815682,14.209986448287964,2.0840344186541366,1739502653.881572,14.209986448287964,0.0,1739502653.8815744,14.209986448287964,-0.10695439136065454,1739502653.8815768,14.209986448287964,0.033775444886139885,1739502653.881579,14.209986448287964,2.190988810014791 +1739502653.9014149,14.229986429214478,28.313082490564447,1739502653.901417,14.229986429214478,-0.04418723745595354,1739502653.9014199,14.229986429214478,27.855598683712042,1739502653.9014223,14.229986429214478,34.23096492622931,1739502653.9014237,14.229986429214478,-0.07184326507248501,1739502653.9014251,14.229986429214478,-0.004673263888998503,1739502653.9014268,14.229986429214478,-0.22748136556305648,1739502653.901428,14.229986429214478,-0.04987981952846195,1739502653.9014292,14.229986429214478,2.0840344186541366,1739502653.9014308,14.229986429214478,0.0,1739502653.901432,14.229986429214478,-0.10695439136065454,1739502653.9014332,14.229986429214478,0.033775444886139885,1739502653.901435,14.229986429214478,2.190988810014791 +1739502653.9217932,14.249986410140991,28.313082490564447,1739502653.9217958,14.249986410140991,-0.04418723745595354,1739502653.921799,14.249986410140991,27.855598683712042,1739502653.9218016,14.249986410140991,34.23096492622931,1739502653.9218028,14.249986410140991,-0.07184326507248501,1739502653.9218042,14.249986410140991,-0.004673263888998503,1739502653.9218059,14.249986410140991,-0.22748136556305648,1739502653.9218073,14.249986410140991,-0.04987981952846195,1739502653.9218085,14.249986410140991,2.0840344186541366,1739502653.9218102,14.249986410140991,0.0,1739502653.9218113,14.249986410140991,-0.10695439136065454,1739502653.921813,14.249986410140991,0.033775444886139885,1739502653.9218144,14.249986410140991,2.190988810014791 +1739502653.9417229,14.269986391067505,28.553367675768996,1739502653.9417262,14.269986391067505,-0.03613522394303459,1739502653.941729,14.269986391067505,27.885169865519224,1739502653.9417317,14.269986391067505,34.23707175149453,1739502653.941733,14.269986391067505,-0.07179279544219395,1739502653.9417343,14.269986391067505,-0.006273567945023129,1739502653.941736,14.269986391067505,-0.22409671977865242,1739502653.9417372,14.269986391067505,-0.05326857331365473,1739502653.9417386,14.269986391067505,2.0896850399901292,1739502653.94174,14.269986391067505,0.0,1739502653.9417412,14.269986391067505,-0.0816704633415855,1739502653.9417427,14.269986391067505,0.033163814106360746,1739502653.941744,14.269986391067505,2.1792567360181256 +1739502653.9613986,14.289986371994019,28.553367675768996,1739502653.9614007,14.289986371994019,-0.03613522394303459,1739502653.9614038,14.289986371994019,27.885169865519224,1739502653.9614067,14.289986371994019,34.23707175149453,1739502653.9614081,14.289986371994019,-0.07179279544219395,1739502653.9614098,14.289986371994019,-0.006273567945023129,1739502653.961411,14.289986371994019,-0.22409671977865242,1739502653.9614127,14.289986371994019,-0.05326857331365473,1739502653.9614139,14.289986371994019,2.0896850399901292,1739502653.9614158,14.289986371994019,0.0,1739502653.961417,14.289986371994019,-0.08957169602799642,1739502653.9614182,14.289986371994019,0.033163814106360746,1739502653.9614198,14.289986371994019,2.1792567360181256 +1739502653.9813795,14.309986352920532,28.553367675768996,1739502653.9813817,14.309986352920532,-0.03613522394303459,1739502653.9813845,14.309986352920532,27.885169865519224,1739502653.981387,14.309986352920532,34.23707175149453,1739502653.9813883,14.309986352920532,-0.07179279544219395,1739502653.9813898,14.309986352920532,-0.006273567945023129,1739502653.9813914,14.309986352920532,-0.22409671977865242,1739502653.9813926,14.309986352920532,-0.05326857331365473,1739502653.9813938,14.309986352920532,2.0896850399901292,1739502653.9813955,14.309986352920532,0.0,1739502653.9813967,14.309986352920532,-0.08957169602799642,1739502653.981398,14.309986352920532,0.033163814106360746,1739502653.9813993,14.309986352920532,2.1792567360181256 +1739502654.0014405,14.329986333847046,28.553367675768996,1739502654.001443,14.329986333847046,-0.03613522394303459,1739502654.0014467,14.329986333847046,27.885169865519224,1739502654.0014496,14.329986333847046,34.23707175149453,1739502654.0014508,14.329986333847046,-0.07179279544219395,1739502654.0014524,14.329986333847046,-0.006273567945023129,1739502654.0014539,14.329986333847046,-0.22409671977865242,1739502654.0014553,14.329986333847046,-0.05326857331365473,1739502654.0014565,14.329986333847046,2.0896850399901292,1739502654.0014582,14.329986333847046,0.0,1739502654.0014594,14.329986333847046,-0.08957169602799642,1739502654.001461,14.329986333847046,0.033163814106360746,1739502654.0014622,14.329986333847046,2.1792567360181256 +1739502654.021422,14.34998631477356,28.553367675768996,1739502654.021424,14.34998631477356,-0.03613522394303459,1739502654.021427,14.34998631477356,27.885169865519224,1739502654.0214295,14.34998631477356,34.23707175149453,1739502654.0214307,14.34998631477356,-0.07179279544219395,1739502654.0214326,14.34998631477356,-0.006273567945023129,1739502654.021434,14.34998631477356,-0.22409671977865242,1739502654.0214355,14.34998631477356,-0.05326857331365473,1739502654.0214367,14.34998631477356,2.0896850399901292,1739502654.0214381,14.34998631477356,0.0,1739502654.0214396,14.34998631477356,-0.08957169602799642,1739502654.021441,14.34998631477356,0.033163814106360746,1739502654.0214427,14.34998631477356,2.1792567360181256 +1739502654.0414834,14.369986295700073,28.79246247079454,1739502654.0414858,14.369986295700073,-0.02826951048121007,1739502654.0414886,14.369986295700073,28.345220084024955,1739502654.0414915,14.369986295700073,34.67749083656294,1739502654.0414927,14.369986295700073,-0.06965094217764445,1739502654.0414946,14.369986295700073,-0.007031529352639643,1739502654.0414958,14.369986295700073,-0.23289620008389866,1739502654.0414972,14.369986295700073,-0.05163713488038437,1739502654.0414987,14.369986295700073,2.0750261827732657,1739502654.0415003,14.369986295700073,0.0,1739502654.0415018,14.369986295700073,-0.0966224191538419,1739502654.041503,14.369986295700073,0.03255218332658161,1739502654.0415046,14.369986295700073,2.1694452495056504 +1739502654.0614238,14.389986276626587,28.79246247079454,1739502654.0614262,14.389986276626587,-0.02826951048121007,1739502654.061429,14.389986276626587,28.345220084024955,1739502654.0614316,14.389986276626587,34.67749083656294,1739502654.0614328,14.389986276626587,-0.06965094217764445,1739502654.0614345,14.389986276626587,-0.007031529352639643,1739502654.061436,14.389986276626587,-0.23289620008389866,1739502654.0614374,14.389986276626587,-0.05163713488038437,1739502654.0614388,14.389986276626587,2.0750261827732657,1739502654.0614402,14.389986276626587,0.0,1739502654.061442,14.389986276626587,-0.09441906673238476,1739502654.061443,14.389986276626587,0.03255218332658161,1739502654.0614445,14.389986276626587,2.1694452495056504 +1739502654.081442,14.4099862575531,28.79246247079454,1739502654.0814438,14.4099862575531,-0.02826951048121007,1739502654.081447,14.4099862575531,28.345220084024955,1739502654.0814497,14.4099862575531,34.67749083656294,1739502654.081451,14.4099862575531,-0.06965094217764445,1739502654.0814528,14.4099862575531,-0.007031529352639643,1739502654.081454,14.4099862575531,-0.23289620008389866,1739502654.0814557,14.4099862575531,-0.05163713488038437,1739502654.0814567,14.4099862575531,2.0750261827732657,1739502654.081458,14.4099862575531,0.0,1739502654.0814595,14.4099862575531,-0.09441906673238476,1739502654.081461,14.4099862575531,0.03255218332658161,1739502654.0814624,14.4099862575531,2.1694452495056504 +1739502654.1015122,14.429986238479614,28.79246247079454,1739502654.1015146,14.429986238479614,-0.02826951048121007,1739502654.1015177,14.429986238479614,28.345220084024955,1739502654.1015203,14.429986238479614,34.67749083656294,1739502654.101522,14.429986238479614,-0.06965094217764445,1739502654.1015236,14.429986238479614,-0.007031529352639643,1739502654.101525,14.429986238479614,-0.23289620008389866,1739502654.1015265,14.429986238479614,-0.05163713488038437,1739502654.1015277,14.429986238479614,2.0750261827732657,1739502654.1015294,14.429986238479614,0.0,1739502654.1015308,14.429986238479614,-0.09441906673238476,1739502654.1015325,14.429986238479614,0.03255218332658161,1739502654.1015337,14.429986238479614,2.1694452495056504 +1739502654.1214676,14.449986219406128,28.79246247079454,1739502654.12147,14.449986219406128,-0.02826951048121007,1739502654.121473,14.449986219406128,28.345220084024955,1739502654.1214764,14.449986219406128,34.67749083656294,1739502654.1214774,14.449986219406128,-0.06965094217764445,1739502654.1214793,14.449986219406128,-0.007031529352639643,1739502654.1214807,14.449986219406128,-0.23289620008389866,1739502654.1214821,14.449986219406128,-0.05163713488038437,1739502654.1214836,14.449986219406128,2.0750261827732657,1739502654.121485,14.449986219406128,0.0,1739502654.1214864,14.449986219406128,-0.09441906673238476,1739502654.1214879,14.449986219406128,0.03255218332658161,1739502654.1214895,14.449986219406128,2.1694452495056504 +1739502654.1414342,14.469986200332642,28.79246247079454,1739502654.1414366,14.469986200332642,-0.02826951048121007,1739502654.1414397,14.469986200332642,28.345220084024955,1739502654.1414423,14.469986200332642,34.67749083656294,1739502654.1414437,14.469986200332642,-0.06965094217764445,1739502654.1414456,14.469986200332642,-0.007031529352639643,1739502654.1414468,14.469986200332642,-0.23289620008389866,1739502654.1414483,14.469986200332642,-0.05163713488038437,1739502654.1414497,14.469986200332642,2.0750261827732657,1739502654.1414514,14.469986200332642,0.0,1739502654.1414526,14.469986200332642,-0.09441906673238476,1739502654.141454,14.469986200332642,0.03255218332658161,1739502654.1414554,14.469986200332642,2.1694452495056504 +1739502654.1614392,14.489986181259155,29.030455416387014,1739502654.1614416,14.489986181259155,-0.020585760127834973,1739502654.1614444,14.489986181259155,28.37450858383354,1739502654.1614473,14.489986181259155,34.68601635432959,1739502654.1614485,14.489986181259155,-0.06961253894446134,1739502654.1614509,14.489986181259155,-0.008668556722790014,1739502654.1614523,14.489986181259155,-0.22961280021238464,1739502654.1614535,14.489986181259155,-0.05512193196405232,1739502654.161455,14.489986181259155,2.0804838600915843,1739502654.1614566,14.489986181259155,0.0,1739502654.161458,14.489986181259155,-0.07138033245885644,1739502654.1614592,14.489986181259155,0.03194055254680247,1739502654.1614606,14.489986181259155,2.15906380173135 +1739502654.1815028,14.509986162185669,29.030455416387014,1739502654.181505,14.509986162185669,-0.020585760127834973,1739502654.1815083,14.509986162185669,28.37450858383354,1739502654.1815112,14.509986162185669,34.68601635432959,1739502654.181513,14.509986162185669,-0.06961253894446134,1739502654.181515,14.509986162185669,-0.008668556722790014,1739502654.1815166,14.509986162185669,-0.22961280021238464,1739502654.1815178,14.509986162185669,-0.05512193196405232,1739502654.181519,14.509986162185669,2.0804838600915843,1739502654.1815207,14.509986162185669,0.0,1739502654.181522,14.509986162185669,-0.07857994163976567,1739502654.1815236,14.509986162185669,0.03194055254680247,1739502654.1815248,14.509986162185669,2.15906380173135 +1739502654.2016454,14.529986143112183,29.030455416387014,1739502654.2016482,14.529986143112183,-0.020585760127834973,1739502654.201651,14.529986143112183,28.37450858383354,1739502654.201654,14.529986143112183,34.68601635432959,1739502654.2016554,14.529986143112183,-0.06961253894446134,1739502654.201657,14.529986143112183,-0.008668556722790014,1739502654.2016582,14.529986143112183,-0.22961280021238464,1739502654.20166,14.529986143112183,-0.05512193196405232,1739502654.201661,14.529986143112183,2.0804838600915843,1739502654.2016628,14.529986143112183,0.0,1739502654.201664,14.529986143112183,-0.07857994163976567,1739502654.2016652,14.529986143112183,0.03194055254680247,1739502654.2016668,14.529986143112183,2.15906380173135 +1739502654.2215836,14.549986124038696,29.030455416387014,1739502654.2215867,14.549986124038696,-0.020585760127834973,1739502654.221591,14.549986124038696,28.37450858383354,1739502654.221594,14.549986124038696,34.68601635432959,1739502654.2215953,14.549986124038696,-0.06961253894446134,1739502654.2215974,14.549986124038696,-0.008668556722790014,1739502654.2215989,14.549986124038696,-0.22961280021238464,1739502654.2216005,14.549986124038696,-0.05512193196405232,1739502654.221602,14.549986124038696,2.0804838600915843,1739502654.2216043,14.549986124038696,0.0,1739502654.2216058,14.549986124038696,-0.07857994163976567,1739502654.2216074,14.549986124038696,0.03194055254680247,1739502654.2216089,14.549986124038696,2.15906380173135 +1739502654.2425003,14.56998610496521,29.030455416387014,1739502654.242506,14.56998610496521,-0.020585760127834973,1739502654.2425113,14.56998610496521,28.37450858383354,1739502654.2425156,14.56998610496521,34.68601635432959,1739502654.2425177,14.56998610496521,-0.06961253894446134,1739502654.2425215,14.56998610496521,-0.008668556722790014,1739502654.2425241,14.56998610496521,-0.22961280021238464,1739502654.242527,14.56998610496521,-0.05512193196405232,1739502654.2425294,14.56998610496521,2.0804838600915843,1739502654.242532,14.56998610496521,0.0,1739502654.2425349,14.56998610496521,-0.07857994163976567,1739502654.2425375,14.56998610496521,0.03194055254680247,1739502654.2425404,14.56998610496521,2.15906380173135 +1739502654.262639,14.589986085891724,29.267400193838746,1739502654.2626452,14.589986085891724,-0.013086674884858596,1739502654.2626517,14.589986085891724,28.403667789630582,1739502654.262656,14.589986085891724,34.69795918104717,1739502654.2626595,14.589986085891724,-0.06955874242771548,1739502654.2626626,14.589986085891724,-0.010398567111768188,1739502654.2626655,14.589986085891724,-0.2261884009505365,1739502654.262668,14.589986085891724,-0.058889752703781814,1739502654.2626703,14.589986085891724,2.086191200122358,1739502654.2626731,14.589986085891724,0.0,1739502654.2626762,14.589986085891724,-0.057757435086314535,1739502654.2626793,14.589986085891724,0.031262265984093325,1739502654.2626822,14.589986085891724,2.1504556727729724 +1739502654.282396,14.609986066818237,29.267400193838746,1739502654.2824004,14.609986066818237,-0.013086674884858596,1739502654.2824056,14.609986066818237,28.403667789630582,1739502654.2824104,14.609986066818237,34.69795918104717,1739502654.2824128,14.609986066818237,-0.06955874242771548,1739502654.2824156,14.609986066818237,-0.010398567111768188,1739502654.2824183,14.609986066818237,-0.2261884009505365,1739502654.2824202,14.609986066818237,-0.058889752703781814,1739502654.2824223,14.609986066818237,2.086191200122358,1739502654.282425,14.609986066818237,0.0,1739502654.2824273,14.609986066818237,-0.0642644726506143,1739502654.2824302,14.609986066818237,0.031262265984093325,1739502654.2824323,14.609986066818237,2.1504556727729724 +1739502654.3033993,14.629986047744751,29.267400193838746,1739502654.303405,14.629986047744751,-0.013086674884858596,1739502654.3034122,14.629986047744751,28.403667789630582,1739502654.3034165,14.629986047744751,34.69795918104717,1739502654.3034189,14.629986047744751,-0.06955874242771548,1739502654.303422,14.629986047744751,-0.010398567111768188,1739502654.3034246,14.629986047744751,-0.2261884009505365,1739502654.3034277,14.629986047744751,-0.058889752703781814,1739502654.3034294,14.629986047744751,2.086191200122358,1739502654.3034322,14.629986047744751,0.0,1739502654.303435,14.629986047744751,-0.0642644726506143,1739502654.3034382,14.629986047744751,0.031262265984093325,1739502654.3034406,14.629986047744751,2.1504556727729724 +1739502654.3227842,14.649986028671265,29.267400193838746,1739502654.3227882,14.649986028671265,-0.013086674884858596,1739502654.3227935,14.649986028671265,28.403667789630582,1739502654.322798,14.649986028671265,34.69795918104717,1739502654.3228004,14.649986028671265,-0.06955874242771548,1739502654.3228035,14.649986028671265,-0.010398567111768188,1739502654.3228061,14.649986028671265,-0.2261884009505365,1739502654.3228097,14.649986028671265,-0.058889752703781814,1739502654.322812,14.649986028671265,2.086191200122358,1739502654.322815,14.649986028671265,0.0,1739502654.3228176,14.649986028671265,-0.0642644726506143,1739502654.3228204,14.649986028671265,0.031262265984093325,1739502654.3228228,14.649986028671265,2.1504556727729724 +1739502654.343174,14.669986009597778,29.267400193838746,1739502654.3431776,14.669986009597778,-0.013086674884858596,1739502654.3431818,14.669986009597778,28.403667789630582,1739502654.3431857,14.669986009597778,34.69795918104717,1739502654.343187,14.669986009597778,-0.06955874242771548,1739502654.3431895,14.669986009597778,-0.010398567111768188,1739502654.3431914,14.669986009597778,-0.2261884009505365,1739502654.3431926,14.669986009597778,-0.058889752703781814,1739502654.343194,14.669986009597778,2.086191200122358,1739502654.3431962,14.669986009597778,0.0,1739502654.343198,14.669986009597778,-0.0642644726506143,1739502654.3431995,14.669986009597778,0.031262265984093325,1739502654.343201,14.669986009597778,2.1504556727729724 +1739502654.363482,14.689985990524292,29.267400193838746,1739502654.363487,14.689985990524292,-0.013086674884858596,1739502654.363492,14.689985990524292,28.403667789630582,1739502654.3634963,14.689985990524292,34.69795918104717,1739502654.3634984,14.689985990524292,-0.06955874242771548,1739502654.3635008,14.689985990524292,-0.010398567111768188,1739502654.3635027,14.689985990524292,-0.2261884009505365,1739502654.3635046,14.689985990524292,-0.058889752703781814,1739502654.3635063,14.689985990524292,2.086191200122358,1739502654.363509,14.689985990524292,0.0,1739502654.3635113,14.689985990524292,-0.0642644726506143,1739502654.3635137,14.689985990524292,0.031262265984093325,1739502654.3635159,14.689985990524292,2.1504556727729724 +1739502654.3831673,14.709985971450806,29.50349744868285,1739502654.3831933,14.709985971450806,-0.0057906523041566516,1739502654.3832,14.709985971450806,28.78491784773263,1739502654.3832054,14.709985971450806,35.0653908937789,1739502654.3832085,14.709985971450806,-0.0680280455311055,1739502654.3832123,14.709985971450806,-0.011189498027027445,1739502654.383216,14.709985971450806,-0.2314204496019397,1739502654.38322,14.709985971450806,-0.057439436913127445,1739502654.3832238,14.709985971450806,2.077477406157633,1739502654.3832288,14.709985971450806,0.0,1739502654.3832324,14.709985971450806,-0.06689205950833868,1739502654.383236,14.709985971450806,0.030428123429082722,1739502654.3832395,14.709985971450806,2.1435483442345635 +1739502654.4020534,14.72998595237732,29.50349744868285,1739502654.4020572,14.72998595237732,-0.0057906523041566516,1739502654.4020607,14.72998595237732,28.78491784773263,1739502654.4020636,14.72998595237732,35.0653908937789,1739502654.402065,14.72998595237732,-0.0680280455311055,1739502654.4020667,14.72998595237732,-0.011189498027027445,1739502654.4020684,14.72998595237732,-0.2314204496019397,1739502654.40207,14.72998595237732,-0.057439436913127445,1739502654.4020712,14.72998595237732,2.077477406157633,1739502654.4020734,14.72998595237732,0.0,1739502654.402096,14.72998595237732,-0.06607093807693065,1739502654.4020975,14.72998595237732,0.030428123429082722,1739502654.4020991,14.72998595237732,2.1435483442345635 +1739502654.4221191,14.749985933303833,29.50349744868285,1739502654.4221256,14.749985933303833,-0.0057906523041566516,1739502654.4221318,14.749985933303833,28.78491784773263,1739502654.4221375,14.749985933303833,35.0653908937789,1739502654.4221406,14.749985933303833,-0.0680280455311055,1739502654.4221444,14.749985933303833,-0.011189498027027445,1739502654.422148,14.749985933303833,-0.2314204496019397,1739502654.422152,14.749985933303833,-0.057439436913127445,1739502654.4221554,14.749985933303833,2.077477406157633,1739502654.422159,14.749985933303833,0.0,1739502654.4221807,14.749985933303833,-0.06607093807693065,1739502654.4221842,14.749985933303833,0.030428123429082722,1739502654.4221876,14.749985933303833,2.1435483442345635 +1739502654.4420307,14.769985914230347,29.50349744868285,1739502654.4420342,14.769985914230347,-0.0057906523041566516,1739502654.44204,14.769985914230347,28.78491784773263,1739502654.442044,14.769985914230347,35.0653908937789,1739502654.4420457,14.769985914230347,-0.0680280455311055,1739502654.4420483,14.769985914230347,-0.011189498027027445,1739502654.4420502,14.769985914230347,-0.2314204496019397,1739502654.4420526,14.769985914230347,-0.057439436913127445,1739502654.442055,14.769985914230347,2.077477406157633,1739502654.4420571,14.769985914230347,0.0,1739502654.4420593,14.769985914230347,-0.06607093807693065,1739502654.4420617,14.769985914230347,0.030428123429082722,1739502654.4420636,14.769985914230347,2.1435483442345635 +1739502654.4625726,14.78998589515686,29.50349744868285,1739502654.4625766,14.78998589515686,-0.0057906523041566516,1739502654.462582,14.78998589515686,28.78491784773263,1739502654.4625874,14.78998589515686,35.0653908937789,1739502654.4625905,14.78998589515686,-0.0680280455311055,1739502654.4625943,14.78998589515686,-0.011189498027027445,1739502654.4625976,14.78998589515686,-0.2314204496019397,1739502654.4626012,14.78998589515686,-0.057439436913127445,1739502654.4626045,14.78998589515686,2.077477406157633,1739502654.462608,14.78998589515686,0.0,1739502654.4626114,14.78998589515686,-0.06607093807693065,1739502654.4626148,14.78998589515686,0.030428123429082722,1739502654.462618,14.78998589515686,2.1435483442345635 +1739502654.489136,14.809985876083374,29.738820215381054,1739502654.489149,14.809985876083374,0.001280355096076491,1739502654.4891644,14.809985876083374,28.796455734308243,1739502654.4891803,14.809985876083374,35.062476415575624,1739502654.4891891,14.809985876083374,-0.06804261792212189,1739502654.489199,14.809985876083374,-0.013020948869882244,1739502654.489207,14.809985876083374,-0.22669934039865414,1739502654.4892147,14.809985876083374,-0.06141255544464366,1739502654.4892218,14.809985876083374,2.0853386404724046,1739502654.48923,14.809985876083374,0.0,1739502654.4892373,14.809985876083374,-0.044125571653652385,1739502654.4892447,14.809985876083374,0.02957171053815513,1739502654.489255,14.809985876083374,2.1363221436297417 +1739502654.5110624,14.829985857009888,29.738820215381054,1739502654.511071,14.829985857009888,0.001280355096076491,1739502654.511082,14.829985857009888,28.796455734308243,1739502654.5110922,14.829985857009888,35.062476415575624,1739502654.5110977,14.829985857009888,-0.06804261792212189,1739502654.5111036,14.829985857009888,-0.013020948869882244,1739502654.5111089,14.829985857009888,-0.22669934039865414,1739502654.511114,14.829985857009888,-0.06141255544464366,1739502654.5111187,14.829985857009888,2.0853386404724046,1739502654.5111244,14.829985857009888,0.0,1739502654.5111294,14.829985857009888,-0.05098350315733713,1739502654.5111346,14.829985857009888,0.02957171053815513,1739502654.5111403,14.829985857009888,2.1363221436297417 +1739502654.5307837,14.849985837936401,29.738820215381054,1739502654.5307937,14.849985837936401,0.001280355096076491,1739502654.5308046,14.849985837936401,28.796455734308243,1739502654.530815,14.849985837936401,35.062476415575624,1739502654.5308201,14.849985837936401,-0.06804261792212189,1739502654.5308263,14.849985837936401,-0.013020948869882244,1739502654.5308316,14.849985837936401,-0.22669934039865414,1739502654.5308366,14.849985837936401,-0.06141255544464366,1739502654.5308414,14.849985837936401,2.0853386404724046,1739502654.5308473,14.849985837936401,0.0,1739502654.5308523,14.849985837936401,-0.05098350315733713,1739502654.5308576,14.849985837936401,0.02957171053815513,1739502654.5308628,14.849985837936401,2.1363221436297417 +1739502654.5583127,14.869985818862915,29.738820215381054,1739502654.5583222,14.869985818862915,0.001280355096076491,1739502654.5583348,14.869985818862915,28.796455734308243,1739502654.558348,14.869985818862915,35.062476415575624,1739502654.5583558,14.869985818862915,-0.06804261792212189,1739502654.5583656,14.869985818862915,-0.013020948869882244,1739502654.5583744,14.869985818862915,-0.22669934039865414,1739502654.5583835,14.869985818862915,-0.06141255544464366,1739502654.558392,14.869985818862915,2.0853386404724046,1739502654.5584013,14.869985818862915,0.0,1739502654.5584102,14.869985818862915,-0.05098350315733713,1739502654.5584192,14.869985818862915,0.02957171053815513,1739502654.558428,14.869985818862915,2.1363221436297417 +1739502654.5747223,14.899985790252686,29.738820215381054,1739502654.574729,14.899985790252686,0.001280355096076491,1739502654.5747366,14.899985790252686,28.796455734308243,1739502654.5747442,14.899985790252686,35.062476415575624,1739502654.5747476,14.899985790252686,-0.06804261792212189,1739502654.5747523,14.899985790252686,-0.013020948869882244,1739502654.5747561,14.899985790252686,-0.22669934039865414,1739502654.5747595,14.899985790252686,-0.06141255544464366,1739502654.574763,14.899985790252686,2.0853386404724046,1739502654.5747669,14.899985790252686,0.0,1739502654.5747702,14.899985790252686,-0.05098350315733713,1739502654.574774,14.899985790252686,0.02957171053815513,1739502654.5747776,14.899985790252686,2.1363221436297417 +1739502654.5942626,14.9199857711792,29.97344925528266,1739502654.5942686,14.9199857711792,0.00812224933692729,1739502654.594276,14.9199857711792,29.66160922492848,1739502654.5942829,14.9199857711792,35.91672585493815,1739502654.594286,14.9199857711792,-0.06488169447398015,1739502654.5942905,14.9199857711792,-0.012282832749030439,1739502654.5942938,14.9199857711792,-0.24317179177571716,1739502654.5942972,14.9199857711792,-0.05285816254363884,1739502654.5943005,14.9199857711792,2.0580384047822022,1739502654.5943043,14.9199857711792,0.0,1739502654.5943077,14.9199857711792,-0.082771040596157,1739502654.5943112,14.9199857711792,0.028640945272488866,1739502654.5943148,14.9199857711792,2.1308758334157445 +1739502654.6135578,14.939985752105713,29.97344925528266,1739502654.6135614,14.939985752105713,0.00812224933692729,1739502654.613566,14.939985752105713,29.66160922492848,1739502654.6135705,14.939985752105713,35.91672585493815,1739502654.6135726,14.939985752105713,-0.06488169447398015,1739502654.6135752,14.939985752105713,-0.012282832749030439,1739502654.6135774,14.939985752105713,-0.24317179177571716,1739502654.6135795,14.939985752105713,-0.05285816254363884,1739502654.6135817,14.939985752105713,2.0580384047822022,1739502654.613584,14.939985752105713,0.0,1739502654.6135862,14.939985752105713,-0.07283742863354226,1739502654.6135886,14.939985752105713,0.028640945272488866,1739502654.613591,14.939985752105713,2.1308758334157445 +1739502654.6324208,14.959985733032227,29.97344925528266,1739502654.6324239,14.959985733032227,0.00812224933692729,1739502654.6324282,14.959985733032227,29.66160922492848,1739502654.632431,14.959985733032227,35.91672585493815,1739502654.6324325,14.959985733032227,-0.06488169447398015,1739502654.6324341,14.959985733032227,-0.012282832749030439,1739502654.6324358,14.959985733032227,-0.24317179177571716,1739502654.6324372,14.959985733032227,-0.05285816254363884,1739502654.6324384,14.959985733032227,2.0580384047822022,1739502654.6324406,14.959985733032227,0.0,1739502654.632442,14.959985733032227,-0.07283742863354226,1739502654.6324437,14.959985733032227,0.028640945272488866,1739502654.632445,14.959985733032227,2.1308758334157445 +1739502654.6523669,14.97998571395874,29.97344925528266,1739502654.6523695,14.97998571395874,0.00812224933692729,1739502654.6523728,14.97998571395874,29.66160922492848,1739502654.6523752,14.97998571395874,35.91672585493815,1739502654.652377,14.97998571395874,-0.06488169447398015,1739502654.6523786,14.97998571395874,-0.012282832749030439,1739502654.6523802,14.97998571395874,-0.24317179177571716,1739502654.6523814,14.97998571395874,-0.05285816254363884,1739502654.6523826,14.97998571395874,2.0580384047822022,1739502654.6523843,14.97998571395874,0.0,1739502654.6523855,14.97998571395874,-0.07283742863354226,1739502654.6523871,14.97998571395874,0.028640945272488866,1739502654.6523883,14.97998571395874,2.1308758334157445 +1739502654.6722476,14.999985694885254,29.97344925528266,1739502654.6722498,14.999985694885254,0.00812224933692729,1739502654.6722524,14.999985694885254,29.66160922492848,1739502654.672255,14.999985694885254,35.91672585493815,1739502654.6722562,14.999985694885254,-0.06488169447398015,1739502654.672258,14.999985694885254,-0.012282832749030439,1739502654.672259,14.999985694885254,-0.24317179177571716,1739502654.6722603,14.999985694885254,-0.05285816254363884,1739502654.6722617,14.999985694885254,2.0580384047822022,1739502654.6722631,14.999985694885254,0.0,1739502654.6722643,14.999985694885254,-0.07283742863354226,1739502654.672266,14.999985694885254,0.028640945272488866,1739502654.6722672,14.999985694885254,2.1308758334157445 +1739502654.6924746,15.019985675811768,29.97344925528266,1739502654.6924777,15.019985675811768,0.00812224933692729,1739502654.6924818,15.019985675811768,29.66160922492848,1739502654.6924846,15.019985675811768,35.91672585493815,1739502654.6924858,15.019985675811768,-0.06488169447398015,1739502654.6924877,15.019985675811768,-0.012282832749030439,1739502654.6924891,15.019985675811768,-0.24317179177571716,1739502654.6924908,15.019985675811768,-0.05285816254363884,1739502654.6924922,15.019985675811768,2.0580384047822022,1739502654.6924944,15.019985675811768,0.0,1739502654.6924958,15.019985675811768,-0.07283742863354226,1739502654.6924975,15.019985675811768,0.028640945272488866,1739502654.692499,15.019985675811768,2.1308758334157445 +1739502654.712411,15.039985656738281,30.207334167869917,1739502654.712413,15.039985656738281,0.014723013834773369,1739502654.712416,15.039985656738281,29.68944813029086,1739502654.7124188,15.039985656738281,35.928220489009085,1739502654.71242,15.039985656738281,-0.06482669622483693,1739502654.7124217,15.039985656738281,-0.013904241254743465,1739502654.712423,15.039985656738281,-0.2379831702543439,1739502654.712425,15.039985656738281,-0.0558273135313432,1739502654.712426,15.039985656738281,2.066598865173549,1739502654.7124279,15.039985656738281,0.0,1739502654.712429,15.039985656738281,-0.04849919556189867,1739502654.7124305,15.039985656738281,0.027702744769348735,1739502654.712432,15.039985656738281,2.122703763557024 +1739502654.7322886,15.059985637664795,30.207334167869917,1739502654.7322907,15.059985637664795,0.014723013834773369,1739502654.7322934,15.059985637664795,29.68944813029086,1739502654.7322962,15.059985637664795,35.928220489009085,1739502654.7322974,15.059985637664795,-0.06482669622483693,1739502654.7322998,15.059985637664795,-0.013904241254743465,1739502654.732301,15.059985637664795,-0.2379831702543439,1739502654.7323027,15.059985637664795,-0.0558273135313432,1739502654.7323039,15.059985637664795,2.066598865173549,1739502654.732306,15.059985637664795,0.0,1739502654.7323072,15.059985637664795,-0.056104898383474655,1739502654.7323086,15.059985637664795,0.027702744769348735,1739502654.73231,15.059985637664795,2.122703763557024 +1739502654.752314,15.079985618591309,30.207334167869917,1739502654.7523167,15.079985618591309,0.014723013834773369,1739502654.7523196,15.079985618591309,29.68944813029086,1739502654.752323,15.079985618591309,35.928220489009085,1739502654.7523243,15.079985618591309,-0.06482669622483693,1739502654.7523263,15.079985618591309,-0.013904241254743465,1739502654.7523277,15.079985618591309,-0.2379831702543439,1739502654.752329,15.079985618591309,-0.0558273135313432,1739502654.7523308,15.079985618591309,2.066598865173549,1739502654.7523327,15.079985618591309,0.0,1739502654.752334,15.079985618591309,-0.056104898383474655,1739502654.7523355,15.079985618591309,0.027702744769348735,1739502654.7523372,15.079985618591309,2.122703763557024 +1739502654.7723825,15.099985599517822,30.207334167869917,1739502654.7723856,15.099985599517822,0.014723013834773369,1739502654.7723885,15.099985599517822,29.68944813029086,1739502654.7723913,15.099985599517822,35.928220489009085,1739502654.7723927,15.099985599517822,-0.06482669622483693,1739502654.7723947,15.099985599517822,-0.013904241254743465,1739502654.772396,15.099985599517822,-0.2379831702543439,1739502654.7723975,15.099985599517822,-0.0558273135313432,1739502654.7723992,15.099985599517822,2.066598865173549,1739502654.7724006,15.099985599517822,0.0,1739502654.7724018,15.099985599517822,-0.056104898383474655,1739502654.7724037,15.099985599517822,0.027702744769348735,1739502654.7724051,15.099985599517822,2.122703763557024 +1739502654.7923234,15.119985580444336,30.207334167869917,1739502654.7923253,15.119985580444336,0.014723013834773369,1739502654.7923281,15.119985580444336,29.68944813029086,1739502654.7923307,15.119985580444336,35.928220489009085,1739502654.7923322,15.119985580444336,-0.06482669622483693,1739502654.792334,15.119985580444336,-0.013904241254743465,1739502654.7923355,15.119985580444336,-0.2379831702543439,1739502654.792337,15.119985580444336,-0.0558273135313432,1739502654.7923381,15.119985580444336,2.066598865173549,1739502654.7923398,15.119985580444336,0.0,1739502654.792341,15.119985580444336,-0.056104898383474655,1739502654.7923424,15.119985580444336,0.027702744769348735,1739502654.7923443,15.119985580444336,2.122703763557024 +1739502654.8123305,15.13998556137085,30.44043408423429,1739502654.8123333,15.13998556137085,0.021082743776418944,1739502654.8123364,15.13998556137085,29.717193380068164,1739502654.8123393,15.13998556137085,35.94366462166115,1739502654.8123405,15.13998556137085,-0.06475280085329596,1739502654.8123422,15.13998556137085,-0.015596036635458712,1739502654.8123438,15.13998556137085,-0.2330786755207802,1739502654.8123453,15.13998556137085,-0.05908354605973651,1739502654.8123467,15.13998556137085,2.0747232918344722,1739502654.8123484,15.13998556137085,0.0,1739502654.81235,15.13998556137085,-0.03534140589371316,1739502654.8123515,15.13998556137085,0.026764544266208605,1739502654.8123531,15.13998556137085,2.1165532933854907 +1739502654.8322425,15.159985542297363,30.44043408423429,1739502654.8322456,15.159985542297363,0.021082743776418944,1739502654.8322492,15.159985542297363,29.717193380068164,1739502654.8322518,15.159985542297363,35.94366462166115,1739502654.8322532,15.159985542297363,-0.06475280085329596,1739502654.832255,15.159985542297363,-0.015596036635458712,1739502654.8322566,15.159985542297363,-0.2330786755207802,1739502654.832258,15.159985542297363,-0.05908354605973651,1739502654.8322594,15.159985542297363,2.0747232918344722,1739502654.832261,15.159985542297363,0.0,1739502654.8322628,15.159985542297363,-0.04183000155101846,1739502654.8322642,15.159985542297363,0.026764544266208605,1739502654.8322656,15.159985542297363,2.1165532933854907 +1739502654.8521667,15.179985523223877,30.44043408423429,1739502654.8521693,15.179985523223877,0.021082743776418944,1739502654.8521721,15.179985523223877,29.717193380068164,1739502654.8521748,15.179985523223877,35.94366462166115,1739502654.852176,15.179985523223877,-0.06475280085329596,1739502654.8521776,15.179985523223877,-0.015596036635458712,1739502654.852179,15.179985523223877,-0.2330786755207802,1739502654.8521802,15.179985523223877,-0.05908354605973651,1739502654.8521814,15.179985523223877,2.0747232918344722,1739502654.852183,15.179985523223877,0.0,1739502654.8521843,15.179985523223877,-0.04183000155101846,1739502654.8521855,15.179985523223877,0.026764544266208605,1739502654.8521872,15.179985523223877,2.1165532933854907 +1739502654.8722394,15.19998550415039,30.44043408423429,1739502654.8722427,15.19998550415039,0.021082743776418944,1739502654.8722458,15.19998550415039,29.717193380068164,1739502654.8722486,15.19998550415039,35.94366462166115,1739502654.87225,15.19998550415039,-0.06475280085329596,1739502654.8722525,15.19998550415039,-0.015596036635458712,1739502654.872254,15.19998550415039,-0.2330786755207802,1739502654.8722556,15.19998550415039,-0.05908354605973651,1739502654.8722568,15.19998550415039,2.0747232918344722,1739502654.8722587,15.19998550415039,0.0,1739502654.8722599,15.19998550415039,-0.04183000155101846,1739502654.8722613,15.19998550415039,0.026764544266208605,1739502654.8722627,15.19998550415039,2.1165532933854907 +1739502654.8922398,15.219985485076904,30.44043408423429,1739502654.8922424,15.219985485076904,0.021082743776418944,1739502654.8922453,15.219985485076904,29.717193380068164,1739502654.8922482,15.219985485076904,35.94366462166115,1739502654.8922493,15.219985485076904,-0.06475280085329596,1739502654.8922508,15.219985485076904,-0.015596036635458712,1739502654.8922522,15.219985485076904,-0.2330786755207802,1739502654.8922534,15.219985485076904,-0.05908354605973651,1739502654.8922548,15.219985485076904,2.0747232918344722,1739502654.8922563,15.219985485076904,0.0,1739502654.8922575,15.219985485076904,-0.04183000155101846,1739502654.8922591,15.219985485076904,0.026764544266208605,1739502654.8922603,15.219985485076904,2.1165532933854907 +1739502654.9131734,15.239985466003418,30.44043408423429,1739502654.913176,15.239985466003418,0.021082743776418944,1739502654.9131794,15.239985466003418,29.717193380068164,1739502654.9131823,15.239985466003418,35.94366462166115,1739502654.9131837,15.239985466003418,-0.06475280085329596,1739502654.9131854,15.239985466003418,-0.015596036635458712,1739502654.9131868,15.239985466003418,-0.2330786755207802,1739502654.913188,15.239985466003418,-0.05908354605973651,1739502654.9131894,15.239985466003418,2.0747232918344722,1739502654.9131908,15.239985466003418,0.0,1739502654.9131923,15.239985466003418,-0.04183000155101846,1739502654.9131937,15.239985466003418,0.026764544266208605,1739502654.9131954,15.239985466003418,2.1165532933854907 +1739502654.9323938,15.259985446929932,30.672957114563587,1739502654.932397,15.259985446929932,0.02720841099401028,1739502654.9324002,15.259985446929932,29.95543511454539,1739502654.9324028,15.259985446929932,36.17300158565084,1739502654.9324043,15.259985446929932,-0.064,1739502654.932406,15.259985446929932,-0.01658169347385257,1739502654.9324076,15.259985446929932,-0.23320824364179646,1739502654.9324093,15.259985446929932,-0.05918299722000368,1739502654.9324107,15.259985446929932,2.0745082485809236,1739502654.9324124,15.259985446929932,0.0,1739502654.9324136,15.259985446929932,-0.03566790296419207,1739502654.9324152,15.259985446929932,0.025826343763068475,1739502654.932417,15.259985446929932,2.112101808616058 +1739502654.952161,15.279985427856445,30.672957114563587,1739502654.9521646,15.279985427856445,0.02720841099401028,1739502654.952168,15.279985427856445,29.95543511454539,1739502654.952171,15.279985427856445,36.17300158565084,1739502654.9521725,15.279985427856445,-0.064,1739502654.9521744,15.279985427856445,-0.01658169347385257,1739502654.9521759,15.279985427856445,-0.23320824364179646,1739502654.9521775,15.279985427856445,-0.05918299722000368,1739502654.9521787,15.279985427856445,2.0745082485809236,1739502654.9521804,15.279985427856445,0.0,1739502654.9521818,15.279985427856445,-0.03759356003513448,1739502654.9521832,15.279985427856445,0.025826343763068475,1739502654.952185,15.279985427856445,2.112101808616058 +1739502654.9722757,15.299985408782959,30.672957114563587,1739502654.9722786,15.299985408782959,0.02720841099401028,1739502654.972282,15.299985408782959,29.95543511454539,1739502654.9722846,15.299985408782959,36.17300158565084,1739502654.9722862,15.299985408782959,-0.064,1739502654.9722884,15.299985408782959,-0.01658169347385257,1739502654.9722896,15.299985408782959,-0.23320824364179646,1739502654.972291,15.299985408782959,-0.05918299722000368,1739502654.9722924,15.299985408782959,2.0745082485809236,1739502654.972294,15.299985408782959,0.0,1739502654.972296,15.299985408782959,-0.03759356003513448,1739502654.9722974,15.299985408782959,0.025826343763068475,1739502654.972299,15.299985408782959,2.112101808616058 +1739502654.9922953,15.319985389709473,30.672957114563587,1739502654.9922974,15.319985389709473,0.02720841099401028,1739502654.9923003,15.319985389709473,29.95543511454539,1739502654.9923031,15.319985389709473,36.17300158565084,1739502654.9923043,15.319985389709473,-0.064,1739502654.9923062,15.319985389709473,-0.01658169347385257,1739502654.9923077,15.319985389709473,-0.23320824364179646,1739502654.992309,15.319985389709473,-0.05918299722000368,1739502654.9923103,15.319985389709473,2.0745082485809236,1739502654.9923117,15.319985389709473,0.0,1739502654.9923131,15.319985389709473,-0.03759356003513448,1739502654.9923143,15.319985389709473,0.025826343763068475,1739502654.992316,15.319985389709473,2.112101808616058 +1739502655.012218,15.339985370635986,30.672957114563587,1739502655.0122209,15.339985370635986,0.02720841099401028,1739502655.0122244,15.339985370635986,29.95543511454539,1739502655.0122273,15.339985370635986,36.17300158565084,1739502655.012229,15.339985370635986,-0.064,1739502655.0122306,15.339985370635986,-0.01658169347385257,1739502655.0122323,15.339985370635986,-0.23320824364179646,1739502655.0122335,15.339985370635986,-0.05918299722000368,1739502655.0122347,15.339985370635986,2.0745082485809236,1739502655.0122366,15.339985370635986,0.0,1739502655.0122378,15.339985370635986,-0.03759356003513448,1739502655.0122395,15.339985370635986,0.025826343763068475,1739502655.0122406,15.339985370635986,2.112101808616058 +1739502655.03218,15.3599853515625,30.905006689060208,1739502655.0321822,15.3599853515625,0.03310374722712428,1739502655.032185,15.3599853515625,30.296695447289068,1739502655.0321877,15.3599853515625,36.50602621915368,1739502655.0321891,15.3599853515625,-0.063,1739502655.0321908,15.3599853515625,-0.01715657608534001,1739502655.0321922,15.3599853515625,-0.2354585703217487,1739502655.0321934,15.3599853515625,-0.05761828190715506,1739502655.0321949,15.3599853515625,2.0707769512362026,1739502655.0321963,15.3599853515625,0.0,1739502655.0321977,15.3599853515625,-0.03703403608218735,1739502655.032199,15.3599853515625,0.024888143259928344,1739502655.0322003,15.3599853515625,2.1079858386683274 +1739502655.0522888,15.379985332489014,30.905006689060208,1739502655.0522916,15.379985332489014,0.03310374722712428,1739502655.0522954,15.379985332489014,30.296695447289068,1739502655.0522983,15.379985332489014,36.50602621915368,1739502655.0522997,15.379985332489014,-0.063,1739502655.0523014,15.379985332489014,-0.01715657608534001,1739502655.052303,15.379985332489014,-0.2354585703217487,1739502655.0523047,15.379985332489014,-0.05761828190715506,1739502655.052306,15.379985332489014,2.0707769512362026,1739502655.0523074,15.379985332489014,0.0,1739502655.052309,15.379985332489014,-0.037208887432124804,1739502655.0523102,15.379985332489014,0.024888143259928344,1739502655.052312,15.379985332489014,2.1079858386683274 +1739502655.0721447,15.399985313415527,30.905006689060208,1739502655.0721467,15.399985313415527,0.03310374722712428,1739502655.0721495,15.399985313415527,30.296695447289068,1739502655.0721524,15.399985313415527,36.50602621915368,1739502655.0721536,15.399985313415527,-0.063,1739502655.0721552,15.399985313415527,-0.01715657608534001,1739502655.0721567,15.399985313415527,-0.2354585703217487,1739502655.072158,15.399985313415527,-0.05761828190715506,1739502655.0721593,15.399985313415527,2.0707769512362026,1739502655.0721607,15.399985313415527,0.0,1739502655.0721624,15.399985313415527,-0.037208887432124804,1739502655.0721638,15.399985313415527,0.024888143259928344,1739502655.072165,15.399985313415527,2.1079858386683274 +1739502655.0923474,15.419985294342041,30.905006689060208,1739502655.0923502,15.419985294342041,0.03310374722712428,1739502655.0923536,15.419985294342041,30.296695447289068,1739502655.092357,15.419985294342041,36.50602621915368,1739502655.092358,15.419985294342041,-0.063,1739502655.09236,15.419985294342041,-0.01715657608534001,1739502655.0923615,15.419985294342041,-0.2354585703217487,1739502655.0923626,15.419985294342041,-0.05761828190715506,1739502655.092364,15.419985294342041,2.0707769512362026,1739502655.0923655,15.419985294342041,0.0,1739502655.0923672,15.419985294342041,-0.037208887432124804,1739502655.0923688,15.419985294342041,0.024888143259928344,1739502655.0923703,15.419985294342041,2.1079858386683274 +1739502655.1121662,15.439985275268555,30.905006689060208,1739502655.112168,15.439985275268555,0.03310374722712428,1739502655.112171,15.439985275268555,30.296695447289068,1739502655.1121738,15.439985275268555,36.50602621915368,1739502655.1121755,15.439985275268555,-0.063,1739502655.1121771,15.439985275268555,-0.01715657608534001,1739502655.112179,15.439985275268555,-0.2354585703217487,1739502655.1121802,15.439985275268555,-0.05761828190715506,1739502655.1121814,15.439985275268555,2.0707769512362026,1739502655.112183,15.439985275268555,0.0,1739502655.1121843,15.439985275268555,-0.037208887432124804,1739502655.112186,15.439985275268555,0.024888143259928344,1739502655.1121871,15.439985275268555,2.1079858386683274 +1739502655.1321394,15.459985256195068,30.905006689060208,1739502655.1321416,15.459985256195068,0.03310374722712428,1739502655.1321442,15.459985256195068,30.296695447289068,1739502655.1321468,15.459985256195068,36.50602621915368,1739502655.1321483,15.459985256195068,-0.063,1739502655.13215,15.459985256195068,-0.01715657608534001,1739502655.1321514,15.459985256195068,-0.2354585703217487,1739502655.1321526,15.459985256195068,-0.05761828190715506,1739502655.1321537,15.459985256195068,2.0707769512362026,1739502655.1321554,15.459985256195068,0.0,1739502655.1321566,15.459985256195068,-0.037208887432124804,1739502655.132158,15.459985256195068,0.024888143259928344,1739502655.1321595,15.459985256195068,2.1079858386683274 +1739502655.1524582,15.479985237121582,31.13661205810854,1739502655.1524615,15.479985237121582,0.03877037066310596,1739502655.1524653,15.479985237121582,30.324262152829252,1739502655.1524682,15.479985237121582,36.52545150864181,1739502655.1524699,15.479985237121582,-0.063,1739502655.1524715,15.479985237121582,-0.018883151948827292,1739502655.1524734,15.479985237121582,-0.2307912426880233,1739502655.152475,15.479985237121582,-0.061006388811240944,1739502655.1524763,15.479985237121582,2.078523399912115,1739502655.1524785,15.479985237121582,0.0,1739502655.1524796,15.479985237121582,-0.020020290743063475,1739502655.1524816,15.479985237121582,0.023949942756788214,1739502655.1524837,15.479985237121582,2.1039151306423007 +1739502655.1722443,15.499985218048096,31.13661205810854,1739502655.1722467,15.499985218048096,0.03877037066310596,1739502655.1722496,15.499985218048096,30.324262152829252,1739502655.1722524,15.499985218048096,36.52545150864181,1739502655.1722538,15.499985218048096,-0.063,1739502655.172256,15.499985218048096,-0.018883151948827292,1739502655.172258,15.499985218048096,-0.2307912426880233,1739502655.172259,15.499985218048096,-0.061006388811240944,1739502655.1722605,15.499985218048096,2.078523399912115,1739502655.1722624,15.499985218048096,0.0,1739502655.1722639,15.499985218048096,-0.025391730730185635,1739502655.1722655,15.499985218048096,0.023949942756788214,1739502655.172267,15.499985218048096,2.1039151306423007 +1739502655.1927004,15.51998519897461,31.13661205810854,1739502655.1927059,15.51998519897461,0.03877037066310596,1739502655.1927106,15.51998519897461,30.324262152829252,1739502655.1927137,15.51998519897461,36.52545150864181,1739502655.1927161,15.51998519897461,-0.063,1739502655.1927183,15.51998519897461,-0.018883151948827292,1739502655.1927204,15.51998519897461,-0.2307912426880233,1739502655.1927223,15.51998519897461,-0.061006388811240944,1739502655.1927242,15.51998519897461,2.078523399912115,1739502655.1927264,15.51998519897461,0.0,1739502655.192728,15.51998519897461,-0.025391730730185635,1739502655.1927302,15.51998519897461,0.023949942756788214,1739502655.192732,15.51998519897461,2.1039151306423007 +1739502655.2123978,15.539985179901123,31.13661205810854,1739502655.2124007,15.539985179901123,0.03877037066310596,1739502655.212404,15.539985179901123,30.324262152829252,1739502655.212407,15.539985179901123,36.52545150864181,1739502655.2124083,15.539985179901123,-0.063,1739502655.2124102,15.539985179901123,-0.018883151948827292,1739502655.2124119,15.539985179901123,-0.2307912426880233,1739502655.2124138,15.539985179901123,-0.061006388811240944,1739502655.2124152,15.539985179901123,2.078523399912115,1739502655.2124166,15.539985179901123,0.0,1739502655.2124183,15.539985179901123,-0.025391730730185635,1739502655.21242,15.539985179901123,0.023949942756788214,1739502655.212422,15.539985179901123,2.1039151306423007 +1739502655.2323914,15.559985160827637,31.13661205810854,1739502655.2323942,15.559985160827637,0.03877037066310596,1739502655.2323973,15.559985160827637,30.324262152829252,1739502655.2324002,15.559985160827637,36.52545150864181,1739502655.2324018,15.559985160827637,-0.063,1739502655.2324038,15.559985160827637,-0.018883151948827292,1739502655.2324052,15.559985160827637,-0.2307912426880233,1739502655.2324069,15.559985160827637,-0.061006388811240944,1739502655.232408,15.559985160827637,2.078523399912115,1739502655.2324102,15.559985160827637,0.0,1739502655.2324114,15.559985160827637,-0.025391730730185635,1739502655.2324128,15.559985160827637,0.023949942756788214,1739502655.2324145,15.559985160827637,2.1039151306423007 +1739502655.252472,15.57998514175415,31.367837159519063,1739502655.2524748,15.57998514175415,0.04421061830649986,1739502655.2524784,15.57998514175415,30.767125566987865,1739502655.2524817,15.57998514175415,36.96273542380738,1739502655.2524834,15.57998514175415,-0.06155010797179716,1739502655.2524853,15.57998514175415,-0.018900814093220804,1739502655.2524874,15.57998514175415,-0.2344697194187723,1739502655.2524889,15.57998514175415,-0.057498333382937875,1739502655.2524903,15.57998514175415,2.0724157510886974,1739502655.252492,15.57998514175415,0.0,1739502655.2524936,15.57998514175415,-0.03022169303438858,1739502655.252495,15.57998514175415,0.023011742253648083,1739502655.2524967,15.57998514175415,2.101128079913406 +1739502655.2723618,15.599985122680664,31.367837159519063,1739502655.2723646,15.599985122680664,0.04421061830649986,1739502655.272368,15.599985122680664,30.767125566987865,1739502655.272371,15.599985122680664,36.96273542380738,1739502655.2723725,15.599985122680664,-0.06155010797179716,1739502655.2723746,15.599985122680664,-0.018900814093220804,1739502655.272376,15.599985122680664,-0.2344697194187723,1739502655.2723775,15.599985122680664,-0.057498333382937875,1739502655.2723792,15.599985122680664,2.0724157510886974,1739502655.2723806,15.599985122680664,0.0,1739502655.2723823,15.599985122680664,-0.028712328824708866,1739502655.2723837,15.599985122680664,0.023011742253648083,1739502655.2723854,15.599985122680664,2.101128079913406 +1739502655.2923594,15.619985103607178,31.367837159519063,1739502655.2923641,15.619985103607178,0.04421061830649986,1739502655.2923675,15.619985103607178,30.767125566987865,1739502655.2923708,15.619985103607178,36.96273542380738,1739502655.2923722,15.619985103607178,-0.06155010797179716,1739502655.2923741,15.619985103607178,-0.018900814093220804,1739502655.2923756,15.619985103607178,-0.2344697194187723,1739502655.292377,15.619985103607178,-0.057498333382937875,1739502655.2923787,15.619985103607178,2.0724157510886974,1739502655.29238,15.619985103607178,0.0,1739502655.2923818,15.619985103607178,-0.028712328824708866,1739502655.2923834,15.619985103607178,0.023011742253648083,1739502655.292385,15.619985103607178,2.101128079913406 +1739502655.3123944,15.639985084533691,31.367837159519063,1739502655.3123972,15.639985084533691,0.04421061830649986,1739502655.3124006,15.639985084533691,30.767125566987865,1739502655.3124037,15.639985084533691,36.96273542380738,1739502655.3124053,15.639985084533691,-0.06155010797179716,1739502655.3124073,15.639985084533691,-0.018900814093220804,1739502655.312409,15.639985084533691,-0.2344697194187723,1739502655.3124104,15.639985084533691,-0.057498333382937875,1739502655.3124118,15.639985084533691,2.0724157510886974,1739502655.3124137,15.639985084533691,0.0,1739502655.312415,15.639985084533691,-0.028712328824708866,1739502655.3124166,15.639985084533691,0.023011742253648083,1739502655.3124177,15.639985084533691,2.101128079913406 +1739502655.3322687,15.659985065460205,31.367837159519063,1739502655.332272,15.659985065460205,0.04421061830649986,1739502655.3322752,15.659985065460205,30.767125566987865,1739502655.3322785,15.659985065460205,36.96273542380738,1739502655.3322802,15.659985065460205,-0.06155010797179716,1739502655.3322818,15.659985065460205,-0.018900814093220804,1739502655.3322835,15.659985065460205,-0.2344697194187723,1739502655.332285,15.659985065460205,-0.057498333382937875,1739502655.3322864,15.659985065460205,2.0724157510886974,1739502655.3322883,15.659985065460205,0.0,1739502655.3322895,15.659985065460205,-0.028712328824708866,1739502655.3322911,15.659985065460205,0.023011742253648083,1739502655.3322926,15.659985065460205,2.101128079913406 +1739502655.3523915,15.679985046386719,31.367837159519063,1739502655.3523946,15.679985046386719,0.04421061830649986,1739502655.3523984,15.679985046386719,30.767125566987865,1739502655.3524015,15.679985046386719,36.96273542380738,1739502655.352403,15.679985046386719,-0.06155010797179716,1739502655.352405,15.679985046386719,-0.018900814093220804,1739502655.3524067,15.679985046386719,-0.2344697194187723,1739502655.3524084,15.679985046386719,-0.057498333382937875,1739502655.3524098,15.679985046386719,2.0724157510886974,1739502655.3524117,15.679985046386719,0.0,1739502655.3524134,15.679985046386719,-0.028712328824708866,1739502655.352415,15.679985046386719,0.023011742253648083,1739502655.3524165,15.679985046386719,2.101128079913406 +1739502655.3724737,15.699985027313232,31.598741995766048,1739502655.3724766,15.699985027313232,0.04942658433025482,1739502655.37248,15.699985027313232,30.794146648794786,1739502655.372483,15.699985027313232,36.98340835472053,1739502655.3724844,15.699985027313232,-0.06139697515021831,1739502655.3724864,15.699985027313232,-0.02057841807090563,1739502655.3724883,15.699985027313232,-0.22964556745414724,1739502655.3724897,15.699985027313232,-0.06079366294550088,1739502655.3724911,15.699985027313232,2.080429323432292,1739502655.3724928,15.699985027313232,0.0,1739502655.3724942,15.699985027313232,-0.012439794207731218,1739502655.3724964,15.699985027313232,0.022073541750507953,1739502655.372498,15.699985027313232,2.0979542880419264 +1739502655.3925576,15.719985008239746,31.598741995766048,1739502655.3925612,15.719985008239746,0.04942658433025482,1739502655.392565,15.719985008239746,30.794146648794786,1739502655.3925683,15.719985008239746,36.98340835472053,1739502655.3925695,15.719985008239746,-0.06139697515021831,1739502655.3925717,15.719985008239746,-0.02057841807090563,1739502655.392573,15.719985008239746,-0.22964556745414724,1739502655.3925748,15.719985008239746,-0.06079366294550088,1739502655.3925762,15.719985008239746,2.080429323432292,1739502655.392578,15.719985008239746,0.0,1739502655.3925793,15.719985008239746,-0.017524964609634264,1739502655.3925812,15.719985008239746,0.022073541750507953,1739502655.3925827,15.719985008239746,2.0979542880419264 +1739502655.4123952,15.73998498916626,31.598741995766048,1739502655.412398,15.73998498916626,0.04942658433025482,1739502655.4124014,15.73998498916626,30.794146648794786,1739502655.4124045,15.73998498916626,36.98340835472053,1739502655.4124057,15.73998498916626,-0.06139697515021831,1739502655.4124076,15.73998498916626,-0.02057841807090563,1739502655.412409,15.73998498916626,-0.22964556745414724,1739502655.4124103,15.73998498916626,-0.06079366294550088,1739502655.4124117,15.73998498916626,2.080429323432292,1739502655.4124134,15.73998498916626,0.0,1739502655.412415,15.73998498916626,-0.017524964609634264,1739502655.4124165,15.73998498916626,0.022073541750507953,1739502655.4124181,15.73998498916626,2.0979542880419264 +1739502655.4326339,15.759984970092773,31.598741995766048,1739502655.4326406,15.759984970092773,0.04942658433025482,1739502655.4326448,15.759984970092773,30.794146648794786,1739502655.4326494,15.759984970092773,36.98340835472053,1739502655.432653,15.759984970092773,-0.06139697515021831,1739502655.4326558,15.759984970092773,-0.02057841807090563,1739502655.432659,15.759984970092773,-0.22964556745414724,1739502655.4326615,15.759984970092773,-0.06079366294550088,1739502655.4326646,15.759984970092773,2.080429323432292,1739502655.432668,15.759984970092773,0.0,1739502655.4326696,15.759984970092773,-0.017524964609634264,1739502655.432692,15.759984970092773,0.022073541750507953,1739502655.4326952,15.759984970092773,2.0979542880419264 +1739502655.4524255,15.779984951019287,31.598741995766048,1739502655.4524288,15.779984951019287,0.04942658433025482,1739502655.4524322,15.779984951019287,30.794146648794786,1739502655.4524353,15.779984951019287,36.98340835472053,1739502655.4524364,15.779984951019287,-0.06139697515021831,1739502655.4524386,15.779984951019287,-0.02057841807090563,1739502655.4524403,15.779984951019287,-0.22964556745414724,1739502655.452442,15.779984951019287,-0.06079366294550088,1739502655.4524431,15.779984951019287,2.080429323432292,1739502655.452445,15.779984951019287,0.0,1739502655.4524462,15.779984951019287,-0.017524964609634264,1739502655.4524477,15.779984951019287,0.022073541750507953,1739502655.4524493,15.779984951019287,2.0979542880419264 +1739502655.4727397,15.7999849319458,31.82936455629971,1739502655.4727435,15.7999849319458,0.054419686825117886,1739502655.472747,15.7999849319458,31.026844390349652,1739502655.472751,15.7999849319458,37.212252598167495,1739502655.4727526,15.7999849319458,-0.06094110496625001,1739502655.4727547,15.7999849319458,-0.021427741847285423,1739502655.4727566,15.7999849319458,-0.22909573244988157,1739502655.4727583,15.7999849319458,-0.06068604867486609,1739502655.47276,15.7999849319458,2.081344639019293,1739502655.4727619,15.7999849319458,0.0,1739502655.4727635,15.7999849319458,-0.013392208948666879,1739502655.4727654,15.7999849319458,0.021135341247367823,1739502655.4727669,15.7999849319458,2.096028334958777 +1739502655.4930515,15.819984912872314,31.82936455629971,1739502655.4930549,15.819984912872314,0.054419686825117886,1739502655.4930592,15.819984912872314,31.026844390349652,1739502655.493063,15.819984912872314,37.212252598167495,1739502655.4930646,15.819984912872314,-0.06094110496625001,1739502655.493067,15.819984912872314,-0.021427741847285423,1739502655.4930692,15.819984912872314,-0.22909573244988157,1739502655.4930708,15.819984912872314,-0.06068604867486609,1739502655.4930727,15.819984912872314,2.081344639019293,1739502655.4930747,15.819984912872314,0.0,1739502655.4930766,15.819984912872314,-0.014683695939484043,1739502655.4930785,15.819984912872314,0.021135341247367823,1739502655.4930804,15.819984912872314,2.096028334958777 +1739502655.522764,15.839984893798828,31.82936455629971,1739502655.522773,15.839984893798828,0.054419686825117886,1739502655.5227833,15.839984893798828,31.026844390349652,1739502655.5227935,15.839984893798828,37.212252598167495,1739502655.5227983,15.839984893798828,-0.06094110496625001,1739502655.5228047,15.839984893798828,-0.021427741847285423,1739502655.5228097,15.839984893798828,-0.22909573244988157,1739502655.5228148,15.839984893798828,-0.06068604867486609,1739502655.5228193,15.839984893798828,2.081344639019293,1739502655.5228252,15.839984893798828,0.0,1739502655.52283,15.839984893798828,-0.014683695939484043,1739502655.5228355,15.839984893798828,0.021135341247367823,1739502655.5228403,15.839984893798828,2.096028334958777 +1739502655.5358462,15.859984874725342,31.82936455629971,1739502655.535854,15.859984874725342,0.054419686825117886,1739502655.5358648,15.859984874725342,31.026844390349652,1739502655.5358753,15.859984874725342,37.212252598167495,1739502655.5358799,15.859984874725342,-0.06094110496625001,1739502655.535886,15.859984874725342,-0.021427741847285423,1739502655.5358913,15.859984874725342,-0.22909573244988157,1739502655.535896,15.859984874725342,-0.06068604867486609,1739502655.5359004,15.859984874725342,2.081344639019293,1739502655.535906,15.859984874725342,0.0,1739502655.5359108,15.859984874725342,-0.014683695939484043,1739502655.5359163,15.859984874725342,0.021135341247367823,1739502655.535921,15.859984874725342,2.096028334958777 +1739502655.561356,15.879984855651855,31.82936455629971,1739502655.561366,15.879984855651855,0.054419686825117886,1739502655.5613794,15.879984855651855,31.026844390349652,1739502655.5613904,15.879984855651855,37.212252598167495,1739502655.5613956,15.879984855651855,-0.06094110496625001,1739502655.561403,15.879984855651855,-0.021427741847285423,1739502655.561431,15.879984855651855,-0.22909573244988157,1739502655.5614386,15.879984855651855,-0.06068604867486609,1739502655.5614448,15.879984855651855,2.081344639019293,1739502655.5614507,15.879984855651855,0.0,1739502655.5614574,15.879984855651855,-0.014683695939484043,1739502655.561462,15.879984855651855,0.021135341247367823,1739502655.5614698,15.879984855651855,2.096028334958777 +1739502655.5810828,15.89998483657837,31.82936455629971,1739502655.5810883,15.89998483657837,0.054419686825117886,1739502655.5810945,15.89998483657837,31.026844390349652,1739502655.5810997,15.89998483657837,37.212252598167495,1739502655.5811026,15.89998483657837,-0.06094110496625001,1739502655.581106,15.89998483657837,-0.021427741847285423,1739502655.5811088,15.89998483657837,-0.22909573244988157,1739502655.581112,15.89998483657837,-0.06068604867486609,1739502655.5811143,15.89998483657837,2.081344639019293,1739502655.5811174,15.89998483657837,0.0,1739502655.58112,15.89998483657837,-0.014683695939484043,1739502655.5811229,15.89998483657837,0.021135341247367823,1739502655.5811257,15.89998483657837,2.096028334958777 +1739502655.6016822,15.919984817504883,32.059800149762985,1739502655.6016865,15.919984817504883,0.05919244723601924,1739502655.6016922,15.919984817504883,31.172579395841357,1739502655.6016972,15.919984817504883,37.35482198811375,1739502655.6017,15.919984817504883,-0.06035197525572831,1739502655.6017032,15.919984817504883,-0.02257292252147225,1739502655.601706,15.919984817504883,-0.2264570713661043,1739502655.6017087,15.919984817504883,-0.06199097523670717,1739502655.6017108,15.919984817504883,2.0857428500220947,1739502655.601714,15.919984817504883,0.0,1739502655.6017168,15.919984817504883,-0.005984914913514595,1739502655.6017194,15.919984817504883,0.020197140744227692,1739502655.601722,15.919984817504883,2.0944461357885276 +1739502655.6187727,15.939984798431396,32.059800149762985,1739502655.6187758,15.939984798431396,0.05919244723601924,1739502655.6187797,15.939984798431396,31.172579395841357,1739502655.6187832,15.939984798431396,37.35482198811375,1739502655.6187851,15.939984798431396,-0.06035197525572831,1739502655.618787,15.939984798431396,-0.02257292252147225,1739502655.618789,15.939984798431396,-0.2264570713661043,1739502655.6187906,15.939984798431396,-0.06199097523670717,1739502655.6187925,15.939984798431396,2.0857428500220947,1739502655.6187944,15.939984798431396,0.0,1739502655.6187963,15.939984798431396,-0.008703285766432867,1739502655.618798,15.939984798431396,0.020197140744227692,1739502655.6188,15.939984798431396,2.0944461357885276 +1739502655.6375632,15.95998477935791,32.059800149762985,1739502655.6375659,15.95998477935791,0.05919244723601924,1739502655.6375692,15.95998477935791,31.172579395841357,1739502655.6375723,15.95998477935791,37.35482198811375,1739502655.637574,15.95998477935791,-0.06035197525572831,1739502655.6375759,15.95998477935791,-0.02257292252147225,1739502655.6375775,15.95998477935791,-0.2264570713661043,1739502655.637579,15.95998477935791,-0.06199097523670717,1739502655.6375804,15.95998477935791,2.0857428500220947,1739502655.6375823,15.95998477935791,0.0,1739502655.6375837,15.95998477935791,-0.008703285766432867,1739502655.6375854,15.95998477935791,0.020197140744227692,1739502655.6375868,15.95998477935791,2.0944461357885276 +1739502655.6578631,15.979984760284424,32.059800149762985,1739502655.6578658,15.979984760284424,0.05919244723601924,1739502655.6578686,15.979984760284424,31.172579395841357,1739502655.6578712,15.979984760284424,37.35482198811375,1739502655.6578727,15.979984760284424,-0.06035197525572831,1739502655.6578743,15.979984760284424,-0.02257292252147225,1739502655.6578758,15.979984760284424,-0.2264570713661043,1739502655.657877,15.979984760284424,-0.06199097523670717,1739502655.6578782,15.979984760284424,2.0857428500220947,1739502655.6578798,15.979984760284424,0.0,1739502655.6578813,15.979984760284424,-0.008703285766432867,1739502655.6578827,15.979984760284424,0.020197140744227692,1739502655.6578841,15.979984760284424,2.0944461357885276 +1739502655.6772997,15.999984741210938,32.059800149762985,1739502655.6773016,15.999984741210938,0.05919244723601924,1739502655.6773045,15.999984741210938,31.172579395841357,1739502655.6773071,15.999984741210938,37.35482198811375,1739502655.677308,15.999984741210938,-0.06035197525572831,1739502655.6773098,15.999984741210938,-0.02257292252147225,1739502655.677311,15.999984741210938,-0.2264570713661043,1739502655.6773124,15.999984741210938,-0.06199097523670717,1739502655.6773133,15.999984741210938,2.0857428500220947,1739502655.6773148,15.999984741210938,0.0,1739502655.677316,15.999984741210938,-0.008703285766432867,1739502655.6773171,15.999984741210938,0.020197140744227692,1739502655.6773183,15.999984741210938,2.0944461357885276 +1739502655.6975687,16.01998472213745,32.290089571891365,1739502655.6975713,16.01998472213745,0.06374166713262852,1739502655.6975741,16.01998472213745,31.564913917569047,1739502655.6975768,16.01998472213745,37.74512271789703,1739502655.697578,16.01998472213745,-0.059,1739502655.6975799,16.01998472213745,-0.022496831151484938,1739502655.697581,16.01998472213745,-0.22744615488662046,1739502655.6975822,16.01998472213745,-0.05866375430368597,1739502655.6975837,16.01998472213745,2.0840931236902276,1739502655.697585,16.01998472213745,0.0,1739502655.6975865,16.01998472213745,-0.009627009117479195,1739502655.697588,16.01998472213745,0.01919943307295354,1739502655.6975892,16.01998472213745,2.093431469071242 +1739502655.7173057,16.039984703063965,32.290089571891365,1739502655.7173078,16.039984703063965,0.06374166713262852,1739502655.7173107,16.039984703063965,31.564913917569047,1739502655.7173135,16.039984703063965,37.74512271789703,1739502655.7173147,16.039984703063965,-0.059,1739502655.7173164,16.039984703063965,-0.022496831151484938,1739502655.7173176,16.039984703063965,-0.22744615488662046,1739502655.717319,16.039984703063965,-0.05866375430368597,1739502655.7173202,16.039984703063965,2.0840931236902276,1739502655.7173216,16.039984703063965,0.0,1739502655.717323,16.039984703063965,-0.009338345381014523,1739502655.7173243,16.039984703063965,0.01919943307295354,1739502655.717326,16.039984703063965,2.093431469071242 +1739502655.7372997,16.05998468399048,32.290089571891365,1739502655.737302,16.05998468399048,0.06374166713262852,1739502655.7373052,16.05998468399048,31.564913917569047,1739502655.7373075,16.05998468399048,37.74512271789703,1739502655.7373095,16.05998468399048,-0.059,1739502655.737311,16.05998468399048,-0.022496831151484938,1739502655.7373126,16.05998468399048,-0.22744615488662046,1739502655.7373166,16.05998468399048,-0.05866375430368597,1739502655.7373211,16.05998468399048,2.0840931236902276,1739502655.7373254,16.05998468399048,0.0,1739502655.7373295,16.05998468399048,-0.009338345381014523,1739502655.7373319,16.05998468399048,0.01919943307295354,1739502655.7373338,16.05998468399048,2.093431469071242 +1739502655.7572732,16.079984664916992,32.290089571891365,1739502655.757275,16.079984664916992,0.06374166713262852,1739502655.7572782,16.079984664916992,31.564913917569047,1739502655.7572808,16.079984664916992,37.74512271789703,1739502655.757282,16.079984664916992,-0.059,1739502655.757284,16.079984664916992,-0.022496831151484938,1739502655.7572854,16.079984664916992,-0.22744615488662046,1739502655.7572865,16.079984664916992,-0.05866375430368597,1739502655.757288,16.079984664916992,2.0840931236902276,1739502655.7572894,16.079984664916992,0.0,1739502655.7572908,16.079984664916992,-0.009338345381014523,1739502655.757292,16.079984664916992,0.01919943307295354,1739502655.7572935,16.079984664916992,2.093431469071242 +1739502655.7772782,16.099984645843506,32.290089571891365,1739502655.7772808,16.099984645843506,0.06374166713262852,1739502655.777284,16.099984645843506,31.564913917569047,1739502655.7772863,16.099984645843506,37.74512271789703,1739502655.777288,16.099984645843506,-0.059,1739502655.7772894,16.099984645843506,-0.022496831151484938,1739502655.7772908,16.099984645843506,-0.22744615488662046,1739502655.7772923,16.099984645843506,-0.05866375430368597,1739502655.7772937,16.099984645843506,2.0840931236902276,1739502655.7772949,16.099984645843506,0.0,1739502655.777296,16.099984645843506,-0.009338345381014523,1739502655.7772977,16.099984645843506,0.01919943307295354,1739502655.777299,16.099984645843506,2.093431469071242 +1739502655.7972755,16.11998462677002,32.290089571891365,1739502655.7972777,16.11998462677002,0.06374166713262852,1739502655.7972806,16.11998462677002,31.564913917569047,1739502655.7972834,16.11998462677002,37.74512271789703,1739502655.7972846,16.11998462677002,-0.059,1739502655.797286,16.11998462677002,-0.022496831151484938,1739502655.7972875,16.11998462677002,-0.22744615488662046,1739502655.7972887,16.11998462677002,-0.05866375430368597,1739502655.79729,16.11998462677002,2.0840931236902276,1739502655.7972918,16.11998462677002,0.0,1739502655.797293,16.11998462677002,-0.009338345381014523,1739502655.7972944,16.11998462677002,0.01919943307295354,1739502655.7972956,16.11998462677002,2.093431469071242 +1739502655.8174152,16.139984607696533,32.52027485063812,1739502655.8174186,16.139984607696533,0.06805488355333367,1739502655.8174224,16.139984607696533,32.28012203552065,1739502655.8174293,16.139984607696533,38.45826806203078,1739502655.8174324,16.139984607696533,-0.057333831587551315,1739502655.817436,16.139984607696533,-0.02111320756321241,1739502655.817439,16.139984607696533,-0.2333112642874401,1739502655.817441,16.139984607696533,-0.05079049296523609,1739502655.8174436,16.139984607696533,2.0743372818829307,1739502655.8174467,16.139984607696533,0.0,1739502655.8174486,16.139984607696533,-0.022033048606218728,1739502655.8174524,16.139984607696533,0.018179410213629132,1739502655.8174555,16.139984607696533,2.0924032331302413 +1739502655.8372629,16.159984588623047,32.52027485063812,1739502655.8372655,16.159984588623047,0.06805488355333367,1739502655.8372679,16.159984588623047,32.28012203552065,1739502655.8372707,16.159984588623047,38.45826806203078,1739502655.8372722,16.159984588623047,-0.057333831587551315,1739502655.8372738,16.159984588623047,-0.02111320756321241,1739502655.837275,16.159984588623047,-0.2333112642874401,1739502655.8372765,16.159984588623047,-0.05079049296523609,1739502655.8372777,16.159984588623047,2.0743372818829307,1739502655.8372793,16.159984588623047,0.0,1739502655.8372805,16.159984588623047,-0.018065951247310696,1739502655.8372817,16.159984588623047,0.018179410213629132,1739502655.8372831,16.159984588623047,2.0924032331302413 +1739502655.8574264,16.17998456954956,32.52027485063812,1739502655.857429,16.17998456954956,0.06805488355333367,1739502655.8574321,16.17998456954956,32.28012203552065,1739502655.8574345,16.17998456954956,38.45826806203078,1739502655.8574362,16.17998456954956,-0.057333831587551315,1739502655.8574376,16.17998456954956,-0.02111320756321241,1739502655.8574393,16.17998456954956,-0.2333112642874401,1739502655.8574407,16.17998456954956,-0.05079049296523609,1739502655.8574421,16.17998456954956,2.0743372818829307,1739502655.8574438,16.17998456954956,0.0,1739502655.8574455,16.17998456954956,-0.018065951247310696,1739502655.857447,16.17998456954956,0.018179410213629132,1739502655.8574483,16.17998456954956,2.0924032331302413 +1739502655.877433,16.199984550476074,32.52027485063812,1739502655.8774357,16.199984550476074,0.06805488355333367,1739502655.877439,16.199984550476074,32.28012203552065,1739502655.8774424,16.199984550476074,38.45826806203078,1739502655.8774438,16.199984550476074,-0.057333831587551315,1739502655.877446,16.199984550476074,-0.02111320756321241,1739502655.8774478,16.199984550476074,-0.2333112642874401,1739502655.8774495,16.199984550476074,-0.05079049296523609,1739502655.8774512,16.199984550476074,2.0743372818829307,1739502655.877453,16.199984550476074,0.0,1739502655.8774548,16.199984550476074,-0.018065951247310696,1739502655.8774567,16.199984550476074,0.018179410213629132,1739502655.877458,16.199984550476074,2.0924032331302413 +1739502655.8973584,16.219984531402588,32.52027485063812,1739502655.8973608,16.219984531402588,0.06805488355333367,1739502655.897364,16.219984531402588,32.28012203552065,1739502655.8973668,16.219984531402588,38.45826806203078,1739502655.8973684,16.219984531402588,-0.057333831587551315,1739502655.89737,16.219984531402588,-0.02111320756321241,1739502655.8973715,16.219984531402588,-0.2333112642874401,1739502655.8973732,16.219984531402588,-0.05079049296523609,1739502655.8973744,16.219984531402588,2.0743372818829307,1739502655.8973763,16.219984531402588,0.0,1739502655.8973777,16.219984531402588,-0.018065951247310696,1739502655.8973794,16.219984531402588,0.018179410213629132,1739502655.8973808,16.219984531402588,2.0924032331302413 +1739502655.9177237,16.2399845123291,32.75030606930743,1739502655.9177268,16.2399845123291,0.07213050731426218,1739502655.9177303,16.2399845123291,32.65783394531403,1739502655.9177337,16.2399845123291,38.83202852844316,1739502655.9177353,16.2399845123291,-0.059143309975288244,1739502655.9177377,16.2399845123291,-0.021581622075049465,1739502655.9177396,16.2399845123291,-0.23560800155974052,1739502655.917741,16.2399845123291,-0.04889419610381168,1739502655.9177427,16.2399845123291,2.070529415021612,1739502655.9177446,16.2399845123291,0.0,1739502655.9177465,16.2399845123291,-0.020739990079637585,1739502655.9177482,16.2399845123291,0.017159387354304723,1739502655.9177501,16.2399845123291,2.0904337674182605 +1739502655.9379225,16.259984493255615,32.75030606930743,1739502655.9379256,16.259984493255615,0.07213050731426218,1739502655.9379299,16.259984493255615,32.65783394531403,1739502655.937934,16.259984493255615,38.83202852844316,1739502655.9379358,16.259984493255615,-0.059143309975288244,1739502655.9379385,16.259984493255615,-0.021581622075049465,1739502655.9379406,16.259984493255615,-0.23560800155974052,1739502655.9379423,16.259984493255615,-0.04889419610381168,1739502655.9379442,16.259984493255615,2.070529415021612,1739502655.9379463,16.259984493255615,0.0,1739502655.9379485,16.259984493255615,-0.019904352396648672,1739502655.9379501,16.259984493255615,0.017159387354304723,1739502655.9379523,16.259984493255615,2.0904337674182605 +1739502655.958528,16.27998447418213,32.75030606930743,1739502655.9585316,16.27998447418213,0.07213050731426218,1739502655.958536,16.27998447418213,32.65783394531403,1739502655.9585402,16.27998447418213,38.83202852844316,1739502655.958542,16.27998447418213,-0.059143309975288244,1739502655.9585445,16.27998447418213,-0.021581622075049465,1739502655.9585464,16.27998447418213,-0.23560800155974052,1739502655.9585483,16.27998447418213,-0.04889419610381168,1739502655.95855,16.27998447418213,2.070529415021612,1739502655.9585526,16.27998447418213,0.0,1739502655.9585543,16.27998447418213,-0.019904352396648672,1739502655.9585564,16.27998447418213,0.017159387354304723,1739502655.9585586,16.27998447418213,2.0904337674182605 +1739502655.977759,16.299984455108643,32.75030606930743,1739502655.9777622,16.299984455108643,0.07213050731426218,1739502655.9777665,16.299984455108643,32.65783394531403,1739502655.9777703,16.299984455108643,38.83202852844316,1739502655.9777722,16.299984455108643,-0.059143309975288244,1739502655.9777749,16.299984455108643,-0.021581622075049465,1739502655.977777,16.299984455108643,-0.23560800155974052,1739502655.977779,16.299984455108643,-0.04889419610381168,1739502655.9777808,16.299984455108643,2.070529415021612,1739502655.977783,16.299984455108643,0.0,1739502655.9777849,16.299984455108643,-0.019904352396648672,1739502655.9777868,16.299984455108643,0.017159387354304723,1739502655.977789,16.299984455108643,2.0904337674182605 +1739502655.9985197,16.319984436035156,32.75030606930743,1739502655.998523,16.319984436035156,0.07213050731426218,1739502655.998527,16.319984436035156,32.65783394531403,1739502655.9985309,16.319984436035156,38.83202852844316,1739502655.9985328,16.319984436035156,-0.059143309975288244,1739502655.9985354,16.319984436035156,-0.021581622075049465,1739502655.9985375,16.319984436035156,-0.23560800155974052,1739502655.9985392,16.319984436035156,-0.04889419610381168,1739502655.998541,16.319984436035156,2.070529415021612,1739502655.9985435,16.319984436035156,0.0,1739502655.9985456,16.319984436035156,-0.019904352396648672,1739502655.9985478,16.319984436035156,0.017159387354304723,1739502655.9985497,16.319984436035156,2.0904337674182605 +1739502656.0178056,16.33998441696167,32.75030606930743,1739502656.017809,16.33998441696167,0.07213050731426218,1739502656.0178127,16.33998441696167,32.65783394531403,1739502656.0178168,16.33998441696167,38.83202852844316,1739502656.017819,16.33998441696167,-0.059143309975288244,1739502656.017821,16.33998441696167,-0.021581622075049465,1739502656.0178232,16.33998441696167,-0.23560800155974052,1739502656.0178251,16.33998441696167,-0.04889419610381168,1739502656.017827,16.33998441696167,2.070529415021612,1739502656.0178292,16.33998441696167,0.0,1739502656.017831,16.33998441696167,-0.019904352396648672,1739502656.0178332,16.33998441696167,0.017159387354304723,1739502656.0178354,16.33998441696167,2.0904337674182605 +1739502656.0378318,16.359984397888184,32.98011098646312,1739502656.0378356,16.359984397888184,0.07596764746495133,1739502656.0378394,16.359984397888184,32.70425837571963,1739502656.0378435,16.359984397888184,38.87405561507705,1739502656.0378456,16.359984397888184,-0.059810406588524476,1739502656.037848,16.359984397888184,-0.02303279912304372,1739502656.03785,16.359984397888184,-0.23088076183577075,1739502656.037852,16.359984397888184,-0.05101108815681943,1739502656.037854,16.359984397888184,2.078374551127439,1739502656.0378563,16.359984397888184,0.0,1739502656.0378582,16.359984397888184,-0.005299023026284153,1739502656.0378604,16.359984397888184,0.016139364494980313,1739502656.0378625,16.359984397888184,2.088237742574464 +1739502656.0580459,16.379984378814697,32.98011098646312,1739502656.0580494,16.379984378814697,0.07596764746495133,1739502656.0580537,16.379984378814697,32.70425837571963,1739502656.0580578,16.379984378814697,38.87405561507705,1739502656.0580595,16.379984378814697,-0.059810406588524476,1739502656.058062,16.379984378814697,-0.02303279912304372,1739502656.0580642,16.379984378814697,-0.23088076183577075,1739502656.0580661,16.379984378814697,-0.05101108815681943,1739502656.0580683,16.379984378814697,2.078374551127439,1739502656.0580702,16.379984378814697,0.0,1739502656.0580723,16.379984378814697,-0.009863191447025077,1739502656.0580747,16.379984378814697,0.016139364494980313,1739502656.0580766,16.379984378814697,2.088237742574464 +1739502656.078568,16.39998435974121,32.98011098646312,1739502656.0785718,16.39998435974121,0.07596764746495133,1739502656.0785766,16.39998435974121,32.70425837571963,1739502656.078581,16.39998435974121,38.87405561507705,1739502656.0785832,16.39998435974121,-0.059810406588524476,1739502656.078586,16.39998435974121,-0.02303279912304372,1739502656.0785885,16.39998435974121,-0.23088076183577075,1739502656.0785904,16.39998435974121,-0.05101108815681943,1739502656.0785928,16.39998435974121,2.078374551127439,1739502656.0785954,16.39998435974121,0.0,1739502656.0785975,16.39998435974121,-0.009863191447025077,1739502656.0786,16.39998435974121,0.016139364494980313,1739502656.0786026,16.39998435974121,2.088237742574464 +1739502656.099267,16.419984340667725,32.98011098646312,1739502656.0992706,16.419984340667725,0.07596764746495133,1739502656.0992754,16.419984340667725,32.70425837571963,1739502656.0992799,16.419984340667725,38.87405561507705,1739502656.099282,16.419984340667725,-0.059810406588524476,1739502656.0992846,16.419984340667725,-0.02303279912304372,1739502656.0992868,16.419984340667725,-0.23088076183577075,1739502656.0992892,16.419984340667725,-0.05101108815681943,1739502656.099291,16.419984340667725,2.078374551127439,1739502656.0992937,16.419984340667725,0.0,1739502656.0992959,16.419984340667725,-0.009863191447025077,1739502656.0992982,16.419984340667725,0.016139364494980313,1739502656.0993004,16.419984340667725,2.088237742574464 +1739502656.118825,16.43998432159424,32.98011098646312,1739502656.1188288,16.43998432159424,0.07596764746495133,1739502656.1188343,16.43998432159424,32.70425837571963,1739502656.1188388,16.43998432159424,38.87405561507705,1739502656.118841,16.43998432159424,-0.059810406588524476,1739502656.1188433,16.43998432159424,-0.02303279912304372,1739502656.1188457,16.43998432159424,-0.23088076183577075,1739502656.118848,16.43998432159424,-0.05101108815681943,1739502656.11885,16.43998432159424,2.078374551127439,1739502656.1188526,16.43998432159424,0.0,1739502656.118855,16.43998432159424,-0.009863191447025077,1739502656.1188571,16.43998432159424,0.016139364494980313,1739502656.1188593,16.43998432159424,2.088237742574464 +1739502656.1388085,16.459984302520752,33.209732747748575,1739502656.1388128,16.459984302520752,0.07956743782865949,1739502656.1388175,16.459984302520752,32.75064557128965,1739502656.1388218,16.459984302520752,38.91826342178535,1739502656.1388242,16.459984302520752,-0.06051211780611655,1739502656.138827,16.459984302520752,-0.024533712391812002,1739502656.1388292,16.459984302520752,-0.22636948246609231,1739502656.1388316,16.459984302520752,-0.05331179081302315,1739502656.1388338,16.459984302520752,2.0858890054802264,1739502656.1388361,16.459984302520752,0.0,1739502656.1388385,16.459984302520752,0.002647887758946057,1739502656.138841,16.459984302520752,0.015119341635655915,1739502656.138843,16.459984302520752,2.087150832536555 +1739502656.1600454,16.479984283447266,33.209732747748575,1739502656.1600497,16.479984283447266,0.07956743782865949,1739502656.1600554,16.479984283447266,32.75064557128965,1739502656.1600602,16.479984283447266,38.91826342178535,1739502656.1600626,16.479984283447266,-0.06051211780611655,1739502656.1600652,16.479984283447266,-0.024533712391812002,1739502656.1600676,16.479984283447266,-0.22636948246609231,1739502656.1600697,16.479984283447266,-0.05331179081302315,1739502656.1600718,16.479984283447266,2.0858890054802264,1739502656.1600747,16.479984283447266,0.0,1739502656.160077,16.479984283447266,-0.0012618270563287126,1739502656.1600797,16.479984283447266,0.015119341635655915,1739502656.1600819,16.479984283447266,2.087150832536555 +1739502656.178332,16.49998426437378,33.209732747748575,1739502656.1783361,16.49998426437378,0.07956743782865949,1739502656.1783412,16.49998426437378,32.75064557128965,1739502656.1783457,16.49998426437378,38.91826342178535,1739502656.178348,16.49998426437378,-0.06051211780611655,1739502656.1783512,16.49998426437378,-0.024533712391812002,1739502656.1783533,16.49998426437378,-0.22636948246609231,1739502656.1783555,16.49998426437378,-0.05331179081302315,1739502656.1783578,16.49998426437378,2.0858890054802264,1739502656.1783602,16.49998426437378,0.0,1739502656.1783626,16.49998426437378,-0.0012618270563287126,1739502656.1783652,16.49998426437378,0.015119341635655915,1739502656.1783674,16.49998426437378,2.087150832536555 +1739502656.199012,16.519984245300293,33.209732747748575,1739502656.1990159,16.519984245300293,0.07956743782865949,1739502656.1990206,16.519984245300293,32.75064557128965,1739502656.199025,16.519984245300293,38.91826342178535,1739502656.1990275,16.519984245300293,-0.06051211780611655,1739502656.19903,16.519984245300293,-0.024533712391812002,1739502656.1990323,16.519984245300293,-0.22636948246609231,1739502656.1990347,16.519984245300293,-0.05331179081302315,1739502656.1990366,16.519984245300293,2.0858890054802264,1739502656.1990392,16.519984245300293,0.0,1739502656.1990414,16.519984245300293,-0.0012618270563287126,1739502656.1990438,16.519984245300293,0.015119341635655915,1739502656.1990461,16.519984245300293,2.087150832536555 +1739502656.2184005,16.539984226226807,33.209732747748575,1739502656.218405,16.539984226226807,0.07956743782865949,1739502656.21841,16.539984226226807,32.75064557128965,1739502656.2184145,16.539984226226807,38.91826342178535,1739502656.2184172,16.539984226226807,-0.06051211780611655,1739502656.21842,16.539984226226807,-0.024533712391812002,1739502656.2184222,16.539984226226807,-0.22636948246609231,1739502656.2184248,16.539984226226807,-0.05331179081302315,1739502656.218427,16.539984226226807,2.0858890054802264,1739502656.2184293,16.539984226226807,0.0,1739502656.2184317,16.539984226226807,-0.0012618270563287126,1739502656.218434,16.539984226226807,0.015119341635655915,1739502656.2184362,16.539984226226807,2.087150832536555 +1739502656.238926,16.55998420715332,33.209732747748575,1739502656.2389297,16.55998420715332,0.07956743782865949,1739502656.2389343,16.55998420715332,32.75064557128965,1739502656.2389388,16.55998420715332,38.91826342178535,1739502656.238941,16.55998420715332,-0.06051211780611655,1739502656.238944,16.55998420715332,-0.024533712391812002,1739502656.2389462,16.55998420715332,-0.22636948246609231,1739502656.2389486,16.55998420715332,-0.05331179081302315,1739502656.2389507,16.55998420715332,2.0858890054802264,1739502656.238953,16.55998420715332,0.0,1739502656.2389555,16.55998420715332,-0.0012618270563287126,1739502656.238958,16.55998420715332,0.015119341635655915,1739502656.23896,16.55998420715332,2.087150832536555 +1739502656.2592509,16.579984188079834,33.43928591044376,1739502656.2592545,16.579984188079834,0.08293194074320098,1739502656.2592592,16.579984188079834,32.797018674657,1739502656.2592638,16.579984188079834,38.96434108279615,1739502656.2592661,16.579984188079834,-0.06124350925073255,1739502656.2592688,16.579984188079834,-0.026088922893328564,1739502656.2592714,16.579984188079834,-0.2220580530620056,1739502656.2592738,16.579984188079834,-0.05582243208756451,1739502656.2592757,16.579984188079834,2.0930959577953416,1739502656.2592783,16.579984188079834,0.0,1739502656.2592804,16.579984188079834,0.009431661700285414,1739502656.2592826,16.579984188079834,0.014099318776331525,1739502656.259285,16.579984188079834,2.087006013522499 +1739502656.278856,16.599984169006348,33.43928591044376,1739502656.27886,16.599984169006348,0.08293194074320098,1739502656.2788649,16.599984169006348,32.797018674657,1739502656.2788694,16.599984169006348,38.96434108279615,1739502656.2788718,16.599984169006348,-0.06124350925073255,1739502656.2788749,16.599984169006348,-0.026088922893328564,1739502656.2788773,16.599984169006348,-0.2220580530620056,1739502656.2788792,16.599984169006348,-0.05582243208756451,1739502656.2788818,16.599984169006348,2.0930959577953416,1739502656.2788844,16.599984169006348,0.0,1739502656.2788866,16.599984169006348,0.006089944272842818,1739502656.278889,16.599984169006348,0.014099318776331525,1739502656.2788913,16.599984169006348,2.087006013522499 +1739502656.299059,16.61998414993286,33.43928591044376,1739502656.2990625,16.61998414993286,0.08293194074320098,1739502656.2990675,16.61998414993286,32.797018674657,1739502656.299072,16.61998414993286,38.96434108279615,1739502656.299074,16.61998414993286,-0.06124350925073255,1739502656.2990768,16.61998414993286,-0.026088922893328564,1739502656.2990794,16.61998414993286,-0.2220580530620056,1739502656.2990816,16.61998414993286,-0.05582243208756451,1739502656.2990837,16.61998414993286,2.0930959577953416,1739502656.2990863,16.61998414993286,0.0,1739502656.2990887,16.61998414993286,0.006089944272842818,1739502656.2990909,16.61998414993286,0.014099318776331525,1739502656.2990932,16.61998414993286,2.087006013522499 +1739502656.3188906,16.639984130859375,33.43928591044376,1739502656.3188944,16.639984130859375,0.08293194074320098,1739502656.318899,16.639984130859375,32.797018674657,1739502656.3189034,16.639984130859375,38.96434108279615,1739502656.3189058,16.639984130859375,-0.06124350925073255,1739502656.3189087,16.639984130859375,-0.026088922893328564,1739502656.318911,16.639984130859375,-0.2220580530620056,1739502656.318913,16.639984130859375,-0.05582243208756451,1739502656.3189151,16.639984130859375,2.0930959577953416,1739502656.318918,16.639984130859375,0.0,1739502656.31892,16.639984130859375,0.006089944272842818,1739502656.3189223,16.639984130859375,0.014099318776331525,1739502656.3189242,16.639984130859375,2.087006013522499 +1739502656.3391004,16.65998411178589,33.43928591044376,1739502656.3391073,16.65998411178589,0.08293194074320098,1739502656.3391147,16.65998411178589,32.797018674657,1739502656.339122,16.65998411178589,38.96434108279615,1739502656.3391263,16.65998411178589,-0.06124350925073255,1739502656.339131,16.65998411178589,-0.026088922893328564,1739502656.3391352,16.65998411178589,-0.2220580530620056,1739502656.3391392,16.65998411178589,-0.05582243208756451,1739502656.3391438,16.65998411178589,2.0930959577953416,1739502656.3391478,16.65998411178589,0.0,1739502656.3391516,16.65998411178589,0.006089944272842818,1739502656.3391557,16.65998411178589,0.014099318776331525,1739502656.33916,16.65998411178589,2.087006013522499 +1739502656.3593383,16.679984092712402,33.668859729520925,1739502656.359342,16.679984092712402,0.08606252202440601,1739502656.3593466,16.679984092712402,33.41406660026998,1739502656.3593514,16.679984092712402,39.5825042512766,1739502656.3593533,16.679984092712402,-0.06968223941759837,1739502656.3593562,16.679984092712402,-0.02633042399599099,1739502656.3593585,16.679984092712402,-0.23307554158170635,1739502656.3593607,16.679984092712402,-0.05114512997789833,1739502656.3593628,16.679984092712402,2.074728493486106,1739502656.3593655,16.679984092712402,0.0,1739502656.3593676,16.679984092712402,-0.021481226174683246,1739502656.35937,16.679984092712402,0.013079295917007135,1739502656.3593726,16.679984092712402,2.08759372324685 +1739502656.3789525,16.699984073638916,33.668859729520925,1739502656.3789568,16.699984073638916,0.08606252202440601,1739502656.3789628,16.699984073638916,33.41406660026998,1739502656.378967,16.699984073638916,39.5825042512766,1739502656.3789694,16.699984073638916,-0.06968223941759837,1739502656.3789725,16.699984073638916,-0.02633042399599099,1739502656.3789785,16.699984073638916,-0.23307554158170635,1739502656.3789852,16.699984073638916,-0.05114512997789833,1739502656.378992,16.699984073638916,2.074728493486106,1739502656.3789995,16.699984073638916,0.0,1739502656.3790064,16.699984073638916,-0.01286522976074389,1739502656.3790138,16.699984073638916,0.013079295917007135,1739502656.3790212,16.699984073638916,2.08759372324685 +1739502656.3995416,16.71998405456543,33.668859729520925,1739502656.3995457,16.71998405456543,0.08606252202440601,1739502656.3995502,16.71998405456543,33.41406660026998,1739502656.3995547,16.71998405456543,39.5825042512766,1739502656.399557,16.71998405456543,-0.06968223941759837,1739502656.39956,16.71998405456543,-0.02633042399599099,1739502656.3995624,16.71998405456543,-0.23307554158170635,1739502656.3995645,16.71998405456543,-0.05114512997789833,1739502656.3995667,16.71998405456543,2.074728493486106,1739502656.399569,16.71998405456543,0.0,1739502656.3995714,16.71998405456543,-0.01286522976074389,1739502656.3995738,16.71998405456543,0.013079295917007135,1739502656.399576,16.71998405456543,2.08759372324685 +1739502656.418891,16.739984035491943,33.668859729520925,1739502656.4188952,16.739984035491943,0.08606252202440601,1739502656.4189005,16.739984035491943,33.41406660026998,1739502656.418905,16.739984035491943,39.5825042512766,1739502656.4189074,16.739984035491943,-0.06968223941759837,1739502656.4189103,16.739984035491943,-0.02633042399599099,1739502656.4189124,16.739984035491943,-0.23307554158170635,1739502656.4189148,16.739984035491943,-0.05114512997789833,1739502656.418917,16.739984035491943,2.074728493486106,1739502656.4189193,16.739984035491943,0.0,1739502656.4189215,16.739984035491943,-0.01286522976074389,1739502656.418924,16.739984035491943,0.013079295917007135,1739502656.4189262,16.739984035491943,2.08759372324685 +1739502656.438903,16.759984016418457,33.668859729520925,1739502656.438907,16.759984016418457,0.08606252202440601,1739502656.4389117,16.759984016418457,33.41406660026998,1739502656.4389164,16.759984016418457,39.5825042512766,1739502656.4389186,16.759984016418457,-0.06968223941759837,1739502656.4389215,16.759984016418457,-0.02633042399599099,1739502656.438924,16.759984016418457,-0.23307554158170635,1739502656.4389262,16.759984016418457,-0.05114512997789833,1739502656.4389284,16.759984016418457,2.074728493486106,1739502656.4389312,16.759984016418457,0.0,1739502656.4389331,16.759984016418457,-0.01286522976074389,1739502656.4389355,16.759984016418457,0.013079295917007135,1739502656.438938,16.759984016418457,2.08759372324685 +1739502656.4588468,16.77998399734497,33.668859729520925,1739502656.4588506,16.77998399734497,0.08606252202440601,1739502656.4588554,16.77998399734497,33.41406660026998,1739502656.4588597,16.77998399734497,39.5825042512766,1739502656.458862,16.77998399734497,-0.06968223941759837,1739502656.4588647,16.77998399734497,-0.02633042399599099,1739502656.4588668,16.77998399734497,-0.23307554158170635,1739502656.4588692,16.77998399734497,-0.05114512997789833,1739502656.4588714,16.77998399734497,2.074728493486106,1739502656.4588737,16.77998399734497,0.0,1739502656.4588761,16.77998399734497,-0.01286522976074389,1739502656.4588785,16.77998399734497,0.013079295917007135,1739502656.4588807,16.77998399734497,2.08759372324685 +1739502656.478492,16.799983978271484,33.89838302137313,1739502656.4784968,16.799983978271484,0.08895827610055385,1739502656.4785018,16.799983978271484,33.42439804415741,1739502656.4785066,16.799983978271484,39.58950533327764,1739502656.4785087,16.799983978271484,-0.06974157062099699,1739502656.4785113,16.799983978271484,-0.027878285181690332,1739502656.4785137,16.799983978271484,-0.22731744183900612,1739502656.4785156,16.799983978271484,-0.053853497181443916,1739502656.478518,16.799983978271484,2.084307734721304,1739502656.4785209,16.799983978271484,0.0,1739502656.4785228,16.799983978271484,0.0034901154465454788,1739502656.4785254,16.799983978271484,0.012059273057682745,1739502656.4785278,16.799983978271484,2.0859286680031013 +1739502656.49924,16.819983959197998,33.89838302137313,1739502656.499244,16.819983959197998,0.08895827610055385,1739502656.4992487,16.819983959197998,33.42439804415741,1739502656.4992533,16.819983959197998,39.58950533327764,1739502656.4992552,16.819983959197998,-0.06974157062099699,1739502656.4992578,16.819983959197998,-0.027878285181690332,1739502656.4992602,16.819983959197998,-0.22731744183900612,1739502656.4992626,16.819983959197998,-0.053853497181443916,1739502656.4992645,16.819983959197998,2.084307734721304,1739502656.499267,16.819983959197998,0.0,1739502656.4992695,16.819983959197998,-0.0016209332817971323,1739502656.4992716,16.819983959197998,0.012059273057682745,1739502656.499274,16.819983959197998,2.0859286680031013 +1739502656.5187774,16.83998394012451,33.89838302137313,1739502656.5187812,16.83998394012451,0.08895827610055385,1739502656.5187862,16.83998394012451,33.42439804415741,1739502656.5187907,16.83998394012451,39.58950533327764,1739502656.5187929,16.83998394012451,-0.06974157062099699,1739502656.5187957,16.83998394012451,-0.027878285181690332,1739502656.518798,16.83998394012451,-0.22731744183900612,1739502656.5188005,16.83998394012451,-0.053853497181443916,1739502656.5188024,16.83998394012451,2.084307734721304,1739502656.5188053,16.83998394012451,0.0,1739502656.5188074,16.83998394012451,-0.0016209332817971323,1739502656.5188096,16.83998394012451,0.012059273057682745,1739502656.518812,16.83998394012451,2.0859286680031013 +1739502656.538345,16.859983921051025,33.89838302137313,1739502656.5383492,16.859983921051025,0.08895827610055385,1739502656.5383537,16.859983921051025,33.42439804415741,1739502656.5383582,16.859983921051025,39.58950533327764,1739502656.5383606,16.859983921051025,-0.06974157062099699,1739502656.5383635,16.859983921051025,-0.027878285181690332,1739502656.5383656,16.859983921051025,-0.22731744183900612,1739502656.538368,16.859983921051025,-0.053853497181443916,1739502656.5383701,16.859983921051025,2.084307734721304,1739502656.5383725,16.859983921051025,0.0,1739502656.538375,16.859983921051025,-0.0016209332817971323,1739502656.5383775,16.859983921051025,0.012059273057682745,1739502656.5383797,16.859983921051025,2.0859286680031013 +1739502656.5592484,16.87998390197754,33.89838302137313,1739502656.5592523,16.87998390197754,0.08895827610055385,1739502656.5592566,16.87998390197754,33.42439804415741,1739502656.5592608,16.87998390197754,39.58950533327764,1739502656.559263,16.87998390197754,-0.06974157062099699,1739502656.5592659,16.87998390197754,-0.027878285181690332,1739502656.559268,16.87998390197754,-0.22731744183900612,1739502656.5592704,16.87998390197754,-0.053853497181443916,1739502656.5592725,16.87998390197754,2.084307734721304,1739502656.559275,16.87998390197754,0.0,1739502656.5592773,16.87998390197754,-0.0016209332817971323,1739502656.5592797,16.87998390197754,0.012059273057682745,1739502656.559282,16.87998390197754,2.0859286680031013 +1739502656.5778778,16.899983882904053,34.12781202998568,1739502656.5778816,16.899983882904053,0.09161876889367804,1739502656.5778854,16.899983882904053,33.43472501003776,1739502656.577889,16.899983882904053,39.599561578856324,1739502656.577891,16.899983882904053,-0.06982679304115529,1739502656.5778933,16.899983882904053,-0.029496733262749736,1739502656.5778954,16.899983882904053,-0.22183851019333975,1739502656.5778975,16.899983882904053,-0.05684808458015872,1739502656.5778992,16.899983882904053,2.0934636095132957,1739502656.5779014,16.899983882904053,0.0,1739502656.5779033,16.899983882904053,0.011893331676817318,1739502656.5779054,16.899983882904053,0.011039250198358354,1739502656.577907,16.899983882904053,2.085793488404998 +1739502656.597975,16.919983863830566,34.12781202998568,1739502656.5979786,16.919983863830566,0.09161876889367804,1739502656.5979824,16.919983863830566,33.43472501003776,1739502656.5979865,16.919983863830566,39.599561578856324,1739502656.5979884,16.919983863830566,-0.06982679304115529,1739502656.597991,16.919983863830566,-0.029496733262749736,1739502656.597993,16.919983863830566,-0.22183851019333975,1739502656.597995,16.919983863830566,-0.05684808458015872,1739502656.5979967,16.919983863830566,2.0934636095132957,1739502656.597999,16.919983863830566,0.0,1739502656.598001,16.919983863830566,0.007670121108297678,1739502656.598003,16.919983863830566,0.011039250198358354,1739502656.5980053,16.919983863830566,2.085793488404998 +1739502656.6210508,16.93998384475708,34.12781202998568,1739502656.62106,16.93998384475708,0.09161876889367804,1739502656.6210706,16.93998384475708,33.43472501003776,1739502656.6210804,16.93998384475708,39.599561578856324,1739502656.6210852,16.93998384475708,-0.06982679304115529,1739502656.6210916,16.93998384475708,-0.029496733262749736,1739502656.6210968,16.93998384475708,-0.22183851019333975,1739502656.6211019,16.93998384475708,-0.05684808458015872,1739502656.6211066,16.93998384475708,2.0934636095132957,1739502656.6211126,16.93998384475708,0.0,1739502656.6211176,16.93998384475708,0.007670121108297678,1739502656.621123,16.93998384475708,0.011039250198358354,1739502656.6211286,16.93998384475708,2.085793488404998 +1739502656.6408982,16.959983825683594,34.12781202998568,1739502656.6409066,16.959983825683594,0.09161876889367804,1739502656.640917,16.959983825683594,33.43472501003776,1739502656.6409276,16.959983825683594,39.599561578856324,1739502656.6409323,16.959983825683594,-0.06982679304115529,1739502656.6409385,16.959983825683594,-0.029496733262749736,1739502656.6409435,16.959983825683594,-0.22183851019333975,1739502656.6409485,16.959983825683594,-0.05684808458015872,1739502656.640953,16.959983825683594,2.0934636095132957,1739502656.6409593,16.959983825683594,0.0,1739502656.6409643,16.959983825683594,0.007670121108297678,1739502656.6409695,16.959983825683594,0.011039250198358354,1739502656.6409748,16.959983825683594,2.085793488404998 +1739502656.663805,16.979983806610107,34.12781202998568,1739502656.6638107,16.979983806610107,0.09161876889367804,1739502656.6638181,16.979983806610107,33.43472501003776,1739502656.6638255,16.979983806610107,39.599561578856324,1739502656.6638288,16.979983806610107,-0.06982679304115529,1739502656.663833,16.979983806610107,-0.029496733262749736,1739502656.6638362,16.979983806610107,-0.22183851019333975,1739502656.6638398,16.979983806610107,-0.05684808458015872,1739502656.6638432,16.979983806610107,2.0934636095132957,1739502656.6638467,16.979983806610107,0.0,1739502656.6638503,16.979983806610107,0.007670121108297678,1739502656.6638541,16.979983806610107,0.011039250198358354,1739502656.6638575,16.979983806610107,2.085793488404998 +1739502656.6829875,17.009983777999878,34.357286533327894,1739502656.682991,17.009983777999878,0.09404568238761524,1739502656.682996,17.009983777999878,33.44505378960166,1739502656.6830003,17.009983777999878,39.61173709260879,1739502656.6830027,17.009983777999878,-0.06992997536109147,1739502656.6830053,17.009983777999878,-0.031196878963921842,1739502656.6830075,17.009983777999878,-0.21661208137284174,1739502656.6830096,17.009983777999878,-0.060187770656856814,1739502656.6830115,17.009983777999878,2.1022350047988554,1739502656.6830142,17.009983777999878,0.0,1739502656.6830163,17.009983777999878,0.019085120275456408,1739502656.6830184,17.009983777999878,0.010019227339033964,1739502656.6830206,17.009983777999878,2.086717074101968 +1739502656.7035372,17.02998375892639,34.357286533327894,1739502656.7035408,17.02998375892639,0.09404568238761524,1739502656.7035456,17.02998375892639,33.44505378960166,1739502656.7035508,17.02998375892639,39.61173709260879,1739502656.7035537,17.02998375892639,-0.06992997536109147,1739502656.7035577,17.02998375892639,-0.031196878963921842,1739502656.703561,17.02998375892639,-0.21661208137284174,1739502656.7035646,17.02998375892639,-0.060187770656856814,1739502656.703568,17.02998375892639,2.1022350047988554,1739502656.7035716,17.02998375892639,0.0,1739502656.703575,17.02998375892639,0.01551793069688756,1739502656.7035785,17.02998375892639,0.010019227339033964,1739502656.703582,17.02998375892639,2.086717074101968 +1739502656.723572,17.049983739852905,34.357286533327894,1739502656.7235756,17.049983739852905,0.09404568238761524,1739502656.7235801,17.049983739852905,33.44505378960166,1739502656.7235854,17.049983739852905,39.61173709260879,1739502656.7235885,17.049983739852905,-0.06992997536109147,1739502656.7235923,17.049983739852905,-0.031196878963921842,1739502656.7235956,17.049983739852905,-0.21661208137284174,1739502656.723599,17.049983739852905,-0.060187770656856814,1739502656.7236025,17.049983739852905,2.1022350047988554,1739502656.723606,17.049983739852905,0.0,1739502656.7236094,17.049983739852905,0.01551793069688756,1739502656.7236128,17.049983739852905,0.010019227339033964,1739502656.7236164,17.049983739852905,2.086717074101968 +1739502656.743398,17.06998372077942,34.357286533327894,1739502656.7434022,17.06998372077942,0.09404568238761524,1739502656.7434068,17.06998372077942,33.44505378960166,1739502656.7434123,17.06998372077942,39.61173709260879,1739502656.743415,17.06998372077942,-0.06992997536109147,1739502656.743419,17.06998372077942,-0.031196878963921842,1739502656.7434225,17.06998372077942,-0.21661208137284174,1739502656.7434258,17.06998372077942,-0.060187770656856814,1739502656.7434292,17.06998372077942,2.1022350047988554,1739502656.7434328,17.06998372077942,0.0,1739502656.7434363,17.06998372077942,0.01551793069688756,1739502656.7434397,17.06998372077942,0.010019227339033964,1739502656.7434433,17.06998372077942,2.086717074101968 +1739502656.7628827,17.089983701705933,34.357286533327894,1739502656.762887,17.089983701705933,0.09404568238761524,1739502656.762892,17.089983701705933,33.44505378960166,1739502656.7628965,17.089983701705933,39.61173709260879,1739502656.7628987,17.089983701705933,-0.06992997536109147,1739502656.7629018,17.089983701705933,-0.031196878963921842,1739502656.7629044,17.089983701705933,-0.21661208137284174,1739502656.7629068,17.089983701705933,-0.060187770656856814,1739502656.762909,17.089983701705933,2.1022350047988554,1739502656.7629116,17.089983701705933,0.0,1739502656.7629135,17.089983701705933,0.01551793069688756,1739502656.762916,17.089983701705933,0.010019227339033964,1739502656.7629185,17.089983701705933,2.086717074101968 +1739502656.782647,17.109983682632446,34.357286533327894,1739502656.7826505,17.109983682632446,0.09404568238761524,1739502656.7826548,17.109983682632446,33.44505378960166,1739502656.782659,17.109983682632446,39.61173709260879,1739502656.7826614,17.109983682632446,-0.06992997536109147,1739502656.7826643,17.109983682632446,-0.031196878963921842,1739502656.7826664,17.109983682632446,-0.21661208137284174,1739502656.782669,17.109983682632446,-0.060187770656856814,1739502656.7826715,17.109983682632446,2.1022350047988554,1739502656.7826738,17.109983682632446,0.0,1739502656.7826765,17.109983682632446,0.01551793069688756,1739502656.7826788,17.109983682632446,0.010019227339033964,1739502656.782681,17.109983682632446,2.086717074101968 +1739502656.8025024,17.12998366355896,34.586906783510294,1739502656.8025062,17.12998366355896,0.09623988775549197,1739502656.8025103,17.12998366355896,33.72031524778467,1739502656.8025143,17.12998366355896,39.890507345688356,1739502656.8025165,17.12998366355896,-0.07387331118212949,1739502656.8025193,17.12998366355896,-0.03206404686376035,1739502656.802522,17.12998366355896,-0.2178338523411978,1739502656.802524,17.12998366355896,-0.05940754788927674,1739502656.8025265,17.12998366355896,2.100181248892076,1739502656.8025296,17.12998366355896,0.0,1739502656.802532,17.12998366355896,0.00995626529961647,1739502656.8025343,17.12998366355896,0.008999204479709574,1739502656.802537,17.12998366355896,2.0884869620162765 +1739502656.822825,17.149983644485474,34.586906783510294,1739502656.8228288,17.149983644485474,0.09623988775549197,1739502656.8228333,17.149983644485474,33.72031524778467,1739502656.8228388,17.149983644485474,39.890507345688356,1739502656.822842,17.149983644485474,-0.07387331118212949,1739502656.8228457,17.149983644485474,-0.03206404686376035,1739502656.8228493,17.149983644485474,-0.2178338523411978,1739502656.8228528,17.149983644485474,-0.05940754788927674,1739502656.8228562,17.149983644485474,2.100181248892076,1739502656.8228598,17.149983644485474,0.0,1739502656.822863,17.149983644485474,0.011694286875799431,1739502656.8228667,17.149983644485474,0.008999204479709574,1739502656.8228703,17.149983644485474,2.0884869620162765 +1739502656.8417678,17.169983625411987,34.586906783510294,1739502656.8417702,17.169983625411987,0.09623988775549197,1739502656.8417735,17.169983625411987,33.72031524778467,1739502656.8417764,17.169983625411987,39.890507345688356,1739502656.8417778,17.169983625411987,-0.07387331118212949,1739502656.8417795,17.169983625411987,-0.03206404686376035,1739502656.841781,17.169983625411987,-0.2178338523411978,1739502656.8417823,17.169983625411987,-0.05940754788927674,1739502656.8417835,17.169983625411987,2.100181248892076,1739502656.8417847,17.169983625411987,0.0,1739502656.8417864,17.169983625411987,0.011694286875799431,1739502656.8417878,17.169983625411987,0.008999204479709574,1739502656.8417895,17.169983625411987,2.0884869620162765 +1739502656.8617735,17.1899836063385,34.586906783510294,1739502656.8617759,17.1899836063385,0.09623988775549197,1739502656.8617787,17.1899836063385,33.72031524778467,1739502656.8617814,17.1899836063385,39.890507345688356,1739502656.8617826,17.1899836063385,-0.07387331118212949,1739502656.861784,17.1899836063385,-0.03206404686376035,1739502656.8617854,17.1899836063385,-0.2178338523411978,1739502656.8617866,17.1899836063385,-0.05940754788927674,1739502656.8617878,17.1899836063385,2.100181248892076,1739502656.8617895,17.1899836063385,0.0,1739502656.8617907,17.1899836063385,0.011694286875799431,1739502656.861792,17.1899836063385,0.008999204479709574,1739502656.8617935,17.1899836063385,2.0884869620162765 +1739502656.8817132,17.209983587265015,34.586906783510294,1739502656.8817153,17.209983587265015,0.09623988775549197,1739502656.8817177,17.209983587265015,33.72031524778467,1739502656.88172,17.209983587265015,39.890507345688356,1739502656.8817213,17.209983587265015,-0.07387331118212949,1739502656.881723,17.209983587265015,-0.03206404686376035,1739502656.881724,17.209983587265015,-0.2178338523411978,1739502656.8817255,17.209983587265015,-0.05940754788927674,1739502656.8817267,17.209983587265015,2.100181248892076,1739502656.881728,17.209983587265015,0.0,1739502656.8817294,17.209983587265015,0.011694286875799431,1739502656.8817306,17.209983587265015,0.008999204479709574,1739502656.8817317,17.209983587265015,2.0884869620162765 +1739502656.9019551,17.22998356819153,34.8166968120731,1739502656.901958,17.22998356819153,0.09820130973275276,1739502656.9019608,17.22998356819153,33.97605578154143,1739502656.9019637,17.22998356819153,40.14879745349436,1739502656.9019651,17.22998356819153,-0.07657342879198549,1739502656.9019673,17.22998356819153,-0.03276610827582575,1739502656.901969,17.22998356819153,-0.21731452280750171,1739502656.9019701,17.22998356819153,-0.05863158641654347,1739502656.9019713,17.22998356819153,2.1010539790922813,1739502656.901973,17.22998356819153,0.0,1739502656.9019744,17.22998356819153,0.011098588876082872,1739502656.901976,17.22998356819153,0.007979181620385184,1739502656.9019773,17.22998356819153,2.089769234469234 +1739502656.921995,17.249983549118042,34.8166968120731,1739502656.9219975,17.249983549118042,0.09820130973275276,1739502656.9220004,17.249983549118042,33.97605578154143,1739502656.9220033,17.249983549118042,40.14879745349436,1739502656.9220045,17.249983549118042,-0.07657342879198549,1739502656.9220273,17.249983549118042,-0.03276610827582575,1739502656.9220285,17.249983549118042,-0.21731452280750171,1739502656.92203,17.249983549118042,-0.05863158641654347,1739502656.9220312,17.249983549118042,2.1010539790922813,1739502656.9220328,17.249983549118042,0.0,1739502656.9220343,17.249983549118042,0.011284744623047516,1739502656.9220355,17.249983549118042,0.007979181620385184,1739502656.922037,17.249983549118042,2.089769234469234 +1739502656.9421089,17.269983530044556,34.8166968120731,1739502656.9421113,17.269983530044556,0.09820130973275276,1739502656.942114,17.269983530044556,33.97605578154143,1739502656.9421165,17.269983530044556,40.14879745349436,1739502656.942118,17.269983530044556,-0.07657342879198549,1739502656.9421194,17.269983530044556,-0.03276610827582575,1739502656.942121,17.269983530044556,-0.21731452280750171,1739502656.9421222,17.269983530044556,-0.05863158641654347,1739502656.9421234,17.269983530044556,2.1010539790922813,1739502656.9421253,17.269983530044556,0.0,1739502656.9421265,17.269983530044556,0.011284744623047516,1739502656.942128,17.269983530044556,0.007979181620385184,1739502656.9421291,17.269983530044556,2.089769234469234 +1739502656.9680605,17.28998351097107,34.8166968120731,1739502656.9680707,17.28998351097107,0.09820130973275276,1739502656.9680817,17.28998351097107,33.97605578154143,1739502656.9680917,17.28998351097107,40.14879745349436,1739502656.9680965,17.28998351097107,-0.07657342879198549,1739502656.9681027,17.28998351097107,-0.03276610827582575,1739502656.9681077,17.28998351097107,-0.21731452280750171,1739502656.9681132,17.28998351097107,-0.05863158641654347,1739502656.9681177,17.28998351097107,2.1010539790922813,1739502656.9681234,17.28998351097107,0.0,1739502656.9681284,17.28998351097107,0.011284744623047516,1739502656.9681337,17.28998351097107,0.007979181620385184,1739502656.9681392,17.28998351097107,2.089769234469234 +1739502656.9870157,17.309983491897583,34.8166968120731,1739502656.9870257,17.309983491897583,0.09820130973275276,1739502656.987037,17.309983491897583,33.97605578154143,1739502656.9870474,17.309983491897583,40.14879745349436,1739502656.9870524,17.309983491897583,-0.07657342879198549,1739502656.9870589,17.309983491897583,-0.03276610827582575,1739502656.987064,17.309983491897583,-0.21731452280750171,1739502656.9870687,17.309983491897583,-0.05863158641654347,1739502656.9870732,17.309983491897583,2.1010539790922813,1739502656.987079,17.309983491897583,0.0,1739502656.9870837,17.309983491897583,0.011284744623047516,1739502656.9870887,17.309983491897583,0.007979181620385184,1739502656.9870934,17.309983491897583,2.089769234469234 +1739502657.0133696,17.329983472824097,34.8166968120731,1739502657.0133753,17.329983472824097,0.09820130973275276,1739502657.013383,17.329983472824097,33.97605578154143,1739502657.01339,17.329983472824097,40.14879745349436,1739502657.0133936,17.329983472824097,-0.07657342879198549,1739502657.013398,17.329983472824097,-0.03276610827582575,1739502657.0134015,17.329983472824097,-0.21731452280750171,1739502657.0134048,17.329983472824097,-0.05863158641654347,1739502657.0134082,17.329983472824097,2.1010539790922813,1739502657.0134122,17.329983472824097,0.0,1739502657.013416,17.329983472824097,0.011284744623047516,1739502657.0134196,17.329983472824097,0.007979181620385184,1739502657.0134232,17.329983472824097,2.089769234469234 +1739502657.0343435,17.359983444213867,35.046626467485424,1739502657.03435,17.359983444213867,0.099929375170972,1739502657.0343573,17.359983444213867,34.21326100725782,1739502657.0343647,17.359983444213867,40.388455508281666,1739502657.034368,17.359983444213867,-0.07863433155372662,1739502657.0343726,17.359983444213867,-0.0334150047169086,1739502657.0343761,17.359983444213867,-0.2157337191412315,1739502657.0343797,17.359983444213867,-0.05799094368515449,1739502657.0343833,17.359983444213867,2.103712742997966,1739502657.034387,17.359983444213867,0.0,1739502657.0343907,17.359983444213867,0.013360112475016924,1739502657.0343943,17.359983444213867,0.006959158761060786,1739502657.0343978,17.359983444213867,2.091001183401914 +1739502657.0517569,17.37998342514038,35.046626467485424,1739502657.0517602,17.37998342514038,0.099929375170972,1739502657.0517645,17.37998342514038,34.21326100725782,1739502657.0517683,17.37998342514038,40.388455508281666,1739502657.0517704,17.37998342514038,-0.07863433155372662,1739502657.0517726,17.37998342514038,-0.0334150047169086,1739502657.0517745,17.37998342514038,-0.2157337191412315,1739502657.0517764,17.37998342514038,-0.05799094368515449,1739502657.0517783,17.37998342514038,2.103712742997966,1739502657.0517805,17.37998342514038,0.0,1739502657.0517821,17.37998342514038,0.01271155959605208,1739502657.0517843,17.37998342514038,0.006959158761060786,1739502657.0517862,17.37998342514038,2.091001183401914 +1739502657.072795,17.399983406066895,35.046626467485424,1739502657.0727983,17.399983406066895,0.099929375170972,1739502657.0728018,17.399983406066895,34.21326100725782,1739502657.0728047,17.399983406066895,40.388455508281666,1739502657.072806,17.399983406066895,-0.07863433155372662,1739502657.072808,17.399983406066895,-0.0334150047169086,1739502657.0728095,17.399983406066895,-0.2157337191412315,1739502657.0728106,17.399983406066895,-0.05799094368515449,1739502657.072812,17.399983406066895,2.103712742997966,1739502657.0728137,17.399983406066895,0.0,1739502657.0728152,17.399983406066895,0.01271155959605208,1739502657.072817,17.399983406066895,0.006959158761060786,1739502657.0728188,17.399983406066895,2.091001183401914 +1739502657.0922978,17.419983386993408,35.046626467485424,1739502657.0923018,17.419983386993408,0.099929375170972,1739502657.0923066,17.419983386993408,34.21326100725782,1739502657.0923119,17.419983386993408,40.388455508281666,1739502657.0923147,17.419983386993408,-0.07863433155372662,1739502657.0923185,17.419983386993408,-0.0334150047169086,1739502657.0923216,17.419983386993408,-0.2157337191412315,1739502657.0923254,17.419983386993408,-0.05799094368515449,1739502657.0923288,17.419983386993408,2.103712742997966,1739502657.0923321,17.419983386993408,0.0,1739502657.0923355,17.419983386993408,0.01271155959605208,1739502657.0923388,17.419983386993408,0.006959158761060786,1739502657.092342,17.419983386993408,2.091001183401914 +1739502657.1123312,17.439983367919922,35.046626467485424,1739502657.1123345,17.439983367919922,0.099929375170972,1739502657.1123393,17.439983367919922,34.21326100725782,1739502657.112344,17.439983367919922,40.388455508281666,1739502657.1123471,17.439983367919922,-0.07863433155372662,1739502657.1123507,17.439983367919922,-0.0334150047169086,1739502657.1123543,17.439983367919922,-0.2157337191412315,1739502657.1123574,17.439983367919922,-0.05799094368515449,1739502657.1123607,17.439983367919922,2.103712742997966,1739502657.1123643,17.439983367919922,0.0,1739502657.1123676,17.439983367919922,0.01271155959605208,1739502657.112371,17.439983367919922,0.006959158761060786,1739502657.1123743,17.439983367919922,2.091001183401914 +1739502657.1324406,17.459983348846436,35.27669951101676,1739502657.1324441,17.459983348846436,0.10142382553458518,1739502657.1324487,17.459983348846436,34.561156626188804,1739502657.1324537,17.459983348846436,40.739068859950606,1739502657.1324565,17.459983348846436,-0.08212652645630397,1739502657.13246,17.459983348846436,-0.03359005996688026,1739502657.1324635,17.459983348846436,-0.21598867797150864,1739502657.1324668,17.459983348846436,-0.05552523218752678,1739502657.1324697,17.459983348846436,2.103283698642757,1739502657.1324732,17.459983348846436,0.0,1739502657.1324766,17.459983348846436,0.010088628258006186,1739502657.13248,17.459983348846436,0.005939135901736386,1739502657.1324832,17.459983348846436,2.0923754038041964 +1739502657.1525278,17.47998332977295,35.27669951101676,1739502657.1525314,17.47998332977295,0.10142382553458518,1739502657.152536,17.47998332977295,34.561156626188804,1739502657.152541,17.47998332977295,40.739068859950606,1739502657.1525438,17.47998332977295,-0.08212652645630397,1739502657.1525474,17.47998332977295,-0.03359005996688026,1739502657.1525505,17.47998332977295,-0.21598867797150864,1739502657.1525538,17.47998332977295,-0.05552523218752678,1739502657.152557,17.47998332977295,2.103283698642757,1739502657.1525602,17.47998332977295,0.0,1739502657.1525636,17.47998332977295,0.010908294838560817,1739502657.1525667,17.47998332977295,0.005939135901736386,1739502657.15257,17.47998332977295,2.0923754038041964 +1739502657.1719007,17.499983310699463,35.27669951101676,1739502657.1719046,17.499983310699463,0.10142382553458518,1739502657.1719089,17.499983310699463,34.561156626188804,1739502657.1719134,17.499983310699463,40.739068859950606,1739502657.171916,17.499983310699463,-0.08212652645630397,1739502657.1719196,17.499983310699463,-0.03359005996688026,1739502657.171923,17.499983310699463,-0.21598867797150864,1739502657.1719258,17.499983310699463,-0.05552523218752678,1739502657.1719291,17.499983310699463,2.103283698642757,1739502657.1719322,17.499983310699463,0.0,1739502657.1719353,17.499983310699463,0.010908294838560817,1739502657.1719387,17.499983310699463,0.005939135901736386,1739502657.171942,17.499983310699463,2.0923754038041964 +1739502657.192844,17.519983291625977,35.27669951101676,1739502657.192848,17.519983291625977,0.10142382553458518,1739502657.1928525,17.519983291625977,34.561156626188804,1739502657.1928573,17.519983291625977,40.739068859950606,1739502657.1928601,17.519983291625977,-0.08212652645630397,1739502657.1928637,17.519983291625977,-0.03359005996688026,1739502657.1928673,17.519983291625977,-0.21598867797150864,1739502657.1928706,17.519983291625977,-0.05552523218752678,1739502657.1928737,17.519983291625977,2.103283698642757,1739502657.192877,17.519983291625977,0.0,1739502657.1928804,17.519983291625977,0.010908294838560817,1739502657.1928837,17.519983291625977,0.005939135901736386,1739502657.192887,17.519983291625977,2.0923754038041964 +1739502657.212061,17.53998327255249,35.27669951101676,1739502657.212064,17.53998327255249,0.10142382553458518,1739502657.2120686,17.53998327255249,34.561156626188804,1739502657.2120736,17.53998327255249,40.739068859950606,1739502657.2120762,17.53998327255249,-0.08212652645630397,1739502657.2120798,17.53998327255249,-0.03359005996688026,1739502657.212083,17.53998327255249,-0.21598867797150864,1739502657.2120862,17.53998327255249,-0.05552523218752678,1739502657.2120895,17.53998327255249,2.103283698642757,1739502657.2121055,17.53998327255249,0.0,1739502657.2121086,17.53998327255249,0.010908294838560817,1739502657.2121117,17.53998327255249,0.005939135901736386,1739502657.212115,17.53998327255249,2.0923754038041964 +1739502657.23067,17.559983253479004,35.50691745660158,1739502657.2306721,17.559983253479004,0.10268438299602956,1739502657.2306745,17.559983253479004,35.22885385032268,1739502657.230677,17.559983253479004,41.409090303397285,1739502657.230678,17.559983253479004,-0.09066838673137677,1739502657.2306795,17.559983253479004,-0.03274787965548321,1739502657.230681,17.559983253479004,-0.22238376872760407,1739502657.2306821,17.559983253479004,-0.0489706705983596,1739502657.2306833,17.559983253479004,2.0925506255332875,1739502657.2306848,17.559983253479004,0.0,1739502657.230686,17.559983253479004,-0.006441297610305042,1739502657.2306871,17.559983253479004,0.004919113042411986,1739502657.2306883,17.559983253479004,2.093570171948545 +1739502657.2523906,17.579983234405518,35.50691745660158,1739502657.2523942,17.579983234405518,0.10268438299602956,1739502657.2523987,17.579983234405518,35.22885385032268,1739502657.2524037,17.579983234405518,41.409090303397285,1739502657.2524066,17.579983234405518,-0.09066838673137677,1739502657.2524104,17.579983234405518,-0.03274787965548321,1739502657.2524135,17.579983234405518,-0.22238376872760407,1739502657.2524168,17.579983234405518,-0.0489706705983596,1739502657.25242,17.579983234405518,2.0925506255332875,1739502657.2524235,17.579983234405518,0.0,1739502657.2524269,17.579983234405518,-0.0010195464152573663,1739502657.2524304,17.579983234405518,0.004919113042411986,1739502657.2524343,17.579983234405518,2.093570171948545 +1739502657.271014,17.59998321533203,35.50691745660158,1739502657.2710164,17.59998321533203,0.10268438299602956,1739502657.2710195,17.59998321533203,35.22885385032268,1739502657.2710223,17.59998321533203,41.409090303397285,1739502657.2710235,17.59998321533203,-0.09066838673137677,1739502657.2710252,17.59998321533203,-0.03274787965548321,1739502657.2710266,17.59998321533203,-0.22238376872760407,1739502657.271028,17.59998321533203,-0.0489706705983596,1739502657.2710295,17.59998321533203,2.0925506255332875,1739502657.2710311,17.59998321533203,0.0,1739502657.2710323,17.59998321533203,-0.0010195464152573663,1739502657.271034,17.59998321533203,0.004919113042411986,1739502657.2710354,17.59998321533203,2.093570171948545 +1739502657.292761,17.619983196258545,35.50691745660158,1739502657.2927644,17.619983196258545,0.10268438299602956,1739502657.292769,17.619983196258545,35.22885385032268,1739502657.2927742,17.619983196258545,41.409090303397285,1739502657.292777,17.619983196258545,-0.09066838673137677,1739502657.2927809,17.619983196258545,-0.03274787965548321,1739502657.2927842,17.619983196258545,-0.22238376872760407,1739502657.2927876,17.619983196258545,-0.0489706705983596,1739502657.2927904,17.619983196258545,2.0925506255332875,1739502657.2927942,17.619983196258545,0.0,1739502657.2927973,17.619983196258545,-0.0010195464152573663,1739502657.2928007,17.619983196258545,0.004919113042411986,1739502657.2928042,17.619983196258545,2.093570171948545 +1739502657.3110392,17.63998317718506,35.50691745660158,1739502657.311042,17.63998317718506,0.10268438299602956,1739502657.3110454,17.63998317718506,35.22885385032268,1739502657.311048,17.63998317718506,41.409090303397285,1739502657.3110495,17.63998317718506,-0.09066838673137677,1739502657.311051,17.63998317718506,-0.03274787965548321,1739502657.3110526,17.63998317718506,-0.22238376872760407,1739502657.311054,17.63998317718506,-0.0489706705983596,1739502657.3110554,17.63998317718506,2.0925506255332875,1739502657.3110569,17.63998317718506,0.0,1739502657.3110583,17.63998317718506,-0.0010195464152573663,1739502657.3110597,17.63998317718506,0.004919113042411986,1739502657.311062,17.63998317718506,2.093570171948545 +1739502657.3328006,17.659983158111572,35.50691745660158,1739502657.3328044,17.659983158111572,0.10268438299602956,1739502657.3328087,17.659983158111572,35.22885385032268,1739502657.3328137,17.659983158111572,41.409090303397285,1739502657.3328166,17.659983158111572,-0.09066838673137677,1739502657.332821,17.659983158111572,-0.03274787965548321,1739502657.332824,17.659983158111572,-0.22238376872760407,1739502657.3328276,17.659983158111572,-0.0489706705983596,1739502657.332831,17.659983158111572,2.0925506255332875,1739502657.3328345,17.659983158111572,0.0,1739502657.3328378,17.659983158111572,-0.0010195464152573663,1739502657.3328412,17.659983158111572,0.004919113042411986,1739502657.3328445,17.659983158111572,2.093570171948545 +1739502657.3522673,17.679983139038086,35.7371920268243,1739502657.3522704,17.679983139038086,0.10371037209999923,1739502657.352275,17.679983139038086,35.263856610985634,1739502657.35228,17.679983139038086,41.44364853815154,1739502657.3522828,17.679983139038086,-0.09132663882193419,1739502657.3522866,17.679983139038086,-0.03416500574983291,1739502657.3522897,17.679983139038086,-0.21728546054547812,1739502657.352293,17.679983139038086,-0.05118110967633384,1739502657.3522964,17.679983139038086,2.1011028287651645,1739502657.3522997,17.679983139038086,0.0,1739502657.3523033,17.679983139038086,0.01173875838587618,1739502657.3523066,17.679983139038086,0.0038990901830875868,1739502657.35231,17.679983139038086,2.0933510432437057 +1739502657.371069,17.6999831199646,35.7371920268243,1739502657.3710713,17.6999831199646,0.10371037209999923,1739502657.3710742,17.6999831199646,35.263856610985634,1739502657.3710768,17.6999831199646,41.44364853815154,1739502657.3710783,17.6999831199646,-0.09132663882193419,1739502657.37108,17.6999831199646,-0.03416500574983291,1739502657.371081,17.6999831199646,-0.21728546054547812,1739502657.3710828,17.6999831199646,-0.05118110967633384,1739502657.3710837,17.6999831199646,2.1011028287651645,1739502657.371086,17.6999831199646,0.0,1739502657.371087,17.6999831199646,0.007751785521458832,1739502657.3710883,17.6999831199646,0.0038990901830875868,1739502657.37109,17.6999831199646,2.0933510432437057 +1739502657.3908415,17.719983100891113,35.7371920268243,1739502657.3908436,17.719983100891113,0.10371037209999923,1739502657.3908465,17.719983100891113,35.263856610985634,1739502657.390849,17.719983100891113,41.44364853815154,1739502657.3908503,17.719983100891113,-0.09132663882193419,1739502657.3908522,17.719983100891113,-0.03416500574983291,1739502657.3908534,17.719983100891113,-0.21728546054547812,1739502657.3908546,17.719983100891113,-0.05118110967633384,1739502657.390856,17.719983100891113,2.1011028287651645,1739502657.3908575,17.719983100891113,0.0,1739502657.3908587,17.719983100891113,0.007751785521458832,1739502657.3908603,17.719983100891113,0.0038990901830875868,1739502657.3908615,17.719983100891113,2.0933510432437057 +1739502657.4110477,17.739983081817627,35.7371920268243,1739502657.4110503,17.739983081817627,0.10371037209999923,1739502657.4110534,17.739983081817627,35.263856610985634,1739502657.4110563,17.739983081817627,41.44364853815154,1739502657.4110577,17.739983081817627,-0.09132663882193419,1739502657.4110591,17.739983081817627,-0.03416500574983291,1739502657.4110608,17.739983081817627,-0.21728546054547812,1739502657.411062,17.739983081817627,-0.05118110967633384,1739502657.4110632,17.739983081817627,2.1011028287651645,1739502657.411065,17.739983081817627,0.0,1739502657.4110663,17.739983081817627,0.007751785521458832,1739502657.411068,17.739983081817627,0.0038990901830875868,1739502657.4110692,17.739983081817627,2.0933510432437057 +1739502657.4314353,17.75998306274414,35.7371920268243,1739502657.4314387,17.75998306274414,0.10371037209999923,1739502657.4314423,17.75998306274414,35.263856610985634,1739502657.431446,17.75998306274414,41.44364853815154,1739502657.4314477,17.75998306274414,-0.09132663882193419,1739502657.4314497,17.75998306274414,-0.03416500574983291,1739502657.4314513,17.75998306274414,-0.21728546054547812,1739502657.4314532,17.75998306274414,-0.05118110967633384,1739502657.4314551,17.75998306274414,2.1011028287651645,1739502657.431457,17.75998306274414,0.0,1739502657.4314585,17.75998306274414,0.007751785521458832,1739502657.4314601,17.75998306274414,0.0038990901830875868,1739502657.431462,17.75998306274414,2.0933510432437057 +1739502657.4515839,17.779983043670654,35.967499829500596,1739502657.4515862,17.779983043670654,0.10450157639324509,1739502657.4515893,17.779983043670654,35.29886418819673,1739502657.4515927,17.779983043670654,41.48033203929768,1739502657.4515944,17.779983043670654,-0.09201256640846867,1739502657.451596,17.779983043670654,-0.035631588780177526,1739502657.4515982,17.779983043670654,-0.21238512149623182,1739502657.4515996,17.779983043670654,-0.05359669991683034,1739502657.4516013,17.779983043670654,2.1093558883019803,1739502657.451603,17.779983043670654,0.0,1739502657.4516044,17.779983043670654,0.01853267853978247,1739502657.451606,17.779983043670654,0.002879067323763187,1739502657.4516075,17.779983043670654,2.094192241039333 +1739502657.4715846,17.799983024597168,35.967499829500596,1739502657.471588,17.799983024597168,0.10450157639324509,1739502657.4715915,17.799983024597168,35.29886418819673,1739502657.4715948,17.799983024597168,41.48033203929768,1739502657.4715962,17.799983024597168,-0.09201256640846867,1739502657.4715989,17.799983024597168,-0.035631588780177526,1739502657.4716005,17.799983024597168,-0.21238512149623182,1739502657.4716024,17.799983024597168,-0.05359669991683034,1739502657.4716039,17.799983024597168,2.1093558883019803,1739502657.471606,17.799983024597168,0.0,1739502657.4716074,17.799983024597168,0.015163647262647295,1739502657.4716094,17.799983024597168,0.002879067323763187,1739502657.4716108,17.799983024597168,2.094192241039333 +1739502657.494845,17.81998300552368,35.967499829500596,1739502657.4948525,17.81998300552368,0.10450157639324509,1739502657.4948633,17.81998300552368,35.29886418819673,1739502657.4948733,17.81998300552368,41.48033203929768,1739502657.4948783,17.81998300552368,-0.09201256640846867,1739502657.4948843,17.81998300552368,-0.035631588780177526,1739502657.4948895,17.81998300552368,-0.21238512149623182,1739502657.494894,17.81998300552368,-0.05359669991683034,1739502657.4948993,17.81998300552368,2.1093558883019803,1739502657.4949045,17.81998300552368,0.0,1739502657.4949095,17.81998300552368,0.015163647262647295,1739502657.4949143,17.81998300552368,0.002879067323763187,1739502657.4949195,17.81998300552368,2.094192241039333 +1739502657.5195978,17.839982986450195,35.967499829500596,1739502657.5196111,17.839982986450195,0.10450157639324509,1739502657.5196245,17.839982986450195,35.29886418819673,1739502657.5196385,17.839982986450195,41.48033203929768,1739502657.5196497,17.839982986450195,-0.09201256640846867,1739502657.5196624,17.839982986450195,-0.035631588780177526,1739502657.5196733,17.839982986450195,-0.21238512149623182,1739502657.5196843,17.839982986450195,-0.05359669991683034,1739502657.5196955,17.839982986450195,2.1093558883019803,1739502657.5197155,17.839982986450195,0.0,1739502657.5197268,17.839982986450195,0.015163647262647295,1739502657.5197382,17.839982986450195,0.002879067323763187,1739502657.5197473,17.839982986450195,2.094192241039333 +1739502657.533767,17.85998296737671,35.967499829500596,1739502657.5337722,17.85998296737671,0.10450157639324509,1739502657.5337787,17.85998296737671,35.29886418819673,1739502657.5337858,17.85998296737671,41.48033203929768,1739502657.5337896,17.85998296737671,-0.09201256640846867,1739502657.533795,17.85998296737671,-0.035631588780177526,1739502657.5337996,17.85998296737671,-0.21238512149623182,1739502657.5338042,17.85998296737671,-0.05359669991683034,1739502657.533809,17.85998296737671,2.1093558883019803,1739502657.5338135,17.85998296737671,0.0,1739502657.533818,17.85998296737671,0.015163647262647295,1739502657.5338228,17.85998296737671,0.002879067323763187,1739502657.5338273,17.85998296737671,2.094192241039333 +1739502657.5526214,17.879982948303223,35.967499829500596,1739502657.5526252,17.879982948303223,0.10450157639324509,1739502657.5526297,17.879982948303223,35.29886418819673,1739502657.5526347,17.879982948303223,41.48033203929768,1739502657.5526373,17.879982948303223,-0.09201256640846867,1739502657.552641,17.879982948303223,-0.035631588780177526,1739502657.5526443,17.879982948303223,-0.21238512149623182,1739502657.5526476,17.879982948303223,-0.05359669991683034,1739502657.5526507,17.879982948303223,2.1093558883019803,1739502657.552654,17.879982948303223,0.0,1739502657.5526574,17.879982948303223,0.015163647262647295,1739502657.5526607,17.879982948303223,0.002879067323763187,1739502657.552664,17.879982948303223,2.094192241039333 +1739502657.5737274,17.899982929229736,36.197949840600515,1739502657.5737305,17.899982929229736,0.10505819533770833,1739502657.5737348,17.899982929229736,35.553284589607145,1739502657.5737395,17.899982929229736,41.73817482639052,1739502657.5737422,17.899982929229736,-0.095890091063972,1739502657.5737457,17.899982929229736,-0.03625488782980238,1739502657.5737488,17.899982929229736,-0.21124745781746013,1739502657.573752,17.899982929229736,-0.05278154819205316,1739502657.5737548,17.899982929229736,2.11127655226103,1739502657.573758,17.899982929229736,0.0,1739502657.573761,17.899982929229736,0.015445117928195919,1739502657.5737643,17.899982929229736,0.0018590444644387876,1739502657.5737674,17.899982929229736,2.095919393973489 +1739502657.591058,17.91998291015625,36.197949840600515,1739502657.5910602,17.91998291015625,0.10505819533770833,1739502657.5910633,17.91998291015625,35.553284589607145,1739502657.591066,17.91998291015625,41.73817482639052,1739502657.591067,17.91998291015625,-0.095890091063972,1739502657.5910687,17.91998291015625,-0.03625488782980238,1739502657.5910704,17.91998291015625,-0.21124745781746013,1739502657.5910716,17.91998291015625,-0.05278154819205316,1739502657.5910728,17.91998291015625,2.11127655226103,1739502657.5910742,17.91998291015625,0.0,1739502657.5910757,17.91998291015625,0.01535715828754114,1739502657.591077,17.91998291015625,0.0018590444644387876,1739502657.5910783,17.91998291015625,2.095919393973489 +1739502657.6114788,17.939982891082764,36.197949840600515,1739502657.6114812,17.939982891082764,0.10505819533770833,1739502657.6114836,17.939982891082764,35.553284589607145,1739502657.6114864,17.939982891082764,41.73817482639052,1739502657.611488,17.939982891082764,-0.095890091063972,1739502657.6114898,17.939982891082764,-0.03625488782980238,1739502657.611491,17.939982891082764,-0.21124745781746013,1739502657.6114924,17.939982891082764,-0.05278154819205316,1739502657.6114936,17.939982891082764,2.11127655226103,1739502657.6114953,17.939982891082764,0.0,1739502657.6114962,17.939982891082764,0.01535715828754114,1739502657.6114976,17.939982891082764,0.0018590444644387876,1739502657.611499,17.939982891082764,2.095919393973489 +1739502657.632011,17.959982872009277,36.197949840600515,1739502657.6320133,17.959982872009277,0.10505819533770833,1739502657.6320162,17.959982872009277,35.553284589607145,1739502657.6320188,17.959982872009277,41.73817482639052,1739502657.63202,17.959982872009277,-0.095890091063972,1739502657.6320214,17.959982872009277,-0.03625488782980238,1739502657.6320229,17.959982872009277,-0.21124745781746013,1739502657.632024,17.959982872009277,-0.05278154819205316,1739502657.632025,17.959982872009277,2.11127655226103,1739502657.6320267,17.959982872009277,0.0,1739502657.6320279,17.959982872009277,0.01535715828754114,1739502657.6320293,17.959982872009277,0.0018590444644387876,1739502657.6320307,17.959982872009277,2.095919393973489 +1739502657.6525455,17.97998285293579,36.197949840600515,1739502657.6525493,17.97998285293579,0.10505819533770833,1739502657.6525545,17.97998285293579,35.553284589607145,1739502657.6525598,17.97998285293579,41.73817482639052,1739502657.6525629,17.97998285293579,-0.095890091063972,1739502657.6525667,17.97998285293579,-0.03625488782980238,1739502657.6525705,17.97998285293579,-0.21124745781746013,1739502657.6525736,17.97998285293579,-0.05278154819205316,1739502657.6525772,17.97998285293579,2.11127655226103,1739502657.652581,17.97998285293579,0.0,1739502657.6525846,17.97998285293579,0.01535715828754114,1739502657.6525881,17.97998285293579,0.0018590444644387876,1739502657.6525917,17.97998285293579,2.095919393973489 +1739502657.6712663,17.999982833862305,36.42858476959887,1739502657.671269,17.999982833862305,0.10538000739741804,1739502657.6712723,17.999982833862305,35.58303681725999,1739502657.6712754,17.999982833862305,41.771280760557694,1739502657.6712766,17.999982833862305,-0.09651473133127722,1739502657.6712782,17.999982833862305,-0.037770952949319425,1739502657.67128,17.999982833862305,-0.2063773045061076,1739502657.6712813,17.999982833862305,-0.055441255187339826,1739502657.6712828,17.999982833862305,2.119518389834024,1739502657.6712842,17.999982833862305,0.0,1739502657.6712854,17.999982833862305,0.024901943912700383,1739502657.671287,17.999982833862305,0.000839021605114388,1739502657.6712883,17.999982833862305,2.0975991933848275 +1739502657.691106,18.01998281478882,36.42858476959887,1739502657.6911087,18.01998281478882,0.10538000739741804,1739502657.6911113,18.01998281478882,35.58303681725999,1739502657.6911142,18.01998281478882,41.771280760557694,1739502657.6911159,18.01998281478882,-0.09651473133127722,1739502657.6911173,18.01998281478882,-0.037770952949319425,1739502657.6911192,18.01998281478882,-0.2063773045061076,1739502657.6911204,18.01998281478882,-0.055441255187339826,1739502657.6911216,18.01998281478882,2.119518389834024,1739502657.6911235,18.01998281478882,0.0,1739502657.6911247,18.01998281478882,0.021919196449196487,1739502657.6911263,18.01998281478882,0.000839021605114388,1739502657.6911278,18.01998281478882,2.0975991933848275 +1739502657.71175,18.039982795715332,36.42858476959887,1739502657.7117527,18.039982795715332,0.10538000739741804,1739502657.7117558,18.039982795715332,35.58303681725999,1739502657.711759,18.039982795715332,41.771280760557694,1739502657.711761,18.039982795715332,-0.09651473133127722,1739502657.7117627,18.039982795715332,-0.037770952949319425,1739502657.7117639,18.039982795715332,-0.2063773045061076,1739502657.7117658,18.039982795715332,-0.055441255187339826,1739502657.711767,18.039982795715332,2.119518389834024,1739502657.7117689,18.039982795715332,0.0,1739502657.71177,18.039982795715332,0.021919196449196487,1739502657.7117715,18.039982795715332,0.000839021605114388,1739502657.711773,18.039982795715332,2.0975991933848275 +1739502657.7328176,18.059982776641846,36.42858476959887,1739502657.7328212,18.059982776641846,0.10538000739741804,1739502657.7328258,18.059982776641846,35.58303681725999,1739502657.7328312,18.059982776641846,41.771280760557694,1739502657.7328343,18.059982776641846,-0.09651473133127722,1739502657.7328382,18.059982776641846,-0.037770952949319425,1739502657.7328417,18.059982776641846,-0.2063773045061076,1739502657.7328453,18.059982776641846,-0.055441255187339826,1739502657.7328486,18.059982776641846,2.119518389834024,1739502657.7328522,18.059982776641846,0.0,1739502657.7328558,18.059982776641846,0.021919196449196487,1739502657.7328594,18.059982776641846,0.000839021605114388,1739502657.732863,18.059982776641846,2.0975991933848275 +1739502657.7514513,18.07998275756836,36.42858476959887,1739502657.751454,18.07998275756836,0.10538000739741804,1739502657.7514572,18.07998275756836,35.58303681725999,1739502657.7514603,18.07998275756836,41.771280760557694,1739502657.751462,18.07998275756836,-0.09651473133127722,1739502657.7514637,18.07998275756836,-0.037770952949319425,1739502657.7514653,18.07998275756836,-0.2063773045061076,1739502657.7514665,18.07998275756836,-0.055441255187339826,1739502657.751468,18.07998275756836,2.119518389834024,1739502657.7514696,18.07998275756836,0.0,1739502657.7514708,18.07998275756836,0.021919196449196487,1739502657.7514725,18.07998275756836,0.000839021605114388,1739502657.751474,18.07998275756836,2.0975991933848275 +1739502657.7727168,18.099982738494873,36.42858476959887,1739502657.7727242,18.099982738494873,0.10538000739741804,1739502657.7727304,18.099982738494873,35.58303681725999,1739502657.7727337,18.099982738494873,41.771280760557694,1739502657.7727363,18.099982738494873,-0.09651473133127722,1739502657.7727382,18.099982738494873,-0.037770952949319425,1739502657.7727406,18.099982738494873,-0.2063773045061076,1739502657.772743,18.099982738494873,-0.055441255187339826,1739502657.772745,18.099982738494873,2.119518389834024,1739502657.7727478,18.099982738494873,0.0,1739502657.7727501,18.099982738494873,0.021919196449196487,1739502657.7727525,18.099982738494873,0.000839021605114388,1739502657.772755,18.099982738494873,2.0975991933848275 +1739502657.7927303,18.119982719421387,36.65944652333276,1739502657.7927356,18.119982719421387,0.105466644449983,1739502657.7927413,18.119982719421387,36.297391000374375,1739502657.7927487,18.119982719421387,42.4904452061596,1739502657.792753,18.119982719421387,-0.10834206286587447,1739502657.7927582,18.119982719421387,-0.03665117646754546,1739502657.792763,18.119982719421387,-0.21275328574439195,1739502657.7927678,18.119982719421387,-0.04798782252039783,1739502657.7927723,18.119982719421387,2.108734708245211,1739502657.7927773,18.119982719421387,0.0,1739502657.7927818,18.119982719421387,0.0026568310093212618,1739502657.7927866,18.119982719421387,6.283004305925377,1739502657.7927914,18.119982719421387,2.1000583840892415 +1739502657.8114529,18.1399827003479,36.65944652333276,1739502657.8114555,18.1399827003479,0.105466644449983,1739502657.8114588,18.1399827003479,36.297391000374375,1739502657.8114617,18.1399827003479,42.4904452061596,1739502657.811463,18.1399827003479,-0.10834206286587447,1739502657.811465,18.1399827003479,-0.03665117646754546,1739502657.8114665,18.1399827003479,-0.21275328574439195,1739502657.8114681,18.1399827003479,-0.04798782252039783,1739502657.8114693,18.1399827003479,2.108734708245211,1739502657.8114717,18.1399827003479,0.0,1739502657.811473,18.1399827003479,0.008676324155969528,1739502657.8114743,18.1399827003479,6.283004305925377,1739502657.811476,18.1399827003479,2.1000583840892415 +1739502657.8309834,18.159982681274414,36.65944652333276,1739502657.830986,18.159982681274414,0.105466644449983,1739502657.830989,18.159982681274414,36.297391000374375,1739502657.830992,18.159982681274414,42.4904452061596,1739502657.8309932,18.159982681274414,-0.10834206286587447,1739502657.8309948,18.159982681274414,-0.03665117646754546,1739502657.8309968,18.159982681274414,-0.21275328574439195,1739502657.830998,18.159982681274414,-0.04798782252039783,1739502657.8309996,18.159982681274414,2.108734708245211,1739502657.831001,18.159982681274414,0.0,1739502657.8310025,18.159982681274414,0.008676324155969528,1739502657.831004,18.159982681274414,6.283004305925377,1739502657.8310053,18.159982681274414,2.1000583840892415 +1739502657.8527472,18.179982662200928,36.65944652333276,1739502657.8527496,18.179982662200928,0.105466644449983,1739502657.8527524,18.179982662200928,36.297391000374375,1739502657.8527553,18.179982662200928,42.4904452061596,1739502657.8527565,18.179982662200928,-0.10834206286587447,1739502657.8527582,18.179982662200928,-0.03665117646754546,1739502657.8527596,18.179982662200928,-0.21275328574439195,1739502657.8527608,18.179982662200928,-0.04798782252039783,1739502657.8527625,18.179982662200928,2.108734708245211,1739502657.852764,18.179982662200928,0.0,1739502657.852765,18.179982662200928,0.008676324155969528,1739502657.8527668,18.179982662200928,6.283004305925377,1739502657.8527684,18.179982662200928,2.1000583840892415 +1739502657.8709714,18.19998264312744,36.65944652333276,1739502657.870974,18.19998264312744,0.105466644449983,1739502657.8709767,18.19998264312744,36.297391000374375,1739502657.87098,18.19998264312744,42.4904452061596,1739502657.8709815,18.19998264312744,-0.10834206286587447,1739502657.8709834,18.19998264312744,-0.03665117646754546,1739502657.8709857,18.19998264312744,-0.21275328574439195,1739502657.8709872,18.19998264312744,-0.04798782252039783,1739502657.8709886,18.19998264312744,2.108734708245211,1739502657.8709903,18.19998264312744,0.0,1739502657.870992,18.19998264312744,0.008676324155969528,1739502657.8709934,18.19998264312744,6.283004305925377,1739502657.870995,18.19998264312744,2.1000583840892415 +1739502657.8915415,18.219982624053955,36.89050324110286,1739502657.8915439,18.219982624053955,0.10531768593398283,1739502657.891547,18.219982624053955,36.32812139487928,1739502657.8915496,18.219982624053955,42.52308840565507,1739502657.891551,18.219982624053955,-0.1089821256010798,1739502657.8915527,18.219982624053955,-0.03802809776985338,1739502657.8915544,18.219982624053955,-0.2075347879979216,1739502657.8915555,18.219982624053955,-0.05016119989417237,1739502657.8915572,18.219982624053955,2.117556652208302,1739502657.891559,18.219982624053955,0.0,1739502657.8915606,18.219982624053955,0.020112551865171868,1739502657.891562,18.219982624053955,6.281984283066052,1739502657.8915632,18.219982624053955,2.101017923845437 +1739502657.9114373,18.23998260498047,36.89050324110286,1739502657.9114404,18.23998260498047,0.10531768593398283,1739502657.9114437,18.23998260498047,36.32812139487928,1739502657.9114468,18.23998260498047,42.52308840565507,1739502657.9114482,18.23998260498047,-0.1089821256010798,1739502657.9114501,18.23998260498047,-0.03802809776985338,1739502657.9114516,18.23998260498047,-0.2075347879979216,1739502657.9114532,18.23998260498047,-0.05016119989417237,1739502657.9114544,18.23998260498047,2.117556652208302,1739502657.911456,18.23998260498047,0.0,1739502657.9114573,18.23998260498047,0.016538728362864852,1739502657.9114587,18.23998260498047,6.281984283066052,1739502657.9114604,18.23998260498047,2.101017923845437 +1739502657.931348,18.259982585906982,36.89050324110286,1739502657.9313505,18.259982585906982,0.10531768593398283,1739502657.9313538,18.259982585906982,36.32812139487928,1739502657.931357,18.259982585906982,42.52308840565507,1739502657.9313586,18.259982585906982,-0.1089821256010798,1739502657.9313605,18.259982585906982,-0.03802809776985338,1739502657.9313622,18.259982585906982,-0.2075347879979216,1739502657.9313638,18.259982585906982,-0.05016119989417237,1739502657.931365,18.259982585906982,2.117556652208302,1739502657.931367,18.259982585906982,0.0,1739502657.9313684,18.259982585906982,0.016538728362864852,1739502657.93137,18.259982585906982,6.281984283066052,1739502657.9313715,18.259982585906982,2.101017923845437 +1739502657.951649,18.279982566833496,36.89050324110286,1739502657.9516516,18.279982566833496,0.10531768593398283,1739502657.951655,18.279982566833496,36.32812139487928,1739502657.951658,18.279982566833496,42.52308840565507,1739502657.9516594,18.279982566833496,-0.1089821256010798,1739502657.9516613,18.279982566833496,-0.03802809776985338,1739502657.9516628,18.279982566833496,-0.2075347879979216,1739502657.9516644,18.279982566833496,-0.05016119989417237,1739502657.9516656,18.279982566833496,2.117556652208302,1739502657.9516678,18.279982566833496,0.0,1739502657.9516695,18.279982566833496,0.016538728362864852,1739502657.9516711,18.279982566833496,6.281984283066052,1739502657.9516726,18.279982566833496,2.101017923845437 +1739502657.9728963,18.29998254776001,36.89050324110286,1739502657.972899,18.29998254776001,0.10531768593398283,1739502657.972902,18.29998254776001,36.32812139487928,1739502657.9729054,18.29998254776001,42.52308840565507,1739502657.972907,18.29998254776001,-0.1089821256010798,1739502657.9729087,18.29998254776001,-0.03802809776985338,1739502657.9729106,18.29998254776001,-0.2075347879979216,1739502657.972912,18.29998254776001,-0.05016119989417237,1739502657.9729135,18.29998254776001,2.117556652208302,1739502657.9729152,18.29998254776001,0.0,1739502657.9729168,18.29998254776001,0.016538728362864852,1739502657.9729185,18.29998254776001,6.281984283066052,1739502657.9729202,18.29998254776001,2.101017923845437 +1739502657.9916844,18.319982528686523,36.89050324110286,1739502657.9916878,18.319982528686523,0.10531768593398283,1739502657.991691,18.319982528686523,36.32812139487928,1739502657.991694,18.319982528686523,42.52308840565507,1739502657.9916956,18.319982528686523,-0.1089821256010798,1739502657.9916973,18.319982528686523,-0.03802809776985338,1739502657.9916992,18.319982528686523,-0.2075347879979216,1739502657.9917006,18.319982528686523,-0.05016119989417237,1739502657.9917023,18.319982528686523,2.117556652208302,1739502657.9917042,18.319982528686523,0.0,1739502657.991706,18.319982528686523,0.016538728362864852,1739502657.9917073,18.319982528686523,6.281984283066052,1739502657.9917092,18.319982528686523,2.101017923845437 +1739502658.012938,18.339982509613037,37.1217123584171,1739502658.012942,18.339982509613037,0.10493278123846217,1739502658.0129476,18.339982509613037,36.358871822577385,1739502658.0129535,18.339982509613037,42.557595603315,1739502658.0129569,18.339982509613037,-0.10966525947158418,1739502658.0129614,18.339982509613037,-0.03945755461532591,1739502658.0129652,18.339982509613037,-0.20252416929937744,1739502658.012969,18.339982509613037,-0.05255052854743525,1739502658.0129728,18.339982509613037,2.126061902611861,1739502658.012977,18.339982509613037,0.0,1739502658.0129807,18.339982509613037,0.026172890900288917,1739502658.0129845,18.339982509613037,6.280964260206727,1739502658.0129886,18.339982509613037,2.102899689478471 +1739502658.0415154,18.35998249053955,37.1217123584171,1739502658.0415242,18.35998249053955,0.10493278123846217,1739502658.0415344,18.35998249053955,36.358871822577385,1739502658.0415444,18.35998249053955,42.557595603315,1739502658.0415497,18.35998249053955,-0.10966525947158418,1739502658.0415554,18.35998249053955,-0.03945755461532591,1739502658.0415604,18.35998249053955,-0.20252416929937744,1739502658.0415652,18.35998249053955,-0.05255052854743525,1739502658.04157,18.35998249053955,2.126061902611861,1739502658.0415757,18.35998249053955,0.0,1739502658.041581,18.35998249053955,0.02316221313338973,1739502658.041586,18.35998249053955,6.280964260206727,1739502658.041591,18.35998249053955,2.102899689478471 +1739502658.072805,18.379982471466064,37.1217123584171,1739502658.0728106,18.379982471466064,0.10493278123846217,1739502658.0728178,18.379982471466064,36.358871822577385,1739502658.0728245,18.379982471466064,42.557595603315,1739502658.0728278,18.379982471466064,-0.10966525947158418,1739502658.0728323,18.379982471466064,-0.03945755461532591,1739502658.072836,18.379982471466064,-0.20252416929937744,1739502658.0728395,18.379982471466064,-0.05255052854743525,1739502658.0728428,18.379982471466064,2.126061902611861,1739502658.072847,18.379982471466064,0.0,1739502658.0728502,18.379982471466064,0.02316221313338973,1739502658.0728543,18.379982471466064,6.280964260206727,1739502658.0728579,18.379982471466064,2.102899689478471 +1739502658.084484,18.409982442855835,37.1217123584171,1739502658.084491,18.409982442855835,0.10493278123846217,1739502658.0844991,18.409982442855835,36.358871822577385,1739502658.084507,18.409982442855835,42.557595603315,1739502658.0845106,18.409982442855835,-0.10966525947158418,1739502658.084515,18.409982442855835,-0.03945755461532591,1739502658.0845187,18.409982442855835,-0.20252416929937744,1739502658.0845225,18.409982442855835,-0.05255052854743525,1739502658.084526,18.409982442855835,2.126061902611861,1739502658.08453,18.409982442855835,0.0,1739502658.0845337,18.409982442855835,0.02316221313338973,1739502658.0845373,18.409982442855835,6.280964260206727,1739502658.084541,18.409982442855835,2.102899689478471 +1739502658.1030002,18.42998242378235,37.1217123584171,1739502658.1030045,18.42998242378235,0.10493278123846217,1739502658.1030087,18.42998242378235,36.358871822577385,1739502658.1030123,18.42998242378235,42.557595603315,1739502658.1030145,18.42998242378235,-0.10966525947158418,1739502658.1030166,18.42998242378235,-0.03945755461532591,1739502658.103019,18.42998242378235,-0.20252416929937744,1739502658.103021,18.42998242378235,-0.05255052854743525,1739502658.1030226,18.42998242378235,2.126061902611861,1739502658.1030252,18.42998242378235,0.0,1739502658.103027,18.42998242378235,0.02316221313338973,1739502658.103029,18.42998242378235,6.280964260206727,1739502658.1030312,18.42998242378235,2.102899689478471 +1739502658.122973,18.449982404708862,37.35315795462964,1739502658.1229773,18.449982404708862,0.10431139501524544,1739502658.1229827,18.449982404708862,36.85321938278743,1739502658.1229868,18.449982404708862,43.05696260827141,1739502658.1229887,18.449982404708862,-0.11880601008184657,1739502658.122991,18.449982404708862,-0.039097360626499315,1739502658.1229932,18.449982404708862,-0.20462983639958746,1739502658.122995,18.449982404708862,-0.04822802111464228,1739502658.1229968,18.449982404708862,2.1224834945514286,1739502658.1229987,18.449982404708862,0.0,1739502658.1230006,18.449982404708862,0.01423585718074313,1739502658.1230028,18.449982404708862,6.279944237347403,1739502658.123005,18.449982404708862,2.1054581493065525 +1739502658.1428711,18.469982385635376,37.35315795462964,1739502658.1428766,18.469982385635376,0.10431139501524544,1739502658.1428833,18.469982385635376,36.85321938278743,1739502658.1428907,18.469982385635376,43.05696260827141,1739502658.1428947,18.469982385635376,-0.11880601008184657,1739502658.1428998,18.469982385635376,-0.039097360626499315,1739502658.1429045,18.469982385635376,-0.20462983639958746,1739502658.1429088,18.469982385635376,-0.04822802111464228,1739502658.142913,18.469982385635376,2.1224834945514286,1739502658.1429176,18.469982385635376,0.0,1739502658.142922,18.469982385635376,0.01702534524487609,1739502658.1429265,18.469982385635376,6.279944237347403,1739502658.1429307,18.469982385635376,2.1054581493065525 +1739502658.1623652,18.48998236656189,37.35315795462964,1739502658.1623712,18.48998236656189,0.10431139501524544,1739502658.1623778,18.48998236656189,36.85321938278743,1739502658.162385,18.48998236656189,43.05696260827141,1739502658.1623893,18.48998236656189,-0.11880601008184657,1739502658.1623943,18.48998236656189,-0.039097360626499315,1739502658.1623993,18.48998236656189,-0.20462983639958746,1739502658.1624036,18.48998236656189,-0.04822802111464228,1739502658.1624074,18.48998236656189,2.1224834945514286,1739502658.1624124,18.48998236656189,0.0,1739502658.162417,18.48998236656189,0.01702534524487609,1739502658.1624217,18.48998236656189,6.279944237347403,1739502658.1624267,18.48998236656189,2.1054581493065525 +1739502658.1875331,18.509982347488403,37.35315795462964,1739502658.1875427,18.509982347488403,0.10431139501524544,1739502658.1875541,18.509982347488403,36.85321938278743,1739502658.1875656,18.509982347488403,43.05696260827141,1739502658.1875699,18.509982347488403,-0.11880601008184657,1739502658.1875763,18.509982347488403,-0.039097360626499315,1739502658.1875813,18.509982347488403,-0.20462983639958746,1739502658.1875858,18.509982347488403,-0.04822802111464228,1739502658.1875906,18.509982347488403,2.1224834945514286,1739502658.187596,18.509982347488403,0.0,1739502658.1876009,18.509982347488403,0.01702534524487609,1739502658.1876063,18.509982347488403,6.279944237347403,1739502658.1876113,18.509982347488403,2.1054581493065525 +1739502658.2071366,18.529982328414917,37.35315795462964,1739502658.2071428,18.529982328414917,0.10431139501524544,1739502658.207151,18.529982328414917,36.85321938278743,1739502658.2071579,18.529982328414917,43.05696260827141,1739502658.207161,18.529982328414917,-0.11880601008184657,1739502658.2071652,18.529982328414917,-0.039097360626499315,1739502658.2071688,18.529982328414917,-0.20462983639958746,1739502658.2071726,18.529982328414917,-0.04822802111464228,1739502658.2071762,18.529982328414917,2.1224834945514286,1739502658.2071803,18.529982328414917,0.0,1739502658.2071838,18.529982328414917,0.01702534524487609,1739502658.2071874,18.529982328414917,6.279944237347403,1739502658.207191,18.529982328414917,2.1054581493065525 +1739502658.2274983,18.54998230934143,37.58485128328884,1739502658.2275057,18.54998230934143,0.10345301594667067,1739502658.2275155,18.54998230934143,36.88426543044869,1739502658.227526,18.54998230934143,43.091738484634746,1739502658.2275317,18.54998230934143,-0.11938240582267541,1739502658.2275393,18.54998230934143,-0.04044279627242325,1739502658.2275462,18.54998230934143,-0.19936811297401408,1739502658.2275527,18.54998230934143,-0.05040262517869,1739502658.2275593,18.54998230934143,2.1314366618664495,1739502658.2275662,18.54998230934143,0.0,1739502658.2275732,18.54998230934143,0.027332060677027432,1739502658.22758,18.54998230934143,6.278924214488079,1739502658.2275867,18.54998230934143,2.1073254518737237 +1739502658.2432277,18.569982290267944,37.58485128328884,1739502658.2432325,18.569982290267944,0.10345301594667067,1739502658.243237,18.569982290267944,36.88426543044869,1739502658.243241,18.569982290267944,43.091738484634746,1739502658.2432427,18.569982290267944,-0.11938240582267541,1739502658.2432454,18.569982290267944,-0.04044279627242325,1739502658.2432473,18.569982290267944,-0.19936811297401408,1739502658.2432494,18.569982290267944,-0.05040262517869,1739502658.2432516,18.569982290267944,2.1314366618664495,1739502658.2432537,18.569982290267944,0.0,1739502658.2432556,18.569982290267944,0.02411120999272587,1739502658.2432575,18.569982290267944,6.278924214488079,1739502658.2432594,18.569982290267944,2.1073254518737237 +1739502658.2634673,18.589982271194458,37.58485128328884,1739502658.2634716,18.589982271194458,0.10345301594667067,1739502658.263476,18.589982271194458,36.88426543044869,1739502658.2634797,18.589982271194458,43.091738484634746,1739502658.2634816,18.589982271194458,-0.11938240582267541,1739502658.2634842,18.589982271194458,-0.04044279627242325,1739502658.2634864,18.589982271194458,-0.19936811297401408,1739502658.263489,18.589982271194458,-0.05040262517869,1739502658.263491,18.589982271194458,2.1314366618664495,1739502658.2634933,18.589982271194458,0.0,1739502658.263496,18.589982271194458,0.02411120999272587,1739502658.263498,18.589982271194458,6.278924214488079,1739502658.2635,18.589982271194458,2.1073254518737237 +1739502658.2839692,18.60998225212097,37.58485128328884,1739502658.2839742,18.60998225212097,0.10345301594667067,1739502658.2839792,18.60998225212097,36.88426543044869,1739502658.283985,18.60998225212097,43.091738484634746,1739502658.283988,18.60998225212097,-0.11938240582267541,1739502658.283992,18.60998225212097,-0.04044279627242325,1739502658.2839956,18.60998225212097,-0.19936811297401408,1739502658.2839992,18.60998225212097,-0.05040262517869,1739502658.2840028,18.60998225212097,2.1314366618664495,1739502658.2840064,18.60998225212097,0.0,1739502658.28401,18.60998225212097,0.02411120999272587,1739502658.2840137,18.60998225212097,6.278924214488079,1739502658.2840176,18.60998225212097,2.1073254518737237 +1739502658.312004,18.629982233047485,37.58485128328884,1739502658.3120115,18.629982233047485,0.10345301594667067,1739502658.3120208,18.629982233047485,36.88426543044869,1739502658.3120315,18.629982233047485,43.091738484634746,1739502658.3120375,18.629982233047485,-0.11938240582267541,1739502658.312045,18.629982233047485,-0.04044279627242325,1739502658.312052,18.629982233047485,-0.19936811297401408,1739502658.3120587,18.629982233047485,-0.05040262517869,1739502658.3120654,18.629982233047485,2.1314366618664495,1739502658.3120728,18.629982233047485,0.0,1739502658.3120794,18.629982233047485,0.02411120999272587,1739502658.3120863,18.629982233047485,6.278924214488079,1739502658.3120933,18.629982233047485,2.1073254518737237 +1739502658.3257742,18.649982213974,37.58485128328884,1739502658.3257804,18.649982213974,0.10345301594667067,1739502658.3257885,18.649982213974,36.88426543044869,1739502658.3257966,18.649982213974,43.091738484634746,1739502658.3257995,18.649982213974,-0.11938240582267541,1739502658.325804,18.649982213974,-0.04044279627242325,1739502658.3258102,18.649982213974,-0.19936811297401408,1739502658.3258154,18.649982213974,-0.05040262517869,1739502658.3258183,18.649982213974,2.1314366618664495,1739502658.3258207,18.649982213974,0.0,1739502658.325823,18.649982213974,0.02411120999272587,1739502658.325825,18.649982213974,6.278924214488079,1739502658.3258271,18.649982213974,2.1073254518737237 +1739502658.3445892,18.669982194900513,37.8167928253646,1739502658.3445942,18.669982194900513,0.10235711953415816,1739502658.3445995,18.669982194900513,37.03230602530713,1739502658.344605,18.669982194900513,43.24517595310344,1739502658.344608,18.669982194900513,-0.12116175953103442,1739502658.3446136,18.669982194900513,-0.041152711544168184,1739502658.3446171,18.669982194900513,-0.19484797678833315,1739502658.3446214,18.669982194900513,-0.050691961408393195,1739502658.344625,18.669982194900513,2.1391581214582716,1739502658.3446286,18.669982194900513,0.0,1739502658.344632,18.669982194900513,0.03140948059587006,1739502658.3446357,18.669982194900513,6.277904191628754,1739502658.344639,18.669982194900513,2.1100293519212348 +1739502658.366459,18.689982175827026,37.8167928253646,1739502658.3664641,18.689982175827026,0.10235711953415816,1739502658.3664708,18.689982175827026,37.03230602530713,1739502658.3664784,18.689982175827026,43.24517595310344,1739502658.3664825,18.689982175827026,-0.12116175953103442,1739502658.3664887,18.689982175827026,-0.041152711544168184,1739502658.3664935,18.689982175827026,-0.19484797678833315,1739502658.3664982,18.689982175827026,-0.050691961408393195,1739502658.366503,18.689982175827026,2.1391581214582716,1739502658.366508,18.689982175827026,0.0,1739502658.366513,18.689982175827026,0.029128769537036803,1739502658.3665178,18.689982175827026,6.277904191628754,1739502658.3665228,18.689982175827026,2.1100293519212348 +1739502658.3861039,18.70998215675354,37.8167928253646,1739502658.38611,18.70998215675354,0.10235711953415816,1739502658.386118,18.70998215675354,37.03230602530713,1739502658.3861268,18.70998215675354,43.24517595310344,1739502658.3861322,18.70998215675354,-0.12116175953103442,1739502658.3861387,18.70998215675354,-0.041152711544168184,1739502658.3861442,18.70998215675354,-0.19484797678833315,1739502658.3861501,18.70998215675354,-0.050691961408393195,1739502658.3861558,18.70998215675354,2.1391581214582716,1739502658.3861616,18.70998215675354,0.0,1739502658.3861673,18.70998215675354,0.029128769537036803,1739502658.3861732,18.70998215675354,6.277904191628754,1739502658.386179,18.70998215675354,2.1100293519212348 +1739502658.4040189,18.729982137680054,37.8167928253646,1739502658.404022,18.729982137680054,0.10235711953415816,1739502658.4040265,18.729982137680054,37.03230602530713,1739502658.4040318,18.729982137680054,43.24517595310344,1739502658.4040346,18.729982137680054,-0.12116175953103442,1739502658.4040382,18.729982137680054,-0.041152711544168184,1739502658.4040413,18.729982137680054,-0.19484797678833315,1739502658.4040446,18.729982137680054,-0.050691961408393195,1739502658.404048,18.729982137680054,2.1391581214582716,1739502658.4040513,18.729982137680054,0.0,1739502658.4040542,18.729982137680054,0.029128769537036803,1739502658.4040575,18.729982137680054,6.277904191628754,1739502658.4040608,18.729982137680054,2.1100293519212348 +1739502658.4231608,18.749982118606567,37.8167928253646,1739502658.4231637,18.749982118606567,0.10235711953415816,1739502658.4231675,18.749982118606567,37.03230602530713,1739502658.4231706,18.749982118606567,43.24517595310344,1739502658.4231718,18.749982118606567,-0.12116175953103442,1739502658.4231734,18.749982118606567,-0.041152711544168184,1739502658.4231746,18.749982118606567,-0.19484797678833315,1739502658.4231763,18.749982118606567,-0.050691961408393195,1739502658.4231775,18.749982118606567,2.1391581214582716,1739502658.4231791,18.749982118606567,0.0,1739502658.4231806,18.749982118606567,0.029128769537036803,1739502658.4231818,18.749982118606567,6.277904191628754,1739502658.4231834,18.749982118606567,2.1100293519212348 +1739502658.4427974,18.76998209953308,38.04905059597657,1739502658.4428,18.76998209953308,0.10102280937972985,1739502658.4428036,18.76998209953308,37.6444682091934,1739502658.4428062,18.76998209953308,43.86362133344525,1739502658.442808,18.76998209953308,-0.13062616501871785,1739502658.4428093,18.76998209953308,-0.039818336629110496,1739502658.4428108,18.76998209953308,-0.19500620311602937,1739502658.4428122,18.76998209953308,-0.04422360216641291,1739502658.4428134,18.76998209953308,2.138887361688027,1739502658.4428153,18.76998209953308,0.0,1739502658.4428165,18.76998209953308,0.02410583801880153,1739502658.4428182,18.76998209953308,6.2768841687694295,1739502658.4428198,18.76998209953308,2.113211856540623 +1739502658.463943,18.789982080459595,38.04905059597657,1739502658.463947,18.789982080459595,0.10102280937972985,1739502658.4639518,18.789982080459595,37.6444682091934,1739502658.4639573,18.789982080459595,43.86362133344525,1739502658.4639602,18.789982080459595,-0.13062616501871785,1739502658.4639642,18.789982080459595,-0.039818336629110496,1739502658.4639676,18.789982080459595,-0.19500620311602937,1739502658.4639711,18.789982080459595,-0.04422360216641291,1739502658.4639747,18.789982080459595,2.138887361688027,1739502658.4639783,18.789982080459595,0.0,1739502658.4639816,18.789982080459595,0.02567550514740402,1739502658.4639852,18.789982080459595,6.2768841687694295,1739502658.4639885,18.789982080459595,2.113211856540623 +1739502658.483652,18.80998206138611,38.04905059597657,1739502658.483656,18.80998206138611,0.10102280937972985,1739502658.4836605,18.80998206138611,37.6444682091934,1739502658.483666,18.80998206138611,43.86362133344525,1739502658.4836688,18.80998206138611,-0.13062616501871785,1739502658.4836726,18.80998206138611,-0.039818336629110496,1739502658.4836762,18.80998206138611,-0.19500620311602937,1739502658.4836795,18.80998206138611,-0.04422360216641291,1739502658.4836829,18.80998206138611,2.138887361688027,1739502658.4836864,18.80998206138611,0.0,1739502658.4836898,18.80998206138611,0.02567550514740402,1739502658.4836936,18.80998206138611,6.2768841687694295,1739502658.483697,18.80998206138611,2.113211856540623 +1739502658.5038214,18.829982042312622,38.04905059597657,1739502658.5038252,18.829982042312622,0.10102280937972985,1739502658.5038297,18.829982042312622,37.6444682091934,1739502658.503835,18.829982042312622,43.86362133344525,1739502658.5038376,18.829982042312622,-0.13062616501871785,1739502658.5038416,18.829982042312622,-0.039818336629110496,1739502658.5038452,18.829982042312622,-0.19500620311602937,1739502658.5038486,18.829982042312622,-0.04422360216641291,1739502658.503852,18.829982042312622,2.138887361688027,1739502658.5038555,18.829982042312622,0.0,1739502658.503859,18.829982042312622,0.02567550514740402,1739502658.5038626,18.829982042312622,6.2768841687694295,1739502658.5038662,18.829982042312622,2.113211856540623 +1739502658.5238023,18.849982023239136,38.04905059597657,1739502658.5238066,18.849982023239136,0.10102280937972985,1739502658.5238113,18.849982023239136,37.6444682091934,1739502658.5238166,18.849982023239136,43.86362133344525,1739502658.5238197,18.849982023239136,-0.13062616501871785,1739502658.5238235,18.849982023239136,-0.039818336629110496,1739502658.5238268,18.849982023239136,-0.19500620311602937,1739502658.5238304,18.849982023239136,-0.04422360216641291,1739502658.5238338,18.849982023239136,2.138887361688027,1739502658.5238378,18.849982023239136,0.0,1739502658.5238414,18.849982023239136,0.02567550514740402,1739502658.5238447,18.849982023239136,6.2768841687694295,1739502658.5238483,18.849982023239136,2.113211856540623 +1739502658.5437942,18.86998200416565,38.04905059597657,1739502658.5437984,18.86998200416565,0.10102280937972985,1739502658.5438032,18.86998200416565,37.6444682091934,1739502658.5438085,18.86998200416565,43.86362133344525,1739502658.5438113,18.86998200416565,-0.13062616501871785,1739502658.5438151,18.86998200416565,-0.039818336629110496,1739502658.5438187,18.86998200416565,-0.19500620311602937,1739502658.543822,18.86998200416565,-0.04422360216641291,1739502658.5438254,18.86998200416565,2.138887361688027,1739502658.543829,18.86998200416565,0.0,1739502658.5438323,18.86998200416565,0.02567550514740402,1739502658.5438359,18.86998200416565,6.2768841687694295,1739502658.5438395,18.86998200416565,2.113211856540623 +1739502658.5637972,18.889981985092163,38.28163642249572,1739502658.563801,18.889981985092163,0.09944936634930457,1739502658.5638056,18.889981985092163,37.67563313650393,1739502658.563811,18.889981985092163,43.90033944404947,1739502658.563814,18.889981985092163,-0.13135325631781136,1739502658.5638177,18.889981985092163,-0.04105448123484763,1739502658.5638213,18.889981985092163,-0.18966137377874817,1739502658.5638247,18.889981985092163,-0.046057635334871366,1739502658.5638282,18.889981985092163,2.1480525325697193,1739502658.5638318,18.889981985092163,0.0,1739502658.5638351,18.889981985092163,0.034962751734506095,1739502658.5638387,18.889981985092163,6.275864145910106,1739502658.563842,18.889981985092163,2.1159920472965568 +1739502658.5837896,18.909981966018677,38.28163642249572,1739502658.5837932,18.909981966018677,0.09944936634930457,1739502658.5837982,18.909981966018677,37.67563313650393,1739502658.5838034,18.909981966018677,43.90033944404947,1739502658.5838065,18.909981966018677,-0.13135325631781136,1739502658.5838106,18.909981966018677,-0.04105448123484763,1739502658.583814,18.909981966018677,-0.18966137377874817,1739502658.5838172,18.909981966018677,-0.046057635334871366,1739502658.5838208,18.909981966018677,2.1480525325697193,1739502658.5838242,18.909981966018677,0.0,1739502658.5838277,18.909981966018677,0.03206048527316252,1739502658.5838313,18.909981966018677,6.275864145910106,1739502658.5838346,18.909981966018677,2.1159920472965568 +1739502658.6039953,18.92998194694519,38.28163642249572,1739502658.6039994,18.92998194694519,0.09944936634930457,1739502658.6040044,18.92998194694519,37.67563313650393,1739502658.6040096,18.92998194694519,43.90033944404947,1739502658.6040125,18.92998194694519,-0.13135325631781136,1739502658.6040163,18.92998194694519,-0.04105448123484763,1739502658.6040196,18.92998194694519,-0.18966137377874817,1739502658.6040232,18.92998194694519,-0.046057635334871366,1739502658.6040266,18.92998194694519,2.1480525325697193,1739502658.6040301,18.92998194694519,0.0,1739502658.6040335,18.92998194694519,0.03206048527316252,1739502658.604037,18.92998194694519,6.275864145910106,1739502658.6040406,18.92998194694519,2.1159920472965568 +1739502658.6235466,18.949981927871704,38.28163642249572,1739502658.6235504,18.949981927871704,0.09944936634930457,1739502658.6235554,18.949981927871704,37.67563313650393,1739502658.6235607,18.949981927871704,43.90033944404947,1739502658.6235635,18.949981927871704,-0.13135325631781136,1739502658.6235673,18.949981927871704,-0.04105448123484763,1739502658.623571,18.949981927871704,-0.18966137377874817,1739502658.6235743,18.949981927871704,-0.046057635334871366,1739502658.6235778,18.949981927871704,2.1480525325697193,1739502658.6235814,18.949981927871704,0.0,1739502658.6235847,18.949981927871704,0.03206048527316252,1739502658.6235883,18.949981927871704,6.275864145910106,1739502658.623592,18.949981927871704,2.1159920472965568 +1739502658.6438987,18.969981908798218,38.28163642249572,1739502658.6439025,18.969981908798218,0.09944936634930457,1739502658.643907,18.969981908798218,37.67563313650393,1739502658.6439126,18.969981908798218,43.90033944404947,1739502658.6439152,18.969981908798218,-0.13135325631781136,1739502658.6439188,18.969981908798218,-0.04105448123484763,1739502658.643922,18.969981908798218,-0.18966137377874817,1739502658.6439254,18.969981908798218,-0.046057635334871366,1739502658.643929,18.969981908798218,2.1480525325697193,1739502658.6439326,18.969981908798218,0.0,1739502658.643936,18.969981908798218,0.03206048527316252,1739502658.6439393,18.969981908798218,6.275864145910106,1739502658.6439428,18.969981908798218,2.1159920472965568 +1739502658.6683123,18.98998188972473,38.51456262701955,1739502658.6683192,18.98998188972473,0.09763601110562181,1739502658.6683283,18.98998188972473,37.706843434554884,1739502658.6683388,18.98998188972473,43.93854774296237,1739502658.6683445,18.98998188972473,-0.132,1739502658.668352,18.98998188972473,-0.04231187054420462,1739502658.6683588,18.98998188972473,-0.18438608870957382,1739502658.6683657,18.98998188972473,-0.048043818427826235,1739502658.6683724,18.98998188972473,2.157136959826355,1739502658.6683793,18.98998188972473,0.0,1739502658.6683862,18.98998188972473,0.040180088330181246,1739502658.6683931,18.98998188972473,6.274844123050781,1739502658.6684,18.98998188972473,2.1194942491151263 +1739502658.6844344,19.009981870651245,38.51456262701955,1739502658.6844385,19.009981870651245,0.09763601110562181,1739502658.6844437,19.009981870651245,37.706843434554884,1739502658.6844494,19.009981870651245,43.93854774296237,1739502658.6844528,19.009981870651245,-0.132,1739502658.6844575,19.009981870651245,-0.04231187054420462,1739502658.6844614,19.009981870651245,-0.18438608870957382,1739502658.6844654,19.009981870651245,-0.048043818427826235,1739502658.6844692,19.009981870651245,2.157136959826355,1739502658.6844733,19.009981870651245,0.0,1739502658.684477,19.009981870651245,0.03764271071122849,1739502658.6844814,19.009981870651245,6.274844123050781,1739502658.6844854,19.009981870651245,2.1194942491151263 +1739502658.7064257,19.02998185157776,38.51456262701955,1739502658.7064304,19.02998185157776,0.09763601110562181,1739502658.7064369,19.02998185157776,37.706843434554884,1739502658.7064445,19.02998185157776,43.93854774296237,1739502658.7064486,19.02998185157776,-0.132,1739502658.706454,19.02998185157776,-0.04231187054420462,1739502658.7064586,19.02998185157776,-0.18438608870957382,1739502658.7064636,19.02998185157776,-0.048043818427826235,1739502658.706468,19.02998185157776,2.157136959826355,1739502658.7064729,19.02998185157776,0.0,1739502658.7064779,19.02998185157776,0.03764271071122849,1739502658.7064826,19.02998185157776,6.274844123050781,1739502658.7064877,19.02998185157776,2.1194942491151263 +1739502658.7239916,19.049981832504272,38.51456262701955,1739502658.723995,19.049981832504272,0.09763601110562181,1739502658.7239995,19.049981832504272,37.706843434554884,1739502658.7240043,19.049981832504272,43.93854774296237,1739502658.724007,19.049981832504272,-0.132,1739502658.7240105,19.049981832504272,-0.04231187054420462,1739502658.7240138,19.049981832504272,-0.18438608870957382,1739502658.7240174,19.049981832504272,-0.048043818427826235,1739502658.7240205,19.049981832504272,2.157136959826355,1739502658.7240238,19.049981832504272,0.0,1739502658.7240272,19.049981832504272,0.03764271071122849,1739502658.7240305,19.049981832504272,6.274844123050781,1739502658.7240338,19.049981832504272,2.1194942491151263 +1739502658.7442322,19.069981813430786,38.51456262701955,1739502658.744236,19.069981813430786,0.09763601110562181,1739502658.7442403,19.069981813430786,37.706843434554884,1739502658.7442665,19.069981813430786,43.93854774296237,1739502658.7442694,19.069981813430786,-0.132,1739502658.7442732,19.069981813430786,-0.04231187054420462,1739502658.7442765,19.069981813430786,-0.18438608870957382,1739502658.7442799,19.069981813430786,-0.048043818427826235,1739502658.7442832,19.069981813430786,2.157136959826355,1739502658.744287,19.069981813430786,0.0,1739502658.7442904,19.069981813430786,0.03764271071122849,1739502658.744294,19.069981813430786,6.274844123050781,1739502658.7442975,19.069981813430786,2.1194942491151263 +1739502658.7640023,19.0899817943573,38.51456262701955,1739502658.764006,19.0899817943573,0.09763601110562181,1739502658.76401,19.0899817943573,37.706843434554884,1739502658.764015,19.0899817943573,43.93854774296237,1739502658.7640176,19.0899817943573,-0.132,1739502658.764021,19.0899817943573,-0.04231187054420462,1739502658.764024,19.0899817943573,-0.18438608870957382,1739502658.764027,19.0899817943573,-0.048043818427826235,1739502658.7640302,19.0899817943573,2.157136959826355,1739502658.7640336,19.0899817943573,0.0,1739502658.7640367,19.0899817943573,0.03764271071122849,1739502658.7640398,19.0899817943573,6.274844123050781,1739502658.7640429,19.0899817943573,2.1194942491151263 +1739502658.7826607,19.109981775283813,38.74790920273608,1739502658.782663,19.109981775283813,0.09558134231027626,1739502658.7826664,19.109981775283813,37.969294643120705,1739502658.782669,19.109981775283813,44.209317236571664,1739502658.7826705,19.109981775283813,-0.13547162844696373,1739502658.7826722,19.109981775283813,-0.042281270324604145,1739502658.7826736,19.109981775283813,-0.17991822264164736,1739502658.7826753,19.109981775283813,-0.04623981701455994,1739502658.7826762,19.109981775283813,2.1648609948059705,1739502658.7826781,19.109981775283813,0.0,1739502658.7826793,19.109981775283813,0.04280942285894622,1739502658.7826805,19.109981775283813,6.273824100191456,1739502658.782682,19.109981775283813,2.1236661705517994 +1739502658.8034465,19.129981756210327,38.74790920273608,1739502658.80345,19.129981756210327,0.09558134231027626,1739502658.8034546,19.129981756210327,37.969294643120705,1739502658.8034601,19.129981756210327,44.209317236571664,1739502658.803463,19.129981756210327,-0.13547162844696373,1739502658.8034666,19.129981756210327,-0.042281270324604145,1739502658.8034701,19.129981756210327,-0.17991822264164736,1739502658.8034735,19.129981756210327,-0.04623981701455994,1739502658.8034766,19.129981756210327,2.1648609948059705,1739502658.8034801,19.129981756210327,0.0,1739502658.8034835,19.129981756210327,0.04119482425417109,1739502658.8034868,19.129981756210327,6.273824100191456,1739502658.8034902,19.129981756210327,2.1236661705517994 +1739502658.8290312,19.14998173713684,38.74790920273608,1739502658.8290455,19.14998173713684,0.09558134231027626,1739502658.829062,19.14998173713684,37.969294643120705,1739502658.8290796,19.14998173713684,44.209317236571664,1739502658.829089,19.14998173713684,-0.13547162844696373,1739502658.8291001,19.14998173713684,-0.042281270324604145,1739502658.82911,19.14998173713684,-0.17991822264164736,1739502658.829119,19.14998173713684,-0.04623981701455994,1739502658.8291266,19.14998173713684,2.1648609948059705,1739502658.829143,19.14998173713684,0.0,1739502658.829159,19.14998173713684,0.04119482425417109,1739502658.829174,19.14998173713684,6.273824100191456,1739502658.8291905,19.14998173713684,2.1236661705517994 +1739502658.8456774,19.169981718063354,38.74790920273608,1739502658.8456836,19.169981718063354,0.09558134231027626,1739502658.8456914,19.169981718063354,37.969294643120705,1739502658.8456998,19.169981718063354,44.209317236571664,1739502658.8457048,19.169981718063354,-0.13547162844696373,1739502658.8457108,19.169981718063354,-0.042281270324604145,1739502658.8457162,19.169981718063354,-0.17991822264164736,1739502658.8457215,19.169981718063354,-0.04623981701455994,1739502658.845727,19.169981718063354,2.1648609948059705,1739502658.845733,19.169981718063354,0.0,1739502658.8457382,19.169981718063354,0.04119482425417109,1739502658.845744,19.169981718063354,6.273824100191456,1739502658.8457496,19.169981718063354,2.1236661705517994 +1739502658.8639627,19.189981698989868,38.74790920273608,1739502658.8639662,19.189981698989868,0.09558134231027626,1739502658.8639708,19.189981698989868,37.969294643120705,1739502658.8639762,19.189981698989868,44.209317236571664,1739502658.8639793,19.189981698989868,-0.13547162844696373,1739502658.8639832,19.189981698989868,-0.042281270324604145,1739502658.8639865,19.189981698989868,-0.17991822264164736,1739502658.86399,19.189981698989868,-0.04623981701455994,1739502658.8639934,19.189981698989868,2.1648609948059705,1739502658.863997,19.189981698989868,0.0,1739502658.8640003,19.189981698989868,0.04119482425417109,1739502658.8640041,19.189981698989868,6.273824100191456,1739502658.8640077,19.189981698989868,2.1236661705517994 +1739502658.8839974,19.209981679916382,38.98172594357323,1739502658.884001,19.209981679916382,0.09328401113110818,1739502658.8840053,19.209981679916382,38.45781427977909,1739502658.8840108,19.209981679916382,44.70681545192054,1739502658.8840137,19.209981679916382,-0.1406417371477281,1739502658.8840175,19.209981679916382,-0.04083703791673779,1739502658.8840208,19.209981679916382,-0.17448074074527922,1739502658.8840241,19.209981679916382,-0.04081247218378629,1739502658.8840275,19.209981679916382,2.17429862066595,1739502658.884031,19.209981679916382,0.0,1739502658.8840344,19.209981679916382,0.04837165707602269,1739502658.884038,19.209981679916382,6.2728040773321325,1739502658.8840415,19.209981679916382,2.128169725317225 +1739502658.9042616,19.229981660842896,38.98172594357323,1739502658.9042652,19.229981660842896,0.09328401113110818,1739502658.90427,19.229981660842896,38.45781427977909,1739502658.904275,19.229981660842896,44.70681545192054,1739502658.9042778,19.229981660842896,-0.1406417371477281,1739502658.9042816,19.229981660842896,-0.04083703791673779,1739502658.9042852,19.229981660842896,-0.17448074074527922,1739502658.9042885,19.229981660842896,-0.04081247218378629,1739502658.9042919,19.229981660842896,2.17429862066595,1739502658.9042957,19.229981660842896,0.0,1739502658.9042993,19.229981660842896,0.046128895348724885,1739502658.9043026,19.229981660842896,6.2728040773321325,1739502658.9043062,19.229981660842896,2.128169725317225 +1739502658.9234936,19.24998164176941,38.98172594357323,1739502658.9234977,19.24998164176941,0.09328401113110818,1739502658.9235024,19.24998164176941,38.45781427977909,1739502658.923507,19.24998164176941,44.70681545192054,1739502658.9235096,19.24998164176941,-0.1406417371477281,1739502658.923513,19.24998164176941,-0.04083703791673779,1739502658.923515,19.24998164176941,-0.17448074074527922,1739502658.923518,19.24998164176941,-0.04081247218378629,1739502658.92352,19.24998164176941,2.17429862066595,1739502658.9235227,19.24998164176941,0.0,1739502658.9235253,19.24998164176941,0.046128895348724885,1739502658.923528,19.24998164176941,6.2728040773321325,1739502658.9235303,19.24998164176941,2.128169725317225 +1739502658.9436426,19.269981622695923,38.98172594357323,1739502658.9436464,19.269981622695923,0.09328401113110818,1739502658.943651,19.269981622695923,38.45781427977909,1739502658.9436553,19.269981622695923,44.70681545192054,1739502658.9436574,19.269981622695923,-0.1406417371477281,1739502658.9436605,19.269981622695923,-0.04083703791673779,1739502658.9436631,19.269981622695923,-0.17448074074527922,1739502658.9436655,19.269981622695923,-0.04081247218378629,1739502658.943668,19.269981622695923,2.17429862066595,1739502658.9436703,19.269981622695923,0.0,1739502658.9436724,19.269981622695923,0.046128895348724885,1739502658.9436748,19.269981622695923,6.2728040773321325,1739502658.9436774,19.269981622695923,2.128169725317225 +1739502658.9641783,19.289981603622437,38.98172594357323,1739502658.964183,19.289981603622437,0.09328401113110818,1739502658.9641883,19.289981603622437,38.45781427977909,1739502658.964195,19.289981603622437,44.70681545192054,1739502658.964198,19.289981603622437,-0.1406417371477281,1739502658.9642026,19.289981603622437,-0.04083703791673779,1739502658.9642055,19.289981603622437,-0.17448074074527922,1739502658.9642105,19.289981603622437,-0.04081247218378629,1739502658.964214,19.289981603622437,2.17429862066595,1739502658.9642177,19.289981603622437,0.0,1739502658.9642217,19.289981603622437,0.046128895348724885,1739502658.9642243,19.289981603622437,6.2728040773321325,1739502658.9642289,19.289981603622437,2.128169725317225 +1739502658.9836915,19.30998158454895,38.98172594357323,1739502658.9836946,19.30998158454895,0.09328401113110818,1739502658.9836988,19.30998158454895,38.45781427977909,1739502658.983704,19.30998158454895,44.70681545192054,1739502658.9837067,19.30998158454895,-0.1406417371477281,1739502658.9837103,19.30998158454895,-0.04083703791673779,1739502658.9837136,19.30998158454895,-0.17448074074527922,1739502658.983717,19.30998158454895,-0.04081247218378629,1739502658.9837198,19.30998158454895,2.17429862066595,1739502658.9837232,19.30998158454895,0.0,1739502658.9837263,19.30998158454895,0.046128895348724885,1739502658.9837296,19.30998158454895,6.2728040773321325,1739502658.983733,19.30998158454895,2.128169725317225 +1739502659.0039394,19.329981565475464,39.21606807144092,1739502659.003943,19.329981565475464,0.09074245288718874,1739502659.0039473,19.329981565475464,38.48851055697151,1739502659.003952,19.329981565475464,44.74770015654981,1739502659.003955,19.329981565475464,-0.1410460799661746,1739502659.0039585,19.329981565475464,-0.041877878574052826,1739502659.0039618,19.329981565475464,-0.16870729913828691,1739502659.003965,19.329981565475464,-0.04226665827122026,1739502659.0039682,19.329981565475464,2.184364397339225,1739502659.0039716,19.329981565475464,0.0,1739502659.003975,19.329981565475464,0.05335880768372137,1739502659.0039783,19.329981565475464,6.271784054472808,1739502659.0039816,19.329981565475464,2.1332649387415348 +1739502659.0227807,19.349981546401978,39.21606807144092,1739502659.0227828,19.349981546401978,0.09074245288718874,1739502659.0227854,19.349981546401978,38.48851055697151,1739502659.0227883,19.349981546401978,44.74770015654981,1739502659.0227897,19.349981546401978,-0.1410460799661746,1739502659.0227914,19.349981546401978,-0.041877878574052826,1739502659.0227928,19.349981546401978,-0.16870729913828691,1739502659.022794,19.349981546401978,-0.04226665827122026,1739502659.0227952,19.349981546401978,2.184364397339225,1739502659.0227969,19.349981546401978,0.0,1739502659.022798,19.349981546401978,0.05109945859769027,1739502659.0227993,19.349981546401978,6.271784054472808,1739502659.022801,19.349981546401978,2.1332649387415348 +1739502659.0434108,19.36998152732849,39.21606807144092,1739502659.0434148,19.36998152732849,0.09074245288718874,1739502659.0434191,19.36998152732849,38.48851055697151,1739502659.043424,19.36998152732849,44.74770015654981,1739502659.0434265,19.36998152732849,-0.1410460799661746,1739502659.04343,19.36998152732849,-0.041877878574052826,1739502659.0434332,19.36998152732849,-0.16870729913828691,1739502659.0434363,19.36998152732849,-0.04226665827122026,1739502659.0434394,19.36998152732849,2.184364397339225,1739502659.043443,19.36998152732849,0.0,1739502659.043446,19.36998152732849,0.05109945859769027,1739502659.0434494,19.36998152732849,6.271784054472808,1739502659.0434527,19.36998152732849,2.1332649387415348 +1739502659.0636923,19.389981508255005,39.21606807144092,1739502659.063696,19.389981508255005,0.09074245288718874,1739502659.0637004,19.389981508255005,38.48851055697151,1739502659.0637057,19.389981508255005,44.74770015654981,1739502659.0637083,19.389981508255005,-0.1410460799661746,1739502659.063712,19.389981508255005,-0.041877878574052826,1739502659.0637152,19.389981508255005,-0.16870729913828691,1739502659.0637186,19.389981508255005,-0.04226665827122026,1739502659.063722,19.389981508255005,2.184364397339225,1739502659.0637255,19.389981508255005,0.0,1739502659.0637288,19.389981508255005,0.05109945859769027,1739502659.0637321,19.389981508255005,6.271784054472808,1739502659.0637355,19.389981508255005,2.1332649387415348 +1739502659.083228,19.40998148918152,39.21606807144092,1739502659.0832317,19.40998148918152,0.09074245288718874,1739502659.0832365,19.40998148918152,38.48851055697151,1739502659.0832415,19.40998148918152,44.74770015654981,1739502659.0832443,19.40998148918152,-0.1410460799661746,1739502659.0832481,19.40998148918152,-0.041877878574052826,1739502659.0832515,19.40998148918152,-0.16870729913828691,1739502659.0832548,19.40998148918152,-0.04226665827122026,1739502659.083258,19.40998148918152,2.184364397339225,1739502659.0832617,19.40998148918152,0.0,1739502659.083265,19.40998148918152,0.05109945859769027,1739502659.0832684,19.40998148918152,6.271784054472808,1739502659.0832717,19.40998148918152,2.1332649387415348 +1739502659.107262,19.429981470108032,39.45098934205834,1739502659.1072688,19.429981470108032,0.0879549527286656,1739502659.1072779,19.429981470108032,38.53428442613373,1739502659.1072884,19.429981470108032,44.80464302818419,1739502659.1072943,19.429981470108032,-0.14160434341357045,1739502659.107302,19.429981470108032,-0.042852745940663774,1739502659.1073089,19.429981470108032,-0.16304408950951235,1739502659.1073155,19.429981470108032,-0.04360510948579184,1739502659.1073225,19.429981470108032,2.1942832602030613,1739502659.1073294,19.429981470108032,0.0,1739502659.107336,19.429981470108032,0.05740199628380625,1739502659.107343,19.429981470108032,6.270764031613483,1739502659.1073499,19.429981470108032,2.1388508082375 +1739502659.1241326,19.449981451034546,39.45098934205834,1739502659.1241362,19.449981451034546,0.0879549527286656,1739502659.124141,19.449981451034546,38.53428442613373,1739502659.1241465,19.449981451034546,44.80464302818419,1739502659.1241493,19.449981451034546,-0.14160434341357045,1739502659.1241534,19.449981451034546,-0.042852745940663774,1739502659.1241567,19.449981451034546,-0.16304408950951235,1739502659.1241603,19.449981451034546,-0.04360510948579184,1739502659.1241639,19.449981451034546,2.1942832602030613,1739502659.1241674,19.449981451034546,0.0,1739502659.124171,19.449981451034546,0.055432451965561125,1739502659.1241746,19.449981451034546,6.270764031613483,1739502659.1241782,19.449981451034546,2.1388508082375 +1739502659.1474955,19.46998143196106,39.45098934205834,1739502659.1475,19.46998143196106,0.0879549527286656,1739502659.1475067,19.46998143196106,38.53428442613373,1739502659.147514,19.46998143196106,44.80464302818419,1739502659.1475182,19.46998143196106,-0.14160434341357045,1739502659.1475236,19.46998143196106,-0.042852745940663774,1739502659.1475282,19.46998143196106,-0.16304408950951235,1739502659.147533,19.46998143196106,-0.04360510948579184,1739502659.1475377,19.46998143196106,2.1942832602030613,1739502659.1475427,19.46998143196106,0.0,1739502659.1475475,19.46998143196106,0.055432451965561125,1739502659.1475523,19.46998143196106,6.270764031613483,1739502659.1475573,19.46998143196106,2.1388508082375 +1739502659.1639361,19.489981412887573,39.45098934205834,1739502659.1639395,19.489981412887573,0.0879549527286656,1739502659.163944,19.489981412887573,38.53428442613373,1739502659.1639488,19.489981412887573,44.80464302818419,1739502659.1639516,19.489981412887573,-0.14160434341357045,1739502659.1639552,19.489981412887573,-0.042852745940663774,1739502659.1639583,19.489981412887573,-0.16304408950951235,1739502659.1639616,19.489981412887573,-0.04360510948579184,1739502659.163965,19.489981412887573,2.1942832602030613,1739502659.1639683,19.489981412887573,0.0,1739502659.1639714,19.489981412887573,0.055432451965561125,1739502659.1639748,19.489981412887573,6.270764031613483,1739502659.163978,19.489981412887573,2.1388508082375 +1739502659.183833,19.509981393814087,39.45098934205834,1739502659.183836,19.509981393814087,0.0879549527286656,1739502659.18384,19.509981393814087,38.53428442613373,1739502659.1838446,19.509981393814087,44.80464302818419,1739502659.1838472,19.509981393814087,-0.14160434341357045,1739502659.1838508,19.509981393814087,-0.042852745940663774,1739502659.1838539,19.509981393814087,-0.16304408950951235,1739502659.183857,19.509981393814087,-0.04360510948579184,1739502659.1838598,19.509981393814087,2.1942832602030613,1739502659.183863,19.509981393814087,0.0,1739502659.183866,19.509981393814087,0.055432451965561125,1739502659.1838691,19.509981393814087,6.270764031613483,1739502659.1838722,19.509981393814087,2.1388508082375 +1739502659.2040389,19.5299813747406,39.45098934205834,1739502659.2040417,19.5299813747406,0.0879549527286656,1739502659.2040458,19.5299813747406,38.53428442613373,1739502659.2040508,19.5299813747406,44.80464302818419,1739502659.2040532,19.5299813747406,-0.14160434341357045,1739502659.2040565,19.5299813747406,-0.042852745940663774,1739502659.2040596,19.5299813747406,-0.16304408950951235,1739502659.2040627,19.5299813747406,-0.04360510948579184,1739502659.2040658,19.5299813747406,2.1942832602030613,1739502659.2040691,19.5299813747406,0.0,1739502659.2040725,19.5299813747406,0.055432451965561125,1739502659.2040756,19.5299813747406,6.270764031613483,1739502659.2040787,19.5299813747406,2.1388508082375 +1739502659.223525,19.549981355667114,39.68655112322249,1739502659.2235284,19.549981355667114,0.08491953293289267,1739502659.2235332,19.549981355667114,39.19712879404457,1739502659.223538,19.549981355667114,45.47956584271043,1739502659.2235408,19.549981355667114,-0.1324384460098159,1739502659.2235444,19.549981355667114,-0.03750310959935965,1739502659.2235477,19.549981355667114,-0.13947504936400498,1739502659.2235513,19.549981355667114,-0.03187286973987029,1739502659.2235544,19.549981355667114,2.2360494990813407,1739502659.2235577,19.549981355667114,0.0,1739502659.223561,19.549981355667114,0.10729842115744835,1739502659.2235646,19.549981355667114,6.269744008754159,1739502659.223568,19.549981355667114,2.1449592039232326 +1739502659.243819,19.569981336593628,39.68655112322249,1739502659.2438223,19.569981336593628,0.08491953293289267,1739502659.2438266,19.569981336593628,39.19712879404457,1739502659.2438314,19.569981336593628,45.47956584271043,1739502659.2438338,19.569981336593628,-0.1324384460098159,1739502659.2438374,19.569981336593628,-0.03750310959935965,1739502659.2438405,19.569981336593628,-0.13947504936400498,1739502659.2438436,19.569981336593628,-0.03187286973987029,1739502659.2438467,19.569981336593628,2.2360494990813407,1739502659.24385,19.569981336593628,0.0,1739502659.243853,19.569981336593628,0.09109029515810807,1739502659.2438564,19.569981336593628,6.269744008754159,1739502659.2438595,19.569981336593628,2.1449592039232326 +1739502659.2637582,19.58998131752014,39.68655112322249,1739502659.2637618,19.58998131752014,0.08491953293289267,1739502659.2637665,19.58998131752014,39.19712879404457,1739502659.2637713,19.58998131752014,45.47956584271043,1739502659.2637742,19.58998131752014,-0.1324384460098159,1739502659.2637777,19.58998131752014,-0.03750310959935965,1739502659.263781,19.58998131752014,-0.13947504936400498,1739502659.2637844,19.58998131752014,-0.03187286973987029,1739502659.2637877,19.58998131752014,2.2360494990813407,1739502659.263791,19.58998131752014,0.0,1739502659.2637944,19.58998131752014,0.09109029515810807,1739502659.263814,19.58998131752014,6.269744008754159,1739502659.2638173,19.58998131752014,2.1449592039232326 +1739502659.291945,19.609981298446655,39.68655112322249,1739502659.2919579,19.609981298446655,0.08491953293289267,1739502659.2919753,19.609981298446655,39.19712879404457,1739502659.2919946,19.609981298446655,45.47956584271043,1739502659.2920055,19.609981298446655,-0.1324384460098159,1739502659.2920196,19.609981298446655,-0.03750310959935965,1739502659.2920325,19.609981298446655,-0.13947504936400498,1739502659.292045,19.609981298446655,-0.03187286973987029,1739502659.2920582,19.609981298446655,2.2360494990813407,1739502659.292071,19.609981298446655,0.0,1739502659.2920837,19.609981298446655,0.09109029515810807,1739502659.2920966,19.609981298446655,6.269744008754159,1739502659.2921095,19.609981298446655,2.1449592039232326 +1739502659.3091893,19.62998127937317,39.68655112322249,1739502659.3091948,19.62998127937317,0.08491953293289267,1739502659.3092022,19.62998127937317,39.19712879404457,1739502659.3092105,19.62998127937317,45.47956584271043,1739502659.3092153,19.62998127937317,-0.1324384460098159,1739502659.3092213,19.62998127937317,-0.03750310959935965,1739502659.3092268,19.62998127937317,-0.13947504936400498,1739502659.3092325,19.62998127937317,-0.03187286973987029,1739502659.3092377,19.62998127937317,2.2360494990813407,1739502659.3092437,19.62998127937317,0.0,1739502659.309249,19.62998127937317,0.09109029515810807,1739502659.309255,19.62998127937317,6.269744008754159,1739502659.3092606,19.62998127937317,2.1449592039232326 +1739502659.3266795,19.649981260299683,39.92296475340714,1739502659.3266838,19.649981260299683,0.08163190846436308,1739502659.3266885,19.649981260299683,39.74725553608601,1739502659.3266943,19.649981260299683,46.04903991578192,1739502659.326697,19.649981260299683,-0.10830180106475606,1739502659.3267012,19.649981260299683,-0.030994214274446034,1739502659.326705,19.649981260299683,-0.10132579614616812,1739502659.3267086,19.649981260299683,-0.020715357483663446,1739502659.3267121,19.649981260299683,2.305344435394214,1739502659.3267157,19.649981260299683,0.0,1739502659.3267195,19.649981260299683,0.1774302978328441,1739502659.326723,19.649981260299683,6.268723985894835,1739502659.3267272,19.649981260299683,2.154895406087523 +1739502659.3472812,19.669981241226196,39.92296475340714,1739502659.3472846,19.669981241226196,0.08163190846436308,1739502659.3472886,19.669981241226196,39.74725553608601,1739502659.3472931,19.669981241226196,46.04903991578192,1739502659.3472958,19.669981241226196,-0.10830180106475606,1739502659.3472993,19.669981241226196,-0.030994214274446034,1739502659.3473024,19.669981241226196,-0.10132579614616812,1739502659.3473058,19.669981241226196,-0.020715357483663446,1739502659.3473089,19.669981241226196,2.305344435394214,1739502659.347312,19.669981241226196,0.0,1739502659.3473148,19.669981241226196,0.1504490293066909,1739502659.347318,19.669981241226196,6.268723985894835,1739502659.3473213,19.669981241226196,2.154895406087523 +1739502659.3673012,19.68998122215271,39.92296475340714,1739502659.3673046,19.68998122215271,0.08163190846436308,1739502659.3673089,19.68998122215271,39.74725553608601,1739502659.3673134,19.68998122215271,46.04903991578192,1739502659.367316,19.68998122215271,-0.10830180106475606,1739502659.3673193,19.68998122215271,-0.030994214274446034,1739502659.3673224,19.68998122215271,-0.10132579614616812,1739502659.3673255,19.68998122215271,-0.020715357483663446,1739502659.3673284,19.68998122215271,2.305344435394214,1739502659.3673317,19.68998122215271,0.0,1739502659.3673346,19.68998122215271,0.1504490293066909,1739502659.367338,19.68998122215271,6.268723985894835,1739502659.367341,19.68998122215271,2.154895406087523 +1739502659.3869097,19.709981203079224,39.92296475340714,1739502659.3869128,19.709981203079224,0.08163190846436308,1739502659.3869169,19.709981203079224,39.74725553608601,1739502659.3869214,19.709981203079224,46.04903991578192,1739502659.3869243,19.709981203079224,-0.10830180106475606,1739502659.3869276,19.709981203079224,-0.030994214274446034,1739502659.3869307,19.709981203079224,-0.10132579614616812,1739502659.3869338,19.709981203079224,-0.020715357483663446,1739502659.386937,19.709981203079224,2.305344435394214,1739502659.38694,19.709981203079224,0.0,1739502659.3869429,19.709981203079224,0.1504490293066909,1739502659.3869462,19.709981203079224,6.268723985894835,1739502659.3869495,19.709981203079224,2.154895406087523 +1739502659.407457,19.729981184005737,39.92296475340714,1739502659.4074602,19.729981184005737,0.08163190846436308,1739502659.4074643,19.729981184005737,39.74725553608601,1739502659.407469,19.729981184005737,46.04903991578192,1739502659.4074717,19.729981184005737,-0.10830180106475606,1739502659.407475,19.729981184005737,-0.030994214274446034,1739502659.407478,19.729981184005737,-0.10132579614616812,1739502659.4074812,19.729981184005737,-0.020715357483663446,1739502659.407484,19.729981184005737,2.305344435394214,1739502659.4074872,19.729981184005737,0.0,1739502659.4074903,19.729981184005737,0.1504490293066909,1739502659.4074936,19.729981184005737,6.268723985894835,1739502659.4074967,19.729981184005737,2.154895406087523 +1739502659.4271233,19.74998116493225,39.92296475340714,1739502659.4271266,19.74998116493225,0.08163190846436308,1739502659.427131,19.74998116493225,39.74725553608601,1739502659.427136,19.74998116493225,46.04903991578192,1739502659.4271395,19.74998116493225,-0.10830180106475606,1739502659.4271436,19.74998116493225,-0.030994214274446034,1739502659.4271455,19.74998116493225,-0.10132579614616812,1739502659.4271476,19.74998116493225,-0.020715357483663446,1739502659.4271493,19.74998116493225,2.305344435394214,1739502659.4271517,19.74998116493225,0.0,1739502659.427154,19.74998116493225,0.1504490293066909,1739502659.4271584,19.74998116493225,6.268723985894835,1739502659.4271622,19.74998116493225,2.154895406087523 +1739502659.4477305,19.769981145858765,40.160852959886405,1739502659.447734,19.769981145858765,0.07808101464133355,1739502659.4477386,19.769981145858765,39.75296485304151,1739502659.4477434,19.769981145858765,46.08873324830353,1739502659.4477463,19.769981145858765,-0.10674082731390637,1739502659.4477499,19.769981145858765,-0.031168306355030487,1739502659.4477532,19.769981145858765,-0.09303180509761641,1739502659.4477563,19.769981145858765,-0.020312585772937833,1739502659.4477596,19.769981145858765,2.3206917000068925,1739502659.447763,19.769981145858765,0.0,1739502659.4477663,19.769981145858765,0.14803436110558169,1739502659.4477696,19.769981145858765,6.26770396303551,1739502659.447773,19.769981145858765,2.17190275459372 +1739502659.4733646,19.78998112678528,40.160852959886405,1739502659.4733703,19.78998112678528,0.07808101464133355,1739502659.4733777,19.78998112678528,39.75296485304151,1739502659.4733846,19.78998112678528,46.08873324830353,1739502659.4733882,19.78998112678528,-0.10674082731390637,1739502659.4733927,19.78998112678528,-0.031168306355030487,1739502659.4733963,19.78998112678528,-0.09303180509761641,1739502659.4733999,19.78998112678528,-0.020312585772937833,1739502659.473403,19.78998112678528,2.3206917000068925,1739502659.473407,19.78998112678528,0.0,1739502659.4734106,19.78998112678528,0.14878894541317234,1739502659.4734142,19.78998112678528,6.26770396303551,1739502659.4734178,19.78998112678528,2.17190275459372 +1739502659.4884408,19.809981107711792,40.160852959886405,1739502659.4884462,19.809981107711792,0.07808101464133355,1739502659.4884524,19.809981107711792,39.75296485304151,1739502659.4884596,19.809981107711792,46.08873324830353,1739502659.4884634,19.809981107711792,-0.10674082731390637,1739502659.4884684,19.809981107711792,-0.031168306355030487,1739502659.4884732,19.809981107711792,-0.09303180509761641,1739502659.4884777,19.809981107711792,-0.020312585772937833,1739502659.4884822,19.809981107711792,2.3206917000068925,1739502659.4884872,19.809981107711792,0.0,1739502659.4884918,19.809981107711792,0.14878894541317234,1739502659.4884965,19.809981107711792,6.26770396303551,1739502659.4885013,19.809981107711792,2.17190275459372 +1739502659.507277,19.829981088638306,40.160852959886405,1739502659.5072803,19.829981088638306,0.07808101464133355,1739502659.5072844,19.829981088638306,39.75296485304151,1739502659.5072894,19.829981088638306,46.08873324830353,1739502659.5072923,19.829981088638306,-0.10674082731390637,1739502659.5072958,19.829981088638306,-0.031168306355030487,1739502659.5072987,19.829981088638306,-0.09303180509761641,1739502659.5073018,19.829981088638306,-0.020312585772937833,1739502659.507305,19.829981088638306,2.3206917000068925,1739502659.5073082,19.829981088638306,0.0,1739502659.5073113,19.829981088638306,0.14878894541317234,1739502659.5073147,19.829981088638306,6.26770396303551,1739502659.507318,19.829981088638306,2.17190275459372 +1739502659.527499,19.84998106956482,40.160852959886405,1739502659.5275025,19.84998106956482,0.07808101464133355,1739502659.5275073,19.84998106956482,39.75296485304151,1739502659.5275118,19.84998106956482,46.08873324830353,1739502659.5275147,19.84998106956482,-0.10674082731390637,1739502659.5275183,19.84998106956482,-0.031168306355030487,1739502659.5275216,19.84998106956482,-0.09303180509761641,1739502659.5275247,19.84998106956482,-0.020312585772937833,1739502659.5275276,19.84998106956482,2.3206917000068925,1739502659.5275307,19.84998106956482,0.0,1739502659.527534,19.84998106956482,0.14878894541317234,1739502659.5275373,19.84998106956482,6.26770396303551,1739502659.5275407,19.84998106956482,2.17190275459372 +1739502659.5475645,19.869981050491333,40.40054661975757,1739502659.547568,19.869981050491333,0.07425862647786019,1739502659.5475721,19.869981050491333,39.75871750087842,1739502659.5475771,19.869981050491333,46.1270087284999,1739502659.5475798,19.869981050491333,-0.10523561180056575,1739502659.5475833,19.869981050491333,-0.031334441007508484,1739502659.547586,19.869981050491333,-0.08497963658148133,1739502659.5475895,19.869981050491333,-0.019882476025351446,1739502659.5475924,19.869981050491333,2.3356892337270203,1739502659.5475957,19.869981050491333,0.0,1739502659.5475988,19.869981050491333,0.14692905364489622,1739502659.547602,19.869981050491333,6.266683940176186,1739502659.547605,19.869981050491333,2.1881789635234625 +1739502659.5671763,19.889981031417847,40.40054661975757,1739502659.5671794,19.889981031417847,0.07425862647786019,1739502659.5671837,19.889981031417847,39.75871750087842,1739502659.5671883,19.889981031417847,46.1270087284999,1739502659.567191,19.889981031417847,-0.10523561180056575,1739502659.5671947,19.889981031417847,-0.031334441007508484,1739502659.5671978,19.889981031417847,-0.08497963658148133,1739502659.5672007,19.889981031417847,-0.019882476025351446,1739502659.5672038,19.889981031417847,2.3356892337270203,1739502659.5672069,19.889981031417847,0.0,1739502659.56721,19.889981031417847,0.14751027020355778,1739502659.567213,19.889981031417847,6.266683940176186,1739502659.5672164,19.889981031417847,2.1881789635234625 +1739502659.5870697,19.90998101234436,40.40054661975757,1739502659.5870733,19.90998101234436,0.07425862647786019,1739502659.5870776,19.90998101234436,39.75871750087842,1739502659.5870829,19.90998101234436,46.1270087284999,1739502659.5870855,19.90998101234436,-0.10523561180056575,1739502659.5870893,19.90998101234436,-0.031334441007508484,1739502659.5870924,19.90998101234436,-0.08497963658148133,1739502659.587096,19.90998101234436,-0.019882476025351446,1739502659.587099,19.90998101234436,2.3356892337270203,1739502659.5871024,19.90998101234436,0.0,1739502659.5871055,19.90998101234436,0.14751027020355778,1739502659.5871089,19.90998101234436,6.266683940176186,1739502659.5871124,19.90998101234436,2.1881789635234625 +1739502659.6072528,19.929980993270874,40.40054661975757,1739502659.6072562,19.929980993270874,0.07425862647786019,1739502659.6072607,19.929980993270874,39.75871750087842,1739502659.6072657,19.929980993270874,46.1270087284999,1739502659.6072683,19.929980993270874,-0.10523561180056575,1739502659.6072721,19.929980993270874,-0.031334441007508484,1739502659.6072752,19.929980993270874,-0.08497963658148133,1739502659.6072786,19.929980993270874,-0.019882476025351446,1739502659.607303,19.929980993270874,2.3356892337270203,1739502659.6073065,19.929980993270874,0.0,1739502659.6073096,19.929980993270874,0.14751027020355778,1739502659.6073132,19.929980993270874,6.266683940176186,1739502659.6073165,19.929980993270874,2.1881789635234625 +1739502659.6272595,19.949980974197388,40.40054661975757,1739502659.6272633,19.949980974197388,0.07425862647786019,1739502659.6272678,19.949980974197388,39.75871750087842,1739502659.6272728,19.949980974197388,46.1270087284999,1739502659.6272757,19.949980974197388,-0.10523561180056575,1739502659.6272795,19.949980974197388,-0.031334441007508484,1739502659.6272829,19.949980974197388,-0.08497963658148133,1739502659.6272864,19.949980974197388,-0.019882476025351446,1739502659.6272898,19.949980974197388,2.3356892337270203,1739502659.6272933,19.949980974197388,0.0,1739502659.627297,19.949980974197388,0.14751027020355778,1739502659.6273005,19.949980974197388,6.266683940176186,1739502659.6273038,19.949980974197388,2.1881789635234625 +1739502659.6462579,19.9699809551239,40.40054661975757,1739502659.6462603,19.9699809551239,0.07425862647786019,1739502659.6462634,19.9699809551239,39.75871750087842,1739502659.6462822,19.9699809551239,46.1270087284999,1739502659.6462839,19.9699809551239,-0.10523561180056575,1739502659.6462855,19.9699809551239,-0.031334441007508484,1739502659.646287,19.9699809551239,-0.08497963658148133,1739502659.6462882,19.9699809551239,-0.019882476025351446,1739502659.646289,19.9699809551239,2.3356892337270203,1739502659.646291,19.9699809551239,0.0,1739502659.6462922,19.9699809551239,0.14751027020355778,1739502659.6462934,19.9699809551239,6.266683940176186,1739502659.6462948,19.9699809551239,2.1881789635234625 +1739502659.6699843,19.989980936050415,40.6420194662428,1739502659.6699927,19.989980936050415,0.07016149347742928,1739502659.6700032,19.989980936050415,39.76451284919406,1739502659.6700137,19.989980936050415,46.16505063178227,1739502659.670019,19.989980936050415,-0.10370502497849401,1739502659.670025,19.989980936050415,-0.03146987823053875,1739502659.6700304,19.989980936050415,-0.07707359979906735,1739502659.6700351,19.989980936050415,-0.019385439659725175,1739502659.67004,19.989980936050415,2.3505088862062786,1739502659.6700451,19.989980936050415,0.0,1739502659.6700501,19.989980936050415,0.1455917012841062,1739502659.6700552,19.989980936050415,6.265663917316862,1739502659.6700604,19.989980936050415,2.204317631741746 +1739502659.689889,20.00998091697693,40.6420194662428,1739502659.6898975,20.00998091697693,0.07016149347742928,1739502659.689908,20.00998091697693,39.76451284919406,1739502659.6899178,20.00998091697693,46.16505063178227,1739502659.6899226,20.00998091697693,-0.10370502497849401,1739502659.6899288,20.00998091697693,-0.03146987823053875,1739502659.6899335,20.00998091697693,-0.07707359979906735,1739502659.6899385,20.00998091697693,-0.019385439659725175,1739502659.6899428,20.00998091697693,2.3505088862062786,1739502659.689948,20.00998091697693,0.0,1739502659.6899533,20.00998091697693,0.14619125446453252,1739502659.6899583,20.00998091697693,6.265663917316862,1739502659.6899633,20.00998091697693,2.204317631741746 +1739502659.7230983,20.0399808883667,40.6420194662428,1739502659.7231045,20.0399808883667,0.07016149347742928,1739502659.7231123,20.0399808883667,39.76451284919406,1739502659.7231195,20.0399808883667,46.16505063178227,1739502659.7231238,20.0399808883667,-0.10370502497849401,1739502659.7231283,20.0399808883667,-0.03146987823053875,1739502659.723132,20.0399808883667,-0.07707359979906735,1739502659.7231355,20.0399808883667,-0.019385439659725175,1739502659.723139,20.0399808883667,2.3505088862062786,1739502659.723143,20.0399808883667,0.0,1739502659.723147,20.0399808883667,0.14619125446453252,1739502659.7231505,20.0399808883667,6.265663917316862,1739502659.723155,20.0399808883667,2.204317631741746 +1739502659.7381604,20.059980869293213,40.6420194662428,1739502659.7381651,20.059980869293213,0.07016149347742928,1739502659.7381713,20.059980869293213,39.76451284919406,1739502659.7381785,20.059980869293213,46.16505063178227,1739502659.7381825,20.059980869293213,-0.10370502497849401,1739502659.7381878,20.059980869293213,-0.03146987823053875,1739502659.7381923,20.059980869293213,-0.07707359979906735,1739502659.738197,20.059980869293213,-0.019385439659725175,1739502659.7382016,20.059980869293213,2.3505088862062786,1739502659.7382064,20.059980869293213,0.0,1739502659.7382112,20.059980869293213,0.14619125446453252,1739502659.7382157,20.059980869293213,6.265663917316862,1739502659.7382205,20.059980869293213,2.204317631741746 +1739502659.756106,20.079980850219727,40.6420194662428,1739502659.7561092,20.079980850219727,0.07016149347742928,1739502659.7561138,20.079980850219727,39.76451284919406,1739502659.7561185,20.079980850219727,46.16505063178227,1739502659.7561212,20.079980850219727,-0.10370502497849401,1739502659.7561247,20.079980850219727,-0.03146987823053875,1739502659.7561278,20.079980850219727,-0.07707359979906735,1739502659.7561312,20.079980850219727,-0.019385439659725175,1739502659.756134,20.079980850219727,2.3505088862062786,1739502659.7561376,20.079980850219727,0.0,1739502659.7561407,20.079980850219727,0.14619125446453252,1739502659.756144,20.079980850219727,6.265663917316862,1739502659.7561471,20.079980850219727,2.204317631741746 +1739502659.775386,20.09998083114624,40.88525562182719,1739502659.775389,20.09998083114624,0.06578626219164718,1739502659.775393,20.09998083114624,40.23545844303586,1739502659.7753978,20.09998083114624,46.66726649226565,1739502659.7754004,20.09998083114624,-0.077323722127898,1739502659.7754037,20.09998083114624,-0.02474584964688027,1739502659.7754068,20.09998083114624,-0.03588487820101388,1739502659.77541,20.09998083114624,-0.008238493942223545,1739502659.775413,20.09998083114624,2.4292506354334176,1739502659.7754161,20.09998083114624,0.0,1739502659.7754195,20.09998083114624,0.23746411794082622,1739502659.7754226,20.09998083114624,6.264643894457537,1739502659.7754254,20.09998083114624,2.2203093060299306 +1739502659.7954724,20.119980812072754,40.88525562182719,1739502659.7954755,20.119980812072754,0.06578626219164718,1739502659.7954795,20.119980812072754,40.23545844303586,1739502659.795484,20.119980812072754,46.66726649226565,1739502659.7954867,20.119980812072754,-0.077323722127898,1739502659.79549,20.119980812072754,-0.02474584964688027,1739502659.7954934,20.119980812072754,-0.03588487820101388,1739502659.7954965,20.119980812072754,-0.008238493942223545,1739502659.7954993,20.119980812072754,2.4292506354334176,1739502659.7955027,20.119980812072754,0.0,1739502659.7955058,20.119980812072754,0.20894132940348698,1739502659.7955086,20.119980812072754,6.264643894457537,1739502659.7955117,20.119980812072754,2.2203093060299306 +1739502659.8156025,20.139980792999268,40.88525562182719,1739502659.8156059,20.139980792999268,0.06578626219164718,1739502659.81561,20.139980792999268,40.23545844303586,1739502659.815615,20.139980792999268,46.66726649226565,1739502659.8156176,20.139980792999268,-0.077323722127898,1739502659.8156211,20.139980792999268,-0.02474584964688027,1739502659.8156247,20.139980792999268,-0.03588487820101388,1739502659.815628,20.139980792999268,-0.008238493942223545,1739502659.8156312,20.139980792999268,2.4292506354334176,1739502659.8156345,20.139980792999268,0.0,1739502659.8156378,20.139980792999268,0.20894132940348698,1739502659.8156412,20.139980792999268,6.264643894457537,1739502659.8156445,20.139980792999268,2.2203093060299306 +1739502659.8348165,20.15998077392578,40.88525562182719,1739502659.8348196,20.15998077392578,0.06578626219164718,1739502659.8348236,20.15998077392578,40.23545844303586,1739502659.8348284,20.15998077392578,46.66726649226565,1739502659.8348308,20.15998077392578,-0.077323722127898,1739502659.8348343,20.15998077392578,-0.02474584964688027,1739502659.8348377,20.15998077392578,-0.03588487820101388,1739502659.8348408,20.15998077392578,-0.008238493942223545,1739502659.8348436,20.15998077392578,2.4292506354334176,1739502659.834847,20.15998077392578,0.0,1739502659.83485,20.15998077392578,0.20894132940348698,1739502659.8348534,20.15998077392578,6.264643894457537,1739502659.8348565,20.15998077392578,2.2203093060299306 +1739502659.8555822,20.179980754852295,40.88525562182719,1739502659.8555872,20.179980754852295,0.06578626219164718,1739502659.8555932,20.179980754852295,40.23545844303586,1739502659.8555996,20.179980754852295,46.66726649226565,1739502659.8556032,20.179980754852295,-0.077323722127898,1739502659.8556077,20.179980754852295,-0.02474584964688027,1739502659.8556125,20.179980754852295,-0.03588487820101388,1739502659.8556166,20.179980754852295,-0.008238493942223545,1739502659.8556206,20.179980754852295,2.4292506354334176,1739502659.8556325,20.179980754852295,0.0,1739502659.8556368,20.179980754852295,0.20894132940348698,1739502659.8556404,20.179980754852295,6.264643894457537,1739502659.8556447,20.179980754852295,2.2203093060299306 +1739502659.8757665,20.19998073577881,41.130575577449626,1739502659.8757699,20.19998073577881,0.06112316558355069,1739502659.8757741,20.19998073577881,40.24674316099449,1739502659.8757792,20.19998073577881,46.724049539602554,1739502659.8757818,20.19998073577881,-0.07377763773731365,1739502659.8757856,20.19998073577881,-0.02411286046801753,1739502659.8757887,20.19998073577881,-0.02546559156880641,1739502659.8757918,20.19998073577881,-0.00624738950560594,1739502659.8757951,20.19998073577881,2.4495841087561443,1739502659.8757982,20.19998073577881,0.0,1739502659.8758016,20.19998073577881,0.2053470182717255,1739502659.875805,20.19998073577881,6.263623871598213,1739502659.875808,20.19998073577881,2.243113867519301 +1739502659.8961296,20.219980716705322,41.130575577449626,1739502659.8961327,20.219980716705322,0.06112316558355069,1739502659.896137,20.219980716705322,40.24674316099449,1739502659.896142,20.219980716705322,46.724049539602554,1739502659.8961449,20.219980716705322,-0.07377763773731365,1739502659.8961484,20.219980716705322,-0.02411286046801753,1739502659.8961518,20.219980716705322,-0.02546559156880641,1739502659.896155,20.219980716705322,-0.00624738950560594,1739502659.8961582,20.219980716705322,2.4495841087561443,1739502659.8961616,20.219980716705322,0.0,1739502659.8961647,20.219980716705322,0.20647024123684332,1739502659.896168,20.219980716705322,6.263623871598213,1739502659.8961713,20.219980716705322,2.243113867519301 +1739502659.9141448,20.239980697631836,41.130575577449626,1739502659.9141474,20.239980697631836,0.06112316558355069,1739502659.9141502,20.239980697631836,40.24674316099449,1739502659.9141526,20.239980697631836,46.724049539602554,1739502659.9141543,20.239980697631836,-0.07377763773731365,1739502659.9141557,20.239980697631836,-0.02411286046801753,1739502659.9141572,20.239980697631836,-0.02546559156880641,1739502659.9141583,20.239980697631836,-0.00624738950560594,1739502659.9141595,20.239980697631836,2.4495841087561443,1739502659.9141612,20.239980697631836,0.0,1739502659.9141624,20.239980697631836,0.20647024123684332,1739502659.9141638,20.239980697631836,6.263623871598213,1739502659.9141653,20.239980697631836,2.243113867519301 +1739502659.934189,20.25998067855835,41.130575577449626,1739502659.9341917,20.25998067855835,0.06112316558355069,1739502659.9341943,20.25998067855835,40.24674316099449,1739502659.934197,20.25998067855835,46.724049539602554,1739502659.9341986,20.25998067855835,-0.07377763773731365,1739502659.9342,20.25998067855835,-0.02411286046801753,1739502659.9342012,20.25998067855835,-0.02546559156880641,1739502659.9342027,20.25998067855835,-0.00624738950560594,1739502659.9342039,20.25998067855835,2.4495841087561443,1739502659.9342055,20.25998067855835,0.0,1739502659.9342067,20.25998067855835,0.20647024123684332,1739502659.934208,20.25998067855835,6.263623871598213,1739502659.9342093,20.25998067855835,2.243113867519301 +1739502659.954159,20.279980659484863,41.130575577449626,1739502659.9541616,20.279980659484863,0.06112316558355069,1739502659.9541643,20.279980659484863,40.24674316099449,1739502659.9541671,20.279980659484863,46.724049539602554,1739502659.9541686,20.279980659484863,-0.07377763773731365,1739502659.9541702,20.279980659484863,-0.02411286046801753,1739502659.9541714,20.279980659484863,-0.02546559156880641,1739502659.9541726,20.279980659484863,-0.00624738950560594,1739502659.954174,20.279980659484863,2.4495841087561443,1739502659.9541755,20.279980659484863,0.0,1739502659.9541764,20.279980659484863,0.20647024123684332,1739502659.954178,20.279980659484863,6.263623871598213,1739502659.9541793,20.279980659484863,2.243113867519301 +1739502659.973975,20.299980640411377,41.130575577449626,1739502659.973977,20.299980640411377,0.06112316558355069,1739502659.97398,20.299980640411377,40.24674316099449,1739502659.9739826,20.299980640411377,46.724049539602554,1739502659.9739838,20.299980640411377,-0.07377763773731365,1739502659.9739854,20.299980640411377,-0.02411286046801753,1739502659.9739869,20.299980640411377,-0.02546559156880641,1739502659.973988,20.299980640411377,-0.00624738950560594,1739502659.9739895,20.299980640411377,2.4495841087561443,1739502659.973991,20.299980640411377,0.0,1739502659.973992,20.299980640411377,0.20647024123684332,1739502659.9739935,20.299980640411377,6.263623871598213,1739502659.9739947,20.299980640411377,2.243113867519301 +1739502659.9941995,20.31998062133789,41.37839862243923,1739502659.9942021,20.31998062133789,0.05615961564114702,1739502659.9942048,20.31998062133789,40.53216636987814,1739502659.9942071,20.31998062133789,47.05343377051037,1739502659.9942086,20.31998062133789,-0.04576913105106447,1739502659.99421,20.31998062133789,-0.017958970406470008,1739502659.9942114,20.31998062133789,0.014885095050759455,1739502659.9942126,20.31998062133789,0.0035484234466033617,1739502659.9942138,20.31998062133789,2.470406361251696,1739502659.9942155,20.31998062133789,0.0,1739502659.9942167,20.31998062133789,0.20391077768701377,1739502659.9942183,20.31998062133789,6.262603848738888,1739502659.9942195,20.31998062133789,2.2656957506809494 +1739502660.0140076,20.339980602264404,41.37839862243923,1739502660.0140097,20.339980602264404,0.05615961564114702,1739502660.014012,20.339980602264404,40.53216636987814,1739502660.0140147,20.339980602264404,47.05343377051037,1739502660.014016,20.339980602264404,-0.04576913105106447,1739502660.0140178,20.339980602264404,-0.017958970406470008,1739502660.014019,20.339980602264404,0.014885095050759455,1739502660.0140204,20.339980602264404,0.0035484234466033617,1739502660.0140216,20.339980602264404,2.470406361251696,1739502660.014023,20.339980602264404,0.0,1739502660.0140243,20.339980602264404,0.2047106105707468,1739502660.0140254,20.339980602264404,6.262603848738888,1739502660.014027,20.339980602264404,2.2656957506809494 +1739502660.033994,20.359980583190918,41.37839862243923,1739502660.033996,20.359980583190918,0.05615961564114702,1739502660.033999,20.359980583190918,40.53216636987814,1739502660.0340016,20.359980583190918,47.05343377051037,1739502660.034003,20.359980583190918,-0.04576913105106447,1739502660.0340044,20.359980583190918,-0.017958970406470008,1739502660.034006,20.359980583190918,0.014885095050759455,1739502660.0340073,20.359980583190918,0.0035484234466033617,1739502660.0340087,20.359980583190918,2.470406361251696,1739502660.0340104,20.359980583190918,0.0,1739502660.0340116,20.359980583190918,0.2047106105707468,1739502660.034013,20.359980583190918,6.262603848738888,1739502660.0340142,20.359980583190918,2.2656957506809494 +1739502660.054201,20.37998056411743,41.37839862243923,1739502660.0542035,20.37998056411743,0.05615961564114702,1739502660.0542061,20.37998056411743,40.53216636987814,1739502660.054209,20.37998056411743,47.05343377051037,1739502660.0542102,20.37998056411743,-0.04576913105106447,1739502660.054212,20.37998056411743,-0.017958970406470008,1739502660.0542133,20.37998056411743,0.014885095050759455,1739502660.0542147,20.37998056411743,0.0035484234466033617,1739502660.054216,20.37998056411743,2.470406361251696,1739502660.0542176,20.37998056411743,0.0,1739502660.054219,20.37998056411743,0.2047106105707468,1739502660.0542202,20.37998056411743,6.262603848738888,1739502660.0542219,20.37998056411743,2.2656957506809494 +1739502660.0740569,20.399980545043945,41.37839862243923,1739502660.0740592,20.399980545043945,0.05615961564114702,1739502660.074062,20.399980545043945,40.53216636987814,1739502660.074065,20.399980545043945,47.05343377051037,1739502660.0740662,20.399980545043945,-0.04576913105106447,1739502660.074068,20.399980545043945,-0.017958970406470008,1739502660.0740693,20.399980545043945,0.014885095050759455,1739502660.0740705,20.399980545043945,0.0035484234466033617,1739502660.074072,20.399980545043945,2.470406361251696,1739502660.0740733,20.399980545043945,0.0,1739502660.0740743,20.399980545043945,0.2047106105707468,1739502660.074076,20.399980545043945,6.262603848738888,1739502660.0740771,20.399980545043945,2.2656957506809494 +1739502660.094172,20.41998052597046,41.62869065371662,1739502660.0941744,20.41998052597046,0.050891207946068384,1739502660.0941772,20.41998052597046,41.09075082753695,1739502660.09418,20.41998052597046,47.65183856766991,1739502660.0941813,20.41998052597046,0.030463601223921777,1739502660.0941832,20.41998052597046,-0.003391503694155559,1739502660.0941844,20.41998052597046,0.10967595770776628,1739502660.0941858,20.41998052597046,0.023217311722467934,1739502660.094187,20.41998052597046,2.2899957592486344,1739502660.0941887,20.41998052597046,0.0,1739502660.0941901,20.41998052597046,-0.09027405052829474,1739502660.0941916,20.41998052597046,6.261583825879564,1739502660.094193,20.41998052597046,2.2880870427437467 +1739502660.1140144,20.439980506896973,41.62869065371662,1739502660.1140165,20.439980506896973,0.050891207946068384,1739502660.1140194,20.439980506896973,41.09075082753695,1739502660.1140223,20.439980506896973,47.65183856766991,1739502660.1140237,20.439980506896973,0.030463601223921777,1739502660.114025,20.439980506896973,-0.003391503694155559,1739502660.1140265,20.439980506896973,0.10967595770776628,1739502660.114028,20.439980506896973,0.023217311722467934,1739502660.1140294,20.439980506896973,2.2899957592486344,1739502660.1140308,20.439980506896973,0.0,1739502660.114032,20.439980506896973,0.0019087165048876642,1739502660.1140337,20.439980506896973,6.261583825879564,1739502660.114035,20.439980506896973,2.2880870427437467 +1739502660.1340258,20.459980487823486,41.62869065371662,1739502660.1340277,20.459980487823486,0.050891207946068384,1739502660.1340306,20.459980487823486,41.09075082753695,1739502660.1340334,20.459980487823486,47.65183856766991,1739502660.1340346,20.459980487823486,0.030463601223921777,1739502660.1340363,20.459980487823486,-0.003391503694155559,1739502660.1340377,20.459980487823486,0.10967595770776628,1739502660.134039,20.459980487823486,0.023217311722467934,1739502660.1340404,20.459980487823486,2.2899957592486344,1739502660.1340418,20.459980487823486,0.0,1739502660.1340432,20.459980487823486,0.0019087165048876642,1739502660.1340446,20.459980487823486,6.261583825879564,1739502660.1340458,20.459980487823486,2.2880870427437467 +1739502660.154517,20.47998046875,41.62869065371662,1739502660.1545203,20.47998046875,0.050891207946068384,1739502660.1545236,20.47998046875,41.09075082753695,1739502660.1545267,20.47998046875,47.65183856766991,1739502660.1545286,20.47998046875,0.030463601223921777,1739502660.1545303,20.47998046875,-0.003391503694155559,1739502660.1545322,20.47998046875,0.10967595770776628,1739502660.1545336,20.47998046875,0.023217311722467934,1739502660.1545348,20.47998046875,2.2899957592486344,1739502660.154537,20.47998046875,0.0,1739502660.1545384,20.47998046875,0.0019087165048876642,1739502660.15454,20.47998046875,6.261583825879564,1739502660.1545417,20.47998046875,2.2880870427437467 +1739502660.1748147,20.499980449676514,41.62869065371662,1739502660.1748183,20.499980449676514,0.050891207946068384,1739502660.1748223,20.499980449676514,41.09075082753695,1739502660.1748264,20.499980449676514,47.65183856766991,1739502660.1748288,20.499980449676514,0.030463601223921777,1739502660.1748312,20.499980449676514,-0.003391503694155559,1739502660.174833,20.499980449676514,0.10967595770776628,1739502660.1748352,20.499980449676514,0.023217311722467934,1739502660.1748369,20.499980449676514,2.2899957592486344,1739502660.1748393,20.499980449676514,0.0,1739502660.1748414,20.499980449676514,0.0019087165048876642,1739502660.1748433,20.499980449676514,6.261583825879564,1739502660.1748455,20.499980449676514,2.2880870427437467 +1739502660.1958978,20.519980430603027,41.62869065371662,1739502660.1959014,20.519980430603027,0.050891207946068384,1739502660.1959062,20.519980430603027,41.09075082753695,1739502660.1959107,20.519980430603027,47.65183856766991,1739502660.1959126,20.519980430603027,0.030463601223921777,1739502660.1959155,20.519980430603027,-0.003391503694155559,1739502660.1959176,20.519980430603027,0.10967595770776628,1739502660.19592,20.519980430603027,0.023217311722467934,1739502660.195922,20.519980430603027,2.2899957592486344,1739502660.1959248,20.519980430603027,0.0,1739502660.1959267,20.519980430603027,0.0019087165048876642,1739502660.195929,20.519980430603027,6.261583825879564,1739502660.1959314,20.519980430603027,2.2880870427437467 +1739502660.215594,20.53998041152954,41.880155505141815,1739502660.2155983,20.53998041152954,0.04536335382304735,1739502660.2156034,20.53998041152954,41.10131235129681,1739502660.2156084,20.53998041152954,47.65907257186002,1739502660.215611,20.53998041152954,0.03161796359468503,1739502660.2156136,20.53998041152954,-0.002378536350053623,1739502660.215616,20.53998041152954,0.1155448740919237,1739502660.2156184,20.53998041152954,0.02657083279398141,1739502660.2156203,20.53998041152954,2.2792691255353534,1739502660.2156231,20.53998041152954,0.0,1739502660.2156255,20.53998041152954,-0.011340212720350714,1739502660.2156281,20.53998041152954,6.260811286249056,1739502660.2156303,20.53998041152954,2.2864690451582295 +1739502660.234198,20.559980392456055,41.880155505141815,1739502660.2342012,20.559980392456055,0.04536335382304735,1739502660.2342038,20.559980392456055,41.10131235129681,1739502660.2342064,20.559980392456055,47.65907257186002,1739502660.234208,20.559980392456055,0.03161796359468503,1739502660.2342095,20.559980392456055,-0.002378536350053623,1739502660.2342107,20.559980392456055,0.1155448740919237,1739502660.2342122,20.559980392456055,0.02657083279398141,1739502660.234213,20.559980392456055,2.2792691255353534,1739502660.234215,20.559980392456055,0.0,1739502660.2342162,20.559980392456055,-0.007199919622876028,1739502660.2342174,20.559980392456055,6.260811286249056,1739502660.2342188,20.559980392456055,2.2864690451582295 +1739502660.254254,20.57998037338257,41.880155505141815,1739502660.254257,20.57998037338257,0.04536335382304735,1739502660.2542593,20.57998037338257,41.10131235129681,1739502660.254262,20.57998037338257,47.65907257186002,1739502660.2542634,20.57998037338257,0.03161796359468503,1739502660.2542648,20.57998037338257,-0.002378536350053623,1739502660.2542658,20.57998037338257,0.1155448740919237,1739502660.2542675,20.57998037338257,0.02657083279398141,1739502660.2542684,20.57998037338257,2.2792691255353534,1739502660.2542698,20.57998037338257,0.0,1739502660.2542715,20.57998037338257,-0.007199919622876028,1739502660.2542727,20.57998037338257,6.260811286249056,1739502660.2542741,20.57998037338257,2.2864690451582295 +1739502660.2739797,20.599980354309082,41.880155505141815,1739502660.2739818,20.599980354309082,0.04536335382304735,1739502660.2739842,20.599980354309082,41.10131235129681,1739502660.2739866,20.599980354309082,47.65907257186002,1739502660.2739878,20.599980354309082,0.03161796359468503,1739502660.2739894,20.599980354309082,-0.002378536350053623,1739502660.2739906,20.599980354309082,0.1155448740919237,1739502660.2739918,20.599980354309082,0.02657083279398141,1739502660.273993,20.599980354309082,2.2792691255353534,1739502660.2739942,20.599980354309082,0.0,1739502660.2739956,20.599980354309082,-0.007199919622876028,1739502660.2739968,20.599980354309082,6.260811286249056,1739502660.273998,20.599980354309082,2.2864690451582295 +1739502660.2941225,20.619980335235596,41.880155505141815,1739502660.294125,20.619980335235596,0.04536335382304735,1739502660.2941277,20.619980335235596,41.10131235129681,1739502660.29413,20.619980335235596,47.65907257186002,1739502660.2941315,20.619980335235596,0.03161796359468503,1739502660.294133,20.619980335235596,-0.002378536350053623,1739502660.2941344,20.619980335235596,0.1155448740919237,1739502660.2941356,20.619980335235596,0.02657083279398141,1739502660.2941368,20.619980335235596,2.2792691255353534,1739502660.2941382,20.619980335235596,0.0,1739502660.2941391,20.619980335235596,-0.007199919622876028,1739502660.2941403,20.619980335235596,6.260811286249056,1739502660.2941418,20.619980335235596,2.2864690451582295 +1739502660.3140323,20.63998031616211,42.13156532001124,1739502660.3140345,20.63998031616211,0.03966803554498899,1739502660.314037,20.63998031616211,41.36633345458069,1739502660.3140395,20.63998031616211,47.91861408684147,1739502660.314041,20.63998031616211,0.07681892802389217,1739502660.3140423,20.63998031616211,0.006419573021337762,1739502660.3140438,20.63998031616211,0.16994116767759024,1739502660.314045,20.63998031616211,0.03896755978940899,1739502660.314046,20.63998031616211,2.1822092863570672,1739502660.3140476,20.63998031616211,0.0,1739502660.3140488,20.63998031616211,-0.14724540986905693,1739502660.31405,20.63998031616211,6.260235489074008,1739502660.3140514,20.63998031616211,2.285690451830118 +1739502660.3342206,20.659980297088623,42.13156532001124,1739502660.3342228,20.659980297088623,0.03966803554498899,1739502660.334226,20.659980297088623,41.36633345458069,1739502660.3342285,20.659980297088623,47.91861408684147,1739502660.33423,20.659980297088623,0.07681892802389217,1739502660.3342316,20.659980297088623,0.006419573021337762,1739502660.334233,20.659980297088623,0.16994116767759024,1739502660.3342345,20.659980297088623,0.03896755978940899,1739502660.3342357,20.659980297088623,2.1822092863570672,1739502660.334237,20.659980297088623,0.0,1739502660.3342385,20.659980297088623,-0.10348116547305075,1739502660.33424,20.659980297088623,6.260235489074008,1739502660.3342416,20.659980297088623,2.285690451830118 +1739502660.3542445,20.679980278015137,42.13156532001124,1739502660.3542469,20.679980278015137,0.03966803554498899,1739502660.35425,20.679980278015137,41.36633345458069,1739502660.3542528,20.679980278015137,47.91861408684147,1739502660.3542542,20.679980278015137,0.07681892802389217,1739502660.3542562,20.679980278015137,0.006419573021337762,1739502660.3542573,20.679980278015137,0.16994116767759024,1739502660.354259,20.679980278015137,0.03896755978940899,1739502660.3542602,20.679980278015137,2.1822092863570672,1739502660.3542619,20.679980278015137,0.0,1739502660.354263,20.679980278015137,-0.10348116547305075,1739502660.3542645,20.679980278015137,6.260235489074008,1739502660.3542662,20.679980278015137,2.285690451830118 +1739502660.3740783,20.69998025894165,42.13156532001124,1739502660.3740807,20.69998025894165,0.03966803554498899,1739502660.3740835,20.69998025894165,41.36633345458069,1739502660.3740866,20.69998025894165,47.91861408684147,1739502660.3740883,20.69998025894165,0.07681892802389217,1739502660.3740897,20.69998025894165,0.006419573021337762,1739502660.3740911,20.69998025894165,0.16994116767759024,1739502660.3740928,20.69998025894165,0.03896755978940899,1739502660.374094,20.69998025894165,2.1822092863570672,1739502660.374096,20.69998025894165,0.0,1739502660.3740973,20.69998025894165,-0.10348116547305075,1739502660.3740988,20.69998025894165,6.260235489074008,1739502660.3741002,20.69998025894165,2.285690451830118 +1739502660.3944814,20.719980239868164,42.13156532001124,1739502660.3944845,20.719980239868164,0.03966803554498899,1739502660.394488,20.719980239868164,41.36633345458069,1739502660.3944912,20.719980239868164,47.91861408684147,1739502660.3944926,20.719980239868164,0.07681892802389217,1739502660.3944948,20.719980239868164,0.006419573021337762,1739502660.3944962,20.719980239868164,0.16994116767759024,1739502660.394498,20.719980239868164,0.03896755978940899,1739502660.3944993,20.719980239868164,2.1822092863570672,1739502660.3945012,20.719980239868164,0.0,1739502660.3945026,20.719980239868164,-0.10348116547305075,1739502660.3945043,20.719980239868164,6.260235489074008,1739502660.3945057,20.719980239868164,2.285690451830118 +1739502660.4142923,20.739980220794678,42.13156532001124,1739502660.4142947,20.739980220794678,0.03966803554498899,1739502660.4142978,20.739980220794678,41.36633345458069,1739502660.4143012,20.739980220794678,47.91861408684147,1739502660.4143028,20.739980220794678,0.07681892802389217,1739502660.4143045,20.739980220794678,0.006419573021337762,1739502660.4143062,20.739980220794678,0.16994116767759024,1739502660.4143076,20.739980220794678,0.03896755978940899,1739502660.414309,20.739980220794678,2.1822092863570672,1739502660.414311,20.739980220794678,0.0,1739502660.4143121,20.739980220794678,-0.10348116547305075,1739502660.4143138,20.739980220794678,6.260235489074008,1739502660.4143152,20.739980220794678,2.285690451830118 +1739502660.4343798,20.75998020172119,42.38227410688138,1739502660.434382,20.75998020172119,0.03387879092921953,1739502660.4343853,20.75998020172119,41.92004264356099,1739502660.4343886,20.75998020172119,48.436127982190776,1739502660.4343903,20.75998020172119,0.18737848983622982,1739502660.434392,20.75998020172119,0.025350267644062417,1739502660.4343936,20.75998020172119,0.2934677824597324,1739502660.434395,20.75998020172119,0.06144943808479767,1739502660.4343965,20.75998020172119,1.9768734003699218,1739502660.4343982,20.75998020172119,0.0,1739502660.4343998,20.75998020172119,-0.38441196485050616,1739502660.4344013,20.75998020172119,6.260055970508774,1739502660.4344027,20.75998020172119,2.2734944328547524 +1739502660.4544842,20.779980182647705,42.38227410688138,1739502660.4544878,20.779980182647705,0.03387879092921953,1739502660.454492,20.779980182647705,41.92004264356099,1739502660.4544954,20.779980182647705,48.436127982190776,1739502660.4544973,20.779980182647705,0.18737848983622982,1739502660.4544992,20.779980182647705,0.025350267644062417,1739502660.454501,20.779980182647705,0.2934677824597324,1739502660.4545026,20.779980182647705,0.06144943808479767,1739502660.4545043,20.779980182647705,1.9768734003699218,1739502660.454506,20.779980182647705,0.0,1739502660.4545076,20.779980182647705,-0.2966210324848306,1739502660.454509,20.779980182647705,6.260055970508774,1739502660.454511,20.779980182647705,2.2734944328547524 +1739502660.474235,20.79998016357422,42.38227410688138,1739502660.4742374,20.79998016357422,0.03387879092921953,1739502660.4742408,20.79998016357422,41.92004264356099,1739502660.4742439,20.79998016357422,48.436127982190776,1739502660.4742453,20.79998016357422,0.18737848983622982,1739502660.4742472,20.79998016357422,0.025350267644062417,1739502660.4742486,20.79998016357422,0.2934677824597324,1739502660.4742503,20.79998016357422,0.06144943808479767,1739502660.4742517,20.79998016357422,1.9768734003699218,1739502660.4742537,20.79998016357422,0.0,1739502660.474255,20.79998016357422,-0.2966210324848306,1739502660.4742568,20.79998016357422,6.260055970508774,1739502660.4742582,20.79998016357422,2.2734944328547524 +1739502660.4944742,20.819980144500732,42.38227410688138,1739502660.4944777,20.819980144500732,0.03387879092921953,1739502660.494481,20.819980144500732,41.92004264356099,1739502660.4944842,20.819980144500732,48.436127982190776,1739502660.4944859,20.819980144500732,0.18737848983622982,1739502660.4944875,20.819980144500732,0.025350267644062417,1739502660.4944894,20.819980144500732,0.2934677824597324,1739502660.4944909,20.819980144500732,0.06144943808479767,1739502660.494492,20.819980144500732,1.9768734003699218,1739502660.4944942,20.819980144500732,0.0,1739502660.4944956,20.819980144500732,-0.2966210324848306,1739502660.4944973,20.819980144500732,6.260055970508774,1739502660.4944987,20.819980144500732,2.2734944328547524 +1739502660.5142438,20.839980125427246,42.38227410688138,1739502660.5142465,20.839980125427246,0.03387879092921953,1739502660.5142498,20.839980125427246,41.92004264356099,1739502660.514253,20.839980125427246,48.436127982190776,1739502660.5142546,20.839980125427246,0.18737848983622982,1739502660.5142567,20.839980125427246,0.025350267644062417,1739502660.5142581,20.839980125427246,0.2934677824597324,1739502660.5142598,20.839980125427246,0.06144943808479767,1739502660.5142612,20.839980125427246,1.9768734003699218,1739502660.5142632,20.839980125427246,0.0,1739502660.5142646,20.839980125427246,-0.2966210324848306,1739502660.514266,20.839980125427246,6.260055970508774,1739502660.5142677,20.839980125427246,2.2734944328547524 +1739502660.5342624,20.85998010635376,42.63055076206798,1739502660.534265,20.85998010635376,0.028158289059372343,1739502660.5342684,20.85998010635376,41.92525645331991,1739502660.5342712,20.85998010635376,48.36851127783877,1739502660.534273,20.85998010635376,0.17100270668130552,1739502660.534275,20.85998010635376,0.02488949153065129,1739502660.5342767,20.85998010635376,0.2734403215586774,1739502660.5342782,20.85998010635376,0.06373445146946112,1739502660.5342796,20.85998010635376,2.0088018998555888,1739502660.5342817,20.85998010635376,0.0,1739502660.534283,20.85998010635376,-0.19578897123722167,1739502660.5342846,20.85998010635376,6.260416901114716,1739502660.534286,20.85998010635376,2.2361009108922802 +1739502660.5544887,20.879980087280273,42.63055076206798,1739502660.554492,20.879980087280273,0.028158289059372343,1739502660.554496,20.879980087280273,41.92525645331991,1739502660.5544994,20.879980087280273,48.36851127783877,1739502660.5545008,20.879980087280273,0.17100270668130552,1739502660.5545032,20.879980087280273,0.02488949153065129,1739502660.5545046,20.879980087280273,0.2734403215586774,1739502660.5545068,20.879980087280273,0.06373445146946112,1739502660.5545082,20.879980087280273,2.0088018998555888,1739502660.55451,20.879980087280273,0.0,1739502660.5545118,20.879980087280273,-0.22729901103669148,1739502660.5545135,20.879980087280273,6.260416901114716,1739502660.5545151,20.879980087280273,2.2361009108922802 +1739502660.574253,20.899980068206787,42.63055076206798,1739502660.5742555,20.899980068206787,0.028158289059372343,1739502660.5742588,20.899980068206787,41.92525645331991,1739502660.5742617,20.899980068206787,48.36851127783877,1739502660.5742633,20.899980068206787,0.17100270668130552,1739502660.574265,20.899980068206787,0.02488949153065129,1739502660.5742667,20.899980068206787,0.2734403215586774,1739502660.5742679,20.899980068206787,0.06373445146946112,1739502660.5742695,20.899980068206787,2.0088018998555888,1739502660.5742712,20.899980068206787,0.0,1739502660.5742729,20.899980068206787,-0.22729901103669148,1739502660.5742743,20.899980068206787,6.260416901114716,1739502660.5742757,20.899980068206787,2.2361009108922802 +1739502660.5944765,20.9199800491333,42.63055076206798,1739502660.5944796,20.9199800491333,0.028158289059372343,1739502660.5944836,20.9199800491333,41.92525645331991,1739502660.5944867,20.9199800491333,48.36851127783877,1739502660.5944884,20.9199800491333,0.17100270668130552,1739502660.5944903,20.9199800491333,0.02488949153065129,1739502660.594492,20.9199800491333,0.2734403215586774,1739502660.5944934,20.9199800491333,0.06373445146946112,1739502660.594495,20.9199800491333,2.0088018998555888,1739502660.5944967,20.9199800491333,0.0,1739502660.5944984,20.9199800491333,-0.22729901103669148,1739502660.5944998,20.9199800491333,6.260416901114716,1739502660.5945013,20.9199800491333,2.2361009108922802 +1739502660.614257,20.939980030059814,42.63055076206798,1739502660.6142595,20.939980030059814,0.028158289059372343,1739502660.6142628,20.939980030059814,41.92525645331991,1739502660.6142657,20.939980030059814,48.36851127783877,1739502660.6142673,20.939980030059814,0.17100270668130552,1739502660.6142693,20.939980030059814,0.02488949153065129,1739502660.6142712,20.939980030059814,0.2734403215586774,1739502660.6142726,20.939980030059814,0.06373445146946112,1739502660.614274,20.939980030059814,2.0088018998555888,1739502660.614276,20.939980030059814,0.0,1739502660.6142774,20.939980030059814,-0.22729901103669148,1739502660.6142788,20.939980030059814,6.260416901114716,1739502660.6142805,20.939980030059814,2.2361009108922802 +1739502660.6342993,20.959980010986328,42.63055076206798,1739502660.6343017,20.959980010986328,0.028158289059372343,1739502660.634305,20.959980010986328,41.92525645331991,1739502660.634308,20.959980010986328,48.36851127783877,1739502660.6343095,20.959980010986328,0.17100270668130552,1739502660.6343114,20.959980010986328,0.02488949153065129,1739502660.6343129,20.959980010986328,0.2734403215586774,1739502660.6343145,20.959980010986328,0.06373445146946112,1739502660.634316,20.959980010986328,2.0088018998555888,1739502660.6343179,20.959980010986328,0.0,1739502660.634319,20.959980010986328,-0.22729901103669148,1739502660.634321,20.959980010986328,6.260416901114716,1739502660.6343224,20.959980010986328,2.2361009108922802 +1739502660.6570318,20.979979991912842,42.87527395127038,1739502660.6570354,20.979979991912842,0.02269722461958068,1739502660.6570399,20.979979991912842,41.930395640293156,1739502660.6570454,20.979979991912842,48.32632746985634,1739502660.657048,20.979979991912842,0.16087859276552233,1739502660.6570518,20.979979991912842,0.02534405153281382,1739502660.6570554,20.979979991912842,0.2565498885888257,1739502660.6570587,20.979979991912842,0.06625559435617998,1739502660.657062,20.979979991912842,2.0361297427666805,1739502660.6570656,20.979979991912842,0.0,1739502660.657069,20.979979991912842,-0.1522614858501486,1739502660.6570728,20.979979991912842,6.261462821346988,1739502660.6570766,20.979979991912842,2.211840470612145 +1739502660.6740088,20.999979972839355,42.87527395127038,1739502660.674011,20.999979972839355,0.02269722461958068,1739502660.6740134,20.999979972839355,41.930395640293156,1739502660.6740158,20.999979972839355,48.32632746985634,1739502660.674017,20.999979972839355,0.16087859276552233,1739502660.6740186,20.999979972839355,0.02534405153281382,1739502660.67402,20.999979972839355,0.2565498885888257,1739502660.6740215,20.999979972839355,0.06625559435617998,1739502660.6740224,20.999979972839355,2.0361297427666805,1739502660.6740239,20.999979972839355,0.0,1739502660.6740253,20.999979972839355,-0.17571072784546438,1739502660.6740265,20.999979972839355,6.261462821346988,1739502660.674028,20.999979972839355,2.211840470612145 +1739502660.6942549,21.01997995376587,42.87527395127038,1739502660.6942573,21.01997995376587,0.02269722461958068,1739502660.6942601,21.01997995376587,41.930395640293156,1739502660.6942627,21.01997995376587,48.32632746985634,1739502660.6942644,21.01997995376587,0.16087859276552233,1739502660.694266,21.01997995376587,0.02534405153281382,1739502660.6942673,21.01997995376587,0.2565498885888257,1739502660.6942687,21.01997995376587,0.06625559435617998,1739502660.6942697,21.01997995376587,2.0361297427666805,1739502660.6942713,21.01997995376587,0.0,1739502660.6942725,21.01997995376587,-0.17571072784546438,1739502660.694274,21.01997995376587,6.261462821346988,1739502660.6942756,21.01997995376587,2.211840470612145 +1739502660.7140412,21.039979934692383,42.87527395127038,1739502660.7140434,21.039979934692383,0.02269722461958068,1739502660.7140462,21.039979934692383,41.930395640293156,1739502660.7140489,21.039979934692383,48.32632746985634,1739502660.71405,21.039979934692383,0.16087859276552233,1739502660.7140517,21.039979934692383,0.02534405153281382,1739502660.7140532,21.039979934692383,0.2565498885888257,1739502660.7140543,21.039979934692383,0.06625559435617998,1739502660.7140558,21.039979934692383,2.0361297427666805,1739502660.7140572,21.039979934692383,0.0,1739502660.7140584,21.039979934692383,-0.17571072784546438,1739502660.71406,21.039979934692383,6.261462821346988,1739502660.7140615,21.039979934692383,2.211840470612145 +1739502660.7340472,21.059979915618896,42.87527395127038,1739502660.7340493,21.059979915618896,0.02269722461958068,1739502660.7340522,21.059979915618896,41.930395640293156,1739502660.7340546,21.059979915618896,48.32632746985634,1739502660.734056,21.059979915618896,0.16087859276552233,1739502660.7340574,21.059979915618896,0.02534405153281382,1739502660.734059,21.059979915618896,0.2565498885888257,1739502660.7340603,21.059979915618896,0.06625559435617998,1739502660.7340615,21.059979915618896,2.0361297427666805,1739502660.7340631,21.059979915618896,0.0,1739502660.7340643,21.059979915618896,-0.17571072784546438,1739502660.7340658,21.059979915618896,6.261462821346988,1739502660.734067,21.059979915618896,2.211840470612145 +1739502660.754207,21.07997989654541,43.117548869564786,1739502660.7542093,21.07997989654541,0.017559468562168057,1739502660.7542124,21.07997989654541,42.405758107181526,1739502660.7542152,21.07997989654541,48.74665945257205,1739502660.7542164,21.07997989654541,0.2792485856695426,1739502660.7542183,21.07997989654541,0.04645509052929829,1739502660.7542198,21.07997989654541,0.3773862329052562,1739502660.7542212,21.07997989654541,0.09124229402122258,1739502660.7542226,21.07997989654541,1.8485133945667873,1739502660.7542238,21.07997989654541,0.0,1739502660.7542253,21.07997989654541,-0.4205919200284161,1739502660.7542267,21.07997989654541,6.262620671619223,1739502660.7542279,21.07997989654541,2.192579891864054 +1739502660.774067,21.099979877471924,43.117548869564786,1739502660.774069,21.099979877471924,0.017559468562168057,1739502660.7740717,21.099979877471924,42.405758107181526,1739502660.7740746,21.099979877471924,48.74665945257205,1739502660.774076,21.099979877471924,0.2792485856695426,1739502660.7740777,21.099979877471924,0.04645509052929829,1739502660.7740793,21.099979877471924,0.3773862329052562,1739502660.7740805,21.099979877471924,0.09124229402122258,1739502660.7740817,21.099979877471924,1.8485133945667873,1739502660.7740834,21.099979877471924,0.0,1739502660.7740848,21.099979877471924,-0.3440664972972667,1739502660.7740862,21.099979877471924,6.262620671619223,1739502660.7740877,21.099979877471924,2.192579891864054 +1739502660.7941985,21.119979858398438,43.117548869564786,1739502660.7942011,21.119979858398438,0.017559468562168057,1739502660.7942045,21.119979858398438,42.405758107181526,1739502660.7942076,21.119979858398438,48.74665945257205,1739502660.794209,21.119979858398438,0.2792485856695426,1739502660.7942111,21.119979858398438,0.04645509052929829,1739502660.7942128,21.119979858398438,0.3773862329052562,1739502660.7942147,21.119979858398438,0.09124229402122258,1739502660.7942162,21.119979858398438,1.8485133945667873,1739502660.7942183,21.119979858398438,0.0,1739502660.7942197,21.119979858398438,-0.3440664972972667,1739502660.7942214,21.119979858398438,6.262620671619223,1739502660.794223,21.119979858398438,2.192579891864054 +1739502660.8141124,21.13997983932495,43.117548869564786,1739502660.8141148,21.13997983932495,0.017559468562168057,1739502660.8141177,21.13997983932495,42.405758107181526,1739502660.8141203,21.13997983932495,48.74665945257205,1739502660.8141217,21.13997983932495,0.2792485856695426,1739502660.8141232,21.13997983932495,0.04645509052929829,1739502660.8141248,21.13997983932495,0.3773862329052562,1739502660.8141263,21.13997983932495,0.09124229402122258,1739502660.8141277,21.13997983932495,1.8485133945667873,1739502660.814129,21.13997983932495,0.0,1739502660.8141305,21.13997983932495,-0.3440664972972667,1739502660.814132,21.13997983932495,6.262620671619223,1739502660.8141332,21.13997983932495,2.192579891864054 +1739502660.8340619,21.159979820251465,43.117548869564786,1739502660.8340642,21.159979820251465,0.017559468562168057,1739502660.8340669,21.159979820251465,42.405758107181526,1739502660.8340697,21.159979820251465,48.74665945257205,1739502660.834071,21.159979820251465,0.2792485856695426,1739502660.8340728,21.159979820251465,0.04645509052929829,1739502660.834074,21.159979820251465,0.3773862329052562,1739502660.8340757,21.159979820251465,0.09124229402122258,1739502660.834077,21.159979820251465,1.8485133945667873,1739502660.8340786,21.159979820251465,0.0,1739502660.8340797,21.159979820251465,-0.3440664972972667,1739502660.8340812,21.159979820251465,6.262620671619223,1739502660.8340826,21.159979820251465,2.192579891864054 +1739502660.8542502,21.17997980117798,43.117548869564786,1739502660.8542528,21.17997980117798,0.017559468562168057,1739502660.8542562,21.17997980117798,42.405758107181526,1739502660.8542588,21.17997980117798,48.74665945257205,1739502660.85426,21.17997980117798,0.2792485856695426,1739502660.8542619,21.17997980117798,0.04645509052929829,1739502660.854263,21.17997980117798,0.3773862329052562,1739502660.8542643,21.17997980117798,0.09124229402122258,1739502660.8542657,21.17997980117798,1.8485133945667873,1739502660.8542671,21.17997980117798,0.0,1739502660.8542683,21.17997980117798,-0.3440664972972667,1739502660.85427,21.17997980117798,6.262620671619223,1739502660.8542714,21.17997980117798,2.192579891864054 +1739502660.874129,21.199979782104492,43.35672332394124,1739502660.8741314,21.199979782104492,0.012794452863626127,1739502660.8741345,21.199979782104492,42.94373257370135,1739502660.8741372,21.199979782104492,49.17603044332558,1739502660.8741386,21.199979782104492,0.44277049110782046,1739502660.8741403,21.199979782104492,0.07375381816577531,1739502660.8741417,21.199979782104492,0.5403121025338296,1739502660.874143,21.199979782104492,0.12180358883113859,1739502660.8741443,21.199979782104492,1.6226182525163046,1739502660.874146,21.199979782104492,0.0,1739502660.8741477,21.199979782104492,-0.615675943420431,1739502660.874149,21.199979782104492,6.264210523691987,1739502660.8741505,21.199979782104492,2.1534161883728884 +1739502660.8942347,21.219979763031006,43.35672332394124,1739502660.8942373,21.219979763031006,0.012794452863626127,1739502660.8942401,21.219979763031006,42.94373257370135,1739502660.894243,21.219979763031006,49.17603044332558,1739502660.8942444,21.219979763031006,0.44277049110782046,1739502660.894246,21.219979763031006,0.07375381816577531,1739502660.8942478,21.219979763031006,0.5403121025338296,1739502660.894249,21.219979763031006,0.12180358883113859,1739502660.8942502,21.219979763031006,1.6226182525163046,1739502660.8942518,21.219979763031006,0.0,1739502660.8942533,21.219979763031006,-0.5307979358565837,1739502660.8942547,21.219979763031006,6.264210523691987,1739502660.8942564,21.219979763031006,2.1534161883728884 +1739502660.9140916,21.23997974395752,43.35672332394124,1739502660.9140937,21.23997974395752,0.012794452863626127,1739502660.9140966,21.23997974395752,42.94373257370135,1739502660.9140995,21.23997974395752,49.17603044332558,1739502660.9141006,21.23997974395752,0.44277049110782046,1739502660.9141023,21.23997974395752,0.07375381816577531,1739502660.9141037,21.23997974395752,0.5403121025338296,1739502660.9141052,21.23997974395752,0.12180358883113859,1739502660.9141064,21.23997974395752,1.6226182525163046,1739502660.9141078,21.23997974395752,0.0,1739502660.9141092,21.23997974395752,-0.5307979358565837,1739502660.9141104,21.23997974395752,6.264210523691987,1739502660.914112,21.23997974395752,2.1534161883728884 +1739502660.9341705,21.259979724884033,43.35672332394124,1739502660.9341726,21.259979724884033,0.012794452863626127,1739502660.9341757,21.259979724884033,42.94373257370135,1739502660.9341784,21.259979724884033,49.17603044332558,1739502660.9341798,21.259979724884033,0.44277049110782046,1739502660.9341817,21.259979724884033,0.07375381816577531,1739502660.934183,21.259979724884033,0.5403121025338296,1739502660.9341846,21.259979724884033,0.12180358883113859,1739502660.9341857,21.259979724884033,1.6226182525163046,1739502660.9341872,21.259979724884033,0.0,1739502660.9341886,21.259979724884033,-0.5307979358565837,1739502660.9341898,21.259979724884033,6.264210523691987,1739502660.9341915,21.259979724884033,2.1534161883728884 +1739502660.9542522,21.279979705810547,43.35672332394124,1739502660.9542546,21.279979705810547,0.012794452863626127,1739502660.9542577,21.279979705810547,42.94373257370135,1739502660.9542606,21.279979705810547,49.17603044332558,1739502660.9542618,21.279979705810547,0.44277049110782046,1739502660.9542634,21.279979705810547,0.07375381816577531,1739502660.9542649,21.279979705810547,0.5403121025338296,1739502660.9542665,21.279979705810547,0.12180358883113859,1739502660.9542677,21.279979705810547,1.6226182525163046,1739502660.9542694,21.279979705810547,0.0,1739502660.9542704,21.279979705810547,-0.5307979358565837,1739502660.954272,21.279979705810547,6.264210523691987,1739502660.9542735,21.279979705810547,2.1534161883728884 +1739502660.9740949,21.29997968673706,43.59068245067479,1739502660.9740973,21.29997968673706,0.008602700397869256,1739502660.9740999,21.29997968673706,42.94841175623602,1739502660.9741027,21.29997968673706,49.07335127787854,1739502660.9741042,21.29997968673706,0.39950501165073327,1739502660.9741058,21.29997968673706,0.07117737152277856,1739502660.9741075,21.29997968673706,0.48108943951323746,1739502660.9741087,21.29997968673706,0.12222513875244176,1739502660.97411,21.29997968673706,1.701345111516238,1739502660.9741116,21.29997968673706,0.0,1739502660.9741127,21.29997968673706,-0.33184840220635603,1739502660.974114,21.29997968673706,6.266725411821695,1739502660.9741156,21.29997968673706,2.095365283751279 +1739502660.9942439,21.319979667663574,43.59068245067479,1739502660.9942467,21.319979667663574,0.008602700397869256,1739502660.9942498,21.319979667663574,42.94841175623602,1739502660.9942524,21.319979667663574,49.07335127787854,1739502660.9942539,21.319979667663574,0.39950501165073327,1739502660.9942555,21.319979667663574,0.07117737152277856,1739502660.9942572,21.319979667663574,0.48108943951323746,1739502660.9942586,21.319979667663574,0.12222513875244176,1739502660.99426,21.319979667663574,1.701345111516238,1739502660.9942615,21.319979667663574,0.0,1739502660.9942627,21.319979667663574,-0.39402017223504116,1739502660.9942648,21.319979667663574,6.266725411821695,1739502660.994266,21.319979667663574,2.095365283751279 +1739502661.0140936,21.339979648590088,43.59068245067479,1739502661.0140958,21.339979648590088,0.008602700397869256,1739502661.0140986,21.339979648590088,42.94841175623602,1739502661.0141015,21.339979648590088,49.07335127787854,1739502661.0141027,21.339979648590088,0.39950501165073327,1739502661.0141044,21.339979648590088,0.07117737152277856,1739502661.0141058,21.339979648590088,0.48108943951323746,1739502661.0141072,21.339979648590088,0.12222513875244176,1739502661.0141084,21.339979648590088,1.701345111516238,1739502661.0141103,21.339979648590088,0.0,1739502661.0141118,21.339979648590088,-0.39402017223504116,1739502661.014113,21.339979648590088,6.266725411821695,1739502661.0141146,21.339979648590088,2.095365283751279 +1739502661.034077,21.3599796295166,43.59068245067479,1739502661.0340793,21.3599796295166,0.008602700397869256,1739502661.034082,21.3599796295166,42.94841175623602,1739502661.034085,21.3599796295166,49.07335127787854,1739502661.0340865,21.3599796295166,0.39950501165073327,1739502661.0340881,21.3599796295166,0.07117737152277856,1739502661.0340896,21.3599796295166,0.48108943951323746,1739502661.034091,21.3599796295166,0.12222513875244176,1739502661.0340922,21.3599796295166,1.701345111516238,1739502661.0340939,21.3599796295166,0.0,1739502661.034095,21.3599796295166,-0.39402017223504116,1739502661.0340967,21.3599796295166,6.266725411821695,1739502661.034098,21.3599796295166,2.095365283751279 +1739502661.0542245,21.379979610443115,43.59068245067479,1739502661.0542266,21.379979610443115,0.008602700397869256,1739502661.0542297,21.379979610443115,42.94841175623602,1739502661.0542328,21.379979610443115,49.07335127787854,1739502661.054234,21.379979610443115,0.39950501165073327,1739502661.054236,21.379979610443115,0.07117737152277856,1739502661.0542371,21.379979610443115,0.48108943951323746,1739502661.0542386,21.379979610443115,0.12222513875244176,1739502661.0542397,21.379979610443115,1.701345111516238,1739502661.0542414,21.379979610443115,0.0,1739502661.0542428,21.379979610443115,-0.39402017223504116,1739502661.0542443,21.379979610443115,6.266725411821695,1739502661.0542462,21.379979610443115,2.095365283751279 +1739502661.0741367,21.39997959136963,43.59068245067479,1739502661.0741389,21.39997959136963,0.008602700397869256,1739502661.074142,21.39997959136963,42.94841175623602,1739502661.0741446,21.39997959136963,49.07335127787854,1739502661.0741458,21.39997959136963,0.39950501165073327,1739502661.0741477,21.39997959136963,0.07117737152277856,1739502661.0741491,21.39997959136963,0.48108943951323746,1739502661.0741503,21.39997959136963,0.12222513875244176,1739502661.0741518,21.39997959136963,1.701345111516238,1739502661.0741532,21.39997959136963,0.0,1739502661.0741544,21.39997959136963,-0.39402017223504116,1739502661.074156,21.39997959136963,6.266725411821695,1739502661.0741572,21.39997959136963,2.095365283751279 +1739502661.094312,21.419979572296143,43.81923445255131,1739502661.0943148,21.419979572296143,0.005179654825904656,1739502661.094318,21.419979572296143,42.95298279627355,1739502661.0943205,21.419979572296143,49.006764324617464,1739502661.094322,21.419979572296143,0.3726888414326589,1739502661.0943236,21.419979572296143,0.07072656939836411,1739502661.094325,21.419979572296143,0.43519119564320213,1739502661.0943263,21.419979572296143,0.1235095019090525,1739502661.0943274,21.419979572296143,1.7649772051268966,1739502661.0943294,21.419979572296143,0.0,1739502661.0943305,21.419979572296143,-0.2459315288323591,1739502661.0943322,21.419979572296143,6.270131841702156,1739502661.0943336,21.419979572296143,2.057186465364639 +1739502661.1140788,21.439979553222656,43.81923445255131,1739502661.1140807,21.439979553222656,0.005179654825904656,1739502661.1140838,21.439979553222656,42.95298279627355,1739502661.1140866,21.439979553222656,49.006764324617464,1739502661.1140878,21.439979553222656,0.3726888414326589,1739502661.1140897,21.439979553222656,0.07072656939836411,1739502661.114091,21.439979553222656,0.43519119564320213,1739502661.1140924,21.439979553222656,0.1235095019090525,1739502661.1140938,21.439979553222656,1.7649772051268966,1739502661.1140954,21.439979553222656,0.0,1739502661.1140966,21.439979553222656,-0.2922092602377424,1739502661.1140978,21.439979553222656,6.270131841702156,1739502661.1140995,21.439979553222656,2.057186465364639 +1739502661.1340783,21.45997953414917,43.81923445255131,1739502661.1340802,21.45997953414917,0.005179654825904656,1739502661.1340833,21.45997953414917,42.95298279627355,1739502661.1340861,21.45997953414917,49.006764324617464,1739502661.1340876,21.45997953414917,0.3726888414326589,1739502661.1340895,21.45997953414917,0.07072656939836411,1739502661.1340907,21.45997953414917,0.43519119564320213,1739502661.1340923,21.45997953414917,0.1235095019090525,1739502661.1340933,21.45997953414917,1.7649772051268966,1739502661.1340952,21.45997953414917,0.0,1739502661.1340964,21.45997953414917,-0.2922092602377424,1739502661.1340976,21.45997953414917,6.270131841702156,1739502661.1340992,21.45997953414917,2.057186465364639 +1739502661.1542597,21.479979515075684,43.81923445255131,1739502661.154262,21.479979515075684,0.005179654825904656,1739502661.1542652,21.479979515075684,42.95298279627355,1739502661.1542678,21.479979515075684,49.006764324617464,1739502661.1542692,21.479979515075684,0.3726888414326589,1739502661.154271,21.479979515075684,0.07072656939836411,1739502661.1542726,21.479979515075684,0.43519119564320213,1739502661.1542737,21.479979515075684,0.1235095019090525,1739502661.1542752,21.479979515075684,1.7649772051268966,1739502661.1542768,21.479979515075684,0.0,1739502661.154278,21.479979515075684,-0.2922092602377424,1739502661.1542797,21.479979515075684,6.270131841702156,1739502661.1542811,21.479979515075684,2.057186465364639 +1739502661.174088,21.499979496002197,43.81923445255131,1739502661.1740901,21.499979496002197,0.005179654825904656,1739502661.1740928,21.499979496002197,42.95298279627355,1739502661.1740956,21.499979496002197,49.006764324617464,1739502661.1740968,21.499979496002197,0.3726888414326589,1739502661.1740985,21.499979496002197,0.07072656939836411,1739502661.1741,21.499979496002197,0.43519119564320213,1739502661.1741018,21.499979496002197,0.1235095019090525,1739502661.174103,21.499979496002197,1.7649772051268966,1739502661.1741047,21.499979496002197,0.0,1739502661.174106,21.499979496002197,-0.2922092602377424,1739502661.1741073,21.499979496002197,6.270131841702156,1739502661.1741087,21.499979496002197,2.057186465364639 +1739502661.1944008,21.51997947692871,44.043616915300525,1739502661.1944034,21.51997947692871,0.0026189383493440133,1739502661.1944065,21.51997947692871,43.227522039985416,1739502661.1944091,21.51997947692871,49.19051556706408,1739502661.1944108,21.51997947692871,0.44891569511809554,1739502661.1944122,21.51997947692871,0.08649543106632505,1739502661.1944144,21.51997947692871,0.49480920330763933,1739502661.1944156,21.51997947692871,0.14227505863441503,1739502661.194417,21.51997947692871,1.68277357434728,1739502661.1944184,21.51997947692871,0.0,1739502661.1944196,21.51997947692871,-0.35679981824989687,1739502661.1944213,21.51997947692871,6.273755743763933,1739502661.1944225,21.51997947692871,2.019388829984348 +1739502661.214485,21.539979457855225,44.043616915300525,1739502661.2144873,21.539979457855225,0.0026189383493440133,1739502661.2144902,21.539979457855225,43.227522039985416,1739502661.214493,21.539979457855225,49.19051556706408,1739502661.2144942,21.539979457855225,0.44891569511809554,1739502661.214496,21.539979457855225,0.08649543106632505,1739502661.2144976,21.539979457855225,0.49480920330763933,1739502661.214502,21.539979457855225,0.14227505863441503,1739502661.2145052,21.539979457855225,1.68277357434728,1739502661.214508,21.539979457855225,0.0,1739502661.214512,21.539979457855225,-0.33661525563706807,1739502661.2145157,21.539979457855225,6.273755743763933,1739502661.2145174,21.539979457855225,2.019388829984348 +1739502661.2362552,21.55997943878174,44.043616915300525,1739502661.2362604,21.55997943878174,0.0026189383493440133,1739502661.2362652,21.55997943878174,43.227522039985416,1739502661.2362707,21.55997943878174,49.19051556706408,1739502661.2362745,21.55997943878174,0.44891569511809554,1739502661.2362783,21.55997943878174,0.08649543106632505,1739502661.2362828,21.55997943878174,0.49480920330763933,1739502661.2362864,21.55997943878174,0.14227505863441503,1739502661.2362897,21.55997943878174,1.68277357434728,1739502661.2362933,21.55997943878174,0.0,1739502661.236297,21.55997943878174,-0.33661525563706807,1739502661.2363002,21.55997943878174,6.273755743763933,1739502661.2363038,21.55997943878174,2.019388829984348 +1739502661.2553933,21.579979419708252,44.043616915300525,1739502661.2553968,21.579979419708252,0.0026189383493440133,1739502661.2554014,21.579979419708252,43.227522039985416,1739502661.2554061,21.579979419708252,49.19051556706408,1739502661.2554083,21.579979419708252,0.44891569511809554,1739502661.2554114,21.579979419708252,0.08649543106632505,1739502661.255414,21.579979419708252,0.49480920330763933,1739502661.2554164,21.579979419708252,0.14227505863441503,1739502661.2554185,21.579979419708252,1.68277357434728,1739502661.2554212,21.579979419708252,0.0,1739502661.2554235,21.579979419708252,-0.33661525563706807,1739502661.255426,21.579979419708252,6.273755743763933,1739502661.2554286,21.579979419708252,2.019388829984348 +1739502661.2753942,21.599979400634766,44.043616915300525,1739502661.2753983,21.599979400634766,0.0026189383493440133,1739502661.2754025,21.599979400634766,43.227522039985416,1739502661.2754073,21.599979400634766,49.19051556706408,1739502661.2754097,21.599979400634766,0.44891569511809554,1739502661.2754128,21.599979400634766,0.08649543106632505,1739502661.275416,21.599979400634766,0.49480920330763933,1739502661.2754183,21.599979400634766,0.14227505863441503,1739502661.2754207,21.599979400634766,1.68277357434728,1739502661.2754238,21.599979400634766,0.0,1739502661.2754261,21.599979400634766,-0.33661525563706807,1739502661.2754283,21.599979400634766,6.273755743763933,1739502661.2754312,21.599979400634766,2.019388829984348 +1739502661.295403,21.61997938156128,44.043616915300525,1739502661.2954063,21.61997938156128,0.0026189383493440133,1739502661.2954106,21.61997938156128,43.227522039985416,1739502661.2954147,21.61997938156128,49.19051556706408,1739502661.2954168,21.61997938156128,0.44891569511809554,1739502661.2954197,21.61997938156128,0.08649543106632505,1739502661.2954218,21.61997938156128,0.49480920330763933,1739502661.2954242,21.61997938156128,0.14227505863441503,1739502661.2954266,21.61997938156128,1.68277357434728,1739502661.2954295,21.61997938156128,0.0,1739502661.2954316,21.61997938156128,-0.33661525563706807,1739502661.2954342,21.61997938156128,6.273755743763933,1739502661.295437,21.61997938156128,2.019388829984348 +1739502661.3154833,21.639979362487793,44.26386852039332,1739502661.3154879,21.639979362487793,0.0009294907662944496,1739502661.3154924,21.639979362487793,43.946901560230636,1739502661.3154967,21.639979362487793,49.762856721833494,1739502661.3154993,21.639979362487793,0.7443527028027865,1739502661.3155022,21.639979362487793,0.13437800077265769,1739502661.3155048,21.639979362487793,0.7729543995269351,1739502661.3155074,21.639979362487793,0.19252484193364278,1739502661.3155098,21.639979362487793,1.3470637345762233,1739502661.3155127,21.639979362487793,0.0,1739502661.3155148,21.639979362487793,-0.7704866074387532,1739502661.3155174,21.639979362487793,6.277813035669526,1739502661.31552,21.639979362487793,1.981965455680571 +1739502661.3340776,21.659979343414307,44.26386852039332,1739502661.3340797,21.659979343414307,0.0009294907662944496,1739502661.3340828,21.659979343414307,43.946901560230636,1739502661.3340855,21.659979343414307,49.762856721833494,1739502661.3340867,21.659979343414307,0.7443527028027865,1739502661.334088,21.659979343414307,0.13437800077265769,1739502661.3340895,21.659979343414307,0.7729543995269351,1739502661.3340907,21.659979343414307,0.19252484193364278,1739502661.3340917,21.659979343414307,1.3470637345762233,1739502661.3340933,21.659979343414307,0.0,1739502661.3340945,21.659979343414307,-0.6349017211043477,1739502661.334096,21.659979343414307,6.277813035669526,1739502661.3340971,21.659979343414307,1.981965455680571 +1739502661.3543134,21.67997932434082,44.26386852039332,1739502661.354316,21.67997932434082,0.0009294907662944496,1739502661.3543186,21.67997932434082,43.946901560230636,1739502661.3543212,21.67997932434082,49.762856721833494,1739502661.3543222,21.67997932434082,0.7443527028027865,1739502661.3543243,21.67997932434082,0.13437800077265769,1739502661.3543255,21.67997932434082,0.7729543995269351,1739502661.3543267,21.67997932434082,0.19252484193364278,1739502661.354328,21.67997932434082,1.3470637345762233,1739502661.3543293,21.67997932434082,0.0,1739502661.3543305,21.67997932434082,-0.6349017211043477,1739502661.354332,21.67997932434082,6.277813035669526,1739502661.3543332,21.67997932434082,1.981965455680571 +1739502661.3740542,21.699979305267334,44.26386852039332,1739502661.374056,21.699979305267334,0.0009294907662944496,1739502661.374059,21.699979305267334,43.946901560230636,1739502661.3740613,21.699979305267334,49.762856721833494,1739502661.3740625,21.699979305267334,0.7443527028027865,1739502661.3740642,21.699979305267334,0.13437800077265769,1739502661.3740654,21.699979305267334,0.7729543995269351,1739502661.3740666,21.699979305267334,0.19252484193364278,1739502661.3740678,21.699979305267334,1.3470637345762233,1739502661.3740692,21.699979305267334,0.0,1739502661.3740706,21.699979305267334,-0.6349017211043477,1739502661.3740718,21.699979305267334,6.277813035669526,1739502661.374073,21.699979305267334,1.981965455680571 +1739502661.3942375,21.719979286193848,44.26386852039332,1739502661.39424,21.719979286193848,0.0009294907662944496,1739502661.3942428,21.719979286193848,43.946901560230636,1739502661.3942451,21.719979286193848,49.762856721833494,1739502661.3942463,21.719979286193848,0.7443527028027865,1739502661.394248,21.719979286193848,0.13437800077265769,1739502661.3942492,21.719979286193848,0.7729543995269351,1739502661.3942504,21.719979286193848,0.19252484193364278,1739502661.3942518,21.719979286193848,1.3470637345762233,1739502661.3942533,21.719979286193848,0.0,1739502661.3942547,21.719979286193848,-0.6349017211043477,1739502661.3942559,21.719979286193848,6.277813035669526,1739502661.394257,21.719979286193848,1.981965455680571 +1739502661.4141238,21.73997926712036,44.478466370170636,1739502661.4141262,21.73997926712036,0.0002307082061516752,1739502661.4141285,21.73997926712036,43.95119351722618,1739502661.4141312,21.73997926712036,49.64601443322917,1739502661.4141326,21.73997926712036,0.6781993482253393,1739502661.414134,21.73997926712036,0.1304522797327586,1739502661.4141355,21.73997926712036,0.6806227207257947,1739502661.414137,21.73997926712036,0.1921729359682519,1739502661.4141378,21.73997926712036,1.4503320863707516,1739502661.4141395,21.73997926712036,0.0,1739502661.4141407,21.73997926712036,-0.3839209272895449,1739502661.4141421,21.73997926712036,6.2826716844289505,1739502661.4141436,21.73997926712036,1.9126845631511535 +1739502661.4343123,21.759979248046875,44.478466370170636,1739502661.4343147,21.759979248046875,0.0002307082061516752,1739502661.434318,21.759979248046875,43.95119351722618,1739502661.434321,21.759979248046875,49.64601443322917,1739502661.434322,21.759979248046875,0.6781993482253393,1739502661.434324,21.759979248046875,0.1304522797327586,1739502661.4343252,21.759979248046875,0.6806227207257947,1739502661.434327,21.759979248046875,0.1921729359682519,1739502661.434328,21.759979248046875,1.4503320863707516,1739502661.4343297,21.759979248046875,0.0,1739502661.4343312,21.759979248046875,-0.4623524767804019,1739502661.4343326,21.759979248046875,6.2826716844289505,1739502661.434334,21.759979248046875,1.9126845631511535 +1739502661.4545097,21.77997922897339,44.478466370170636,1739502661.4545126,21.77997922897339,0.0002307082061516752,1739502661.4545162,21.77997922897339,43.95119351722618,1739502661.454519,21.77997922897339,49.64601443322917,1739502661.4545205,21.77997922897339,0.6781993482253393,1739502661.4545221,21.77997922897339,0.1304522797327586,1739502661.4545238,21.77997922897339,0.6806227207257947,1739502661.4545255,21.77997922897339,0.1921729359682519,1739502661.4545267,21.77997922897339,1.4503320863707516,1739502661.4545283,21.77997922897339,0.0,1739502661.4545298,21.77997922897339,-0.4623524767804019,1739502661.4545314,21.77997922897339,6.2826716844289505,1739502661.4545329,21.77997922897339,1.9126845631511535 +1739502661.4744189,21.799979209899902,44.478466370170636,1739502661.4744213,21.799979209899902,0.0002307082061516752,1739502661.4744246,21.799979209899902,43.95119351722618,1739502661.4744277,21.799979209899902,49.64601443322917,1739502661.4744291,21.799979209899902,0.6781993482253393,1739502661.4744313,21.799979209899902,0.1304522797327586,1739502661.4744327,21.799979209899902,0.6806227207257947,1739502661.4744344,21.799979209899902,0.1921729359682519,1739502661.4744358,21.799979209899902,1.4503320863707516,1739502661.4744377,21.799979209899902,0.0,1739502661.4744391,21.799979209899902,-0.4623524767804019,1739502661.474441,21.799979209899902,6.2826716844289505,1739502661.4744425,21.799979209899902,1.9126845631511535 +1739502661.4945774,21.819979190826416,44.478466370170636,1739502661.4945807,21.819979190826416,0.0002307082061516752,1739502661.4945846,21.819979190826416,43.95119351722618,1739502661.494588,21.819979190826416,49.64601443322917,1739502661.4945898,21.819979190826416,0.6781993482253393,1739502661.4945922,21.819979190826416,0.1304522797327586,1739502661.494594,21.819979190826416,0.6806227207257947,1739502661.494596,21.819979190826416,0.1921729359682519,1739502661.4945977,21.819979190826416,1.4503320863707516,1739502661.4945996,21.819979190826416,0.0,1739502661.4946012,21.819979190826416,-0.4623524767804019,1739502661.4946039,21.819979190826416,6.2826716844289505,1739502661.4946055,21.819979190826416,1.9126845631511535 +1739502661.5143974,21.83997917175293,44.478466370170636,1739502661.5144,21.83997917175293,0.0002307082061516752,1739502661.5144033,21.83997917175293,43.95119351722618,1739502661.5144067,21.83997917175293,49.64601443322917,1739502661.514408,21.83997917175293,0.6781993482253393,1739502661.51441,21.83997917175293,0.1304522797327586,1739502661.514412,21.83997917175293,0.6806227207257947,1739502661.5144136,21.83997917175293,0.1921729359682519,1739502661.514415,21.83997917175293,1.4503320863707516,1739502661.514417,21.83997917175293,0.0,1739502661.5144184,21.83997917175293,-0.4623524767804019,1739502661.51442,21.83997917175293,6.2826716844289505,1739502661.5144215,21.83997917175293,1.9126845631511535 +1739502661.5346913,21.859979152679443,44.6865710430066,1739502661.5346947,21.859979152679443,0.0006567275120659133,1739502661.5346985,21.859979152679443,43.9553556106829,1739502661.534702,21.859979152679443,49.56552173107943,1739502661.534704,21.859979152679443,0.6337620092807383,1739502661.534706,21.859979152679443,0.12904153332234125,1739502661.5347083,21.859979152679443,0.6071014307674599,1739502661.53471,21.859979152679443,0.19236317501357147,1739502661.5347116,21.859979152679443,1.5381949018281647,1739502661.5347135,21.859979152679443,0.0,1739502661.5347157,21.859979152679443,-0.264654240426957,1739502661.5347173,21.859979152679443,0.005327987419951665,1739502661.5347192,21.859979152679443,1.8646298816221825 +1739502661.5552423,21.879979133605957,44.6865710430066,1739502661.5552454,21.879979133605957,0.0006567275120659133,1739502661.55525,21.879979133605957,43.9553556106829,1739502661.5552537,21.879979133605957,49.56552173107943,1739502661.555256,21.879979133605957,0.6337620092807383,1739502661.5552583,21.879979133605957,0.12904153332234125,1739502661.5552602,21.879979133605957,0.6071014307674599,1739502661.5552623,21.879979133605957,0.19236317501357147,1739502661.555264,21.879979133605957,1.5381949018281647,1739502661.5552664,21.879979133605957,0.0,1739502661.5552683,21.879979133605957,-0.3264349797940178,1739502661.5552704,21.879979133605957,0.005327987419951665,1739502661.555272,21.879979133605957,1.8646298816221825 +1739502661.5749238,21.89997911453247,44.6865710430066,1739502661.5749276,21.89997911453247,0.0006567275120659133,1739502661.5749328,21.89997911453247,43.9553556106829,1739502661.5749369,21.89997911453247,49.56552173107943,1739502661.5749388,21.89997911453247,0.6337620092807383,1739502661.5749412,21.89997911453247,0.12904153332234125,1739502661.5749433,21.89997911453247,0.6071014307674599,1739502661.5749452,21.89997911453247,0.19236317501357147,1739502661.5749474,21.89997911453247,1.5381949018281647,1739502661.5749497,21.89997911453247,0.0,1739502661.5749516,21.89997911453247,-0.3264349797940178,1739502661.5749543,21.89997911453247,0.005327987419951665,1739502661.5749562,21.89997911453247,1.8646298816221825 +1739502661.5948505,21.919979095458984,44.6865710430066,1739502661.5948536,21.919979095458984,0.0006567275120659133,1739502661.594858,21.919979095458984,43.9553556106829,1739502661.594862,21.919979095458984,49.56552173107943,1739502661.594864,21.919979095458984,0.6337620092807383,1739502661.5948663,21.919979095458984,0.12904153332234125,1739502661.5948682,21.919979095458984,0.6071014307674599,1739502661.59487,21.919979095458984,0.19236317501357147,1739502661.5948718,21.919979095458984,1.5381949018281647,1739502661.5948741,21.919979095458984,0.0,1739502661.594876,21.919979095458984,-0.3264349797940178,1739502661.594878,21.919979095458984,0.005327987419951665,1739502661.59488,21.919979095458984,1.8646298816221825 +1739502661.6152291,21.939979076385498,44.6865710430066,1739502661.6152332,21.939979076385498,0.0006567275120659133,1739502661.6152377,21.939979076385498,43.9553556106829,1739502661.6152418,21.939979076385498,49.56552173107943,1739502661.6152437,21.939979076385498,0.6337620092807383,1739502661.6152463,21.939979076385498,0.12904153332234125,1739502661.6152484,21.939979076385498,0.6071014307674599,1739502661.61525,21.939979076385498,0.19236317501357147,1739502661.6152523,21.939979076385498,1.5381949018281647,1739502661.6152546,21.939979076385498,0.0,1739502661.6152563,21.939979076385498,-0.3264349797940178,1739502661.6152585,21.939979076385498,0.005327987419951665,1739502661.6152604,21.939979076385498,1.8646298816221825 +1739502661.6351442,21.95997905731201,44.88974404350032,1739502661.6351478,21.95997905731201,0.0023432854094140865,1739502661.6351519,21.95997905731201,43.959419070692775,1739502661.635156,21.95997905731201,49.5038365202575,1739502661.6351578,21.95997905731201,0.5999108292313629,1739502661.6351602,21.95997905731201,0.12879235571702313,1739502661.6351624,21.95997905731201,0.5424564410522004,1739502661.6351643,21.95997905731201,0.19219183717616228,1739502661.6351662,21.95997905731201,1.6198370844490884,1739502661.6351686,21.95997905731201,0.0,1739502661.6351702,21.95997905731201,-0.15355405267168853,1739502661.6351726,21.95997905731201,0.011935142161647386,1739502661.6351748,21.95997905731201,1.8274164622682683 +1739502661.6550295,21.979979038238525,44.88974404350032,1739502661.6550329,21.979979038238525,0.0023432854094140865,1739502661.6550372,21.979979038238525,43.959419070692775,1739502661.6550412,21.979979038238525,49.5038365202575,1739502661.6550431,21.979979038238525,0.5999108292313629,1739502661.6550453,21.979979038238525,0.12879235571702313,1739502661.6550474,21.979979038238525,0.5424564410522004,1739502661.6550496,21.979979038238525,0.19219183717616228,1739502661.6550515,21.979979038238525,1.6198370844490884,1739502661.6550539,21.979979038238525,0.0,1739502661.6550558,21.979979038238525,-0.2075793778191799,1739502661.6550577,21.979979038238525,0.011935142161647386,1739502661.6550598,21.979979038238525,1.8274164622682683 +1739502661.6751018,21.99997901916504,44.88974404350032,1739502661.6751053,21.99997901916504,0.0023432854094140865,1739502661.6751096,21.99997901916504,43.959419070692775,1739502661.6751134,21.99997901916504,49.5038365202575,1739502661.6751156,21.99997901916504,0.5999108292313629,1739502661.675118,21.99997901916504,0.12879235571702313,1739502661.67512,21.99997901916504,0.5424564410522004,1739502661.675122,21.99997901916504,0.19219183717616228,1739502661.675124,21.99997901916504,1.6198370844490884,1739502661.675126,21.99997901916504,0.0,1739502661.675128,21.99997901916504,-0.2075793778191799,1739502661.6751301,21.99997901916504,0.011935142161647386,1739502661.6751323,21.99997901916504,1.8274164622682683 +1739502661.6952977,22.019979000091553,44.88974404350032,1739502661.695301,22.019979000091553,0.0023432854094140865,1739502661.695305,22.019979000091553,43.959419070692775,1739502661.6953096,22.019979000091553,49.5038365202575,1739502661.6953115,22.019979000091553,0.5999108292313629,1739502661.695314,22.019979000091553,0.12879235571702313,1739502661.695316,22.019979000091553,0.5424564410522004,1739502661.695318,22.019979000091553,0.19219183717616228,1739502661.69532,22.019979000091553,1.6198370844490884,1739502661.6953218,22.019979000091553,0.0,1739502661.695324,22.019979000091553,-0.2075793778191799,1739502661.6953259,22.019979000091553,0.011935142161647386,1739502661.695328,22.019979000091553,1.8274164622682683 +1739502661.715127,22.039978981018066,44.88974404350032,1739502661.7151308,22.039978981018066,0.0023432854094140865,1739502661.7151353,22.039978981018066,43.959419070692775,1739502661.7151392,22.039978981018066,49.5038365202575,1739502661.715141,22.039978981018066,0.5999108292313629,1739502661.7151437,22.039978981018066,0.12879235571702313,1739502661.7151458,22.039978981018066,0.5424564410522004,1739502661.7151477,22.039978981018066,0.19219183717616228,1739502661.7151496,22.039978981018066,1.6198370844490884,1739502661.7151518,22.039978981018066,0.0,1739502661.7151537,22.039978981018066,-0.2075793778191799,1739502661.715156,22.039978981018066,0.011935142161647386,1739502661.715158,22.039978981018066,1.8274164622682683 +1739502661.7351003,22.05997896194458,44.88974404350032,1739502661.7351038,22.05997896194458,0.0023432854094140865,1739502661.7351081,22.05997896194458,43.959419070692775,1739502661.7351122,22.05997896194458,49.5038365202575,1739502661.7351146,22.05997896194458,0.5999108292313629,1739502661.7351167,22.05997896194458,0.12879235571702313,1739502661.7351189,22.05997896194458,0.5424564410522004,1739502661.735121,22.05997896194458,0.19219183717616228,1739502661.7351227,22.05997896194458,1.6198370844490884,1739502661.735125,22.05997896194458,0.0,1739502661.7351267,22.05997896194458,-0.2075793778191799,1739502661.7351289,22.05997896194458,0.011935142161647386,1739502661.735131,22.05997896194458,1.8274164622682683 +1739502661.7551284,22.079978942871094,45.089700668006536,1739502661.7551315,22.079978942871094,0.005333708707708773,1739502661.7551355,22.079978942871094,44.996061025612036,1739502661.7551394,22.079978942871094,50.33734518915617,1739502661.7551413,22.079978942871094,1.1375551547641336,1739502661.7551436,22.079978942871094,0.21250058563630184,1739502661.7551458,22.079978942871094,1.0344681638319468,1739502661.7551475,22.079978942871094,0.2748976386927798,1739502661.7551494,22.079978942871094,1.092770484935204,1739502661.7551515,22.079978942871094,0.0,1739502661.7551537,22.079978942871094,-0.7129823144418133,1739502661.7551556,22.079978942871094,0.018591813643428594,1739502661.7551575,22.079978942871094,1.8057527993770173 +1739502661.7751913,22.099978923797607,45.089700668006536,1739502661.7751951,22.099978923797607,0.005333708707708773,1739502661.7751994,22.099978923797607,44.996061025612036,1739502661.7752035,22.099978923797607,50.33734518915617,1739502661.7752054,22.099978923797607,1.1375551547641336,1739502661.775208,22.099978923797607,0.21250058563630184,1739502661.77521,22.099978923797607,1.0344681638319468,1739502661.775212,22.099978923797607,0.2748976386927798,1739502661.7752137,22.099978923797607,1.092770484935204,1739502661.775216,22.099978923797607,0.0,1739502661.7752182,22.099978923797607,-0.7129823144418133,1739502661.7752202,22.099978923797607,0.018591813643428594,1739502661.7752223,22.099978923797607,1.8057527993770173 +1739502661.7975023,22.11997890472412,45.089700668006536,1739502661.797507,22.11997890472412,0.005333708707708773,1739502661.7975137,22.11997890472412,44.996061025612036,1739502661.7975214,22.11997890472412,50.33734518915617,1739502661.7975261,22.11997890472412,1.1375551547641336,1739502661.7975314,22.11997890472412,0.21250058563630184,1739502661.7975366,22.11997890472412,1.0344681638319468,1739502661.7975416,22.11997890472412,0.2748976386927798,1739502661.7975464,22.11997890472412,1.092770484935204,1739502661.7975516,22.11997890472412,0.0,1739502661.7975564,22.11997890472412,-0.7129823144418133,1739502661.7975616,22.11997890472412,0.018591813643428594,1739502661.7975667,22.11997890472412,1.8057527993770173 +1739502661.8151202,22.139978885650635,45.089700668006536,1739502661.8151238,22.139978885650635,0.005333708707708773,1739502661.8151283,22.139978885650635,44.996061025612036,1739502661.8151324,22.139978885650635,50.33734518915617,1739502661.8151345,22.139978885650635,1.1375551547641336,1739502661.8151367,22.139978885650635,0.21250058563630184,1739502661.8151388,22.139978885650635,1.0344681638319468,1739502661.815141,22.139978885650635,0.2748976386927798,1739502661.8151426,22.139978885650635,1.092770484935204,1739502661.815145,22.139978885650635,0.0,1739502661.815147,22.139978885650635,-0.7129823144418133,1739502661.8151495,22.139978885650635,0.018591813643428594,1739502661.8151517,22.139978885650635,1.8057527993770173 +1739502661.835243,22.15997886657715,45.089700668006536,1739502661.8352468,22.15997886657715,0.005333708707708773,1739502661.835251,22.15997886657715,44.996061025612036,1739502661.8352551,22.15997886657715,50.33734518915617,1739502661.835257,22.15997886657715,1.1375551547641336,1739502661.8352594,22.15997886657715,0.21250058563630184,1739502661.8352613,22.15997886657715,1.0344681638319468,1739502661.8352633,22.15997886657715,0.2748976386927798,1739502661.835265,22.15997886657715,1.092770484935204,1739502661.8352673,22.15997886657715,0.0,1739502661.8352692,22.15997886657715,-0.7129823144418133,1739502661.8352711,22.15997886657715,0.018591813643428594,1739502661.8352733,22.15997886657715,1.8057527993770173 +1739502661.855594,22.179978847503662,45.284881159392306,1739502661.8555973,22.179978847503662,0.00956748587000611,1739502661.8556013,22.179978847503662,45.03120621539297,1739502661.8556056,22.179978847503662,50.249917405419794,1739502661.8556075,22.179978847503662,1.0692227850817486,1739502661.8556101,22.179978847503662,0.21026880481745802,1739502661.8556118,22.179978847503662,0.9320084668004515,1739502661.855614,22.179978847503662,0.2769208534947852,1739502661.8556159,22.179978847503662,1.1861158278755555,1739502661.8556178,22.179978847503662,0.0,1739502661.85562,22.179978847503662,-0.4709328847101557,1739502661.8556218,22.179978847503662,0.025641794650124266,1739502661.8556237,22.179978847503662,1.7326892089706283 +1739502661.8750696,22.199978828430176,45.284881159392306,1739502661.8750734,22.199978828430176,0.00956748587000611,1739502661.875078,22.199978828430176,45.03120621539297,1739502661.875082,22.199978828430176,50.249917405419794,1739502661.8750844,22.199978828430176,1.0692227850817486,1739502661.8750868,22.199978828430176,0.21026880481745802,1739502661.875089,22.199978828430176,0.9320084668004515,1739502661.8750908,22.199978828430176,0.2769208534947852,1739502661.8750927,22.199978828430176,1.1861158278755555,1739502661.8750954,22.199978828430176,0.0,1739502661.8750973,22.199978828430176,-0.5465733810950728,1739502661.8750994,22.199978828430176,0.025641794650124266,1739502661.875101,22.199978828430176,1.7326892089706283 +1739502661.8952472,22.21997880935669,45.284881159392306,1739502661.89525,22.21997880935669,0.00956748587000611,1739502661.8952546,22.21997880935669,45.03120621539297,1739502661.8952584,22.21997880935669,50.249917405419794,1739502661.8952603,22.21997880935669,1.0692227850817486,1739502661.8952627,22.21997880935669,0.21026880481745802,1739502661.8952649,22.21997880935669,0.9320084668004515,1739502661.8952668,22.21997880935669,0.2769208534947852,1739502661.8952687,22.21997880935669,1.1861158278755555,1739502661.8952708,22.21997880935669,0.0,1739502661.8952727,22.21997880935669,-0.5465733810950728,1739502661.8952746,22.21997880935669,0.025641794650124266,1739502661.895277,22.21997880935669,1.7326892089706283 +1739502661.9150841,22.239978790283203,45.284881159392306,1739502661.9150884,22.239978790283203,0.00956748587000611,1739502661.915093,22.239978790283203,45.03120621539297,1739502661.9150968,22.239978790283203,50.249917405419794,1739502661.915099,22.239978790283203,1.0692227850817486,1739502661.9151013,22.239978790283203,0.21026880481745802,1739502661.9151034,22.239978790283203,0.9320084668004515,1739502661.9151056,22.239978790283203,0.2769208534947852,1739502661.9151073,22.239978790283203,1.1861158278755555,1739502661.9151099,22.239978790283203,0.0,1739502661.915112,22.239978790283203,-0.5465733810950728,1739502661.9151137,22.239978790283203,0.025641794650124266,1739502661.915116,22.239978790283203,1.7326892089706283 +1739502661.9352405,22.259978771209717,45.284881159392306,1739502661.9352443,22.259978771209717,0.00956748587000611,1739502661.9352486,22.259978771209717,45.03120621539297,1739502661.9352527,22.259978771209717,50.249917405419794,1739502661.9352546,22.259978771209717,1.0692227850817486,1739502661.9352572,22.259978771209717,0.21026880481745802,1739502661.935259,22.259978771209717,0.9320084668004515,1739502661.9352612,22.259978771209717,0.2769208534947852,1739502661.935263,22.259978771209717,1.1861158278755555,1739502661.9352653,22.259978771209717,0.0,1739502661.9352672,22.259978771209717,-0.5465733810950728,1739502661.9352694,22.259978771209717,0.025641794650124266,1739502661.9352713,22.259978771209717,1.7326892089706283 +1739502661.9552712,22.27997875213623,45.284881159392306,1739502661.9552748,22.27997875213623,0.00956748587000611,1739502661.9552789,22.27997875213623,45.03120621539297,1739502661.9552827,22.27997875213623,50.249917405419794,1739502661.9552848,22.27997875213623,1.0692227850817486,1739502661.955287,22.27997875213623,0.21026880481745802,1739502661.955289,22.27997875213623,0.9320084668004515,1739502661.9552908,22.27997875213623,0.2769208534947852,1739502661.9552932,22.27997875213623,1.1861158278755555,1739502661.9552956,22.27997875213623,0.0,1739502661.9552972,22.27997875213623,-0.5465733810950728,1739502661.9552994,22.27997875213623,0.025641794650124266,1739502661.9553013,22.27997875213623,1.7326892089706283 +1739502661.9751654,22.299978733062744,45.47254100391904,1739502661.9751692,22.299978733062744,0.015051414227924553,1739502661.9751742,22.299978733062744,45.276269616014545,1739502661.975178,22.299978733062744,50.35076731642279,1739502661.9751801,22.299978733062744,1.1485368952550068,1739502661.9751825,22.299978733062744,0.22830492644071762,1739502661.9751847,22.299978733062744,0.9682491651263272,1739502661.9751866,22.299978733062744,0.2955155657915696,1739502661.9751885,22.299978733062744,1.1522210179983938,1739502661.9751909,22.299978733062744,0.0,1739502661.9751925,22.299978733062744,-0.5109736734782911,1739502661.975195,22.299978733062744,0.033746324119567524,1739502661.9751966,22.299978733062744,1.6743196074009925 +1739502661.9952092,22.319978713989258,45.47254100391904,1739502661.9952126,22.319978713989258,0.015051414227924553,1739502661.9952166,22.319978713989258,45.276269616014545,1739502661.9952207,22.319978713989258,50.35076731642279,1739502661.9952228,22.319978713989258,1.1485368952550068,1739502661.9952252,22.319978713989258,0.22830492644071762,1739502661.995227,22.319978713989258,0.9682491651263272,1739502661.9952292,22.319978713989258,0.2955155657915696,1739502661.995231,22.319978713989258,1.1522210179983938,1739502661.9952333,22.319978713989258,0.0,1739502661.995235,22.319978713989258,-0.5220985894025987,1739502661.995237,22.319978713989258,0.033746324119567524,1739502661.9952393,22.319978713989258,1.6743196074009925 +1739502662.015116,22.33997869491577,45.47254100391904,1739502662.01512,22.33997869491577,0.015051414227924553,1739502662.0151246,22.33997869491577,45.276269616014545,1739502662.0151286,22.33997869491577,50.35076731642279,1739502662.0151303,22.33997869491577,1.1485368952550068,1739502662.0151331,22.33997869491577,0.22830492644071762,1739502662.0151353,22.33997869491577,0.9682491651263272,1739502662.0151372,22.33997869491577,0.2955155657915696,1739502662.015139,22.33997869491577,1.1522210179983938,1739502662.0151415,22.33997869491577,0.0,1739502662.0151434,22.33997869491577,-0.5220985894025987,1739502662.0151455,22.33997869491577,0.033746324119567524,1739502662.0151474,22.33997869491577,1.6743196074009925 +1739502662.0350666,22.359978675842285,45.47254100391904,1739502662.0350704,22.359978675842285,0.015051414227924553,1739502662.0350752,22.359978675842285,45.276269616014545,1739502662.0350792,22.359978675842285,50.35076731642279,1739502662.0350811,22.359978675842285,1.1485368952550068,1739502662.0350838,22.359978675842285,0.22830492644071762,1739502662.0350857,22.359978675842285,0.9682491651263272,1739502662.0350876,22.359978675842285,0.2955155657915696,1739502662.0350895,22.359978675842285,1.1522210179983938,1739502662.0350919,22.359978675842285,0.0,1739502662.0350938,22.359978675842285,-0.5220985894025987,1739502662.0350957,22.359978675842285,0.033746324119567524,1739502662.0350978,22.359978675842285,1.6743196074009925 +1739502662.0550206,22.3799786567688,45.47254100391904,1739502662.0550244,22.3799786567688,0.015051414227924553,1739502662.0550284,22.3799786567688,45.276269616014545,1739502662.0550323,22.3799786567688,50.35076731642279,1739502662.0550344,22.3799786567688,1.1485368952550068,1739502662.0550368,22.3799786567688,0.22830492644071762,1739502662.0550387,22.3799786567688,0.9682491651263272,1739502662.0550406,22.3799786567688,0.2955155657915696,1739502662.0550423,22.3799786567688,1.1522210179983938,1739502662.0550447,22.3799786567688,0.0,1739502662.0550466,22.3799786567688,-0.5220985894025987,1739502662.0550487,22.3799786567688,0.033746324119567524,1739502662.0550508,22.3799786567688,1.6743196074009925 +1739502662.075185,22.399978637695312,45.65372096552338,1739502662.0751894,22.399978637695312,0.021904041544273056,1739502662.0751944,22.399978637695312,45.45558614884508,1739502662.0751987,22.399978637695312,50.4010627637355,1739502662.075201,22.399978637695312,1.1896877157835926,1739502662.0752034,22.399978637695312,0.24119803268575019,1739502662.0752056,22.399978637695312,0.962968209659161,1739502662.0752077,22.399978637695312,0.3083362539433513,1739502662.0752096,22.399978637695312,1.1570991775876158,1739502662.0752118,22.399978637695312,0.0,1739502662.075214,22.399978637695312,-0.4318526942993438,1739502662.075216,22.399978637695312,0.04292973668914304,1739502662.0752184,22.399978637695312,1.6171537325973075 +1739502662.0952218,22.419978618621826,45.65372096552338,1739502662.095225,22.419978618621826,0.021904041544273056,1739502662.0952294,22.419978618621826,45.45558614884508,1739502662.0952332,22.419978618621826,50.4010627637355,1739502662.0952353,22.419978618621826,1.1896877157835926,1739502662.095238,22.419978618621826,0.24119803268575019,1739502662.0952399,22.419978618621826,0.962968209659161,1739502662.0952423,22.419978618621826,0.3083362539433513,1739502662.0952442,22.419978618621826,1.1570991775876158,1739502662.0952463,22.419978618621826,0.0,1739502662.0952482,22.419978618621826,-0.4600545550096917,1739502662.0952504,22.419978618621826,0.04292973668914304,1739502662.0952525,22.419978618621826,1.6171537325973075 +1739502662.1151288,22.43997859954834,45.65372096552338,1739502662.1151326,22.43997859954834,0.021904041544273056,1739502662.1151369,22.43997859954834,45.45558614884508,1739502662.1151407,22.43997859954834,50.4010627637355,1739502662.1151426,22.43997859954834,1.1896877157835926,1739502662.1151454,22.43997859954834,0.24119803268575019,1739502662.1151476,22.43997859954834,0.962968209659161,1739502662.1151493,22.43997859954834,0.3083362539433513,1739502662.1151514,22.43997859954834,1.1570991775876158,1739502662.1151536,22.43997859954834,0.0,1739502662.1151557,22.43997859954834,-0.4600545550096917,1739502662.1151578,22.43997859954834,0.04292973668914304,1739502662.1151597,22.43997859954834,1.6171537325973075 +1739502662.135073,22.459978580474854,45.65372096552338,1739502662.1350765,22.459978580474854,0.021904041544273056,1739502662.1350813,22.459978580474854,45.45558614884508,1739502662.1350853,22.459978580474854,50.4010627637355,1739502662.1350873,22.459978580474854,1.1896877157835926,1739502662.1350899,22.459978580474854,0.24119803268575019,1739502662.135092,22.459978580474854,0.962968209659161,1739502662.135094,22.459978580474854,0.3083362539433513,1739502662.1350958,22.459978580474854,1.1570991775876158,1739502662.1350982,22.459978580474854,0.0,1739502662.1351001,22.459978580474854,-0.4600545550096917,1739502662.1351025,22.459978580474854,0.04292973668914304,1739502662.1351042,22.459978580474854,1.6171537325973075 +1739502662.1552455,22.479978561401367,45.65372096552338,1739502662.155249,22.479978561401367,0.021904041544273056,1739502662.1552534,22.479978561401367,45.45558614884508,1739502662.1552577,22.479978561401367,50.4010627637355,1739502662.1552596,22.479978561401367,1.1896877157835926,1739502662.155262,22.479978561401367,0.24119803268575019,1739502662.155264,22.479978561401367,0.962968209659161,1739502662.155266,22.479978561401367,0.3083362539433513,1739502662.155268,22.479978561401367,1.1570991775876158,1739502662.1552699,22.479978561401367,0.0,1739502662.1552718,22.479978561401367,-0.4600545550096917,1739502662.1552737,22.479978561401367,0.04292973668914304,1739502662.1552758,22.479978561401367,1.6171537325973075 +1739502662.1749668,22.49997854232788,45.65372096552338,1739502662.1749709,22.49997854232788,0.021904041544273056,1739502662.1749756,22.49997854232788,45.45558614884508,1739502662.1749797,22.49997854232788,50.4010627637355,1739502662.1749814,22.49997854232788,1.1896877157835926,1739502662.174984,22.49997854232788,0.24119803268575019,1739502662.174986,22.49997854232788,0.962968209659161,1739502662.174988,22.49997854232788,0.3083362539433513,1739502662.17499,22.49997854232788,1.1570991775876158,1739502662.174992,22.49997854232788,0.0,1739502662.1749942,22.49997854232788,-0.4600545550096917,1739502662.1749964,22.49997854232788,0.04292973668914304,1739502662.1749988,22.49997854232788,1.6171537325973075 +1739502662.1955833,22.519978523254395,45.82893869301794,1739502662.1955864,22.519978523254395,0.030230827506923852,1739502662.1955907,22.519978523254395,45.45892361245344,1739502662.1955948,22.519978523254395,50.32649883352763,1739502662.1955965,22.519978523254395,1.1286808637953332,1739502662.195599,22.519978523254395,0.23954303762279347,1739502662.1956012,22.519978523254395,0.8576643354783533,1739502662.1956031,22.519978523254395,0.30623180147540446,1739502662.195605,22.519978523254395,1.2588004749243802,1739502662.1956072,22.519978523254395,0.0,1739502662.1956093,22.519978523254395,-0.2396317980697083,1739502662.1956115,22.519978523254395,0.05321632636998234,1739502662.1956134,22.519978523254395,1.5673144297004946 +1739502662.2151048,22.539978504180908,45.82893869301794,1739502662.2151089,22.539978504180908,0.030230827506923852,1739502662.2151132,22.539978504180908,45.45892361245344,1739502662.215117,22.539978504180908,50.32649883352763,1739502662.2151191,22.539978504180908,1.1286808637953332,1739502662.2151217,22.539978504180908,0.23954303762279347,1739502662.2151234,22.539978504180908,0.8576643354783533,1739502662.2151256,22.539978504180908,0.30623180147540446,1739502662.2151275,22.539978504180908,1.2588004749243802,1739502662.2151296,22.539978504180908,0.0,1739502662.215132,22.539978504180908,-0.30851395477611443,1739502662.215134,22.539978504180908,0.05321632636998234,1739502662.215136,22.539978504180908,1.5673144297004946 +1739502662.234951,22.559978485107422,45.82893869301794,1739502662.2349548,22.559978485107422,0.030230827506923852,1739502662.2349594,22.559978485107422,45.45892361245344,1739502662.2349632,22.559978485107422,50.32649883352763,1739502662.2349653,22.559978485107422,1.1286808637953332,1739502662.2349677,22.559978485107422,0.23954303762279347,1739502662.2349699,22.559978485107422,0.8576643354783533,1739502662.234972,22.559978485107422,0.30623180147540446,1739502662.2349737,22.559978485107422,1.2588004749243802,1739502662.234976,22.559978485107422,0.0,1739502662.2349777,22.559978485107422,-0.30851395477611443,1739502662.2349806,22.559978485107422,0.05321632636998234,1739502662.2349827,22.559978485107422,1.5673144297004946 +1739502662.2553582,22.579978466033936,45.82893869301794,1739502662.2553616,22.579978466033936,0.030230827506923852,1739502662.2553658,22.579978466033936,45.45892361245344,1739502662.2553697,22.579978466033936,50.32649883352763,1739502662.2553718,22.579978466033936,1.1286808637953332,1739502662.2553742,22.579978466033936,0.23954303762279347,1739502662.255376,22.579978466033936,0.8576643354783533,1739502662.2553782,22.579978466033936,0.30623180147540446,1739502662.25538,22.579978466033936,1.2588004749243802,1739502662.2553823,22.579978466033936,0.0,1739502662.2553842,22.579978466033936,-0.30851395477611443,1739502662.2553864,22.579978466033936,0.05321632636998234,1739502662.2553885,22.579978466033936,1.5673144297004946 +1739502662.275106,22.59997844696045,45.82893869301794,1739502662.2751095,22.59997844696045,0.030230827506923852,1739502662.275114,22.59997844696045,45.45892361245344,1739502662.2751179,22.59997844696045,50.32649883352763,1739502662.2751198,22.59997844696045,1.1286808637953332,1739502662.2751226,22.59997844696045,0.23954303762279347,1739502662.275125,22.59997844696045,0.8576643354783533,1739502662.2751267,22.59997844696045,0.30623180147540446,1739502662.2751288,22.59997844696045,1.2588004749243802,1739502662.2751312,22.59997844696045,0.0,1739502662.275133,22.59997844696045,-0.30851395477611443,1739502662.275135,22.59997844696045,0.05321632636998234,1739502662.275137,22.59997844696045,1.5673144297004946 +1739502662.29801,22.619978427886963,45.99923811296317,1739502662.298015,22.619978427886963,0.04016848539633333,1739502662.2980218,22.619978427886963,45.46216923909029,1739502662.2980297,22.619978427886963,50.274418506535156,1739502662.298034,22.619978427886963,1.0878902906934533,1739502662.2980394,22.619978427886963,0.24033404625904728,1739502662.2980444,22.619978427886963,0.7694884271930014,1739502662.2980492,22.619978427886963,0.3039724977960144,1739502662.2980545,22.619978427886963,1.3508040261876184,1739502662.2980595,22.619978427886963,0.0,1739502662.2980645,22.619978427886963,-0.1242096819881911,1739502662.2980695,22.619978427886963,0.06461462367847921,1739502662.2980752,22.619978427886963,1.5326088311843409 +1739502662.3143547,22.639978408813477,45.99923811296317,1739502662.3143573,22.639978408813477,0.04016848539633333,1739502662.314361,22.639978408813477,45.46216923909029,1739502662.314364,22.639978408813477,50.274418506535156,1739502662.3143654,22.639978408813477,1.0878902906934533,1739502662.3143675,22.639978408813477,0.24033404625904728,1739502662.3143687,22.639978408813477,0.7694884271930014,1739502662.3143702,22.639978408813477,0.3039724977960144,1739502662.3143713,22.639978408813477,1.3508040261876184,1739502662.3143735,22.639978408813477,0.0,1739502662.3143747,22.639978408813477,-0.18180480499672247,1739502662.314376,22.639978408813477,0.06461462367847921,1739502662.3143778,22.639978408813477,1.5326088311843409 +1739502662.334141,22.65997838973999,45.99923811296317,1739502662.334143,22.65997838973999,0.04016848539633333,1739502662.3341458,22.65997838973999,45.46216923909029,1739502662.3341484,22.65997838973999,50.274418506535156,1739502662.3341496,22.65997838973999,1.0878902906934533,1739502662.3341515,22.65997838973999,0.24033404625904728,1739502662.3341527,22.65997838973999,0.7694884271930014,1739502662.334154,22.65997838973999,0.3039724977960144,1739502662.3341553,22.65997838973999,1.3508040261876184,1739502662.3341568,22.65997838973999,0.0,1739502662.3341582,22.65997838973999,-0.18180480499672247,1739502662.3341594,22.65997838973999,0.06461462367847921,1739502662.3341606,22.65997838973999,1.5326088311843409 +1739502662.3543725,22.679978370666504,45.99923811296317,1739502662.3543751,22.679978370666504,0.04016848539633333,1739502662.3543785,22.679978370666504,45.46216923909029,1739502662.3543813,22.679978370666504,50.274418506535156,1739502662.3543828,22.679978370666504,1.0878902906934533,1739502662.3543844,22.679978370666504,0.24033404625904728,1739502662.3543859,22.679978370666504,0.7694884271930014,1739502662.3543878,22.679978370666504,0.3039724977960144,1739502662.3543887,22.679978370666504,1.3508040261876184,1739502662.3543904,22.679978370666504,0.0,1739502662.3543916,22.679978370666504,-0.18180480499672247,1739502662.3543928,22.679978370666504,0.06461462367847921,1739502662.3543947,22.679978370666504,1.5326088311843409 +1739502662.3741333,22.699978351593018,45.99923811296317,1739502662.3741355,22.699978351593018,0.04016848539633333,1739502662.374138,22.699978351593018,45.46216923909029,1739502662.3741407,22.699978351593018,50.274418506535156,1739502662.374142,22.699978351593018,1.0878902906934533,1739502662.3741436,22.699978351593018,0.24033404625904728,1739502662.3741448,22.699978351593018,0.7694884271930014,1739502662.374146,22.699978351593018,0.3039724977960144,1739502662.3741477,22.699978351593018,1.3508040261876184,1739502662.374149,22.699978351593018,0.0,1739502662.3741505,22.699978351593018,-0.18180480499672247,1739502662.3741517,22.699978351593018,0.06461462367847921,1739502662.374153,22.699978351593018,1.5326088311843409 +1739502662.3944144,22.71997833251953,45.99923811296317,1739502662.3944168,22.71997833251953,0.04016848539633333,1739502662.39442,22.71997833251953,45.46216923909029,1739502662.3944228,22.71997833251953,50.274418506535156,1739502662.394424,22.71997833251953,1.0878902906934533,1739502662.3944259,22.71997833251953,0.24033404625904728,1739502662.394427,22.71997833251953,0.7694884271930014,1739502662.3944287,22.71997833251953,0.3039724977960144,1739502662.39443,22.71997833251953,1.3508040261876184,1739502662.3944316,22.71997833251953,0.0,1739502662.3944333,22.71997833251953,-0.18180480499672247,1739502662.394435,22.71997833251953,0.06461462367847921,1739502662.3944361,22.71997833251953,1.5326088311843409 +1739502662.414501,22.739978313446045,46.16652527096918,1739502662.4145033,22.739978313446045,0.05189340258527064,1739502662.4145067,22.739978313446045,45.46535942000959,1739502662.41451,22.739978313446045,50.247087497011364,1739502662.4145117,22.739978313446045,1.0670666643896112,1739502662.4145136,22.739978313446045,0.2438326351916835,1739502662.4145153,22.739978313446045,0.700625379112181,1739502662.4145167,22.739978313446045,0.30327972328463926,1739502662.4145184,22.739978313446045,1.4273083938772477,1739502662.41452,22.739978313446045,0.0,1739502662.4145217,22.739978313446045,-0.043216483219311756,1739502662.4145234,22.739978313446045,0.07643251245251903,1739502662.4145253,22.739978313446045,1.5138337560475141 +1739502662.436121,22.75997829437256,46.16652527096918,1739502662.436126,22.75997829437256,0.05189340258527064,1739502662.4361308,22.75997829437256,45.46535942000959,1739502662.4361355,22.75997829437256,50.247087497011364,1739502662.436138,22.75997829437256,1.0670666643896112,1739502662.4361408,22.75997829437256,0.2438326351916835,1739502662.4361436,22.75997829437256,0.700625379112181,1739502662.436146,22.75997829437256,0.30327972328463926,1739502662.436148,22.75997829437256,1.4273083938772477,1739502662.4361513,22.75997829437256,0.0,1739502662.4361537,22.75997829437256,-0.0865253621702664,1739502662.4361567,22.75997829437256,0.07643251245251903,1739502662.436159,22.75997829437256,1.5138337560475141 +1739502662.4554622,22.779978275299072,46.16652527096918,1739502662.455469,22.779978275299072,0.05189340258527064,1739502662.455476,22.779978275299072,45.46535942000959,1739502662.4554818,22.779978275299072,50.247087497011364,1739502662.455485,22.779978275299072,1.0670666643896112,1739502662.4554896,22.779978275299072,0.2438326351916835,1739502662.4554937,22.779978275299072,0.700625379112181,1739502662.4554965,22.779978275299072,0.30327972328463926,1739502662.4555137,22.779978275299072,1.4273083938772477,1739502662.4555178,22.779978275299072,0.0,1739502662.4555213,22.779978275299072,-0.0865253621702664,1739502662.4555254,22.779978275299072,0.07643251245251903,1739502662.455528,22.779978275299072,1.5138337560475141 +1739502662.4753146,22.799978256225586,46.16652527096918,1739502662.4753182,22.799978256225586,0.05189340258527064,1739502662.4753232,22.799978256225586,45.46535942000959,1739502662.4753277,22.799978256225586,50.247087497011364,1739502662.47533,22.799978256225586,1.0670666643896112,1739502662.475333,22.799978256225586,0.2438326351916835,1739502662.475335,22.799978256225586,0.700625379112181,1739502662.4753373,22.799978256225586,0.30327972328463926,1739502662.4753392,22.799978256225586,1.4273083938772477,1739502662.475342,22.799978256225586,0.0,1739502662.4753444,22.799978256225586,-0.0865253621702664,1739502662.4753468,22.799978256225586,0.07643251245251903,1739502662.475349,22.799978256225586,1.5138337560475141 +1739502662.4956381,22.8199782371521,46.16652527096918,1739502662.4956417,22.8199782371521,0.05189340258527064,1739502662.4956467,22.8199782371521,45.46535942000959,1739502662.4956512,22.8199782371521,50.247087497011364,1739502662.4956536,22.8199782371521,1.0670666643896112,1739502662.4956565,22.8199782371521,0.2438326351916835,1739502662.4956586,22.8199782371521,0.700625379112181,1739502662.495661,22.8199782371521,0.30327972328463926,1739502662.4956632,22.8199782371521,1.4273083938772477,1739502662.4956656,22.8199782371521,0.0,1739502662.495668,22.8199782371521,-0.0865253621702664,1739502662.4956703,22.8199782371521,0.07643251245251903,1739502662.4956725,22.8199782371521,1.5138337560475141 +1739502662.51545,22.839978218078613,46.33199612346015,1739502662.5154533,22.839978218078613,0.06545892752239357,1739502662.5154576,22.839978218078613,45.468516931731855,1739502662.5154614,22.839978218078613,50.23426444606662,1739502662.515463,22.839978218078613,1.0575952832491957,1739502662.5154657,22.839978218078613,0.24897094739996908,1739502662.5154674,22.839978218078613,0.6443455068588919,1739502662.5154696,22.839978218078613,0.3041939468792044,1739502662.5154712,22.839978218078613,1.4930400246266564,1739502662.5154734,22.839978218078613,0.0,1739502662.5154753,22.839978218078613,0.022974657585347204,1739502662.515477,22.839978218078613,0.08825040122655885,1739502662.515479,22.839978218078613,1.504284145650518 +1739502662.534602,22.859978199005127,46.33199612346015,1739502662.534605,22.859978199005127,0.06545892752239357,1739502662.5346088,22.859978199005127,45.468516931731855,1739502662.534612,22.859978199005127,50.23426444606662,1739502662.5346138,22.859978199005127,1.0575952832491957,1739502662.5346158,22.859978199005127,0.24897094739996908,1739502662.5346177,22.859978199005127,0.6443455068588919,1739502662.534619,22.859978199005127,0.3041939468792044,1739502662.5346208,22.859978199005127,1.4930400246266564,1739502662.5346224,22.859978199005127,0.0,1739502662.5346243,22.859978199005127,-0.01124412102386163,1739502662.5346258,22.859978199005127,0.08825040122655885,1739502662.5346277,22.859978199005127,1.504284145650518 +1739502662.5547173,22.87997817993164,46.33199612346015,1739502662.5547202,22.87997817993164,0.06545892752239357,1739502662.5547237,22.87997817993164,45.468516931731855,1739502662.554727,22.87997817993164,50.23426444606662,1739502662.5547287,22.87997817993164,1.0575952832491957,1739502662.5547307,22.87997817993164,0.24897094739996908,1739502662.5547323,22.87997817993164,0.6443455068588919,1739502662.554734,22.87997817993164,0.3041939468792044,1739502662.5547357,22.87997817993164,1.4930400246266564,1739502662.5547373,22.87997817993164,0.0,1739502662.554739,22.87997817993164,-0.01124412102386163,1739502662.5547407,22.87997817993164,0.08825040122655885,1739502662.5547423,22.87997817993164,1.504284145650518 +1739502662.574559,22.899978160858154,46.33199612346015,1739502662.5745618,22.899978160858154,0.06545892752239357,1739502662.5745654,22.899978160858154,45.468516931731855,1739502662.5745687,22.899978160858154,50.23426444606662,1739502662.5745704,22.899978160858154,1.0575952832491957,1739502662.5745726,22.899978160858154,0.24897094739996908,1739502662.5745742,22.899978160858154,0.6443455068588919,1739502662.5745761,22.899978160858154,0.3041939468792044,1739502662.5745776,22.899978160858154,1.4930400246266564,1739502662.5745795,22.899978160858154,0.0,1739502662.574581,22.899978160858154,-0.01124412102386163,1739502662.5745828,22.899978160858154,0.08825040122655885,1739502662.5745842,22.899978160858154,1.504284145650518 +1739502662.594583,22.919978141784668,46.33199612346015,1739502662.594586,22.919978141784668,0.06545892752239357,1739502662.5945895,22.919978141784668,45.468516931731855,1739502662.594593,22.919978141784668,50.23426444606662,1739502662.5945945,22.919978141784668,1.0575952832491957,1739502662.5945966,22.919978141784668,0.24897094739996908,1739502662.5945983,22.919978141784668,0.6443455068588919,1739502662.5946,22.919978141784668,0.3041939468792044,1739502662.5946014,22.919978141784668,1.4930400246266564,1739502662.5946035,22.919978141784668,0.0,1739502662.594605,22.919978141784668,-0.01124412102386163,1739502662.5946069,22.919978141784668,0.08825040122655885,1739502662.5946085,22.919978141784668,1.504284145650518 +1739502662.6145618,22.93997812271118,46.33199612346015,1739502662.6145647,22.93997812271118,0.06545892752239357,1739502662.6145682,22.93997812271118,45.468516931731855,1739502662.6145713,22.93997812271118,50.23426444606662,1739502662.614573,22.93997812271118,1.0575952832491957,1739502662.6145751,22.93997812271118,0.24897094739996908,1739502662.6145766,22.93997812271118,0.6443455068588919,1739502662.6145785,22.93997812271118,0.3041939468792044,1739502662.61458,22.93997812271118,1.4930400246266564,1739502662.614582,22.93997812271118,0.0,1739502662.6145835,22.93997812271118,-0.01124412102386163,1739502662.6145854,22.93997812271118,0.08825040122655885,1739502662.614587,22.93997812271118,1.504284145650518 +1739502662.6347013,22.959978103637695,46.49674486524493,1739502662.6347044,22.959978103637695,0.08092820346907814,1739502662.634708,22.959978103637695,45.73343089244336,1739502662.634711,22.959978103637695,50.440281192072675,1739502662.634713,22.959978103637695,1.222281737857003,1739502662.6347148,22.959978103637695,0.2817259013725689,1739502662.6347165,22.959978103637695,0.7416790738441386,1739502662.6347182,22.959978103637695,0.3365447117089435,1739502662.6347194,22.959978103637695,1.3811927988081896,1739502662.6347215,22.959978103637695,0.0,1739502662.6347232,22.959978103637695,-0.1731270779889052,1739502662.6347249,22.959978103637695,0.10006829000059866,1739502662.6347268,22.959978103637695,1.5037314195771414 +1739502662.6550343,22.97997808456421,46.49674486524493,1739502662.6550376,22.97997808456421,0.08092820346907814,1739502662.6550424,22.97997808456421,45.73343089244336,1739502662.6550457,22.97997808456421,50.440281192072675,1739502662.6550474,22.97997808456421,1.222281737857003,1739502662.6550496,22.97997808456421,0.2817259013725689,1739502662.6550512,22.97997808456421,0.7416790738441386,1739502662.6550531,22.97997808456421,0.3365447117089435,1739502662.6550546,22.97997808456421,1.3811927988081896,1739502662.6550567,22.97997808456421,0.0,1739502662.6550581,22.97997808456421,-0.12253862076895183,1739502662.65506,22.97997808456421,0.10006829000059866,1739502662.6550615,22.97997808456421,1.5037314195771414 +1739502662.6745317,22.999978065490723,46.49674486524493,1739502662.6745343,22.999978065490723,0.08092820346907814,1739502662.674538,22.999978065490723,45.73343089244336,1739502662.6745412,22.999978065490723,50.440281192072675,1739502662.674543,22.999978065490723,1.222281737857003,1739502662.6745448,22.999978065490723,0.2817259013725689,1739502662.6745465,22.999978065490723,0.7416790738441386,1739502662.6745481,22.999978065490723,0.3365447117089435,1739502662.6745498,22.999978065490723,1.3811927988081896,1739502662.6745515,22.999978065490723,0.0,1739502662.6745534,22.999978065490723,-0.12253862076895183,1739502662.674555,22.999978065490723,0.10006829000059866,1739502662.674557,22.999978065490723,1.5037314195771414 +1739502662.694919,23.019978046417236,46.49674486524493,1739502662.6949224,23.019978046417236,0.08092820346907814,1739502662.6949265,23.019978046417236,45.73343089244336,1739502662.6949298,23.019978046417236,50.440281192072675,1739502662.6949317,23.019978046417236,1.222281737857003,1739502662.6949337,23.019978046417236,0.2817259013725689,1739502662.6949353,23.019978046417236,0.7416790738441386,1739502662.694937,23.019978046417236,0.3365447117089435,1739502662.6949387,23.019978046417236,1.3811927988081896,1739502662.6949406,23.019978046417236,0.0,1739502662.6949422,23.019978046417236,-0.12253862076895183,1739502662.694944,23.019978046417236,0.10006829000059866,1739502662.6949458,23.019978046417236,1.5037314195771414 +1739502662.7149756,23.03997802734375,46.49674486524493,1739502662.714979,23.03997802734375,0.08092820346907814,1739502662.7149825,23.03997802734375,45.73343089244336,1739502662.7149854,23.03997802734375,50.440281192072675,1739502662.7149873,23.03997802734375,1.222281737857003,1739502662.7149897,23.03997802734375,0.2817259013725689,1739502662.714991,23.03997802734375,0.7416790738441386,1739502662.714993,23.03997802734375,0.3365447117089435,1739502662.7149944,23.03997802734375,1.3811927988081896,1739502662.7149966,23.03997802734375,0.0,1739502662.714998,23.03997802734375,-0.12253862076895183,1739502662.715,23.03997802734375,0.10006829000059866,1739502662.7150016,23.03997802734375,1.5037314195771414 +1739502662.734599,23.059978008270264,46.66059047426573,1739502662.734602,23.059978008270264,0.09828417760622976,1739502662.7346053,23.059978008270264,45.926574578027136,1739502662.7346087,23.059978008270264,50.56399651153039,1739502662.73461,23.059978008270264,1.3336876743281814,1739502662.7346122,23.059978008270264,0.3065191268704497,1739502662.7346137,23.059978008270264,0.7901171296422699,1739502662.7346156,23.059978008270264,0.36025621886615283,1739502662.734617,23.059978008270264,1.3286946952359155,1739502662.734619,23.059978008270264,0.0,1739502662.7346203,23.059978008270264,-0.17951643885724497,1739502662.7346222,23.059978008270264,0.11231812695984851,1739502662.734624,23.059978008270264,1.490405554266321 +1739502662.7547662,23.079977989196777,46.66059047426573,1739502662.7547703,23.079977989196777,0.09828417760622976,1739502662.7547739,23.079977989196777,45.926574578027136,1739502662.7547774,23.079977989196777,50.56399651153039,1739502662.754779,23.079977989196777,1.3336876743281814,1739502662.7547812,23.079977989196777,0.3065191268704497,1739502662.7547834,23.079977989196777,0.7901171296422699,1739502662.754785,23.079977989196777,0.36025621886615283,1739502662.7547865,23.079977989196777,1.3286946952359155,1739502662.7547886,23.079977989196777,0.0,1739502662.75479,23.079977989196777,-0.1617108590304055,1739502662.7547922,23.079977989196777,0.11231812695984851,1739502662.754794,23.079977989196777,1.490405554266321 +1739502662.7746923,23.09997797012329,46.66059047426573,1739502662.7746956,23.09997797012329,0.09828417760622976,1739502662.7746992,23.09997797012329,45.926574578027136,1739502662.7747025,23.09997797012329,50.56399651153039,1739502662.7747042,23.09997797012329,1.3336876743281814,1739502662.7747064,23.09997797012329,0.3065191268704497,1739502662.7747083,23.09997797012329,0.7901171296422699,1739502662.7747097,23.09997797012329,0.36025621886615283,1739502662.7747116,23.09997797012329,1.3286946952359155,1739502662.7747133,23.09997797012329,0.0,1739502662.7747152,23.09997797012329,-0.1617108590304055,1739502662.7747169,23.09997797012329,0.11231812695984851,1739502662.7747185,23.09997797012329,1.490405554266321 +1739502662.7945166,23.119977951049805,46.66059047426573,1739502662.794519,23.119977951049805,0.09828417760622976,1739502662.7945223,23.119977951049805,45.926574578027136,1739502662.7945256,23.119977951049805,50.56399651153039,1739502662.7945275,23.119977951049805,1.3336876743281814,1739502662.7945292,23.119977951049805,0.3065191268704497,1739502662.7945309,23.119977951049805,0.7901171296422699,1739502662.7945323,23.119977951049805,0.36025621886615283,1739502662.794534,23.119977951049805,1.3286946952359155,1739502662.7945359,23.119977951049805,0.0,1739502662.7945375,23.119977951049805,-0.1617108590304055,1739502662.794539,23.119977951049805,0.11231812695984851,1739502662.794541,23.119977951049805,1.490405554266321 +1739502662.8145611,23.13997793197632,46.66059047426573,1739502662.814564,23.13997793197632,0.09828417760622976,1739502662.8145676,23.13997793197632,45.926574578027136,1739502662.814571,23.13997793197632,50.56399651153039,1739502662.8145726,23.13997793197632,1.3336876743281814,1739502662.8145745,23.13997793197632,0.3065191268704497,1739502662.8145764,23.13997793197632,0.7901171296422699,1739502662.8145778,23.13997793197632,0.36025621886615283,1739502662.8145795,23.13997793197632,1.3286946952359155,1739502662.8145814,23.13997793197632,0.0,1739502662.814583,23.13997793197632,-0.1617108590304055,1739502662.8145847,23.13997793197632,0.11231812695984851,1739502662.8145866,23.13997793197632,1.490405554266321 +1739502662.8345685,23.159977912902832,46.66059047426573,1739502662.8345714,23.159977912902832,0.09828417760622976,1739502662.834575,23.159977912902832,45.926574578027136,1739502662.834578,23.159977912902832,50.56399651153039,1739502662.8345797,23.159977912902832,1.3336876743281814,1739502662.8345819,23.159977912902832,0.3065191268704497,1739502662.8345833,23.159977912902832,0.7901171296422699,1739502662.8345847,23.159977912902832,0.36025621886615283,1739502662.8345864,23.159977912902832,1.3286946952359155,1739502662.834588,23.159977912902832,0.0,1739502662.8345897,23.159977912902832,-0.1617108590304055,1739502662.8345912,23.159977912902832,0.11231812695984851,1739502662.834593,23.159977912902832,1.490405554266321 +1739502662.8549535,23.179977893829346,46.82247335614242,1739502662.8549569,23.179977893829346,0.11752572921932991,1739502662.8549604,23.179977893829346,46.828169778250434,1739502662.854964,23.179977893829346,51.126614119125215,1739502662.8549657,23.179977893829346,1.9883207864899046,1739502662.8549678,23.179977893829346,0.4100158625708444,1739502662.8549695,23.179977893829346,1.3162525316660152,1739502662.8549714,23.179977893829346,0.4554285996082476,1739502662.8549728,23.179977893829346,0.8722220059837461,1739502662.854975,23.179977893829346,0.0,1739502662.8549764,23.179977893829346,-0.7993863655654471,1739502662.8549783,23.179977893829346,0.1257389312373576,1739502662.8549798,23.179977893829346,1.4723346451029562 +1739502662.874565,23.19997787475586,46.82247335614242,1739502662.8745677,23.19997787475586,0.11752572921932991,1739502662.874571,23.19997787475586,46.828169778250434,1739502662.8745744,23.19997787475586,51.126614119125215,1739502662.8745759,23.19997787475586,1.9883207864899046,1739502662.874578,23.19997787475586,0.4100158625708444,1739502662.8745797,23.19997787475586,1.3162525316660152,1739502662.8745813,23.19997787475586,0.4554285996082476,1739502662.874583,23.19997787475586,0.8722220059837461,1739502662.874585,23.19997787475586,0.0,1739502662.8745863,23.19997787475586,-0.6001126391192101,1739502662.8745883,23.19997787475586,0.1257389312373576,1739502662.87459,23.19997787475586,1.4723346451029562 +1739502662.8949766,23.219977855682373,46.82247335614242,1739502662.8949795,23.219977855682373,0.11752572921932991,1739502662.8949835,23.219977855682373,46.828169778250434,1739502662.894987,23.219977855682373,51.126614119125215,1739502662.8949885,23.219977855682373,1.9883207864899046,1739502662.8949912,23.219977855682373,0.4100158625708444,1739502662.8949926,23.219977855682373,1.3162525316660152,1739502662.8949945,23.219977855682373,0.4554285996082476,1739502662.894996,23.219977855682373,0.8722220059837461,1739502662.894998,23.219977855682373,0.0,1739502662.8949997,23.219977855682373,-0.6001126391192101,1739502662.8950016,23.219977855682373,0.1257389312373576,1739502662.8950036,23.219977855682373,1.4723346451029562 +1739502662.9146614,23.239977836608887,46.82247335614242,1739502662.9146645,23.239977836608887,0.11752572921932991,1739502662.914668,23.239977836608887,46.828169778250434,1739502662.9146714,23.239977836608887,51.126614119125215,1739502662.914673,23.239977836608887,1.9883207864899046,1739502662.9146752,23.239977836608887,0.4100158625708444,1739502662.914677,23.239977836608887,1.3162525316660152,1739502662.9146786,23.239977836608887,0.4554285996082476,1739502662.91468,23.239977836608887,0.8722220059837461,1739502662.9146821,23.239977836608887,0.0,1739502662.9146836,23.239977836608887,-0.6001126391192101,1739502662.9146855,23.239977836608887,0.1257389312373576,1739502662.9146872,23.239977836608887,1.4723346451029562 +1739502662.9351103,23.2599778175354,46.82247335614242,1739502662.9351134,23.2599778175354,0.11752572921932991,1739502662.935117,23.2599778175354,46.828169778250434,1739502662.9351203,23.2599778175354,51.126614119125215,1739502662.935122,23.2599778175354,1.9883207864899046,1739502662.935124,23.2599778175354,0.4100158625708444,1739502662.9351256,23.2599778175354,1.3162525316660152,1739502662.935127,23.2599778175354,0.4554285996082476,1739502662.9351287,23.2599778175354,0.8722220059837461,1739502662.9351306,23.2599778175354,0.0,1739502662.9351323,23.2599778175354,-0.6001126391192101,1739502662.9351337,23.2599778175354,0.1257389312373576,1739502662.9351356,23.2599778175354,1.4723346451029562 +1739502662.9548073,23.279977798461914,46.979850334782334,1739502662.9548109,23.279977798461914,0.13845943442215436,1739502662.9548142,23.279977798461914,46.92416596208705,1739502662.9548175,23.279977798461914,51.10711779446093,1739502662.9548194,23.279977798461914,1.9596178640674853,1739502662.9548216,23.279977798461914,0.4155539811479867,1739502662.9548233,23.279977798461914,1.2256561290723575,1739502662.954825,23.279977798461914,0.4589219248958546,1739502662.9548268,23.279977798461914,0.9377853713183676,1739502662.9548285,23.279977798461914,0.0,1739502662.9548302,23.279977798461914,-0.409697233202136,1739502662.9548318,23.279977798461914,0.14040364357366894,1739502662.954834,23.279977798461914,1.4069874578840114 +1739502662.9745932,23.299977779388428,46.979850334782334,1739502662.9745965,23.299977779388428,0.13845943442215436,1739502662.9745998,23.299977779388428,46.92416596208705,1739502662.9746032,23.299977779388428,51.10711779446093,1739502662.974605,23.299977779388428,1.9596178640674853,1739502662.9746068,23.299977779388428,0.4155539811479867,1739502662.9746087,23.299977779388428,1.2256561290723575,1739502662.97461,23.299977779388428,0.4589219248958546,1739502662.974612,23.299977779388428,0.9377853713183676,1739502662.9746137,23.299977779388428,0.0,1739502662.9746156,23.299977779388428,-0.4692020865656438,1739502662.9746172,23.299977779388428,0.14040364357366894,1739502662.974619,23.299977779388428,1.4069874578840114 +1739502662.9948182,23.31997776031494,46.979850334782334,1739502662.9948218,23.31997776031494,0.13845943442215436,1739502662.9948258,23.31997776031494,46.92416596208705,1739502662.994829,23.31997776031494,51.10711779446093,1739502662.9948308,23.31997776031494,1.9596178640674853,1739502662.994833,23.31997776031494,0.4155539811479867,1739502662.9948347,23.31997776031494,1.2256561290723575,1739502662.9948363,23.31997776031494,0.4589219248958546,1739502662.9948378,23.31997776031494,0.9377853713183676,1739502662.99484,23.31997776031494,0.0,1739502662.9948413,23.31997776031494,-0.4692020865656438,1739502662.9948432,23.31997776031494,0.14040364357366894,1739502662.994845,23.31997776031494,1.4069874578840114 +1739502663.0146058,23.339977741241455,46.979850334782334,1739502663.0146086,23.339977741241455,0.13845943442215436,1739502663.0146122,23.339977741241455,46.92416596208705,1739502663.0146155,23.339977741241455,51.10711779446093,1739502663.0146172,23.339977741241455,1.9596178640674853,1739502663.014619,23.339977741241455,0.4155539811479867,1739502663.014621,23.339977741241455,1.2256561290723575,1739502663.0146224,23.339977741241455,0.4589219248958546,1739502663.014624,23.339977741241455,0.9377853713183676,1739502663.014626,23.339977741241455,0.0,1739502663.0146277,23.339977741241455,-0.4692020865656438,1739502663.0146294,23.339977741241455,0.14040364357366894,1739502663.0146308,23.339977741241455,1.4069874578840114 +1739502663.0346398,23.35997772216797,46.979850334782334,1739502663.034643,23.35997772216797,0.13845943442215436,1739502663.0346463,23.35997772216797,46.92416596208705,1739502663.0346496,23.35997772216797,51.10711779446093,1739502663.034651,23.35997772216797,1.9596178640674853,1739502663.0346532,23.35997772216797,0.4155539811479867,1739502663.034655,23.35997772216797,1.2256561290723575,1739502663.0346565,23.35997772216797,0.4589219248958546,1739502663.034658,23.35997772216797,0.9377853713183676,1739502663.0346599,23.35997772216797,0.0,1739502663.0346615,23.35997772216797,-0.4692020865656438,1739502663.0346632,23.35997772216797,0.14040364357366894,1739502663.0346649,23.35997772216797,1.4069874578840114 +1739502663.0547597,23.379977703094482,46.979850334782334,1739502663.0547628,23.379977703094482,0.13845943442215436,1739502663.0547667,23.379977703094482,46.92416596208705,1739502663.0547702,23.379977703094482,51.10711779446093,1739502663.054772,23.379977703094482,1.9596178640674853,1739502663.054774,23.379977703094482,0.4155539811479867,1739502663.054776,23.379977703094482,1.2256561290723575,1739502663.0547776,23.379977703094482,0.4589219248958546,1739502663.0547793,23.379977703094482,0.9377853713183676,1739502663.0547812,23.379977703094482,0.0,1739502663.0547829,23.379977703094482,-0.4692020865656438,1739502663.0547848,23.379977703094482,0.14040364357366894,1739502663.0547864,23.379977703094482,1.4069874578840114 +1739502663.075104,23.399977684020996,47.1305013800405,1739502663.0751076,23.399977684020996,0.16084496671536552,1739502663.0751114,23.399977684020996,46.927073103011544,1739502663.0751152,23.399977684020996,51.051200296895956,1739502663.075117,23.399977684020996,1.8796869037456703,1739502663.0751197,23.399977684020996,0.4131672130753632,1739502663.0751216,23.399977684020996,1.087191383672408,1739502663.0751235,23.399977684020996,0.4521541046243205,1739502663.075125,23.399977684020996,1.0476374956209697,1739502663.0751276,23.399977684020996,0.0,1739502663.0751293,23.399977684020996,-0.2363544999826731,1739502663.0751314,23.399977684020996,0.1563929095303462,1739502663.075133,23.399977684020996,1.3567569141192195 +1739502663.095045,23.41997766494751,47.1305013800405,1739502663.09505,23.41997766494751,0.16084496671536552,1739502663.0950563,23.41997766494751,46.927073103011544,1739502663.0950634,23.41997766494751,51.051200296895956,1739502663.0950677,23.41997766494751,1.8796869037456703,1739502663.0950735,23.41997766494751,0.4131672130753632,1739502663.0950797,23.41997766494751,1.087191383672408,1739502663.0950854,23.41997766494751,0.4521541046243205,1739502663.0950885,23.41997766494751,1.0476374956209697,1739502663.095091,23.41997766494751,0.0,1739502663.0950944,23.41997766494751,-0.30911941849824975,1739502663.0951006,23.41997766494751,0.1563929095303462,1739502663.095105,23.41997766494751,1.3567569141192195 +1739502663.1150393,23.439977645874023,47.1305013800405,1739502663.115043,23.439977645874023,0.16084496671536552,1739502663.1150467,23.439977645874023,46.927073103011544,1739502663.1150506,23.439977645874023,51.051200296895956,1739502663.1150522,23.439977645874023,1.8796869037456703,1739502663.1150546,23.439977645874023,0.4131672130753632,1739502663.1150568,23.439977645874023,1.087191383672408,1739502663.1150582,23.439977645874023,0.4521541046243205,1739502663.1150599,23.439977645874023,1.0476374956209697,1739502663.1150622,23.439977645874023,0.0,1739502663.1150641,23.439977645874023,-0.30911941849824975,1739502663.1150658,23.439977645874023,0.1563929095303462,1739502663.115068,23.439977645874023,1.3567569141192195 +1739502663.135069,23.459977626800537,47.1305013800405,1739502663.1350722,23.459977626800537,0.16084496671536552,1739502663.1350763,23.459977626800537,46.927073103011544,1739502663.1350799,23.459977626800537,51.051200296895956,1739502663.1350818,23.459977626800537,1.8796869037456703,1739502663.135084,23.459977626800537,0.4131672130753632,1739502663.1350858,23.459977626800537,1.087191383672408,1739502663.135088,23.459977626800537,0.4521541046243205,1739502663.1350896,23.459977626800537,1.0476374956209697,1739502663.135092,23.459977626800537,0.0,1739502663.1350937,23.459977626800537,-0.30911941849824975,1739502663.1350956,23.459977626800537,0.1563929095303462,1739502663.1350973,23.459977626800537,1.3567569141192195 +1739502663.1549098,23.47997760772705,47.1305013800405,1739502663.154913,23.47997760772705,0.16084496671536552,1739502663.1549168,23.47997760772705,46.927073103011544,1739502663.1549208,23.47997760772705,51.051200296895956,1739502663.1549225,23.47997760772705,1.8796869037456703,1739502663.1549249,23.47997760772705,0.4131672130753632,1739502663.1549268,23.47997760772705,1.087191383672408,1739502663.1549287,23.47997760772705,0.4521541046243205,1739502663.15493,23.47997760772705,1.0476374956209697,1739502663.1549323,23.47997760772705,0.0,1739502663.154934,23.47997760772705,-0.30911941849824975,1739502663.154936,23.47997760772705,0.1563929095303462,1739502663.1549377,23.47997760772705,1.3567569141192195 +1739502663.1750658,23.499977588653564,47.27601153586769,1739502663.175069,23.499977588653564,0.1849440898256045,1739502663.1750734,23.499977588653564,46.92988599421848,1739502663.1750772,23.499977588653564,51.013771297667326,1739502663.1750789,23.499977588653564,1.8284238810184406,1739502663.1750813,23.499977588653564,0.4142525522963405,1739502663.175083,23.499977588653564,0.9726246705170164,1739502663.1750848,23.499977588653564,0.4447581342962402,1739502663.1750865,23.499977588653564,1.14819482933308,1739502663.1750886,23.499977588653564,0.0,1739502663.1750908,23.499977588653564,-0.11464607746113609,1739502663.1750925,23.499977588653564,0.17373407954622683,1739502663.1750946,23.499977588653564,1.323613865714171 +1739502663.194936,23.519977569580078,47.27601153586769,1739502663.1949391,23.519977569580078,0.1849440898256045,1739502663.1949427,23.519977569580078,46.92988599421848,1739502663.1949463,23.519977569580078,51.013771297667326,1739502663.1949482,23.519977569580078,1.8284238810184406,1739502663.19495,23.519977569580078,0.4142525522963405,1739502663.1949522,23.519977569580078,0.9726246705170164,1739502663.194954,23.519977569580078,0.4447581342962402,1739502663.1949558,23.519977569580078,1.14819482933308,1739502663.1949577,23.519977569580078,0.0,1739502663.1949596,23.519977569580078,-0.17541903638109102,1739502663.1949613,23.519977569580078,0.17373407954622683,1739502663.1949632,23.519977569580078,1.323613865714171 +1739502663.215046,23.539977550506592,47.27601153586769,1739502663.2150495,23.539977550506592,0.1849440898256045,1739502663.2150536,23.539977550506592,46.92988599421848,1739502663.2150571,23.539977550506592,51.013771297667326,1739502663.215059,23.539977550506592,1.8284238810184406,1739502663.2150612,23.539977550506592,0.4142525522963405,1739502663.215063,23.539977550506592,0.9726246705170164,1739502663.2150648,23.539977550506592,0.4447581342962402,1739502663.2150667,23.539977550506592,1.14819482933308,1739502663.2150686,23.539977550506592,0.0,1739502663.2150707,23.539977550506592,-0.17541903638109102,1739502663.2150724,23.539977550506592,0.17373407954622683,1739502663.2150743,23.539977550506592,1.323613865714171 +1739502663.2350025,23.559977531433105,47.27601153586769,1739502663.2350059,23.559977531433105,0.1849440898256045,1739502663.2350104,23.559977531433105,46.92988599421848,1739502663.2350142,23.559977531433105,51.013771297667326,1739502663.2350159,23.559977531433105,1.8284238810184406,1739502663.2350183,23.559977531433105,0.4142525522963405,1739502663.2350204,23.559977531433105,0.9726246705170164,1739502663.2350218,23.559977531433105,0.4447581342962402,1739502663.2350235,23.559977531433105,1.14819482933308,1739502663.235026,23.559977531433105,0.0,1739502663.2350278,23.559977531433105,-0.17541903638109102,1739502663.2350295,23.559977531433105,0.17373407954622683,1739502663.2350316,23.559977531433105,1.323613865714171 +1739502663.2548413,23.57997751235962,47.27601153586769,1739502663.2548444,23.57997751235962,0.1849440898256045,1739502663.2548482,23.57997751235962,46.92988599421848,1739502663.2548518,23.57997751235962,51.013771297667326,1739502663.254854,23.57997751235962,1.8284238810184406,1739502663.254856,23.57997751235962,0.4142525522963405,1739502663.254858,23.57997751235962,0.9726246705170164,1739502663.2548597,23.57997751235962,0.4447581342962402,1739502663.2548614,23.57997751235962,1.14819482933308,1739502663.2548633,23.57997751235962,0.0,1739502663.2548652,23.57997751235962,-0.17541903638109102,1739502663.2548673,23.57997751235962,0.17373407954622683,1739502663.254869,23.57997751235962,1.323613865714171 +1739502663.2750723,23.599977493286133,47.27601153586769,1739502663.275076,23.599977493286133,0.1849440898256045,1739502663.27508,23.599977493286133,46.92988599421848,1739502663.275084,23.599977493286133,51.013771297667326,1739502663.275086,23.599977493286133,1.8284238810184406,1739502663.275088,23.599977493286133,0.4142525522963405,1739502663.2750902,23.599977493286133,0.9726246705170164,1739502663.2750916,23.599977493286133,0.4447581342962402,1739502663.2750938,23.599977493286133,1.14819482933308,1739502663.2750957,23.599977493286133,0.0,1739502663.2750976,23.599977493286133,-0.17541903638109102,1739502663.2750993,23.599977493286133,0.17373407954622683,1739502663.2751014,23.599977493286133,1.323613865714171 +1739502663.2949448,23.619977474212646,47.41836759433695,1739502663.2949479,23.619977474212646,0.21114970938960376,1739502663.2949517,23.619977474212646,47.3172589008869,1739502663.2949555,23.619977474212646,51.2109649118825,1739502663.2949572,23.619977474212646,2.119060886868755,1739502663.2949595,23.619977474212646,0.46609412034641834,1739502663.2949615,23.619977474212646,1.148615208424179,1739502663.2949631,23.619977474212646,0.4851514315788401,1739502663.294965,23.619977474212646,0.9974019459342122,1739502663.294967,23.619977474212646,0.0,1739502663.2949688,23.619977474212646,-0.36854922192115647,1739502663.2949712,23.619977474212646,0.19212827218315282,1739502663.294973,23.619977474212646,1.3055979453034419 +1739502663.3150597,23.63997745513916,47.41836759433695,1739502663.3150635,23.63997745513916,0.21114970938960376,1739502663.315067,23.63997745513916,47.3172589008869,1739502663.3150709,23.63997745513916,51.2109649118825,1739502663.3150728,23.63997745513916,2.119060886868755,1739502663.3150752,23.63997745513916,0.46609412034641834,1739502663.315077,23.63997745513916,1.148615208424179,1739502663.3150792,23.63997745513916,0.4851514315788401,1739502663.3150806,23.63997745513916,0.9974019459342122,1739502663.315083,23.63997745513916,0.0,1739502663.3150845,23.63997745513916,-0.3081959993692297,1739502663.3150866,23.63997745513916,0.19212827218315282,1739502663.3150883,23.63997745513916,1.3055979453034419 +1739502663.335034,23.659977436065674,47.41836759433695,1739502663.3350377,23.659977436065674,0.21114970938960376,1739502663.3350415,23.659977436065674,47.3172589008869,1739502663.335045,23.659977436065674,51.2109649118825,1739502663.335047,23.659977436065674,2.119060886868755,1739502663.3350492,23.659977436065674,0.46609412034641834,1739502663.3350513,23.659977436065674,1.148615208424179,1739502663.335053,23.659977436065674,0.4851514315788401,1739502663.3350546,23.659977436065674,0.9974019459342122,1739502663.3350568,23.659977436065674,0.0,1739502663.3350587,23.659977436065674,-0.3081959993692297,1739502663.3350606,23.659977436065674,0.19212827218315282,1739502663.3350625,23.659977436065674,1.3055979453034419 +1739502663.3551178,23.679977416992188,47.41836759433695,1739502663.355121,23.679977416992188,0.21114970938960376,1739502663.3551247,23.679977416992188,47.3172589008869,1739502663.3551283,23.679977416992188,51.2109649118825,1739502663.3551302,23.679977416992188,2.119060886868755,1739502663.3551323,23.679977416992188,0.46609412034641834,1739502663.3551342,23.679977416992188,1.148615208424179,1739502663.355136,23.679977416992188,0.4851514315788401,1739502663.3551376,23.679977416992188,0.9974019459342122,1739502663.3551395,23.679977416992188,0.0,1739502663.3551414,23.679977416992188,-0.3081959993692297,1739502663.355143,23.679977416992188,0.19212827218315282,1739502663.3551452,23.679977416992188,1.3055979453034419 +1739502663.3750486,23.6999773979187,47.41836759433695,1739502663.375052,23.6999773979187,0.21114970938960376,1739502663.375056,23.6999773979187,47.3172589008869,1739502663.3750596,23.6999773979187,51.2109649118825,1739502663.3750615,23.6999773979187,2.119060886868755,1739502663.375064,23.6999773979187,0.46609412034641834,1739502663.3750656,23.6999773979187,1.148615208424179,1739502663.3750675,23.6999773979187,0.4851514315788401,1739502663.3750691,23.6999773979187,0.9974019459342122,1739502663.3750713,23.6999773979187,0.0,1739502663.375073,23.6999773979187,-0.3081959993692297,1739502663.375075,23.6999773979187,0.19212827218315282,1739502663.3750768,23.6999773979187,1.3055979453034419 +1739502663.3950627,23.719977378845215,47.55768861257462,1739502663.3950658,23.719977378845215,0.23948032396789998,1739502663.3950696,23.719977378845215,47.325426843843076,1739502663.395073,23.719977378845215,51.18373232147841,1739502663.3950748,23.719977378845215,2.0752807458774707,1739502663.3950772,23.719977378845215,0.4686605178430561,1739502663.395079,23.719977378845215,1.0351684233839915,1739502663.3950808,23.719977378845215,0.47722195915101673,1739502663.3950822,23.719977378845215,1.0921584780004758,1739502663.3950846,23.719977378845215,0.0,1739502663.395086,23.719977378845215,-0.12693031217748754,1739502663.3950882,23.719977378845215,0.21112387268005653,1739502663.3950899,23.719977378845215,1.275734354565109 +1739502663.4150298,23.73997735977173,47.55768861257462,1739502663.415033,23.73997735977173,0.23948032396789998,1739502663.4150376,23.73997735977173,47.325426843843076,1739502663.4150414,23.73997735977173,51.18373232147841,1739502663.4150434,23.73997735977173,2.0752807458774707,1739502663.4150457,23.73997735977173,0.4686605178430561,1739502663.4150476,23.73997735977173,1.0351684233839915,1739502663.4150496,23.73997735977173,0.47722195915101673,1739502663.4150512,23.73997735977173,1.0921584780004758,1739502663.4150536,23.73997735977173,0.0,1739502663.4150553,23.73997735977173,-0.18357587656463314,1739502663.4150572,23.73997735977173,0.21112387268005653,1739502663.415059,23.73997735977173,1.275734354565109 +1739502663.4351387,23.759977340698242,47.55768861257462,1739502663.4351425,23.759977340698242,0.23948032396789998,1739502663.4351463,23.759977340698242,47.325426843843076,1739502663.4351501,23.759977340698242,51.18373232147841,1739502663.435152,23.759977340698242,2.0752807458774707,1739502663.4351544,23.759977340698242,0.4686605178430561,1739502663.435156,23.759977340698242,1.0351684233839915,1739502663.4351578,23.759977340698242,0.47722195915101673,1739502663.4351594,23.759977340698242,1.0921584780004758,1739502663.4351618,23.759977340698242,0.0,1739502663.4351637,23.759977340698242,-0.18357587656463314,1739502663.4351656,23.759977340698242,0.21112387268005653,1739502663.4351678,23.759977340698242,1.275734354565109 +1739502663.4550052,23.779977321624756,47.55768861257462,1739502663.4550085,23.779977321624756,0.23948032396789998,1739502663.4550123,23.779977321624756,47.325426843843076,1739502663.455016,23.779977321624756,51.18373232147841,1739502663.4550178,23.779977321624756,2.0752807458774707,1739502663.4550197,23.779977321624756,0.4686605178430561,1739502663.4550219,23.779977321624756,1.0351684233839915,1739502663.4550235,23.779977321624756,0.47722195915101673,1739502663.4550252,23.779977321624756,1.0921584780004758,1739502663.455027,23.779977321624756,0.0,1739502663.455029,23.779977321624756,-0.18357587656463314,1739502663.4550312,23.779977321624756,0.21112387268005653,1739502663.4550328,23.779977321624756,1.275734354565109 +1739502663.4750721,23.79997730255127,47.55768861257462,1739502663.4750764,23.79997730255127,0.23948032396789998,1739502663.4750807,23.79997730255127,47.325426843843076,1739502663.475085,23.79997730255127,51.18373232147841,1739502663.4750872,23.79997730255127,2.0752807458774707,1739502663.4750896,23.79997730255127,0.4686605178430561,1739502663.4750922,23.79997730255127,1.0351684233839915,1739502663.4750946,23.79997730255127,0.47722195915101673,1739502663.4750965,23.79997730255127,1.0921584780004758,1739502663.4750986,23.79997730255127,0.0,1739502663.4751008,23.79997730255127,-0.18357587656463314,1739502663.475103,23.79997730255127,0.21112387268005653,1739502663.4751055,23.79997730255127,1.275734354565109 +1739502663.4948285,23.819977283477783,47.55768861257462,1739502663.4948316,23.819977283477783,0.23948032396789998,1739502663.4948354,23.819977283477783,47.325426843843076,1739502663.494839,23.819977283477783,51.18373232147841,1739502663.4948409,23.819977283477783,2.0752807458774707,1739502663.4948432,23.819977283477783,0.4686605178430561,1739502663.494845,23.819977283477783,1.0351684233839915,1739502663.4948468,23.819977283477783,0.47722195915101673,1739502663.4948483,23.819977283477783,1.0921584780004758,1739502663.4948504,23.819977283477783,0.0,1739502663.494852,23.819977283477783,-0.18357587656463314,1739502663.494854,23.819977283477783,0.21112387268005653,1739502663.4948556,23.819977283477783,1.275734354565109 +1739502663.5151598,23.839977264404297,47.6934121698956,1739502663.5151632,23.839977264404297,0.26985811887787925,1739502663.5151672,23.839977264404297,47.69496520498757,1739502663.515171,23.839977264404297,51.34150907232136,1739502663.515173,23.839977264404297,2.34692484565306,1739502663.515175,23.839977264404297,0.5175824987997248,1739502663.515177,23.839977264404297,1.1857778895240498,1739502663.5151787,23.839977264404297,0.5117385347023096,1739502663.5151806,23.839977264404297,0.9681854981490045,1739502663.5151825,23.839977264404297,0.0,1739502663.5151844,23.839977264404297,-0.3236817504625001,1739502663.5151865,23.839977264404297,0.23121901277838186,1739502663.5151885,23.839977264404297,1.2480841343119744 +1739502663.5350847,23.85997724533081,47.6934121698956,1739502663.535088,23.85997724533081,0.26985811887787925,1739502663.535092,23.85997724533081,47.69496520498757,1739502663.5350957,23.85997724533081,51.34150907232136,1739502663.5350978,23.85997724533081,2.34692484565306,1739502663.5351005,23.85997724533081,0.5175824987997248,1739502663.5351021,23.85997724533081,1.1857778895240498,1739502663.535104,23.85997724533081,0.5117385347023096,1739502663.5351055,23.85997724533081,0.9681854981490045,1739502663.5351079,23.85997724533081,0.0,1739502663.5351095,23.85997724533081,-0.27989863616296995,1739502663.5351114,23.85997724533081,0.23121901277838186,1739502663.5351133,23.85997724533081,1.2480841343119744 +1739502663.5551045,23.879977226257324,47.6934121698956,1739502663.5551076,23.879977226257324,0.26985811887787925,1739502663.5551114,23.879977226257324,47.69496520498757,1739502663.5551152,23.879977226257324,51.34150907232136,1739502663.555117,23.879977226257324,2.34692484565306,1739502663.555119,23.879977226257324,0.5175824987997248,1739502663.555121,23.879977226257324,1.1857778895240498,1739502663.5551229,23.879977226257324,0.5117385347023096,1739502663.5551248,23.879977226257324,0.9681854981490045,1739502663.5551267,23.879977226257324,0.0,1739502663.5551283,23.879977226257324,-0.27989863616296995,1739502663.5551305,23.879977226257324,0.23121901277838186,1739502663.5551324,23.879977226257324,1.2480841343119744 +1739502663.57515,23.899977207183838,47.6934121698956,1739502663.5751536,23.899977207183838,0.26985811887787925,1739502663.5751576,23.899977207183838,47.69496520498757,1739502663.5751615,23.899977207183838,51.34150907232136,1739502663.5751634,23.899977207183838,2.34692484565306,1739502663.5751657,23.899977207183838,0.5175824987997248,1739502663.5751674,23.899977207183838,1.1857778895240498,1739502663.5751693,23.899977207183838,0.5117385347023096,1739502663.575171,23.899977207183838,0.9681854981490045,1739502663.5751731,23.899977207183838,0.0,1739502663.5751748,23.899977207183838,-0.27989863616296995,1739502663.575177,23.899977207183838,0.23121901277838186,1739502663.5751789,23.899977207183838,1.2480841343119744 +1739502663.5942655,23.91997718811035,47.6934121698956,1739502663.5942674,23.91997718811035,0.26985811887787925,1739502663.5942702,23.91997718811035,47.69496520498757,1739502663.5942726,23.91997718811035,51.34150907232136,1739502663.594274,23.91997718811035,2.34692484565306,1739502663.5942755,23.91997718811035,0.5175824987997248,1739502663.5942771,23.91997718811035,1.1857778895240498,1739502663.5942783,23.91997718811035,0.5117385347023096,1739502663.5942795,23.91997718811035,0.9681854981490045,1739502663.594281,23.91997718811035,0.0,1739502663.594282,23.91997718811035,-0.27989863616296995,1739502663.5942833,23.91997718811035,0.23121901277838186,1739502663.5942845,23.91997718811035,1.2480841343119744 +1739502663.6146216,23.939977169036865,47.825266873290325,1739502663.6146245,23.939977169036865,0.3021921965171783,1739502663.6146278,23.939977169036865,47.88031752955088,1739502663.614631,23.939977169036865,51.39891792892731,1739502663.6146324,23.939977169036865,2.4572824940000784,1739502663.6146345,23.939977169036865,0.5426591357841861,1739502663.614636,23.939977169036865,1.1961736330598323,1739502663.6146376,23.939977169036865,0.5221619271405198,1739502663.614639,23.939977169036865,0.9601668816519424,1739502663.614641,23.939977169036865,0.0,1739502663.6146421,23.939977169036865,-0.2472509525649595,1739502663.614644,23.939977169036865,0.2519476846163402,1739502663.6146457,23.939977169036865,1.2176202420305 +1739502663.6356237,23.95997714996338,47.825266873290325,1739502663.635628,23.95997714996338,0.3021921965171783,1739502663.6356332,23.95997714996338,47.88031752955088,1739502663.635638,23.95997714996338,51.39891792892731,1739502663.6356409,23.95997714996338,2.4572824940000784,1739502663.6356437,23.95997714996338,0.5426591357841861,1739502663.6356468,23.95997714996338,1.1961736330598323,1739502663.6356492,23.95997714996338,0.5221619271405198,1739502663.6356516,23.95997714996338,0.9601668816519424,1739502663.6356542,23.95997714996338,0.0,1739502663.635656,23.95997714996338,-0.2574533603785576,1739502663.6356587,23.95997714996338,0.2519476846163402,1739502663.6356611,23.95997714996338,1.2176202420305 +1739502663.6558459,23.979977130889893,47.825266873290325,1739502663.6558495,23.979977130889893,0.3021921965171783,1739502663.655854,23.979977130889893,47.88031752955088,1739502663.6558585,23.979977130889893,51.39891792892731,1739502663.6558604,23.979977130889893,2.4572824940000784,1739502663.6558633,23.979977130889893,0.5426591357841861,1739502663.6558654,23.979977130889893,1.1961736330598323,1739502663.6558676,23.979977130889893,0.5221619271405198,1739502663.6558697,23.979977130889893,0.9601668816519424,1739502663.655872,23.979977130889893,0.0,1739502663.655874,23.979977130889893,-0.2574533603785576,1739502663.6558764,23.979977130889893,0.2519476846163402,1739502663.6558785,23.979977130889893,1.2176202420305 +1739502663.6759622,23.999977111816406,47.825266873290325,1739502663.6759667,23.999977111816406,0.3021921965171783,1739502663.6759717,23.999977111816406,47.88031752955088,1739502663.6759765,23.999977111816406,51.39891792892731,1739502663.675979,23.999977111816406,2.4572824940000784,1739502663.6759818,23.999977111816406,0.5426591357841861,1739502663.675984,23.999977111816406,1.1961736330598323,1739502663.675987,23.999977111816406,0.5221619271405198,1739502663.675989,23.999977111816406,0.9601668816519424,1739502663.6759915,23.999977111816406,0.0,1739502663.675994,23.999977111816406,-0.2574533603785576,1739502663.675996,23.999977111816406,0.2519476846163402,1739502663.6759984,23.999977111816406,1.2176202420305 +1739502663.696369,24.01997709274292,47.825266873290325,1739502663.6963725,24.01997709274292,0.3021921965171783,1739502663.6963768,24.01997709274292,47.88031752955088,1739502663.6963813,24.01997709274292,51.39891792892731,1739502663.6963835,24.01997709274292,2.4572824940000784,1739502663.696386,24.01997709274292,0.5426591357841861,1739502663.696388,24.01997709274292,1.1961736330598323,1739502663.6963902,24.01997709274292,0.5221619271405198,1739502663.6963923,24.01997709274292,0.9601668816519424,1739502663.6963944,24.01997709274292,0.0,1739502663.6963968,24.01997709274292,-0.2574533603785576,1739502663.6963987,24.01997709274292,0.2519476846163402,1739502663.6964011,24.01997709274292,1.2176202420305 +1739502663.71532,24.039977073669434,47.825266873290325,1739502663.7153237,24.039977073669434,0.3021921965171783,1739502663.7153282,24.039977073669434,47.88031752955088,1739502663.715332,24.039977073669434,51.39891792892731,1739502663.715334,24.039977073669434,2.4572824940000784,1739502663.715336,24.039977073669434,0.5426591357841861,1739502663.7153382,24.039977073669434,1.1961736330598323,1739502663.7153404,24.039977073669434,0.5221619271405198,1739502663.7153418,24.039977073669434,0.9601668816519424,1739502663.7153442,24.039977073669434,0.0,1739502663.7153456,24.039977073669434,-0.2574533603785576,1739502663.7153478,24.039977073669434,0.2519476846163402,1739502663.7153494,24.039977073669434,1.2176202420305 +1739502663.7351084,24.059977054595947,47.95317430929381,1739502663.735112,24.059977054595947,0.33647648215371184,1739502663.7351158,24.059977054595947,47.88288490797749,1739502663.7351196,24.059977054595947,51.37224964280906,1739502663.7351215,24.059977054595947,2.4059576308578183,1739502663.7351236,24.059977054595947,0.5442892217323383,1739502663.7351258,24.059977054595947,1.0666480596636716,1739502663.7351272,24.059977054595947,0.5079516679823235,1739502663.735129,24.059977054595947,1.0649973215090163,1739502663.735131,24.059977054595947,0.0,1739502663.735133,24.059977054595947,-0.06102274934571208,1739502663.7351346,24.059977054595947,0.27412601182778307,1739502663.7351365,24.059977054595947,1.1874046770493767 +1739502663.7552357,24.07997703552246,47.95317430929381,1739502663.7552388,24.07997703552246,0.33647648215371184,1739502663.7552426,24.07997703552246,47.88288490797749,1739502663.7552462,24.07997703552246,51.37224964280906,1739502663.7552478,24.07997703552246,2.4059576308578183,1739502663.7552502,24.07997703552246,0.5442892217323383,1739502663.755252,24.07997703552246,1.0666480596636716,1739502663.7552538,24.07997703552246,0.5079516679823235,1739502663.7552555,24.07997703552246,1.0649973215090163,1739502663.7552576,24.07997703552246,0.0,1739502663.7552593,24.07997703552246,-0.12240735554036042,1739502663.7552612,24.07997703552246,0.27412601182778307,1739502663.755263,24.07997703552246,1.1874046770493767 +1739502663.7750835,24.099977016448975,47.95317430929381,1739502663.7750869,24.099977016448975,0.33647648215371184,1739502663.7750907,24.099977016448975,47.88288490797749,1739502663.7750943,24.099977016448975,51.37224964280906,1739502663.7750962,24.099977016448975,2.4059576308578183,1739502663.7750983,24.099977016448975,0.5442892217323383,1739502663.7751005,24.099977016448975,1.0666480596636716,1739502663.7751021,24.099977016448975,0.5079516679823235,1739502663.7751038,24.099977016448975,1.0649973215090163,1739502663.775106,24.099977016448975,0.0,1739502663.775108,24.099977016448975,-0.12240735554036042,1739502663.7751102,24.099977016448975,0.27412601182778307,1739502663.775112,24.099977016448975,1.1874046770493767 +1739502663.7954862,24.11997699737549,47.95317430929381,1739502663.795489,24.11997699737549,0.33647648215371184,1739502663.7954931,24.11997699737549,47.88288490797749,1739502663.795497,24.11997699737549,51.37224964280906,1739502663.7954988,24.11997699737549,2.4059576308578183,1739502663.795501,24.11997699737549,0.5442892217323383,1739502663.795503,24.11997699737549,1.0666480596636716,1739502663.7955046,24.11997699737549,0.5079516679823235,1739502663.7955065,24.11997699737549,1.0649973215090163,1739502663.7955084,24.11997699737549,0.0,1739502663.79551,24.11997699737549,-0.12240735554036042,1739502663.7955117,24.11997699737549,0.27412601182778307,1739502663.7955136,24.11997699737549,1.1874046770493767 +1739502663.8149703,24.139976978302002,47.95317430929381,1739502663.8149734,24.139976978302002,0.33647648215371184,1739502663.8149772,24.139976978302002,47.88288490797749,1739502663.8149807,24.139976978302002,51.37224964280906,1739502663.8149827,24.139976978302002,2.4059576308578183,1739502663.814985,24.139976978302002,0.5442892217323383,1739502663.8149867,24.139976978302002,1.0666480596636716,1739502663.8149886,24.139976978302002,0.5079516679823235,1739502663.8149903,24.139976978302002,1.0649973215090163,1739502663.8149924,24.139976978302002,0.0,1739502663.814994,24.139976978302002,-0.12240735554036042,1739502663.814996,24.139976978302002,0.27412601182778307,1739502663.8149977,24.139976978302002,1.1874046770493767 +1739502663.8351114,24.159976959228516,48.07785180542216,1739502663.8351145,24.159976959228516,0.37291619269550846,1739502663.8351185,24.159976959228516,47.8853995392461,1739502663.8351223,24.159976959228516,51.36097511763568,1739502663.8351243,24.159976959228516,2.3837843980168345,1739502663.8351266,24.159976959228516,0.5495500853773714,1739502663.8351283,24.159976959228516,0.963255121714345,1739502663.8351302,24.159976959228516,0.4945634054653278,1739502663.835132,24.159976959228516,1.1568336195030333,1739502663.835134,24.159976959228516,0.0,1739502663.8351357,24.159976959228516,0.031092514469664385,1739502663.8351376,24.159976959228516,0.29666716659062037,1739502663.8351395,24.159976959228516,1.173709845862259 +1739502663.8551116,24.17997694015503,48.07785180542216,1739502663.8551147,24.17997694015503,0.37291619269550846,1739502663.8551183,24.17997694015503,47.8853995392461,1739502663.855122,24.17997694015503,51.36097511763568,1739502663.855124,24.17997694015503,2.3837843980168345,1739502663.8551264,24.17997694015503,0.5495500853773714,1739502663.855128,24.17997694015503,0.963255121714345,1739502663.85513,24.17997694015503,0.4945634054653278,1739502663.8551314,24.17997694015503,1.1568336195030333,1739502663.8551338,24.17997694015503,0.0,1739502663.8551352,24.17997694015503,-0.0168762263592257,1739502663.8551373,24.17997694015503,0.29666716659062037,1739502663.855139,24.17997694015503,1.173709845862259 +1739502663.875011,24.199976921081543,48.07785180542216,1739502663.875014,24.199976921081543,0.37291619269550846,1739502663.8750184,24.199976921081543,47.8853995392461,1739502663.8750224,24.199976921081543,51.36097511763568,1739502663.875024,24.199976921081543,2.3837843980168345,1739502663.8750267,24.199976921081543,0.5495500853773714,1739502663.8750284,24.199976921081543,0.963255121714345,1739502663.8750303,24.199976921081543,0.4945634054653278,1739502663.875032,24.199976921081543,1.1568336195030333,1739502663.8750346,24.199976921081543,0.0,1739502663.8750365,24.199976921081543,-0.0168762263592257,1739502663.8750381,24.199976921081543,0.29666716659062037,1739502663.87504,24.199976921081543,1.173709845862259 +1739502663.895628,24.219976902008057,48.07785180542216,1739502663.8956313,24.219976902008057,0.37291619269550846,1739502663.8956363,24.219976902008057,47.8853995392461,1739502663.8956406,24.219976902008057,51.36097511763568,1739502663.8956425,24.219976902008057,2.3837843980168345,1739502663.895645,24.219976902008057,0.5495500853773714,1739502663.895647,24.219976902008057,0.963255121714345,1739502663.895649,24.219976902008057,0.4945634054653278,1739502663.8956509,24.219976902008057,1.1568336195030333,1739502663.8956535,24.219976902008057,0.0,1739502663.8956552,24.219976902008057,-0.0168762263592257,1739502663.8956573,24.219976902008057,0.29666716659062037,1739502663.8956592,24.219976902008057,1.173709845862259 +1739502663.9170456,24.23997688293457,48.07785180542216,1739502663.9170501,24.23997688293457,0.37291619269550846,1739502663.917056,24.23997688293457,47.8853995392461,1739502663.9170618,24.23997688293457,51.36097511763568,1739502663.9170647,24.23997688293457,2.3837843980168345,1739502663.917068,24.23997688293457,0.5495500853773714,1739502663.9170709,24.23997688293457,0.963255121714345,1739502663.9170735,24.23997688293457,0.4945634054653278,1739502663.917076,24.23997688293457,1.1568336195030333,1739502663.9170792,24.23997688293457,0.0,1739502663.917082,24.23997688293457,-0.0168762263592257,1739502663.917085,24.23997688293457,0.29666716659062037,1739502663.9170878,24.23997688293457,1.173709845862259 +1739502663.9373379,24.259976863861084,48.07785180542216,1739502663.9373426,24.259976863861084,0.37291619269550846,1739502663.9373488,24.259976863861084,47.8853995392461,1739502663.9373548,24.259976863861084,51.36097511763568,1739502663.9373577,24.259976863861084,2.3837843980168345,1739502663.937361,24.259976863861084,0.5495500853773714,1739502663.9373636,24.259976863861084,0.963255121714345,1739502663.9373665,24.259976863861084,0.4945634054653278,1739502663.937369,24.259976863861084,1.1568336195030333,1739502663.9373727,24.259976863861084,0.0,1739502663.9373755,24.259976863861084,-0.0168762263592257,1739502663.9373784,24.259976863861084,0.29666716659062037,1739502663.937381,24.259976863861084,1.173709845862259 +1739502663.956653,24.279976844787598,48.20092257108941,1739502663.9566576,24.279976844787598,0.4119204185088634,1739502663.9566643,24.279976844787598,47.88789390069703,1739502663.95667,24.279976844787598,51.36129266200581,1739502663.956697,24.279976844787598,2.3844089019447603,1739502663.956708,24.279976844787598,0.5579749780965672,1739502663.9567144,24.279976844787598,0.8810751095213984,1739502663.9567227,24.279976844787598,0.48333292601534944,1739502663.9567292,24.279976844787598,1.235444277501496,1739502663.956736,24.279976844787598,0.0,1739502663.9567423,24.279976844787598,0.09877113756267496,1739502663.9567492,24.279976844787598,0.31920832135345767,1739502663.9567566,24.279976844787598,1.1728129648595307 +1739502663.9758399,24.29997682571411,48.20092257108941,1739502663.9758441,24.29997682571411,0.4119204185088634,1739502663.9758494,24.29997682571411,47.88789390069703,1739502663.9758542,24.29997682571411,51.36129266200581,1739502663.9758563,24.29997682571411,2.3844089019447603,1739502663.9758599,24.29997682571411,0.5579749780965672,1739502663.9758625,24.29997682571411,0.8810751095213984,1739502663.975865,24.29997682571411,0.48333292601534944,1739502663.975867,24.29997682571411,1.235444277501496,1739502663.9758697,24.29997682571411,0.0,1739502663.9758723,24.29997682571411,0.06263131264196531,1739502663.9758747,24.29997682571411,0.31920832135345767,1739502663.9758768,24.29997682571411,1.1728129648595307 +1739502663.995405,24.319976806640625,48.20092257108941,1739502663.995409,24.319976806640625,0.4119204185088634,1739502663.9954138,24.319976806640625,47.88789390069703,1739502663.9954176,24.319976806640625,51.36129266200581,1739502663.9954195,24.319976806640625,2.3844089019447603,1739502663.995422,24.319976806640625,0.5579749780965672,1739502663.995424,24.319976806640625,0.8810751095213984,1739502663.9954264,24.319976806640625,0.48333292601534944,1739502663.9954278,24.319976806640625,1.235444277501496,1739502663.9954302,24.319976806640625,0.0,1739502663.9954321,24.319976806640625,0.06263131264196531,1739502663.9954343,24.319976806640625,0.31920832135345767,1739502663.995436,24.319976806640625,1.1728129648595307 +1739502664.0145047,24.33997678756714,48.20092257108941,1739502664.0145068,24.33997678756714,0.4119204185088634,1739502664.0145102,24.33997678756714,47.88789390069703,1739502664.0145128,24.33997678756714,51.36129266200581,1739502664.0145144,24.33997678756714,2.3844089019447603,1739502664.0145166,24.33997678756714,0.5579749780965672,1739502664.0145178,24.33997678756714,0.8810751095213984,1739502664.0145192,24.33997678756714,0.48333292601534944,1739502664.0145206,24.33997678756714,1.235444277501496,1739502664.0145223,24.33997678756714,0.0,1739502664.0145237,24.33997678756714,0.06263131264196531,1739502664.0145254,24.33997678756714,0.31920832135345767,1739502664.014527,24.33997678756714,1.1728129648595307 +1739502664.0344872,24.359976768493652,48.20092257108941,1739502664.0344896,24.359976768493652,0.4119204185088634,1739502664.0344927,24.359976768493652,47.88789390069703,1739502664.0344956,24.359976768493652,51.36129266200581,1739502664.0344968,24.359976768493652,2.3844089019447603,1739502664.0344985,24.359976768493652,0.5579749780965672,1739502664.0345001,24.359976768493652,0.8810751095213984,1739502664.0345016,24.359976768493652,0.48333292601534944,1739502664.034503,24.359976768493652,1.235444277501496,1739502664.0345044,24.359976768493652,0.0,1739502664.034506,24.359976768493652,0.06263131264196531,1739502664.0345075,24.359976768493652,0.31920832135345767,1739502664.0345087,24.359976768493652,1.1728129648595307 +1739502664.0550213,24.379976749420166,48.3232989772473,1739502664.0550246,24.379976749420166,0.4537643448223836,1739502664.0550287,24.379976749420166,47.890386428119285,1739502664.0550318,24.379976749420166,51.36858099676866,1739502664.0550337,24.379976749420166,2.398742626978359,1739502664.0550354,24.379976749420166,0.5683802900220298,1739502664.0550373,24.379976749420166,0.8119164362578698,1739502664.055039,24.379976749420166,0.47359898757400654,1739502664.0550408,24.379976749420166,1.3057238781235236,1739502664.0550425,24.379976749420166,0.0,1739502664.0550442,24.379976749420166,0.15497420983744292,1739502664.0550456,24.379976749420166,0.34174947611629497,1739502664.0550473,24.379976749420166,1.1796068425799053 +1739502664.0744526,24.39997673034668,48.3232989772473,1739502664.0744557,24.39997673034668,0.4537643448223836,1739502664.0744588,24.39997673034668,47.890386428119285,1739502664.074462,24.39997673034668,51.36858099676866,1739502664.0744636,24.39997673034668,2.398742626978359,1739502664.0744653,24.39997673034668,0.5683802900220298,1739502664.0744667,24.39997673034668,0.8119164362578698,1739502664.0744684,24.39997673034668,0.47359898757400654,1739502664.0744698,24.39997673034668,1.3057238781235236,1739502664.0744717,24.39997673034668,0.0,1739502664.074473,24.39997673034668,0.1261170355436183,1739502664.0744748,24.39997673034668,0.34174947611629497,1739502664.0744765,24.39997673034668,1.1796068425799053 +1739502664.0945575,24.419976711273193,48.3232989772473,1739502664.0945606,24.419976711273193,0.4537643448223836,1739502664.094565,24.419976711273193,47.890386428119285,1739502664.094568,24.419976711273193,51.36858099676866,1739502664.0945697,24.419976711273193,2.398742626978359,1739502664.0945716,24.419976711273193,0.5683802900220298,1739502664.094573,24.419976711273193,0.8119164362578698,1739502664.0945747,24.419976711273193,0.47359898757400654,1739502664.0945761,24.419976711273193,1.3057238781235236,1739502664.094578,24.419976711273193,0.0,1739502664.0945795,24.419976711273193,0.1261170355436183,1739502664.094581,24.419976711273193,0.34174947611629497,1739502664.0945828,24.419976711273193,1.1796068425799053 +1739502664.1145866,24.439976692199707,48.3232989772473,1739502664.1145897,24.439976692199707,0.4537643448223836,1739502664.1145928,24.439976692199707,47.890386428119285,1739502664.114596,24.439976692199707,51.36858099676866,1739502664.1145973,24.439976692199707,2.398742626978359,1739502664.1145992,24.439976692199707,0.5683802900220298,1739502664.1146007,24.439976692199707,0.8119164362578698,1739502664.1146023,24.439976692199707,0.47359898757400654,1739502664.114604,24.439976692199707,1.3057238781235236,1739502664.114606,24.439976692199707,0.0,1739502664.114607,24.439976692199707,0.1261170355436183,1739502664.1146085,24.439976692199707,0.34174947611629497,1739502664.1146102,24.439976692199707,1.1796068425799053 +1739502664.1347709,24.45997667312622,48.3232989772473,1739502664.1347744,24.45997667312622,0.4537643448223836,1739502664.1347783,24.45997667312622,47.890386428119285,1739502664.1347818,24.45997667312622,51.36858099676866,1739502664.1347837,24.45997667312622,2.398742626978359,1739502664.1347861,24.45997667312622,0.5683802900220298,1739502664.1347878,24.45997667312622,0.8119164362578698,1739502664.1347895,24.45997667312622,0.47359898757400654,1739502664.1347911,24.45997667312622,1.3057238781235236,1739502664.1347933,24.45997667312622,0.0,1739502664.134795,24.45997667312622,0.1261170355436183,1739502664.1347969,24.45997667312622,0.34174947611629497,1739502664.1347988,24.45997667312622,1.1796068425799053 +1739502664.1591508,24.479976654052734,48.3232989772473,1739502664.1591568,24.479976654052734,0.4537643448223836,1739502664.1591644,24.479976654052734,47.890386428119285,1739502664.1591735,24.479976654052734,51.36858099676866,1739502664.1591783,24.479976654052734,2.398742626978359,1739502664.1591847,24.479976654052734,0.5683802900220298,1739502664.1591902,24.479976654052734,0.8119164362578698,1739502664.159196,24.479976654052734,0.47359898757400654,1739502664.1592019,24.479976654052734,1.3057238781235236,1739502664.1592073,24.479976654052734,0.0,1739502664.159213,24.479976654052734,0.1261170355436183,1739502664.159219,24.479976654052734,0.34174947611629497,1739502664.1592247,24.479976654052734,1.1796068425799053 +1739502664.1779037,24.499976634979248,48.44579730899187,1739502664.1779077,24.499976634979248,0.4987600450601759,1739502664.1779134,24.499976634979248,48.55867616354688,1739502664.1779196,24.499976634979248,51.633217345677686,1739502664.1779234,24.499976634979248,3.0424594708949324,1739502664.177928,24.499976634979248,0.6735467355488397,1739502664.177932,24.499976634979248,1.241138624318388,1739502664.177936,24.499976634979248,0.5663504238480399,1739502664.1779401,24.499976634979248,0.9262416033884863,1739502664.1779444,24.499976634979248,0.0,1739502664.1779485,24.499976634979248,-0.4467955230060776,1739502664.1779528,24.499976634979248,0.36429063087913227,1739502664.177957,24.499976634979248,1.1940018344630992 +1739502664.1965106,24.51997661590576,48.44579730899187,1739502664.1965137,24.51997661590576,0.4987600450601759,1739502664.1965177,24.51997661590576,48.55867616354688,1739502664.1965222,24.51997661590576,51.633217345677686,1739502664.1965249,24.51997661590576,3.0424594708949324,1739502664.1965284,24.51997661590576,0.6735467355488397,1739502664.1965315,24.51997661590576,1.241138624318388,1739502664.1965346,24.51997661590576,0.5663504238480399,1739502664.1965375,24.51997661590576,0.9262416033884863,1739502664.1965406,24.51997661590576,0.0,1739502664.1965437,24.51997661590576,-0.2677602310746129,1739502664.1965468,24.51997661590576,0.36429063087913227,1739502664.1965501,24.51997661590576,1.1940018344630992 +1739502664.2162185,24.539976596832275,48.44579730899187,1739502664.2162213,24.539976596832275,0.4987600450601759,1739502664.2162256,24.539976596832275,48.55867616354688,1739502664.2162304,24.539976596832275,51.633217345677686,1739502664.216233,24.539976596832275,3.0424594708949324,1739502664.2162364,24.539976596832275,0.6735467355488397,1739502664.2162395,24.539976596832275,1.241138624318388,1739502664.2162423,24.539976596832275,0.5663504238480399,1739502664.2162454,24.539976596832275,0.9262416033884863,1739502664.2162485,24.539976596832275,0.0,1739502664.2162516,24.539976596832275,-0.2677602310746129,1739502664.2162547,24.539976596832275,0.36429063087913227,1739502664.2162578,24.539976596832275,1.1940018344630992 +1739502664.2366223,24.55997657775879,48.44579730899187,1739502664.2366257,24.55997657775879,0.4987600450601759,1739502664.23663,24.55997657775879,48.55867616354688,1739502664.2366352,24.55997657775879,51.633217345677686,1739502664.2366376,24.55997657775879,3.0424594708949324,1739502664.2366416,24.55997657775879,0.6735467355488397,1739502664.2366447,24.55997657775879,1.241138624318388,1739502664.2366478,24.55997657775879,0.5663504238480399,1739502664.2366512,24.55997657775879,0.9262416033884863,1739502664.2366545,24.55997657775879,0.0,1739502664.2366579,24.55997657775879,-0.2677602310746129,1739502664.2366612,24.55997657775879,0.36429063087913227,1739502664.2366645,24.55997657775879,1.1940018344630992 +1739502664.2573059,24.579976558685303,48.44579730899187,1739502664.2573092,24.579976558685303,0.4987600450601759,1739502664.2573135,24.579976558685303,48.55867616354688,1739502664.2573185,24.579976558685303,51.633217345677686,1739502664.2573211,24.579976558685303,3.0424594708949324,1739502664.2573247,24.579976558685303,0.6735467355488397,1739502664.257328,24.579976558685303,1.241138624318388,1739502664.2573311,24.579976558685303,0.5663504238480399,1739502664.2573345,24.579976558685303,0.9262416033884863,1739502664.2573378,24.579976558685303,0.0,1739502664.257341,24.579976558685303,-0.2677602310746129,1739502664.2573442,24.579976558685303,0.36429063087913227,1739502664.2573476,24.579976558685303,1.1940018344630992 +1739502664.2745605,24.599976539611816,48.566723563991665,1739502664.274563,24.599976539611816,0.546308734635975,1739502664.2745662,24.599976539611816,48.657183595905714,1739502664.274569,24.599976539611816,51.64428009636474,1739502664.2745702,24.599976539611816,3.0803889018219714,1739502664.2745721,24.599976539611816,0.6888511657268808,1739502664.2745733,24.599976539611816,1.1834674553019429,1739502664.2745745,24.599976539611816,0.5651116005608319,1739502664.274576,24.599976539611816,0.9699766961437273,1739502664.2745774,24.599976539611816,0.0,1739502664.274579,24.599976539611816,-0.16123816733800725,1739502664.2745805,24.599976539611816,0.38744640035374084,1739502664.2745817,24.599976539611816,1.1645030302248467 +1739502664.2944322,24.61997652053833,48.566723563991665,1739502664.294435,24.61997652053833,0.546308734635975,1739502664.2944381,24.61997652053833,48.657183595905714,1739502664.2944407,24.61997652053833,51.64428009636474,1739502664.294443,24.61997652053833,3.0803889018219714,1739502664.2944448,24.61997652053833,0.6888511657268808,1739502664.294446,24.61997652053833,1.1834674553019429,1739502664.294448,24.61997652053833,0.5651116005608319,1739502664.2944489,24.61997652053833,0.9699766961437273,1739502664.2944508,24.61997652053833,0.0,1739502664.2944517,24.61997652053833,-0.1945263340811194,1739502664.2944531,24.61997652053833,0.38744640035374084,1739502664.294455,24.61997652053833,1.1645030302248467 +1739502664.3142893,24.639976501464844,48.566723563991665,1739502664.3142917,24.639976501464844,0.546308734635975,1739502664.3142946,24.639976501464844,48.657183595905714,1739502664.3142972,24.639976501464844,51.64428009636474,1739502664.3142986,24.639976501464844,3.0803889018219714,1739502664.3143,24.639976501464844,0.6888511657268808,1739502664.3143015,24.639976501464844,1.1834674553019429,1739502664.3143027,24.639976501464844,0.5651116005608319,1739502664.314304,24.639976501464844,0.9699766961437273,1739502664.3143055,24.639976501464844,0.0,1739502664.3143065,24.639976501464844,-0.1945263340811194,1739502664.3143082,24.639976501464844,0.38744640035374084,1739502664.3143094,24.639976501464844,1.1645030302248467 +1739502664.3343737,24.659976482391357,48.566723563991665,1739502664.3343759,24.659976482391357,0.546308734635975,1739502664.3343787,24.659976482391357,48.657183595905714,1739502664.3343813,24.659976482391357,51.64428009636474,1739502664.3343825,24.659976482391357,3.0803889018219714,1739502664.3343842,24.659976482391357,0.6888511657268808,1739502664.3343856,24.659976482391357,1.1834674553019429,1739502664.3343868,24.659976482391357,0.5651116005608319,1739502664.334388,24.659976482391357,0.9699766961437273,1739502664.3343894,24.659976482391357,0.0,1739502664.3343909,24.659976482391357,-0.1945263340811194,1739502664.334392,24.659976482391357,0.38744640035374084,1739502664.3343933,24.659976482391357,1.1645030302248467 +1739502664.3543823,24.67997646331787,48.566723563991665,1739502664.3543854,24.67997646331787,0.546308734635975,1739502664.3543882,24.67997646331787,48.657183595905714,1739502664.354391,24.67997646331787,51.64428009636474,1739502664.3543923,24.67997646331787,3.0803889018219714,1739502664.3543942,24.67997646331787,0.6888511657268808,1739502664.3543956,24.67997646331787,1.1834674553019429,1739502664.3543973,24.67997646331787,0.5651116005608319,1739502664.3543985,24.67997646331787,0.9699766961437273,1739502664.3544004,24.67997646331787,0.0,1739502664.3544016,24.67997646331787,-0.1945263340811194,1739502664.354403,24.67997646331787,0.38744640035374084,1739502664.3544047,24.67997646331787,1.1645030302248467 +1739502664.374576,24.699976444244385,48.566723563991665,1739502664.374579,24.699976444244385,0.546308734635975,1739502664.3745825,24.699976444244385,48.657183595905714,1739502664.3745856,24.699976444244385,51.64428009636474,1739502664.3745875,24.699976444244385,3.0803889018219714,1739502664.3745894,24.699976444244385,0.6888511657268808,1739502664.3745914,24.699976444244385,1.1834674553019429,1739502664.3745928,24.699976444244385,0.5651116005608319,1739502664.3745942,24.699976444244385,0.9699766961437273,1739502664.374596,24.699976444244385,0.0,1739502664.3745975,24.699976444244385,-0.1945263340811194,1739502664.3745995,24.699976444244385,0.38744640035374084,1739502664.374601,24.699976444244385,1.1645030302248467 +1739502664.3955963,24.7199764251709,48.683595931475715,1739502664.3956,24.7199764251709,0.5955187081804221,1739502664.395605,24.7199764251709,48.755716481012385,1739502664.3956094,24.7199764251709,51.65609540563555,1739502664.3956113,24.7199764251709,3.1220958454288774,1739502664.3956141,24.7199764251709,0.7044848035091011,1739502664.3956165,24.7199764251709,1.1243571893332187,1739502664.3956187,24.7199764251709,0.5607510859519873,1739502664.3956206,24.7199764251709,1.0169469784001532,1739502664.3956234,24.7199764251709,0.0,1739502664.3956254,24.7199764251709,-0.08607245059535884,1739502664.3956277,24.7199764251709,0.41212970365060864,1739502664.3956301,24.7199764251709,1.1369112898060478 +1739502664.4162767,24.739976406097412,48.683595931475715,1739502664.4162803,24.739976406097412,0.5955187081804221,1739502664.416285,24.739976406097412,48.755716481012385,1739502664.4162896,24.739976406097412,51.65609540563555,1739502664.416292,24.739976406097412,3.1220958454288774,1739502664.4162946,24.739976406097412,0.7044848035091011,1739502664.416297,24.739976406097412,1.1243571893332187,1739502664.4162993,24.739976406097412,0.5607510859519873,1739502664.4163013,24.739976406097412,1.0169469784001532,1739502664.4163036,24.739976406097412,0.0,1739502664.416306,24.739976406097412,-0.11996431140589459,1739502664.4163082,24.739976406097412,0.41212970365060864,1739502664.4163105,24.739976406097412,1.1369112898060478 +1739502664.4361613,24.759976387023926,48.683595931475715,1739502664.436165,24.759976387023926,0.5955187081804221,1739502664.43617,24.759976387023926,48.755716481012385,1739502664.4361746,24.759976387023926,51.65609540563555,1739502664.4361765,24.759976387023926,3.1220958454288774,1739502664.4361792,24.759976387023926,0.7044848035091011,1739502664.4361815,24.759976387023926,1.1243571893332187,1739502664.4361837,24.759976387023926,0.5607510859519873,1739502664.4361858,24.759976387023926,1.0169469784001532,1739502664.4361882,24.759976387023926,0.0,1739502664.4361904,24.759976387023926,-0.11996431140589459,1739502664.4361928,24.759976387023926,0.41212970365060864,1739502664.4361951,24.759976387023926,1.1369112898060478 +1739502664.4558392,24.77997636795044,48.683595931475715,1739502664.4558427,24.77997636795044,0.5955187081804221,1739502664.4558477,24.77997636795044,48.755716481012385,1739502664.455852,24.77997636795044,51.65609540563555,1739502664.4558544,24.77997636795044,3.1220958454288774,1739502664.455857,24.77997636795044,0.7044848035091011,1739502664.4558594,24.77997636795044,1.1243571893332187,1739502664.4558618,24.77997636795044,0.5607510859519873,1739502664.4558637,24.77997636795044,1.0169469784001532,1739502664.455866,24.77997636795044,0.0,1739502664.4558685,24.77997636795044,-0.11996431140589459,1739502664.4558706,24.77997636795044,0.41212970365060864,1739502664.455873,24.77997636795044,1.1369112898060478 +1739502664.4754665,24.799976348876953,48.683595931475715,1739502664.4754698,24.799976348876953,0.5955187081804221,1739502664.4754739,24.799976348876953,48.755716481012385,1739502664.4754777,24.799976348876953,51.65609540563555,1739502664.4754796,24.799976348876953,3.1220958454288774,1739502664.4754817,24.799976348876953,0.7044848035091011,1739502664.4754837,24.799976348876953,1.1243571893332187,1739502664.4754858,24.799976348876953,0.5607510859519873,1739502664.4754872,24.799976348876953,1.0169469784001532,1739502664.4754894,24.799976348876953,0.0,1739502664.4754913,24.799976348876953,-0.11996431140589459,1739502664.4754932,24.799976348876953,0.41212970365060864,1739502664.475495,24.799976348876953,1.1369112898060478 +1739502664.4952419,24.819976329803467,48.79692305836316,1739502664.4952447,24.819976329803467,0.6465985020879206,1739502664.495248,24.819976329803467,48.875778852142396,1739502664.4952512,24.819976329803467,51.68044343684398,1739502664.4952528,24.819976329803467,3.2109592684279256,1739502664.4952548,24.819976329803467,0.726880874946547,1739502664.4952564,24.819976329803467,1.1026004156299587,1739502664.4952579,24.819976329803467,0.5620094181472438,1739502664.4952593,24.819976329803467,1.0348023055788271,1739502664.4952614,24.819976329803467,0.0,1739502664.4952629,24.819976329803467,-0.0736848351770936,1739502664.4952648,24.819976329803467,0.43710887044253477,1739502664.4952662,24.819976329803467,1.1229494865596739 +1739502664.5147557,24.83997631072998,48.79692305836316,1739502664.514759,24.83997631072998,0.6465985020879206,1739502664.5147626,24.83997631072998,48.875778852142396,1739502664.5147665,24.83997631072998,51.68044343684398,1739502664.514768,24.83997631072998,3.2109592684279256,1739502664.5147703,24.83997631072998,0.726880874946547,1739502664.5147717,24.83997631072998,1.1026004156299587,1739502664.5147731,24.83997631072998,0.5620094181472438,1739502664.5147748,24.83997631072998,1.0348023055788271,1739502664.5147765,24.83997631072998,0.0,1739502664.5147784,24.83997631072998,-0.08814718098084673,1739502664.5147798,24.83997631072998,0.43710887044253477,1739502664.5147817,24.83997631072998,1.1229494865596739 +1739502664.5347238,24.859976291656494,48.79692305836316,1739502664.5347269,24.859976291656494,0.6465985020879206,1739502664.534731,24.859976291656494,48.875778852142396,1739502664.5347342,24.859976291656494,51.68044343684398,1739502664.534736,24.859976291656494,3.2109592684279256,1739502664.5347385,24.859976291656494,0.726880874946547,1739502664.53474,24.859976291656494,1.1026004156299587,1739502664.5347419,24.859976291656494,0.5620094181472438,1739502664.5347433,24.859976291656494,1.0348023055788271,1739502664.534745,24.859976291656494,0.0,1739502664.5347466,24.859976291656494,-0.08814718098084673,1739502664.5347483,24.859976291656494,0.43710887044253477,1739502664.5347502,24.859976291656494,1.1229494865596739 +1739502664.5550058,24.879976272583008,48.79692305836316,1739502664.5550084,24.879976272583008,0.6465985020879206,1739502664.555012,24.879976272583008,48.875778852142396,1739502664.5550156,24.879976272583008,51.68044343684398,1739502664.5550172,24.879976272583008,3.2109592684279256,1739502664.5550194,24.879976272583008,0.726880874946547,1739502664.5550208,24.879976272583008,1.1026004156299587,1739502664.5550225,24.879976272583008,0.5620094181472438,1739502664.5550241,24.879976272583008,1.0348023055788271,1739502664.5550258,24.879976272583008,0.0,1739502664.5550275,24.879976272583008,-0.08814718098084673,1739502664.5550292,24.879976272583008,0.43710887044253477,1739502664.555031,24.879976272583008,1.1229494865596739 +1739502664.5749385,24.89997625350952,48.79692305836316,1739502664.5749419,24.89997625350952,0.6465985020879206,1739502664.5749454,24.89997625350952,48.875778852142396,1739502664.5749497,24.89997625350952,51.68044343684398,1739502664.5749512,24.89997625350952,3.2109592684279256,1739502664.5749533,24.89997625350952,0.726880874946547,1739502664.5749552,24.89997625350952,1.1026004156299587,1739502664.5749571,24.89997625350952,0.5620094181472438,1739502664.5749586,24.89997625350952,1.0348023055788271,1739502664.5749605,24.89997625350952,0.0,1739502664.5749621,24.89997625350952,-0.08814718098084673,1739502664.574964,24.89997625350952,0.43710887044253477,1739502664.5749655,24.89997625350952,1.1229494865596739 +1739502664.5949109,24.919976234436035,48.79692305836316,1739502664.5949137,24.919976234436035,0.6465985020879206,1739502664.5949173,24.919976234436035,48.875778852142396,1739502664.5949209,24.919976234436035,51.68044343684398,1739502664.5949225,24.919976234436035,3.2109592684279256,1739502664.5949242,24.919976234436035,0.726880874946547,1739502664.594926,24.919976234436035,1.1026004156299587,1739502664.5949275,24.919976234436035,0.5620094181472438,1739502664.5949292,24.919976234436035,1.0348023055788271,1739502664.594931,24.919976234436035,0.0,1739502664.5949326,24.919976234436035,-0.08814718098084673,1739502664.594934,24.919976234436035,0.43710887044253477,1739502664.594936,24.919976234436035,1.1229494865596739 +1739502664.6148605,24.93997621536255,48.907819569870256,1739502664.614864,24.93997621536255,0.6999551789829823,1739502664.6148677,24.93997621536255,49.01794893409945,1739502664.614871,24.93997621536255,51.70941343662869,1739502664.6148727,24.93997621536255,3.330906287368168,1739502664.6148746,24.93997621536255,0.7539972877438939,1739502664.6148765,24.93997621536255,1.106024999280327,1739502664.614878,24.93997621536255,0.568178301156633,1739502664.6148794,24.93997621536255,1.0319711718856721,1739502664.6148813,24.93997621536255,0.0,1739502664.6148827,24.93997621536255,-0.07863042366268114,1739502664.6148849,24.93997621536255,0.4620880372344609,1739502664.6148868,24.93997621536255,1.1135755841601789 +1739502664.6346693,24.959976196289062,48.907819569870256,1739502664.6346726,24.959976196289062,0.6999551789829823,1739502664.6346762,24.959976196289062,49.01794893409945,1739502664.6346798,24.959976196289062,51.70941343662869,1739502664.6346817,24.959976196289062,3.330906287368168,1739502664.6346834,24.959976196289062,0.7539972877438939,1739502664.6346853,24.959976196289062,1.106024999280327,1739502664.6346867,24.959976196289062,0.568178301156633,1739502664.6346881,24.959976196289062,1.0319711718856721,1739502664.63469,24.959976196289062,0.0,1739502664.6346915,24.959976196289062,-0.08160441227450677,1739502664.6346934,24.959976196289062,0.4620880372344609,1739502664.6346948,24.959976196289062,1.1135755841601789 +1739502664.6550086,24.979976177215576,48.907819569870256,1739502664.6550114,24.979976177215576,0.6999551789829823,1739502664.655015,24.979976177215576,49.01794893409945,1739502664.6550183,24.979976177215576,51.70941343662869,1739502664.6550198,24.979976177215576,3.330906287368168,1739502664.655022,24.979976177215576,0.7539972877438939,1739502664.6550236,24.979976177215576,1.106024999280327,1739502664.6550252,24.979976177215576,0.568178301156633,1739502664.6550267,24.979976177215576,1.0319711718856721,1739502664.6550286,24.979976177215576,0.0,1739502664.65503,24.979976177215576,-0.08160441227450677,1739502664.6550314,24.979976177215576,0.4620880372344609,1739502664.6550333,24.979976177215576,1.1135755841601789 +1739502664.6747694,24.99997615814209,48.907819569870256,1739502664.6747725,24.99997615814209,0.6999551789829823,1739502664.674776,24.99997615814209,49.01794893409945,1739502664.6747794,24.99997615814209,51.70941343662869,1739502664.6747808,24.99997615814209,3.330906287368168,1739502664.674783,24.99997615814209,0.7539972877438939,1739502664.6747847,24.99997615814209,1.106024999280327,1739502664.6747866,24.99997615814209,0.568178301156633,1739502664.674788,24.99997615814209,1.0319711718856721,1739502664.67479,24.99997615814209,0.0,1739502664.6747916,24.99997615814209,-0.08160441227450677,1739502664.6747935,24.99997615814209,0.4620880372344609,1739502664.674795,24.99997615814209,1.1135755841601789 +1739502664.695547,25.019976139068604,48.907819569870256,1739502664.6955504,25.019976139068604,0.6999551789829823,1739502664.6955545,25.019976139068604,49.01794893409945,1739502664.6955578,25.019976139068604,51.70941343662869,1739502664.6955597,25.019976139068604,3.330906287368168,1739502664.695562,25.019976139068604,0.7539972877438939,1739502664.6955638,25.019976139068604,1.106024999280327,1739502664.6955655,25.019976139068604,0.568178301156633,1739502664.6955671,25.019976139068604,1.0319711718856721,1739502664.6955688,25.019976139068604,0.0,1739502664.6955707,25.019976139068604,-0.08160441227450677,1739502664.6955724,25.019976139068604,0.4620880372344609,1739502664.6955743,25.019976139068604,1.1135755841601789 +1739502664.7148635,25.039976119995117,49.01643531628282,1739502664.7148666,25.039976119995117,0.7556035539725539,1739502664.7148702,25.039976119995117,49.19358522900819,1739502664.7148738,25.039976119995117,51.73976105396167,1739502664.7148757,25.039976119995117,3.4857046972176455,1739502664.7148778,25.039976119995117,0.7866405752291352,1739502664.7148795,25.039976119995117,1.1375285422339911,1739502664.7148812,25.039976119995117,0.5801656757992953,1739502664.7148826,25.039976119995117,1.0062875824652449,1739502664.7148845,25.039976119995117,0.0,1739502664.7148862,25.039976119995117,-0.10595400376330989,1739502664.7148879,25.039976119995117,0.48719539662995837,1739502664.7148898,25.039976119995117,1.1046323338992892 +1739502664.7347727,25.05997610092163,49.01643531628282,1739502664.7347755,25.05997610092163,0.7556035539725539,1739502664.734779,25.05997610092163,49.19358522900819,1739502664.7347822,25.05997610092163,51.73976105396167,1739502664.734784,25.05997610092163,3.4857046972176455,1739502664.734786,25.05997610092163,0.7866405752291352,1739502664.7347877,25.05997610092163,1.1375285422339911,1739502664.7347894,25.05997610092163,0.5801656757992953,1739502664.7347906,25.05997610092163,1.0062875824652449,1739502664.7347927,25.05997610092163,0.0,1739502664.7347941,25.05997610092163,-0.09834475143404431,1739502664.7347958,25.05997610092163,0.48719539662995837,1739502664.7347977,25.05997610092163,1.1046323338992892 +1739502664.75507,25.079976081848145,49.01643531628282,1739502664.7550728,25.079976081848145,0.7556035539725539,1739502664.7550762,25.079976081848145,49.19358522900819,1739502664.7550797,25.079976081848145,51.73976105396167,1739502664.7550812,25.079976081848145,3.4857046972176455,1739502664.755083,25.079976081848145,0.7866405752291352,1739502664.7550848,25.079976081848145,1.1375285422339911,1739502664.7550867,25.079976081848145,0.5801656757992953,1739502664.755088,25.079976081848145,1.0062875824652449,1739502664.75509,25.079976081848145,0.0,1739502664.7550914,25.079976081848145,-0.09834475143404431,1739502664.7550933,25.079976081848145,0.48719539662995837,1739502664.7550948,25.079976081848145,1.1046323338992892 +1739502664.7748847,25.099976062774658,49.01643531628282,1739502664.7748876,25.099976062774658,0.7556035539725539,1739502664.7748914,25.099976062774658,49.19358522900819,1739502664.7748945,25.099976062774658,51.73976105396167,1739502664.7748964,25.099976062774658,3.4857046972176455,1739502664.7748985,25.099976062774658,0.7866405752291352,1739502664.7749002,25.099976062774658,1.1375285422339911,1739502664.7749019,25.099976062774658,0.5801656757992953,1739502664.7749033,25.099976062774658,1.0062875824652449,1739502664.7749054,25.099976062774658,0.0,1739502664.7749069,25.099976062774658,-0.09834475143404431,1739502664.7749088,25.099976062774658,0.48719539662995837,1739502664.7749104,25.099976062774658,1.1046323338992892 +1739502664.7951875,25.119976043701172,49.01643531628282,1739502664.7951903,25.119976043701172,0.7556035539725539,1739502664.795194,25.119976043701172,49.19358522900819,1739502664.795197,25.119976043701172,51.73976105396167,1739502664.7951987,25.119976043701172,3.4857046972176455,1739502664.7952006,25.119976043701172,0.7866405752291352,1739502664.7952023,25.119976043701172,1.1375285422339911,1739502664.795204,25.119976043701172,0.5801656757992953,1739502664.7952054,25.119976043701172,1.0062875824652449,1739502664.7952073,25.119976043701172,0.0,1739502664.7952087,25.119976043701172,-0.09834475143404431,1739502664.7952106,25.119976043701172,0.48719539662995837,1739502664.7952123,25.119976043701172,1.1046323338992892 +1739502664.8148427,25.139976024627686,49.01643531628282,1739502664.814846,25.139976024627686,0.7556035539725539,1739502664.8148499,25.139976024627686,49.19358522900819,1739502664.8148532,25.139976024627686,51.73976105396167,1739502664.8148546,25.139976024627686,3.4857046972176455,1739502664.8148568,25.139976024627686,0.7866405752291352,1739502664.8148587,25.139976024627686,1.1375285422339911,1739502664.8148606,25.139976024627686,0.5801656757992953,1739502664.814862,25.139976024627686,1.0062875824652449,1739502664.814864,25.139976024627686,0.0,1739502664.8148656,25.139976024627686,-0.09834475143404431,1739502664.8148673,25.139976024627686,0.48719539662995837,1739502664.8148687,25.139976024627686,1.1046323338992892 +1739502664.834837,25.1599760055542,49.12265197621588,1739502664.83484,25.1599760055542,0.8134606016487069,1739502664.8348439,25.1599760055542,49.30238197771366,1739502664.8348472,25.1599760055542,51.75364381999208,1739502664.834849,25.1599760055542,3.571525432678283,1739502664.8348508,25.1599760055542,0.8089736148313283,1739502664.8348527,25.1599760055542,1.1124035818708469,1739502664.8348544,25.1599760055542,0.580651599409126,1739502664.8348558,25.1599760055542,1.0267185742538691,1739502664.8348577,25.1599760055542,0.0,1739502664.8348594,25.1599760055542,-0.052728463481064594,1739502664.834861,25.1599760055542,0.5128242215510951,1739502664.8348627,25.1599760055542,1.0937021370666113 +1739502664.8550792,25.179975986480713,49.12265197621588,1739502664.855082,25.179975986480713,0.8134606016487069,1739502664.8550854,25.179975986480713,49.30238197771366,1739502664.8550887,25.179975986480713,51.75364381999208,1739502664.8550901,25.179975986480713,3.571525432678283,1739502664.8550923,25.179975986480713,0.8089736148313283,1739502664.855094,25.179975986480713,1.1124035818708469,1739502664.8550956,25.179975986480713,0.580651599409126,1739502664.855097,25.179975986480713,1.0267185742538691,1739502664.855099,25.179975986480713,0.0,1739502664.8551004,25.179975986480713,-0.0669835628127422,1739502664.8551023,25.179975986480713,0.5128242215510951,1739502664.8551037,25.179975986480713,1.0937021370666113 +1739502664.874848,25.199975967407227,49.12265197621588,1739502664.874851,25.199975967407227,0.8134606016487069,1739502664.8748546,25.199975967407227,49.30238197771366,1739502664.8748577,25.199975967407227,51.75364381999208,1739502664.8748596,25.199975967407227,3.571525432678283,1739502664.8748617,25.199975967407227,0.8089736148313283,1739502664.8748634,25.199975967407227,1.1124035818708469,1739502664.874865,25.199975967407227,0.580651599409126,1739502664.8748667,25.199975967407227,1.0267185742538691,1739502664.8748684,25.199975967407227,0.0,1739502664.8748703,25.199975967407227,-0.0669835628127422,1739502664.8748717,25.199975967407227,0.5128242215510951,1739502664.8748736,25.199975967407227,1.0937021370666113 +1739502664.8950999,25.21997594833374,49.12265197621588,1739502664.8951027,25.21997594833374,0.8134606016487069,1739502664.8951066,25.21997594833374,49.30238197771366,1739502664.8951097,25.21997594833374,51.75364381999208,1739502664.895111,25.21997594833374,3.571525432678283,1739502664.8951132,25.21997594833374,0.8089736148313283,1739502664.895115,25.21997594833374,1.1124035818708469,1739502664.8951168,25.21997594833374,0.580651599409126,1739502664.8951182,25.21997594833374,1.0267185742538691,1739502664.8951201,25.21997594833374,0.0,1739502664.8951218,25.21997594833374,-0.0669835628127422,1739502664.8951237,25.21997594833374,0.5128242215510951,1739502664.8951252,25.21997594833374,1.0937021370666113 +1739502664.9148085,25.239975929260254,49.12265197621588,1739502664.9148118,25.239975929260254,0.8134606016487069,1739502664.9148154,25.239975929260254,49.30238197771366,1739502664.9148185,25.239975929260254,51.75364381999208,1739502664.9148204,25.239975929260254,3.571525432678283,1739502664.9148223,25.239975929260254,0.8089736148313283,1739502664.914824,25.239975929260254,1.1124035818708469,1739502664.9148254,25.239975929260254,0.580651599409126,1739502664.914827,25.239975929260254,1.0267185742538691,1739502664.9148288,25.239975929260254,0.0,1739502664.9148304,25.239975929260254,-0.0669835628127422,1739502664.914832,25.239975929260254,0.5128242215510951,1739502664.914834,25.239975929260254,1.0937021370666113 +1739502664.934942,25.259975910186768,49.22645589044781,1739502664.9349453,25.259975910186768,0.8735267995967755,1739502664.9349487,25.259975910186768,49.4770610227397,1739502664.934952,25.259975910186768,51.777948850596,1739502664.9349535,25.259975910186768,3.7296112645295554,1739502664.9349556,25.259975910186768,0.8416655019986481,1739502664.9349573,25.259975910186768,1.1425172503771983,1739502664.934959,25.259975910186768,0.5904906477313316,1739502664.9349604,25.259975910186768,1.0022795257496366,1739502664.9349625,25.259975910186768,0.0,1739502664.9349637,25.259975910186768,-0.09182294859592002,1739502664.9349656,25.259975910186768,0.5387300305509897,1739502664.9349673,25.259975910186768,1.0863401611989445 +1739502664.9550962,25.27997589111328,49.22645589044781,1739502664.955099,25.27997589111328,0.8735267995967755,1739502664.9551024,25.27997589111328,49.4770610227397,1739502664.955106,25.27997589111328,51.777948850596,1739502664.955108,25.27997589111328,3.7296112645295554,1739502664.9551096,25.27997589111328,0.8416655019986481,1739502664.9551113,25.27997589111328,1.1425172503771983,1739502664.955113,25.27997589111328,0.5904906477313316,1739502664.9551146,25.27997589111328,1.0022795257496366,1739502664.9551163,25.27997589111328,0.0,1739502664.9551182,25.27997589111328,-0.08406063544930786,1739502664.9551198,25.27997589111328,0.5387300305509897,1739502664.9551215,25.27997589111328,1.0863401611989445 +1739502664.9747791,25.299975872039795,49.22645589044781,1739502664.974782,25.299975872039795,0.8735267995967755,1739502664.9747856,25.299975872039795,49.4770610227397,1739502664.974789,25.299975872039795,51.777948850596,1739502664.9747906,25.299975872039795,3.7296112645295554,1739502664.9747927,25.299975872039795,0.8416655019986481,1739502664.9747944,25.299975872039795,1.1425172503771983,1739502664.974796,25.299975872039795,0.5904906477313316,1739502664.9747975,25.299975872039795,1.0022795257496366,1739502664.9747996,25.299975872039795,0.0,1739502664.974801,25.299975872039795,-0.08406063544930786,1739502664.974803,25.299975872039795,0.5387300305509897,1739502664.9748044,25.299975872039795,1.0863401611989445 +1739502664.9951544,25.31997585296631,49.22645589044781,1739502664.995157,25.31997585296631,0.8735267995967755,1739502664.9951603,25.31997585296631,49.4770610227397,1739502664.9951637,25.31997585296631,51.777948850596,1739502664.995165,25.31997585296631,3.7296112645295554,1739502664.995167,25.31997585296631,0.8416655019986481,1739502664.9951684,25.31997585296631,1.1425172503771983,1739502664.9951704,25.31997585296631,0.5904906477313316,1739502664.9951718,25.31997585296631,1.0022795257496366,1739502664.9951737,25.31997585296631,0.0,1739502664.9951751,25.31997585296631,-0.08406063544930786,1739502664.995177,25.31997585296631,0.5387300305509897,1739502664.9951785,25.31997585296631,1.0863401611989445 +1739502665.014897,25.339975833892822,49.22645589044781,1739502665.0149004,25.339975833892822,0.8735267995967755,1739502665.0149038,25.339975833892822,49.4770610227397,1739502665.0149074,25.339975833892822,51.777948850596,1739502665.014909,25.339975833892822,3.7296112645295554,1739502665.0149107,25.339975833892822,0.8416655019986481,1739502665.0149126,25.339975833892822,1.1425172503771983,1739502665.014914,25.339975833892822,0.5904906477313316,1739502665.0149155,25.339975833892822,1.0022795257496366,1739502665.0149176,25.339975833892822,0.0,1739502665.0149195,25.339975833892822,-0.08406063544930786,1739502665.014921,25.339975833892822,0.5387300305509897,1739502665.0149229,25.339975833892822,1.0863401611989445 +1739502665.0347545,25.359975814819336,49.22645589044781,1739502665.034758,25.359975814819336,0.8735267995967755,1739502665.0347614,25.359975814819336,49.4770610227397,1739502665.0347648,25.359975814819336,51.777948850596,1739502665.0347664,25.359975814819336,3.7296112645295554,1739502665.0347683,25.359975814819336,0.8416655019986481,1739502665.03477,25.359975814819336,1.1425172503771983,1739502665.0347714,25.359975814819336,0.5904906477313316,1739502665.0347729,25.359975814819336,1.0022795257496366,1739502665.034775,25.359975814819336,0.0,1739502665.0347767,25.359975814819336,-0.08406063544930786,1739502665.0347786,25.359975814819336,0.5387300305509897,1739502665.0347805,25.359975814819336,1.0863401611989445 +1739502665.0551012,25.37997579574585,49.327881343302934,1739502665.055104,25.37997579574585,0.9358016060050476,1739502665.0551076,25.37997579574585,49.569256887526045,1739502665.055111,25.37997579574585,51.786836462308294,1739502665.0551126,25.37997579574585,3.802528160774692,1739502665.0551145,25.37997579574585,0.861816056538829,1739502665.0551162,25.37997579574585,1.1044024000763257,1739502665.0551178,25.37997579574585,0.5869986716544966,1739502665.0551193,25.37997579574585,1.0333116221845278,1739502665.0551212,25.37997579574585,0.0,1739502665.0551226,25.37997579574585,-0.025297132866957773,1739502665.0551245,25.37997579574585,0.5650660921102498,1739502665.0551262,25.37997579574585,1.0769723616485887 +1739502665.0748136,25.399975776672363,49.327881343302934,1739502665.0748167,25.399975776672363,0.9358016060050476,1739502665.0748203,25.399975776672363,49.569256887526045,1739502665.0748236,25.399975776672363,51.786836462308294,1739502665.0748253,25.399975776672363,3.802528160774692,1739502665.0748274,25.399975776672363,0.861816056538829,1739502665.0748293,25.399975776672363,1.1044024000763257,1739502665.0748308,25.399975776672363,0.5869986716544966,1739502665.0748324,25.399975776672363,1.0333116221845278,1739502665.0748343,25.399975776672363,0.0,1739502665.074836,25.399975776672363,-0.043660739464060905,1739502665.0748374,25.399975776672363,0.5650660921102498,1739502665.0748394,25.399975776672363,1.0769723616485887 +1739502665.0951684,25.419975757598877,49.327881343302934,1739502665.095171,25.419975757598877,0.9358016060050476,1739502665.0951743,25.419975757598877,49.569256887526045,1739502665.0951777,25.419975757598877,51.786836462308294,1739502665.0951793,25.419975757598877,3.802528160774692,1739502665.095181,25.419975757598877,0.861816056538829,1739502665.095183,25.419975757598877,1.1044024000763257,1739502665.0951846,25.419975757598877,0.5869986716544966,1739502665.0951865,25.419975757598877,1.0333116221845278,1739502665.0951881,25.419975757598877,0.0,1739502665.0951898,25.419975757598877,-0.043660739464060905,1739502665.0951915,25.419975757598877,0.5650660921102498,1739502665.0951931,25.419975757598877,1.0769723616485887 +1739502665.1148171,25.43997573852539,49.327881343302934,1739502665.11482,25.43997573852539,0.9358016060050476,1739502665.1148236,25.43997573852539,49.569256887526045,1739502665.1148267,25.43997573852539,51.786836462308294,1739502665.1148286,25.43997573852539,3.802528160774692,1739502665.1148305,25.43997573852539,0.861816056538829,1739502665.1148324,25.43997573852539,1.1044024000763257,1739502665.114834,25.43997573852539,0.5869986716544966,1739502665.1148355,25.43997573852539,1.0333116221845278,1739502665.1148374,25.43997573852539,0.0,1739502665.114839,25.43997573852539,-0.043660739464060905,1739502665.1148407,25.43997573852539,0.5650660921102498,1739502665.1148427,25.43997573852539,1.0769723616485887 +1739502665.1348033,25.459975719451904,49.327881343302934,1739502665.1348062,25.459975719451904,0.9358016060050476,1739502665.13481,25.459975719451904,49.569256887526045,1739502665.134813,25.459975719451904,51.786836462308294,1739502665.1348152,25.459975719451904,3.802528160774692,1739502665.1348176,25.459975719451904,0.861816056538829,1739502665.1348193,25.459975719451904,1.1044024000763257,1739502665.134821,25.459975719451904,0.5869986716544966,1739502665.1348228,25.459975719451904,1.0333116221845278,1739502665.1348248,25.459975719451904,0.0,1739502665.1348262,25.459975719451904,-0.043660739464060905,1739502665.134828,25.459975719451904,0.5650660921102498,1739502665.1348295,25.459975719451904,1.0769723616485887 +1739502665.1552668,25.479975700378418,49.426953670347736,1739502665.1552696,25.479975700378418,1.0002963303879087,1739502665.1552732,25.479975700378418,49.659721030065214,1739502665.1552765,25.479975700378418,51.795256104163116,1739502665.1552784,25.479975700378418,3.8829224582991335,1739502665.1552804,25.479975700378418,0.8830358060405308,1739502665.155282,25.479975700378418,1.072332171463286,1739502665.1552837,25.479975700378418,0.5842016686667225,1739502665.1552854,25.479975700378418,1.0601654646873961,1739502665.155287,25.479975700378418,0.0,1739502665.1552885,25.479975700378418,0.0024029830275208615,1739502665.1552904,25.479975700378418,0.5914913851163595,1739502665.1552918,25.479975700378418,1.0721574043765414 +1739502665.1747944,25.49997568130493,49.426953670347736,1739502665.1747973,25.49997568130493,1.0002963303879087,1739502665.1748009,25.49997568130493,49.659721030065214,1739502665.174804,25.49997568130493,51.795256104163116,1739502665.1748056,25.49997568130493,3.8829224582991335,1739502665.1748078,25.49997568130493,0.8830358060405308,1739502665.1748095,25.49997568130493,1.072332171463286,1739502665.1748111,25.49997568130493,0.5842016686667225,1739502665.1748126,25.49997568130493,1.0601654646873961,1739502665.1748147,25.49997568130493,0.0,1739502665.1748164,25.49997568130493,-0.011991939689145248,1739502665.1748178,25.49997568130493,0.5914913851163595,1739502665.1748195,25.49997568130493,1.0721574043765414 +1739502665.195262,25.519975662231445,49.426953670347736,1739502665.1952648,25.519975662231445,1.0002963303879087,1739502665.1952682,25.519975662231445,49.659721030065214,1739502665.1952717,25.519975662231445,51.795256104163116,1739502665.1952732,25.519975662231445,3.8829224582991335,1739502665.1952753,25.519975662231445,0.8830358060405308,1739502665.1952767,25.519975662231445,1.072332171463286,1739502665.1952784,25.519975662231445,0.5842016686667225,1739502665.1952798,25.519975662231445,1.0601654646873961,1739502665.1952817,25.519975662231445,0.0,1739502665.1952832,25.519975662231445,-0.011991939689145248,1739502665.195285,25.519975662231445,0.5914913851163595,1739502665.1952865,25.519975662231445,1.0721574043765414 +1739502665.2149124,25.53997564315796,49.426953670347736,1739502665.2149155,25.53997564315796,1.0002963303879087,1739502665.2149193,25.53997564315796,49.659721030065214,1739502665.2149227,25.53997564315796,51.795256104163116,1739502665.2149246,25.53997564315796,3.8829224582991335,1739502665.214927,25.53997564315796,0.8830358060405308,1739502665.2149284,25.53997564315796,1.072332171463286,1739502665.21493,25.53997564315796,0.5842016686667225,1739502665.2149317,25.53997564315796,1.0601654646873961,1739502665.2149334,25.53997564315796,0.0,1739502665.214935,25.53997564315796,-0.011991939689145248,1739502665.2149367,25.53997564315796,0.5914913851163595,1739502665.2149386,25.53997564315796,1.0721574043765414 +1739502665.2348151,25.559975624084473,49.426953670347736,1739502665.2348182,25.559975624084473,1.0002963303879087,1739502665.2348218,25.559975624084473,49.659721030065214,1739502665.2348251,25.559975624084473,51.795256104163116,1739502665.234827,25.559975624084473,3.8829224582991335,1739502665.234829,25.559975624084473,0.8830358060405308,1739502665.2348306,25.559975624084473,1.072332171463286,1739502665.2348323,25.559975624084473,0.5842016686667225,1739502665.2348337,25.559975624084473,1.0601654646873961,1739502665.2348354,25.559975624084473,0.0,1739502665.234837,25.559975624084473,-0.011991939689145248,1739502665.2348385,25.559975624084473,0.5914913851163595,1739502665.2348404,25.559975624084473,1.0721574043765414 +1739502665.2549858,25.579975605010986,49.426953670347736,1739502665.2549884,25.579975605010986,1.0002963303879087,1739502665.2549918,25.579975605010986,49.659721030065214,1739502665.254995,25.579975605010986,51.795256104163116,1739502665.2549968,25.579975605010986,3.8829224582991335,1739502665.2549987,25.579975605010986,0.8830358060405308,1739502665.2550004,25.579975605010986,1.072332171463286,1739502665.2550018,25.579975605010986,0.5842016686667225,1739502665.2550035,25.579975605010986,1.0601654646873961,1739502665.2550054,25.579975605010986,0.0,1739502665.2550068,25.579975605010986,-0.011991939689145248,1739502665.2550085,25.579975605010986,0.5914913851163595,1739502665.2550101,25.579975605010986,1.0721574043765414 +1739502665.2750514,25.5999755859375,49.524023287387024,1739502665.275054,25.5999755859375,1.0672052731387556,1739502665.2750583,25.5999755859375,49.772459251743186,1739502665.2750616,25.5999755859375,51.803949680835466,1739502665.275063,25.5999755859375,3.9932452125319795,1739502665.2750654,25.5999755859375,0.9088769558279619,1739502665.2750669,25.5999755859375,1.0641288723820141,1739502665.2750688,25.5999755859375,0.5863595637869147,1739502665.2750702,25.5999755859375,1.0671458279437223,1739502665.275072,25.5999755859375,0.0,1739502665.2750735,25.5999755859375,-0.0003427369742076414,1739502665.2750754,25.5999755859375,0.6179166781224691,1739502665.2750769,25.5999755859375,1.0711289431531659 +1739502665.2956662,25.619975566864014,49.524023287387024,1739502665.29567,25.619975566864014,1.0672052731387556,1739502665.2956738,25.619975566864014,49.772459251743186,1739502665.2956774,25.619975566864014,51.803949680835466,1739502665.2956796,25.619975566864014,3.9932452125319795,1739502665.2956815,25.619975566864014,0.9088769558279619,1739502665.2956834,25.619975566864014,1.0641288723820141,1739502665.2956848,25.619975566864014,0.5863595637869147,1739502665.2956865,25.619975566864014,1.0671458279437223,1739502665.2956884,25.619975566864014,0.0,1739502665.29569,25.619975566864014,-0.003983115209443611,1739502665.295692,25.619975566864014,0.6179166781224691,1739502665.2956939,25.619975566864014,1.0711289431531659 +1739502665.3148263,25.639975547790527,49.524023287387024,1739502665.3148293,25.639975547790527,1.0672052731387556,1739502665.314833,25.639975547790527,49.772459251743186,1739502665.3148363,25.639975547790527,51.803949680835466,1739502665.314838,25.639975547790527,3.9932452125319795,1739502665.31484,25.639975547790527,0.9088769558279619,1739502665.3148417,25.639975547790527,1.0641288723820141,1739502665.3148434,25.639975547790527,0.5863595637869147,1739502665.3148448,25.639975547790527,1.0671458279437223,1739502665.3148468,25.639975547790527,0.0,1739502665.3148482,25.639975547790527,-0.003983115209443611,1739502665.31485,25.639975547790527,0.6179166781224691,1739502665.3148518,25.639975547790527,1.0711289431531659 +1739502665.3348012,25.65997552871704,49.524023287387024,1739502665.3348045,25.65997552871704,1.0672052731387556,1739502665.334808,25.65997552871704,49.772459251743186,1739502665.3348112,25.65997552871704,51.803949680835466,1739502665.3348126,25.65997552871704,3.9932452125319795,1739502665.3348148,25.65997552871704,0.9088769558279619,1739502665.3348165,25.65997552871704,1.0641288723820141,1739502665.3348184,25.65997552871704,0.5863595637869147,1739502665.3348198,25.65997552871704,1.0671458279437223,1739502665.3348217,25.65997552871704,0.0,1739502665.3348231,25.65997552871704,-0.003983115209443611,1739502665.3348248,25.65997552871704,0.6179166781224691,1739502665.3348265,25.65997552871704,1.0711289431531659 +1739502665.3547945,25.679975509643555,49.524023287387024,1739502665.3547971,25.679975509643555,1.0672052731387556,1739502665.3548002,25.679975509643555,49.772459251743186,1739502665.354803,25.679975509643555,51.803949680835466,1739502665.3548045,25.679975509643555,3.9932452125319795,1739502665.3548064,25.679975509643555,0.9088769558279619,1739502665.354808,25.679975509643555,1.0641288723820141,1739502665.3548095,25.679975509643555,0.5863595637869147,1739502665.3548107,25.679975509643555,1.0671458279437223,1739502665.3548124,25.679975509643555,0.0,1739502665.3548138,25.679975509643555,-0.003983115209443611,1739502665.3548152,25.679975509643555,0.6179166781224691,1739502665.3548164,25.679975509643555,1.0711289431531659 +1739502665.3750687,25.69997549057007,49.61921169543759,1739502665.375072,25.69997549057007,1.136597953711866,1739502665.3750758,25.69997549057007,49.91880703843801,1739502665.3750794,25.69997549057007,51.810741812497874,1739502665.3750813,25.69997549057007,4.138545312446753,1739502665.3750834,25.69997549057007,0.9401949818480234,1739502665.3750854,25.69997549057007,1.0836506781643336,1739502665.375087,25.69997549057007,0.594534868544838,1739502665.3750887,25.69997549057007,1.0506092030914038,1739502665.3750906,25.69997549057007,0.0,1739502665.3750925,25.69997549057007,-0.02739202623331777,1739502665.3750944,25.69997549057007,0.6443419711285787,1739502665.375096,25.69997549057007,1.0706859398334834 +1739502665.3965468,25.719975471496582,49.61921169543759,1739502665.3965545,25.719975471496582,1.136597953711866,1739502665.3965616,25.719975471496582,49.91880703843801,1739502665.396582,25.719975471496582,51.810741812497874,1739502665.3965847,25.719975471496582,4.138545312446753,1739502665.396589,25.719975471496582,0.9401949818480234,1739502665.3966,25.719975471496582,1.0836506781643336,1739502665.3966026,25.719975471496582,0.594534868544838,1739502665.3966062,25.719975471496582,1.0506092030914038,1739502665.3966093,25.719975471496582,0.0,1739502665.396613,25.719975471496582,-0.02007673674207955,1739502665.3966155,25.719975471496582,0.6443419711285787,1739502665.3966193,25.719975471496582,1.0706859398334834 +1739502665.4155843,25.739975452423096,49.61921169543759,1739502665.4155881,25.739975452423096,1.136597953711866,1739502665.4155927,25.739975452423096,49.91880703843801,1739502665.415597,25.739975452423096,51.810741812497874,1739502665.4155993,25.739975452423096,4.138545312446753,1739502665.415602,25.739975452423096,0.9401949818480234,1739502665.415604,25.739975452423096,1.0836506781643336,1739502665.4156065,25.739975452423096,0.594534868544838,1739502665.4156084,25.739975452423096,1.0506092030914038,1739502665.4156108,25.739975452423096,0.0,1739502665.4156132,25.739975452423096,-0.02007673674207955,1739502665.4156156,25.739975452423096,0.6443419711285787,1739502665.4156175,25.739975452423096,1.0706859398334834 +1739502665.4359295,25.75997543334961,49.61921169543759,1739502665.4359334,25.75997543334961,1.136597953711866,1739502665.4359381,25.75997543334961,49.91880703843801,1739502665.4359426,25.75997543334961,51.810741812497874,1739502665.435945,25.75997543334961,4.138545312446753,1739502665.4359474,25.75997543334961,0.9401949818480234,1739502665.4359496,25.75997543334961,1.0836506781643336,1739502665.435952,25.75997543334961,0.594534868544838,1739502665.4359539,25.75997543334961,1.0506092030914038,1739502665.4359565,25.75997543334961,0.0,1739502665.4359586,25.75997543334961,-0.02007673674207955,1739502665.4359608,25.75997543334961,0.6443419711285787,1739502665.4359632,25.75997543334961,1.0706859398334834 +1739502665.456201,25.779975414276123,49.61921169543759,1739502665.4562051,25.779975414276123,1.136597953711866,1739502665.4562097,25.779975414276123,49.91880703843801,1739502665.456214,25.779975414276123,51.810741812497874,1739502665.456216,25.779975414276123,4.138545312446753,1739502665.456219,25.779975414276123,0.9401949818480234,1739502665.456221,25.779975414276123,1.0836506781643336,1739502665.4562235,25.779975414276123,0.594534868544838,1739502665.4562254,25.779975414276123,1.0506092030914038,1739502665.456228,25.779975414276123,0.0,1739502665.4562302,25.779975414276123,-0.02007673674207955,1739502665.456233,25.779975414276123,0.6443419711285787,1739502665.4562352,25.779975414276123,1.0706859398334834 +1739502665.4756951,25.799975395202637,49.61921169543759,1739502665.4756982,25.799975395202637,1.136597953711866,1739502665.4757023,25.799975395202637,49.91880703843801,1739502665.4757059,25.799975395202637,51.810741812497874,1739502665.4757075,25.799975395202637,4.138545312446753,1739502665.47571,25.799975395202637,0.9401949818480234,1739502665.4757118,25.799975395202637,1.0836506781643336,1739502665.4757135,25.799975395202637,0.594534868544838,1739502665.4757156,25.799975395202637,1.0506092030914038,1739502665.4757178,25.799975395202637,0.0,1739502665.4757197,25.799975395202637,-0.02007673674207955,1739502665.4757214,25.799975395202637,0.6443419711285787,1739502665.4757235,25.799975395202637,1.0706859398334834 +1739502665.495275,25.81997537612915,49.71240745943211,1739502665.4952776,25.81997537612915,1.2084003688693334,1739502665.4952812,25.81997537612915,50.04159590211148,1739502665.4952846,25.81997537612915,51.81285789312185,1739502665.495286,25.81997537612915,4.256610749184268,1739502665.4952881,25.81997537612915,0.9674391884763198,1739502665.4952896,25.81997537612915,1.0811759575496105,1739502665.4952915,25.81997537612915,0.5978922203941561,1739502665.495293,25.81997537612915,1.0526912347923925,1739502665.4952948,25.81997537612915,0.0,1739502665.4952962,25.81997537612915,-0.01363612090851837,1739502665.4952981,25.81997537612915,0.6710528977786145,1739502665.4952998,25.81997537612915,1.0683400494685236 +1739502665.5148978,25.839975357055664,49.71240745943211,1739502665.5149012,25.839975357055664,1.2084003688693334,1739502665.5149047,25.839975357055664,50.04159590211148,1739502665.514908,25.839975357055664,51.81285789312185,1739502665.5149097,25.839975357055664,4.256610749184268,1739502665.5149117,25.839975357055664,0.9674391884763198,1739502665.5149136,25.839975357055664,1.0811759575496105,1739502665.514915,25.839975357055664,0.5978922203941561,1739502665.5149167,25.839975357055664,1.0526912347923925,1739502665.5149186,25.839975357055664,0.0,1739502665.5149202,25.839975357055664,-0.015648814676131106,1739502665.514922,25.839975357055664,0.6710528977786145,1739502665.5149238,25.839975357055664,1.0683400494685236 +1739502665.5348423,25.859975337982178,49.71240745943211,1739502665.5348456,25.859975337982178,1.2084003688693334,1739502665.5348492,25.859975337982178,50.04159590211148,1739502665.534853,25.859975337982178,51.81285789312185,1739502665.5348544,25.859975337982178,4.256610749184268,1739502665.5348566,25.859975337982178,0.9674391884763198,1739502665.5348582,25.859975337982178,1.0811759575496105,1739502665.5348597,25.859975337982178,0.5978922203941561,1739502665.5348613,25.859975337982178,1.0526912347923925,1739502665.534863,25.859975337982178,0.0,1739502665.534865,25.859975337982178,-0.015648814676131106,1739502665.5348666,25.859975337982178,0.6710528977786145,1739502665.5348682,25.859975337982178,1.0683400494685236 +1739502665.554776,25.87997531890869,49.71240745943211,1739502665.5547788,25.87997531890869,1.2084003688693334,1739502665.5547822,25.87997531890869,50.04159590211148,1739502665.5547855,25.87997531890869,51.81285789312185,1739502665.5547872,25.87997531890869,4.256610749184268,1739502665.554789,25.87997531890869,0.9674391884763198,1739502665.5547907,25.87997531890869,1.0811759575496105,1739502665.5547924,25.87997531890869,0.5978922203941561,1739502665.554794,25.87997531890869,1.0526912347923925,1739502665.5547957,25.87997531890869,0.0,1739502665.5547974,25.87997531890869,-0.015648814676131106,1739502665.554799,25.87997531890869,0.6710528977786145,1739502665.5548007,25.87997531890869,1.0683400494685236 +1739502665.5748277,25.899975299835205,49.71240745943211,1739502665.5748308,25.899975299835205,1.2084003688693334,1739502665.574834,25.899975299835205,50.04159590211148,1739502665.5748374,25.899975299835205,51.81285789312185,1739502665.5748394,25.899975299835205,4.256610749184268,1739502665.574841,25.899975299835205,0.9674391884763198,1739502665.574843,25.899975299835205,1.0811759575496105,1739502665.5748444,25.899975299835205,0.5978922203941561,1739502665.574846,25.899975299835205,1.0526912347923925,1739502665.5748477,25.899975299835205,0.0,1739502665.5748496,25.899975299835205,-0.015648814676131106,1739502665.5748513,25.899975299835205,0.6710528977786145,1739502665.574853,25.899975299835205,1.0683400494685236 +1739502665.5953119,25.91997528076172,49.803474371849575,1739502665.5953145,25.91997528076172,1.2825351033675005,1739502665.595318,25.91997528076172,50.158141787231315,1739502665.5953214,25.91997528076172,51.812038271014046,1739502665.595323,25.91997528076172,4.369718600061429,1739502665.5953252,25.91997528076172,0.9939897986668627,1739502665.5953267,25.91997528076172,1.0744962181625957,1739502665.5953286,25.91997528076172,0.6002001951720689,1739502665.59533,25.91997528076172,1.0583316544661376,1739502665.5953324,25.91997528076172,0.0,1739502665.5953338,25.91997528076172,-0.004946335861940527,1739502665.5953355,25.91997528076172,0.6979453675196218,1739502665.5953372,25.91997528076172,1.0666225171503554 +1739502665.6149616,25.939975261688232,49.803474371849575,1739502665.6149645,25.939975261688232,1.2825351033675005,1739502665.6149683,25.939975261688232,50.158141787231315,1739502665.6149716,25.939975261688232,51.812038271014046,1739502665.614973,25.939975261688232,4.369718600061429,1739502665.6149752,25.939975261688232,0.9939897986668627,1739502665.6149771,25.939975261688232,1.0744962181625957,1739502665.6149786,25.939975261688232,0.6002001951720689,1739502665.6149797,25.939975261688232,1.0583316544661376,1739502665.614982,25.939975261688232,0.0,1739502665.6149833,25.939975261688232,-0.008290862684217748,1739502665.6149852,25.939975261688232,0.6979453675196218,1739502665.614987,25.939975261688232,1.0666225171503554 +1739502665.6348126,25.959975242614746,49.803474371849575,1739502665.634816,25.959975242614746,1.2825351033675005,1739502665.6348195,25.959975242614746,50.158141787231315,1739502665.6348228,25.959975242614746,51.812038271014046,1739502665.6348248,25.959975242614746,4.369718600061429,1739502665.6348267,25.959975242614746,0.9939897986668627,1739502665.6348283,25.959975242614746,1.0744962181625957,1739502665.63483,25.959975242614746,0.6002001951720689,1739502665.6348317,25.959975242614746,1.0583316544661376,1739502665.6348333,25.959975242614746,0.0,1739502665.634835,25.959975242614746,-0.008290862684217748,1739502665.6348367,25.959975242614746,0.6979453675196218,1739502665.6348386,25.959975242614746,1.0666225171503554 +1739502665.6553488,25.97997522354126,49.803474371849575,1739502665.6553516,25.97997522354126,1.2825351033675005,1739502665.6553552,25.97997522354126,50.158141787231315,1739502665.6553586,25.97997522354126,51.812038271014046,1739502665.6553602,25.97997522354126,4.369718600061429,1739502665.6553621,25.97997522354126,0.9939897986668627,1739502665.6553636,25.97997522354126,1.0744962181625957,1739502665.6553655,25.97997522354126,0.6002001951720689,1739502665.655367,25.97997522354126,1.0583316544661376,1739502665.6553688,25.97997522354126,0.0,1739502665.6553702,25.97997522354126,-0.008290862684217748,1739502665.6553721,25.97997522354126,0.6979453675196218,1739502665.6553736,25.97997522354126,1.0666225171503554 +1739502665.6751676,25.999975204467773,49.803474371849575,1739502665.675171,25.999975204467773,1.2825351033675005,1739502665.6751747,25.999975204467773,50.158141787231315,1739502665.6751778,25.999975204467773,51.812038271014046,1739502665.6751795,25.999975204467773,4.369718600061429,1739502665.6751816,25.999975204467773,0.9939897986668627,1739502665.6751838,25.999975204467773,1.0744962181625957,1739502665.6751857,25.999975204467773,0.6002001951720689,1739502665.675187,25.999975204467773,1.0583316544661376,1739502665.6751893,25.999975204467773,0.0,1739502665.6751907,25.999975204467773,-0.008290862684217748,1739502665.6751926,25.999975204467773,0.6979453675196218,1739502665.6751943,25.999975204467773,1.0666225171503554 +1739502665.6952834,26.019975185394287,49.803474371849575,1739502665.695286,26.019975185394287,1.2825351033675005,1739502665.6952896,26.019975185394287,50.158141787231315,1739502665.695293,26.019975185394287,51.812038271014046,1739502665.6952944,26.019975185394287,4.369718600061429,1739502665.6952963,26.019975185394287,0.9939897986668627,1739502665.6952977,26.019975185394287,1.0744962181625957,1739502665.6952996,26.019975185394287,0.6002001951720689,1739502665.6953008,26.019975185394287,1.0583316544661376,1739502665.6953027,26.019975185394287,0.0,1739502665.6953042,26.019975185394287,-0.008290862684217748,1739502665.695306,26.019975185394287,0.6979453675196218,1739502665.6953075,26.019975185394287,1.0666225171503554 +1739502665.7149563,26.0399751663208,49.89240079607856,1739502665.7149596,26.0399751663208,1.359007578204368,1739502665.7149634,26.0399751663208,50.33452182613426,1739502665.7149668,26.0399751663208,51.80616847827058,1739502665.7149682,26.0399751663208,4.5443043476707565,1739502665.7149706,26.0399751663208,1.0297792527580998,1739502665.7149723,26.0399751663208,1.115032737925314,1739502665.714974,26.0399751663208,0.6108,1739502665.7149756,26.0399751663208,1.0245613210666966,1739502665.7149773,26.0399751663208,0.0,1739502665.714979,26.0399751663208,-0.05618618271948797,1739502665.7149806,26.0399751663208,0.7250205582208973,1739502665.7149825,26.0399751663208,1.0657802064618378 +1739502665.73489,26.059975147247314,49.89240079607856,1739502665.734893,26.059975147247314,1.359007578204368,1739502665.7348967,26.059975147247314,50.33452182613426,1739502665.7349,26.059975147247314,51.80616847827058,1739502665.7349017,26.059975147247314,4.5443043476707565,1739502665.7349038,26.059975147247314,1.0297792527580998,1739502665.7349055,26.059975147247314,1.115032737925314,1739502665.7349072,26.059975147247314,0.6108,1739502665.7349086,26.059975147247314,1.0245613210666966,1739502665.7349105,26.059975147247314,0.0,1739502665.734912,26.059975147247314,-0.04121888539514118,1739502665.7349138,26.059975147247314,0.7250205582208973,1739502665.7349153,26.059975147247314,1.0657802064618378 +1739502665.7553399,26.079975128173828,49.89240079607856,1739502665.7553422,26.079975128173828,1.359007578204368,1739502665.7553458,26.079975128173828,50.33452182613426,1739502665.7553492,26.079975128173828,51.80616847827058,1739502665.7553508,26.079975128173828,4.5443043476707565,1739502665.7553525,26.079975128173828,1.0297792527580998,1739502665.7553546,26.079975128173828,1.115032737925314,1739502665.755356,26.079975128173828,0.6108,1739502665.7553577,26.079975128173828,1.0245613210666966,1739502665.7553596,26.079975128173828,0.0,1739502665.7553613,26.079975128173828,-0.04121888539514118,1739502665.7553627,26.079975128173828,0.7250205582208973,1739502665.7553644,26.079975128173828,1.0657802064618378 +1739502665.7749338,26.099975109100342,49.89240079607856,1739502665.7749374,26.099975109100342,1.359007578204368,1739502665.7749407,26.099975109100342,50.33452182613426,1739502665.774944,26.099975109100342,51.80616847827058,1739502665.7749457,26.099975109100342,4.5443043476707565,1739502665.774948,26.099975109100342,1.0297792527580998,1739502665.7749496,26.099975109100342,1.115032737925314,1739502665.7749512,26.099975109100342,0.6108,1739502665.7749527,26.099975109100342,1.0245613210666966,1739502665.7749548,26.099975109100342,0.0,1739502665.7749562,26.099975109100342,-0.04121888539514118,1739502665.7749581,26.099975109100342,0.7250205582208973,1739502665.7749596,26.099975109100342,1.0657802064618378 +1739502665.795177,26.119975090026855,49.89240079607856,1739502665.7951796,26.119975090026855,1.359007578204368,1739502665.795183,26.119975090026855,50.33452182613426,1739502665.7951858,26.119975090026855,51.80616847827058,1739502665.7951875,26.119975090026855,4.5443043476707565,1739502665.7951896,26.119975090026855,1.0297792527580998,1739502665.7951913,26.119975090026855,1.115032737925314,1739502665.7951932,26.119975090026855,0.6108,1739502665.7951946,26.119975090026855,1.0245613210666966,1739502665.7951965,26.119975090026855,0.0,1739502665.7951982,26.119975090026855,-0.04121888539514118,1739502665.7951996,26.119975090026855,0.7250205582208973,1739502665.7952015,26.119975090026855,1.0657802064618378 +1739502665.8149822,26.13997507095337,49.97901293903882,1739502665.8149855,26.13997507095337,1.4376872207119424,1739502665.8149893,26.13997507095337,50.49382673445897,1739502665.8149927,26.13997507095337,51.79464253062789,1739502665.814994,26.13997507095337,4.694177505529902,1739502665.8149965,26.13997507095337,1.0621812797691028,1739502665.8149984,26.13997507095337,1.136321481832651,1739502665.815,26.13997507095337,0.6108,1739502665.8150015,26.13997507095337,1.0072597717006744,1739502665.8150036,26.13997507095337,0.0,1739502665.8150053,26.13997507095337,-0.059856852207762754,1739502665.815007,26.13997507095337,0.7524827019597181,1739502665.8150084,26.13997507095337,1.0612922554607394 +1739502665.8348618,26.159975051879883,49.97901293903882,1739502665.8348653,26.159975051879883,1.4376872207119424,1739502665.8348696,26.159975051879883,50.49382673445897,1739502665.8348727,26.159975051879883,51.79464253062789,1739502665.8348746,26.159975051879883,4.694177505529902,1739502665.8348768,26.159975051879883,1.0621812797691028,1739502665.8348782,26.159975051879883,1.136321481832651,1739502665.83488,26.159975051879883,0.6108,1739502665.8348815,26.159975051879883,1.0072597717006744,1739502665.8348832,26.159975051879883,0.0,1739502665.834885,26.159975051879883,-0.054032483760064975,1739502665.8348866,26.159975051879883,0.7524827019597181,1739502665.8348882,26.159975051879883,1.0612922554607394 +1739502665.8549662,26.179975032806396,49.97901293903882,1739502665.8549688,26.179975032806396,1.4376872207119424,1739502665.8549724,26.179975032806396,50.49382673445897,1739502665.8549757,26.179975032806396,51.79464253062789,1739502665.8549774,26.179975032806396,4.694177505529902,1739502665.8549793,26.179975032806396,1.0621812797691028,1739502665.8549812,26.179975032806396,1.136321481832651,1739502665.8549829,26.179975032806396,0.6108,1739502665.8549845,26.179975032806396,1.0072597717006744,1739502665.854986,26.179975032806396,0.0,1739502665.8549876,26.179975032806396,-0.054032483760064975,1739502665.8549893,26.179975032806396,0.7524827019597181,1739502665.854991,26.179975032806396,1.0612922554607394 +1739502665.8749177,26.19997501373291,49.97901293903882,1739502665.8749208,26.19997501373291,1.4376872207119424,1739502665.874925,26.19997501373291,50.49382673445897,1739502665.8749285,26.19997501373291,51.79464253062789,1739502665.8749301,26.19997501373291,4.694177505529902,1739502665.8749323,26.19997501373291,1.0621812797691028,1739502665.874934,26.19997501373291,1.136321481832651,1739502665.8749359,26.19997501373291,0.6108,1739502665.8749373,26.19997501373291,1.0072597717006744,1739502665.8749392,26.19997501373291,0.0,1739502665.8749406,26.19997501373291,-0.054032483760064975,1739502665.8749428,26.19997501373291,0.7524827019597181,1739502665.8749442,26.19997501373291,1.0612922554607394 +1739502665.8953657,26.219974994659424,49.97901293903882,1739502665.895368,26.219974994659424,1.4376872207119424,1739502665.895372,26.219974994659424,50.49382673445897,1739502665.8953753,26.219974994659424,51.79464253062789,1739502665.8953772,26.219974994659424,4.694177505529902,1739502665.8953793,26.219974994659424,1.0621812797691028,1739502665.895381,26.219974994659424,1.136321481832651,1739502665.8953826,26.219974994659424,0.6108,1739502665.895384,26.219974994659424,1.0072597717006744,1739502665.8953857,26.219974994659424,0.0,1739502665.8953876,26.219974994659424,-0.054032483760064975,1739502665.895389,26.219974994659424,0.7524827019597181,1739502665.895391,26.219974994659424,1.0612922554607394 +1739502665.914877,26.239974975585938,49.97901293903882,1739502665.9148805,26.239974975585938,1.4376872207119424,1739502665.914884,26.239974975585938,50.49382673445897,1739502665.9148872,26.239974975585938,51.79464253062789,1739502665.9148889,26.239974975585938,4.694177505529902,1739502665.9148912,26.239974975585938,1.0621812797691028,1739502665.9148932,26.239974975585938,1.136321481832651,1739502665.9148948,26.239974975585938,0.6108,1739502665.9148965,26.239974975585938,1.0072597717006744,1739502665.9148982,26.239974975585938,0.0,1739502665.9148998,26.239974975585938,-0.054032483760064975,1739502665.9149015,26.239974975585938,0.7524827019597181,1739502665.914903,26.239974975585938,1.0612922554607394 +1739502665.935042,26.25997495651245,50.063002851029964,1739502665.9350445,26.25997495651245,1.5183212725293256,1739502665.9350483,26.25997495651245,50.57318845233767,1739502665.9350517,26.25997495651245,51.787120375956825,1739502665.9350536,26.25997495651245,4.761041102606041,1739502665.9350557,26.25997495651245,1.082120290528676,1739502665.9350572,26.25997495651245,1.0924611572568017,1739502665.9350588,26.25997495651245,0.6108,1739502665.9350605,26.25997495651245,1.043230142529477,1739502665.9350626,26.25997495651245,0.0,1739502665.935064,26.25997495651245,0.007070859276556929,1739502665.9350657,26.25997495651245,0.7800843909022661,1739502665.9350674,26.25997495651245,1.0552540904713956 +1739502665.954709,26.279974937438965,50.063002851029964,1739502665.954712,26.279974937438965,1.5183212725293256,1739502665.9547155,26.279974937438965,50.57318845233767,1739502665.954718,26.279974937438965,51.787120375956825,1739502665.9547198,26.279974937438965,4.761041102606041,1739502665.9547215,26.279974937438965,1.082120290528676,1739502665.9547231,26.279974937438965,1.0924611572568017,1739502665.9547248,26.279974937438965,0.6108,1739502665.9547265,26.279974937438965,1.043230142529477,1739502665.9547281,26.279974937438965,0.0,1739502665.9547298,26.279974937438965,-0.012023947941918633,1739502665.9547312,26.279974937438965,0.7800843909022661,1739502665.9547334,26.279974937438965,1.0552540904713956 +1739502665.974918,26.29997491836548,50.063002851029964,1739502665.974921,26.29997491836548,1.5183212725293256,1739502665.9749243,26.29997491836548,50.57318845233767,1739502665.9749277,26.29997491836548,51.787120375956825,1739502665.9749293,26.29997491836548,4.761041102606041,1739502665.9749315,26.29997491836548,1.082120290528676,1739502665.974933,26.29997491836548,1.0924611572568017,1739502665.9749348,26.29997491836548,0.6108,1739502665.9749362,26.29997491836548,1.043230142529477,1739502665.9749382,26.29997491836548,0.0,1739502665.9749396,26.29997491836548,-0.012023947941918633,1739502665.9749415,26.29997491836548,0.7800843909022661,1739502665.974943,26.29997491836548,1.0552540904713956 +1739502665.995074,26.319974899291992,50.063002851029964,1739502665.9950767,26.319974899291992,1.5183212725293256,1739502665.99508,26.319974899291992,50.57318845233767,1739502665.9950833,26.319974899291992,51.787120375956825,1739502665.9950848,26.319974899291992,4.761041102606041,1739502665.995087,26.319974899291992,1.082120290528676,1739502665.9950883,26.319974899291992,1.0924611572568017,1739502665.99509,26.319974899291992,0.6108,1739502665.9950914,26.319974899291992,1.043230142529477,1739502665.9950933,26.319974899291992,0.0,1739502665.9950948,26.319974899291992,-0.012023947941918633,1739502665.9950967,26.319974899291992,0.7800843909022661,1739502665.9950984,26.319974899291992,1.0552540904713956 +1739502666.0173705,26.339974880218506,50.063002851029964,1739502666.0173752,26.339974880218506,1.5183212725293256,1739502666.017381,26.339974880218506,50.57318845233767,1739502666.0173872,26.339974880218506,51.787120375956825,1739502666.017391,26.339974880218506,4.761041102606041,1739502666.0173955,26.339974880218506,1.082120290528676,1739502666.0173995,26.339974880218506,1.0924611572568017,1739502666.0174036,26.339974880218506,0.6108,1739502666.0174077,26.339974880218506,1.043230142529477,1739502666.0174122,26.339974880218506,0.0,1739502666.0174162,26.339974880218506,-0.012023947941918633,1739502666.0174203,26.339974880218506,0.7800843909022661,1739502666.0174243,26.339974880218506,1.0552540904713956 +1739502666.0349298,26.35997486114502,50.144431524686674,1739502666.034933,26.35997486114502,1.600936003455046,1739502666.0349367,26.35997486114502,50.574991743730806,1739502666.03494,26.35997486114502,51.78722088929976,1739502666.0349417,26.35997486114502,4.760147650668804,1739502666.0349436,26.35997486114502,1.0912772072065857,1739502666.0349452,26.35997486114502,0.9963331965920571,1739502666.0349472,26.35997486114502,0.5955388810755085,1739502666.0349486,26.35997486114502,1.1266224501193647,1739502666.0349505,26.35997486114502,0.0,1739502666.0349522,26.35997486114502,0.1112393575998272,1739502666.0349538,26.35997486114502,0.8076860798448141,1739502666.0349555,26.35997486114502,1.0539029007568874 +1739502666.0553784,26.379974842071533,50.144431524686674,1739502666.0553813,26.379974842071533,1.600936003455046,1739502666.0553846,26.379974842071533,50.574991743730806,1739502666.055388,26.379974842071533,51.78722088929976,1739502666.0553894,26.379974842071533,4.760147650668804,1739502666.0553913,26.379974842071533,1.0912772072065857,1739502666.055393,26.379974842071533,0.9963331965920571,1739502666.055395,26.379974842071533,0.5955388810755085,1739502666.0553963,26.379974842071533,1.1266224501193647,1739502666.0553982,26.379974842071533,0.0,1739502666.0553997,26.379974842071533,0.07271954936247726,1739502666.0554013,26.379974842071533,0.8076860798448141,1739502666.055403,26.379974842071533,1.0539029007568874 +1739502666.0749512,26.399974822998047,50.144431524686674,1739502666.0749543,26.399974822998047,1.600936003455046,1739502666.0749578,26.399974822998047,50.574991743730806,1739502666.0749612,26.399974822998047,51.78722088929976,1739502666.074963,26.399974822998047,4.760147650668804,1739502666.074965,26.399974822998047,1.0912772072065857,1739502666.0749664,26.399974822998047,0.9963331965920571,1739502666.0749683,26.399974822998047,0.5955388810755085,1739502666.0749698,26.399974822998047,1.1266224501193647,1739502666.0749717,26.399974822998047,0.0,1739502666.074973,26.399974822998047,0.07271954936247726,1739502666.074975,26.399974822998047,0.8076860798448141,1739502666.0749764,26.399974822998047,1.0539029007568874 +1739502666.095621,26.41997480392456,50.144431524686674,1739502666.0956242,26.41997480392456,1.600936003455046,1739502666.0956278,26.41997480392456,50.574991743730806,1739502666.0956311,26.41997480392456,51.78722088929976,1739502666.0956326,26.41997480392456,4.760147650668804,1739502666.0956347,26.41997480392456,1.0912772072065857,1739502666.0956361,26.41997480392456,0.9963331965920571,1739502666.095638,26.41997480392456,0.5955388810755085,1739502666.0956392,26.41997480392456,1.1266224501193647,1739502666.0956414,26.41997480392456,0.0,1739502666.0956428,26.41997480392456,0.07271954936247726,1739502666.0956447,26.41997480392456,0.8076860798448141,1739502666.0956461,26.41997480392456,1.0539029007568874 +1739502666.1149328,26.439974784851074,50.144431524686674,1739502666.114936,26.439974784851074,1.600936003455046,1739502666.11494,26.439974784851074,50.574991743730806,1739502666.1149435,26.439974784851074,51.78722088929976,1739502666.114945,26.439974784851074,4.760147650668804,1739502666.114947,26.439974784851074,1.0912772072065857,1739502666.1149487,26.439974784851074,0.9963331965920571,1739502666.1149507,26.439974784851074,0.5955388810755085,1739502666.114952,26.439974784851074,1.1266224501193647,1739502666.114954,26.439974784851074,0.0,1739502666.1149557,26.439974784851074,0.07271954936247726,1739502666.1149573,26.439974784851074,0.8076860798448141,1739502666.114959,26.439974784851074,1.0539029007568874 +1739502666.1348634,26.459974765777588,50.144431524686674,1739502666.1348667,26.459974765777588,1.600936003455046,1739502666.1348705,26.459974765777588,50.574991743730806,1739502666.1348739,26.459974765777588,51.78722088929976,1739502666.1348755,26.459974765777588,4.760147650668804,1739502666.1348777,26.459974765777588,1.0912772072065857,1739502666.1348794,26.459974765777588,0.9963331965920571,1739502666.1348808,26.459974765777588,0.5955388810755085,1739502666.1348822,26.459974765777588,1.1266224501193647,1739502666.1348846,26.459974765777588,0.0,1739502666.1348858,26.459974765777588,0.07271954936247726,1739502666.1348877,26.459974765777588,0.8076860798448141,1739502666.1348894,26.459974765777588,1.0539029007568874 +1739502666.1554687,26.4799747467041,50.22381918923415,1739502666.1554716,26.4799747467041,1.6860596163655002,1739502666.1554754,26.4799747467041,50.88394490356246,1739502666.1554785,26.4799747467041,51.73626100749219,1739502666.1554801,26.4799747467041,5.082479145781805,1739502666.155482,26.4799747467041,1.1518538102496951,1739502666.1554837,26.4799747467041,1.1574164470322914,1739502666.1554854,26.4799747467041,0.6108,1739502666.155487,26.4799747467041,0.9904039133753775,1739502666.1554887,26.4799747467041,0.0,1739502666.1554904,26.4799747467041,-0.13812342625485546,1739502666.1554918,26.4799747467041,0.8352877687873621,1739502666.1554937,26.4799747467041,1.062638866549967 +1739502666.1748714,26.499974727630615,50.22381918923415,1739502666.1748743,26.499974727630615,1.6860596163655002,1739502666.1748784,26.499974727630615,50.88394490356246,1739502666.1748817,26.499974727630615,51.73626100749219,1739502666.1748836,26.499974727630615,5.082479145781805,1739502666.1748857,26.499974727630615,1.1518538102496951,1739502666.1748874,26.499974727630615,1.1574164470322914,1739502666.1748888,26.499974727630615,0.6108,1739502666.1748905,26.499974727630615,0.9904039133753775,1739502666.1748924,26.499974727630615,0.0,1739502666.1748943,26.499974727630615,-0.07223495317458961,1739502666.1748962,26.499974727630615,0.8352877687873621,1739502666.1748977,26.499974727630615,1.062638866549967 +1739502666.1951578,26.51997470855713,50.22381918923415,1739502666.1951604,26.51997470855713,1.6860596163655002,1739502666.195164,26.51997470855713,50.88394490356246,1739502666.1951673,26.51997470855713,51.73626100749219,1739502666.1951687,26.51997470855713,5.082479145781805,1739502666.1951709,26.51997470855713,1.1518538102496951,1739502666.1951725,26.51997470855713,1.1574164470322914,1739502666.1951742,26.51997470855713,0.6108,1739502666.1951756,26.51997470855713,0.9904039133753775,1739502666.1951778,26.51997470855713,0.0,1739502666.1951792,26.51997470855713,-0.07223495317458961,1739502666.1951811,26.51997470855713,0.8352877687873621,1739502666.1951826,26.51997470855713,1.062638866549967 +1739502666.2148776,26.539974689483643,50.22381918923415,1739502666.214881,26.539974689483643,1.6860596163655002,1739502666.2148845,26.539974689483643,50.88394490356246,1739502666.2148879,26.539974689483643,51.73626100749219,1739502666.2148898,26.539974689483643,5.082479145781805,1739502666.2148921,26.539974689483643,1.1518538102496951,1739502666.2148936,26.539974689483643,1.1574164470322914,1739502666.2148952,26.539974689483643,0.6108,1739502666.214897,26.539974689483643,0.9904039133753775,1739502666.2148986,26.539974689483643,0.0,1739502666.2149003,26.539974689483643,-0.07223495317458961,1739502666.214902,26.539974689483643,0.8352877687873621,1739502666.2149038,26.539974689483643,1.062638866549967 +1739502666.23488,26.559974670410156,50.22381918923415,1739502666.2348833,26.559974670410156,1.6860596163655002,1739502666.234887,26.559974670410156,50.88394490356246,1739502666.2348905,26.559974670410156,51.73626100749219,1739502666.2348924,26.559974670410156,5.082479145781805,1739502666.2348943,26.559974670410156,1.1518538102496951,1739502666.234896,26.559974670410156,1.1574164470322914,1739502666.2348976,26.559974670410156,0.6108,1739502666.2348993,26.559974670410156,0.9904039133753775,1739502666.2349012,26.559974670410156,0.0,1739502666.2349029,26.559974670410156,-0.07223495317458961,1739502666.2349043,26.559974670410156,0.8352877687873621,1739502666.2349062,26.559974670410156,1.062638866549967 +1739502666.2551973,26.57997465133667,50.3009130074523,1739502666.2552,26.57997465133667,1.7734323516627946,1739502666.2552032,26.57997465133667,50.962621913420115,1739502666.2552066,26.57997465133667,51.72447647740513,1739502666.2552083,26.57997465133667,5.144457044758174,1739502666.2552102,26.57997465133667,1.1712199245122188,1739502666.2552118,26.57997465133667,1.1104757603897903,1739502666.2552135,26.57997465133667,0.6108,1739502666.2552152,26.57997465133667,1.028303260034236,1739502666.2552168,26.57997465133667,0.0,1739502666.2552185,26.57997465133667,-0.005771376147793512,1739502666.25522,26.57997465133667,0.8628894577299101,1739502666.2552218,26.57997465133667,1.0548445176206989 +1739502666.2748723,26.599974632263184,50.3009130074523,1739502666.2748756,26.599974632263184,1.7734323516627946,1739502666.2748795,26.599974632263184,50.962621913420115,1739502666.2748828,26.599974632263184,51.72447647740513,1739502666.2748847,26.599974632263184,5.144457044758174,1739502666.2748866,26.599974632263184,1.1712199245122188,1739502666.2748883,26.599974632263184,1.1104757603897903,1739502666.27489,26.599974632263184,0.6108,1739502666.2748916,26.599974632263184,1.028303260034236,1739502666.2748933,26.599974632263184,0.0,1739502666.274895,26.599974632263184,-0.026541257586462752,1739502666.2748966,26.599974632263184,0.8628894577299101,1739502666.2748983,26.599974632263184,1.0548445176206989 +1739502666.2952154,26.619974613189697,50.3009130074523,1739502666.295218,26.619974613189697,1.7734323516627946,1739502666.2952216,26.619974613189697,50.962621913420115,1739502666.295225,26.619974613189697,51.72447647740513,1739502666.2952266,26.619974613189697,5.144457044758174,1739502666.2952287,26.619974613189697,1.1712199245122188,1739502666.2952302,26.619974613189697,1.1104757603897903,1739502666.2952318,26.619974613189697,0.6108,1739502666.2952332,26.619974613189697,1.028303260034236,1739502666.2952352,26.619974613189697,0.0,1739502666.2952366,26.619974613189697,-0.026541257586462752,1739502666.2952385,26.619974613189697,0.8628894577299101,1739502666.29524,26.619974613189697,1.0548445176206989 +1739502666.3150043,26.63997459411621,50.3009130074523,1739502666.3150077,26.63997459411621,1.7734323516627946,1739502666.3150113,26.63997459411621,50.962621913420115,1739502666.3150146,26.63997459411621,51.72447647740513,1739502666.3150165,26.63997459411621,5.144457044758174,1739502666.3150182,26.63997459411621,1.1712199245122188,1739502666.31502,26.63997459411621,1.1104757603897903,1739502666.3150218,26.63997459411621,0.6108,1739502666.3150234,26.63997459411621,1.028303260034236,1739502666.315025,26.63997459411621,0.0,1739502666.3150268,26.63997459411621,-0.026541257586462752,1739502666.3150284,26.63997459411621,0.8628894577299101,1739502666.31503,26.63997459411621,1.0548445176206989 +1739502666.3348932,26.659974575042725,50.3009130074523,1739502666.3348966,26.659974575042725,1.7734323516627946,1739502666.3349004,26.659974575042725,50.962621913420115,1739502666.3349035,26.659974575042725,51.72447647740513,1739502666.3349054,26.659974575042725,5.144457044758174,1739502666.3349073,26.659974575042725,1.1712199245122188,1739502666.334909,26.659974575042725,1.1104757603897903,1739502666.3349106,26.659974575042725,0.6108,1739502666.3349123,26.659974575042725,1.028303260034236,1739502666.334914,26.659974575042725,0.0,1739502666.3349156,26.659974575042725,-0.026541257586462752,1739502666.3349173,26.659974575042725,0.8628894577299101,1739502666.334919,26.659974575042725,1.0548445176206989 +1739502666.3548656,26.67997455596924,50.3009130074523,1739502666.3548682,26.67997455596924,1.7734323516627946,1739502666.3548717,26.67997455596924,50.962621913420115,1739502666.354875,26.67997455596924,51.72447647740513,1739502666.3548768,26.67997455596924,5.144457044758174,1739502666.3548787,26.67997455596924,1.1712199245122188,1739502666.3548803,26.67997455596924,1.1104757603897903,1739502666.3548818,26.67997455596924,0.6108,1739502666.3548834,26.67997455596924,1.028303260034236,1739502666.354885,26.67997455596924,0.0,1739502666.3548868,26.67997455596924,-0.026541257586462752,1739502666.3548884,26.67997455596924,0.8628894577299101,1739502666.3548903,26.67997455596924,1.0548445176206989 +1739502666.3935175,26.70997452735901,50.375180971341145,1739502666.3935215,26.70997452735901,1.8624401832373723,1739502666.3935268,26.70997452735901,51.095716827134,1739502666.3935325,26.70997452735901,51.69656511163945,1739502666.3935354,26.70997452735901,5.269464205223597,1739502666.3935394,26.70997452735901,1.2008154537082234,1739502666.3935428,26.70997452735901,1.1159026803606162,1739502666.3935456,26.70997452735901,0.6108,1739502666.393549,26.70997452735901,1.0238485216366437,1739502666.3935523,26.70997452735901,0.0,1739502666.3935556,26.70997452735901,-0.02938948423734491,1739502666.393559,26.70997452735901,0.8904911466724581,1739502666.3935626,26.70997452735901,1.0523479344620117 +1739502666.412824,26.729974508285522,50.375180971341145,1739502666.412828,26.729974508285522,1.8624401832373723,1739502666.4128325,26.729974508285522,51.095716827134,1739502666.4128377,26.729974508285522,51.69656511163945,1739502666.4128404,26.729974508285522,5.269464205223597,1739502666.4128447,26.729974508285522,1.2008154537082234,1739502666.4128478,26.729974508285522,1.1159026803606162,1739502666.4128516,26.729974508285522,0.6108,1739502666.4128547,26.729974508285522,1.0238485216366437,1739502666.4128585,26.729974508285522,0.0,1739502666.4128616,26.729974508285522,-0.028499412825367942,1739502666.4128656,26.729974508285522,0.8904911466724581,1739502666.412869,26.729974508285522,1.0523479344620117 +1739502666.4305174,26.749974489212036,50.375180971341145,1739502666.4305198,26.749974489212036,1.8624401832373723,1739502666.4305227,26.749974489212036,51.095716827134,1739502666.4305255,26.749974489212036,51.69656511163945,1739502666.4305267,26.749974489212036,5.269464205223597,1739502666.4305282,26.749974489212036,1.2008154537082234,1739502666.4305298,26.749974489212036,1.1159026803606162,1739502666.430531,26.749974489212036,0.6108,1739502666.4305325,26.749974489212036,1.0238485216366437,1739502666.430534,26.749974489212036,0.0,1739502666.430535,26.749974489212036,-0.028499412825367942,1739502666.4305365,26.749974489212036,0.8904911466724581,1739502666.430538,26.749974489212036,1.0523479344620117 +1739502666.4505405,26.76997447013855,50.375180971341145,1739502666.4505436,26.76997447013855,1.8624401832373723,1739502666.4505467,26.76997447013855,51.095716827134,1739502666.4505494,26.76997447013855,51.69656511163945,1739502666.4505506,26.76997447013855,5.269464205223597,1739502666.4505522,26.76997447013855,1.2008154537082234,1739502666.4505537,26.76997447013855,1.1159026803606162,1739502666.450555,26.76997447013855,0.6108,1739502666.450557,26.76997447013855,1.0238485216366437,1739502666.4505584,26.76997447013855,0.0,1739502666.4505599,26.76997447013855,-0.028499412825367942,1739502666.450561,26.76997447013855,0.8904911466724581,1739502666.4505625,26.76997447013855,1.0523479344620117 +1739502666.470259,26.789974451065063,50.375180971341145,1739502666.4702613,26.789974451065063,1.8624401832373723,1739502666.470264,26.789974451065063,51.095716827134,1739502666.4702666,26.789974451065063,51.69656511163945,1739502666.470268,26.789974451065063,5.269464205223597,1739502666.4702694,26.789974451065063,1.2008154537082234,1739502666.4702709,26.789974451065063,1.1159026803606162,1739502666.4702723,26.789974451065063,0.6108,1739502666.4702737,26.789974451065063,1.0238485216366437,1739502666.4702754,26.789974451065063,0.0,1739502666.4702766,26.789974451065063,-0.028499412825367942,1739502666.4702783,26.789974451065063,0.8904911466724581,1739502666.4702795,26.789974451065063,1.0523479344620117 +1739502666.4906576,26.809974431991577,50.44676490348642,1739502666.4906602,26.809974431991577,1.9532108640644354,1739502666.490663,26.809974431991577,51.24805154149173,1739502666.490666,26.809974431991577,51.66052321709311,1739502666.4906673,26.809974431991577,5.411081537325255,1739502666.490669,26.809974431991577,1.2332191483352095,1739502666.4906704,26.809974431991577,1.1358267654969445,1739502666.4906719,26.809974431991577,0.6108,1739502666.4906733,26.809974431991577,1.0076584968885036,1739502666.490675,26.809974431991577,0.0,1739502666.4906762,26.809974431991577,-0.047540751780248115,1739502666.4906778,26.809974431991577,0.9180928356150061,1739502666.490679,26.809974431991577,1.0492488263439508 +1739502666.5114243,26.82997441291809,50.44676490348642,1739502666.5114272,26.82997441291809,1.9532108640644354,1739502666.5114305,26.82997441291809,51.24805154149173,1739502666.5114331,26.82997441291809,51.66052321709311,1739502666.5114346,26.82997441291809,5.411081537325255,1739502666.5114362,26.82997441291809,1.2332191483352095,1739502666.5114377,26.82997441291809,1.1358267654969445,1739502666.5114388,26.82997441291809,0.6108,1739502666.5114403,26.82997441291809,1.0076584968885036,1739502666.511442,26.82997441291809,0.0,1739502666.5114431,26.82997441291809,-0.04159032945544716,1739502666.5114446,26.82997441291809,0.9180928356150061,1739502666.511446,26.82997441291809,1.0492488263439508 +1739502666.5311584,26.849974393844604,50.44676490348642,1739502666.531161,26.849974393844604,1.9532108640644354,1739502666.531164,26.849974393844604,51.24805154149173,1739502666.5311668,26.849974393844604,51.66052321709311,1739502666.531168,26.849974393844604,5.411081537325255,1739502666.53117,26.849974393844604,1.2332191483352095,1739502666.5311713,26.849974393844604,1.1358267654969445,1739502666.5311725,26.849974393844604,0.6108,1739502666.531174,26.849974393844604,1.0076584968885036,1739502666.5311754,26.849974393844604,0.0,1739502666.531177,26.849974393844604,-0.04159032945544716,1739502666.5311782,26.849974393844604,0.9180928356150061,1739502666.5311797,26.849974393844604,1.0492488263439508 +1739502666.5516083,26.869974374771118,50.44676490348642,1739502666.5516112,26.869974374771118,1.9532108640644354,1739502666.5516145,26.869974374771118,51.24805154149173,1739502666.5516174,26.869974374771118,51.66052321709311,1739502666.5516188,26.869974374771118,5.411081537325255,1739502666.5516207,26.869974374771118,1.2332191483352095,1739502666.5516222,26.869974374771118,1.1358267654969445,1739502666.5516236,26.869974374771118,0.6108,1739502666.551625,26.869974374771118,1.0076584968885036,1739502666.5516264,26.869974374771118,0.0,1739502666.551628,26.869974374771118,-0.04159032945544716,1739502666.5516293,26.869974374771118,0.9180928356150061,1739502666.5516307,26.869974374771118,1.0492488263439508 +1739502666.570504,26.889974355697632,50.44676490348642,1739502666.5705085,26.889974355697632,1.9532108640644354,1739502666.5705142,26.889974355697632,51.24805154149173,1739502666.5705185,26.889974355697632,51.66052321709311,1739502666.5705209,26.889974355697632,5.411081537325255,1739502666.570524,26.889974355697632,1.2332191483352095,1739502666.570526,26.889974355697632,1.1358267654969445,1739502666.5705283,26.889974355697632,0.6108,1739502666.5705307,26.889974355697632,1.0076584968885036,1739502666.5705333,26.889974355697632,0.0,1739502666.5705354,26.889974355697632,-0.04159032945544716,1739502666.570538,26.889974355697632,0.9180928356150061,1739502666.5705402,26.889974355697632,1.0492488263439508 +1739502666.5902143,26.909974336624146,50.515570507517864,1739502666.5902164,26.909974336624146,2.045591690671431,1739502666.5902193,26.909974336624146,51.33865184766837,1739502666.5902221,26.909974336624146,51.638693556213056,1739502666.5902233,26.909974336624146,5.48960817381645,1739502666.5902252,26.909974336624146,1.255562154450074,1739502666.5902264,26.909974336624146,1.104624503938603,1739502666.5902276,26.909974336624146,0.6108,1739502666.590229,26.909974336624146,1.0331280364932687,1739502666.5902305,26.909974336624146,0.0,1739502666.590232,26.909974336624146,0.002066997683778325,1739502666.590233,26.909974336624146,0.9456945245575541,1739502666.5902345,26.909974336624146,1.0447039624854961 +1739502666.610229,26.92997431755066,50.515570507517864,1739502666.6102314,26.92997431755066,2.045591690671431,1739502666.610234,26.92997431755066,51.33865184766837,1739502666.610237,26.92997431755066,51.638693556213056,1739502666.6102383,26.92997431755066,5.48960817381645,1739502666.61024,26.92997431755066,1.255562154450074,1739502666.6102412,26.92997431755066,1.104624503938603,1739502666.6102428,26.92997431755066,0.6108,1739502666.610244,26.92997431755066,1.0331280364932687,1739502666.6102457,26.92997431755066,0.0,1739502666.610247,26.92997431755066,-0.011575925992227454,1739502666.610248,26.92997431755066,0.9456945245575541,1739502666.6102498,26.92997431755066,1.0447039624854961 +1739502666.6307843,26.949974298477173,50.515570507517864,1739502666.6307874,26.949974298477173,2.045591690671431,1739502666.630791,26.949974298477173,51.33865184766837,1739502666.6307945,26.949974298477173,51.638693556213056,1739502666.630796,26.949974298477173,5.48960817381645,1739502666.630798,26.949974298477173,1.255562154450074,1739502666.6307998,26.949974298477173,1.104624503938603,1739502666.6308017,26.949974298477173,0.6108,1739502666.630803,26.949974298477173,1.0331280364932687,1739502666.6308053,26.949974298477173,0.0,1739502666.6308067,26.949974298477173,-0.011575925992227454,1739502666.6308086,26.949974298477173,0.9456945245575541,1739502666.63081,26.949974298477173,1.0447039624854961 +1739502666.6534421,26.969974279403687,50.515570507517864,1739502666.6534457,26.969974279403687,2.045591690671431,1739502666.6534505,26.969974279403687,51.33865184766837,1739502666.6534548,26.969974279403687,51.638693556213056,1739502666.653457,26.969974279403687,5.48960817381645,1739502666.6534598,26.969974279403687,1.255562154450074,1739502666.6534617,26.969974279403687,1.104624503938603,1739502666.6534643,26.969974279403687,0.6108,1739502666.6534662,26.969974279403687,1.0331280364932687,1739502666.6534684,26.969974279403687,0.0,1739502666.6534705,26.969974279403687,-0.011575925992227454,1739502666.6534724,26.969974279403687,0.9456945245575541,1739502666.6534748,26.969974279403687,1.0447039624854961 +1739502666.6718698,26.9899742603302,50.515570507517864,1739502666.6718733,26.9899742603302,2.045591690671431,1739502666.6718779,26.9899742603302,51.33865184766837,1739502666.671882,26.9899742603302,51.638693556213056,1739502666.6718838,26.9899742603302,5.48960817381645,1739502666.6718864,26.9899742603302,1.255562154450074,1739502666.6718884,26.9899742603302,1.104624503938603,1739502666.6718905,26.9899742603302,0.6108,1739502666.6718922,26.9899742603302,1.0331280364932687,1739502666.6718946,26.9899742603302,0.0,1739502666.6718965,26.9899742603302,-0.011575925992227454,1739502666.6718986,26.9899742603302,0.9456945245575541,1739502666.671901,26.9899742603302,1.0447039624854961 +1739502666.6930604,27.009974241256714,50.515570507517864,1739502666.6930654,27.009974241256714,2.045591690671431,1739502666.6930726,27.009974241256714,51.33865184766837,1739502666.6930807,27.009974241256714,51.638693556213056,1739502666.6930852,27.009974241256714,5.48960817381645,1739502666.693091,27.009974241256714,1.255562154450074,1739502666.6930962,27.009974241256714,1.104624503938603,1739502666.6931014,27.009974241256714,0.6108,1739502666.6931067,27.009974241256714,1.0331280364932687,1739502666.6931121,27.009974241256714,0.0,1739502666.6931174,27.009974241256714,-0.011575925992227454,1739502666.6931226,27.009974241256714,0.9456945245575541,1739502666.6931279,27.009974241256714,1.0447039624854961 +1739502666.7121894,27.029974222183228,50.58161993948238,1739502666.7121928,27.029974222183228,2.1395810405074274,1739502666.7121973,27.029974222183228,51.49154892227132,1739502666.7122014,27.029974222183228,51.59300027208146,1739502666.7122037,27.029974222183228,5.633418564924786,1739502666.7122066,27.029974222183228,1.2890227924947104,1739502666.7122087,27.029974222183228,1.1294010549652358,1739502666.7122107,27.029974222183228,0.6108,1739502666.7122128,27.029974222183228,1.0128517710956586,1739502666.712215,27.029974222183228,0.0,1739502666.712217,27.029974222183228,-0.03961730700556462,1739502666.7122195,27.029974222183228,0.9732962135001021,1739502666.7122216,27.029974222183228,1.043706140789126 +1739502666.731329,27.04997420310974,50.58161993948238,1739502666.7313325,27.04997420310974,2.1395810405074274,1739502666.7313366,27.04997420310974,51.49154892227132,1739502666.7313411,27.04997420310974,51.59300027208146,1739502666.731343,27.04997420310974,5.633418564924786,1739502666.7313457,27.04997420310974,1.2890227924947104,1739502666.7313478,27.04997420310974,1.1294010549652358,1739502666.7313497,27.04997420310974,0.6108,1739502666.7313516,27.04997420310974,1.0128517710956586,1739502666.7313538,27.04997420310974,0.0,1739502666.731356,27.04997420310974,-0.03085436969346733,1739502666.731358,27.04997420310974,0.9732962135001021,1739502666.7313604,27.04997420310974,1.043706140789126 +1739502666.7515554,27.069974184036255,50.58161993948238,1739502666.751559,27.069974184036255,2.1395810405074274,1739502666.751563,27.069974184036255,51.49154892227132,1739502666.7515674,27.069974184036255,51.59300027208146,1739502666.7515695,27.069974184036255,5.633418564924786,1739502666.751572,27.069974184036255,1.2890227924947104,1739502666.751574,27.069974184036255,1.1294010549652358,1739502666.751576,27.069974184036255,0.6108,1739502666.751578,27.069974184036255,1.0128517710956586,1739502666.7515805,27.069974184036255,0.0,1739502666.7515824,27.069974184036255,-0.03085436969346733,1739502666.7515845,27.069974184036255,0.9732962135001021,1739502666.7515867,27.069974184036255,1.043706140789126 +1739502666.773944,27.08997416496277,50.58161993948238,1739502666.7739491,27.08997416496277,2.1395810405074274,1739502666.7739563,27.08997416496277,51.49154892227132,1739502666.7739644,27.08997416496277,51.59300027208146,1739502666.773969,27.08997416496277,5.633418564924786,1739502666.773975,27.08997416496277,1.2890227924947104,1739502666.77398,27.08997416496277,1.1294010549652358,1739502666.773985,27.08997416496277,0.6108,1739502666.7739904,27.08997416496277,1.0128517710956586,1739502666.7739959,27.08997416496277,0.0,1739502666.774001,27.08997416496277,-0.03085436969346733,1739502666.7740064,27.08997416496277,0.9732962135001021,1739502666.7740116,27.08997416496277,1.043706140789126 +1739502666.7911863,27.109974145889282,50.58161993948238,1739502666.79119,27.109974145889282,2.1395810405074274,1739502666.7911944,27.109974145889282,51.49154892227132,1739502666.7911985,27.109974145889282,51.59300027208146,1739502666.7912004,27.109974145889282,5.633418564924786,1739502666.7912028,27.109974145889282,1.2890227924947104,1739502666.7912052,27.109974145889282,1.1294010549652358,1739502666.791207,27.109974145889282,0.6108,1739502666.791209,27.109974145889282,1.0128517710956586,1739502666.7912114,27.109974145889282,0.0,1739502666.7912133,27.109974145889282,-0.03085436969346733,1739502666.7912154,27.109974145889282,0.9732962135001021,1739502666.7912176,27.109974145889282,1.043706140789126 +1739502666.8130856,27.129974126815796,50.64491993074157,1739502666.8130908,27.129974126815796,2.2351595298064924,1739502666.813098,27.129974126815796,51.64210091236253,1739502666.8131065,27.129974126815796,51.54426888948229,1739502666.813111,27.129974126815796,5.768717934939669,1739502666.8131168,27.129974126815796,1.3215713673638954,1739502666.813122,27.129974126815796,1.1493071157052523,1739502666.8131273,27.129974126815796,0.6108,1739502666.8131325,27.129974126815796,0.9968500109685942,1739502666.8131378,27.129974126815796,0.0,1739502666.813143,27.129974126815796,-0.04923647935475777,1739502666.8131485,27.129974126815796,1.00089790244265,1739502666.8131537,27.129974126815796,1.040342077287868 +1739502666.8318918,27.14997410774231,50.64491993074157,1739502666.831895,27.14997410774231,2.2351595298064924,1739502666.8318994,27.14997410774231,51.64210091236253,1739502666.8319037,27.14997410774231,51.54426888948229,1739502666.8319058,27.14997410774231,5.768717934939669,1739502666.8319087,27.14997410774231,1.3215713673638954,1739502666.8319106,27.14997410774231,1.1493071157052523,1739502666.8319125,27.14997410774231,0.6108,1739502666.8319144,27.14997410774231,0.9968500109685942,1739502666.8319168,27.14997410774231,0.0,1739502666.831919,27.14997410774231,-0.043492066319273825,1739502666.831921,27.14997410774231,1.00089790244265,1739502666.8319235,27.14997410774231,1.040342077287868 +1739502666.8514912,27.169974088668823,50.64491993074157,1739502666.851495,27.169974088668823,2.2351595298064924,1739502666.8514993,27.169974088668823,51.64210091236253,1739502666.8515031,27.169974088668823,51.54426888948229,1739502666.851505,27.169974088668823,5.768717934939669,1739502666.8515077,27.169974088668823,1.3215713673638954,1739502666.8515098,27.169974088668823,1.1493071157052523,1739502666.8515117,27.169974088668823,0.6108,1739502666.8515139,27.169974088668823,0.9968500109685942,1739502666.8515162,27.169974088668823,0.0,1739502666.8515184,27.169974088668823,-0.043492066319273825,1739502666.8515205,27.169974088668823,1.00089790244265,1739502666.8515224,27.169974088668823,1.040342077287868 +1739502666.8732295,27.189974069595337,50.64491993074157,1739502666.873233,27.189974069595337,2.2351595298064924,1739502666.8732376,27.189974069595337,51.64210091236253,1739502666.8732417,27.189974069595337,51.54426888948229,1739502666.8732433,27.189974069595337,5.768717934939669,1739502666.8732462,27.189974069595337,1.3215713673638954,1739502666.8732483,27.189974069595337,1.1493071157052523,1739502666.8732502,27.189974069595337,0.6108,1739502666.8732522,27.189974069595337,0.9968500109685942,1739502666.8732543,27.189974069595337,0.0,1739502666.8732564,27.189974069595337,-0.043492066319273825,1739502666.8732586,27.189974069595337,1.00089790244265,1739502666.8732605,27.189974069595337,1.040342077287868 +1739502666.8925266,27.20997405052185,50.64491993074157,1739502666.8925302,27.20997405052185,2.2351595298064924,1739502666.8925343,27.20997405052185,51.64210091236253,1739502666.8925383,27.20997405052185,51.54426888948229,1739502666.8925405,27.20997405052185,5.768717934939669,1739502666.8925428,27.20997405052185,1.3215713673638954,1739502666.8925447,27.20997405052185,1.1493071157052523,1739502666.8925474,27.20997405052185,0.6108,1739502666.892549,27.20997405052185,0.9968500109685942,1739502666.8925514,27.20997405052185,0.0,1739502666.8925536,27.20997405052185,-0.043492066319273825,1739502666.8925555,27.20997405052185,1.00089790244265,1739502666.8925576,27.20997405052185,1.040342077287868 +1739502666.9110572,27.229974031448364,50.64491993074157,1739502666.911061,27.229974031448364,2.2351595298064924,1739502666.911065,27.229974031448364,51.64210091236253,1739502666.9110687,27.229974031448364,51.54426888948229,1739502666.9110708,27.229974031448364,5.768717934939669,1739502666.911073,27.229974031448364,1.3215713673638954,1739502666.911075,27.229974031448364,1.1493071157052523,1739502666.9110768,27.229974031448364,0.6108,1739502666.9110787,27.229974031448364,0.9968500109685942,1739502666.9110806,27.229974031448364,0.0,1739502666.9110827,27.229974031448364,-0.043492066319273825,1739502666.9110851,27.229974031448364,1.00089790244265,1739502666.9110873,27.229974031448364,1.040342077287868 +1739502666.9308195,27.249974012374878,50.70531779948901,1739502666.9308224,27.249974012374878,2.332062505839323,1739502666.9308255,27.249974012374878,51.70990539250868,1739502666.9308283,27.249974012374878,51.523210577539324,1739502666.9308298,27.249974012374878,5.822803511725583,1739502666.9308317,27.249974012374878,1.340644533037631,1739502666.9308329,27.249974012374878,1.101041273253449,1739502666.9308345,27.249974012374878,0.6108,1739502666.9308357,27.249974012374878,1.0360938341829227,1739502666.930838,27.249974012374878,0.0,1739502666.9308393,27.249974012374878,0.020690024888245187,1739502666.9308405,27.249974012374878,1.0284995913851993,1739502666.9308422,27.249974012374878,1.0354607259473665 +1739502666.9507499,27.26997399330139,50.70531779948901,1739502666.950753,27.26997399330139,2.332062505839323,1739502666.950756,27.26997399330139,51.70990539250868,1739502666.950759,27.26997399330139,51.523210577539324,1739502666.9507604,27.26997399330139,5.822803511725583,1739502666.950762,27.26997399330139,1.340644533037631,1739502666.9507635,27.26997399330139,1.101041273253449,1739502666.9507651,27.26997399330139,0.6108,1739502666.9507663,27.26997399330139,1.0360938341829227,1739502666.9507678,27.26997399330139,0.0,1739502666.9507694,27.26997399330139,0.000633108235556179,1739502666.9507709,27.26997399330139,1.0284995913851993,1739502666.9507723,27.26997399330139,1.0354607259473665 +1739502666.970776,27.289973974227905,50.70531779948901,1739502666.9707787,27.289973974227905,2.332062505839323,1739502666.9707813,27.289973974227905,51.70990539250868,1739502666.9707842,27.289973974227905,51.523210577539324,1739502666.9707856,27.289973974227905,5.822803511725583,1739502666.9707873,27.289973974227905,1.340644533037631,1739502666.970789,27.289973974227905,1.101041273253449,1739502666.9707904,27.289973974227905,0.6108,1739502666.9707916,27.289973974227905,1.0360938341829227,1739502666.9707932,27.289973974227905,0.0,1739502666.9707944,27.289973974227905,0.000633108235556179,1739502666.970796,27.289973974227905,1.0284995913851993,1739502666.9707973,27.289973974227905,1.0354607259473665 +1739502666.9905775,27.30997395515442,50.70531779948901,1739502666.9905803,27.30997395515442,2.332062505839323,1739502666.9905832,27.30997395515442,51.70990539250868,1739502666.990586,27.30997395515442,51.523210577539324,1739502666.9905875,27.30997395515442,5.822803511725583,1739502666.9905891,27.30997395515442,1.340644533037631,1739502666.9905908,27.30997395515442,1.101041273253449,1739502666.990592,27.30997395515442,0.6108,1739502666.9905932,27.30997395515442,1.0360938341829227,1739502666.9905949,27.30997395515442,0.0,1739502666.990596,27.30997395515442,0.000633108235556179,1739502666.990598,27.30997395515442,1.0284995913851993,1739502666.9905992,27.30997395515442,1.0354607259473665 +1739502667.010492,27.329973936080933,50.70531779948901,1739502667.0104947,27.329973936080933,2.332062505839323,1739502667.0104978,27.329973936080933,51.70990539250868,1739502667.0105007,27.329973936080933,51.523210577539324,1739502667.0105019,27.329973936080933,5.822803511725583,1739502667.0105038,27.329973936080933,1.340644533037631,1739502667.0105052,27.329973936080933,1.101041273253449,1739502667.0105069,27.329973936080933,0.6108,1739502667.0105083,27.329973936080933,1.0360938341829227,1739502667.0105097,27.329973936080933,0.0,1739502667.010511,27.329973936080933,0.000633108235556179,1739502667.0105124,27.329973936080933,1.0284995913851993,1739502667.010514,27.329973936080933,1.0354607259473665 +1739502667.0310323,27.349973917007446,50.76286888730258,1739502667.0310352,27.349973917007446,2.4303428052262124,1739502667.031038,27.349973917007446,51.89838380774463,1739502667.0310404,27.349973917007446,51.453491024818234,1739502667.031042,27.349973917007446,5.9979733270526525,1739502667.0310438,27.349973917007446,1.379581336227799,1739502667.0310452,27.349973917007446,1.155088309988938,1739502667.0310464,27.349973917007446,0.6108,1739502667.0310478,27.349973917007446,0.9922502691001882,1739502667.0310497,27.349973917007446,0.0,1739502667.031051,27.349973917007446,-0.06318797705534847,1739502667.0310526,27.349973917007446,1.0561012803277485,1739502667.0310538,27.349973917007446,1.0354941439257566 +1739502667.051025,27.36997389793396,50.76286888730258,1739502667.0510275,27.36997389793396,2.4303428052262124,1739502667.0510302,27.36997389793396,51.89838380774463,1739502667.0510328,27.36997389793396,51.453491024818234,1739502667.0510345,27.36997389793396,5.9979733270526525,1739502667.051036,27.36997389793396,1.379581336227799,1739502667.0510375,27.36997389793396,1.155088309988938,1739502667.0510387,27.36997389793396,0.6108,1739502667.05104,27.36997389793396,0.9922502691001882,1739502667.0510418,27.36997389793396,0.0,1739502667.051043,27.36997389793396,-0.04324387482556835,1739502667.0510447,27.36997389793396,1.0561012803277485,1739502667.0510461,27.36997389793396,1.0354941439257566 +1739502667.0709527,27.389973878860474,50.76286888730258,1739502667.0709555,27.389973878860474,2.4303428052262124,1739502667.0709586,27.389973878860474,51.89838380774463,1739502667.0709615,27.389973878860474,51.453491024818234,1739502667.0709627,27.389973878860474,5.9979733270526525,1739502667.0709646,27.389973878860474,1.379581336227799,1739502667.070966,27.389973878860474,1.155088309988938,1739502667.0709674,27.389973878860474,0.6108,1739502667.070969,27.389973878860474,0.9922502691001882,1739502667.0709705,27.389973878860474,0.0,1739502667.070972,27.389973878860474,-0.04324387482556835,1739502667.0709732,27.389973878860474,1.0561012803277485,1739502667.0709748,27.389973878860474,1.0354941439257566 +1739502667.0905442,27.409973859786987,50.76286888730258,1739502667.0905466,27.409973859786987,2.4303428052262124,1739502667.0905497,27.409973859786987,51.89838380774463,1739502667.0905526,27.409973859786987,51.453491024818234,1739502667.090554,27.409973859786987,5.9979733270526525,1739502667.0905561,27.409973859786987,1.379581336227799,1739502667.0905578,27.409973859786987,1.155088309988938,1739502667.0905592,27.409973859786987,0.6108,1739502667.0905604,27.409973859786987,0.9922502691001882,1739502667.090562,27.409973859786987,0.0,1739502667.0905633,27.409973859786987,-0.04324387482556835,1739502667.090565,27.409973859786987,1.0561012803277485,1739502667.0905662,27.409973859786987,1.0354941439257566 +1739502667.1108925,27.4299738407135,50.76286888730258,1739502667.1108956,27.4299738407135,2.4303428052262124,1739502667.1108985,27.4299738407135,51.89838380774463,1739502667.1109014,27.4299738407135,51.453491024818234,1739502667.1109025,27.4299738407135,5.9979733270526525,1739502667.1109042,27.4299738407135,1.379581336227799,1739502667.110906,27.4299738407135,1.155088309988938,1739502667.110907,27.4299738407135,0.6108,1739502667.1109087,27.4299738407135,0.9922502691001882,1739502667.1109102,27.4299738407135,0.0,1739502667.1109114,27.4299738407135,-0.04324387482556835,1739502667.110913,27.4299738407135,1.0561012803277485,1739502667.1109145,27.4299738407135,1.0354941439257566 +1739502667.1304228,27.449973821640015,50.76286888730258,1739502667.1304255,27.449973821640015,2.4303428052262124,1739502667.130428,27.449973821640015,51.89838380774463,1739502667.130431,27.449973821640015,51.453491024818234,1739502667.1304324,27.449973821640015,5.9979733270526525,1739502667.1304338,27.449973821640015,1.379581336227799,1739502667.1304352,27.449973821640015,1.155088309988938,1739502667.1304367,27.449973821640015,0.6108,1739502667.1304379,27.449973821640015,0.9922502691001882,1739502667.1304398,27.449973821640015,0.0,1739502667.130441,27.449973821640015,-0.04324387482556835,1739502667.1304424,27.449973821640015,1.0561012803277485,1739502667.130444,27.449973821640015,1.0354941439257566 +1739502667.1507654,27.46997380256653,50.81755918070452,1739502667.150768,27.46997380256653,2.5299408103897436,1739502667.1507711,27.46997380256653,52.08962780718099,1739502667.150774,27.46997380256653,51.380805241440164,1739502667.150776,27.46997380256653,6.16367811481744,1739502667.1507773,27.46997380256653,1.417015517573807,1739502667.1507788,27.46997380256653,1.2030655636273369,1739502667.1507804,27.46997380256653,0.6108,1739502667.1507816,27.46997380256653,0.9548875262211166,1739502667.1507833,27.46997380256653,0.0,1739502667.1507845,27.46997380256653,-0.09011876726547859,1739502667.1507862,27.46997380256653,1.0837029692702977,1739502667.1507874,27.46997380256653,1.030357879994875 +1739502667.1711307,27.489973783493042,50.81755918070452,1739502667.1711333,27.489973783493042,2.5299408103897436,1739502667.171136,27.489973783493042,52.08962780718099,1739502667.1711385,27.489973783493042,51.380805241440164,1739502667.1711402,27.489973783493042,6.16367811481744,1739502667.1711419,27.489973783493042,1.417015517573807,1739502667.171143,27.489973783493042,1.2030655636273369,1739502667.1711447,27.489973783493042,0.6108,1739502667.171146,27.489973783493042,0.9548875262211166,1739502667.1711478,27.489973783493042,0.0,1739502667.171149,27.489973783493042,-0.07547035377375833,1739502667.1711507,27.489973783493042,1.0837029692702977,1739502667.1711519,27.489973783493042,1.030357879994875 +1739502667.1911244,27.509973764419556,50.81755918070452,1739502667.191127,27.509973764419556,2.5299408103897436,1739502667.19113,27.509973764419556,52.08962780718099,1739502667.1911328,27.509973764419556,51.380805241440164,1739502667.191134,27.509973764419556,6.16367811481744,1739502667.191136,27.509973764419556,1.417015517573807,1739502667.1911373,27.509973764419556,1.2030655636273369,1739502667.1911385,27.509973764419556,0.6108,1739502667.19114,27.509973764419556,0.9548875262211166,1739502667.1911416,27.509973764419556,0.0,1739502667.1911426,27.509973764419556,-0.07547035377375833,1739502667.1911445,27.509973764419556,1.0837029692702977,1739502667.1911457,27.509973764419556,1.030357879994875 +1739502667.2110238,27.52997374534607,50.81755918070452,1739502667.211027,27.52997374534607,2.5299408103897436,1739502667.2110298,27.52997374534607,52.08962780718099,1739502667.2110329,27.52997374534607,51.380805241440164,1739502667.211034,27.52997374534607,6.16367811481744,1739502667.2110357,27.52997374534607,1.417015517573807,1739502667.2110372,27.52997374534607,1.2030655636273369,1739502667.2110388,27.52997374534607,0.6108,1739502667.2110398,27.52997374534607,0.9548875262211166,1739502667.2110417,27.52997374534607,0.0,1739502667.2110431,27.52997374534607,-0.07547035377375833,1739502667.2110443,27.52997374534607,1.0837029692702977,1739502667.211046,27.52997374534607,1.030357879994875 +1739502667.2309139,27.549973726272583,50.81755918070452,1739502667.2309165,27.549973726272583,2.5299408103897436,1739502667.2309196,27.549973726272583,52.08962780718099,1739502667.2309227,27.549973726272583,51.380805241440164,1739502667.2309241,27.549973726272583,6.16367811481744,1739502667.2309258,27.549973726272583,1.417015517573807,1739502667.230927,27.549973726272583,1.2030655636273369,1739502667.2309287,27.549973726272583,0.6108,1739502667.2309299,27.549973726272583,0.9548875262211166,1739502667.2309315,27.549973726272583,0.0,1739502667.2309327,27.549973726272583,-0.07547035377375833,1739502667.2309344,27.549973726272583,1.0837029692702977,1739502667.2309356,27.549973726272583,1.030357879994875 +1739502667.2504683,27.569973707199097,50.86916246364028,1739502667.250471,27.569973707199097,2.6303903854838637,1739502667.250474,27.569973707199097,52.22236451519019,1739502667.2504768,27.569973707199097,51.329048441906465,1739502667.2504783,27.569973707199097,6.267770599533365,1739502667.2504802,27.569973707199097,1.4450303343649342,1739502667.2504816,27.569973707199097,1.2009653456121931,1739502667.250483,27.569973707199097,0.6108,1739502667.2504842,27.569973707199097,0.9564932523813796,1739502667.250486,27.569973707199097,0.0,1739502667.250488,27.569973707199097,-0.061149106141662524,1739502667.2504897,27.569973707199097,1.111304658212847,1739502667.2504911,27.569973707199097,1.0221177513423683 +1739502667.270781,27.58997368812561,50.86916246364028,1739502667.2707837,27.58997368812561,2.6303903854838637,1739502667.2707868,27.58997368812561,52.22236451519019,1739502667.2707896,27.58997368812561,51.329048441906465,1739502667.270791,27.58997368812561,6.267770599533365,1739502667.270793,27.58997368812561,1.4450303343649342,1739502667.2707944,27.58997368812561,1.2009653456121931,1739502667.270796,27.58997368812561,0.6108,1739502667.2707973,27.58997368812561,0.9564932523813796,1739502667.270799,27.58997368812561,0.0,1739502667.2708004,27.58997368812561,-0.06562449896098865,1739502667.2708018,27.58997368812561,1.111304658212847,1739502667.2708032,27.58997368812561,1.0221177513423683 +1739502667.2905629,27.609973669052124,50.86916246364028,1739502667.2905657,27.609973669052124,2.6303903854838637,1739502667.2905686,27.609973669052124,52.22236451519019,1739502667.2905717,27.609973669052124,51.329048441906465,1739502667.2905734,27.609973669052124,6.267770599533365,1739502667.2905748,27.609973669052124,1.4450303343649342,1739502667.2905765,27.609973669052124,1.2009653456121931,1739502667.2905777,27.609973669052124,0.6108,1739502667.2905788,27.609973669052124,0.9564932523813796,1739502667.2905805,27.609973669052124,0.0,1739502667.290582,27.609973669052124,-0.06562449896098865,1739502667.2905834,27.609973669052124,1.111304658212847,1739502667.290585,27.609973669052124,1.0221177513423683 +1739502667.3113165,27.629973649978638,50.86916246364028,1739502667.311319,27.629973649978638,2.6303903854838637,1739502667.3113222,27.629973649978638,52.22236451519019,1739502667.3113246,27.629973649978638,51.329048441906465,1739502667.3113263,27.629973649978638,6.267770599533365,1739502667.311328,27.629973649978638,1.4450303343649342,1739502667.3113296,27.629973649978638,1.2009653456121931,1739502667.3113308,27.629973649978638,0.6108,1739502667.311332,27.629973649978638,0.9564932523813796,1739502667.3113337,27.629973649978638,0.0,1739502667.311335,27.629973649978638,-0.06562449896098865,1739502667.3113365,27.629973649978638,1.111304658212847,1739502667.3113377,27.629973649978638,1.0221177513423683 +1739502667.3306623,27.64997363090515,50.86916246364028,1739502667.3306646,27.64997363090515,2.6303903854838637,1739502667.330668,27.64997363090515,52.22236451519019,1739502667.3306708,27.64997363090515,51.329048441906465,1739502667.330672,27.64997363090515,6.267770599533365,1739502667.330674,27.64997363090515,1.4450303343649342,1739502667.3306754,27.64997363090515,1.2009653456121931,1739502667.3306768,27.64997363090515,0.6108,1739502667.330678,27.64997363090515,0.9564932523813796,1739502667.33068,27.64997363090515,0.0,1739502667.330681,27.64997363090515,-0.06562449896098865,1739502667.3306823,27.64997363090515,1.111304658212847,1739502667.330684,27.64997363090515,1.0221177513423683 +1739502667.3511875,27.669973611831665,50.86916246364028,1739502667.35119,27.669973611831665,2.6303903854838637,1739502667.3511934,27.669973611831665,52.22236451519019,1739502667.351196,27.669973611831665,51.329048441906465,1739502667.3511975,27.669973611831665,6.267770599533365,1739502667.3511992,27.669973611831665,1.4450303343649342,1739502667.3512008,27.669973611831665,1.2009653456121931,1739502667.351202,27.669973611831665,0.6108,1739502667.3512034,27.669973611831665,0.9564932523813796,1739502667.351205,27.669973611831665,0.0,1739502667.3512063,27.669973611831665,-0.06562449896098865,1739502667.3512077,27.669973611831665,1.111304658212847,1739502667.3512092,27.669973611831665,1.0221177513423683 +1739502667.3709812,27.68997359275818,50.91760553420527,1739502667.3709838,27.68997359275818,2.7314581160579436,1739502667.3709867,27.68997359275818,52.30823866157963,1739502667.3709896,27.68997359275818,51.295775368264266,1739502667.370991,27.68997359275818,6.331240977351508,1739502667.370993,27.68997359275818,1.4661267404316305,1739502667.3709943,27.68997359275818,1.1633809878876011,1739502667.3709958,27.68997359275818,0.6108,1739502667.370997,27.68997359275818,0.9856893267747936,1739502667.3709989,27.68997359275818,0.0,1739502667.3709998,27.68997359275818,-0.012823751552775795,1739502667.3710012,27.68997359275818,1.1389063471553962,1739502667.3710027,27.68997359275818,1.0150133227110392 +1739502667.3907948,27.709973573684692,50.91760553420527,1739502667.3907979,27.709973573684692,2.7314581160579436,1739502667.3908012,27.709973573684692,52.30823866157963,1739502667.390804,27.709973573684692,51.295775368264266,1739502667.3908055,27.709973573684692,6.331240977351508,1739502667.3908072,27.709973573684692,1.4661267404316305,1739502667.3908086,27.709973573684692,1.1633809878876011,1739502667.3908107,27.709973573684692,0.6108,1739502667.3908122,27.709973573684692,0.9856893267747936,1739502667.390814,27.709973573684692,0.0,1739502667.3908155,27.709973573684692,-0.029323995936245573,1739502667.390817,27.709973573684692,1.1389063471553962,1739502667.3908184,27.709973573684692,1.0150133227110392 +1739502667.411516,27.729973554611206,50.91760553420527,1739502667.4115188,27.729973554611206,2.7314581160579436,1739502667.4115214,27.729973554611206,52.30823866157963,1739502667.4115243,27.729973554611206,51.295775368264266,1739502667.411526,27.729973554611206,6.331240977351508,1739502667.4115276,27.729973554611206,1.4661267404316305,1739502667.4115293,27.729973554611206,1.1633809878876011,1739502667.4115305,27.729973554611206,0.6108,1739502667.4115317,27.729973554611206,0.9856893267747936,1739502667.4115334,27.729973554611206,0.0,1739502667.4115348,27.729973554611206,-0.029323995936245573,1739502667.4115365,27.729973554611206,1.1389063471553962,1739502667.411538,27.729973554611206,1.0150133227110392 +1739502667.4308274,27.74997353553772,50.91760553420527,1739502667.4308302,27.74997353553772,2.7314581160579436,1739502667.4308333,27.74997353553772,52.30823866157963,1739502667.4308362,27.74997353553772,51.295775368264266,1739502667.4308374,27.74997353553772,6.331240977351508,1739502667.4308393,27.74997353553772,1.4661267404316305,1739502667.4308407,27.74997353553772,1.1633809878876011,1739502667.4308422,27.74997353553772,0.6108,1739502667.4308434,27.74997353553772,0.9856893267747936,1739502667.4308455,27.74997353553772,0.0,1739502667.4308467,27.74997353553772,-0.029323995936245573,1739502667.4308484,27.74997353553772,1.1389063471553962,1739502667.43085,27.74997353553772,1.0150133227110392 +1739502667.4507,27.769973516464233,50.91760553420527,1739502667.4507027,27.769973516464233,2.7314581160579436,1739502667.4507058,27.769973516464233,52.30823866157963,1739502667.4507084,27.769973516464233,51.295775368264266,1739502667.45071,27.769973516464233,6.331240977351508,1739502667.4507117,27.769973516464233,1.4661267404316305,1739502667.4507132,27.769973516464233,1.1633809878876011,1739502667.4507146,27.769973516464233,0.6108,1739502667.450716,27.769973516464233,0.9856893267747936,1739502667.4507174,27.769973516464233,0.0,1739502667.4507186,27.769973516464233,-0.029323995936245573,1739502667.4507203,27.769973516464233,1.1389063471553962,1739502667.4507217,27.769973516464233,1.0150133227110392 +1739502667.4709861,27.789973497390747,50.962996274365544,1739502667.470989,27.789973497390747,2.8332781315387328,1739502667.470992,27.789973497390747,52.42755100577242,1739502667.4709947,27.789973497390747,51.24103499807973,1739502667.4709961,27.789973497390747,6.429889759469732,1739502667.470998,27.789973497390747,1.4936440344676385,1739502667.4709995,27.789973497390747,1.1591554692364376,1739502667.4710011,27.789973497390747,0.6108,1739502667.4710023,27.789973497390747,0.9890270038707942,1739502667.4710042,27.789973497390747,0.0,1739502667.4710054,27.789973497390747,-0.01975386310945819,1739502667.4710066,27.789973497390747,1.1665080360979454,1739502667.4710083,27.789973497390747,1.0117715354494585 +1739502667.4904606,27.80997347831726,50.962996274365544,1739502667.4904633,27.80997347831726,2.8332781315387328,1739502667.4904664,27.80997347831726,52.42755100577242,1739502667.4904692,27.80997347831726,51.24103499807973,1739502667.4904704,27.80997347831726,6.429889759469732,1739502667.490472,27.80997347831726,1.4936440344676385,1739502667.4904735,27.80997347831726,1.1591554692364376,1739502667.490475,27.80997347831726,0.6108,1739502667.4904766,27.80997347831726,0.9890270038707942,1739502667.490478,27.80997347831726,0.0,1739502667.4904795,27.80997347831726,-0.022744531578664295,1739502667.490481,27.80997347831726,1.1665080360979454,1739502667.4904823,27.80997347831726,1.0117715354494585 +1739502667.5106747,27.829973459243774,50.962996274365544,1739502667.5106776,27.829973459243774,2.8332781315387328,1739502667.5106804,27.829973459243774,52.42755100577242,1739502667.510683,27.829973459243774,51.24103499807973,1739502667.5106847,27.829973459243774,6.429889759469732,1739502667.5106862,27.829973459243774,1.4936440344676385,1739502667.5106876,27.829973459243774,1.1591554692364376,1739502667.510689,27.829973459243774,0.6108,1739502667.5106902,27.829973459243774,0.9890270038707942,1739502667.510692,27.829973459243774,0.0,1739502667.510693,27.829973459243774,-0.022744531578664295,1739502667.5106947,27.829973459243774,1.1665080360979454,1739502667.5106962,27.829973459243774,1.0117715354494585 +1739502667.5308192,27.849973440170288,50.962996274365544,1739502667.5308213,27.849973440170288,2.8332781315387328,1739502667.5308244,27.849973440170288,52.42755100577242,1739502667.530827,27.849973440170288,51.24103499807973,1739502667.5308285,27.849973440170288,6.429889759469732,1739502667.5308304,27.849973440170288,1.4936440344676385,1739502667.5308316,27.849973440170288,1.1591554692364376,1739502667.5308332,27.849973440170288,0.6108,1739502667.530835,27.849973440170288,0.9890270038707942,1739502667.5308366,27.849973440170288,0.0,1739502667.530838,27.849973440170288,-0.022744531578664295,1739502667.5308392,27.849973440170288,1.1665080360979454,1739502667.5308409,27.849973440170288,1.0117715354494585 +1739502667.5531256,27.8699734210968,50.962996274365544,1739502667.5531294,27.8699734210968,2.8332781315387328,1739502667.553134,27.8699734210968,52.42755100577242,1739502667.5531392,27.8699734210968,51.24103499807973,1739502667.5531423,27.8699734210968,6.429889759469732,1739502667.5531461,27.8699734210968,1.4936440344676385,1739502667.5531495,27.8699734210968,1.1591554692364376,1739502667.553153,27.8699734210968,0.6108,1739502667.5531564,27.8699734210968,0.9890270038707942,1739502667.55316,27.8699734210968,0.0,1739502667.5531635,27.8699734210968,-0.022744531578664295,1739502667.5531669,27.8699734210968,1.1665080360979454,1739502667.5531704,27.8699734210968,1.0117715354494585 +1739502667.573303,27.889973402023315,50.962996274365544,1739502667.5733066,27.889973402023315,2.8332781315387328,1739502667.5733113,27.889973402023315,52.42755100577242,1739502667.5733166,27.889973402023315,51.24103499807973,1739502667.5733197,27.889973402023315,6.429889759469732,1739502667.5733235,27.889973402023315,1.4936440344676385,1739502667.573327,27.889973402023315,1.1591554692364376,1739502667.5733304,27.889973402023315,0.6108,1739502667.573334,27.889973402023315,0.9890270038707942,1739502667.5733373,27.889973402023315,0.0,1739502667.573341,27.889973402023315,-0.022744531578664295,1739502667.5733445,27.889973402023315,1.1665080360979454,1739502667.5733485,27.889973402023315,1.0117715354494585 +1739502667.593095,27.90997338294983,51.00544228915263,1739502667.593099,27.90997338294983,2.9360282869739134,1739502667.593104,27.90997338294983,52.56656956060017,1739502667.593109,27.90997338294983,51.17355641375544,1739502667.593112,27.90997338294983,6.545826372475461,1739502667.593116,27.90997338294983,1.5242583385796629,1739502667.5931194,27.90997338294983,1.1715057945934466,1739502667.5931227,27.90997338294983,0.6108,1739502667.5931263,27.90997338294983,0.9793032752300489,1739502667.5931299,27.90997338294983,0.0,1739502667.5931334,27.90997338294983,-0.03334818769347787,1739502667.5931373,27.90997338294983,1.1941097250404946,1739502667.593141,27.90997338294983,1.0093378182150528 +1739502667.6133366,27.929973363876343,51.00544228915263,1739502667.6133404,27.929973363876343,2.9360282869739134,1739502667.6133456,27.929973363876343,52.56656956060017,1739502667.6133509,27.929973363876343,51.17355641375544,1739502667.613354,27.929973363876343,6.545826372475461,1739502667.6133578,27.929973363876343,1.5242583385796629,1739502667.6133614,27.929973363876343,1.1715057945934466,1739502667.6133647,27.929973363876343,0.6108,1739502667.6133683,27.929973363876343,0.9793032752300489,1739502667.6133718,27.929973363876343,0.0,1739502667.6133754,27.929973363876343,-0.030034542985003854,1739502667.613379,27.929973363876343,1.1941097250404946,1739502667.6133826,27.929973363876343,1.0093378182150528 +1739502667.6329584,27.949973344802856,51.00544228915263,1739502667.6329625,27.949973344802856,2.9360282869739134,1739502667.6329675,27.949973344802856,52.56656956060017,1739502667.6329727,27.949973344802856,51.17355641375544,1739502667.6329756,27.949973344802856,6.545826372475461,1739502667.6329796,27.949973344802856,1.5242583385796629,1739502667.6329832,27.949973344802856,1.1715057945934466,1739502667.6329868,27.949973344802856,0.6108,1739502667.6329904,27.949973344802856,0.9793032752300489,1739502667.632994,27.949973344802856,0.0,1739502667.6329975,27.949973344802856,-0.030034542985003854,1739502667.6330013,27.949973344802856,1.1941097250404946,1739502667.6330044,27.949973344802856,1.0093378182150528 +1739502667.653573,27.96997332572937,51.00544228915263,1739502667.6535769,27.96997332572937,2.9360282869739134,1739502667.6535819,27.96997332572937,52.56656956060017,1739502667.653587,27.96997332572937,51.17355641375544,1739502667.6535902,27.96997332572937,6.545826372475461,1739502667.653594,27.96997332572937,1.5242583385796629,1739502667.6535974,27.96997332572937,1.1715057945934466,1739502667.653601,27.96997332572937,0.6108,1739502667.6536045,27.96997332572937,0.9793032752300489,1739502667.6536086,27.96997332572937,0.0,1739502667.6536117,27.96997332572937,-0.030034542985003854,1739502667.6536155,27.96997332572937,1.1941097250404946,1739502667.6536186,27.96997332572937,1.0093378182150528 +1739502667.6729295,27.989973306655884,51.00544228915263,1739502667.6729324,27.989973306655884,2.9360282869739134,1739502667.6729355,27.989973306655884,52.56656956060017,1739502667.6729383,27.989973306655884,51.17355641375544,1739502667.6729395,27.989973306655884,6.545826372475461,1739502667.6729412,27.989973306655884,1.5242583385796629,1739502667.6729429,27.989973306655884,1.1715057945934466,1739502667.672944,27.989973306655884,0.6108,1739502667.6729457,27.989973306655884,0.9793032752300489,1739502667.6729474,27.989973306655884,0.0,1739502667.6729488,27.989973306655884,-0.030034542985003854,1739502667.6729503,27.989973306655884,1.1941097250404946,1739502667.6729522,27.989973306655884,1.0093378182150528 +1739502667.6913996,28.009973287582397,51.04492566356124,1739502667.6914022,28.009973287582397,3.0396195318412964,1739502667.6914053,28.009973287582397,52.63620423956039,1739502667.6914082,28.009973287582397,51.14068694054335,1739502667.6914093,28.009973287582397,6.599650134860268,1739502667.6914113,28.009973287582397,1.5439038077547458,1739502667.6914127,28.009973287582397,1.1276804060314878,1739502667.6914144,28.009973287582397,0.6108,1739502667.6914155,28.009973287582397,1.0142469409703683,1739502667.691417,28.009973287582397,0.0,1739502667.6914184,28.009973287582397,0.0255693875166962,1739502667.6914198,28.009973287582397,1.2217114139830438,1739502667.6914213,28.009973287582397,1.0060537931282039 +1739502667.7104862,28.02997326850891,51.04492566356124,1739502667.7104893,28.02997326850891,3.0396195318412964,1739502667.7104926,28.02997326850891,52.63620423956039,1739502667.7104952,28.02997326850891,51.14068694054335,1739502667.7104967,28.02997326850891,6.599650134860268,1739502667.7104986,28.02997326850891,1.5439038077547458,1739502667.7105,28.02997326850891,1.1276804060314878,1739502667.7105014,28.02997326850891,0.6108,1739502667.7105029,28.02997326850891,1.0142469409703683,1739502667.7105045,28.02997326850891,0.0,1739502667.7105057,28.02997326850891,0.008193147842164406,1739502667.710507,28.02997326850891,1.2217114139830438,1739502667.7105086,28.02997326850891,1.0060537931282039 +1739502667.7310755,28.049973249435425,51.04492566356124,1739502667.7310784,28.049973249435425,3.0396195318412964,1739502667.7310812,28.049973249435425,52.63620423956039,1739502667.7310839,28.049973249435425,51.14068694054335,1739502667.7310853,28.049973249435425,6.599650134860268,1739502667.7310867,28.049973249435425,1.5439038077547458,1739502667.7310884,28.049973249435425,1.1276804060314878,1739502667.7310896,28.049973249435425,0.6108,1739502667.7310913,28.049973249435425,1.0142469409703683,1739502667.731093,28.049973249435425,0.0,1739502667.7310946,28.049973249435425,0.008193147842164406,1739502667.731096,28.049973249435425,1.2217114139830438,1739502667.7310977,28.049973249435425,1.0060537931282039 +1739502667.7510672,28.06997323036194,51.04492566356124,1739502667.7510698,28.06997323036194,3.0396195318412964,1739502667.7510724,28.06997323036194,52.63620423956039,1739502667.7510753,28.06997323036194,51.14068694054335,1739502667.751077,28.06997323036194,6.599650134860268,1739502667.7510786,28.06997323036194,1.5439038077547458,1739502667.75108,28.06997323036194,1.1276804060314878,1739502667.7510815,28.06997323036194,0.6108,1739502667.7510827,28.06997323036194,1.0142469409703683,1739502667.7510843,28.06997323036194,0.0,1739502667.7510858,28.06997323036194,0.008193147842164406,1739502667.7510872,28.06997323036194,1.2217114139830438,1739502667.7510889,28.06997323036194,1.0060537931282039 +1739502667.7709303,28.089973211288452,51.04492566356124,1739502667.7709327,28.089973211288452,3.0396195318412964,1739502667.7709358,28.089973211288452,52.63620423956039,1739502667.7709384,28.089973211288452,51.14068694054335,1739502667.7709398,28.089973211288452,6.599650134860268,1739502667.7709417,28.089973211288452,1.5439038077547458,1739502667.7709432,28.089973211288452,1.1276804060314878,1739502667.7709446,28.089973211288452,0.6108,1739502667.7709458,28.089973211288452,1.0142469409703683,1739502667.7709472,28.089973211288452,0.0,1739502667.770949,28.089973211288452,0.008193147842164406,1739502667.77095,28.089973211288452,1.2217114139830438,1739502667.7709517,28.089973211288452,1.0060537931282039 +1739502667.790621,28.109973192214966,51.04492566356124,1739502667.7906232,28.109973192214966,3.0396195318412964,1739502667.7906258,28.109973192214966,52.63620423956039,1739502667.7906287,28.109973192214966,51.14068694054335,1739502667.79063,28.109973192214966,6.599650134860268,1739502667.7906318,28.109973192214966,1.5439038077547458,1739502667.790633,28.109973192214966,1.1276804060314878,1739502667.7906342,28.109973192214966,0.6108,1739502667.7906356,28.109973192214966,1.0142469409703683,1739502667.790637,28.109973192214966,0.0,1739502667.7906384,28.109973192214966,0.008193147842164406,1739502667.7906399,28.109973192214966,1.2217114139830438,1739502667.790641,28.109973192214966,1.0060537931282039 +1739502667.8111198,28.12997317314148,51.08149427490017,1739502667.8111222,28.12997317314148,3.1441477770375865,1739502667.8111253,28.12997317314148,52.637850478049835,1739502667.811128,28.12997317314148,51.1385329516113,1739502667.8111293,28.12997317314148,6.603177291736486,1739502667.8111308,28.12997317314148,1.55430802929555,1739502667.8111324,28.12997317314148,1.038847425625865,1739502667.8111336,28.12997317314148,0.6108,1739502667.811135,28.12997317314148,1.0889487609487287,1739502667.8111365,28.12997317314148,0.0,1739502667.8111377,28.12997317314148,0.11504192282245913,1739502667.811139,28.12997317314148,1.249313102925593,1739502667.8111405,28.12997317314148,1.0072971021999748 +1739502667.8307784,28.149973154067993,51.08149427490017,1739502667.8307807,28.149973154067993,3.1441477770375865,1739502667.8307838,28.149973154067993,52.637850478049835,1739502667.8307862,28.149973154067993,51.1385329516113,1739502667.8307877,28.149973154067993,6.603177291736486,1739502667.8307893,28.149973154067993,1.55430802929555,1739502667.8307908,28.149973154067993,1.038847425625865,1739502667.830792,28.149973154067993,0.6108,1739502667.8307931,28.149973154067993,1.0889487609487287,1739502667.8307948,28.149973154067993,0.0,1739502667.8307962,28.149973154067993,0.08165165874875391,1739502667.830798,28.149973154067993,1.249313102925593,1739502667.830799,28.149973154067993,1.0072971021999748 +1739502667.8509812,28.169973134994507,51.08149427490017,1739502667.8509834,28.169973134994507,3.1441477770375865,1739502667.8509862,28.169973134994507,52.637850478049835,1739502667.850989,28.169973134994507,51.1385329516113,1739502667.8509905,28.169973134994507,6.603177291736486,1739502667.8509924,28.169973134994507,1.55430802929555,1739502667.8509936,28.169973134994507,1.038847425625865,1739502667.8509953,28.169973134994507,0.6108,1739502667.8509963,28.169973134994507,1.0889487609487287,1739502667.850998,28.169973134994507,0.0,1739502667.8509994,28.169973134994507,0.08165165874875391,1739502667.8510008,28.169973134994507,1.249313102925593,1739502667.8510022,28.169973134994507,1.0072971021999748 +1739502667.870813,28.18997311592102,51.08149427490017,1739502667.8708153,28.18997311592102,3.1441477770375865,1739502667.8708186,28.18997311592102,52.637850478049835,1739502667.8708212,28.18997311592102,51.1385329516113,1739502667.8708227,28.18997311592102,6.603177291736486,1739502667.870824,28.18997311592102,1.55430802929555,1739502667.8708255,28.18997311592102,1.038847425625865,1739502667.870827,28.18997311592102,0.6108,1739502667.870828,28.18997311592102,1.0889487609487287,1739502667.8708296,28.18997311592102,0.0,1739502667.8708308,28.18997311592102,0.08165165874875391,1739502667.8708327,28.18997311592102,1.249313102925593,1739502667.8708339,28.18997311592102,1.0072971021999748 +1739502667.8905694,28.209973096847534,51.08149427490017,1739502667.8905718,28.209973096847534,3.1441477770375865,1739502667.8905747,28.209973096847534,52.637850478049835,1739502667.890577,28.209973096847534,51.1385329516113,1739502667.8905785,28.209973096847534,6.603177291736486,1739502667.89058,28.209973096847534,1.55430802929555,1739502667.8905816,28.209973096847534,1.038847425625865,1739502667.8905826,28.209973096847534,0.6108,1739502667.890584,28.209973096847534,1.0889487609487287,1739502667.8905857,28.209973096847534,0.0,1739502667.8905869,28.209973096847534,0.08165165874875391,1739502667.890588,28.209973096847534,1.249313102925593,1739502667.89059,28.209973096847534,1.0072971021999748 +1739502667.9114227,28.229973077774048,51.11531129458047,1739502667.911425,28.229973077774048,3.250113147973728,1739502667.9114277,28.229973077774048,52.93682256746448,1739502667.9114304,28.229973077774048,50.96220618947752,1739502667.911432,28.229973077774048,6.866162839092416,1739502667.9114335,28.229973077774048,1.6131114843092988,1739502667.911435,28.229973077774048,1.19400036168493,1739502667.9114363,28.229973077774048,0.6108,1739502667.9114375,28.229973077774048,0.9618376962436943,1739502667.9114392,28.229973077774048,0.0,1739502667.9114404,28.229973077774048,-0.11615902830290756,1739502667.9114418,28.229973077774048,1.2769147918681423,1739502667.9114435,28.229973077774048,1.0161808443133082 +1739502667.9307625,28.24997305870056,51.11531129458047,1739502667.9307644,28.24997305870056,3.250113147973728,1739502667.9307675,28.24997305870056,52.93682256746448,1739502667.9307702,28.24997305870056,50.96220618947752,1739502667.9307714,28.24997305870056,6.866162839092416,1739502667.930773,28.24997305870056,1.6131114843092988,1739502667.9307745,28.24997305870056,1.19400036168493,1739502667.930776,28.24997305870056,0.6108,1739502667.930777,28.24997305870056,0.9618376962436943,1739502667.9307787,28.24997305870056,0.0,1739502667.93078,28.24997305870056,-0.054343148069613934,1739502667.9307811,28.24997305870056,1.2769147918681423,1739502667.9307828,28.24997305870056,1.0161808443133082 +1739502667.9509988,28.269973039627075,51.11531129458047,1739502667.9510014,28.269973039627075,3.250113147973728,1739502667.9510043,28.269973039627075,52.93682256746448,1739502667.9510067,28.269973039627075,50.96220618947752,1739502667.951008,28.269973039627075,6.866162839092416,1739502667.9510098,28.269973039627075,1.6131114843092988,1739502667.9510112,28.269973039627075,1.19400036168493,1739502667.9510124,28.269973039627075,0.6108,1739502667.9510136,28.269973039627075,0.9618376962436943,1739502667.9510157,28.269973039627075,0.0,1739502667.951017,28.269973039627075,-0.054343148069613934,1739502667.9510183,28.269973039627075,1.2769147918681423,1739502667.9510198,28.269973039627075,1.0161808443133082 +1739502667.9708016,28.28997302055359,51.11531129458047,1739502667.970804,28.28997302055359,3.250113147973728,1739502667.9708068,28.28997302055359,52.93682256746448,1739502667.9708095,28.28997302055359,50.96220618947752,1739502667.9708107,28.28997302055359,6.866162839092416,1739502667.9708123,28.28997302055359,1.6131114843092988,1739502667.970814,28.28997302055359,1.19400036168493,1739502667.9708152,28.28997302055359,0.6108,1739502667.9708164,28.28997302055359,0.9618376962436943,1739502667.9708178,28.28997302055359,0.0,1739502667.970819,28.28997302055359,-0.054343148069613934,1739502667.9708207,28.28997302055359,1.2769147918681423,1739502667.9708219,28.28997302055359,1.0161808443133082 +1739502667.9906292,28.309973001480103,51.11531129458047,1739502667.9906313,28.309973001480103,3.250113147973728,1739502667.9906344,28.309973001480103,52.93682256746448,1739502667.990637,28.309973001480103,50.96220618947752,1739502667.9906385,28.309973001480103,6.866162839092416,1739502667.9906404,28.309973001480103,1.6131114843092988,1739502667.9906416,28.309973001480103,1.19400036168493,1739502667.9906433,28.309973001480103,0.6108,1739502667.9906442,28.309973001480103,0.9618376962436943,1739502667.9906456,28.309973001480103,0.0,1739502667.990647,28.309973001480103,-0.054343148069613934,1739502667.9906487,28.309973001480103,1.2769147918681423,1739502667.9906502,28.309973001480103,1.0161808443133082 +1739502668.0109465,28.329972982406616,51.11531129458047,1739502668.010949,28.329972982406616,3.250113147973728,1739502668.0109518,28.329972982406616,52.93682256746448,1739502668.0109544,28.329972982406616,50.96220618947752,1739502668.0109558,28.329972982406616,6.866162839092416,1739502668.0109575,28.329972982406616,1.6131114843092988,1739502668.010959,28.329972982406616,1.19400036168493,1739502668.01096,28.329972982406616,0.6108,1739502668.0109613,28.329972982406616,0.9618376962436943,1739502668.010963,28.329972982406616,0.0,1739502668.0109644,28.329972982406616,-0.054343148069613934,1739502668.0109658,28.329972982406616,1.2769147918681423,1739502668.010967,28.329972982406616,1.0161808443133082 +1739502668.0303411,28.34997296333313,51.146231070215634,1739502668.0303435,28.34997296333313,3.3570956061457498,1739502668.030346,28.34997296333313,53.07183027847615,1739502668.0303485,28.34997296333313,50.89024392093808,1739502668.0303497,28.34997296333313,6.962978455256597,1739502668.0303516,28.34997296333313,1.6416689575912404,1739502668.0303528,28.34997296333313,1.195832508791774,1739502668.0303545,28.34997296333313,0.6108,1739502668.0303557,28.34997296333313,0.9604289463887462,1739502668.0303574,28.34997296333313,0.0,1739502668.0303586,28.34997296333313,-0.045941509722442375,1739502668.03036,28.34997296333313,1.3045164808106915,1739502668.0303614,28.34997296333313,1.0089959698161006 +1739502668.0506907,28.369972944259644,51.146231070215634,1739502668.0506928,28.369972944259644,3.3570956061457498,1739502668.050696,28.369972944259644,53.07183027847615,1739502668.0506985,28.369972944259644,50.89024392093808,1739502668.0507,28.369972944259644,6.962978455256597,1739502668.0507016,28.369972944259644,1.6416689575912404,1739502668.0507028,28.369972944259644,1.195832508791774,1739502668.0507042,28.369972944259644,0.6108,1739502668.0507054,28.369972944259644,0.9604289463887462,1739502668.0507069,28.369972944259644,0.0,1739502668.0507083,28.369972944259644,-0.04856702342735442,1739502668.0507097,28.369972944259644,1.3045164808106915,1739502668.0507112,28.369972944259644,1.0089959698161006 +1739502668.0707588,28.389972925186157,51.146231070215634,1739502668.070761,28.389972925186157,3.3570956061457498,1739502668.070764,28.389972925186157,53.07183027847615,1739502668.0707667,28.389972925186157,50.89024392093808,1739502668.0707679,28.389972925186157,6.962978455256597,1739502668.0707693,28.389972925186157,1.6416689575912404,1739502668.0707707,28.389972925186157,1.195832508791774,1739502668.070772,28.389972925186157,0.6108,1739502668.0707734,28.389972925186157,0.9604289463887462,1739502668.070775,28.389972925186157,0.0,1739502668.070776,28.389972925186157,-0.04856702342735442,1739502668.0707777,28.389972925186157,1.3045164808106915,1739502668.0707788,28.389972925186157,1.0089959698161006 +1739502668.096123,28.40997290611267,51.146231070215634,1739502668.0961285,28.40997290611267,3.3570956061457498,1739502668.0961356,28.40997290611267,53.07183027847615,1739502668.096144,28.40997290611267,50.89024392093808,1739502668.0961483,28.40997290611267,6.962978455256597,1739502668.0961542,28.40997290611267,1.6416689575912404,1739502668.0961595,28.40997290611267,1.195832508791774,1739502668.0961647,28.40997290611267,0.6108,1739502668.0961697,28.40997290611267,0.9604289463887462,1739502668.0961752,28.40997290611267,0.0,1739502668.0961802,28.40997290611267,-0.04856702342735442,1739502668.0961857,28.40997290611267,1.3045164808106915,1739502668.096191,28.40997290611267,1.0089959698161006 +1739502668.1120558,28.429972887039185,51.146231070215634,1739502668.1120603,28.429972887039185,3.3570956061457498,1739502668.1120656,28.429972887039185,53.07183027847615,1739502668.1120703,28.429972887039185,50.89024392093808,1739502668.1120727,28.429972887039185,6.962978455256597,1739502668.1120758,28.429972887039185,1.6416689575912404,1739502668.1120784,28.429972887039185,1.195832508791774,1739502668.1120808,28.429972887039185,0.6108,1739502668.1120832,28.429972887039185,0.9604289463887462,1739502668.112086,28.429972887039185,0.0,1739502668.1120887,28.429972887039185,-0.04856702342735442,1739502668.1120913,28.429972887039185,1.3045164808106915,1739502668.1120937,28.429972887039185,1.0089959698161006 +1739502668.1378832,28.4499728679657,51.174024943189856,1739502668.137892,28.4499728679657,3.4642689867526233,1739502668.1379023,28.4499728679657,53.2357069514314,1739502668.137912,28.4499728679657,50.794927632562164,1739502668.1379173,28.4499728679657,7.082937620667067,1739502668.1379232,28.4499728679657,1.675177122165626,1739502668.1379282,28.4499728679657,1.2238704827979388,1739502668.1379328,28.4499728679657,0.6108,1739502668.1379373,28.4499728679657,0.9391259709887139,1739502668.137943,28.4499728679657,0.0,1739502668.1379476,28.4499728679657,-0.07180943563854668,1739502668.1379528,28.4499728679657,1.3321181697532407,1739502668.1379576,28.4499728679657,1.0036721480490995 +1739502668.1721783,28.489972829818726,51.174024943189856,1739502668.1721823,28.489972829818726,3.4642689867526233,1739502668.1721873,28.489972829818726,53.2357069514314,1739502668.172192,28.489972829818726,50.794927632562164,1739502668.172194,28.489972829818726,7.082937620667067,1739502668.1721973,28.489972829818726,1.675177122165626,1739502668.1722004,28.489972829818726,1.2238704827979388,1739502668.1722026,28.489972829818726,0.6108,1739502668.1722045,28.489972829818726,0.9391259709887139,1739502668.172207,28.489972829818726,0.0,1739502668.1722095,28.489972829818726,-0.06454617706038568,1739502668.1722116,28.489972829818726,1.3321181697532407,1739502668.1722145,28.489972829818726,1.0036721480490995 +1739502668.1944196,28.50997281074524,51.174024943189856,1739502668.1944246,28.50997281074524,3.4642689867526233,1739502668.19443,28.50997281074524,53.2357069514314,1739502668.194436,28.50997281074524,50.794927632562164,1739502668.194439,28.50997281074524,7.082937620667067,1739502668.1944425,28.50997281074524,1.675177122165626,1739502668.1944456,28.50997281074524,1.2238704827979388,1739502668.1944485,28.50997281074524,0.6108,1739502668.194451,28.50997281074524,0.9391259709887139,1739502668.1944544,28.50997281074524,0.0,1739502668.1944573,28.50997281074524,-0.06454617706038568,1739502668.1944604,28.50997281074524,1.3321181697532407,1739502668.1944635,28.50997281074524,1.0036721480490995 +1739502668.2110329,28.529972791671753,51.174024943189856,1739502668.2110355,28.529972791671753,3.4642689867526233,1739502668.2110388,28.529972791671753,53.2357069514314,1739502668.2110422,28.529972791671753,50.794927632562164,1739502668.2110436,28.529972791671753,7.082937620667067,1739502668.2110453,28.529972791671753,1.675177122165626,1739502668.2110472,28.529972791671753,1.2238704827979388,1739502668.2110486,28.529972791671753,0.6108,1739502668.2110503,28.529972791671753,0.9391259709887139,1739502668.2110522,28.529972791671753,0.0,1739502668.2110538,28.529972791671753,-0.06454617706038568,1739502668.2110553,28.529972791671753,1.3321181697532407,1739502668.2110574,28.529972791671753,1.0036721480490995 +1739502668.2304006,28.549972772598267,51.174024943189856,1739502668.2304025,28.549972772598267,3.4642689867526233,1739502668.230405,28.549972772598267,53.2357069514314,1739502668.230408,28.549972772598267,50.794927632562164,1739502668.2304091,28.549972772598267,7.082937620667067,1739502668.2304108,28.549972772598267,1.675177122165626,1739502668.2304122,28.549972772598267,1.2238704827979388,1739502668.2304137,28.549972772598267,0.6108,1739502668.2304275,28.549972772598267,0.9391259709887139,1739502668.230429,28.549972772598267,0.0,1739502668.23043,28.549972772598267,-0.06454617706038568,1739502668.2304313,28.549972772598267,1.3321181697532407,1739502668.2304325,28.549972772598267,1.0036721480490995 +1739502668.2511919,28.56997275352478,51.19869989201104,1739502668.251194,28.56997275352478,3.5715120586092475,1739502668.2511969,28.56997275352478,53.314161817754545,1739502668.2511995,28.56997275352478,50.75352967188019,1739502668.2512007,28.56997275352478,7.132001870364223,1739502668.2512023,28.56997275352478,1.6951814622596875,1739502668.2512038,28.56997275352478,1.1812575593790242,1739502668.2512052,28.56997275352478,0.6108,1739502668.2512062,28.56997275352478,0.9716930509197603,1739502668.2512076,28.56997275352478,0.0,1739502668.251209,28.56997275352478,-0.006805580790054003,1739502668.2512102,28.56997275352478,1.35971985869579,1739502668.251212,28.56997275352478,0.9965425798748273 +1739502668.2710452,28.589972734451294,51.19869989201104,1739502668.2710474,28.589972734451294,3.5715120586092475,1739502668.2710507,28.589972734451294,53.314161817754545,1739502668.271053,28.589972734451294,50.75352967188019,1739502668.2710543,28.589972734451294,7.132001870364223,1739502668.2710564,28.589972734451294,1.6951814622596875,1739502668.2710576,28.589972734451294,1.1812575593790242,1739502668.271059,28.589972734451294,0.6108,1739502668.2710602,28.589972734451294,0.9716930509197603,1739502668.2710617,28.589972734451294,0.0,1739502668.271063,28.589972734451294,-0.02484952895506698,1739502668.2710643,28.589972734451294,1.35971985869579,1739502668.2710657,28.589972734451294,0.9965425798748273 +1739502668.2910852,28.609972715377808,51.19869989201104,1739502668.2910876,28.609972715377808,3.5715120586092475,1739502668.2910907,28.609972715377808,53.314161817754545,1739502668.2910933,28.609972715377808,50.75352967188019,1739502668.2910945,28.609972715377808,7.132001870364223,1739502668.291096,28.609972715377808,1.6951814622596875,1739502668.2910974,28.609972715377808,1.1812575593790242,1739502668.2910986,28.609972715377808,0.6108,1739502668.2910998,28.609972715377808,0.9716930509197603,1739502668.2911012,28.609972715377808,0.0,1739502668.2911024,28.609972715377808,-0.02484952895506698,1739502668.291104,28.609972715377808,1.35971985869579,1739502668.291105,28.609972715377808,0.9965425798748273 +1739502668.3107154,28.62997269630432,51.19869989201104,1739502668.310718,28.62997269630432,3.5715120586092475,1739502668.3107207,28.62997269630432,53.314161817754545,1739502668.3107235,28.62997269630432,50.75352967188019,1739502668.310725,28.62997269630432,7.132001870364223,1739502668.3107266,28.62997269630432,1.6951814622596875,1739502668.3107278,28.62997269630432,1.1812575593790242,1739502668.3107295,28.62997269630432,0.6108,1739502668.3107307,28.62997269630432,0.9716930509197603,1739502668.3107324,28.62997269630432,0.0,1739502668.3107336,28.62997269630432,-0.02484952895506698,1739502668.3107347,28.62997269630432,1.35971985869579,1739502668.3107364,28.62997269630432,0.9965425798748273 +1739502668.3308663,28.649972677230835,51.19869989201104,1739502668.3308687,28.649972677230835,3.5715120586092475,1739502668.3308716,28.649972677230835,53.314161817754545,1739502668.3308742,28.649972677230835,50.75352967188019,1739502668.3308754,28.649972677230835,7.132001870364223,1739502668.3308768,28.649972677230835,1.6951814622596875,1739502668.3308787,28.649972677230835,1.1812575593790242,1739502668.33088,28.649972677230835,0.6108,1739502668.330881,28.649972677230835,0.9716930509197603,1739502668.3308825,28.649972677230835,0.0,1739502668.3308837,28.649972677230835,-0.02484952895506698,1739502668.3308852,28.649972677230835,1.35971985869579,1739502668.3308864,28.649972677230835,0.9965425798748273 +1739502668.3508692,28.66997265815735,51.22029140892946,1739502668.350872,28.66997265815735,3.6788330139243666,1739502668.3508754,28.66997265815735,53.413577742155454,1739502668.3508787,28.66997265815735,50.69119904163215,1739502668.3508801,28.66997265815735,7.202237409128557,1739502668.3508823,28.66997265815735,1.719847735806075,1739502668.3508837,28.66997265815735,1.1630469076063648,1739502668.3508854,28.66997265815735,0.6108,1739502668.3508868,28.66997265815735,0.9859528014759066,1739502668.3508885,28.66997265815735,0.0,1739502668.35089,28.66997265815735,-0.00010164190528857541,1739502668.3508916,28.66997265815735,1.3873215476383391,1739502668.350893,28.66997265815735,0.9937881631548727 +1739502668.3713796,28.689972639083862,51.22029140892946,1739502668.3713832,28.689972639083862,3.6788330139243666,1739502668.3713875,28.689972639083862,53.413577742155454,1739502668.3713915,28.689972639083862,50.69119904163215,1739502668.3713932,28.689972639083862,7.202237409128557,1739502668.3713956,28.689972639083862,1.719847735806075,1739502668.3713977,28.689972639083862,1.1630469076063648,1739502668.3713994,28.689972639083862,0.6108,1739502668.3714015,28.689972639083862,0.9859528014759066,1739502668.3714035,28.689972639083862,0.0,1739502668.3714056,28.689972639083862,-0.007835361678966146,1739502668.3714075,28.689972639083862,1.3873215476383391,1739502668.3714097,28.689972639083862,0.9937881631548727 +1739502668.3917506,28.709972620010376,51.22029140892946,1739502668.3917537,28.709972620010376,3.6788330139243666,1739502668.3917577,28.709972620010376,53.413577742155454,1739502668.391762,28.709972620010376,50.69119904163215,1739502668.391764,28.709972620010376,7.202237409128557,1739502668.3917663,28.709972620010376,1.719847735806075,1739502668.3917682,28.709972620010376,1.1630469076063648,1739502668.3917701,28.709972620010376,0.6108,1739502668.3917718,28.709972620010376,0.9859528014759066,1739502668.3917742,28.709972620010376,0.0,1739502668.391776,28.709972620010376,-0.007835361678966146,1739502668.3917782,28.709972620010376,1.3873215476383391,1739502668.3917801,28.709972620010376,0.9937881631548727 +1739502668.4116967,28.72997260093689,51.22029140892946,1739502668.4117,28.72997260093689,3.6788330139243666,1739502668.4117045,28.72997260093689,53.413577742155454,1739502668.4117086,28.72997260093689,50.69119904163215,1739502668.4117107,28.72997260093689,7.202237409128557,1739502668.4117134,28.72997260093689,1.719847735806075,1739502668.411715,28.72997260093689,1.1630469076063648,1739502668.4117172,28.72997260093689,0.6108,1739502668.4117188,28.72997260093689,0.9859528014759066,1739502668.4117212,28.72997260093689,0.0,1739502668.4117234,28.72997260093689,-0.007835361678966146,1739502668.4117253,28.72997260093689,1.3873215476383391,1739502668.4117274,28.72997260093689,0.9937881631548727 +1739502668.4311664,28.749972581863403,51.22029140892946,1739502668.4311697,28.749972581863403,3.6788330139243666,1739502668.4311738,28.749972581863403,53.413577742155454,1739502668.4311776,28.749972581863403,50.69119904163215,1739502668.4311798,28.749972581863403,7.202237409128557,1739502668.4311824,28.749972581863403,1.719847735806075,1739502668.4311843,28.749972581863403,1.1630469076063648,1739502668.4311862,28.749972581863403,0.6108,1739502668.4311879,28.749972581863403,0.9859528014759066,1739502668.4311903,28.749972581863403,0.0,1739502668.4311924,28.749972581863403,-0.007835361678966146,1739502668.4311943,28.749972581863403,1.3873215476383391,1739502668.4311962,28.749972581863403,0.9937881631548727 +1739502668.4518793,28.769972562789917,51.22029140892946,1739502668.4518821,28.769972562789917,3.6788330139243666,1739502668.4518867,28.769972562789917,53.413577742155454,1739502668.4518907,28.769972562789917,50.69119904163215,1739502668.4518924,28.769972562789917,7.202237409128557,1739502668.451895,28.769972562789917,1.719847735806075,1739502668.4518974,28.769972562789917,1.1630469076063648,1739502668.451899,28.769972562789917,0.6108,1739502668.451901,28.769972562789917,0.9859528014759066,1739502668.4519033,28.769972562789917,0.0,1739502668.4519053,28.769972562789917,-0.007835361678966146,1739502668.4519074,28.769972562789917,1.3873215476383391,1739502668.4519093,28.769972562789917,0.9937881631548727 +1739502668.47113,28.78997254371643,51.23888067802692,1739502668.4711335,28.78997254371643,3.7865253034714446,1739502668.4711375,28.78997254371643,53.61364862531078,1739502668.4711413,28.78997254371643,50.55624149272735,1739502668.4711432,28.78997254371643,7.348008877154067,1739502668.4711456,28.78997254371643,1.7601721997567545,1739502668.4711478,28.78997254371643,1.2272573141099012,1739502668.4711497,28.78997254371643,0.6108,1739502668.4711514,28.78997254371643,0.9365848860381581,1739502668.4711537,28.78997254371643,0.0,1739502668.4711556,28.78997254371643,-0.07861746448066483,1739502668.4711578,28.78997254371643,1.4149232365808884,1739502668.4711597,28.78997254371643,0.9930829288906692 +1739502668.4980872,28.809972524642944,51.23888067802692,1739502668.4980955,28.809972524642944,3.7865253034714446,1739502668.4981058,28.809972524642944,53.61364862531078,1739502668.4981158,28.809972524642944,50.55624149272735,1739502668.4981208,28.809972524642944,7.348008877154067,1739502668.4981272,28.809972524642944,1.7601721997567545,1739502668.4981322,28.809972524642944,1.2272573141099012,1739502668.4981368,28.809972524642944,0.6108,1739502668.4981415,28.809972524642944,0.9365848860381581,1739502668.498147,28.809972524642944,0.0,1739502668.498152,28.809972524642944,-0.05649804285251103,1739502668.498157,28.809972524642944,1.4149232365808884,1739502668.498162,28.809972524642944,0.9930829288906692 +1739502668.5261295,28.839972496032715,51.23888067802692,1739502668.5261378,28.839972496032715,3.7865253034714446,1739502668.5261486,28.839972496032715,53.61364862531078,1739502668.5261588,28.839972496032715,50.55624149272735,1739502668.5261638,28.839972496032715,7.348008877154067,1739502668.5261698,28.839972496032715,1.7601721997567545,1739502668.5261753,28.839972496032715,1.2272573141099012,1739502668.5261903,28.839972496032715,0.6108,1739502668.5262043,28.839972496032715,0.9365848860381581,1739502668.526213,28.839972496032715,0.0,1739502668.526225,28.839972496032715,-0.05649804285251103,1739502668.5262332,28.839972496032715,1.4149232365808884,1739502668.526241,28.839972496032715,0.9930829288906692 +1739502668.550008,28.85997247695923,51.23888067802692,1739502668.5500183,28.85997247695923,3.7865253034714446,1739502668.5500307,28.85997247695923,53.61364862531078,1739502668.550042,28.85997247695923,50.55624149272735,1739502668.550047,28.85997247695923,7.348008877154067,1739502668.550054,28.85997247695923,1.7601721997567545,1739502668.5500596,28.85997247695923,1.2272573141099012,1739502668.550065,28.85997247695923,0.6108,1739502668.5500708,28.85997247695923,0.9365848860381581,1739502668.5500772,28.85997247695923,0.0,1739502668.5500824,28.85997247695923,-0.05649804285251103,1739502668.5500886,28.85997247695923,1.4149232365808884,1739502668.5500948,28.85997247695923,0.9930829288906692 +1739502668.5626264,28.879972457885742,51.23888067802692,1739502668.56263,28.879972457885742,3.7865253034714446,1739502668.5626345,28.879972457885742,53.61364862531078,1739502668.5626388,28.879972457885742,50.55624149272735,1739502668.562641,28.879972457885742,7.348008877154067,1739502668.5626435,28.879972457885742,1.7601721997567545,1739502668.5626454,28.879972457885742,1.2272573141099012,1739502668.5626478,28.879972457885742,0.6108,1739502668.5626495,28.879972457885742,0.9365848860381581,1739502668.562652,28.879972457885742,0.0,1739502668.5626543,28.879972457885742,-0.05649804285251103,1739502668.5626562,28.879972457885742,1.4149232365808884,1739502668.5626585,28.879972457885742,0.9930829288906692 +1739502668.5820873,28.899972438812256,51.254442419460545,1739502668.58209,28.899972438812256,3.8943447252683416,1739502668.582093,28.899972438812256,53.73649130023683,1739502668.5820963,28.899972438812256,50.47845365218066,1739502668.582098,28.899972438812256,7.4265463478193405,1739502668.5821002,28.899972438812256,1.7870507598913727,1739502668.582102,28.899972438812256,1.2214526393185032,1739502668.5821035,28.899972438812256,0.6108,1739502668.5821052,28.899972438812256,0.9409442566380992,1739502668.5821068,28.899972438812256,0.0,1739502668.5821085,28.899972438812256,-0.04121288185508482,1739502668.5821102,28.899972438812256,1.4425249255234376,1739502668.5821118,28.899972438812256,0.9869337544366732 +1739502668.6027932,28.91997241973877,51.254442419460545,1739502668.602796,28.91997241973877,3.8943447252683416,1739502668.6027997,28.91997241973877,53.73649130023683,1739502668.6028028,28.91997241973877,50.47845365218066,1739502668.6028042,28.91997241973877,7.4265463478193405,1739502668.602806,28.91997241973877,1.7870507598913727,1739502668.6028078,28.91997241973877,1.2214526393185032,1739502668.6028094,28.91997241973877,0.6108,1739502668.6028109,28.91997241973877,0.9409442566380992,1739502668.6028128,28.91997241973877,0.0,1739502668.6028142,28.91997241973877,-0.045989497798573975,1739502668.6028156,28.91997241973877,1.4425249255234376,1739502668.6028175,28.91997241973877,0.9869337544366732 +1739502668.6226869,28.939972400665283,51.254442419460545,1739502668.6226895,28.939972400665283,3.8943447252683416,1739502668.6226928,28.939972400665283,53.73649130023683,1739502668.6226962,28.939972400665283,50.47845365218066,1739502668.6226978,28.939972400665283,7.4265463478193405,1739502668.6226997,28.939972400665283,1.7870507598913727,1739502668.6227016,28.939972400665283,1.2214526393185032,1739502668.6227028,28.939972400665283,0.6108,1739502668.6227043,28.939972400665283,0.9409442566380992,1739502668.6227062,28.939972400665283,0.0,1739502668.6227076,28.939972400665283,-0.045989497798573975,1739502668.6227098,28.939972400665283,1.4425249255234376,1739502668.6227112,28.939972400665283,0.9869337544366732 +1739502668.6428657,28.959972381591797,51.254442419460545,1739502668.6428685,28.959972381591797,3.8943447252683416,1739502668.6428719,28.959972381591797,53.73649130023683,1739502668.642875,28.959972381591797,50.47845365218066,1739502668.6428764,28.959972381591797,7.4265463478193405,1739502668.6428783,28.959972381591797,1.7870507598913727,1739502668.6428797,28.959972381591797,1.2214526393185032,1739502668.6428814,28.959972381591797,0.6108,1739502668.6428828,28.959972381591797,0.9409442566380992,1739502668.6428845,28.959972381591797,0.0,1739502668.642886,28.959972381591797,-0.045989497798573975,1739502668.6428876,28.959972381591797,1.4425249255234376,1739502668.6428893,28.959972381591797,0.9869337544366732 +1739502668.662112,28.97997236251831,51.254442419460545,1739502668.6621146,28.97997236251831,3.8943447252683416,1739502668.6621182,28.97997236251831,53.73649130023683,1739502668.6621215,28.97997236251831,50.47845365218066,1739502668.662123,28.97997236251831,7.4265463478193405,1739502668.6621253,28.97997236251831,1.7870507598913727,1739502668.6621268,28.97997236251831,1.2214526393185032,1739502668.6621287,28.97997236251831,0.6108,1739502668.6621299,28.97997236251831,0.9409442566380992,1739502668.662132,28.97997236251831,0.0,1739502668.6621335,28.97997236251831,-0.045989497798573975,1739502668.6621351,28.97997236251831,1.4425249255234376,1739502668.6621366,28.97997236251831,0.9869337544366732 +1739502668.6820714,28.999972343444824,51.266949315596854,1739502668.682074,28.999972343444824,4.001925103129183,1739502668.6820772,28.999972343444824,53.84386624838429,1739502668.6820798,28.999972343444824,50.40768635415465,1739502668.682081,28.999972343444824,7.493288554177723,1739502668.682083,28.999972343444824,1.812111421628833,1739502668.682084,28.999972343444824,1.2057937755127,1739502668.6820853,28.999972343444824,0.6108,1739502668.6820867,28.999972343444824,0.9528056905245168,1739502668.6820881,28.999972343444824,0.0,1739502668.6820896,28.999972343444824,-0.021396313932027657,1739502668.6820908,28.999972343444824,1.4701266144659868,1739502668.682092,28.999972343444824,0.9818873794537647 +1739502668.7022254,29.019972324371338,51.266949315596854,1739502668.7022274,29.019972324371338,4.001925103129183,1739502668.7022302,29.019972324371338,53.84386624838429,1739502668.7022328,29.019972324371338,50.40768635415465,1739502668.702234,29.019972324371338,7.493288554177723,1739502668.7022357,29.019972324371338,1.812111421628833,1739502668.702237,29.019972324371338,1.2057937755127,1739502668.7022383,29.019972324371338,0.6108,1739502668.7022395,29.019972324371338,0.9528056905245168,1739502668.7022407,29.019972324371338,0.0,1739502668.7022421,29.019972324371338,-0.029081688929247895,1739502668.7022433,29.019972324371338,1.4701266144659868,1739502668.7022445,29.019972324371338,0.9818873794537647 +1739502668.721684,29.03997230529785,51.266949315596854,1739502668.7216861,29.03997230529785,4.001925103129183,1739502668.7216885,29.03997230529785,53.84386624838429,1739502668.7216911,29.03997230529785,50.40768635415465,1739502668.7216923,29.03997230529785,7.493288554177723,1739502668.721694,29.03997230529785,1.812111421628833,1739502668.7216952,29.03997230529785,1.2057937755127,1739502668.7216966,29.03997230529785,0.6108,1739502668.7216976,29.03997230529785,0.9528056905245168,1739502668.721699,29.03997230529785,0.0,1739502668.7217002,29.03997230529785,-0.029081688929247895,1739502668.7217016,29.03997230529785,1.4701266144659868,1739502668.7217026,29.03997230529785,0.9818873794537647 +1739502668.7421427,29.059972286224365,51.266949315596854,1739502668.7421458,29.059972286224365,4.001925103129183,1739502668.7421498,29.059972286224365,53.84386624838429,1739502668.742154,29.059972286224365,50.40768635415465,1739502668.7421556,29.059972286224365,7.493288554177723,1739502668.7421584,29.059972286224365,1.812111421628833,1739502668.74216,29.059972286224365,1.2057937755127,1739502668.7421618,29.059972286224365,0.6108,1739502668.742163,29.059972286224365,0.9528056905245168,1739502668.7421722,29.059972286224365,0.0,1739502668.7421782,29.059972286224365,-0.029081688929247895,1739502668.7421846,29.059972286224365,1.4701266144659868,1739502668.7421863,29.059972286224365,0.9818873794537647 +1739502668.761755,29.07997226715088,51.266949315596854,1739502668.761757,29.07997226715088,4.001925103129183,1739502668.7617598,29.07997226715088,53.84386624838429,1739502668.7617624,29.07997226715088,50.40768635415465,1739502668.7617633,29.07997226715088,7.493288554177723,1739502668.761765,29.07997226715088,1.812111421628833,1739502668.7617664,29.07997226715088,1.2057937755127,1739502668.7617676,29.07997226715088,0.6108,1739502668.761769,29.07997226715088,0.9528056905245168,1739502668.7617705,29.07997226715088,0.0,1739502668.7617717,29.07997226715088,-0.029081688929247895,1739502668.761773,29.07997226715088,1.4701266144659868,1739502668.7617743,29.07997226715088,0.9818873794537647 +1739502668.7816024,29.099972248077393,51.266949315596854,1739502668.7816045,29.099972248077393,4.001925103129183,1739502668.7816072,29.099972248077393,53.84386624838429,1739502668.7816098,29.099972248077393,50.40768635415465,1739502668.781611,29.099972248077393,7.493288554177723,1739502668.7816126,29.099972248077393,1.812111421628833,1739502668.7816138,29.099972248077393,1.2057937755127,1739502668.781615,29.099972248077393,0.6108,1739502668.7816162,29.099972248077393,0.9528056905245168,1739502668.7816176,29.099972248077393,0.0,1739502668.7816188,29.099972248077393,-0.029081688929247895,1739502668.7816205,29.099972248077393,1.4701266144659868,1739502668.7816217,29.099972248077393,0.9818873794537647 +1739502668.8017697,29.119972229003906,51.27644271424494,1739502668.801772,29.119972229003906,4.109365661867949,1739502668.8017747,29.119972229003906,53.99293654410807,1739502668.8017776,29.119972229003906,50.301376771383886,1739502668.801779,29.119972229003906,7.588917846279991,1739502668.8017805,29.119972229003906,1.8440159069810937,1739502668.8017817,29.119972229003906,1.2264820220581045,1739502668.8017833,29.119972229003906,0.6108,1739502668.8017848,29.119972229003906,0.9371659676771033,1739502668.8017864,29.119972229003906,0.0,1739502668.8017876,29.119972229003906,-0.04741557542617229,1739502668.8017893,29.119972229003906,1.497728303408536,1739502668.8017905,29.119972229003906,0.9788521998165365 +1739502668.821707,29.13997220993042,51.27644271424494,1739502668.8217094,29.13997220993042,4.109365661867949,1739502668.821712,29.13997220993042,53.99293654410807,1739502668.8217149,29.13997220993042,50.301376771383886,1739502668.8217163,29.13997220993042,7.588917846279991,1739502668.821718,29.13997220993042,1.8440159069810937,1739502668.8217194,29.13997220993042,1.2264820220581045,1739502668.821721,29.13997220993042,0.6108,1739502668.8217223,29.13997220993042,0.9371659676771033,1739502668.821724,29.13997220993042,0.0,1739502668.8217251,29.13997220993042,-0.04168623213943323,1739502668.8217268,29.13997220993042,1.497728303408536,1739502668.821728,29.13997220993042,0.9788521998165365 +1739502668.8417227,29.159972190856934,51.27644271424494,1739502668.8417249,29.159972190856934,4.109365661867949,1739502668.8417275,29.159972190856934,53.99293654410807,1739502668.8417304,29.159972190856934,50.301376771383886,1739502668.8417315,29.159972190856934,7.588917846279991,1739502668.8417335,29.159972190856934,1.8440159069810937,1739502668.8417346,29.159972190856934,1.2264820220581045,1739502668.8417358,29.159972190856934,0.6108,1739502668.8417373,29.159972190856934,0.9371659676771033,1739502668.8417387,29.159972190856934,0.0,1739502668.8417401,29.159972190856934,-0.04168623213943323,1739502668.8417413,29.159972190856934,1.497728303408536,1739502668.8417428,29.159972190856934,0.9788521998165365 +1739502668.8618593,29.179972171783447,51.27644271424494,1739502668.861862,29.179972171783447,4.109365661867949,1739502668.861865,29.179972171783447,53.99293654410807,1739502668.8618677,29.179972171783447,50.301376771383886,1739502668.8618693,29.179972171783447,7.588917846279991,1739502668.861871,29.179972171783447,1.8440159069810937,1739502668.8618727,29.179972171783447,1.2264820220581045,1739502668.861874,29.179972171783447,0.6108,1739502668.8618755,29.179972171783447,0.9371659676771033,1739502668.8618772,29.179972171783447,0.0,1739502668.8618789,29.179972171783447,-0.04168623213943323,1739502668.8618803,29.179972171783447,1.497728303408536,1739502668.861882,29.179972171783447,0.9788521998165365 +1739502668.881848,29.19997215270996,51.27644271424494,1739502668.8818505,29.19997215270996,4.109365661867949,1739502668.8818536,29.19997215270996,53.99293654410807,1739502668.8818567,29.19997215270996,50.301376771383886,1739502668.8818583,29.19997215270996,7.588917846279991,1739502668.8818603,29.19997215270996,1.8440159069810937,1739502668.881862,29.19997215270996,1.2264820220581045,1739502668.8818634,29.19997215270996,0.6108,1739502668.881865,29.19997215270996,0.9371659676771033,1739502668.8818665,29.19997215270996,0.0,1739502668.8818681,29.19997215270996,-0.04168623213943323,1739502668.8818696,29.19997215270996,1.497728303408536,1739502668.881871,29.19997215270996,0.9788521998165365 +1739502668.9019036,29.219972133636475,51.2829426463818,1739502668.901906,29.219972133636475,4.216613497061765,1739502668.9019096,29.219972133636475,54.07109689191094,1739502668.9019122,29.219972133636475,50.24875824083117,1739502668.901914,29.219972133636475,7.6336162306940984,1739502668.9019163,29.219972133636475,1.8646901855550937,1739502668.9019175,29.219972133636475,1.1884207318285136,1739502668.901919,29.219972133636475,0.6108,1739502668.9019203,29.219972133636475,0.9661406513193578,1739502668.9019222,29.219972133636475,0.0,1739502668.9019237,29.219972133636475,0.007085998391138791,1739502668.901925,29.219972133636475,1.5253299923510852,1739502668.9019268,29.219972133636475,0.9742959849620187 +1739502668.9218657,29.23997211456299,51.2829426463818,1739502668.921868,29.23997211456299,4.216613497061765,1739502668.9218712,29.23997211456299,54.07109689191094,1739502668.9218738,29.23997211456299,50.24875824083117,1739502668.9218755,29.23997211456299,7.6336162306940984,1739502668.9218771,29.23997211456299,1.8646901855550937,1739502668.921879,29.23997211456299,1.1884207318285136,1739502668.9218805,29.23997211456299,0.6108,1739502668.921882,29.23997211456299,0.9661406513193578,1739502668.9218836,29.23997211456299,0.0,1739502668.9218853,29.23997211456299,-0.008155333642660967,1739502668.9218864,29.23997211456299,1.5253299923510852,1739502668.921888,29.23997211456299,0.9742959849620187 +1739502668.9419458,29.259972095489502,51.2829426463818,1739502668.941951,29.259972095489502,4.216613497061765,1739502668.9419556,29.259972095489502,54.07109689191094,1739502668.9419587,29.259972095489502,50.24875824083117,1739502668.94196,29.259972095489502,7.6336162306940984,1739502668.9419622,29.259972095489502,1.8646901855550937,1739502668.9419637,29.259972095489502,1.1884207318285136,1739502668.941965,29.259972095489502,0.6108,1739502668.9419665,29.259972095489502,0.9661406513193578,1739502668.9419682,29.259972095489502,0.0,1739502668.9419696,29.259972095489502,-0.008155333642660967,1739502668.9419713,29.259972095489502,1.5253299923510852,1739502668.9419727,29.259972095489502,0.9742959849620187 +1739502668.9618661,29.279972076416016,51.2829426463818,1739502668.9618685,29.279972076416016,4.216613497061765,1739502668.9618716,29.279972076416016,54.07109689191094,1739502668.9618745,29.279972076416016,50.24875824083117,1739502668.961876,29.279972076416016,7.6336162306940984,1739502668.9618778,29.279972076416016,1.8646901855550937,1739502668.9618793,29.279972076416016,1.1884207318285136,1739502668.961881,29.279972076416016,0.6108,1739502668.961882,29.279972076416016,0.9661406513193578,1739502668.961884,29.279972076416016,0.0,1739502668.9618855,29.279972076416016,-0.008155333642660967,1739502668.961887,29.279972076416016,1.5253299923510852,1739502668.9618883,29.279972076416016,0.9742959849620187 +1739502668.9819448,29.29997205734253,51.2829426463818,1739502668.9819472,29.29997205734253,4.216613497061765,1739502668.9819505,29.29997205734253,54.07109689191094,1739502668.9819534,29.29997205734253,50.24875824083117,1739502668.981955,29.29997205734253,7.6336162306940984,1739502668.981957,29.29997205734253,1.8646901855550937,1739502668.9819584,29.29997205734253,1.1884207318285136,1739502668.9819596,29.29997205734253,0.6108,1739502668.9819615,29.29997205734253,0.9661406513193578,1739502668.981963,29.29997205734253,0.0,1739502668.9819646,29.29997205734253,-0.008155333642660967,1739502668.981966,29.29997205734253,1.5253299923510852,1739502668.9819677,29.29997205734253,0.9742959849620187 +1739502669.0081062,29.319972038269043,51.2829426463818,1739502669.0081158,29.319972038269043,4.216613497061765,1739502669.0081263,29.319972038269043,54.07109689191094,1739502669.0081365,29.319972038269043,50.24875824083117,1739502669.0081413,29.319972038269043,7.6336162306940984,1739502669.0081477,29.319972038269043,1.8646901855550937,1739502669.0081527,29.319972038269043,1.1884207318285136,1739502669.008158,29.319972038269043,0.6108,1739502669.008163,29.319972038269043,0.9661406513193578,1739502669.0081685,29.319972038269043,0.0,1739502669.0081735,29.319972038269043,-0.008155333642660967,1739502669.0081787,29.319972038269043,1.5253299923510852,1739502669.0081837,29.319972038269043,0.9742959849620187 +1739502669.0219216,29.339972019195557,51.28646967912529,1739502669.0219243,29.339972019195557,4.32370873086624,1739502669.0219283,29.339972019195557,54.17115707217145,1739502669.021931,29.339972019195557,50.17216065609314,1739502669.0219324,29.339972019195557,7.696139172701053,1739502669.021934,29.339972019195557,1.8899200689863644,1739502669.0219355,29.339972019195557,1.1743752841370059,1739502669.0219371,29.339972019195557,0.6108,1739502669.0219383,29.339972019195557,0.9770577731874058,1739502669.02194,29.339972019195557,0.0,1739502669.0219412,29.339972019195557,0.0085839848036056,1739502669.0219429,29.339972019195557,1.5529316812936345,1739502669.0219445,29.339972019195557,0.9737048288279959 +1739502669.041669,29.35997200012207,51.28646967912529,1739502669.0416708,29.35997200012207,4.32370873086624,1739502669.041674,29.35997200012207,54.17115707217145,1739502669.0416765,29.35997200012207,50.17216065609314,1739502669.0416777,29.35997200012207,7.696139172701053,1739502669.0416796,29.35997200012207,1.8899200689863644,1739502669.0416808,29.35997200012207,1.1743752841370059,1739502669.0416822,29.35997200012207,0.6108,1739502669.0416834,29.35997200012207,0.9770577731874058,1739502669.041685,29.35997200012207,0.0,1739502669.0416863,29.35997200012207,0.003352944359409915,1739502669.0416875,29.35997200012207,1.5529316812936345,1739502669.041689,29.35997200012207,0.9737048288279959 +1739502669.0616963,29.379971981048584,51.28646967912529,1739502669.0616987,29.379971981048584,4.32370873086624,1739502669.0617013,29.379971981048584,54.17115707217145,1739502669.061704,29.379971981048584,50.17216065609314,1739502669.061705,29.379971981048584,7.696139172701053,1739502669.061707,29.379971981048584,1.8899200689863644,1739502669.0617082,29.379971981048584,1.1743752841370059,1739502669.06171,29.379971981048584,0.6108,1739502669.061711,29.379971981048584,0.9770577731874058,1739502669.0617123,29.379971981048584,0.0,1739502669.061714,29.379971981048584,0.003352944359409915,1739502669.0617151,29.379971981048584,1.5529316812936345,1739502669.0617166,29.379971981048584,0.9737048288279959 +1739502669.089278,29.399971961975098,51.28646967912529,1739502669.089289,29.399971961975098,4.32370873086624,1739502669.0893023,29.399971961975098,54.17115707217145,1739502669.0893135,29.399971961975098,50.17216065609314,1739502669.089319,29.399971961975098,7.696139172701053,1739502669.089326,29.399971961975098,1.8899200689863644,1739502669.0893319,29.399971961975098,1.1743752841370059,1739502669.089338,29.399971961975098,0.6108,1739502669.0893433,29.399971961975098,0.9770577731874058,1739502669.0893645,29.399971961975098,0.0,1739502669.0893693,29.399971961975098,0.003352944359409915,1739502669.0893755,29.399971961975098,1.5529316812936345,1739502669.0893815,29.399971961975098,0.9737048288279959 +1739502669.1038787,29.41997194290161,51.28646967912529,1739502669.103883,29.41997194290161,4.32370873086624,1739502669.1038897,29.41997194290161,54.17115707217145,1739502669.1038947,29.41997194290161,50.17216065609314,1739502669.1038978,29.41997194290161,7.696139172701053,1739502669.1039011,29.41997194290161,1.8899200689863644,1739502669.1039038,29.41997194290161,1.1743752841370059,1739502669.1039064,29.41997194290161,0.6108,1739502669.103909,29.41997194290161,0.9770577731874058,1739502669.1039119,29.41997194290161,0.0,1739502669.1039145,29.41997194290161,0.003352944359409915,1739502669.1039174,29.41997194290161,1.5529316812936345,1739502669.1039202,29.41997194290161,0.9737048288279959 +1739502669.1234276,29.439971923828125,51.28703928045949,1739502669.123431,29.439971923828125,4.430827216195938,1739502669.123435,29.439971923828125,54.345856065072894,1739502669.1234388,29.439971923828125,50.03228739613409,1739502669.1234412,29.439971923828125,7.8019474387463275,1739502669.1234434,29.439971923828125,1.9271154007670748,1739502669.1234455,29.439971923828125,1.2218681779033929,1739502669.1234477,29.439971923828125,0.6108,1739502669.123449,29.439971923828125,0.9406315097084551,1739502669.1234515,29.439971923828125,0.0,1739502669.1234531,29.439971923828125,-0.05015097783791825,1739502669.123455,29.439971923828125,1.5805333702361837,1739502669.1234567,29.439971923828125,0.9740625008972308 +1739502669.1433365,29.45997190475464,51.28703928045949,1739502669.1433396,29.45997190475464,4.430827216195938,1739502669.1433434,29.45997190475464,54.345856065072894,1739502669.143347,29.45997190475464,50.03228739613409,1739502669.143349,29.45997190475464,7.8019474387463275,1739502669.1433513,29.45997190475464,1.9271154007670748,1739502669.143353,29.45997190475464,1.2218681779033929,1739502669.1433551,29.45997190475464,0.6108,1739502669.1433566,29.45997190475464,0.9406315097084551,1739502669.1433587,29.45997190475464,0.0,1739502669.1433606,29.45997190475464,-0.03343099118877568,1739502669.1433623,29.45997190475464,1.5805333702361837,1739502669.1433647,29.45997190475464,0.9740625008972308 +1739502669.163354,29.479971885681152,51.28703928045949,1739502669.1633575,29.479971885681152,4.430827216195938,1739502669.1633615,29.479971885681152,54.345856065072894,1739502669.1633651,29.479971885681152,50.03228739613409,1739502669.1633673,29.479971885681152,7.8019474387463275,1739502669.1633692,29.479971885681152,1.9271154007670748,1739502669.1633713,29.479971885681152,1.2218681779033929,1739502669.163373,29.479971885681152,0.6108,1739502669.163375,29.479971885681152,0.9406315097084551,1739502669.1633768,29.479971885681152,0.0,1739502669.1633787,29.479971885681152,-0.03343099118877568,1739502669.1633806,29.479971885681152,1.5805333702361837,1739502669.1633828,29.479971885681152,0.9740625008972308 +1739502669.1830356,29.499971866607666,51.28703928045949,1739502669.1830387,29.499971866607666,4.430827216195938,1739502669.1830425,29.499971866607666,54.345856065072894,1739502669.1830463,29.499971866607666,50.03228739613409,1739502669.1830482,29.499971866607666,7.8019474387463275,1739502669.1830504,29.499971866607666,1.9271154007670748,1739502669.1830525,29.499971866607666,1.2218681779033929,1739502669.1830544,29.499971866607666,0.6108,1739502669.183056,29.499971866607666,0.9406315097084551,1739502669.1830583,29.499971866607666,0.0,1739502669.1830602,29.499971866607666,-0.03343099118877568,1739502669.183062,29.499971866607666,1.5805333702361837,1739502669.1830637,29.499971866607666,0.9740625008972308 +1739502669.2058315,29.51997184753418,51.28703928045949,1739502669.205836,29.51997184753418,4.430827216195938,1739502669.205841,29.51997184753418,54.345856065072894,1739502669.2058456,29.51997184753418,50.03228739613409,1739502669.2058473,29.51997184753418,7.8019474387463275,1739502669.20585,29.51997184753418,1.9271154007670748,1739502669.2058516,29.51997184753418,1.2218681779033929,1739502669.2058535,29.51997184753418,0.6108,1739502669.2058554,29.51997184753418,0.9406315097084551,1739502669.2058578,29.51997184753418,0.0,1739502669.2058597,29.51997184753418,-0.03343099118877568,1739502669.2058616,29.51997184753418,1.5805333702361837,1739502669.2058637,29.51997184753418,0.9740625008972308 +1739502669.2238426,29.539971828460693,51.28703928045949,1739502669.2238455,29.539971828460693,4.430827216195938,1739502669.2238495,29.539971828460693,54.345856065072894,1739502669.2238533,29.539971828460693,50.03228739613409,1739502669.223855,29.539971828460693,7.8019474387463275,1739502669.2238574,29.539971828460693,1.9271154007670748,1739502669.2238593,29.539971828460693,1.2218681779033929,1739502669.223861,29.539971828460693,0.6108,1739502669.223863,29.539971828460693,0.9406315097084551,1739502669.2238648,29.539971828460693,0.0,1739502669.2238667,29.539971828460693,-0.03343099118877568,1739502669.2238686,29.539971828460693,1.5805333702361837,1739502669.2238705,29.539971828460693,0.9740625008972308 +1739502669.25591,29.559971809387207,51.28465774264606,1739502669.2559192,29.559971809387207,4.537729038449298,1739502669.2559302,29.559971809387207,54.45590196602243,1739502669.2559407,29.559971809387207,49.9497262390568,1739502669.2559457,29.559971809387207,7.861933279435291,1739502669.2559521,29.559971809387207,1.9526633994298583,1739502669.2559574,29.559971809387207,1.2099083104405213,1739502669.2559621,29.559971809387207,0.6108,1739502669.2559671,29.559971809387207,0.9496745647676575,1739502669.2559729,29.559971809387207,0.0,1739502669.2559776,29.559971809387207,-0.014463829605130952,1739502669.255983,29.559971809387207,1.608135059178733,1739502669.2559881,29.559971809387207,0.9700656362538801 +1739502669.2848563,29.599971771240234,51.28465774264606,1739502669.2848613,29.599971771240234,4.537729038449298,1739502669.284867,29.599971771240234,54.45590196602243,1739502669.2848725,29.599971771240234,49.9497262390568,1739502669.284875,29.599971771240234,7.861933279435291,1739502669.2848785,29.599971771240234,1.9526633994298583,1739502669.2848814,29.599971771240234,1.2099083104405213,1739502669.284884,29.599971771240234,0.6108,1739502669.2848866,29.599971771240234,0.9496745647676575,1739502669.28489,29.599971771240234,0.0,1739502669.2848923,29.599971771240234,-0.020391071486222545,1739502669.2848952,29.599971771240234,1.608135059178733,1739502669.284898,29.599971771240234,0.9700656362538801 +1739502669.306282,29.619971752166748,51.28465774264606,1739502669.3062887,29.619971752166748,4.537729038449298,1739502669.3062975,29.619971752166748,54.45590196602243,1739502669.3063037,29.619971752166748,49.9497262390568,1739502669.306307,29.619971752166748,7.861933279435291,1739502669.3063111,29.619971752166748,1.9526633994298583,1739502669.3063142,29.619971752166748,1.2099083104405213,1739502669.306317,29.619971752166748,0.6108,1739502669.306321,29.619971752166748,0.9496745647676575,1739502669.306324,29.619971752166748,0.0,1739502669.3063276,29.619971752166748,-0.020391071486222545,1739502669.3063312,29.619971752166748,1.608135059178733,1739502669.3063345,29.619971752166748,0.9700656362538801 +1739502669.3241274,29.63997173309326,51.28465774264606,1739502669.3241305,29.63997173309326,4.537729038449298,1739502669.324134,29.63997173309326,54.45590196602243,1739502669.3241377,29.63997173309326,49.9497262390568,1739502669.3241396,29.63997173309326,7.861933279435291,1739502669.3241417,29.63997173309326,1.9526633994298583,1739502669.3241436,29.63997173309326,1.2099083104405213,1739502669.3241453,29.63997173309326,0.6108,1739502669.3241472,29.63997173309326,0.9496745647676575,1739502669.3241491,29.63997173309326,0.0,1739502669.324151,29.63997173309326,-0.020391071486222545,1739502669.3241532,29.63997173309326,1.608135059178733,1739502669.3241549,29.63997173309326,0.9700656362538801 +1739502669.3438148,29.659971714019775,51.279343743527996,1739502669.3438172,29.659971714019775,4.644176671039832,1739502669.3438203,29.659971714019775,54.614108735412216,1739502669.3438232,29.659971714019775,49.821976384962674,1739502669.3438244,29.659971714019775,7.947151283567967,1739502669.3438258,29.659971714019775,1.9863321834037386,1739502669.3438272,29.659971714019775,1.2399495609029203,1739502669.3438287,29.659971714019775,0.6108,1739502669.34383,29.659971714019775,0.9271231105927804,1739502669.3438313,29.659971714019775,0.0,1739502669.3438325,29.659971714019775,-0.04983048014058825,1739502669.3438342,29.659971714019775,1.6357367481212821,1739502669.3438356,29.659971714019775,0.9677537694970065 +1739502669.3634598,29.67997169494629,51.279343743527996,1739502669.3634624,29.67997169494629,4.644176671039832,1739502669.3634655,29.67997169494629,54.614108735412216,1739502669.3634686,29.67997169494629,49.821976384962674,1739502669.3634698,29.67997169494629,7.947151283567967,1739502669.3634715,29.67997169494629,1.9863321834037386,1739502669.3634732,29.67997169494629,1.2399495609029203,1739502669.3634746,29.67997169494629,0.6108,1739502669.363476,29.67997169494629,0.9271231105927804,1739502669.3634777,29.67997169494629,0.0,1739502669.3634791,29.67997169494629,-0.040630658904226125,1739502669.3634806,29.67997169494629,1.6357367481212821,1739502669.363482,29.67997169494629,0.9677537694970065 +1739502669.384998,29.699971675872803,51.279343743527996,1739502669.385001,29.699971675872803,4.644176671039832,1739502669.385004,29.699971675872803,54.614108735412216,1739502669.3850071,29.699971675872803,49.821976384962674,1739502669.3850088,29.699971675872803,7.947151283567967,1739502669.3850105,29.699971675872803,1.9863321834037386,1739502669.385012,29.699971675872803,1.2399495609029203,1739502669.3850133,29.699971675872803,0.6108,1739502669.3850145,29.699971675872803,0.9271231105927804,1739502669.385016,29.699971675872803,0.0,1739502669.3850174,29.699971675872803,-0.040630658904226125,1739502669.3850188,29.699971675872803,1.6357367481212821,1739502669.3850205,29.699971675872803,0.9677537694970065 +1739502669.403325,29.719971656799316,51.279343743527996,1739502669.4033272,29.719971656799316,4.644176671039832,1739502669.4033303,29.719971656799316,54.614108735412216,1739502669.403333,29.719971656799316,49.821976384962674,1739502669.4033341,29.719971656799316,7.947151283567967,1739502669.403336,29.719971656799316,1.9863321834037386,1739502669.4033372,29.719971656799316,1.2399495609029203,1739502669.4033387,29.719971656799316,0.6108,1739502669.40334,29.719971656799316,0.9271231105927804,1739502669.4033415,29.719971656799316,0.0,1739502669.4033425,29.719971656799316,-0.040630658904226125,1739502669.4033442,29.719971656799316,1.6357367481212821,1739502669.4033453,29.719971656799316,0.9677537694970065 +1739502669.4229498,29.73997163772583,51.279343743527996,1739502669.422952,29.73997163772583,4.644176671039832,1739502669.4229546,29.73997163772583,54.614108735412216,1739502669.422957,29.73997163772583,49.821976384962674,1739502669.4229584,29.73997163772583,7.947151283567967,1739502669.42296,29.73997163772583,1.9863321834037386,1739502669.4229617,29.73997163772583,1.2399495609029203,1739502669.422963,29.73997163772583,0.6108,1739502669.4229643,29.73997163772583,0.9271231105927804,1739502669.4229658,29.73997163772583,0.0,1739502669.422967,29.73997163772583,-0.040630658904226125,1739502669.4229684,29.73997163772583,1.6357367481212821,1739502669.4229696,29.73997163772583,0.9677537694970065 +1739502669.4430902,29.759971618652344,51.279343743527996,1739502669.4430928,29.759971618652344,4.644176671039832,1739502669.4430952,29.759971618652344,54.614108735412216,1739502669.4430978,29.759971618652344,49.821976384962674,1739502669.4430997,29.759971618652344,7.947151283567967,1739502669.4431012,29.759971618652344,1.9863321834037386,1739502669.4431024,29.759971618652344,1.2399495609029203,1739502669.4431038,29.759971618652344,0.6108,1739502669.4431047,29.759971618652344,0.9271231105927804,1739502669.4431064,29.759971618652344,0.0,1739502669.4431076,29.759971618652344,-0.040630658904226125,1739502669.4431088,29.759971618652344,1.6357367481212821,1739502669.4431105,29.759971618652344,0.9677537694970065 +1739502669.4650154,29.779971599578857,51.271123333442496,1739502669.4650176,29.779971599578857,4.750067208471215,1739502669.4650204,29.779971599578857,54.69719249701436,1739502669.465023,29.779971599578857,49.75954781348303,1739502669.4650245,29.779971599578857,7.986517341063742,1739502669.4650261,29.779971599578857,2.007736061686445,1739502669.4650276,29.779971599578857,1.2060269313719993,1739502669.4650295,29.779971599578857,0.6108,1739502669.4650307,29.779971599578857,0.9526279853146208,1739502669.465032,29.779971599578857,0.0,1739502669.4650335,29.779971599578857,0.003211645908907032,1739502669.465035,29.779971599578857,1.6633384370638313,1739502669.4650366,29.779971599578857,0.963117068642716 +1739502669.48298,29.79997158050537,51.271123333442496,1739502669.4829824,29.79997158050537,4.750067208471215,1739502669.482985,29.79997158050537,54.69719249701436,1739502669.4829874,29.79997158050537,49.75954781348303,1739502669.4829888,29.79997158050537,7.986517341063742,1739502669.4829905,29.79997158050537,2.007736061686445,1739502669.482992,29.79997158050537,1.2060269313719993,1739502669.4829931,29.79997158050537,0.6108,1739502669.4829943,29.79997158050537,0.9526279853146208,1739502669.482996,29.79997158050537,0.0,1739502669.4829972,29.79997158050537,-0.010489083328095172,1739502669.482999,29.79997158050537,1.6633384370638313,1739502669.4830003,29.79997158050537,0.963117068642716 +1739502669.5031073,29.819971561431885,51.271123333442496,1739502669.50311,29.819971561431885,4.750067208471215,1739502669.503113,29.819971561431885,54.69719249701436,1739502669.503116,29.819971561431885,49.75954781348303,1739502669.5031173,29.819971561431885,7.986517341063742,1739502669.503119,29.819971561431885,2.007736061686445,1739502669.5031204,29.819971561431885,1.2060269313719993,1739502669.5031219,29.819971561431885,0.6108,1739502669.5031233,29.819971561431885,0.9526279853146208,1739502669.503125,29.819971561431885,0.0,1739502669.5031266,29.819971561431885,-0.010489083328095172,1739502669.503128,29.819971561431885,1.6633384370638313,1739502669.5031295,29.819971561431885,0.963117068642716 +1739502669.5231285,29.8399715423584,51.271123333442496,1739502669.5231311,29.8399715423584,4.750067208471215,1739502669.5231342,29.8399715423584,54.69719249701436,1739502669.5231373,29.8399715423584,49.75954781348303,1739502669.5231388,29.8399715423584,7.986517341063742,1739502669.5231407,29.8399715423584,2.007736061686445,1739502669.5231419,29.8399715423584,1.2060269313719993,1739502669.5231435,29.8399715423584,0.6108,1739502669.523145,29.8399715423584,0.9526279853146208,1739502669.5231464,29.8399715423584,0.0,1739502669.5231478,29.8399715423584,-0.010489083328095172,1739502669.5231493,29.8399715423584,1.6633384370638313,1739502669.523151,29.8399715423584,0.963117068642716 +1739502669.5432827,29.859971523284912,51.271123333442496,1739502669.5432851,29.859971523284912,4.750067208471215,1739502669.543289,29.859971523284912,54.69719249701436,1739502669.5432918,29.859971523284912,49.75954781348303,1739502669.5432937,29.859971523284912,7.986517341063742,1739502669.5432959,29.859971523284912,2.007736061686445,1739502669.5432973,29.859971523284912,1.2060269313719993,1739502669.5432987,29.859971523284912,0.6108,1739502669.5433004,29.859971523284912,0.9526279853146208,1739502669.543302,29.859971523284912,0.0,1739502669.5433037,29.859971523284912,-0.010489083328095172,1739502669.5433054,29.859971523284912,1.6633384370638313,1739502669.543307,29.859971523284912,0.963117068642716 +1739502669.5634098,29.879971504211426,51.260017776037174,1739502669.5634124,29.879971504211426,4.855358629228681,1739502669.563416,29.879971504211426,54.85595339944647,1739502669.5634189,29.879971504211426,49.624966532008045,1739502669.5634205,29.879971504211426,8.066203146363867,1739502669.5634224,29.879971504211426,2.041798883373426,1739502669.563424,29.879971504211426,1.2384291547610147,1739502669.5634258,29.879971504211426,0.6108,1739502669.5634272,29.879971504211426,0.9282514796226669,1739502669.5634296,29.879971504211426,0.0,1739502669.5634313,29.879971504211426,-0.044238847506355816,1739502669.5634327,29.879971504211426,1.6909401260063806,1739502669.5634346,29.879971504211426,0.9619435189082899 +1739502669.583261,29.89997148513794,51.260017776037174,1739502669.5832636,29.89997148513794,4.855358629228681,1739502669.5832672,29.89997148513794,54.85595339944647,1739502669.5832703,29.89997148513794,49.624966532008045,1739502669.583272,29.89997148513794,8.066203146363867,1739502669.583274,29.89997148513794,2.041798883373426,1739502669.5832756,29.89997148513794,1.2384291547610147,1739502669.583277,29.89997148513794,0.6108,1739502669.5832787,29.89997148513794,0.9282514796226669,1739502669.5832806,29.89997148513794,0.0,1739502669.5832822,29.89997148513794,-0.03369203928562303,1739502669.5832837,29.89997148513794,1.6909401260063806,1739502669.5832856,29.89997148513794,0.9619435189082899 +1739502669.6034148,29.919971466064453,51.260017776037174,1739502669.6034179,29.919971466064453,4.855358629228681,1739502669.6034212,29.919971466064453,54.85595339944647,1739502669.6034243,29.919971466064453,49.624966532008045,1739502669.6034257,29.919971466064453,8.066203146363867,1739502669.603428,29.919971466064453,2.041798883373426,1739502669.6034293,29.919971466064453,1.2384291547610147,1739502669.603431,29.919971466064453,0.6108,1739502669.6034324,29.919971466064453,0.9282514796226669,1739502669.6034343,29.919971466064453,0.0,1739502669.6034358,29.919971466064453,-0.03369203928562303,1739502669.6034377,29.919971466064453,1.6909401260063806,1739502669.603439,29.919971466064453,0.9619435189082899 +1739502669.6232972,29.939971446990967,51.260017776037174,1739502669.6232998,29.939971446990967,4.855358629228681,1739502669.6233034,29.939971446990967,54.85595339944647,1739502669.6233065,29.939971446990967,49.624966532008045,1739502669.623308,29.939971446990967,8.066203146363867,1739502669.6233099,29.939971446990967,2.041798883373426,1739502669.6233115,29.939971446990967,1.2384291547610147,1739502669.6233132,29.939971446990967,0.6108,1739502669.6233146,29.939971446990967,0.9282514796226669,1739502669.6233165,29.939971446990967,0.0,1739502669.623318,29.939971446990967,-0.03369203928562303,1739502669.6233196,29.939971446990967,1.6909401260063806,1739502669.623321,29.939971446990967,0.9619435189082899 +1739502669.6433008,29.95997142791748,51.260017776037174,1739502669.6433034,29.95997142791748,4.855358629228681,1739502669.6433067,29.95997142791748,54.85595339944647,1739502669.6433098,29.95997142791748,49.624966532008045,1739502669.6433113,29.95997142791748,8.066203146363867,1739502669.6433134,29.95997142791748,2.041798883373426,1739502669.6433148,29.95997142791748,1.2384291547610147,1739502669.6433165,29.95997142791748,0.6108,1739502669.643318,29.95997142791748,0.9282514796226669,1739502669.6433198,29.95997142791748,0.0,1739502669.6433213,29.95997142791748,-0.03369203928562303,1739502669.643323,29.95997142791748,1.6909401260063806,1739502669.6433244,29.95997142791748,0.9619435189082899 +1739502669.6635091,29.979971408843994,51.260017776037174,1739502669.663512,29.979971408843994,4.855358629228681,1739502669.6635156,29.979971408843994,54.85595339944647,1739502669.663519,29.979971408843994,49.624966532008045,1739502669.6635206,29.979971408843994,8.066203146363867,1739502669.6635222,29.979971408843994,2.041798883373426,1739502669.6635242,29.979971408843994,1.2384291547610147,1739502669.6635256,29.979971408843994,0.6108,1739502669.663527,29.979971408843994,0.9282514796226669,1739502669.6635287,29.979971408843994,0.0,1739502669.6635306,29.979971408843994,-0.03369203928562303,1739502669.663532,29.979971408843994,1.6909401260063806,1739502669.663534,29.979971408843994,0.9619435189082899 +1739502669.6851568,29.999971389770508,51.24604701077133,1739502669.68516,29.999971389770508,4.960036000753799,1739502669.6851635,29.999971389770508,54.95589043784319,1739502669.6851668,29.999971389770508,49.54458746937684,1739502669.6851683,29.999971389770508,8.111225016703541,1739502669.6851704,29.999971389770508,2.065884743029347,1739502669.685172,29.999971389770508,1.2190409550679555,1739502669.6851735,29.999971389770508,0.6108,1739502669.685175,29.999971389770508,0.9427614173971139,1739502669.685177,29.999971389770508,0.0,1739502669.6851785,29.999971389770508,-0.006909753123853512,1739502669.6851804,29.999971389770508,1.7185418149489298,1739502669.685182,29.999971389770508,0.9580406404339725 +1739502669.703638,30.01997137069702,51.24604701077133,1739502669.703641,30.01997137069702,4.960036000753799,1739502669.7036445,30.01997137069702,54.95589043784319,1739502669.7036479,30.01997137069702,49.54458746937684,1739502669.7036493,30.01997137069702,8.111225016703541,1739502669.7036514,30.01997137069702,2.065884743029347,1739502669.703653,30.01997137069702,1.2190409550679555,1739502669.7036548,30.01997137069702,0.6108,1739502669.7036562,30.01997137069702,0.9427614173971139,1739502669.7036583,30.01997137069702,0.0,1739502669.7036598,30.01997137069702,-0.01527922303685858,1739502669.7036612,30.01997137069702,1.7185418149489298,1739502669.703663,30.01997137069702,0.9580406404339725 +1739502669.724633,30.039971351623535,51.24604701077133,1739502669.724638,30.039971351623535,4.960036000753799,1739502669.724644,30.039971351623535,54.95589043784319,1739502669.7246487,30.039971351623535,49.54458746937684,1739502669.7246518,30.039971351623535,8.111225016703541,1739502669.724655,30.039971351623535,2.065884743029347,1739502669.7246573,30.039971351623535,1.2190409550679555,1739502669.7246604,30.039971351623535,0.6108,1739502669.724663,30.039971351623535,0.9427614173971139,1739502669.7246659,30.039971351623535,0.0,1739502669.7246687,30.039971351623535,-0.01527922303685858,1739502669.7246876,30.039971351623535,1.7185418149489298,1739502669.7246914,30.039971351623535,0.9580406404339725 +1739502669.7434523,30.05997133255005,51.24604701077133,1739502669.7434554,30.05997133255005,4.960036000753799,1739502669.7434587,30.05997133255005,54.95589043784319,1739502669.7434618,30.05997133255005,49.54458746937684,1739502669.7434635,30.05997133255005,8.111225016703541,1739502669.7434654,30.05997133255005,2.065884743029347,1739502669.743467,30.05997133255005,1.2190409550679555,1739502669.7434685,30.05997133255005,0.6108,1739502669.7434702,30.05997133255005,0.9427614173971139,1739502669.743472,30.05997133255005,0.0,1739502669.7434738,30.05997133255005,-0.01527922303685858,1739502669.7434757,30.05997133255005,1.7185418149489298,1739502669.7434773,30.05997133255005,0.9580406404339725 +1739502669.7633424,30.079971313476562,51.24604701077133,1739502669.763345,30.079971313476562,4.960036000753799,1739502669.7633483,30.079971313476562,54.95589043784319,1739502669.7633512,30.079971313476562,49.54458746937684,1739502669.7633529,30.079971313476562,8.111225016703541,1739502669.7633548,30.079971313476562,2.065884743029347,1739502669.7633564,30.079971313476562,1.2190409550679555,1739502669.763358,30.079971313476562,0.6108,1739502669.7633595,30.079971313476562,0.9427614173971139,1739502669.7633615,30.079971313476562,0.0,1739502669.7633631,30.079971313476562,-0.01527922303685858,1739502669.7633646,30.079971313476562,1.7185418149489298,1739502669.7633662,30.079971313476562,0.9580406404339725 +1739502669.783594,30.099971294403076,51.22924192706406,1739502669.7835968,30.099971294403076,5.0639796824833425,1739502669.7836003,30.099971294403076,54.97110417790889,1739502669.7836034,30.099971294403076,49.534196370928065,1739502669.783605,30.099971294403076,8.116892888584694,1739502669.783607,30.099971294403076,2.0776401536723714,1739502669.783609,30.099971294403076,1.136473070186046,1739502669.7836106,30.099971294403076,0.6108,1739502669.7836123,30.099971294403076,1.0071376280268611,1739502669.783614,30.099971294403076,0.0,1739502669.7836156,30.099971294403076,0.0808151979452264,1739502669.783617,30.099971294403076,1.746143503891479,1739502669.783619,30.099971294403076,0.956351956327428 +1739502669.8036284,30.11997127532959,51.22924192706406,1739502669.803633,30.11997127532959,5.0639796824833425,1739502669.8036382,30.11997127532959,54.97110417790889,1739502669.8036444,30.11997127532959,49.534196370928065,1739502669.8036478,30.11997127532959,8.116892888584694,1739502669.8036523,30.11997127532959,2.0776401536723714,1739502669.803656,30.11997127532959,1.136473070186046,1739502669.8036604,30.11997127532959,0.6108,1739502669.8036642,30.11997127532959,1.0071376280268611,1739502669.8036683,30.11997127532959,0.0,1739502669.8036723,30.11997127532959,0.050785671699433155,1739502669.8036764,30.11997127532959,1.746143503891479,1739502669.8036804,30.11997127532959,0.956351956327428 +1739502669.8232903,30.139971256256104,51.22924192706406,1739502669.8232927,30.139971256256104,5.0639796824833425,1739502669.8232965,30.139971256256104,54.97110417790889,1739502669.8232996,30.139971256256104,49.534196370928065,1739502669.8233013,30.139971256256104,8.116892888584694,1739502669.8233035,30.139971256256104,2.0776401536723714,1739502669.823305,30.139971256256104,1.136473070186046,1739502669.8233066,30.139971256256104,0.6108,1739502669.823308,30.139971256256104,1.0071376280268611,1739502669.82331,30.139971256256104,0.0,1739502669.8233113,30.139971256256104,0.050785671699433155,1739502669.823313,30.139971256256104,1.746143503891479,1739502669.8233144,30.139971256256104,0.956351956327428 +1739502669.8432553,30.159971237182617,51.22924192706406,1739502669.8432581,30.159971237182617,5.0639796824833425,1739502669.8432615,30.159971237182617,54.97110417790889,1739502669.8432646,30.159971237182617,49.534196370928065,1739502669.843266,30.159971237182617,8.116892888584694,1739502669.8432682,30.159971237182617,2.0776401536723714,1739502669.8432696,30.159971237182617,1.136473070186046,1739502669.8432713,30.159971237182617,0.6108,1739502669.8432727,30.159971237182617,1.0071376280268611,1739502669.8432746,30.159971237182617,0.0,1739502669.843276,30.159971237182617,0.050785671699433155,1739502669.843278,30.159971237182617,1.746143503891479,1739502669.8432794,30.159971237182617,0.956351956327428 +1739502669.863506,30.17997121810913,51.22924192706406,1739502669.8635092,30.17997121810913,5.0639796824833425,1739502669.8635125,30.17997121810913,54.97110417790889,1739502669.8635159,30.17997121810913,49.534196370928065,1739502669.8635175,30.17997121810913,8.116892888584694,1739502669.8635194,30.17997121810913,2.0776401536723714,1739502669.863521,30.17997121810913,1.136473070186046,1739502669.8635225,30.17997121810913,0.6108,1739502669.8635242,30.17997121810913,1.0071376280268611,1739502669.8635259,30.17997121810913,0.0,1739502669.8635275,30.17997121810913,0.050785671699433155,1739502669.863529,30.17997121810913,1.746143503891479,1739502669.8635304,30.17997121810913,0.956351956327428 +1739502669.8833628,30.199971199035645,51.22924192706406,1739502669.8833656,30.199971199035645,5.0639796824833425,1739502669.883369,30.199971199035645,54.97110417790889,1739502669.883372,30.199971199035645,49.534196370928065,1739502669.8833735,30.199971199035645,8.116892888584694,1739502669.8833756,30.199971199035645,2.0776401536723714,1739502669.883377,30.199971199035645,1.136473070186046,1739502669.8833787,30.199971199035645,0.6108,1739502669.8833802,30.199971199035645,1.0071376280268611,1739502669.8833826,30.199971199035645,0.0,1739502669.883384,30.199971199035645,0.050785671699433155,1739502669.8833857,30.199971199035645,1.746143503891479,1739502669.883387,30.199971199035645,0.956351956327428 +1739502669.9033246,30.219971179962158,51.20952833422985,1739502669.903327,30.219971179962158,5.1676530698808545,1739502669.9033303,30.219971179962158,55.179767958856246,1739502669.9033337,30.219971179962158,49.33701563510973,1739502669.903335,30.219971179962158,8.216587416023167,1739502669.9033372,30.219971179962158,2.1215576253138853,1739502669.9033387,30.219971179962158,1.2195433458938258,1739502669.90334,30.219971179962158,0.6108,1739502669.9033415,30.219971179962158,0.942382585781157,1739502669.9033434,30.219971179962158,0.0,1739502669.9033449,30.219971179962158,-0.052369038292911556,1739502669.9033465,30.219971179962158,1.7737451928340282,1739502669.903348,30.219971179962158,0.9625157560659787 +1739502669.9232893,30.239971160888672,51.20952833422985,1739502669.923292,30.239971160888672,5.1676530698808545,1739502669.9232953,30.239971160888672,55.179767958856246,1739502669.9232986,30.239971160888672,49.33701563510973,1739502669.9233,30.239971160888672,8.216587416023167,1739502669.9233022,30.239971160888672,2.1215576253138853,1739502669.9233036,30.239971160888672,1.2195433458938258,1739502669.9233055,30.239971160888672,0.6108,1739502669.9233067,30.239971160888672,0.942382585781157,1739502669.9233086,30.239971160888672,0.0,1739502669.92331,30.239971160888672,-0.020133170284821755,1739502669.9233117,30.239971160888672,1.7737451928340282,1739502669.9233134,30.239971160888672,0.9625157560659787 +1739502669.9434295,30.259971141815186,51.20952833422985,1739502669.9434319,30.259971141815186,5.1676530698808545,1739502669.9434354,30.259971141815186,55.179767958856246,1739502669.9434385,30.259971141815186,49.33701563510973,1739502669.9434402,30.259971141815186,8.216587416023167,1739502669.943442,30.259971141815186,2.1215576253138853,1739502669.9434438,30.259971141815186,1.2195433458938258,1739502669.9434452,30.259971141815186,0.6108,1739502669.9434469,30.259971141815186,0.942382585781157,1739502669.9434485,30.259971141815186,0.0,1739502669.9434502,30.259971141815186,-0.020133170284821755,1739502669.943452,30.259971141815186,1.7737451928340282,1739502669.9434536,30.259971141815186,0.9625157560659787 +1739502669.963293,30.2799711227417,51.20952833422985,1739502669.963296,30.2799711227417,5.1676530698808545,1739502669.9632993,30.2799711227417,55.179767958856246,1739502669.9633026,30.2799711227417,49.33701563510973,1739502669.9633043,30.2799711227417,8.216587416023167,1739502669.9633062,30.2799711227417,2.1215576253138853,1739502669.9633079,30.2799711227417,1.2195433458938258,1739502669.9633093,30.2799711227417,0.6108,1739502669.963311,30.2799711227417,0.942382585781157,1739502669.9633124,30.2799711227417,0.0,1739502669.9633143,30.2799711227417,-0.020133170284821755,1739502669.9633157,30.2799711227417,1.7737451928340282,1739502669.9633174,30.2799711227417,0.9625157560659787 +1739502669.9832716,30.299971103668213,51.20952833422985,1739502669.9832747,30.299971103668213,5.1676530698808545,1739502669.983278,30.299971103668213,55.179767958856246,1739502669.9832811,30.299971103668213,49.33701563510973,1739502669.9832828,30.299971103668213,8.216587416023167,1739502669.9832847,30.299971103668213,2.1215576253138853,1739502669.9832866,30.299971103668213,1.2195433458938258,1739502669.983288,30.299971103668213,0.6108,1739502669.9832897,30.299971103668213,0.942382585781157,1739502669.9832914,30.299971103668213,0.0,1739502669.9832928,30.299971103668213,-0.020133170284821755,1739502669.9832945,30.299971103668213,1.7737451928340282,1739502669.983296,30.299971103668213,0.9625157560659787 +1739502670.0033176,30.319971084594727,51.18691021985771,1739502670.0033207,30.319971084594727,5.270985132356767,1739502670.0033238,30.319971084594727,55.24955587930495,1739502670.0033267,30.319971084594727,49.27724237599002,1739502670.0033283,30.319971084594727,8.243346069486984,1739502670.0033302,30.319971084594727,2.141863422233805,1739502670.003332,30.319971084594727,1.1799146957883533,1739502670.0033336,30.319971084594727,0.6108,1739502670.003335,30.319971084594727,0.9727374928120174,1739502670.0033371,30.319971084594727,0.0,1739502670.0033388,30.319971084594727,0.027143614380528137,1739502670.0033402,30.319971084594727,1.8013468817765774,1739502670.0033422,30.319971084594727,0.9603678833260035 +1739502670.0233,30.33997106552124,51.18691021985771,1739502670.0233023,30.33997106552124,5.270985132356767,1739502670.0233057,30.33997106552124,55.24955587930495,1739502670.0233088,30.33997106552124,49.27724237599002,1739502670.0233104,30.33997106552124,8.243346069486984,1739502670.023312,30.33997106552124,2.141863422233805,1739502670.0233138,30.33997106552124,1.1799146957883533,1739502670.0233152,30.33997106552124,0.6108,1739502670.0233166,30.33997106552124,0.9727374928120174,1739502670.0233188,30.33997106552124,0.0,1739502670.02332,30.33997106552124,0.012369609486013844,1739502670.0233219,30.33997106552124,1.8013468817765774,1739502670.0233233,30.33997106552124,0.9603678833260035 +1739502670.0432727,30.359971046447754,51.18691021985771,1739502670.0432754,30.359971046447754,5.270985132356767,1739502670.0432782,30.359971046447754,55.24955587930495,1739502670.0432813,30.359971046447754,49.27724237599002,1739502670.043283,30.359971046447754,8.243346069486984,1739502670.043285,30.359971046447754,2.141863422233805,1739502670.0432866,30.359971046447754,1.1799146957883533,1739502670.043288,30.359971046447754,0.6108,1739502670.0432897,30.359971046447754,0.9727374928120174,1739502670.0432913,30.359971046447754,0.0,1739502670.043293,30.359971046447754,0.012369609486013844,1739502670.0432944,30.359971046447754,1.8013468817765774,1739502670.043296,30.359971046447754,0.9603678833260035 +1739502670.0632634,30.379971027374268,51.18691021985771,1739502670.063266,30.379971027374268,5.270985132356767,1739502670.0632694,30.379971027374268,55.24955587930495,1739502670.0632727,30.379971027374268,49.27724237599002,1739502670.0632741,30.379971027374268,8.243346069486984,1739502670.0632763,30.379971027374268,2.141863422233805,1739502670.0632782,30.379971027374268,1.1799146957883533,1739502670.0632796,30.379971027374268,0.6108,1739502670.063281,30.379971027374268,0.9727374928120174,1739502670.063283,30.379971027374268,0.0,1739502670.0632844,30.379971027374268,0.012369609486013844,1739502670.0632863,30.379971027374268,1.8013468817765774,1739502670.0632877,30.379971027374268,0.9603678833260035 +1739502670.083256,30.39997100830078,51.18691021985771,1739502670.0832586,30.39997100830078,5.270985132356767,1739502670.0832617,30.39997100830078,55.24955587930495,1739502670.083265,30.39997100830078,49.27724237599002,1739502670.0832665,30.39997100830078,8.243346069486984,1739502670.0832686,30.39997100830078,2.141863422233805,1739502670.08327,30.39997100830078,1.1799146957883533,1739502670.083272,30.39997100830078,0.6108,1739502670.0832732,30.39997100830078,0.9727374928120174,1739502670.083275,30.39997100830078,0.0,1739502670.0832765,30.39997100830078,0.012369609486013844,1739502670.0832784,30.39997100830078,1.8013468817765774,1739502670.0832798,30.39997100830078,0.9603678833260035 +1739502670.103362,30.419970989227295,51.18691021985771,1739502670.1033647,30.419970989227295,5.270985132356767,1739502670.1033683,30.419970989227295,55.24955587930495,1739502670.1033714,30.419970989227295,49.27724237599002,1739502670.103373,30.419970989227295,8.243346069486984,1739502670.103375,30.419970989227295,2.141863422233805,1739502670.1033766,30.419970989227295,1.1799146957883533,1739502670.103378,30.419970989227295,0.6108,1739502670.1033797,30.419970989227295,0.9727374928120174,1739502670.1033814,30.419970989227295,0.0,1739502670.103383,30.419970989227295,0.012369609486013844,1739502670.103385,30.419970989227295,1.8013468817765774,1739502670.1033869,30.419970989227295,0.9603678833260035 +1739502670.123322,30.43997097015381,51.16145889775232,1739502670.1233246,30.43997097015381,5.373609210269073,1739502670.123328,30.43997097015381,55.42036614623544,1739502670.123331,30.43997097015381,49.11762331623492,1739502670.1233325,30.43997097015381,8.312842882053099,1739502670.1233346,30.43997097015381,2.17840371029853,1739502670.123336,30.43997097015381,1.2257396415274684,1739502670.1233377,30.43997097015381,0.6108,1739502670.1233392,30.43997097015381,0.9377227200042761,1739502670.123341,30.43997097015381,0.0,1739502670.1233425,30.43997097015381,-0.040960258488494175,1739502670.1233442,30.43997097015381,1.8289485707191266,1739502670.1233456,30.43997097015381,0.9620173838239212 +1739502670.143268,30.459970951080322,51.16145889775232,1739502670.1432705,30.459970951080322,5.373609210269073,1739502670.1432743,30.459970951080322,55.42036614623544,1739502670.1432772,30.459970951080322,49.11762331623492,1739502670.1432788,30.459970951080322,8.312842882053099,1739502670.143281,30.459970951080322,2.17840371029853,1739502670.1432824,30.459970951080322,1.2257396415274684,1739502670.143284,30.459970951080322,0.6108,1739502670.1432853,30.459970951080322,0.9377227200042761,1739502670.143287,30.459970951080322,0.0,1739502670.1432886,30.459970951080322,-0.024294663819645068,1739502670.1432903,30.459970951080322,1.8289485707191266,1739502670.143292,30.459970951080322,0.9620173838239212 +1739502670.1632876,30.479970932006836,51.16145889775232,1739502670.16329,30.479970932006836,5.373609210269073,1739502670.1632934,30.479970932006836,55.42036614623544,1739502670.1632967,30.479970932006836,49.11762331623492,1739502670.1632986,30.479970932006836,8.312842882053099,1739502670.1633005,30.479970932006836,2.17840371029853,1739502670.1633022,30.479970932006836,1.2257396415274684,1739502670.1633036,30.479970932006836,0.6108,1739502670.1633053,30.479970932006836,0.9377227200042761,1739502670.163307,30.479970932006836,0.0,1739502670.1633086,30.479970932006836,-0.024294663819645068,1739502670.16331,30.479970932006836,1.8289485707191266,1739502670.163312,30.479970932006836,0.9620173838239212 +1739502670.1832905,30.49997091293335,51.16145889775232,1739502670.1832929,30.49997091293335,5.373609210269073,1739502670.1832962,30.49997091293335,55.42036614623544,1739502670.1832993,30.49997091293335,49.11762331623492,1739502670.183301,30.49997091293335,8.312842882053099,1739502670.1833029,30.49997091293335,2.17840371029853,1739502670.1833045,30.49997091293335,1.2257396415274684,1739502670.1833062,30.49997091293335,0.6108,1739502670.183308,30.49997091293335,0.9377227200042761,1739502670.1833096,30.49997091293335,0.0,1739502670.183311,30.49997091293335,-0.024294663819645068,1739502670.183313,30.49997091293335,1.8289485707191266,1739502670.1833143,30.49997091293335,0.9620173838239212 +1739502670.2033885,30.519970893859863,51.16145889775232,1739502670.203391,30.519970893859863,5.373609210269073,1739502670.203394,30.519970893859863,55.42036614623544,1739502670.2033973,30.519970893859863,49.11762331623492,1739502670.203399,30.519970893859863,8.312842882053099,1739502670.2034006,30.519970893859863,2.17840371029853,1739502670.2034025,30.519970893859863,1.2257396415274684,1739502670.203404,30.519970893859863,0.6108,1739502670.2034056,30.519970893859863,0.9377227200042761,1739502670.2034073,30.519970893859863,0.0,1739502670.2034087,30.519970893859863,-0.024294663819645068,1739502670.2034104,30.519970893859863,1.8289485707191266,1739502670.203412,30.519970893859863,0.9620173838239212 +1739502670.2233377,30.539970874786377,51.13319668289231,1739502670.2233403,30.539970874786377,5.475453926419348,1739502670.2233434,30.539970874786377,55.56232906291481,1739502670.2233465,30.539970874786377,48.99062061549687,1739502670.223348,30.539970874786377,8.363392269188672,1739502670.22335,30.539970874786377,2.2090965116794195,1739502670.2233515,30.539970874786377,1.2416386999006102,1739502670.2233531,30.539970874786377,0.6108,1739502670.2233548,30.539970874786377,0.925871124853061,1739502670.2233567,30.539970874786377,0.0,1739502670.2233582,30.539970874786377,-0.03770562842705671,1739502670.2233598,30.539970874786377,1.8565502596616759,1739502670.2233615,30.539970874786377,0.9593858240925143 +1739502670.2432785,30.55997085571289,51.13319668289231,1739502670.2432811,30.55997085571289,5.475453926419348,1739502670.2432842,30.55997085571289,55.56232906291481,1739502670.2432873,30.55997085571289,48.99062061549687,1739502670.2432888,30.55997085571289,8.363392269188672,1739502670.243291,30.55997085571289,2.2090965116794195,1739502670.2432923,30.55997085571289,1.2416386999006102,1739502670.2432942,30.55997085571289,0.6108,1739502670.2432957,30.55997085571289,0.925871124853061,1739502670.2432976,30.55997085571289,0.0,1739502670.2432988,30.55997085571289,-0.03351469923945327,1739502670.2433007,30.55997085571289,1.8565502596616759,1739502670.243302,30.55997085571289,0.9593858240925143 +1739502670.2632866,30.579970836639404,51.13319668289231,1739502670.263289,30.579970836639404,5.475453926419348,1739502670.2632923,30.579970836639404,55.56232906291481,1739502670.2632954,30.579970836639404,48.99062061549687,1739502670.263297,30.579970836639404,8.363392269188672,1739502670.2632987,30.579970836639404,2.2090965116794195,1739502670.263301,30.579970836639404,1.2416386999006102,1739502670.2633023,30.579970836639404,0.6108,1739502670.263304,30.579970836639404,0.925871124853061,1739502670.2633057,30.579970836639404,0.0,1739502670.2633073,30.579970836639404,-0.03351469923945327,1739502670.263309,30.579970836639404,1.8565502596616759,1739502670.2633107,30.579970836639404,0.9593858240925143 +1739502670.2832782,30.599970817565918,51.13319668289231,1739502670.283281,30.599970817565918,5.475453926419348,1739502670.2832847,30.599970817565918,55.56232906291481,1739502670.2832878,30.599970817565918,48.99062061549687,1739502670.2832894,30.599970817565918,8.363392269188672,1739502670.283291,30.599970817565918,2.2090965116794195,1739502670.2832928,30.599970817565918,1.2416386999006102,1739502670.2832944,30.599970817565918,0.6108,1739502670.2832956,30.599970817565918,0.925871124853061,1739502670.2832975,30.599970817565918,0.0,1739502670.283299,30.599970817565918,-0.03351469923945327,1739502670.2833006,30.599970817565918,1.8565502596616759,1739502670.283302,30.599970817565918,0.9593858240925143 +1739502670.303321,30.61997079849243,51.13319668289231,1739502670.3033235,30.61997079849243,5.475453926419348,1739502670.303327,30.61997079849243,55.56232906291481,1739502670.30333,30.61997079849243,48.99062061549687,1739502670.3033316,30.61997079849243,8.363392269188672,1739502670.3033335,30.61997079849243,2.2090965116794195,1739502670.3033354,30.61997079849243,1.2416386999006102,1739502670.3033369,30.61997079849243,0.6108,1739502670.3033385,30.61997079849243,0.925871124853061,1739502670.3033402,30.61997079849243,0.0,1739502670.3033419,30.61997079849243,-0.03351469923945327,1739502670.3033435,30.61997079849243,1.8565502596616759,1739502670.3033452,30.61997079849243,0.9593858240925143 +1739502670.3233771,30.639970779418945,51.13319668289231,1739502670.3233798,30.639970779418945,5.475453926419348,1739502670.323383,30.639970779418945,55.56232906291481,1739502670.3233864,30.639970779418945,48.99062061549687,1739502670.3233879,30.639970779418945,8.363392269188672,1739502670.32339,30.639970779418945,2.2090965116794195,1739502670.3233914,30.639970779418945,1.2416386999006102,1739502670.323393,30.639970779418945,0.6108,1739502670.3233945,30.639970779418945,0.925871124853061,1739502670.3233964,30.639970779418945,0.0,1739502670.3233979,30.639970779418945,-0.03351469923945327,1739502670.3233993,30.639970779418945,1.8565502596616759,1739502670.323401,30.639970779418945,0.9593858240925143 +1739502670.3433318,30.65997076034546,51.10223940101324,1739502670.3433342,30.65997076034546,5.5761394766254835,1739502670.3433375,30.65997076034546,55.65915920985995,1739502670.3433409,30.65997076034546,48.90668153065347,1739502670.3433423,30.65997076034546,8.393882483404452,1739502670.3433444,30.65997076034546,2.232718970595635,1739502670.3433459,30.65997076034546,1.220067625385146,1739502670.3433475,30.65997076034546,0.6108,1739502670.343349,30.65997076034546,0.9419874111695661,1739502670.3433504,30.65997076034546,0.0,1739502670.343352,30.65997076034546,-0.00460785407826594,1739502670.3433537,30.65997076034546,1.884151948604225,1739502670.3433554,30.65997076034546,0.9556286602834584 +1739502670.3632996,30.679970741271973,51.10223940101324,1739502670.3633022,30.679970741271973,5.5761394766254835,1739502670.3633056,30.679970741271973,55.65915920985995,1739502670.363309,30.679970741271973,48.90668153065347,1739502670.3633103,30.679970741271973,8.393882483404452,1739502670.3633125,30.679970741271973,2.232718970595635,1739502670.3633142,30.679970741271973,1.220067625385146,1739502670.3633158,30.679970741271973,0.6108,1739502670.3633173,30.679970741271973,0.9419874111695661,1739502670.3633192,30.679970741271973,0.0,1739502670.3633206,30.679970741271973,-0.013641249113892306,1739502670.3633223,30.679970741271973,1.884151948604225,1739502670.363324,30.679970741271973,0.9556286602834584 +1739502670.3833013,30.699970722198486,51.10223940101324,1739502670.383304,30.699970722198486,5.5761394766254835,1739502670.3833075,30.699970722198486,55.65915920985995,1739502670.3833108,30.699970722198486,48.90668153065347,1739502670.3833127,30.699970722198486,8.393882483404452,1739502670.3833146,30.699970722198486,2.232718970595635,1739502670.3833163,30.699970722198486,1.220067625385146,1739502670.383318,30.699970722198486,0.6108,1739502670.3833196,30.699970722198486,0.9419874111695661,1739502670.3833213,30.699970722198486,0.0,1739502670.383323,30.699970722198486,-0.013641249113892306,1739502670.3833244,30.699970722198486,1.884151948604225,1739502670.3833263,30.699970722198486,0.9556286602834584 +1739502670.4032888,30.719970703125,51.10223940101324,1739502670.4032915,30.719970703125,5.5761394766254835,1739502670.403295,30.719970703125,55.65915920985995,1739502670.4032981,30.719970703125,48.90668153065347,1739502670.4032996,30.719970703125,8.393882483404452,1739502670.4033017,30.719970703125,2.232718970595635,1739502670.4033031,30.719970703125,1.220067625385146,1739502670.4033048,30.719970703125,0.6108,1739502670.4033062,30.719970703125,0.9419874111695661,1739502670.403308,30.719970703125,0.0,1739502670.4033096,30.719970703125,-0.013641249113892306,1739502670.403311,30.719970703125,1.884151948604225,1739502670.4033127,30.719970703125,0.9556286602834584 +1739502670.423299,30.739970684051514,51.10223940101324,1739502670.4233017,30.739970684051514,5.5761394766254835,1739502670.423305,30.739970684051514,55.65915920985995,1739502670.4233081,30.739970684051514,48.90668153065347,1739502670.4233096,30.739970684051514,8.393882483404452,1739502670.4233117,30.739970684051514,2.232718970595635,1739502670.4233131,30.739970684051514,1.220067625385146,1739502670.4233146,30.739970684051514,0.6108,1739502670.4233162,30.739970684051514,0.9419874111695661,1739502670.423318,30.739970684051514,0.0,1739502670.4233196,30.739970684051514,-0.013641249113892306,1739502670.423321,30.739970684051514,1.884151948604225,1739502670.423323,30.739970684051514,0.9556286602834584 +1739502670.4434621,30.759970664978027,51.068610827096464,1739502670.4434648,30.759970664978027,5.675647443335077,1739502670.4434679,30.759970664978027,55.73611080028489,1739502670.4434712,30.759970664978027,48.83657176045372,1739502670.4434729,30.759970664978027,8.417339177852542,1739502670.4434748,30.759970664978027,2.2540819956962963,1739502670.4434762,30.759970664978027,1.1867589126920939,1739502670.4434779,30.759970664978027,0.6108,1739502670.4434793,30.759970664978027,0.967425946319449,1739502670.4434814,30.759970664978027,0.0,1739502670.4434826,30.759970664978027,0.025557416389428437,1739502670.4434843,30.759970664978027,1.9117536375467743,1739502670.443486,30.759970664978027,0.954118120931266 +1739502670.463302,30.77997064590454,51.068610827096464,1739502670.4633048,30.77997064590454,5.675647443335077,1739502670.463308,30.77997064590454,55.73611080028489,1739502670.4633114,30.77997064590454,48.83657176045372,1739502670.4633129,30.77997064590454,8.417339177852542,1739502670.463315,30.77997064590454,2.2540819956962963,1739502670.4633167,30.77997064590454,1.1867589126920939,1739502670.4633183,30.77997064590454,0.6108,1739502670.4633195,30.77997064590454,0.967425946319449,1739502670.4633214,30.77997064590454,0.0,1739502670.4633229,30.77997064590454,0.013307825388182981,1739502670.4633243,30.77997064590454,1.9117536375467743,1739502670.463326,30.77997064590454,0.954118120931266 +1739502670.4832811,30.799970626831055,51.068610827096464,1739502670.4832838,30.799970626831055,5.675647443335077,1739502670.483287,30.799970626831055,55.73611080028489,1739502670.4832904,30.799970626831055,48.83657176045372,1739502670.4832919,30.799970626831055,8.417339177852542,1739502670.4832938,30.799970626831055,2.2540819956962963,1739502670.4832954,30.799970626831055,1.1867589126920939,1739502670.483297,30.799970626831055,0.6108,1739502670.4832985,30.799970626831055,0.967425946319449,1739502670.4833004,30.799970626831055,0.0,1739502670.4833019,30.799970626831055,0.013307825388182981,1739502670.4833038,30.799970626831055,1.9117536375467743,1739502670.4833052,30.799970626831055,0.954118120931266 +1739502670.5032995,30.81997060775757,51.068610827096464,1739502670.503302,30.81997060775757,5.675647443335077,1739502670.503306,30.81997060775757,55.73611080028489,1739502670.5033092,30.81997060775757,48.83657176045372,1739502670.5033112,30.81997060775757,8.417339177852542,1739502670.5033128,30.81997060775757,2.2540819956962963,1739502670.5033147,30.81997060775757,1.1867589126920939,1739502670.5033162,30.81997060775757,0.6108,1739502670.5033176,30.81997060775757,0.967425946319449,1739502670.5033195,30.81997060775757,0.0,1739502670.5033212,30.81997060775757,0.013307825388182981,1739502670.5033226,30.81997060775757,1.9117536375467743,1739502670.5033243,30.81997060775757,0.954118120931266 +1739502670.5233188,30.839970588684082,51.068610827096464,1739502670.5233216,30.839970588684082,5.675647443335077,1739502670.523325,30.839970588684082,55.73611080028489,1739502670.523328,30.839970588684082,48.83657176045372,1739502670.5233295,30.839970588684082,8.417339177852542,1739502670.5233316,30.839970588684082,2.2540819956962963,1739502670.523333,30.839970588684082,1.1867589126920939,1739502670.5233347,30.839970588684082,0.6108,1739502670.5233366,30.839970588684082,0.967425946319449,1739502670.5233383,30.839970588684082,0.0,1739502670.52334,30.839970588684082,0.013307825388182981,1739502670.5233417,30.839970588684082,1.9117536375467743,1739502670.523343,30.839970588684082,0.954118120931266 +1739502670.5433915,30.859970569610596,51.068610827096464,1739502670.543394,30.859970569610596,5.675647443335077,1739502670.5433977,30.859970569610596,55.73611080028489,1739502670.543401,30.859970569610596,48.83657176045372,1739502670.5434024,30.859970569610596,8.417339177852542,1739502670.5434048,30.859970569610596,2.2540819956962963,1739502670.5434062,30.859970569610596,1.1867589126920939,1739502670.543408,30.859970569610596,0.6108,1739502670.5434093,30.859970569610596,0.967425946319449,1739502670.5434113,30.859970569610596,0.0,1739502670.5434124,30.859970569610596,0.013307825388182981,1739502670.5434144,30.859970569610596,1.9117536375467743,1739502670.5434158,30.859970569610596,0.954118120931266 +1739502670.5633252,30.87997055053711,51.03224492590729,1739502670.5633278,30.87997055053711,5.774197782836119,1739502670.5633311,30.87997055053711,55.73780725078454,1739502670.5633345,30.87997055053711,48.831720673031455,1739502670.563336,30.87997055053711,8.418915781264777,1739502670.5633378,30.87997055053711,2.264773763247304,1739502670.5633397,30.87997055053711,1.099936758406893,1739502670.5633414,30.87997055053711,0.6108,1739502670.5633428,30.87997055053711,1.0370097435953713,1739502670.5633447,30.87997055053711,0.0,1739502670.5633461,30.87997055053711,0.11204471989496578,1739502670.5633478,30.87997055053711,1.9393553264893235,1739502670.5633495,30.87997055053711,0.9558203234640862 +1739502670.5832818,30.899970531463623,51.03224492590729,1739502670.5832841,30.899970531463623,5.774197782836119,1739502670.5832875,30.899970531463623,55.73780725078454,1739502670.5832906,30.899970531463623,48.831720673031455,1739502670.5832922,30.899970531463623,8.418915781264777,1739502670.5832942,30.899970531463623,2.264773763247304,1739502670.5832963,30.899970531463623,1.099936758406893,1739502670.5832977,30.899970531463623,0.6108,1739502670.5832994,30.899970531463623,1.0370097435953713,1739502670.583301,30.899970531463623,0.0,1739502670.5833027,30.899970531463623,0.08118942013128516,1739502670.5833042,30.899970531463623,1.9393553264893235,1739502670.5833058,30.899970531463623,0.9558203234640862 +1739502670.6033685,30.919970512390137,51.03224492590729,1739502670.6033714,30.919970512390137,5.774197782836119,1739502670.6033745,30.919970512390137,55.73780725078454,1739502670.6033778,30.919970512390137,48.831720673031455,1739502670.6033795,30.919970512390137,8.418915781264777,1739502670.6033814,30.919970512390137,2.264773763247304,1739502670.6033833,30.919970512390137,1.099936758406893,1739502670.603385,30.919970512390137,0.6108,1739502670.6033864,30.919970512390137,1.0370097435953713,1739502670.603388,30.919970512390137,0.0,1739502670.6033897,30.919970512390137,0.08118942013128516,1739502670.6033914,30.919970512390137,1.9393553264893235,1739502670.603393,30.919970512390137,0.9558203234640862 +1739502670.6233134,30.93997049331665,51.03224492590729,1739502670.623316,30.93997049331665,5.774197782836119,1739502670.6233191,30.93997049331665,55.73780725078454,1739502670.623322,30.93997049331665,48.831720673031455,1739502670.623324,30.93997049331665,8.418915781264777,1739502670.6233256,30.93997049331665,2.264773763247304,1739502670.6233275,30.93997049331665,1.099936758406893,1739502670.623329,30.93997049331665,0.6108,1739502670.6233306,30.93997049331665,1.0370097435953713,1739502670.6233323,30.93997049331665,0.0,1739502670.623334,30.93997049331665,0.08118942013128516,1739502670.6233354,30.93997049331665,1.9393553264893235,1739502670.623337,30.93997049331665,0.9558203234640862 +1739502670.6432936,30.959970474243164,51.03224492590729,1739502670.6432965,30.959970474243164,5.774197782836119,1739502670.6432998,30.959970474243164,55.73780725078454,1739502670.643303,30.959970474243164,48.831720673031455,1739502670.6433043,30.959970474243164,8.418915781264777,1739502670.6433063,30.959970474243164,2.264773763247304,1739502670.643308,30.959970474243164,1.099936758406893,1739502670.6433096,30.959970474243164,0.6108,1739502670.6433108,30.959970474243164,1.0370097435953713,1739502670.6433127,30.959970474243164,0.0,1739502670.6433141,30.959970474243164,0.08118942013128516,1739502670.6433158,30.959970474243164,1.9393553264893235,1739502670.6433175,30.959970474243164,0.9558203234640862 +1739502670.6630244,30.979970455169678,50.99297746932043,1739502670.6630266,30.979970455169678,5.872189979938453,1739502670.6630294,30.979970455169678,55.979435253213886,1739502670.663032,30.979970455169678,48.58330507812356,1739502670.6630335,30.979970455169678,8.493166103516021,1739502670.6630352,30.979970455169678,2.3142158870075153,1739502670.6630366,30.979970455169678,1.2116613011031172,1739502670.663038,30.979970455169678,0.6108,1739502670.6630392,30.979970455169678,0.9483436816803946,1739502670.6630409,30.979970455169678,0.0,1739502670.663042,30.979970455169678,-0.06063499629076618,1739502670.6630435,30.979970455169678,1.9669570154318727,1739502670.663045,30.979970455169678,0.964658518780709 +1739502670.6877122,30.99997043609619,50.99297746932043,1739502670.6877215,30.99997043609619,5.872189979938453,1739502670.6877322,30.99997043609619,55.979435253213886,1739502670.687743,30.99997043609619,48.58330507812356,1739502670.687748,30.99997043609619,8.493166103516021,1739502670.687754,30.99997043609619,2.3142158870075153,1739502670.6877594,30.99997043609619,1.2116613011031172,1739502670.6877642,30.99997043609619,0.6108,1739502670.687769,30.99997043609619,0.9483436816803946,1739502670.6877747,30.99997043609619,0.0,1739502670.68778,30.99997043609619,-0.01631483710031434,1739502670.687785,30.99997043609619,1.9669570154318727,1739502670.6877902,30.99997043609619,0.964658518780709 +1739502670.7131073,31.019970417022705,50.99297746932043,1739502670.7131164,31.019970417022705,5.872189979938453,1739502670.7131274,31.019970417022705,55.979435253213886,1739502670.7131374,31.019970417022705,48.58330507812356,1739502670.7131422,31.019970417022705,8.493166103516021,1739502670.7131486,31.019970417022705,2.3142158870075153,1739502670.7131536,31.019970417022705,1.2116613011031172,1739502670.7131584,31.019970417022705,0.6108,1739502670.713163,31.019970417022705,0.9483436816803946,1739502670.7131689,31.019970417022705,0.0,1739502670.7131734,31.019970417022705,-0.01631483710031434,1739502670.7131789,31.019970417022705,1.9669570154318727,1739502670.7131836,31.019970417022705,0.964658518780709 +1739502670.7281613,31.03997039794922,50.99297746932043,1739502670.7281692,31.03997039794922,5.872189979938453,1739502670.7281795,31.03997039794922,55.979435253213886,1739502670.7281897,31.03997039794922,48.58330507812356,1739502670.7281947,31.03997039794922,8.493166103516021,1739502670.728201,31.03997039794922,2.3142158870075153,1739502670.7282062,31.03997039794922,1.2116613011031172,1739502670.7282112,31.03997039794922,0.6108,1739502670.7282162,31.03997039794922,0.9483436816803946,1739502670.7282214,31.03997039794922,0.0,1739502670.7282262,31.03997039794922,-0.01631483710031434,1739502670.7282312,31.03997039794922,1.9669570154318727,1739502670.728236,31.03997039794922,0.964658518780709 +1739502670.7498615,31.059970378875732,50.99297746932043,1739502670.7498696,31.059970378875732,5.872189979938453,1739502670.7498794,31.059970378875732,55.979435253213886,1739502670.7498891,31.059970378875732,48.58330507812356,1739502670.7498941,31.059970378875732,8.493166103516021,1739502670.7499006,31.059970378875732,2.3142158870075153,1739502670.7499053,31.059970378875732,1.2116613011031172,1739502670.7499104,31.059970378875732,0.6108,1739502670.749915,31.059970378875732,0.9483436816803946,1739502670.7499206,31.059970378875732,0.0,1739502670.7499251,31.059970378875732,-0.01631483710031434,1739502670.7499304,31.059970378875732,1.9669570154318727,1739502670.7499356,31.059970378875732,0.964658518780709 +1739502670.7797887,31.079970359802246,50.99297746932043,1739502670.779807,31.079970359802246,5.872189979938453,1739502670.7798297,31.079970359802246,55.979435253213886,1739502670.7798567,31.079970359802246,48.58330507812356,1739502670.7798731,31.079970359802246,8.493166103516021,1739502670.7798927,31.079970359802246,2.3142158870075153,1739502670.7799103,31.079970359802246,1.2116613011031172,1739502670.7799275,31.079970359802246,0.6108,1739502670.7799447,31.079970359802246,0.9483436816803946,1739502670.7799625,31.079970359802246,0.0,1739502670.7799797,31.079970359802246,-0.01631483710031434,1739502670.7799976,31.079970359802246,1.9669570154318727,1739502670.780015,31.079970359802246,0.964658518780709 +1739502670.7939517,31.109970331192017,50.95087677224477,1739502670.7939563,31.109970331192017,5.969400482561571,1739502670.7939618,31.109970331192017,56.14054697476636,1739502670.793967,31.109970331192017,48.43235565847738,1739502670.7939694,31.109970331192017,8.531573277453415,1739502670.7939727,31.109970331192017,2.347603024561999,1739502670.7939756,31.109970331192017,1.2422063464171988,1739502670.7939782,31.109970331192017,0.6108,1739502670.7939804,31.109970331192017,0.9254507662912479,1739502670.7939835,31.109970331192017,0.0,1739502670.793986,31.109970331192017,-0.04573142703750262,1739502670.793989,31.109970331192017,1.994558704374422,1739502670.7939916,31.109970331192017,0.9619895029461817 +1739502670.8125165,31.12997031211853,50.95087677224477,1739502670.812519,31.12997031211853,5.969400482561571,1739502670.8125226,31.12997031211853,56.14054697476636,1739502670.8125257,31.12997031211853,48.43235565847738,1739502670.8125274,31.12997031211853,8.531573277453415,1739502670.8125293,31.12997031211853,2.347603024561999,1739502670.812531,31.12997031211853,1.2422063464171988,1739502670.812533,31.12997031211853,0.6108,1739502670.8125346,31.12997031211853,0.9254507662912479,1739502670.8125362,31.12997031211853,0.0,1739502670.812538,31.12997031211853,-0.03653873665493379,1739502670.8125393,31.12997031211853,1.994558704374422,1739502670.8125412,31.12997031211853,0.9619895029461817 +1739502670.8310742,31.149970293045044,50.95087677224477,1739502670.8310776,31.149970293045044,5.969400482561571,1739502670.8310807,31.149970293045044,56.14054697476636,1739502670.8310835,31.149970293045044,48.43235565847738,1739502670.831085,31.149970293045044,8.531573277453415,1739502670.8310869,31.149970293045044,2.347603024561999,1739502670.8310883,31.149970293045044,1.2422063464171988,1739502670.83109,31.149970293045044,0.6108,1739502670.8310914,31.149970293045044,0.9254507662912479,1739502670.8310938,31.149970293045044,0.0,1739502670.831095,31.149970293045044,-0.03653873665493379,1739502670.8310966,31.149970293045044,1.994558704374422,1739502670.831098,31.149970293045044,0.9619895029461817 +1739502670.8518724,31.169970273971558,50.95087677224477,1739502670.8518755,31.169970273971558,5.969400482561571,1739502670.8518786,31.169970273971558,56.14054697476636,1739502670.8518813,31.169970273971558,48.43235565847738,1739502670.8518825,31.169970273971558,8.531573277453415,1739502670.8518844,31.169970273971558,2.347603024561999,1739502670.8518858,31.169970273971558,1.2422063464171988,1739502670.8518875,31.169970273971558,0.6108,1739502670.8518887,31.169970273971558,0.9254507662912479,1739502670.85189,31.169970273971558,0.0,1739502670.8518915,31.169970273971558,-0.03653873665493379,1739502670.851893,31.169970273971558,1.994558704374422,1739502670.8518946,31.169970273971558,0.9619895029461817 +1739502670.8730583,31.18997025489807,50.95087677224477,1739502670.8730612,31.18997025489807,5.969400482561571,1739502670.8730645,31.18997025489807,56.14054697476636,1739502670.8730674,31.18997025489807,48.43235565847738,1739502670.8730688,31.18997025489807,8.531573277453415,1739502670.8730705,31.18997025489807,2.347603024561999,1739502670.8730721,31.18997025489807,1.2422063464171988,1739502670.8730736,31.18997025489807,0.6108,1739502670.873075,31.18997025489807,0.9254507662912479,1739502670.8730764,31.18997025489807,0.0,1739502670.8730779,31.18997025489807,-0.03653873665493379,1739502670.8730793,31.18997025489807,1.994558704374422,1739502670.8730807,31.18997025489807,0.9619895029461817 +1739502670.9266908,31.2299702167511,50.90623460202116,1739502670.9266958,31.2299702167511,6.065144205310764,1739502670.926702,31.2299702167511,56.22552676781097,1739502670.9267077,31.2299702167511,48.3569866482854,1739502670.9267106,31.2299702167511,8.54920267034292,1739502670.9267144,31.2299702167511,2.3691453893799963,1739502670.9267178,31.2299702167511,1.2104183686212844,1739502670.9267206,31.2299702167511,0.6108,1739502670.926723,31.2299702167511,0.9492871323935961,1739502670.926726,31.2299702167511,0.0,1739502670.9267292,31.2299702167511,0.003634581974682062,1739502670.9267325,31.2299702167511,2.022160393316969,1739502670.9267354,31.2299702167511,0.9582067207218244 +1739502670.9403338,31.249970197677612,50.90623460202116,1739502670.9403374,31.249970197677612,6.065144205310764,1739502670.9403422,31.249970197677612,56.22552676781097,1739502670.9403467,31.249970197677612,48.3569866482854,1739502670.9403489,31.249970197677612,8.54920267034292,1739502670.9403517,31.249970197677612,2.3691453893799963,1739502670.940354,31.249970197677612,1.2104183686212844,1739502670.9403563,31.249970197677612,0.6108,1739502670.9403582,31.249970197677612,0.9492871323935961,1739502670.9403608,31.249970197677612,0.0,1739502670.9403627,31.249970197677612,-0.008919588328228367,1739502670.940365,31.249970197677612,2.022160393316969,1739502670.9403677,31.249970197677612,0.9582067207218244 +1739502670.9594548,31.269970178604126,50.90623460202116,1739502670.9594584,31.269970178604126,6.065144205310764,1739502670.9594626,31.269970178604126,56.22552676781097,1739502670.959468,31.269970178604126,48.3569866482854,1739502670.9594698,31.269970178604126,8.54920267034292,1739502670.9594724,31.269970178604126,2.3691453893799963,1739502670.9594743,31.269970178604126,1.2104183686212844,1739502670.9594767,31.269970178604126,0.6108,1739502670.9594789,31.269970178604126,0.9492871323935961,1739502670.959481,31.269970178604126,0.0,1739502670.9594834,31.269970178604126,-0.008919588328228367,1739502670.9594855,31.269970178604126,2.022160393316969,1739502670.9594877,31.269970178604126,0.9582067207218244 +1739502670.9783359,31.28997015953064,50.90623460202116,1739502670.9783394,31.28997015953064,6.065144205310764,1739502670.9783437,31.28997015953064,56.22552676781097,1739502670.9783475,31.28997015953064,48.3569866482854,1739502670.97835,31.28997015953064,8.54920267034292,1739502670.978352,31.28997015953064,2.3691453893799963,1739502670.9783542,31.28997015953064,1.2104183686212844,1739502670.9783561,31.28997015953064,0.6108,1739502670.9783583,31.28997015953064,0.9492871323935961,1739502670.9783607,31.28997015953064,0.0,1739502670.9783623,31.28997015953064,-0.008919588328228367,1739502670.9783645,31.28997015953064,2.022160393316969,1739502670.9783664,31.28997015953064,0.9582067207218244 +1739502670.9978418,31.309970140457153,50.85912165671652,1739502670.9978447,31.309970140457153,6.159308991127009,1739502670.997848,31.309970140457153,56.38617265374674,1739502670.9978511,31.309970140457153,48.20223738705996,1739502670.9978526,31.309970140457153,8.57879376882334,1739502670.9978547,31.309970140457153,2.4029260517680737,1739502670.9978561,31.309970140457153,1.2428629783844412,1739502670.9978583,31.309970140457153,0.6108,1739502670.99786,31.309970140457153,0.9249647495102815,1739502670.9978616,31.309970140457153,0.0,1739502670.997863,31.309970140457153,-0.042052606378144924,1739502670.997865,31.309970140457153,2.049762082259516,1739502670.9978664,31.309970140457153,0.956663280959167 +1739502671.0181243,31.329970121383667,50.85912165671652,1739502671.0181265,31.329970121383667,6.159308991127009,1739502671.0181293,31.329970121383667,56.38617265374674,1739502671.0181322,31.329970121383667,48.20223738705996,1739502671.0181334,31.329970121383667,8.57879376882334,1739502671.0181353,31.329970121383667,2.4029260517680737,1739502671.0181365,31.329970121383667,1.2428629783844412,1739502671.0181384,31.329970121383667,0.6108,1739502671.0181396,31.329970121383667,0.9249647495102815,1739502671.0181413,31.329970121383667,0.0,1739502671.0181427,31.329970121383667,-0.03169853144888546,1739502671.018144,31.329970121383667,2.049762082259516,1739502671.0181456,31.329970121383667,0.956663280959167 +1739502671.0436454,31.34997010231018,50.85912165671652,1739502671.043654,31.34997010231018,6.159308991127009,1739502671.0436642,31.34997010231018,56.38617265374674,1739502671.0436745,31.34997010231018,48.20223738705996,1739502671.0436792,31.34997010231018,8.57879376882334,1739502671.0436852,31.34997010231018,2.4029260517680737,1739502671.0436902,31.34997010231018,1.2428629783844412,1739502671.0436947,31.34997010231018,0.6108,1739502671.0436995,31.34997010231018,0.9249647495102815,1739502671.043705,31.34997010231018,0.0,1739502671.0437098,31.34997010231018,-0.03169853144888546,1739502671.043715,31.34997010231018,2.049762082259516,1739502671.04372,31.34997010231018,0.956663280959167 +1739502671.0832016,31.389970064163208,50.85912165671652,1739502671.0832107,31.389970064163208,6.159308991127009,1739502671.0832214,31.389970064163208,56.38617265374674,1739502671.0832317,31.389970064163208,48.20223738705996,1739502671.083237,31.389970064163208,8.57879376882334,1739502671.0832434,31.389970064163208,2.4029260517680737,1739502671.0832484,31.389970064163208,1.2428629783844412,1739502671.0832536,31.389970064163208,0.6108,1739502671.0832582,31.389970064163208,0.9249647495102815,1739502671.0832636,31.389970064163208,0.0,1739502671.0832684,31.389970064163208,-0.03169853144888546,1739502671.0832736,31.389970064163208,2.049762082259516,1739502671.083279,31.389970064163208,0.956663280959167 +1739502671.1049566,31.40997004508972,50.85912165671652,1739502671.1049626,31.40997004508972,6.159308991127009,1739502671.1049685,31.40997004508972,56.38617265374674,1739502671.1049743,31.40997004508972,48.20223738705996,1739502671.1049771,31.40997004508972,8.57879376882334,1739502671.1049805,31.40997004508972,2.4029260517680737,1739502671.104984,31.40997004508972,1.2428629783844412,1739502671.1049867,31.40997004508972,0.6108,1739502671.1049893,31.40997004508972,0.9249647495102815,1739502671.1049922,31.40997004508972,0.0,1739502671.104995,31.40997004508972,-0.03169853144888546,1739502671.1049979,31.40997004508972,2.049762082259516,1739502671.1050007,31.40997004508972,0.956663280959167 +1739502671.1184402,31.429970026016235,50.80954970058305,1739502671.1184428,31.429970026016235,6.25191133823656,1739502671.118446,31.429970026016235,56.47109413012366,1739502671.1184492,31.429970026016235,48.125641442629295,1739502671.1184506,31.429970026016235,8.590974066743769,1739502671.1184528,31.429970026016235,2.4247406289497153,1739502671.1184542,31.429970026016235,1.2119865394617189,1739502671.118456,31.429970026016235,0.6108,1739502671.1184573,31.429970026016235,0.948096963584726,1739502671.1184592,31.429970026016235,0.0,1739502671.1184607,31.429970026016235,0.007301850680402464,1739502671.1184623,31.429970026016235,2.0773637712020627,1739502671.1184638,31.429970026016235,0.9529827403105572 +1739502671.1390908,31.44997000694275,50.80954970058305,1739502671.1390934,31.44997000694275,6.25191133823656,1739502671.1390965,31.44997000694275,56.47109413012366,1739502671.1390994,31.44997000694275,48.125641442629295,1739502671.139101,31.44997000694275,8.590974066743769,1739502671.1391025,31.44997000694275,2.4247406289497153,1739502671.139104,31.44997000694275,1.2119865394617189,1739502671.139106,31.44997000694275,0.6108,1739502671.1391072,31.44997000694275,0.948096963584726,1739502671.139109,31.44997000694275,0.0,1739502671.1391103,31.44997000694275,-0.004885776725831237,1739502671.139112,31.44997000694275,2.0773637712020627,1739502671.1391132,31.44997000694275,0.9529827403105572 +1739502671.1586778,31.469969987869263,50.80954970058305,1739502671.1586804,31.469969987869263,6.25191133823656,1739502671.1586833,31.469969987869263,56.47109413012366,1739502671.1586862,31.469969987869263,48.125641442629295,1739502671.1586876,31.469969987869263,8.590974066743769,1739502671.158689,31.469969987869263,2.4247406289497153,1739502671.1586902,31.469969987869263,1.2119865394617189,1739502671.1586916,31.469969987869263,0.6108,1739502671.1586928,31.469969987869263,0.948096963584726,1739502671.1586947,31.469969987869263,0.0,1739502671.158696,31.469969987869263,-0.004885776725831237,1739502671.1586971,31.469969987869263,2.0773637712020627,1739502671.1586988,31.469969987869263,0.9529827403105572 +1739502671.1844747,31.489969968795776,50.80954970058305,1739502671.1844828,31.489969968795776,6.25191133823656,1739502671.1844933,31.489969968795776,56.47109413012366,1739502671.1845036,31.489969968795776,48.125641442629295,1739502671.184508,31.489969968795776,8.590974066743769,1739502671.1845143,31.489969968795776,2.4247406289497153,1739502671.184519,31.489969968795776,1.2119865394617189,1739502671.184524,31.489969968795776,0.6108,1739502671.1845286,31.489969968795776,0.948096963584726,1739502671.1845345,31.489969968795776,0.0,1739502671.1845393,31.489969968795776,-0.004885776725831237,1739502671.1845446,31.489969968795776,2.0773637712020627,1739502671.1845493,31.489969968795776,0.9529827403105572 +1739502671.2056665,31.50996994972229,50.80954970058305,1739502671.2056754,31.50996994972229,6.25191133823656,1739502671.2056856,31.50996994972229,56.47109413012366,1739502671.205695,31.50996994972229,48.125641442629295,1739502671.2057,31.50996994972229,8.590974066743769,1739502671.205706,31.50996994972229,2.4247406289497153,1739502671.205711,31.50996994972229,1.2119865394617189,1739502671.2057157,31.50996994972229,0.6108,1739502671.2057204,31.50996994972229,0.948096963584726,1739502671.2057264,31.50996994972229,0.0,1739502671.2057314,31.50996994972229,-0.004885776725831237,1739502671.2057362,31.50996994972229,2.0773637712020627,1739502671.2057412,31.50996994972229,0.9529827403105572 +1739502671.239588,31.529969930648804,50.75755700338367,1739502671.2396016,31.529969930648804,6.342905534800188,1739502671.2396185,31.529969930648804,56.57822856046014,1739502671.2396386,31.529969930648804,48.02045754993868,1739502671.239649,31.529969930648804,8.606017586427322,1739502671.2396631,31.529969930648804,2.4507055499644097,1739502671.239676,31.529969930648804,1.2035900431649036,1739502671.2396884,31.529969930648804,0.6108,1739502671.239701,31.529969930648804,0.9544869550889936,1739502671.2397141,31.529969930648804,0.0,1739502671.2397268,31.529969930648804,0.0050425423792873885,1739502671.2397397,31.529969930648804,2.1049654601446095,1739502671.2397525,31.529969930648804,0.95254701446428 +1739502671.2533479,31.549969911575317,50.75755700338367,1739502671.2533557,31.549969911575317,6.342905534800188,1739502671.2533662,31.549969911575317,56.57822856046014,1739502671.2533762,31.549969911575317,48.02045754993868,1739502671.2533815,31.549969911575317,8.606017586427322,1739502671.2533872,31.549969911575317,2.4507055499644097,1739502671.2533925,31.549969911575317,1.2035900431649036,1739502671.253397,31.549969911575317,0.6108,1739502671.2534015,31.549969911575317,0.9544869550889936,1739502671.2534072,31.549969911575317,0.0,1739502671.253412,31.549969911575317,0.0019399406247135875,1739502671.2534173,31.549969911575317,2.1049654601446095,1739502671.253422,31.549969911575317,0.95254701446428 +1739502671.2880185,31.579969882965088,50.75755700338367,1739502671.2880237,31.579969882965088,6.342905534800188,1739502671.2880309,31.579969882965088,56.57822856046014,1739502671.2880394,31.579969882965088,48.02045754993868,1739502671.2880442,31.579969882965088,8.606017586427322,1739502671.2880502,31.579969882965088,2.4507055499644097,1739502671.288056,31.579969882965088,1.2035900431649036,1739502671.2880611,31.579969882965088,0.6108,1739502671.2880666,31.579969882965088,0.9544869550889936,1739502671.288072,31.579969882965088,0.0,1739502671.2880776,31.579969882965088,0.0019399406247135875,1739502671.2880833,31.579969882965088,2.1049654601446095,1739502671.2880888,31.579969882965088,0.95254701446428 +1739502671.3065062,31.5999698638916,50.75755700338367,1739502671.306511,31.5999698638916,6.342905534800188,1739502671.306517,31.5999698638916,56.57822856046014,1739502671.3065245,31.5999698638916,48.02045754993868,1739502671.3065283,31.5999698638916,8.606017586427322,1739502671.3065336,31.5999698638916,2.4507055499644097,1739502671.3065383,31.5999698638916,1.2035900431649036,1739502671.3065429,31.5999698638916,0.6108,1739502671.3065474,31.5999698638916,0.9544869550889936,1739502671.3065524,31.5999698638916,0.0,1739502671.306557,31.5999698638916,0.0019399406247135875,1739502671.3065617,31.5999698638916,2.1049654601446095,1739502671.3065665,31.5999698638916,0.95254701446428 +1739502671.3251996,31.619969844818115,50.75755700338367,1739502671.325203,31.619969844818115,6.342905534800188,1739502671.3252072,31.619969844818115,56.57822856046014,1739502671.3252108,31.619969844818115,48.02045754993868,1739502671.325213,31.619969844818115,8.606017586427322,1739502671.3252153,31.619969844818115,2.4507055499644097,1739502671.325217,31.619969844818115,1.2035900431649036,1739502671.3252192,31.619969844818115,0.6108,1739502671.325221,31.619969844818115,0.9544869550889936,1739502671.3252234,31.619969844818115,0.0,1739502671.325225,31.619969844818115,0.0019399406247135875,1739502671.325227,31.619969844818115,2.1049654601446095,1739502671.3252296,31.619969844818115,0.95254701446428 +1739502671.3445368,31.63996982574463,50.703076519506574,1739502671.344541,31.63996982574463,6.4324238741589745,1739502671.344549,31.63996982574463,56.72491892260526,1739502671.3445559,31.63996982574463,47.87415929178772,1739502671.344559,31.63996982574463,8.622561061968575,1739502671.3445635,31.63996982574463,2.4827849109464952,1739502671.3445673,31.63996982574463,1.2274950743111706,1739502671.3445714,31.63996982574463,0.6108,1739502671.3445766,31.63996982574463,0.9364067568906959,1739502671.3445792,31.63996982574463,0.0,1739502671.3445818,31.63996982574463,-0.024757525643129864,1739502671.3445845,31.63996982574463,2.1325671490871563,1739502671.3445873,31.63996982574463,0.9528213188550514 +1739502671.364773,31.659969806671143,50.703076519506574,1739502671.3647764,31.659969806671143,6.4324238741589745,1739502671.3647802,31.659969806671143,56.72491892260526,1739502671.3647838,31.659969806671143,47.87415929178772,1739502671.3647857,31.659969806671143,8.622561061968575,1739502671.3647878,31.659969806671143,2.4827849109464952,1739502671.3647895,31.659969806671143,1.2274950743111706,1739502671.3647914,31.659969806671143,0.6108,1739502671.364793,31.659969806671143,0.9364067568906959,1739502671.3647952,31.659969806671143,0.0,1739502671.3647969,31.659969806671143,-0.016414561964355534,1739502671.3647988,31.659969806671143,2.1325671490871563,1739502671.3648005,31.659969806671143,0.9528213188550514 +1739502671.384172,31.679969787597656,50.703076519506574,1739502671.384175,31.679969787597656,6.4324238741589745,1739502671.3841786,31.679969787597656,56.72491892260526,1739502671.3841817,31.679969787597656,47.87415929178772,1739502671.3841836,31.679969787597656,8.622561061968575,1739502671.3841856,31.679969787597656,2.4827849109464952,1739502671.3841872,31.679969787597656,1.2274950743111706,1739502671.384189,31.679969787597656,0.6108,1739502671.3841906,31.679969787597656,0.9364067568906959,1739502671.3841922,31.679969787597656,0.0,1739502671.384194,31.679969787597656,-0.016414561964355534,1739502671.3841953,31.679969787597656,2.1325671490871563,1739502671.3841972,31.679969787597656,0.9528213188550514 +1739502671.4037638,31.69996976852417,50.703076519506574,1739502671.4037662,31.69996976852417,6.4324238741589745,1739502671.4037695,31.69996976852417,56.72491892260526,1739502671.4037726,31.69996976852417,47.87415929178772,1739502671.4037745,31.69996976852417,8.622561061968575,1739502671.4037762,31.69996976852417,2.4827849109464952,1739502671.4037778,31.69996976852417,1.2274950743111706,1739502671.4037795,31.69996976852417,0.6108,1739502671.4037812,31.69996976852417,0.9364067568906959,1739502671.403783,31.69996976852417,0.0,1739502671.4037845,31.69996976852417,-0.016414561964355534,1739502671.4037862,31.69996976852417,2.1325671490871563,1739502671.4037879,31.69996976852417,0.9528213188550514 +1739502671.4244258,31.719969749450684,50.703076519506574,1739502671.4244282,31.719969749450684,6.4324238741589745,1739502671.4244316,31.719969749450684,56.72491892260526,1739502671.4244347,31.719969749450684,47.87415929178772,1739502671.4244363,31.719969749450684,8.622561061968575,1739502671.4244382,31.719969749450684,2.4827849109464952,1739502671.42444,31.719969749450684,1.2274950743111706,1739502671.4244413,31.719969749450684,0.6108,1739502671.4244428,31.719969749450684,0.9364067568906959,1739502671.4244447,31.719969749450684,0.0,1739502671.424446,31.719969749450684,-0.016414561964355534,1739502671.424448,31.719969749450684,2.1325671490871563,1739502671.4244494,31.719969749450684,0.9528213188550514 +1739502671.4490814,31.739969730377197,50.703076519506574,1739502671.4490898,31.739969730377197,6.4324238741589745,1739502671.4491007,31.739969730377197,56.72491892260526,1739502671.449111,31.739969730377197,47.87415929178772,1739502671.449116,31.739969730377197,8.622561061968575,1739502671.4491217,31.739969730377197,2.4827849109464952,1739502671.449127,31.739969730377197,1.2274950743111706,1739502671.4491317,31.739969730377197,0.6108,1739502671.4491365,31.739969730377197,0.9364067568906959,1739502671.4491422,31.739969730377197,0.0,1739502671.4491472,31.739969730377197,-0.016414561964355534,1739502671.4491522,31.739969730377197,2.1325671490871563,1739502671.4491575,31.739969730377197,0.9528213188550514 +1739502671.4684365,31.75996971130371,50.64618597792596,1739502671.4684405,31.75996971130371,6.520344135815201,1739502671.4684463,31.75996971130371,56.812354518353025,1739502671.4684513,31.75996971130371,47.79056935244804,1739502671.468454,31.75996971130371,8.629339415471998,1739502671.4684572,31.75996971130371,2.505464526447172,1739502671.4684598,31.75996971130371,1.2015815784542747,1739502671.4684622,31.75996971130371,0.6108,1739502671.4684649,31.75996971130371,0.956021830548896,1739502671.4684684,31.75996971130371,0.0,1739502671.468471,31.75996971130371,0.014710165835820558,1739502671.468474,31.75996971130371,2.160168838029703,1739502671.4684765,31.75996971130371,0.9510381485278102 +1739502671.485197,31.779969692230225,50.64618597792596,1739502671.485201,31.779969692230225,6.520344135815201,1739502671.4852054,31.779969692230225,56.812354518353025,1739502671.4852104,31.779969692230225,47.79056935244804,1739502671.4852123,31.779969692230225,8.629339415471998,1739502671.4852154,31.779969692230225,2.505464526447172,1739502671.4852178,31.779969692230225,1.2015815784542747,1739502671.48522,31.779969692230225,0.6108,1739502671.4852219,31.779969692230225,0.956021830548896,1739502671.4852242,31.779969692230225,0.0,1739502671.4852262,31.779969692230225,0.004983682021085789,1739502671.4852288,31.779969692230225,2.160168838029703,1739502671.4852312,31.779969692230225,0.9510381485278102 +1739502671.5043602,31.79996967315674,50.64618597792596,1739502671.5043628,31.79996967315674,6.520344135815201,1739502671.5043662,31.79996967315674,56.812354518353025,1739502671.5043693,31.79996967315674,47.79056935244804,1739502671.5043705,31.79996967315674,8.629339415471998,1739502671.5043726,31.79996967315674,2.505464526447172,1739502671.504374,31.79996967315674,1.2015815784542747,1739502671.5043752,31.79996967315674,0.6108,1739502671.504377,31.79996967315674,0.956021830548896,1739502671.5043786,31.79996967315674,0.0,1739502671.5043802,31.79996967315674,0.004983682021085789,1739502671.5043821,31.79996967315674,2.160168838029703,1739502671.5043838,31.79996967315674,0.9510381485278102 +1739502671.52357,31.819969654083252,50.64618597792596,1739502671.5235727,31.819969654083252,6.520344135815201,1739502671.5235763,31.819969654083252,56.812354518353025,1739502671.5235794,31.819969654083252,47.79056935244804,1739502671.5235808,31.819969654083252,8.629339415471998,1739502671.5235825,31.819969654083252,2.505464526447172,1739502671.523584,31.819969654083252,1.2015815784542747,1739502671.5235856,31.819969654083252,0.6108,1739502671.523587,31.819969654083252,0.956021830548896,1739502671.5235887,31.819969654083252,0.0,1739502671.5235898,31.819969654083252,0.004983682021085789,1739502671.5235915,31.819969654083252,2.160168838029703,1739502671.5235927,31.819969654083252,0.9510381485278102 +1739502671.5431669,31.839969635009766,50.64618597792596,1739502671.5431695,31.839969635009766,6.520344135815201,1739502671.5431724,31.839969635009766,56.812354518353025,1739502671.543175,31.839969635009766,47.79056935244804,1739502671.5431762,31.839969635009766,8.629339415471998,1739502671.5431778,31.839969635009766,2.505464526447172,1739502671.543179,31.839969635009766,1.2015815784542747,1739502671.5431802,31.839969635009766,0.6108,1739502671.5431817,31.839969635009766,0.956021830548896,1739502671.5431833,31.839969635009766,0.0,1739502671.5431848,31.839969635009766,0.004983682021085789,1739502671.543186,31.839969635009766,2.160168838029703,1739502671.5431871,31.839969635009766,0.9510381485278102 +1739502671.5634706,31.85996961593628,50.586955527586525,1739502671.563473,31.85996961593628,6.606565417077631,1739502671.5634754,31.85996961593628,56.97688168153525,1739502671.5634782,31.85996961593628,47.625827499492,1739502671.5634797,31.85996961593628,8.637810105655268,1739502671.563481,31.85996961593628,2.5403450586952463,1739502671.5634823,31.85996961593628,1.2399762390055067,1739502671.5634842,31.85996961593628,0.6108,1739502671.5634851,31.85996961593628,0.9271033236955684,1739502671.5634868,31.85996961593628,0.0,1739502671.5634878,31.85996961593628,-0.037400086310676886,1739502671.5634892,31.85996961593628,2.18777052697225,1739502671.5634906,31.85996961593628,0.9512584737185125 +1739502671.5834577,31.879969596862793,50.586955527586525,1739502671.5834606,31.879969596862793,6.606565417077631,1739502671.5834637,31.879969596862793,56.97688168153525,1739502671.5834665,31.879969596862793,47.625827499492,1739502671.583468,31.879969596862793,8.637810105655268,1739502671.5834699,31.879969596862793,2.5403450586952463,1739502671.583471,31.879969596862793,1.2399762390055067,1739502671.5834725,31.879969596862793,0.6108,1739502671.583474,31.879969596862793,0.9271033236955684,1739502671.5834754,31.879969596862793,0.0,1739502671.583477,31.879969596862793,-0.024155150022944105,1739502671.5834785,31.879969596862793,2.18777052697225,1739502671.5834796,31.879969596862793,0.9512584737185125 +1739502671.603617,31.899969577789307,50.586955527586525,1739502671.6036193,31.899969577789307,6.606565417077631,1739502671.603622,31.899969577789307,56.97688168153525,1739502671.6036243,31.899969577789307,47.625827499492,1739502671.6036258,31.899969577789307,8.637810105655268,1739502671.6036272,31.899969577789307,2.5403450586952463,1739502671.6036286,31.899969577789307,1.2399762390055067,1739502671.6036298,31.899969577789307,0.6108,1739502671.603631,31.899969577789307,0.9271033236955684,1739502671.6036327,31.899969577789307,0.0,1739502671.6036339,31.899969577789307,-0.024155150022944105,1739502671.6036353,31.899969577789307,2.18777052697225,1739502671.6036365,31.899969577789307,0.9512584737185125 +1739502671.623381,31.91996955871582,50.586955527586525,1739502671.6233835,31.91996955871582,6.606565417077631,1739502671.6233864,31.91996955871582,56.97688168153525,1739502671.6233892,31.91996955871582,47.625827499492,1739502671.6233904,31.91996955871582,8.637810105655268,1739502671.623392,31.91996955871582,2.5403450586952463,1739502671.6233933,31.91996955871582,1.2399762390055067,1739502671.6233947,31.91996955871582,0.6108,1739502671.623396,31.91996955871582,0.9271033236955684,1739502671.6233976,31.91996955871582,0.0,1739502671.623399,31.91996955871582,-0.024155150022944105,1739502671.6234004,31.91996955871582,2.18777052697225,1739502671.6234016,31.91996955871582,0.9512584737185125 +1739502671.6433306,31.939969539642334,50.586955527586525,1739502671.6433327,31.939969539642334,6.606565417077631,1739502671.6433353,31.939969539642334,56.97688168153525,1739502671.643338,31.939969539642334,47.625827499492,1739502671.6433392,31.939969539642334,8.637810105655268,1739502671.643341,31.939969539642334,2.5403450586952463,1739502671.6433425,31.939969539642334,1.2399762390055067,1739502671.643344,31.939969539642334,0.6108,1739502671.643345,31.939969539642334,0.9271033236955684,1739502671.643347,31.939969539642334,0.0,1739502671.6433482,31.939969539642334,-0.024155150022944105,1739502671.6433494,31.939969539642334,2.18777052697225,1739502671.6433508,31.939969539642334,0.9512584737185125 +1739502671.6634324,31.959969520568848,50.586955527586525,1739502671.6634347,31.959969520568848,6.606565417077631,1739502671.6634374,31.959969520568848,56.97688168153525,1739502671.66344,31.959969520568848,47.625827499492,1739502671.6634414,31.959969520568848,8.637810105655268,1739502671.663443,31.959969520568848,2.5403450586952463,1739502671.6634445,31.959969520568848,1.2399762390055067,1739502671.6634457,31.959969520568848,0.6108,1739502671.6634471,31.959969520568848,0.9271033236955684,1739502671.6634486,31.959969520568848,0.0,1739502671.6634495,31.959969520568848,-0.024155150022944105,1739502671.6634512,31.959969520568848,2.18777052697225,1739502671.6634524,31.959969520568848,0.9512584737185125 +1739502671.6835394,31.97996950149536,50.5254255862397,1739502671.683542,31.97996950149536,6.6910416052682695,1739502671.683545,31.97996950149536,57.06386284198682,1739502671.6835482,31.97996950149536,47.54414621671242,1739502671.6835494,31.97996950149536,8.640755791981965,1739502671.6835515,31.97996950149536,2.56242060970074,1739502671.683553,31.97996950149536,1.2115953386096179,1739502671.6835544,31.97996950149536,0.6108,1739502671.6835556,31.97996950149536,0.9483937270919816,1739502671.6835573,31.97996950149536,0.0,1739502671.6835587,31.97996950149536,0.01062658708344018,1739502671.6835601,31.97996950149536,2.2153722159147966,1739502671.6835616,31.97996950149536,0.9486364399807549 +1739502671.7032628,31.999969482421875,50.5254255862397,1739502671.703265,31.999969482421875,6.6910416052682695,1739502671.703268,31.999969482421875,57.06386284198682,1739502671.703271,31.999969482421875,47.54414621671242,1739502671.7032723,31.999969482421875,8.640755791981965,1739502671.7032743,31.999969482421875,2.56242060970074,1739502671.7032757,31.999969482421875,1.2115953386096179,1739502671.703277,31.999969482421875,0.6108,1739502671.7032785,31.999969482421875,0.9483937270919816,1739502671.7032804,31.999969482421875,0.0,1739502671.7032816,31.999969482421875,-0.00024271288877331099,1739502671.7032833,31.999969482421875,2.2153722159147966,1739502671.7032845,31.999969482421875,0.9486364399807549 +1739502671.72361,32.01996946334839,50.5254255862397,1739502671.723612,32.01996946334839,6.6910416052682695,1739502671.7236152,32.01996946334839,57.06386284198682,1739502671.723618,32.01996946334839,47.54414621671242,1739502671.7236197,32.01996946334839,8.640755791981965,1739502671.7236214,32.01996946334839,2.56242060970074,1739502671.7236226,32.01996946334839,1.2115953386096179,1739502671.7236242,32.01996946334839,0.6108,1739502671.7236254,32.01996946334839,0.9483937270919816,1739502671.7236273,32.01996946334839,0.0,1739502671.7236285,32.01996946334839,-0.00024271288877331099,1739502671.7236302,32.01996946334839,2.2153722159147966,1739502671.7236316,32.01996946334839,0.9486364399807549 +1739502671.743494,32.0399694442749,50.5254255862397,1739502671.743497,32.0399694442749,6.6910416052682695,1739502671.7434998,32.0399694442749,57.06386284198682,1739502671.7435024,32.0399694442749,47.54414621671242,1739502671.7435038,32.0399694442749,8.640755791981965,1739502671.7435057,32.0399694442749,2.56242060970074,1739502671.7435071,32.0399694442749,1.2115953386096179,1739502671.7435086,32.0399694442749,0.6108,1739502671.7435098,32.0399694442749,0.9483937270919816,1739502671.7435114,32.0399694442749,0.0,1739502671.7435129,32.0399694442749,-0.00024271288877331099,1739502671.7435143,32.0399694442749,2.2153722159147966,1739502671.7435157,32.0399694442749,0.9486364399807549 +1739502671.7634943,32.059969425201416,50.5254255862397,1739502671.7634966,32.059969425201416,6.6910416052682695,1739502671.7634995,32.059969425201416,57.06386284198682,1739502671.7635026,32.059969425201416,47.54414621671242,1739502671.7635038,32.059969425201416,8.640755791981965,1739502671.763506,32.059969425201416,2.56242060970074,1739502671.7635074,32.059969425201416,1.2115953386096179,1739502671.763509,32.059969425201416,0.6108,1739502671.7635102,32.059969425201416,0.9483937270919816,1739502671.763512,32.059969425201416,0.0,1739502671.763513,32.059969425201416,-0.00024271288877331099,1739502671.763515,32.059969425201416,2.2153722159147966,1739502671.7635162,32.059969425201416,0.9486364399807549 +1739502671.783554,32.07996940612793,50.46170937077643,1739502671.7835565,32.07996940612793,6.773628735777631,1739502671.7835593,32.07996940612793,57.149642414129254,1739502671.7835622,32.07996940612793,47.459162474573816,1739502671.7835639,32.07996940612793,8.642,1739502671.7835655,32.07996940612793,2.5849645577694824,1739502671.7835672,32.07996940612793,1.1859769351861194,1739502671.7835684,32.07996940612793,0.6108,1739502671.7835696,32.07996940612793,0.9680313399243524,1739502671.7835717,32.07996940612793,0.0,1739502671.783573,32.07996940612793,0.028888429409519266,1739502671.7835746,32.07996940612793,2.2429739048573434,1739502671.783576,32.07996940612793,0.9482463984517614 +1739502671.8036761,32.09996938705444,50.46170937077643,1739502671.8036788,32.09996938705444,6.773628735777631,1739502671.803682,32.09996938705444,57.149642414129254,1739502671.8036852,32.09996938705444,47.459162474573816,1739502671.8036866,32.09996938705444,8.642,1739502671.8036885,32.09996938705444,2.5849645577694824,1739502671.80369,32.09996938705444,1.1859769351861194,1739502671.8036916,32.09996938705444,0.6108,1739502671.803693,32.09996938705444,0.9680313399243524,1739502671.803695,32.09996938705444,0.0,1739502671.8036964,32.09996938705444,0.019784941472591022,1739502671.803698,32.09996938705444,2.2429739048573434,1739502671.8036997,32.09996938705444,0.9482463984517614 +1739502671.823815,32.11996936798096,50.46170937077643,1739502671.8238187,32.11996936798096,6.773628735777631,1739502671.823822,32.11996936798096,57.149642414129254,1739502671.8238254,32.11996936798096,47.459162474573816,1739502671.823827,32.11996936798096,8.642,1739502671.823829,32.11996936798096,2.5849645577694824,1739502671.8238308,32.11996936798096,1.1859769351861194,1739502671.8238323,32.11996936798096,0.6108,1739502671.8238337,32.11996936798096,0.9680313399243524,1739502671.8238356,32.11996936798096,0.0,1739502671.823837,32.11996936798096,0.019784941472591022,1739502671.8238387,32.11996936798096,2.2429739048573434,1739502671.8238409,32.11996936798096,0.9482463984517614 +1739502671.8437865,32.13996934890747,50.46170937077643,1739502671.843789,32.13996934890747,6.773628735777631,1739502671.8437924,32.13996934890747,57.149642414129254,1739502671.8437955,32.13996934890747,47.459162474573816,1739502671.843797,32.13996934890747,8.642,1739502671.843799,32.13996934890747,2.5849645577694824,1739502671.8438005,32.13996934890747,1.1859769351861194,1739502671.8438022,32.13996934890747,0.6108,1739502671.8438036,32.13996934890747,0.9680313399243524,1739502671.8438058,32.13996934890747,0.0,1739502671.843807,32.13996934890747,0.019784941472591022,1739502671.8438087,32.13996934890747,2.2429739048573434,1739502671.8438103,32.13996934890747,0.9482463984517614 +1739502671.863678,32.159969329833984,50.46170937077643,1739502671.8636808,32.159969329833984,6.773628735777631,1739502671.8636844,32.159969329833984,57.149642414129254,1739502671.8636875,32.159969329833984,47.459162474573816,1739502671.863689,32.159969329833984,8.642,1739502671.8636909,32.159969329833984,2.5849645577694824,1739502671.8636925,32.159969329833984,1.1859769351861194,1739502671.8636942,32.159969329833984,0.6108,1739502671.8636956,32.159969329833984,0.9680313399243524,1739502671.863698,32.159969329833984,0.0,1739502671.8636992,32.159969329833984,0.019784941472591022,1739502671.863701,32.159969329833984,2.2429739048573434,1739502671.8637025,32.159969329833984,0.9482463984517614 +1739502671.8839128,32.1799693107605,50.46170937077643,1739502671.8839152,32.1799693107605,6.773628735777631,1739502671.8839188,32.1799693107605,57.149642414129254,1739502671.883922,32.1799693107605,47.459162474573816,1739502671.8839238,32.1799693107605,8.642,1739502671.883926,32.1799693107605,2.5849645577694824,1739502671.8839276,32.1799693107605,1.1859769351861194,1739502671.8839293,32.1799693107605,0.6108,1739502671.883931,32.1799693107605,0.9680313399243524,1739502671.8839326,32.1799693107605,0.0,1739502671.8839343,32.1799693107605,0.019784941472591022,1739502671.883936,32.1799693107605,2.2429739048573434,1739502671.8839376,32.1799693107605,0.9482463984517614 +1739502671.903757,32.19996929168701,50.3956752016473,1739502671.90376,32.19996929168701,6.854502089755112,1739502671.9037633,32.19996929168701,57.31332172780676,1739502671.9037662,32.19996929168701,47.29120282908766,1739502671.9037678,32.19996929168701,8.639774431515068,1739502671.90377,32.19996929168701,2.6197097832778895,1739502671.9037716,32.19996929168701,1.2250702473644608,1739502671.903773,32.19996929168701,0.6108,1739502671.9037747,32.19996929168701,0.9382250193790125,1739502671.9037764,32.19996929168701,0.0,1739502671.903778,32.19996929168701,-0.026698776182173173,1739502671.9037795,32.19996929168701,2.27057559379989,1739502671.9037814,32.19996929168701,0.9503976242699718 +1739502671.9237936,32.219969272613525,50.3956752016473,1739502671.9237967,32.219969272613525,6.854502089755112,1739502671.9238005,32.219969272613525,57.31332172780676,1739502671.923804,32.219969272613525,47.29120282908766,1739502671.9238057,32.219969272613525,8.639774431515068,1739502671.9238079,32.219969272613525,2.6197097832778895,1739502671.9238098,32.219969272613525,1.2250702473644608,1739502671.9238117,32.219969272613525,0.6108,1739502671.923813,32.219969272613525,0.9382250193790125,1739502671.9238155,32.219969272613525,0.0,1739502671.9238172,32.219969272613525,-0.012172604890959282,1739502671.923819,32.219969272613525,2.27057559379989,1739502671.9238207,32.219969272613525,0.9503976242699718 +1739502671.943949,32.23996925354004,50.3956752016473,1739502671.9439518,32.23996925354004,6.854502089755112,1739502671.9439554,32.23996925354004,57.31332172780676,1739502671.943959,32.23996925354004,47.29120282908766,1739502671.943961,32.23996925354004,8.639774431515068,1739502671.943963,32.23996925354004,2.6197097832778895,1739502671.943965,32.23996925354004,1.2250702473644608,1739502671.9439666,32.23996925354004,0.6108,1739502671.9439685,32.23996925354004,0.9382250193790125,1739502671.9439704,32.23996925354004,0.0,1739502671.9439723,32.23996925354004,-0.012172604890959282,1739502671.9439743,32.23996925354004,2.27057559379989,1739502671.943976,32.23996925354004,0.9503976242699718 +1739502671.9640222,32.25996923446655,50.3956752016473,1739502671.9640253,32.25996923446655,6.854502089755112,1739502671.9640288,32.25996923446655,57.31332172780676,1739502671.9640322,32.25996923446655,47.29120282908766,1739502671.964034,32.25996923446655,8.639774431515068,1739502671.964036,32.25996923446655,2.6197097832778895,1739502671.964038,32.25996923446655,1.2250702473644608,1739502671.9640396,32.25996923446655,0.6108,1739502671.9640415,32.25996923446655,0.9382250193790125,1739502671.9640436,32.25996923446655,0.0,1739502671.9640453,32.25996923446655,-0.012172604890959282,1739502671.964047,32.25996923446655,2.27057559379989,1739502671.9640486,32.25996923446655,0.9503976242699718 +1739502671.9842708,32.279969215393066,50.3956752016473,1739502671.9842746,32.279969215393066,6.854502089755112,1739502671.9842784,32.279969215393066,57.31332172780676,1739502671.984282,32.279969215393066,47.29120282908766,1739502671.984284,32.279969215393066,8.639774431515068,1739502671.9842863,32.279969215393066,2.6197097832778895,1739502671.9842882,32.279969215393066,1.2250702473644608,1739502671.9842901,32.279969215393066,0.6108,1739502671.9842916,32.279969215393066,0.9382250193790125,1739502671.984294,32.279969215393066,0.0,1739502671.9842954,32.279969215393066,-0.012172604890959282,1739502671.9842978,32.279969215393066,2.27057559379989,1739502671.9842994,32.279969215393066,0.9503976242699718 +1739502672.0041163,32.29996919631958,50.327360089310055,1739502672.0041196,32.29996919631958,6.9336093431591,1739502672.0041234,32.29996919631958,57.416074394901955,1739502672.0041268,32.29996919631958,47.190246690152975,1739502672.0041285,32.29996919631958,8.63537162513605,1739502672.0041306,32.29996919631958,2.644555811888228,1739502672.0041325,32.29996919631958,1.21163926992367,1739502672.0041342,32.29996919631958,0.6108,1739502672.0041358,32.29996919631958,0.9483603963315547,1739502672.004138,32.29996919631958,0.0,1739502672.0041394,32.29996919631958,0.003801495085516744,1739502672.0041416,32.29996919631958,2.298177282742437,1739502672.0041435,32.29996919631958,0.9495508107616376 +1739502672.0243893,32.319969177246094,50.327360089310055,1739502672.0243926,32.319969177246094,6.9336093431591,1739502672.0243971,32.319969177246094,57.416074394901955,1739502672.0244007,32.319969177246094,47.190246690152975,1739502672.0244024,32.319969177246094,8.63537162513605,1739502672.0244048,32.319969177246094,2.644555811888228,1739502672.0244064,32.319969177246094,1.21163926992367,1739502672.0244083,32.319969177246094,0.6108,1739502672.0244098,32.319969177246094,0.9483603963315547,1739502672.0244122,32.319969177246094,0.0,1739502672.024414,32.319969177246094,-0.0011904144300829422,1739502672.024416,32.319969177246094,2.298177282742437,1739502672.0244179,32.319969177246094,0.9495508107616376 +1739502672.0571666,32.33996915817261,50.327360089310055,1739502672.057176,32.33996915817261,6.9336093431591,1739502672.0571868,32.33996915817261,57.416074394901955,1739502672.0571966,32.33996915817261,47.190246690152975,1739502672.0572014,32.33996915817261,8.63537162513605,1739502672.0572076,32.33996915817261,2.644555811888228,1739502672.0572128,32.33996915817261,1.21163926992367,1739502672.0572178,32.33996915817261,0.6108,1739502672.0572224,32.33996915817261,0.9483603963315547,1739502672.057228,32.33996915817261,0.0,1739502672.0572329,32.33996915817261,-0.0011904144300829422,1739502672.057238,32.33996915817261,2.298177282742437,1739502672.057243,32.33996915817261,0.9495508107616376 +1739502672.0736125,32.35996913909912,50.327360089310055,1739502672.073626,32.35996913909912,6.9336093431591,1739502672.0736425,32.35996913909912,57.416074394901955,1739502672.0736592,32.35996913909912,47.190246690152975,1739502672.0736666,32.35996913909912,8.63537162513605,1739502672.0736773,32.35996913909912,2.644555811888228,1739502672.0736868,32.35996913909912,1.21163926992367,1739502672.073695,32.35996913909912,0.6108,1739502672.0737026,32.35996913909912,0.9483603963315547,1739502672.0737116,32.35996913909912,0.0,1739502672.07372,32.35996913909912,-0.0011904144300829422,1739502672.073729,32.35996913909912,2.298177282742437,1739502672.0737374,32.35996913909912,0.9495508107616376 +1739502672.1011305,32.38996911048889,50.327360089310055,1739502672.1011345,32.38996911048889,6.9336093431591,1739502672.1011393,32.38996911048889,57.416074394901955,1739502672.1011438,32.38996911048889,47.190246690152975,1739502672.1011462,32.38996911048889,8.63537162513605,1739502672.1011486,32.38996911048889,2.644555811888228,1739502672.1011508,32.38996911048889,1.21163926992367,1739502672.1011531,32.38996911048889,0.6108,1739502672.101155,32.38996911048889,0.9483603963315547,1739502672.1011577,32.38996911048889,0.0,1739502672.10116,32.38996911048889,-0.0011904144300829422,1739502672.1011622,32.38996911048889,2.298177282742437,1739502672.1011646,32.38996911048889,0.9495508107616376 +1739502672.1182125,32.41996908187866,50.256944209287575,1739502672.118215,32.41996908187866,7.01073891650125,1739502672.118219,32.41996908187866,57.55859229668236,1739502672.1182225,32.41996908187866,47.048347939360305,1739502672.1182246,32.41996908187866,8.625915840711823,1739502672.1182268,32.41996908187866,2.6752363139488198,1739502672.1182284,32.41996908187866,1.22992548799359,1739502672.1182303,32.41996908187866,0.6108,1739502672.118232,32.41996908187866,0.9345878411154276,1739502672.118234,32.41996908187866,0.0,1739502672.1182356,32.41996908187866,-0.021019988808318037,1739502672.1182375,32.41996908187866,2.3257789716849837,1739502672.1182392,32.41996908187866,0.9494110838676438 +1739502672.1384838,32.439969062805176,50.256944209287575,1739502672.1384869,32.439969062805176,7.01073891650125,1739502672.1384907,32.439969062805176,57.55859229668236,1739502672.1384943,32.439969062805176,47.048347939360305,1739502672.1384962,32.439969062805176,8.625915840711823,1739502672.1384983,32.439969062805176,2.6752363139488198,1739502672.1385005,32.439969062805176,1.22992548799359,1739502672.1385021,32.439969062805176,0.6108,1739502672.1385043,32.439969062805176,0.9345878411154276,1739502672.1385062,32.439969062805176,0.0,1739502672.138508,32.439969062805176,-0.014823242752216248,1739502672.13851,32.439969062805176,2.3257789716849837,1739502672.138512,32.439969062805176,0.9494110838676438 +1739502672.1582131,32.45996904373169,50.256944209287575,1739502672.1582167,32.45996904373169,7.01073891650125,1739502672.1582208,32.45996904373169,57.55859229668236,1739502672.1582246,32.45996904373169,47.048347939360305,1739502672.1582265,32.45996904373169,8.625915840711823,1739502672.1582286,32.45996904373169,2.6752363139488198,1739502672.1582305,32.45996904373169,1.22992548799359,1739502672.158232,32.45996904373169,0.6108,1739502672.158234,32.45996904373169,0.9345878411154276,1739502672.1582358,32.45996904373169,0.0,1739502672.1582377,32.45996904373169,-0.014823242752216248,1739502672.1582398,32.45996904373169,2.3257789716849837,1739502672.1582415,32.45996904373169,0.9494110838676438 +1739502672.178295,32.4799690246582,50.256944209287575,1739502672.1782978,32.4799690246582,7.01073891650125,1739502672.178302,32.4799690246582,57.55859229668236,1739502672.1783056,32.4799690246582,47.048347939360305,1739502672.1783073,32.4799690246582,8.625915840711823,1739502672.1783097,32.4799690246582,2.6752363139488198,1739502672.1783113,32.4799690246582,1.22992548799359,1739502672.1783133,32.4799690246582,0.6108,1739502672.178315,32.4799690246582,0.9345878411154276,1739502672.178317,32.4799690246582,0.0,1739502672.1783187,32.4799690246582,-0.014823242752216248,1739502672.1783206,32.4799690246582,2.3257789716849837,1739502672.1783223,32.4799690246582,0.9494110838676438 +1739502672.1978278,32.49996900558472,50.256944209287575,1739502672.1978314,32.49996900558472,7.01073891650125,1739502672.1978354,32.49996900558472,57.55859229668236,1739502672.1978393,32.49996900558472,47.048347939360305,1739502672.1978414,32.49996900558472,8.625915840711823,1739502672.197844,32.49996900558472,2.6752363139488198,1739502672.1978457,32.49996900558472,1.22992548799359,1739502672.1978476,32.49996900558472,0.6108,1739502672.1978493,32.49996900558472,0.9345878411154276,1739502672.1978517,32.49996900558472,0.0,1739502672.1978533,32.49996900558472,-0.014823242752216248,1739502672.1978555,32.49996900558472,2.3257789716849837,1739502672.1978574,32.49996900558472,0.9494110838676438 +1739502672.218188,32.51996898651123,50.184485599229745,1739502672.2181916,32.51996898651123,7.085835106639463,1739502672.2181954,32.51996898651123,57.629937808390586,1739502672.218199,32.51996898651123,46.980557195136676,1739502672.218201,32.51996898651123,8.619236635398634,1739502672.2182028,32.51996898651123,2.695210786934836,1739502672.2182047,32.51996898651123,1.1906619539365078,1739502672.2182062,32.51996898651123,0.6108,1739502672.218208,32.51996898651123,0.9644099347213981,1739502672.21821,32.51996898651123,0.0,1739502672.218212,32.51996898651123,0.030900060930156063,1739502672.2182136,32.51996898651123,2.3533806606275305,1739502672.2182152,32.51996898651123,0.9477984155602814 +1739502672.2370727,32.539968967437744,50.184485599229745,1739502672.237075,32.539968967437744,7.085835106639463,1739502672.2370782,32.539968967437744,57.629937808390586,1739502672.2370808,32.539968967437744,46.980557195136676,1739502672.2370825,32.539968967437744,8.619236635398634,1739502672.2370842,32.539968967437744,2.695210786934836,1739502672.2370856,32.539968967437744,1.1906619539365078,1739502672.2370872,32.539968967437744,0.6108,1739502672.2370887,32.539968967437744,0.9644099347213981,1739502672.2370903,32.539968967437744,0.0,1739502672.2370915,32.539968967437744,0.016611519161116695,1739502672.2370932,32.539968967437744,2.3533806606275305,1739502672.2370946,32.539968967437744,0.9477984155602814 +1739502672.2569137,32.55996894836426,50.184485599229745,1739502672.2569163,32.55996894836426,7.085835106639463,1739502672.2569196,32.55996894836426,57.629937808390586,1739502672.2569227,32.55996894836426,46.980557195136676,1739502672.256924,32.55996894836426,8.619236635398634,1739502672.256926,32.55996894836426,2.695210786934836,1739502672.2569275,32.55996894836426,1.1906619539365078,1739502672.256929,32.55996894836426,0.6108,1739502672.2569304,32.55996894836426,0.9644099347213981,1739502672.256932,32.55996894836426,0.0,1739502672.2569335,32.55996894836426,0.016611519161116695,1739502672.256935,32.55996894836426,2.3533806606275305,1739502672.2569366,32.55996894836426,0.9477984155602814 +1739502672.2777698,32.57996892929077,50.184485599229745,1739502672.2777734,32.57996892929077,7.085835106639463,1739502672.2777772,32.57996892929077,57.629937808390586,1739502672.2777808,32.57996892929077,46.980557195136676,1739502672.2777824,32.57996892929077,8.619236635398634,1739502672.2777848,32.57996892929077,2.695210786934836,1739502672.2777867,32.57996892929077,1.1906619539365078,1739502672.2777882,32.57996892929077,0.6108,1739502672.27779,32.57996892929077,0.9644099347213981,1739502672.277792,32.57996892929077,0.0,1739502672.2777936,32.57996892929077,0.016611519161116695,1739502672.2777953,32.57996892929077,2.3533806606275305,1739502672.2777975,32.57996892929077,0.9477984155602814 +1739502672.2974176,32.599968910217285,50.184485599229745,1739502672.2974207,32.599968910217285,7.085835106639463,1739502672.2974243,32.599968910217285,57.629937808390586,1739502672.2974277,32.599968910217285,46.980557195136676,1739502672.2974296,32.599968910217285,8.619236635398634,1739502672.2974315,32.599968910217285,2.695210786934836,1739502672.2974331,32.599968910217285,1.1906619539365078,1739502672.2974348,32.599968910217285,0.6108,1739502672.2974365,32.599968910217285,0.9644099347213981,1739502672.2974381,32.599968910217285,0.0,1739502672.29744,32.599968910217285,0.016611519161116695,1739502672.2974417,32.599968910217285,2.3533806606275305,1739502672.2974436,32.599968910217285,0.9477984155602814 +1739502672.317526,32.6199688911438,50.184485599229745,1739502672.3175287,32.6199688911438,7.085835106639463,1739502672.3175323,32.6199688911438,57.629937808390586,1739502672.3175356,32.6199688911438,46.980557195136676,1739502672.3175375,32.6199688911438,8.619236635398634,1739502672.31754,32.6199688911438,2.695210786934836,1739502672.3175416,32.6199688911438,1.1906619539365078,1739502672.3175433,32.6199688911438,0.6108,1739502672.3175447,32.6199688911438,0.9644099347213981,1739502672.3175468,32.6199688911438,0.0,1739502672.3175483,32.6199688911438,0.016611519161116695,1739502672.3175502,32.6199688911438,2.3533806606275305,1739502672.3175516,32.6199688911438,0.9477984155602814 +1739502672.3368537,32.63996887207031,50.109967771378855,1739502672.3368556,32.63996887207031,7.1589156867473385,1739502672.3368583,32.63996887207031,57.729835452328516,1739502672.336861,32.63996887207031,46.87705552891564,1739502672.3368623,32.63996887207031,8.60804846052294,1739502672.3368638,32.63996887207031,2.720200168680172,1739502672.336865,32.63996887207031,1.178878170466792,1739502672.3368664,32.63996887207031,0.6108,1739502672.3368673,32.63996887207031,0.9735444409686831,1739502672.3368688,32.63996887207031,0.0,1739502672.33687,32.63996887207031,0.026836429147696926,1739502672.3368714,32.63996887207031,2.3809823495700773,1739502672.3368723,32.63996887207031,0.9499032982867855 +1739502672.3567522,32.659968852996826,50.109967771378855,1739502672.356767,32.659968852996826,7.1589156867473385,1739502672.35677,32.659968852996826,57.729835452328516,1739502672.3567724,32.659968852996826,46.87705552891564,1739502672.3567736,32.659968852996826,8.60804846052294,1739502672.3567755,32.659968852996826,2.720200168680172,1739502672.3567767,32.659968852996826,1.178878170466792,1739502672.356778,32.659968852996826,0.6108,1739502672.356779,32.659968852996826,0.9735444409686831,1739502672.3567805,32.659968852996826,0.0,1739502672.3567815,32.659968852996826,0.023641142681897542,1739502672.356783,32.659968852996826,2.3809823495700773,1739502672.3567843,32.659968852996826,0.9499032982867855 +1739502672.377022,32.67996883392334,50.109967771378855,1739502672.3770242,32.67996883392334,7.1589156867473385,1739502672.377027,32.67996883392334,57.729835452328516,1739502672.37703,32.67996883392334,46.87705552891564,1739502672.377031,32.67996883392334,8.60804846052294,1739502672.3770328,32.67996883392334,2.720200168680172,1739502672.377034,32.67996883392334,1.178878170466792,1739502672.3770356,32.67996883392334,0.6108,1739502672.3770368,32.67996883392334,0.9735444409686831,1739502672.3770382,32.67996883392334,0.0,1739502672.3770397,32.67996883392334,0.023641142681897542,1739502672.377041,32.67996883392334,2.3809823495700773,1739502672.3770425,32.67996883392334,0.9499032982867855 +1739502672.3976197,32.69996881484985,50.109967771378855,1739502672.397622,32.69996881484985,7.1589156867473385,1739502672.3976247,32.69996881484985,57.729835452328516,1739502672.3976274,32.69996881484985,46.87705552891564,1739502672.3976288,32.69996881484985,8.60804846052294,1739502672.3976305,32.69996881484985,2.720200168680172,1739502672.3976316,32.69996881484985,1.178878170466792,1739502672.3976333,32.69996881484985,0.6108,1739502672.3976345,32.69996881484985,0.9735444409686831,1739502672.3976362,32.69996881484985,0.0,1739502672.3976374,32.69996881484985,0.023641142681897542,1739502672.3976386,32.69996881484985,2.3809823495700773,1739502672.3976402,32.69996881484985,0.9499032982867855 +1739502672.4174185,32.71996879577637,50.109967771378855,1739502672.4174209,32.71996879577637,7.1589156867473385,1739502672.4174237,32.71996879577637,57.729835452328516,1739502672.417426,32.71996879577637,46.87705552891564,1739502672.4174275,32.71996879577637,8.60804846052294,1739502672.417429,32.71996879577637,2.720200168680172,1739502672.4174306,32.71996879577637,1.178878170466792,1739502672.4174318,32.71996879577637,0.6108,1739502672.417433,32.71996879577637,0.9735444409686831,1739502672.4174347,32.71996879577637,0.0,1739502672.417436,32.71996879577637,0.023641142681897542,1739502672.4174376,32.71996879577637,2.3809823495700773,1739502672.4174387,32.71996879577637,0.9499032982867855 +1739502672.4370081,32.73996877670288,50.03328445190242,1739502672.4370108,32.73996877670288,7.230075905866313,1739502672.437014,32.73996877670288,57.879136436451304,1739502672.4370167,32.73996877670288,46.72361250764034,1739502672.4370182,32.73996877670288,8.590343355397511,1739502672.4370198,32.73996877670288,2.751641627402783,1739502672.4370213,32.73996877670288,1.203627094592804,1739502672.4370224,32.73996877670288,0.6108,1739502672.437024,32.73996877670288,0.9544586634246156,1739502672.4370253,32.73996877670288,0.0,1739502672.4370265,32.73996877670288,-0.007878321849086092,1739502672.4370282,32.73996877670288,2.408584038512624,1739502672.4370296,32.73996877670288,0.9524871461497115 +1739502672.45728,32.759968757629395,50.03328445190242,1739502672.4572833,32.759968757629395,7.230075905866313,1739502672.4572868,32.759968757629395,57.879136436451304,1739502672.4572902,32.759968757629395,46.72361250764034,1739502672.457292,32.759968757629395,8.590343355397511,1739502672.4572942,32.759968757629395,2.751641627402783,1739502672.4572961,32.759968757629395,1.203627094592804,1739502672.4572976,32.759968757629395,0.6108,1739502672.4572992,32.759968757629395,0.9544586634246156,1739502672.4573011,32.759968757629395,0.0,1739502672.4573028,32.759968757629395,0.0019715172749040777,1739502672.4573047,32.759968757629395,2.408584038512624,1739502672.4573066,32.759968757629395,0.9524871461497115 +1739502672.4775612,32.77996873855591,50.03328445190242,1739502672.477564,32.77996873855591,7.230075905866313,1739502672.477568,32.77996873855591,57.879136436451304,1739502672.4775715,32.77996873855591,46.72361250764034,1739502672.4775734,32.77996873855591,8.590343355397511,1739502672.477576,32.77996873855591,2.751641627402783,1739502672.4775777,32.77996873855591,1.203627094592804,1739502672.4775796,32.77996873855591,0.6108,1739502672.477581,32.77996873855591,0.9544586634246156,1739502672.4775832,32.77996873855591,0.0,1739502672.4775848,32.77996873855591,0.0019715172749040777,1739502672.477587,32.77996873855591,2.408584038512624,1739502672.4775887,32.77996873855591,0.9524871461497115 +1739502672.4975464,32.79996871948242,50.03328445190242,1739502672.4975502,32.79996871948242,7.230075905866313,1739502672.4975553,32.79996871948242,57.879136436451304,1739502672.4975593,32.79996871948242,46.72361250764034,1739502672.4975615,32.79996871948242,8.590343355397511,1739502672.4975638,32.79996871948242,2.751641627402783,1739502672.497566,32.79996871948242,1.203627094592804,1739502672.497568,32.79996871948242,0.6108,1739502672.4975698,32.79996871948242,0.9544586634246156,1739502672.4975722,32.79996871948242,0.0,1739502672.497574,32.79996871948242,0.0019715172749040777,1739502672.4975762,32.79996871948242,2.408584038512624,1739502672.497578,32.79996871948242,0.9524871461497115 +1739502672.5176954,32.819968700408936,50.03328445190242,1739502672.5176983,32.819968700408936,7.230075905866313,1739502672.5177019,32.819968700408936,57.879136436451304,1739502672.5177057,32.819968700408936,46.72361250764034,1739502672.5177076,32.819968700408936,8.590343355397511,1739502672.5177095,32.819968700408936,2.751641627402783,1739502672.5177116,32.819968700408936,1.203627094592804,1739502672.5177133,32.819968700408936,0.6108,1739502672.517715,32.819968700408936,0.9544586634246156,1739502672.517717,32.819968700408936,0.0,1739502672.5177188,32.819968700408936,0.0019715172749040777,1739502672.517721,32.819968700408936,2.408584038512624,1739502672.5177228,32.819968700408936,0.9524871461497115 +1739502672.537538,32.83996868133545,50.03328445190242,1739502672.5375419,32.83996868133545,7.230075905866313,1739502672.5375473,32.83996868133545,57.879136436451304,1739502672.537551,32.83996868133545,46.72361250764034,1739502672.537553,32.83996868133545,8.590343355397511,1739502672.5375555,32.83996868133545,2.751641627402783,1739502672.5375574,32.83996868133545,1.203627094592804,1739502672.5375593,32.83996868133545,0.6108,1739502672.5375612,32.83996868133545,0.9544586634246156,1739502672.5375633,32.83996868133545,0.0,1739502672.5375652,32.83996868133545,0.0019715172749040777,1739502672.5375671,32.83996868133545,2.408584038512624,1739502672.537569,32.83996868133545,0.9524871461497115 +1739502672.5575962,32.85996866226196,49.95455537928009,1739502672.5576,32.85996866226196,7.299191055068736,1739502672.5576038,32.85996866226196,57.981188522717154,1739502672.5576074,32.85996866226196,46.62250563337788,1739502672.5576093,32.85996866226196,8.576320107809,1739502672.5576115,32.85996866226196,2.7755771369410476,1739502672.5576136,32.85996866226196,1.1879740681335,1739502672.5576153,32.85996866226196,0.6108,1739502672.5576172,32.85996866226196,0.9664859449703158,1739502672.557619,32.85996866226196,0.0,1739502672.557621,32.85996866226196,0.0194360609092306,1739502672.5576227,32.85996866226196,2.436185727455171,1739502672.5576246,32.85996866226196,0.9525075575251418 +1739502672.5776112,32.87996864318848,49.95455537928009,1739502672.5776153,32.87996864318848,7.299191055068736,1739502672.5776198,32.87996864318848,57.981188522717154,1739502672.5776258,32.87996864318848,46.62250563337788,1739502672.5776293,32.87996864318848,8.576320107809,1739502672.5776322,32.87996864318848,2.7755771369410476,1739502672.5776496,32.87996864318848,1.1879740681335,1739502672.5776534,32.87996864318848,0.6108,1739502672.5776567,32.87996864318848,0.9664859449703158,1739502672.577661,32.87996864318848,0.0,1739502672.5776641,32.87996864318848,0.01397838744517399,1739502672.5776734,32.87996864318848,2.436185727455171,1739502672.5776758,32.87996864318848,0.9525075575251418 +1739502672.5975301,32.89996862411499,49.95455537928009,1739502672.5975342,32.89996862411499,7.299191055068736,1739502672.5975385,32.89996862411499,57.981188522717154,1739502672.5975423,32.89996862411499,46.62250563337788,1739502672.5975444,32.89996862411499,8.576320107809,1739502672.5975468,32.89996862411499,2.7755771369410476,1739502672.5975492,32.89996862411499,1.1879740681335,1739502672.597551,32.89996862411499,0.6108,1739502672.597553,32.89996862411499,0.9664859449703158,1739502672.5975556,32.89996862411499,0.0,1739502672.5975575,32.89996862411499,0.01397838744517399,1739502672.5975597,32.89996862411499,2.436185727455171,1739502672.5975618,32.89996862411499,0.9525075575251418 +1739502672.6174634,32.919968605041504,49.95455537928009,1739502672.6174664,32.919968605041504,7.299191055068736,1739502672.6174703,32.919968605041504,57.981188522717154,1739502672.6174738,32.919968605041504,46.62250563337788,1739502672.6174755,32.919968605041504,8.576320107809,1739502672.617478,32.919968605041504,2.7755771369410476,1739502672.6174796,32.919968605041504,1.1879740681335,1739502672.6174815,32.919968605041504,0.6108,1739502672.617483,32.919968605041504,0.9664859449703158,1739502672.617485,32.919968605041504,0.0,1739502672.617487,32.919968605041504,0.01397838744517399,1739502672.6174886,32.919968605041504,2.436185727455171,1739502672.6174908,32.919968605041504,0.9525075575251418 +1739502672.637989,32.93996858596802,49.95455537928009,1739502672.6379926,32.93996858596802,7.299191055068736,1739502672.6379974,32.93996858596802,57.981188522717154,1739502672.6380012,32.93996858596802,46.62250563337788,1739502672.6380029,32.93996858596802,8.576320107809,1739502672.6380055,32.93996858596802,2.7755771369410476,1739502672.6380076,32.93996858596802,1.1879740681335,1739502672.6380095,32.93996858596802,0.6108,1739502672.6380115,32.93996858596802,0.9664859449703158,1739502672.6380134,32.93996858596802,0.0,1739502672.6380153,32.93996858596802,0.01397838744517399,1739502672.6380177,32.93996858596802,2.436185727455171,1739502672.6380198,32.93996858596802,0.9525075575251418 +1739502672.6581554,32.95996856689453,49.87388390242983,1739502672.6581585,32.95996856689453,7.366160517051526,1739502672.6581626,32.95996856689453,58.147717294344055,1739502672.6581662,32.95996856689453,46.45578726122637,1739502672.658168,32.95996856689453,8.54543523342846,1739502672.6581705,32.95996856689453,2.809370900071626,1739502672.6581721,32.95996856689453,1.2248397725191364,1739502672.658174,32.95996856689453,0.6108,1739502672.6581757,32.95996856689453,0.9383980251408895,1739502672.6581779,32.95996856689453,0.0,1739502672.6581795,32.95996856689453,-0.029089992426181828,1739502672.6581814,32.95996856689453,2.4637874163977176,1739502672.658183,32.95996856689453,0.9540291400329449 +1739502672.6782167,32.979968547821045,49.87388390242983,1739502672.6782198,32.979968547821045,7.366160517051526,1739502672.6782236,32.979968547821045,58.147717294344055,1739502672.6782272,32.979968547821045,46.45578726122637,1739502672.6782293,32.979968547821045,8.54543523342846,1739502672.6782315,32.979968547821045,2.809370900071626,1739502672.6782334,32.979968547821045,1.2248397725191364,1739502672.678235,32.979968547821045,0.6108,1739502672.6782367,32.979968547821045,0.9383980251408895,1739502672.6782389,32.979968547821045,0.0,1739502672.6782408,32.979968547821045,-0.015631114892055376,1739502672.6782424,32.979968547821045,2.4637874163977176,1739502672.6782448,32.979968547821045,0.9540291400329449 +1739502672.6982372,32.99996852874756,49.87388390242983,1739502672.6982408,32.99996852874756,7.366160517051526,1739502672.698245,32.99996852874756,58.147717294344055,1739502672.6982486,32.99996852874756,46.45578726122637,1739502672.6982505,32.99996852874756,8.54543523342846,1739502672.6982532,32.99996852874756,2.809370900071626,1739502672.698255,32.99996852874756,1.2248397725191364,1739502672.698257,32.99996852874756,0.6108,1739502672.6982586,32.99996852874756,0.9383980251408895,1739502672.6982608,32.99996852874756,0.0,1739502672.6982627,32.99996852874756,-0.015631114892055376,1739502672.6982648,32.99996852874756,2.4637874163977176,1739502672.6982665,32.99996852874756,0.9540291400329449 +1739502672.7176678,33.01996850967407,49.87388390242983,1739502672.7176712,33.01996850967407,7.366160517051526,1739502672.717675,33.01996850967407,58.147717294344055,1739502672.7176785,33.01996850967407,46.45578726122637,1739502672.7176805,33.01996850967407,8.54543523342846,1739502672.7176826,33.01996850967407,2.809370900071626,1739502672.7176847,33.01996850967407,1.2248397725191364,1739502672.7176864,33.01996850967407,0.6108,1739502672.717688,33.01996850967407,0.9383980251408895,1739502672.7176902,33.01996850967407,0.0,1739502672.717692,33.01996850967407,-0.015631114892055376,1739502672.7176938,33.01996850967407,2.4637874163977176,1739502672.7176955,33.01996850967407,0.9540291400329449 +1739502672.7374403,33.039968490600586,49.87388390242983,1739502672.7374427,33.039968490600586,7.366160517051526,1739502672.7374463,33.039968490600586,58.147717294344055,1739502672.7374494,33.039968490600586,46.45578726122637,1739502672.737451,33.039968490600586,8.54543523342846,1739502672.737453,33.039968490600586,2.809370900071626,1739502672.737455,33.039968490600586,1.2248397725191364,1739502672.7374563,33.039968490600586,0.6108,1739502672.7374578,33.039968490600586,0.9383980251408895,1739502672.7374597,33.039968490600586,0.0,1739502672.7374613,33.039968490600586,-0.015631114892055376,1739502672.7374628,33.039968490600586,2.4637874163977176,1739502672.7374647,33.039968490600586,0.9540291400329449 +1739502672.7571988,33.0599684715271,49.87388390242983,1739502672.7572021,33.0599684715271,7.366160517051526,1739502672.7572057,33.0599684715271,58.147717294344055,1739502672.757209,33.0599684715271,46.45578726122637,1739502672.7572107,33.0599684715271,8.54543523342846,1739502672.7572129,33.0599684715271,2.809370900071626,1739502672.7572148,33.0599684715271,1.2248397725191364,1739502672.7572162,33.0599684715271,0.6108,1739502672.7572181,33.0599684715271,0.9383980251408895,1739502672.7572198,33.0599684715271,0.0,1739502672.7572215,33.0599684715271,-0.015631114892055376,1739502672.7572231,33.0599684715271,2.4637874163977176,1739502672.757225,33.0599684715271,0.9540291400329449 +1739502672.7777224,33.07996845245361,49.791409557310125,1739502672.777725,33.07996845245361,7.4308677109018255,1739502672.7777283,33.07996845245361,58.23334973436541,1739502672.7777314,33.07996845245361,46.37595694294477,1739502672.7777328,33.07996845245361,8.528195743975141,1739502672.777735,33.07996845245361,2.8307260077495555,1739502672.7777364,33.07996845245361,1.1941090169909234,1739502672.777738,33.07996845245361,0.6108,1739502672.7777395,33.07996845245361,0.9617540928619662,1739502672.7777412,33.07996845245361,0.0,1739502672.7777429,33.07996845245361,0.02122268721138828,1739502672.7777445,33.07996845245361,2.4913891053402644,1739502672.7777462,33.07996845245361,0.9520482263589202 +1739502672.7972887,33.09996843338013,49.791409557310125,1739502672.797292,33.09996843338013,7.4308677109018255,1739502672.797296,33.09996843338013,58.23334973436541,1739502672.7972991,33.09996843338013,46.37595694294477,1739502672.797301,33.09996843338013,8.528195743975141,1739502672.797303,33.09996843338013,2.8307260077495555,1739502672.7973046,33.09996843338013,1.1941090169909234,1739502672.797306,33.09996843338013,0.6108,1739502672.797308,33.09996843338013,0.9617540928619662,1739502672.7973096,33.09996843338013,0.0,1739502672.7973113,33.09996843338013,0.009705866503046057,1739502672.797313,33.09996843338013,2.4913891053402644,1739502672.797315,33.09996843338013,0.9520482263589202 +1739502672.8172922,33.11996841430664,49.791409557310125,1739502672.8172948,33.11996841430664,7.4308677109018255,1739502672.8172984,33.11996841430664,58.23334973436541,1739502672.8173018,33.11996841430664,46.37595694294477,1739502672.8173032,33.11996841430664,8.528195743975141,1739502672.817305,33.11996841430664,2.8307260077495555,1739502672.817307,33.11996841430664,1.1941090169909234,1739502672.8173084,33.11996841430664,0.6108,1739502672.8173096,33.11996841430664,0.9617540928619662,1739502672.8173115,33.11996841430664,0.0,1739502672.817313,33.11996841430664,0.009705866503046057,1739502672.8173149,33.11996841430664,2.4913891053402644,1739502672.8173163,33.11996841430664,0.9520482263589202 +1739502672.837265,33.139968395233154,49.791409557310125,1739502672.8372686,33.139968395233154,7.4308677109018255,1739502672.837273,33.139968395233154,58.23334973436541,1739502672.8372765,33.139968395233154,46.37595694294477,1739502672.837278,33.139968395233154,8.528195743975141,1739502672.83728,33.139968395233154,2.8307260077495555,1739502672.8372817,33.139968395233154,1.1941090169909234,1739502672.8372834,33.139968395233154,0.6108,1739502672.8372848,33.139968395233154,0.9617540928619662,1739502672.837287,33.139968395233154,0.0,1739502672.8372884,33.139968395233154,0.009705866503046057,1739502672.8372905,33.139968395233154,2.4913891053402644,1739502672.8372922,33.139968395233154,0.9520482263589202 +1739502672.8573735,33.15996837615967,49.791409557310125,1739502672.857376,33.15996837615967,7.4308677109018255,1739502672.8573794,33.15996837615967,58.23334973436541,1739502672.8573823,33.15996837615967,46.37595694294477,1739502672.8573842,33.15996837615967,8.528195743975141,1739502672.8573864,33.15996837615967,2.8307260077495555,1739502672.8573878,33.15996837615967,1.1941090169909234,1739502672.8573895,33.15996837615967,0.6108,1739502672.8573909,33.15996837615967,0.9617540928619662,1739502672.8573928,33.15996837615967,0.0,1739502672.8573945,33.15996837615967,0.009705866503046057,1739502672.857396,33.15996837615967,2.4913891053402644,1739502672.8573976,33.15996837615967,0.9520482263589202 +1739502672.8775287,33.17996835708618,49.70722771610914,1739502672.8775313,33.17996835708618,7.4932384117797035,1739502672.8775349,33.17996835708618,58.235151987151006,1739502672.877538,33.17996835708618,46.37215848422261,1739502672.8775396,33.17996835708618,8.527367874766465,1739502672.8775415,33.17996835708618,2.8409164075496145,1739502672.8775432,33.17996835708618,1.104758776343148,1739502672.8775446,33.17996835708618,0.6108,1739502672.8775463,33.17996835708618,1.033017065984956,1739502672.877548,33.17996835708618,0.0,1739502672.8775496,33.17996835708618,0.11184449362408722,1739502672.8775513,33.17996835708618,2.518990794282811,1739502672.8775532,33.17996835708618,0.9530909142634899 +1739502672.8972032,33.199968338012695,49.70722771610914,1739502672.8972068,33.199968338012695,7.4932384117797035,1739502672.8972106,33.199968338012695,58.235151987151006,1739502672.897214,33.199968338012695,46.37215848422261,1739502672.8972158,33.199968338012695,8.527367874766465,1739502672.8972178,33.199968338012695,2.8409164075496145,1739502672.8972197,33.199968338012695,1.104758776343148,1739502672.8972213,33.199968338012695,0.6108,1739502672.8972232,33.199968338012695,1.033017065984956,1739502672.8972251,33.199968338012695,0.0,1739502672.8972268,33.199968338012695,0.07992615172146611,1739502672.8972285,33.199968338012695,2.518990794282811,1739502672.8972304,33.199968338012695,0.9530909142634899 +1739502672.917608,33.21996831893921,49.70722771610914,1739502672.9176111,33.21996831893921,7.4932384117797035,1739502672.917615,33.21996831893921,58.235151987151006,1739502672.9176188,33.21996831893921,46.37215848422261,1739502672.9176202,33.21996831893921,8.527367874766465,1739502672.9176226,33.21996831893921,2.8409164075496145,1739502672.9176242,33.21996831893921,1.104758776343148,1739502672.917626,33.21996831893921,0.6108,1739502672.9176276,33.21996831893921,1.033017065984956,1739502672.9176297,33.21996831893921,0.0,1739502672.9176314,33.21996831893921,0.07992615172146611,1739502672.9176333,33.21996831893921,2.518990794282811,1739502672.917635,33.21996831893921,0.9530909142634899 +1739502672.9422762,33.23996829986572,49.70722771610914,1739502672.9422843,33.23996829986572,7.4932384117797035,1739502672.9422946,33.23996829986572,58.235151987151006,1739502672.9423048,33.23996829986572,46.37215848422261,1739502672.9423096,33.23996829986572,8.527367874766465,1739502672.9423158,33.23996829986572,2.8409164075496145,1739502672.9423208,33.23996829986572,1.104758776343148,1739502672.9423256,33.23996829986572,0.6108,1739502672.9423301,33.23996829986572,1.033017065984956,1739502672.9423358,33.23996829986572,0.0,1739502672.9423406,33.23996829986572,0.07992615172146611,1739502672.942346,33.23996829986572,2.518990794282811,1739502672.942351,33.23996829986572,0.9530909142634899 +1739502672.9628696,33.259968280792236,49.70722771610914,1739502672.9628782,33.259968280792236,7.4932384117797035,1739502672.9628887,33.259968280792236,58.235151987151006,1739502672.9628987,33.259968280792236,46.37215848422261,1739502672.9629035,33.259968280792236,8.527367874766465,1739502672.96291,33.259968280792236,2.8409164075496145,1739502672.9629147,33.259968280792236,1.104758776343148,1739502672.9629197,33.259968280792236,0.6108,1739502672.9629242,33.259968280792236,1.033017065984956,1739502672.9629307,33.259968280792236,0.0,1739502672.9629354,33.259968280792236,0.07992615172146611,1739502672.962941,33.259968280792236,2.518990794282811,1739502672.9629464,33.259968280792236,0.9530909142634899 +1739502672.9885037,33.27996826171875,49.70722771610914,1739502672.9885101,33.27996826171875,7.4932384117797035,1739502672.988518,33.27996826171875,58.235151987151006,1739502672.988525,33.27996826171875,46.37215848422261,1739502672.988528,33.27996826171875,8.527367874766465,1739502672.9885325,33.27996826171875,2.8409164075496145,1739502672.9885364,33.27996826171875,1.104758776343148,1739502672.98854,33.27996826171875,0.6108,1739502672.9885433,33.27996826171875,1.033017065984956,1739502672.9885473,33.27996826171875,0.0,1739502672.988551,33.27996826171875,0.07992615172146611,1739502672.9885547,33.27996826171875,2.518990794282811,1739502672.9885583,33.27996826171875,0.9530909142634899 +1739502673.010143,33.299968242645264,49.620891441693324,1739502673.01015,33.299968242645264,7.553584794028998,1739502673.0101576,33.299968242645264,58.466503115877835,1739502673.0101645,33.299968242645264,46.13026902774672,1739502673.0101683,33.299968242645264,8.464185690493544,1739502673.010173,33.299968242645264,2.886409258454766,1739502673.0101767,33.299968242645264,1.2024122356530884,1739502673.01018,33.299968242645264,0.6108,1739502673.010184,33.299968242645264,0.9553867404565152,1739502673.0101879,33.299968242645264,0.0,1739502673.010192,33.299968242645264,-0.0466572553886889,1739502673.0101957,33.299968242645264,2.546592483225358,1739502673.0102005,33.299968242645264,0.962486655187467 +1739502673.0443764,33.33996820449829,49.620891441693324,1739502673.0443852,33.33996820449829,7.553584794028998,1739502673.0443974,33.33996820449829,58.466503115877835,1739502673.0444112,33.33996820449829,46.13026902774672,1739502673.0444188,33.33996820449829,8.464185690493544,1739502673.0444286,33.33996820449829,2.886409258454766,1739502673.0444374,33.33996820449829,1.2024122356530884,1739502673.0444462,33.33996820449829,0.6108,1739502673.0444548,33.33996820449829,0.9553867404565152,1739502673.0444639,33.33996820449829,0.0,1739502673.044473,33.33996820449829,-0.0070999147309518396,1739502673.0444815,33.33996820449829,2.546592483225358,1739502673.0444906,33.33996820449829,0.962486655187467 +1739502673.060589,33.359968185424805,49.620891441693324,1739502673.0605955,33.359968185424805,7.553584794028998,1739502673.060603,33.359968185424805,58.466503115877835,1739502673.0606098,33.359968185424805,46.13026902774672,1739502673.0606132,33.359968185424805,8.464185690493544,1739502673.0606172,33.359968185424805,2.886409258454766,1739502673.0606205,33.359968185424805,1.2024122356530884,1739502673.060624,33.359968185424805,0.6108,1739502673.0606272,33.359968185424805,0.9553867404565152,1739502673.0606313,33.359968185424805,0.0,1739502673.0606349,33.359968185424805,-0.0070999147309518396,1739502673.0606384,33.359968185424805,2.546592483225358,1739502673.0606418,33.359968185424805,0.962486655187467 +1739502673.0819025,33.37996816635132,49.620891441693324,1739502673.081906,33.37996816635132,7.553584794028998,1739502673.0819106,33.37996816635132,58.466503115877835,1739502673.081915,33.37996816635132,46.13026902774672,1739502673.0819168,33.37996816635132,8.464185690493544,1739502673.08192,33.37996816635132,2.886409258454766,1739502673.081922,33.37996816635132,1.2024122356530884,1739502673.0819244,33.37996816635132,0.6108,1739502673.081926,33.37996816635132,0.9553867404565152,1739502673.081929,33.37996816635132,0.0,1739502673.081931,33.37996816635132,-0.0070999147309518396,1739502673.081933,33.37996816635132,2.546592483225358,1739502673.0819356,33.37996816635132,0.962486655187467 +1739502673.1020458,33.39996814727783,49.53244290289095,1739502673.1020494,33.39996814727783,7.611844561047773,1739502673.1020539,33.39996814727783,58.587434304384054,1739502673.1020582,33.39996814727783,46.016498198787,1739502673.1020603,33.39996814727783,8.424648310216758,1739502673.1020632,33.39996814727783,2.9144071743539848,1739502673.102065,33.39996814727783,1.2041703190894681,1739502673.1020672,33.39996814727783,0.6108,1739502673.1020691,33.39996814727783,0.9540439652791985,1739502673.1020715,33.39996814727783,0.0,1739502673.1020737,33.39996814727783,-0.008699475058054549,1739502673.1020758,33.39996814727783,2.5741941721679047,1739502673.1020782,33.39996814727783,0.9622435774072978 +1739502673.1225264,33.419968128204346,49.53244290289095,1739502673.1225295,33.419968128204346,7.611844561047773,1739502673.1225336,33.419968128204346,58.587434304384054,1739502673.1225386,33.419968128204346,46.016498198787,1739502673.1225414,33.419968128204346,8.424648310216758,1739502673.122545,33.419968128204346,2.9144071743539848,1739502673.1225479,33.419968128204346,1.2041703190894681,1739502673.122551,33.419968128204346,0.6108,1739502673.122554,33.419968128204346,0.9540439652791985,1739502673.1225574,33.419968128204346,0.0,1739502673.1225605,33.419968128204346,-0.008199612128099276,1739502673.1225636,33.419968128204346,2.5741941721679047,1739502673.122567,33.419968128204346,0.9622435774072978 +1739502673.1425483,33.43996810913086,49.53244290289095,1739502673.1425512,33.43996810913086,7.611844561047773,1739502673.1425557,33.43996810913086,58.587434304384054,1739502673.1425602,33.43996810913086,46.016498198787,1739502673.1425629,33.43996810913086,8.424648310216758,1739502673.1425664,33.43996810913086,2.9144071743539848,1739502673.1425695,33.43996810913086,1.2041703190894681,1739502673.1425726,33.43996810913086,0.6108,1739502673.1425753,33.43996810913086,0.9540439652791985,1739502673.1425788,33.43996810913086,0.0,1739502673.142582,33.43996810913086,-0.008199612128099276,1739502673.142585,33.43996810913086,2.5741941721679047,1739502673.1425881,33.43996810913086,0.9622435774072978 +1739502673.1637604,33.45996809005737,49.53244290289095,1739502673.163764,33.45996809005737,7.611844561047773,1739502673.1637685,33.45996809005737,58.587434304384054,1739502673.1637738,33.45996809005737,46.016498198787,1739502673.1637764,33.45996809005737,8.424648310216758,1739502673.1637802,33.45996809005737,2.9144071743539848,1739502673.1637833,33.45996809005737,1.2041703190894681,1739502673.1637866,33.45996809005737,0.6108,1739502673.16379,33.45996809005737,0.9540439652791985,1739502673.1637933,33.45996809005737,0.0,1739502673.1637967,33.45996809005737,-0.008199612128099276,1739502673.1638002,33.45996809005737,2.5741941721679047,1739502673.1638038,33.45996809005737,0.9622435774072978 +1739502673.181152,33.47996807098389,49.53244290289095,1739502673.181154,33.47996807098389,7.611844561047773,1739502673.1811569,33.47996807098389,58.587434304384054,1739502673.1811597,33.47996807098389,46.016498198787,1739502673.1811607,33.47996807098389,8.424648310216758,1739502673.1811626,33.47996807098389,2.9144071743539848,1739502673.1811638,33.47996807098389,1.2041703190894681,1739502673.181165,33.47996807098389,0.6108,1739502673.1811664,33.47996807098389,0.9540439652791985,1739502673.181168,33.47996807098389,0.0,1739502673.1811695,33.47996807098389,-0.008199612128099276,1739502673.181171,33.47996807098389,2.5741941721679047,1739502673.1811724,33.47996807098389,0.9622435774072978 +1739502673.2008822,33.4999680519104,49.53244290289095,1739502673.2008846,33.4999680519104,7.611844561047773,1739502673.2008874,33.4999680519104,58.587434304384054,1739502673.20089,33.4999680519104,46.016498198787,1739502673.2008915,33.4999680519104,8.424648310216758,1739502673.2008932,33.4999680519104,2.9144071743539848,1739502673.2008944,33.4999680519104,1.2041703190894681,1739502673.2008958,33.4999680519104,0.6108,1739502673.200897,33.4999680519104,0.9540439652791985,1739502673.2008986,33.4999680519104,0.0,1739502673.2008998,33.4999680519104,-0.008199612128099276,1739502673.2009013,33.4999680519104,2.5741941721679047,1739502673.2009027,33.4999680519104,0.9622435774072978 +1739502673.220819,33.519968032836914,49.44251743559071,1739502673.2208219,33.519968032836914,7.667580759088082,1739502673.2208247,33.519968032836914,58.67767337091755,1739502673.2208276,33.519968032836914,45.934362656498784,1739502673.220829,33.519968032836914,8.391958533370458,1739502673.2208307,33.519968032836914,2.937970338854154,1739502673.2208323,33.519968032836914,1.181676379604376,1739502673.2208338,33.519968032836914,0.6108,1739502673.220835,33.519968032836914,0.9713675336940375,1739502673.2208366,33.519968032836914,0.0,1739502673.220838,33.519968032836914,0.018320165062830504,1739502673.2208395,33.519968032836914,2.6017958611104515,1739502673.220841,33.519968032836914,0.9613348044370389 +1739502673.2406285,33.53996801376343,49.44251743559071,1739502673.2406309,33.53996801376343,7.667580759088082,1739502673.2406335,33.53996801376343,58.67767337091755,1739502673.2406368,33.53996801376343,45.934362656498784,1739502673.2406383,33.53996801376343,8.391958533370458,1739502673.24064,33.53996801376343,2.937970338854154,1739502673.2406416,33.53996801376343,1.181676379604376,1739502673.240643,33.53996801376343,0.6108,1739502673.240644,33.53996801376343,0.9713675336940375,1739502673.240646,33.53996801376343,0.0,1739502673.240647,33.53996801376343,0.010032729256998607,1739502673.2406485,33.53996801376343,2.6017958611104515,1739502673.24065,33.53996801376343,0.9613348044370389 +1739502673.2620258,33.55996799468994,49.44251743559071,1739502673.2620282,33.55996799468994,7.667580759088082,1739502673.262031,33.55996799468994,58.67767337091755,1739502673.2620342,33.55996799468994,45.934362656498784,1739502673.2620354,33.55996799468994,8.391958533370458,1739502673.262037,33.55996799468994,2.937970338854154,1739502673.2620385,33.55996799468994,1.181676379604376,1739502673.26204,33.55996799468994,0.6108,1739502673.262041,33.55996799468994,0.9713675336940375,1739502673.2620425,33.55996799468994,0.0,1739502673.262044,33.55996799468994,0.010032729256998607,1739502673.2620454,33.55996799468994,2.6017958611104515,1739502673.2620468,33.55996799468994,0.9613348044370389 +1739502673.281208,33.579967975616455,49.44251743559071,1739502673.2812104,33.579967975616455,7.667580759088082,1739502673.2812133,33.579967975616455,58.67767337091755,1739502673.2812157,33.579967975616455,45.934362656498784,1739502673.2812173,33.579967975616455,8.391958533370458,1739502673.281219,33.579967975616455,2.937970338854154,1739502673.2812204,33.579967975616455,1.181676379604376,1739502673.2812216,33.579967975616455,0.6108,1739502673.2812228,33.579967975616455,0.9713675336940375,1739502673.2812245,33.579967975616455,0.0,1739502673.281226,33.579967975616455,0.010032729256998607,1739502673.2812274,33.579967975616455,2.6017958611104515,1739502673.2812285,33.579967975616455,0.9613348044370389 +1739502673.3055263,33.59996795654297,49.44251743559071,1739502673.305536,33.59996795654297,7.667580759088082,1739502673.3055465,33.59996795654297,58.67767337091755,1739502673.3055563,33.59996795654297,45.934362656498784,1739502673.3055613,33.59996795654297,8.391958533370458,1739502673.3055677,33.59996795654297,2.937970338854154,1739502673.3055735,33.59996795654297,1.181676379604376,1739502673.3055785,33.59996795654297,0.6108,1739502673.305583,33.59996795654297,0.9713675336940375,1739502673.3055887,33.59996795654297,0.0,1739502673.305594,33.59996795654297,0.010032729256998607,1739502673.3055992,33.59996795654297,2.6017958611104515,1739502673.3056045,33.59996795654297,0.9613348044370389 +1739502673.3272,33.609967947006226,49.44251743559071,1739502673.3272073,33.609967947006226,7.667580759088082,1739502673.3272169,33.609967947006226,58.67767337091755,1739502673.3272247,33.609967947006226,45.934362656498784,1739502673.3272283,33.609967947006226,8.391958533370458,1739502673.3272328,33.609967947006226,2.937970338854154,1739502673.3272367,33.609967947006226,1.181676379604376,1739502673.32724,33.609967947006226,0.6108,1739502673.3272433,33.609967947006226,0.9713675336940375,1739502673.3272476,33.609967947006226,0.0,1739502673.3272512,33.609967947006226,0.010032729256998607,1739502673.327255,33.609967947006226,2.6017958611104515,1739502673.3272586,33.609967947006226,0.9613348044370389 +1739502673.3449242,33.639967918395996,49.3510903398005,1739502673.3449278,33.639967918395996,7.7208119802899695,1739502673.3449326,33.639967918395996,58.8471830290107,1739502673.3449373,33.639967918395996,45.776489178972774,1739502673.3449395,33.639967918395996,8.32452092416762,1739502673.344942,33.639967918395996,2.9742829972812634,1739502673.3449445,33.639967918395996,1.2256473760326947,1739502673.3449464,33.639967918395996,0.6108,1739502673.3449485,33.639967918395996,0.9377919381193998,1739502673.3449512,33.639967918395996,0.0,1739502673.344953,33.639967918395996,-0.0403814225586671,1739502673.3449554,33.639967918395996,2.6293975500529982,1739502673.344958,33.639967918395996,0.9624189279062603 +1739502673.3638005,33.65996789932251,49.3510903398005,1739502673.3638039,33.65996789932251,7.7208119802899695,1739502673.3638077,33.65996789932251,58.8471830290107,1739502673.3638113,33.65996789932251,45.776489178972774,1739502673.3638132,33.65996789932251,8.32452092416762,1739502673.3638153,33.65996789932251,2.9742829972812634,1739502673.3638172,33.65996789932251,1.2256473760326947,1739502673.3638191,33.65996789932251,0.6108,1739502673.3638206,33.65996789932251,0.9377919381193998,1739502673.3638227,33.65996789932251,0.0,1739502673.3638244,33.65996789932251,-0.02462698978686051,1739502673.3638263,33.65996789932251,2.6293975500529982,1739502673.363828,33.65996789932251,0.9624189279062603 +1739502673.3827584,33.67996788024902,49.3510903398005,1739502673.382761,33.67996788024902,7.7208119802899695,1739502673.3827639,33.67996788024902,58.8471830290107,1739502673.3827665,33.67996788024902,45.776489178972774,1739502673.382768,33.67996788024902,8.32452092416762,1739502673.3827696,33.67996788024902,2.9742829972812634,1739502673.3827713,33.67996788024902,1.2256473760326947,1739502673.3827724,33.67996788024902,0.6108,1739502673.382774,33.67996788024902,0.9377919381193998,1739502673.3827755,33.67996788024902,0.0,1739502673.3827767,33.67996788024902,-0.02462698978686051,1739502673.3827784,33.67996788024902,2.6293975500529982,1739502673.3827798,33.67996788024902,0.9624189279062603 +1739502673.4170053,33.68996787071228,49.3510903398005,1739502673.4170148,33.68996787071228,7.7208119802899695,1739502673.4170256,33.68996787071228,58.8471830290107,1739502673.417036,33.68996787071228,45.776489178972774,1739502673.4170418,33.68996787071228,8.32452092416762,1739502673.4170487,33.68996787071228,2.9742829972812634,1739502673.4170542,33.68996787071228,1.2256473760326947,1739502673.4170592,33.68996787071228,0.6108,1739502673.417064,33.68996787071228,0.9377919381193998,1739502673.41707,33.68996787071228,0.0,1739502673.4170747,33.68996787071228,-0.02462698978686051,1739502673.4170806,33.68996787071228,2.6293975500529982,1739502673.4170856,33.68996787071228,0.9624189279062603 +1739502673.4352207,33.71996784210205,49.3510903398005,1739502673.4352305,33.71996784210205,7.7208119802899695,1739502673.4352412,33.71996784210205,58.8471830290107,1739502673.4352512,33.71996784210205,45.776489178972774,1739502673.4352562,33.71996784210205,8.32452092416762,1739502673.4352627,33.71996784210205,2.9742829972812634,1739502673.4352682,33.71996784210205,1.2256473760326947,1739502673.4352732,33.71996784210205,0.6108,1739502673.435278,33.71996784210205,0.9377919381193998,1739502673.4352834,33.71996784210205,0.0,1739502673.435289,33.71996784210205,-0.02462698978686051,1739502673.4352942,33.71996784210205,2.6293975500529982,1739502673.4352994,33.71996784210205,0.9624189279062603 +1739502673.4498887,33.739967823028564,49.258251367101124,1739502673.4498968,33.739967823028564,7.771488575810691,1739502673.4499028,33.739967823028564,58.93767931563759,1739502673.4499073,33.739967823028564,45.69885896412622,1739502673.4499106,33.739967823028564,8.287880561954523,1739502673.4499185,33.739967823028564,2.997519163371843,1739502673.4499254,33.739967823028564,1.201201156548607,1739502673.449929,33.739967823028564,0.6108,1739502673.449932,33.739967823028564,0.9563128281447041,1739502673.4499357,33.739967823028564,0.0,1739502673.4499388,33.739967823028564,0.0056956373400582246,1739502673.449942,33.739967823028564,2.656999238995545,1739502673.4499454,33.739967823028564,0.9600930179946444 +1739502673.4685175,33.75996780395508,49.258251367101124,1739502673.4685225,33.75996780395508,7.771488575810691,1739502673.468528,33.75996780395508,58.93767931563759,1739502673.4685338,33.75996780395508,45.69885896412622,1739502673.4685361,33.75996780395508,8.287880561954523,1739502673.4685397,33.75996780395508,2.997519163371843,1739502673.4685426,33.75996780395508,1.201201156548607,1739502673.468545,33.75996780395508,0.6108,1739502673.4685476,33.75996780395508,0.9563128281447041,1739502673.468551,33.75996780395508,0.0,1739502673.4685535,33.75996780395508,-0.0037801898499403297,1739502673.468556,33.75996780395508,2.656999238995545,1739502673.468559,33.75996780395508,0.9600930179946444 +1739502673.4882658,33.77996778488159,49.258251367101124,1739502673.4882693,33.77996778488159,7.771488575810691,1739502673.4882734,33.77996778488159,58.93767931563759,1739502673.488277,33.77996778488159,45.69885896412622,1739502673.4882789,33.77996778488159,8.287880561954523,1739502673.488281,33.77996778488159,2.997519163371843,1739502673.488283,33.77996778488159,1.201201156548607,1739502673.4882846,33.77996778488159,0.6108,1739502673.4882865,33.77996778488159,0.9563128281447041,1739502673.4882884,33.77996778488159,0.0,1739502673.48829,33.77996778488159,-0.0037801898499403297,1739502673.4882925,33.77996778488159,2.656999238995545,1739502673.4882944,33.77996778488159,0.9600930179946444 +1739502673.5075545,33.799967765808105,49.258251367101124,1739502673.5075576,33.799967765808105,7.771488575810691,1739502673.5075614,33.799967765808105,58.93767931563759,1739502673.5075648,33.799967765808105,45.69885896412622,1739502673.5075665,33.799967765808105,8.287880561954523,1739502673.5075684,33.799967765808105,2.997519163371843,1739502673.5075703,33.799967765808105,1.201201156548607,1739502673.507572,33.799967765808105,0.6108,1739502673.5075736,33.799967765808105,0.9563128281447041,1739502673.5075755,33.799967765808105,0.0,1739502673.507577,33.799967765808105,-0.0037801898499403297,1739502673.5075786,33.799967765808105,2.656999238995545,1739502673.50758,33.799967765808105,0.9600930179946444 +1739502673.5275993,33.81996774673462,49.258251367101124,1739502673.5276017,33.81996774673462,7.771488575810691,1739502673.5276048,33.81996774673462,58.93767931563759,1739502673.527608,33.81996774673462,45.69885896412622,1739502673.5276093,33.81996774673462,8.287880561954523,1739502673.5276115,33.81996774673462,2.997519163371843,1739502673.527613,33.81996774673462,1.201201156548607,1739502673.5276144,33.81996774673462,0.6108,1739502673.527616,33.81996774673462,0.9563128281447041,1739502673.5276175,33.81996774673462,0.0,1739502673.5276191,33.81996774673462,-0.0037801898499403297,1739502673.5276208,33.81996774673462,2.656999238995545,1739502673.5276225,33.81996774673462,0.9600930179946444 +1739502673.548177,33.83996772766113,49.16421627874305,1739502673.5481799,33.83996772766113,7.8194977166542134,1739502673.548183,33.83996772766113,59.028459879047354,1739502673.548186,33.83996772766113,45.61822517627131,1739502673.5481877,33.83996772766113,8.248089833985288,1739502673.5481896,33.83996772766113,3.021309453551576,1739502673.5481913,33.83996772766113,1.1800587641498521,1739502673.5481932,33.83996772766113,0.6108,1739502673.5481946,33.83996772766113,0.9726253867151118,1739502673.5481963,33.83996772766113,0.0,1739502673.548198,33.83996772766113,0.020574682704034414,1739502673.5481994,33.83996772766113,2.684600927938092,1739502673.5482013,33.83996772766113,0.9596616066742911 +1739502673.568067,33.85996770858765,49.16421627874305,1739502673.56807,33.85996770858765,7.8194977166542134,1739502673.5680733,33.85996770858765,59.028459879047354,1739502673.5680764,33.85996770858765,45.61822517627131,1739502673.5680778,33.85996770858765,8.248089833985288,1739502673.56808,33.85996770858765,3.021309453551576,1739502673.5680814,33.85996770858765,1.1800587641498521,1739502673.5680833,33.85996770858765,0.6108,1739502673.5680845,33.85996770858765,0.9726253867151118,1739502673.5680864,33.85996770858765,0.0,1739502673.5680878,33.85996770858765,0.01296378004082066,1739502673.5680892,33.85996770858765,2.684600927938092,1739502673.568091,33.85996770858765,0.9596616066742911 +1739502673.5878174,33.87996768951416,49.16421627874305,1739502673.5878205,33.87996768951416,7.8194977166542134,1739502673.587824,33.87996768951416,59.028459879047354,1739502673.5878274,33.87996768951416,45.61822517627131,1739502673.5878294,33.87996768951416,8.248089833985288,1739502673.5878315,33.87996768951416,3.021309453551576,1739502673.5878332,33.87996768951416,1.1800587641498521,1739502673.5878348,33.87996768951416,0.6108,1739502673.5878367,33.87996768951416,0.9726253867151118,1739502673.5878384,33.87996768951416,0.0,1739502673.58784,33.87996768951416,0.01296378004082066,1739502673.5878417,33.87996768951416,2.684600927938092,1739502673.5878437,33.87996768951416,0.9596616066742911 +1739502673.6075637,33.899967670440674,49.16421627874305,1739502673.6075673,33.899967670440674,7.8194977166542134,1739502673.607571,33.899967670440674,59.028459879047354,1739502673.6075742,33.899967670440674,45.61822517627131,1739502673.6075761,33.899967670440674,8.248089833985288,1739502673.607578,33.899967670440674,3.021309453551576,1739502673.6075797,33.899967670440674,1.1800587641498521,1739502673.6075811,33.899967670440674,0.6108,1739502673.6075828,33.899967670440674,0.9726253867151118,1739502673.6075845,33.899967670440674,0.0,1739502673.6075864,33.899967670440674,0.01296378004082066,1739502673.607588,33.899967670440674,2.684600927938092,1739502673.6075897,33.899967670440674,0.9596616066742911 +1739502673.6277254,33.91996765136719,49.16421627874305,1739502673.6277282,33.91996765136719,7.8194977166542134,1739502673.6277318,33.91996765136719,59.028459879047354,1739502673.627735,33.91996765136719,45.61822517627131,1739502673.6277366,33.91996765136719,8.248089833985288,1739502673.6277385,33.91996765136719,3.021309453551576,1739502673.6277401,33.91996765136719,1.1800587641498521,1739502673.6277418,33.91996765136719,0.6108,1739502673.6277432,33.91996765136719,0.9726253867151118,1739502673.627745,33.91996765136719,0.0,1739502673.6277466,33.91996765136719,0.01296378004082066,1739502673.6277483,33.91996765136719,2.684600927938092,1739502673.62775,33.91996765136719,0.9596616066742911 +1739502673.647812,33.9399676322937,49.16421627874305,1739502673.6478152,33.9399676322937,7.8194977166542134,1739502673.6478188,33.9399676322937,59.028459879047354,1739502673.6478221,33.9399676322937,45.61822517627131,1739502673.6478236,33.9399676322937,8.248089833985288,1739502673.6478255,33.9399676322937,3.021309453551576,1739502673.6478271,33.9399676322937,1.1800587641498521,1739502673.6478288,33.9399676322937,0.6108,1739502673.6478302,33.9399676322937,0.9726253867151118,1739502673.6478322,33.9399676322937,0.0,1739502673.6478336,33.9399676322937,0.01296378004082066,1739502673.6478355,33.9399676322937,2.684600927938092,1739502673.647837,33.9399676322937,0.9596616066742911 +1739502673.6677623,33.959967613220215,49.06883458893053,1739502673.6677656,33.959967613220215,7.864920221186871,1739502673.6677685,33.959967613220215,59.11209727173639,1739502673.6677718,33.959967613220215,45.54101588932011,1739502673.6677735,33.959967613220215,8.208469098185846,1739502673.6677754,33.959967613220215,3.0445159501037513,1739502673.667777,33.959967613220215,1.1563269292715181,1739502673.6677785,33.959967613220215,0.6108,1739502673.6677802,33.959967613220215,0.9912675398184108,1739502673.6677818,33.959967613220215,0.0,1739502673.6677835,33.959967613220215,0.03779264717229028,1739502673.6677852,33.959967613220215,2.7122026168806386,1739502673.6677868,33.959967613220215,0.9612339187119187 +1739502673.6878107,33.97996759414673,49.06883458893053,1739502673.687814,33.97996759414673,7.864920221186871,1739502673.6878176,33.97996759414673,59.11209727173639,1739502673.6878211,33.97996759414673,45.54101588932011,1739502673.6878228,33.97996759414673,8.208469098185846,1739502673.6878252,33.97996759414673,3.0445159501037513,1739502673.687827,33.97996759414673,1.1563269292715181,1739502673.687829,33.97996759414673,0.6108,1739502673.6878307,33.97996759414673,0.9912675398184108,1739502673.6878326,33.97996759414673,0.0,1739502673.6878343,33.97996759414673,0.030033621106492103,1739502673.6878362,33.97996759414673,2.7122026168806386,1739502673.6878378,33.97996759414673,0.9612339187119187 +1739502673.7082384,33.99996757507324,49.06883458893053,1739502673.7082422,33.99996757507324,7.864920221186871,1739502673.7082462,33.99996757507324,59.11209727173639,1739502673.70825,33.99996757507324,45.54101588932011,1739502673.7082522,33.99996757507324,8.208469098185846,1739502673.7082548,33.99996757507324,3.0445159501037513,1739502673.7082567,33.99996757507324,1.1563269292715181,1739502673.7082589,33.99996757507324,0.6108,1739502673.7082605,33.99996757507324,0.9912675398184108,1739502673.708263,33.99996757507324,0.0,1739502673.708265,33.99996757507324,0.030033621106492103,1739502673.708267,33.99996757507324,2.7122026168806386,1739502673.7082691,33.99996757507324,0.9612339187119187 +1739502673.729521,34.019967555999756,49.06883458893053,1739502673.7295275,34.019967555999756,7.864920221186871,1739502673.7295349,34.019967555999756,59.11209727173639,1739502673.7295432,34.019967555999756,45.54101588932011,1739502673.729547,34.019967555999756,8.208469098185846,1739502673.7295518,34.019967555999756,3.0445159501037513,1739502673.7295566,34.019967555999756,1.1563269292715181,1739502673.7295609,34.019967555999756,0.6108,1739502673.7295647,34.019967555999756,0.9912675398184108,1739502673.7295694,34.019967555999756,0.0,1739502673.7295737,34.019967555999756,0.030033621106492103,1739502673.7295783,34.019967555999756,2.7122026168806386,1739502673.7295825,34.019967555999756,0.9612339187119187 +1739502673.7490566,34.03996753692627,49.06883458893053,1739502673.7490609,34.03996753692627,7.864920221186871,1739502673.7490656,34.03996753692627,59.11209727173639,1739502673.7490704,34.03996753692627,45.54101588932011,1739502673.7490726,34.03996753692627,8.208469098185846,1739502673.7490754,34.03996753692627,3.0445159501037513,1739502673.7490776,34.03996753692627,1.1563269292715181,1739502673.7490797,34.03996753692627,0.6108,1739502673.749082,34.03996753692627,0.9912675398184108,1739502673.749085,34.03996753692627,0.0,1739502673.7490869,34.03996753692627,0.030033621106492103,1739502673.7490895,34.03996753692627,2.7122026168806386,1739502673.7490919,34.03996753692627,0.9612339187119187 +1739502673.769018,34.05996751785278,48.972008473061955,1739502673.769022,34.05996751785278,7.907793149671118,1739502673.7690268,34.05996751785278,59.113946600089676,1739502673.7690315,34.05996751785278,45.533621972400155,1739502673.7690337,34.05996751785278,8.204480274584293,1739502673.7690365,34.05996751785278,3.055519119185671,1739502673.7690392,34.05996751785278,1.0715723757627358,1739502673.7690418,34.05996751785278,0.6108,1739502673.7690437,34.05996751785278,1.0608100679038035,1739502673.7690465,34.05996751785278,0.0,1739502673.769049,34.05996751785278,0.1264213961691917,1739502673.769051,34.05996751785278,2.7398043058231853,1739502673.7690537,34.05996751785278,0.9645098711907027 +1739502673.7888253,34.0799674987793,48.972008473061955,1739502673.7888293,34.0799674987793,7.907793149671118,1739502673.7888343,34.0799674987793,59.113946600089676,1739502673.7888389,34.0799674987793,45.533621972400155,1739502673.7888415,34.0799674987793,8.204480274584293,1739502673.788844,34.0799674987793,3.055519119185671,1739502673.7888463,34.0799674987793,1.0715723757627358,1739502673.7888486,34.0799674987793,0.6108,1739502673.788851,34.0799674987793,1.0608100679038035,1739502673.7888534,34.0799674987793,0.0,1739502673.7888556,34.0799674987793,0.09630019671310075,1739502673.788858,34.0799674987793,2.7398043058231853,1739502673.7888603,34.0799674987793,0.9645098711907027 +1739502673.808032,34.09996747970581,48.972008473061955,1739502673.8080356,34.09996747970581,7.907793149671118,1739502673.8080397,34.09996747970581,59.113946600089676,1739502673.8080435,34.09996747970581,45.533621972400155,1739502673.8080454,34.09996747970581,8.204480274584293,1739502673.8080478,34.09996747970581,3.055519119185671,1739502673.8080497,34.09996747970581,1.0715723757627358,1739502673.8080513,34.09996747970581,0.6108,1739502673.8080533,34.09996747970581,1.0608100679038035,1739502673.8080556,34.09996747970581,0.0,1739502673.8080573,34.09996747970581,0.09630019671310075,1739502673.8080595,34.09996747970581,2.7398043058231853,1739502673.8080614,34.09996747970581,0.9645098711907027 +1739502673.8278112,34.119967460632324,48.972008473061955,1739502673.8278143,34.119967460632324,7.907793149671118,1739502673.827818,34.119967460632324,59.113946600089676,1739502673.8278213,34.119967460632324,45.533621972400155,1739502673.8278232,34.119967460632324,8.204480274584293,1739502673.8278253,34.119967460632324,3.055519119185671,1739502673.827827,34.119967460632324,1.0715723757627358,1739502673.8278286,34.119967460632324,0.6108,1739502673.8278303,34.119967460632324,1.0608100679038035,1739502673.8278322,34.119967460632324,0.0,1739502673.8278341,34.119967460632324,0.09630019671310075,1739502673.8278358,34.119967460632324,2.7398043058231853,1739502673.8278375,34.119967460632324,0.9645098711907027 +1739502673.8474288,34.13996744155884,48.972008473061955,1739502673.8474321,34.13996744155884,7.907793149671118,1739502673.8474355,34.13996744155884,59.113946600089676,1739502673.8474383,34.13996744155884,45.533621972400155,1739502673.8474398,34.13996744155884,8.204480274584293,1739502673.8474417,34.13996744155884,3.055519119185671,1739502673.847443,34.13996744155884,1.0715723757627358,1739502673.8474445,34.13996744155884,0.6108,1739502673.847446,34.13996744155884,1.0608100679038035,1739502673.8474479,34.13996744155884,0.0,1739502673.847449,34.13996744155884,0.09630019671310075,1739502673.8474507,34.13996744155884,2.7398043058231853,1739502673.8474522,34.13996744155884,0.9645098711907027 +1739502673.8674314,34.15996742248535,48.972008473061955,1739502673.8674345,34.15996742248535,7.907793149671118,1739502673.8674376,34.15996742248535,59.113946600089676,1739502673.8674405,34.15996742248535,45.533621972400155,1739502673.867442,34.15996742248535,8.204480274584293,1739502673.8674438,34.15996742248535,3.055519119185671,1739502673.8674452,34.15996742248535,1.0715723757627358,1739502673.8674464,34.15996742248535,0.6108,1739502673.8674479,34.15996742248535,1.0608100679038035,1739502673.8674495,34.15996742248535,0.0,1739502673.867451,34.15996742248535,0.09630019671310075,1739502673.8674524,34.15996742248535,2.7398043058231853,1739502673.867454,34.15996742248535,0.9645098711907027 +1739502673.8877072,34.179967403411865,48.873308955288536,1739502673.8877096,34.179967403411865,7.948273680785173,1739502673.887713,34.179967403411865,59.376620922421154,1739502673.8877158,34.179967403411865,45.28670483427115,1739502673.8877175,34.179967403411865,8.062288622117984,1739502673.8877192,34.179967403411865,3.1098142484672584,1739502673.8877206,34.179967403411865,1.2048340113095657,1739502673.8877223,34.179967403411865,0.6108,1739502673.8877237,34.179967403411865,0.953537546487671,1739502673.8877254,34.179967403411865,0.0,1739502673.8877268,34.179967403411865,-0.07595781492392806,1739502673.8877285,34.179967403411865,2.767405994765732,1739502673.8877304,34.179967403411865,0.9756646974808939 +1739502673.9074302,34.19996738433838,48.873308955288536,1739502673.907433,34.19996738433838,7.948273680785173,1739502673.9074361,34.19996738433838,59.376620922421154,1739502673.9074388,34.19996738433838,45.28670483427115,1739502673.9074402,34.19996738433838,8.062288622117984,1739502673.907442,34.19996738433838,3.1098142484672584,1739502673.9074435,34.19996738433838,1.2048340113095657,1739502673.907445,34.19996738433838,0.6108,1739502673.9074469,34.19996738433838,0.953537546487671,1739502673.9074485,34.19996738433838,0.0,1739502673.90745,34.19996738433838,-0.022127150993222933,1739502673.9074516,34.19996738433838,2.767405994765732,1739502673.9074533,34.19996738433838,0.9756646974808939 +1739502673.9274716,34.21996736526489,48.873308955288536,1739502673.9274743,34.21996736526489,7.948273680785173,1739502673.9274778,34.21996736526489,59.376620922421154,1739502673.927481,34.21996736526489,45.28670483427115,1739502673.9274824,34.21996736526489,8.062288622117984,1739502673.9274843,34.21996736526489,3.1098142484672584,1739502673.9274857,34.21996736526489,1.2048340113095657,1739502673.9274871,34.21996736526489,0.6108,1739502673.9274886,34.21996736526489,0.953537546487671,1739502673.9274902,34.21996736526489,0.0,1739502673.9274917,34.21996736526489,-0.022127150993222933,1739502673.927493,34.21996736526489,2.767405994765732,1739502673.9274948,34.21996736526489,0.9756646974808939 +1739502673.947413,34.239967346191406,48.873308955288536,1739502673.9474158,34.239967346191406,7.948273680785173,1739502673.947419,34.239967346191406,59.376620922421154,1739502673.947422,34.239967346191406,45.28670483427115,1739502673.9474232,34.239967346191406,8.062288622117984,1739502673.9474251,34.239967346191406,3.1098142484672584,1739502673.9474266,34.239967346191406,1.2048340113095657,1739502673.9474277,34.239967346191406,0.6108,1739502673.9474294,34.239967346191406,0.953537546487671,1739502673.9474308,34.239967346191406,0.0,1739502673.9474325,34.239967346191406,-0.022127150993222933,1739502673.9474342,34.239967346191406,2.767405994765732,1739502673.9474356,34.239967346191406,0.9756646974808939 +1739502673.9674525,34.25996732711792,48.873308955288536,1739502673.967455,34.25996732711792,7.948273680785173,1739502673.967458,34.25996732711792,59.376620922421154,1739502673.9674609,34.25996732711792,45.28670483427115,1739502673.9674625,34.25996732711792,8.062288622117984,1739502673.9674647,34.25996732711792,3.1098142484672584,1739502673.9674664,34.25996732711792,1.2048340113095657,1739502673.9674675,34.25996732711792,0.6108,1739502673.967469,34.25996732711792,0.953537546487671,1739502673.967471,34.25996732711792,0.0,1739502673.967472,34.25996732711792,-0.022127150993222933,1739502673.9674735,34.25996732711792,2.767405994765732,1739502673.967475,34.25996732711792,0.9756646974808939 +1739502673.9877105,34.279967308044434,48.77302042804887,1739502673.9877133,34.279967308044434,7.986211307105339,1739502673.9877164,34.279967308044434,59.54467062647438,1739502673.9877195,34.279967308044434,45.14922949016388,1739502673.9877207,34.279967308044434,7.974048582611208,1739502673.9877224,34.279967308044434,-3.138236312390359,1739502673.9877243,34.279967308044434,1.2423971805682101,1739502673.9877255,34.279967308044434,0.6108,1739502673.987727,34.279967308044434,0.9253094909865531,1739502673.9877286,34.279967308044434,0.0,1739502673.98773,34.279967308044434,-0.059800790711290165,1739502673.9877317,34.279967308044434,2.795007683708279,1739502673.9877336,34.279967308044434,0.9733372615669538 +1739502674.007467,34.29996728897095,48.77302042804887,1739502674.0074697,34.29996728897095,7.986211307105339,1739502674.0074732,34.29996728897095,59.54467062647438,1739502674.0074759,34.29996728897095,45.14922949016388,1739502674.0074775,34.29996728897095,7.974048582611208,1739502674.0074792,34.29996728897095,-3.138236312390359,1739502674.0074809,34.29996728897095,1.2423971805682101,1739502674.007482,34.29996728897095,0.6108,1739502674.0074835,34.29996728897095,0.9253094909865531,1739502674.0074852,34.29996728897095,0.0,1739502674.0074866,34.29996728897095,-0.04802777058040064,1739502674.007488,34.29996728897095,2.795007683708279,1739502674.0074894,34.29996728897095,0.9733372615669538 +1739502674.0274432,34.31996726989746,48.77302042804887,1739502674.0274458,34.31996726989746,7.986211307105339,1739502674.0274491,34.31996726989746,59.54467062647438,1739502674.0274522,34.31996726989746,45.14922949016388,1739502674.0274537,34.31996726989746,7.974048582611208,1739502674.0274553,34.31996726989746,-3.138236312390359,1739502674.0274568,34.31996726989746,1.2423971805682101,1739502674.0274582,34.31996726989746,0.6108,1739502674.0274596,34.31996726989746,0.9253094909865531,1739502674.0274615,34.31996726989746,0.0,1739502674.0274632,34.31996726989746,-0.04802777058040064,1739502674.0274646,34.31996726989746,2.795007683708279,1739502674.0274663,34.31996726989746,0.9733372615669538 +1739502674.0475159,34.339967250823975,48.77302042804887,1739502674.0475187,34.339967250823975,7.986211307105339,1739502674.0475225,34.339967250823975,59.54467062647438,1739502674.047526,34.339967250823975,45.14922949016388,1739502674.0475273,34.339967250823975,7.974048582611208,1739502674.0475295,34.339967250823975,-3.138236312390359,1739502674.047531,34.339967250823975,1.2423971805682101,1739502674.0475323,34.339967250823975,0.6108,1739502674.0475338,34.339967250823975,0.9253094909865531,1739502674.0475357,34.339967250823975,0.0,1739502674.0475368,34.339967250823975,-0.04802777058040064,1739502674.0475385,34.339967250823975,2.795007683708279,1739502674.0475402,34.339967250823975,0.9733372615669538 +1739502674.067664,34.35996723175049,48.77302042804887,1739502674.0676668,34.35996723175049,7.986211307105339,1739502674.0676703,34.35996723175049,59.54467062647438,1739502674.0676732,34.35996723175049,45.14922949016388,1739502674.0676746,34.35996723175049,7.974048582611208,1739502674.0676763,34.35996723175049,-3.138236312390359,1739502674.0676777,34.35996723175049,1.2423971805682101,1739502674.0676792,34.35996723175049,0.6108,1739502674.0676806,34.35996723175049,0.9253094909865531,1739502674.0676823,34.35996723175049,0.0,1739502674.0676837,34.35996723175049,-0.04802777058040064,1739502674.0676851,34.35996723175049,2.795007683708279,1739502674.0676868,34.35996723175049,0.9733372615669538 +1739502674.087407,34.379967212677,48.77302042804887,1739502674.0874097,34.379967212677,7.986211307105339,1739502674.0874128,34.379967212677,59.54467062647438,1739502674.0874157,34.379967212677,45.14922949016388,1739502674.0874174,34.379967212677,7.974048582611208,1739502674.087419,34.379967212677,-3.138236312390359,1739502674.0874207,34.379967212677,1.2423971805682101,1739502674.0874221,34.379967212677,0.6108,1739502674.0874238,34.379967212677,0.9253094909865531,1739502674.0874252,34.379967212677,0.0,1739502674.087427,34.379967212677,-0.04802777058040064,1739502674.0874283,34.379967212677,2.795007683708279,1739502674.08743,34.379967212677,0.9733372615669538 +1739502674.1077273,34.399967193603516,48.67214509170796,1739502674.1077302,34.399967193603516,8.02122090225478,1739502674.1077335,34.399967193603516,59.63138109725967,1739502674.1077363,34.399967193603516,45.0868051068259,1739502674.1077378,34.399967193603516,7.93120942368796,1739502674.1077397,34.399967193603516,-3.116492502637753,1739502674.107741,34.399967193603516,1.2098380804601072,1739502674.1077425,34.399967193603516,0.6108,1739502674.1077437,34.399967193603516,0.9497279227674427,1739502674.1077456,34.399967193603516,0.0,1739502674.1077468,34.399967193603516,-0.004511981446326571,1739502674.1077483,34.399967193603516,2.8226093726508257,1739502674.10775,34.399967193603516,0.9678385972341653 +1739502674.1274152,34.41996717453003,48.67214509170796,1739502674.127418,34.41996717453003,8.02122090225478,1739502674.1274211,34.41996717453003,59.63138109725967,1739502674.1274242,34.41996717453003,45.0868051068259,1739502674.127426,34.41996717453003,7.93120942368796,1739502674.1274276,34.41996717453003,-3.116492502637753,1739502674.127429,34.41996717453003,1.2098380804601072,1739502674.1274307,34.41996717453003,0.6108,1739502674.1274319,34.41996717453003,0.9497279227674427,1739502674.1274338,34.41996717453003,0.0,1739502674.127435,34.41996717453003,-0.018110674466722654,1739502674.1274369,34.41996717453003,2.8226093726508257,1739502674.1274383,34.41996717453003,0.9678385972341653 +1739502674.1476388,34.43996715545654,48.67214509170796,1739502674.1476417,34.43996715545654,8.02122090225478,1739502674.147645,34.43996715545654,59.63138109725967,1739502674.147648,34.43996715545654,45.0868051068259,1739502674.1476495,34.43996715545654,7.93120942368796,1739502674.1476514,34.43996715545654,-3.116492502637753,1739502674.1476529,34.43996715545654,1.2098380804601072,1739502674.147654,34.43996715545654,0.6108,1739502674.1476557,34.43996715545654,0.9497279227674427,1739502674.1476572,34.43996715545654,0.0,1739502674.1476588,34.43996715545654,-0.018110674466722654,1739502674.1476603,34.43996715545654,2.8226093726508257,1739502674.1476622,34.43996715545654,0.9678385972341653 +1739502674.1674552,34.45996713638306,48.67214509170796,1739502674.167458,34.45996713638306,8.02122090225478,1739502674.1674614,34.45996713638306,59.63138109725967,1739502674.1674645,34.45996713638306,45.0868051068259,1739502674.167466,34.45996713638306,7.93120942368796,1739502674.1674678,34.45996713638306,-3.116492502637753,1739502674.1674693,34.45996713638306,1.2098380804601072,1739502674.1674707,34.45996713638306,0.6108,1739502674.167472,34.45996713638306,0.9497279227674427,1739502674.167474,34.45996713638306,0.0,1739502674.1674752,34.45996713638306,-0.018110674466722654,1739502674.1674767,34.45996713638306,2.8226093726508257,1739502674.1674783,34.45996713638306,0.9678385972341653 +1739502674.1874762,34.47996711730957,48.67214509170796,1739502674.1874788,34.47996711730957,8.02122090225478,1739502674.187482,34.47996711730957,59.63138109725967,1739502674.187485,34.47996711730957,45.0868051068259,1739502674.1874866,34.47996711730957,7.93120942368796,1739502674.1874886,34.47996711730957,-3.116492502637753,1739502674.18749,34.47996711730957,1.2098380804601072,1739502674.1874917,34.47996711730957,0.6108,1739502674.187493,34.47996711730957,0.9497279227674427,1739502674.187495,34.47996711730957,0.0,1739502674.1874964,34.47996711730957,-0.018110674466722654,1739502674.187498,34.47996711730957,2.8226093726508257,1739502674.1874995,34.47996711730957,0.9678385972341653 +1739502674.2074895,34.499967098236084,48.57074664210171,1739502674.2074924,34.499967098236084,8.05330420610513,1739502674.2074957,34.499967098236084,59.79509464196052,1739502674.2074986,34.499967098236084,44.95800420270389,1739502674.2075,34.499967098236084,7.836821429362095,1739502674.2075021,34.499967098236084,-3.081742212338896,1739502674.2075036,34.499967098236084,1.2452112402950306,1739502674.207505,34.499967098236084,0.6108,1739502674.2075064,34.499967098236084,0.9232287330774159,1739502674.2075083,34.499967098236084,0.0,1739502674.2075098,34.499967098236084,-0.053733915447561766,1739502674.2075112,34.499967098236084,2.8502110615933725,1739502674.2075129,34.499967098236084,0.9658303784195804 +1739502674.2278042,34.5199670791626,48.57074664210171,1739502674.227807,34.5199670791626,8.05330420610513,1739502674.2278101,34.5199670791626,59.79509464196052,1739502674.227813,34.5199670791626,44.95800420270389,1739502674.2278144,34.5199670791626,7.836821429362095,1739502674.227816,34.5199670791626,-3.081742212338896,1739502674.2278178,34.5199670791626,1.2452112402950306,1739502674.2278194,34.5199670791626,0.6108,1739502674.2278209,34.5199670791626,0.9232287330774159,1739502674.2278225,34.5199670791626,0.0,1739502674.2278242,34.5199670791626,-0.042601645342164485,1739502674.2278256,34.5199670791626,2.8502110615933725,1739502674.2278273,34.5199670791626,0.9658303784195804 +1739502674.2474713,34.53996706008911,48.57074664210171,1739502674.247474,34.53996706008911,8.05330420610513,1739502674.247477,34.53996706008911,59.79509464196052,1739502674.2474802,34.53996706008911,44.95800420270389,1739502674.2474813,34.53996706008911,7.836821429362095,1739502674.2474835,34.53996706008911,-3.081742212338896,1739502674.2474847,34.53996706008911,1.2452112402950306,1739502674.247486,34.53996706008911,0.6108,1739502674.2474878,34.53996706008911,0.9232287330774159,1739502674.2474892,34.53996706008911,0.0,1739502674.247491,34.53996706008911,-0.042601645342164485,1739502674.2474923,34.53996706008911,2.8502110615933725,1739502674.2474937,34.53996706008911,0.9658303784195804 +1739502674.2674317,34.559967041015625,48.57074664210171,1739502674.2674344,34.559967041015625,8.05330420610513,1739502674.2674375,34.559967041015625,59.79509464196052,1739502674.2674403,34.559967041015625,44.95800420270389,1739502674.267442,34.559967041015625,7.836821429362095,1739502674.2674437,34.559967041015625,-3.081742212338896,1739502674.2674453,34.559967041015625,1.2452112402950306,1739502674.2674468,34.559967041015625,0.6108,1739502674.267448,34.559967041015625,0.9232287330774159,1739502674.2674496,34.559967041015625,0.0,1739502674.267451,34.559967041015625,-0.042601645342164485,1739502674.2674527,34.559967041015625,2.8502110615933725,1739502674.2674541,34.559967041015625,0.9658303784195804 +1739502674.287479,34.57996702194214,48.57074664210171,1739502674.2874818,34.57996702194214,8.05330420610513,1739502674.2874851,34.57996702194214,59.79509464196052,1739502674.287488,34.57996702194214,44.95800420270389,1739502674.2874897,34.57996702194214,7.836821429362095,1739502674.2874913,34.57996702194214,-3.081742212338896,1739502674.2874925,34.57996702194214,1.2452112402950306,1739502674.2874942,34.57996702194214,0.6108,1739502674.2874956,34.57996702194214,0.9232287330774159,1739502674.2874973,34.57996702194214,0.0,1739502674.2874987,34.57996702194214,-0.042601645342164485,1739502674.2875004,34.57996702194214,2.8502110615933725,1739502674.2875018,34.57996702194214,0.9658303784195804 +1739502674.3075156,34.59996700286865,48.57074664210171,1739502674.3075185,34.59996700286865,8.05330420610513,1739502674.307522,34.59996700286865,59.79509464196052,1739502674.3075252,34.59996700286865,44.95800420270389,1739502674.3075264,34.59996700286865,7.836821429362095,1739502674.3075283,34.59996700286865,-3.081742212338896,1739502674.3075297,34.59996700286865,1.2452112402950306,1739502674.3075314,34.59996700286865,0.6108,1739502674.3075325,34.59996700286865,0.9232287330774159,1739502674.307534,34.59996700286865,0.0,1739502674.3075356,34.59996700286865,-0.042601645342164485,1739502674.307537,34.59996700286865,2.8502110615933725,1739502674.3075387,34.59996700286865,0.9658303784195804 +1739502674.3279204,34.619966983795166,48.468857305370676,1739502674.3279233,34.619966983795166,8.082475752761193,1739502674.327927,34.619966983795166,59.88063087380595,1739502674.3279302,34.619966983795166,44.89808679674463,1739502674.3279316,34.619966983795166,7.790469437395704,1739502674.3279338,34.619966983795166,-3.0599973821769377,1739502674.3279352,34.619966983795166,1.212918797791644,1739502674.3279366,34.619966983795166,0.6108,1739502674.3279383,34.619966983795166,0.9473901301645239,1739502674.3279405,34.619966983795166,0.0,1739502674.327942,34.619966983795166,-0.00034336089574516643,1739502674.3279436,34.619966983795166,2.8778127505359192,1739502674.3279452,34.619966983795166,0.9609392136081215 +1739502674.3476558,34.63996696472168,48.468857305370676,1739502674.3476586,34.63996696472168,8.082475752761193,1739502674.347662,34.63996696472168,59.88063087380595,1739502674.347665,34.63996696472168,44.89808679674463,1739502674.347667,34.63996696472168,7.790469437395704,1739502674.347669,34.63996696472168,-3.0599973821769377,1739502674.3476706,34.63996696472168,1.212918797791644,1739502674.347672,34.63996696472168,0.6108,1739502674.3476737,34.63996696472168,0.9473901301645239,1739502674.3476756,34.63996696472168,0.0,1739502674.3476772,34.63996696472168,-0.01354908344359762,1739502674.347679,34.63996696472168,2.8778127505359192,1739502674.3476806,34.63996696472168,0.9609392136081215 +1739502674.3676543,34.65996694564819,48.468857305370676,1739502674.3676574,34.65996694564819,8.082475752761193,1739502674.3676608,34.65996694564819,59.88063087380595,1739502674.3676639,34.65996694564819,44.89808679674463,1739502674.3676653,34.65996694564819,7.790469437395704,1739502674.3676674,34.65996694564819,-3.0599973821769377,1739502674.3676693,34.65996694564819,1.212918797791644,1739502674.367671,34.65996694564819,0.6108,1739502674.3676727,34.65996694564819,0.9473901301645239,1739502674.3676744,34.65996694564819,0.0,1739502674.367676,34.65996694564819,-0.01354908344359762,1739502674.3676777,34.65996694564819,2.8778127505359192,1739502674.3676796,34.65996694564819,0.9609392136081215 +1739502674.387977,34.67996692657471,48.468857305370676,1739502674.38798,34.67996692657471,8.082475752761193,1739502674.3879833,34.67996692657471,59.88063087380595,1739502674.3879867,34.67996692657471,44.89808679674463,1739502674.3879883,34.67996692657471,7.790469437395704,1739502674.38799,34.67996692657471,-3.0599973821769377,1739502674.387992,34.67996692657471,1.212918797791644,1739502674.3879933,34.67996692657471,0.6108,1739502674.3879948,34.67996692657471,0.9473901301645239,1739502674.3879967,34.67996692657471,0.0,1739502674.387998,34.67996692657471,-0.01354908344359762,1739502674.3879998,34.67996692657471,2.8778127505359192,1739502674.3880014,34.67996692657471,0.9609392136081215 +1739502674.4077404,34.69996690750122,48.468857305370676,1739502674.4077437,34.69996690750122,8.082475752761193,1739502674.407747,34.69996690750122,59.88063087380595,1739502674.4077501,34.69996690750122,44.89808679674463,1739502674.4077518,34.69996690750122,7.790469437395704,1739502674.4077537,34.69996690750122,-3.0599973821769377,1739502674.4077554,34.69996690750122,1.212918797791644,1739502674.407757,34.69996690750122,0.6108,1739502674.4077585,34.69996690750122,0.9473901301645239,1739502674.4077604,34.69996690750122,0.0,1739502674.4077618,34.69996690750122,-0.01354908344359762,1739502674.4077637,34.69996690750122,2.8778127505359192,1739502674.4077654,34.69996690750122,0.9609392136081215 +1739502674.427767,34.719966888427734,48.366553765706286,1739502674.4277701,34.719966888427734,8.108732966422554,1739502674.4277735,34.719966888427734,59.985002199791175,1739502674.4277766,34.719966888427734,44.81916094225737,1739502674.4277782,34.719966888427734,7.726883280306881,1739502674.4277804,34.719966888427734,-3.0343631869860843,1739502674.4277818,34.719966888427734,1.2012989531218177,1739502674.4277835,34.719966888427734,0.6108,1739502674.427785,34.719966888427734,0.9562380117774478,1739502674.427787,34.719966888427734,0.0,1739502674.4277885,34.719966888427734,0.00151379491705115,1739502674.4277902,34.719966888427734,2.905414439478466,1739502674.4277916,34.719966888427734,0.9594313694343491 +1739502674.4477599,34.73996686935425,48.366553765706286,1739502674.447763,34.73996686935425,8.108732966422554,1739502674.447766,34.73996686935425,59.985002199791175,1739502674.4477694,34.73996686935425,44.81916094225737,1739502674.4477708,34.73996686935425,7.726883280306881,1739502674.447773,34.73996686935425,-3.0343631869860843,1739502674.4477744,34.73996686935425,1.2012989531218177,1739502674.4477763,34.73996686935425,0.6108,1739502674.4477777,34.73996686935425,0.9562380117774478,1739502674.44778,34.73996686935425,0.0,1739502674.4477813,34.73996686935425,-0.003193357656901319,1739502674.4477832,34.73996686935425,2.905414439478466,1739502674.4477847,34.73996686935425,0.9594313694343491 +1739502674.4680116,34.75996685028076,48.366553765706286,1739502674.4680142,34.75996685028076,8.108732966422554,1739502674.4680178,34.75996685028076,59.985002199791175,1739502674.4680212,34.75996685028076,44.81916094225737,1739502674.4680228,34.75996685028076,7.726883280306881,1739502674.4680247,34.75996685028076,-3.0343631869860843,1739502674.4680264,34.75996685028076,1.2012989531218177,1739502674.4680278,34.75996685028076,0.6108,1739502674.4680295,34.75996685028076,0.9562380117774478,1739502674.4680312,34.75996685028076,0.0,1739502674.4680326,34.75996685028076,-0.003193357656901319,1739502674.4680343,34.75996685028076,2.905414439478466,1739502674.4680362,34.75996685028076,0.9594313694343491 +1739502674.487731,34.779966831207275,48.366553765706286,1739502674.4877343,34.779966831207275,8.108732966422554,1739502674.487738,34.779966831207275,59.985002199791175,1739502674.4877412,34.779966831207275,44.81916094225737,1739502674.4877427,34.779966831207275,7.726883280306881,1739502674.4877448,34.779966831207275,-3.0343631869860843,1739502674.4877462,34.779966831207275,1.2012989531218177,1739502674.487748,34.779966831207275,0.6108,1739502674.4877496,34.779966831207275,0.9562380117774478,1739502674.4877515,34.779966831207275,0.0,1739502674.487753,34.779966831207275,-0.003193357656901319,1739502674.4877553,34.779966831207275,2.905414439478466,1739502674.4877567,34.779966831207275,0.9594313694343491 +1739502674.5079203,34.79996681213379,48.366553765706286,1739502674.5079234,34.79996681213379,8.108732966422554,1739502674.507927,34.79996681213379,59.985002199791175,1739502674.5079303,34.79996681213379,44.81916094225737,1739502674.507932,34.79996681213379,7.726883280306881,1739502674.5079339,34.79996681213379,-3.0343631869860843,1739502674.5079355,34.79996681213379,1.2012989531218177,1739502674.507937,34.79996681213379,0.6108,1739502674.5079386,34.79996681213379,0.9562380117774478,1739502674.5079405,34.79996681213379,0.0,1739502674.5079422,34.79996681213379,-0.003193357656901319,1739502674.5079439,34.79996681213379,2.905414439478466,1739502674.5079455,34.79996681213379,0.9594313694343491 +1739502674.5277774,34.8199667930603,48.366553765706286,1739502674.5277805,34.8199667930603,8.108732966422554,1739502674.5277839,34.8199667930603,59.985002199791175,1739502674.5277874,34.8199667930603,44.81916094225737,1739502674.527789,34.8199667930603,7.726883280306881,1739502674.5277913,34.8199667930603,-3.0343631869860843,1739502674.527793,34.8199667930603,1.2012989531218177,1739502674.5277946,34.8199667930603,0.6108,1739502674.5277965,34.8199667930603,0.9562380117774478,1739502674.5277982,34.8199667930603,0.0,1739502674.5277998,34.8199667930603,-0.003193357656901319,1739502674.5278015,34.8199667930603,2.905414439478466,1739502674.5278032,34.8199667930603,0.9594313694343491 +1739502674.5531566,34.839966773986816,48.263656016463656,1739502674.5531647,34.839966773986816,8.132135707689947,1739502674.553175,34.839966773986816,60.12773542068641,1739502674.553185,34.839966773986816,44.71181593902724,1739502674.55319,34.839966773986816,7.633637322073743,1739502674.5531962,34.839966773986816,-3.002154110909515,1739502674.5532014,34.839966773986816,1.22316485928183,1739502674.5532062,34.839966773986816,0.6108,1739502674.5532112,34.839966773986816,0.9396562561430767,1739502674.5532165,34.839966773986816,0.0,1739502674.5532215,34.839966773986816,-0.026939146594976503,1739502674.5532265,34.839966773986816,2.933016128421013,1739502674.5532317,34.839966773986816,0.9591748388296039 +1739502674.5729864,34.85996675491333,48.263656016463656,1739502674.5729961,34.85996675491333,8.132135707689947,1739502674.5730066,34.85996675491333,60.12773542068641,1739502674.5730171,34.85996675491333,44.71181593902724,1739502674.5730221,34.85996675491333,7.633637322073743,1739502674.5730283,34.85996675491333,-3.002154110909515,1739502674.5730336,34.85996675491333,1.22316485928183,1739502674.5730383,34.85996675491333,0.6108,1739502674.5730429,34.85996675491333,0.9396562561430767,1739502674.5730488,34.85996675491333,0.0,1739502674.5730536,34.85996675491333,-0.019518582686527175,1739502674.573059,34.85996675491333,2.933016128421013,1739502674.573064,34.85996675491333,0.9591748388296039 +1739502674.5954545,34.86996674537659,48.263656016463656,1739502674.5954635,34.86996674537659,8.132135707689947,1739502674.5954745,34.86996674537659,60.12773542068641,1739502674.5954847,34.86996674537659,44.71181593902724,1739502674.5954893,34.86996674537659,7.633637322073743,1739502674.5954955,34.86996674537659,-3.002154110909515,1739502674.5955002,34.86996674537659,1.22316485928183,1739502674.5955052,34.86996674537659,0.6108,1739502674.5955098,34.86996674537659,0.9396562561430767,1739502674.5955155,34.86996674537659,0.0,1739502674.5955205,34.86996674537659,-0.019518582686527175,1739502674.5955257,34.86996674537659,2.933016128421013,1739502674.5955307,34.86996674537659,0.9591748388296039 +1739502674.6120071,34.89996671676636,48.263656016463656,1739502674.6120136,34.89996671676636,8.132135707689947,1739502674.612021,34.89996671676636,60.12773542068641,1739502674.612028,34.89996671676636,44.71181593902724,1739502674.6120312,34.89996671676636,7.633637322073743,1739502674.6120355,34.89996671676636,-3.002154110909515,1739502674.6120389,34.89996671676636,1.22316485928183,1739502674.6120422,34.89996671676636,0.6108,1739502674.6120455,34.89996671676636,0.9396562561430767,1739502674.6120496,34.89996671676636,0.0,1739502674.612053,34.89996671676636,-0.019518582686527175,1739502674.6120567,34.89996671676636,2.933016128421013,1739502674.6120608,34.89996671676636,0.9591748388296039 +1739502674.6415868,34.91996669769287,48.263656016463656,1739502674.6415915,34.91996669769287,8.132135707689947,1739502674.6415977,34.91996669769287,60.12773542068641,1739502674.6416032,34.91996669769287,44.71181593902724,1739502674.6416059,34.91996669769287,7.633637322073743,1739502674.6416097,34.91996669769287,-3.002154110909515,1739502674.6416123,34.91996669769287,1.22316485928183,1739502674.641615,34.91996669769287,0.6108,1739502674.6416173,34.91996669769287,0.9396562561430767,1739502674.6416204,34.91996669769287,0.0,1739502674.641623,34.91996669769287,-0.019518582686527175,1739502674.641626,34.91996669769287,2.933016128421013,1739502674.6416285,34.91996669769287,0.9591748388296039 +1739502674.661347,34.94996666908264,48.16027235060678,1739502674.6613505,34.94996666908264,8.152666256340236,1739502674.6613548,34.94996666908264,60.21167224869451,1739502674.6613584,34.94996666908264,44.65253598207883,1739502674.6613605,34.94996666908264,7.5804722851490975,1739502674.6613626,34.94996666908264,-2.979893422651204,1739502674.6613646,34.94996666908264,1.1942017695872635,1739502674.6613665,34.94996666908264,0.6108,1739502674.6613681,34.94996666908264,0.961682731358262,1739502674.6613703,34.94996666908264,0.0,1739502674.6613722,34.94996666908264,0.015610660275922214,1739502674.661374,34.94996666908264,2.9606178173635596,1739502674.6613762,34.94996666908264,0.9570499667057745 +1739502674.6808217,34.969966650009155,48.16027235060678,1739502674.680825,34.969966650009155,8.152666256340236,1739502674.6808293,34.969966650009155,60.21167224869451,1739502674.680833,34.969966650009155,44.65253598207883,1739502674.6808348,34.969966650009155,7.5804722851490975,1739502674.6808372,34.969966650009155,-2.979893422651204,1739502674.6808388,34.969966650009155,1.1942017695872635,1739502674.6808407,34.969966650009155,0.6108,1739502674.6808424,34.969966650009155,0.961682731358262,1739502674.6808445,34.969966650009155,0.0,1739502674.6808467,34.969966650009155,0.00463276465248752,1739502674.6808484,34.969966650009155,2.9606178173635596,1739502674.6808505,34.969966650009155,0.9570499667057745 +1739502674.7006917,34.98996663093567,48.16027235060678,1739502674.7006962,34.98996663093567,8.152666256340236,1739502674.7007008,34.98996663093567,60.21167224869451,1739502674.7007046,34.98996663093567,44.65253598207883,1739502674.7007065,34.98996663093567,7.5804722851490975,1739502674.7007089,34.98996663093567,-2.979893422651204,1739502674.700711,34.98996663093567,1.1942017695872635,1739502674.7007132,34.98996663093567,0.6108,1739502674.7007158,34.98996663093567,0.961682731358262,1739502674.7007184,34.98996663093567,0.0,1739502674.7007205,34.98996663093567,0.00463276465248752,1739502674.700723,34.98996663093567,2.9606178173635596,1739502674.7007253,34.98996663093567,0.9570499667057745 +1739502674.7205093,35.00996661186218,48.16027235060678,1739502674.7205126,35.00996661186218,8.152666256340236,1739502674.7205162,35.00996661186218,60.21167224869451,1739502674.7205198,35.00996661186218,44.65253598207883,1739502674.7205215,35.00996661186218,7.5804722851490975,1739502674.7205236,35.00996661186218,-2.979893422651204,1739502674.7205255,35.00996661186218,1.1942017695872635,1739502674.7205274,35.00996661186218,0.6108,1739502674.7205288,35.00996661186218,0.961682731358262,1739502674.720531,35.00996661186218,0.0,1739502674.7205327,35.00996661186218,0.00463276465248752,1739502674.7205348,35.00996661186218,2.9606178173635596,1739502674.720537,35.00996661186218,0.9570499667057745 +1739502674.7408059,35.029966592788696,48.16027235060678,1739502674.7408097,35.029966592788696,8.152666256340236,1739502674.7408137,35.029966592788696,60.21167224869451,1739502674.740818,35.029966592788696,44.65253598207883,1739502674.7408197,35.029966592788696,7.5804722851490975,1739502674.7408223,35.029966592788696,-2.979893422651204,1739502674.740824,35.029966592788696,1.1942017695872635,1739502674.7408266,35.029966592788696,0.6108,1739502674.7408288,35.029966592788696,0.961682731358262,1739502674.740831,35.029966592788696,0.0,1739502674.7408328,35.029966592788696,0.00463276465248752,1739502674.7408347,35.029966592788696,2.9606178173635596,1739502674.7408369,35.029966592788696,0.9570499667057745 +1739502674.7598615,35.04996657371521,48.05646998058152,1739502674.759864,35.04996657371521,8.170316609022036,1739502674.759867,35.04996657371521,60.34235599064908,1739502674.75987,35.04996657371521,44.555975267828096,1739502674.7598715,35.04996657371521,7.490975267828095,1739502674.7598734,35.04996657371521,-2.949905373140618,1739502674.7598748,35.04996657371521,1.2061463003710087,1739502674.759876,35.04996657371521,0.6108,1739502674.7598774,35.04996657371521,0.9525370182589201,1739502674.7598794,35.04996657371521,0.0,1739502674.759881,35.04996657371521,-0.009379516838764824,1739502674.7598822,35.04996657371521,2.9882195063061063,1739502674.7598839,35.04996657371521,0.9575376942606768 +1739502674.785214,35.069966554641724,48.05646998058152,1739502674.7852187,35.069966554641724,8.170316609022036,1739502674.7852247,35.069966554641724,60.34235599064908,1739502674.7852304,35.069966554641724,44.555975267828096,1739502674.7852328,35.069966554641724,7.490975267828095,1739502674.7852366,35.069966554641724,-2.949905373140618,1739502674.7852392,35.069966554641724,1.2061463003710087,1739502674.7852418,35.069966554641724,0.6108,1739502674.7852447,35.069966554641724,0.9525370182589201,1739502674.7852478,35.069966554641724,0.0,1739502674.7852507,35.069966554641724,-0.005000676001756688,1739502674.7852535,35.069966554641724,2.9882195063061063,1739502674.7852564,35.069966554641724,0.9575376942606768 +1739502674.8048081,35.08996653556824,48.05646998058152,1739502674.8048131,35.08996653556824,8.170316609022036,1739502674.8048193,35.08996653556824,60.34235599064908,1739502674.8048253,35.08996653556824,44.555975267828096,1739502674.8048282,35.08996653556824,7.490975267828095,1739502674.8048315,35.08996653556824,-2.949905373140618,1739502674.8048344,35.08996653556824,1.2061463003710087,1739502674.8048372,35.08996653556824,0.6108,1739502674.8048396,35.08996653556824,0.9525370182589201,1739502674.804843,35.08996653556824,0.0,1739502674.8048458,35.08996653556824,-0.005000676001756688,1739502674.8048494,35.08996653556824,2.9882195063061063,1739502674.804859,35.08996653556824,0.9575376942606768 +1739502674.824313,35.10996651649475,48.05646998058152,1739502674.8243172,35.10996651649475,8.170316609022036,1739502674.8243232,35.10996651649475,60.34235599064908,1739502674.824329,35.10996651649475,44.555975267828096,1739502674.8243318,35.10996651649475,7.490975267828095,1739502674.824335,35.10996651649475,-2.949905373140618,1739502674.824338,35.10996651649475,1.2061463003710087,1739502674.8243408,35.10996651649475,0.6108,1739502674.8243432,35.10996651649475,0.9525370182589201,1739502674.8243465,35.10996651649475,0.0,1739502674.8243494,35.10996651649475,-0.005000676001756688,1739502674.8243525,35.10996651649475,2.9882195063061063,1739502674.8243554,35.10996651649475,0.9575376942606768 +1739502674.8401694,35.129966497421265,48.05646998058152,1739502674.8401725,35.129966497421265,8.170316609022036,1739502674.840176,35.129966497421265,60.34235599064908,1739502674.8401794,35.129966497421265,44.555975267828096,1739502674.8401814,35.129966497421265,7.490975267828095,1739502674.8401833,35.129966497421265,-2.949905373140618,1739502674.8401852,35.129966497421265,1.2061463003710087,1739502674.8401866,35.129966497421265,0.6108,1739502674.8401883,35.129966497421265,0.9525370182589201,1739502674.8401902,35.129966497421265,0.0,1739502674.840192,35.129966497421265,-0.005000676001756688,1739502674.8401935,35.129966497421265,2.9882195063061063,1739502674.8401954,35.129966497421265,0.9575376942606768 +1739502674.8596005,35.14996647834778,48.05646998058152,1739502674.8596027,35.14996647834778,8.170316609022036,1739502674.8596053,35.14996647834778,60.34235599064908,1739502674.8596082,35.14996647834778,44.555975267828096,1739502674.8596091,35.14996647834778,7.490975267828095,1739502674.8596106,35.14996647834778,-2.949905373140618,1739502674.859612,35.14996647834778,1.2061463003710087,1739502674.8596132,35.14996647834778,0.6108,1739502674.8596141,35.14996647834778,0.9525370182589201,1739502674.8596158,35.14996647834778,0.0,1739502674.859617,35.14996647834778,-0.005000676001756688,1739502674.8596182,35.14996647834778,2.9882195063061063,1739502674.8596196,35.14996647834778,0.9575376942606768 +1739502674.8844733,35.16996645927429,47.95222225641988,1739502674.8844814,35.16996645927429,8.185095477477912,1739502674.8844914,35.16996645927429,60.4545270300111,1739502674.8845015,35.16996645927429,44.47756878507157,1739502674.8845067,35.16996645927429,7.412544828686652,1739502674.8845131,35.16996645927429,-2.9228125184434903,1739502674.8845181,35.16996645927429,1.2023094203127922,1739502674.884523,35.16996645927429,0.6108,1739502674.884528,35.16996645927429,0.9554653264186754,1739502674.8845332,35.16996645927429,0.0,1739502674.8845382,35.16996645927429,0.0001825806656386656,1739502674.8845432,35.16996645927429,3.015821195248653,1739502674.8845482,35.16996645927429,0.956902514523601 +1739502674.905717,35.189966440200806,47.95222225641988,1739502674.9057255,35.189966440200806,8.185095477477912,1739502674.905736,35.189966440200806,60.4545270300111,1739502674.905746,35.189966440200806,44.47756878507157,1739502674.905751,35.189966440200806,7.412544828686652,1739502674.9057572,35.189966440200806,-2.9228125184434903,1739502674.9057627,35.189966440200806,1.2023094203127922,1739502674.9057674,35.189966440200806,0.6108,1739502674.905772,35.189966440200806,0.9554653264186754,1739502674.905778,35.189966440200806,0.0,1739502674.9057827,35.189966440200806,-0.0014371881049255464,1739502674.9057877,35.189966440200806,3.015821195248653,1739502674.9057927,35.189966440200806,0.956902514523601 +1739502674.9219055,35.20996642112732,47.95222225641988,1739502674.9219096,35.20996642112732,8.185095477477912,1739502674.9219139,35.20996642112732,60.4545270300111,1739502674.9219182,35.20996642112732,44.47756878507157,1739502674.9219205,35.20996642112732,7.412544828686652,1739502674.9219234,35.20996642112732,-2.9228125184434903,1739502674.9219255,35.20996642112732,1.2023094203127922,1739502674.921928,35.20996642112732,0.6108,1739502674.92193,35.20996642112732,0.9554653264186754,1739502674.9219325,35.20996642112732,0.0,1739502674.9219348,35.20996642112732,-0.0014371881049255464,1739502674.9219377,35.20996642112732,3.015821195248653,1739502674.9219398,35.20996642112732,0.956902514523601 +1739502674.9406183,35.22996640205383,47.95222225641988,1739502674.9406216,35.22996640205383,8.185095477477912,1739502674.9406254,35.22996640205383,60.4545270300111,1739502674.9406295,35.22996640205383,44.47756878507157,1739502674.9406314,35.22996640205383,7.412544828686652,1739502674.9406333,35.22996640205383,-2.9228125184434903,1739502674.9406354,35.22996640205383,1.2023094203127922,1739502674.940637,35.22996640205383,0.6108,1739502674.940639,35.22996640205383,0.9554653264186754,1739502674.940641,35.22996640205383,0.0,1739502674.9406428,35.22996640205383,-0.0014371881049255464,1739502674.940645,35.22996640205383,3.015821195248653,1739502674.9406466,35.22996640205383,0.956902514523601 +1739502674.9595745,35.24996638298035,47.95222225641988,1739502674.9595766,35.24996638298035,8.185095477477912,1739502674.9595795,35.24996638298035,60.4545270300111,1739502674.9595819,35.24996638298035,44.47756878507157,1739502674.9595833,35.24996638298035,7.412544828686652,1739502674.9595847,35.24996638298035,-2.9228125184434903,1739502674.9595861,35.24996638298035,1.2023094203127922,1739502674.9595873,35.24996638298035,0.6108,1739502674.9595885,35.24996638298035,0.9554653264186754,1739502674.95959,35.24996638298035,0.0,1739502674.9595912,35.24996638298035,-0.0014371881049255464,1739502674.9595923,35.24996638298035,3.015821195248653,1739502674.9595938,35.24996638298035,0.956902514523601 +1739502674.9800668,35.26996636390686,47.84764886002732,1739502674.9800692,35.26996636390686,8.19698671900107,1739502674.9800725,35.26996636390686,60.613232684098435,1739502674.9800751,35.26996636390686,44.36928303757347,1739502674.980076,35.26996636390686,7.296963394935049,1739502674.9800777,35.26996636390686,-2.888396834217152,1739502674.9800794,35.26996636390686,1.2366120662252422,1739502674.980081,35.26996636390686,0.6108,1739502674.9800825,35.26996636390686,0.9296018329670557,1739502674.980084,35.26996636390686,0.0,1739502674.9800851,35.26996636390686,-0.038823672712319506,1739502674.9800868,35.26996636390686,3.0434228841912,1739502674.980088,35.26996636390686,0.9567422215794066 +1739502675.0000725,35.289966344833374,47.84764886002732,1739502675.000075,35.289966344833374,8.19698671900107,1739502675.000078,35.289966344833374,60.613232684098435,1739502675.0000806,35.289966344833374,44.36928303757347,1739502675.0000818,35.289966344833374,7.296963394935049,1739502675.0000834,35.289966344833374,-2.888396834217152,1739502675.0000844,35.289966344833374,1.2366120662252422,1739502675.0000858,35.289966344833374,0.6108,1739502675.000087,35.289966344833374,0.9296018329670557,1739502675.0000887,35.289966344833374,0.0,1739502675.0000896,35.289966344833374,-0.027140388612350907,1739502675.0000908,35.289966344833374,3.0434228841912,1739502675.0000923,35.289966344833374,0.9567422215794066 +1739502675.0199323,35.30996632575989,47.84764886002732,1739502675.019935,35.30996632575989,8.19698671900107,1739502675.0199385,35.30996632575989,60.613232684098435,1739502675.019941,35.30996632575989,44.36928303757347,1739502675.0199423,35.30996632575989,7.296963394935049,1739502675.019944,35.30996632575989,-2.888396834217152,1739502675.0199456,35.30996632575989,1.2366120662252422,1739502675.019947,35.30996632575989,0.6108,1739502675.0199485,35.30996632575989,0.9296018329670557,1739502675.0199502,35.30996632575989,0.0,1739502675.019951,35.30996632575989,-0.027140388612350907,1739502675.0199525,35.30996632575989,3.0434228841912,1739502675.0199542,35.30996632575989,0.9567422215794066 +1739502675.0400455,35.3299663066864,47.84764886002732,1739502675.040048,35.3299663066864,8.19698671900107,1739502675.0400505,35.3299663066864,60.613232684098435,1739502675.0400531,35.3299663066864,44.36928303757347,1739502675.0400546,35.3299663066864,7.296963394935049,1739502675.040056,35.3299663066864,-2.888396834217152,1739502675.0400574,35.3299663066864,1.2366120662252422,1739502675.0400586,35.3299663066864,0.6108,1739502675.0400598,35.3299663066864,0.9296018329670557,1739502675.0400617,35.3299663066864,0.0,1739502675.040063,35.3299663066864,-0.027140388612350907,1739502675.0400643,35.3299663066864,3.0434228841912,1739502675.0400655,35.3299663066864,0.9567422215794066 +1739502675.059642,35.349966287612915,47.84764886002732,1739502675.0596442,35.349966287612915,8.19698671900107,1739502675.059647,35.349966287612915,60.613232684098435,1739502675.0596492,35.349966287612915,44.36928303757347,1739502675.059651,35.349966287612915,7.296963394935049,1739502675.059652,35.349966287612915,-2.888396834217152,1739502675.0596535,35.349966287612915,1.2366120662252422,1739502675.059655,35.349966287612915,0.6108,1739502675.059656,35.349966287612915,0.9296018329670557,1739502675.0596576,35.349966287612915,0.0,1739502675.0596588,35.349966287612915,-0.027140388612350907,1739502675.05966,35.349966287612915,3.0434228841912,1739502675.0596614,35.349966287612915,0.9567422215794066 +1739502675.0796413,35.36996626853943,47.84764886002732,1739502675.079644,35.36996626853943,8.19698671900107,1739502675.079647,35.36996626853943,60.613232684098435,1739502675.0796494,35.36996626853943,44.36928303757347,1739502675.0796509,35.36996626853943,7.296963394935049,1739502675.0796525,35.36996626853943,-2.888396834217152,1739502675.079654,35.36996626853943,1.2366120662252422,1739502675.0796554,35.36996626853943,0.6108,1739502675.0796564,35.36996626853943,0.9296018329670557,1739502675.0796583,35.36996626853943,0.0,1739502675.0796592,35.36996626853943,-0.027140388612350907,1739502675.079661,35.36996626853943,3.0434228841912,1739502675.0796626,35.36996626853943,0.9567422215794066 +1739502675.1017232,35.38996624946594,47.7429665961659,1739502675.1017263,35.38996624946594,8.205972744901963,1739502675.1017308,35.38996624946594,60.69637088795051,1739502675.1017356,35.38996624946594,44.31821659531423,1739502675.1017385,35.38996624946594,7.239705357718887,1739502675.1017423,35.38996624946594,-2.866598355927956,1739502675.1017456,35.38996624946594,1.2053399468591346,1739502675.101749,35.38996624946594,0.6108,1739502675.101752,35.38996624946594,0.9531516817479208,1739502675.1017554,35.38996624946594,0.0,1739502675.1017587,35.38996624946594,0.011779087824704805,1739502675.101762,35.38996624946594,3.0710245731337467,1739502675.1017656,35.38996624946594,0.9535349382840502 +1739502675.1196387,35.409966230392456,47.7429665961659,1739502675.119641,35.409966230392456,8.205972744901963,1739502675.119644,35.409966230392456,60.69637088795051,1739502675.1196465,35.409966230392456,44.31821659531423,1739502675.1196477,35.409966230392456,7.239705357718887,1739502675.1196496,35.409966230392456,-2.866598355927956,1739502675.1196508,35.409966230392456,1.2053399468591346,1739502675.119652,35.409966230392456,0.6108,1739502675.1196535,35.409966230392456,0.9531516817479208,1739502675.1196547,35.409966230392456,0.0,1739502675.1196558,35.409966230392456,-0.00038325653612947264,1739502675.1196573,35.409966230392456,3.0710245731337467,1739502675.1196587,35.409966230392456,0.9535349382840502 +1739502675.1398005,35.42996621131897,47.7429665961659,1739502675.1398032,35.42996621131897,8.205972744901963,1739502675.139806,35.42996621131897,60.69637088795051,1739502675.1398087,35.42996621131897,44.31821659531423,1739502675.13981,35.42996621131897,7.239705357718887,1739502675.1398115,35.42996621131897,-2.866598355927956,1739502675.1398132,35.42996621131897,1.2053399468591346,1739502675.1398144,35.42996621131897,0.6108,1739502675.1398156,35.42996621131897,0.9531516817479208,1739502675.1398175,35.42996621131897,0.0,1739502675.1398187,35.42996621131897,-0.00038325653612947264,1739502675.1398203,35.42996621131897,3.0710245731337467,1739502675.1398215,35.42996621131897,0.9535349382840502 +1739502675.159809,35.44996619224548,47.7429665961659,1739502675.1598115,35.44996619224548,8.205972744901963,1739502675.1598146,35.44996619224548,60.69637088795051,1739502675.1598175,35.44996619224548,44.31821659531423,1739502675.1598186,35.44996619224548,7.239705357718887,1739502675.1598206,35.44996619224548,-2.866598355927956,1739502675.1598217,35.44996619224548,1.2053399468591346,1739502675.1598234,35.44996619224548,0.6108,1739502675.1598248,35.44996619224548,0.9531516817479208,1739502675.1598265,35.44996619224548,0.0,1739502675.159828,35.44996619224548,-0.00038325653612947264,1739502675.1598291,35.44996619224548,3.0710245731337467,1739502675.1598308,35.44996619224548,0.9535349382840502 +1739502675.1813867,35.469966173172,47.7429665961659,1739502675.1813903,35.469966173172,8.205972744901963,1739502675.1813943,35.469966173172,60.69637088795051,1739502675.1813996,35.469966173172,44.31821659531423,1739502675.1814015,35.469966173172,7.239705357718887,1739502675.181405,35.469966173172,-2.866598355927956,1739502675.1814075,35.469966173172,1.2053399468591346,1739502675.1814103,35.469966173172,0.6108,1739502675.1814144,35.469966173172,0.9531516817479208,1739502675.1814184,35.469966173172,0.0,1739502675.181421,35.469966173172,-0.00038325653612947264,1739502675.1814246,35.469966173172,3.0710245731337467,1739502675.181427,35.469966173172,0.9535349382840502 +1739502675.2009966,35.48996615409851,47.63826547554641,1739502675.2010007,35.48996615409851,8.212054504465192,1739502675.201005,35.48996615409851,60.79765229866976,1739502675.2010098,35.48996615409851,44.25274368166663,1739502675.201012,35.48996615409851,7.162599792959142,1739502675.201015,35.48996615409851,-2.8410023559160833,1739502675.2010176,35.48996615409851,1.1939050576869943,1739502675.2010202,35.48996615409851,0.6108,1739502675.2010226,35.48996615409851,0.9619110326216127,1739502675.2010252,35.48996615409851,0.0,1739502675.2010279,35.48996615409851,0.012450302459234772,1739502675.2010305,35.48996615409851,3.0986262620762934,1739502675.2010329,35.48996615409851,0.9534712199779113 +1739502675.2213798,35.509966135025024,47.63826547554641,1739502675.221384,35.509966135025024,8.212054504465192,1739502675.2213886,35.509966135025024,60.79765229866976,1739502675.2213929,35.509966135025024,44.25274368166663,1739502675.2213953,35.509966135025024,7.162599792959142,1739502675.2213984,35.509966135025024,-2.8410023559160833,1739502675.221401,35.509966135025024,1.1939050576869943,1739502675.2214034,35.509966135025024,0.6108,1739502675.2214057,35.509966135025024,0.9619110326216127,1739502675.2214086,35.509966135025024,0.0,1739502675.2214108,35.509966135025024,0.008439812643701416,1739502675.2214134,35.509966135025024,3.0986262620762934,1739502675.221416,35.509966135025024,0.9534712199779113 +1739502675.2410252,35.52996611595154,47.63826547554641,1739502675.241029,35.52996611595154,8.212054504465192,1739502675.2410338,35.52996611595154,60.79765229866976,1739502675.2410388,35.52996611595154,44.25274368166663,1739502675.2410417,35.52996611595154,7.162599792959142,1739502675.241046,35.52996611595154,-2.8410023559160833,1739502675.2410493,35.52996611595154,1.1939050576869943,1739502675.2410529,35.52996611595154,0.6108,1739502675.2410562,35.52996611595154,0.9619110326216127,1739502675.2410595,35.52996611595154,0.0,1739502675.241063,35.52996611595154,0.008439812643701416,1739502675.2410667,35.52996611595154,3.0986262620762934,1739502675.2410703,35.52996611595154,0.9534712199779113 +1739502675.2611964,35.54996609687805,47.63826547554641,1739502675.2612004,35.54996609687805,8.212054504465192,1739502675.261205,35.54996609687805,60.79765229866976,1739502675.2612092,35.54996609687805,44.25274368166663,1739502675.2612119,35.54996609687805,7.162599792959142,1739502675.2612147,35.54996609687805,-2.8410023559160833,1739502675.2612176,35.54996609687805,1.1939050576869943,1739502675.26122,35.54996609687805,0.6108,1739502675.2612224,35.54996609687805,0.9619110326216127,1739502675.2612252,35.54996609687805,0.0,1739502675.2612278,35.54996609687805,0.008439812643701416,1739502675.2612302,35.54996609687805,3.0986262620762934,1739502675.261233,35.54996609687805,0.9534712199779113 +1739502675.2800815,35.569966077804565,47.63826547554641,1739502675.2800834,35.569966077804565,8.212054504465192,1739502675.2800858,35.569966077804565,60.79765229866976,1739502675.2800884,35.569966077804565,44.25274368166663,1739502675.2800896,35.569966077804565,7.162599792959142,1739502675.2800908,35.569966077804565,-2.8410023559160833,1739502675.2800922,35.569966077804565,1.1939050576869943,1739502675.2800934,35.569966077804565,0.6108,1739502675.2800944,35.569966077804565,0.9619110326216127,1739502675.2800963,35.569966077804565,0.0,1739502675.2800972,35.569966077804565,0.008439812643701416,1739502675.2800987,35.569966077804565,3.0986262620762934,1739502675.2800999,35.569966077804565,0.9534712199779113 +1739502675.2999644,35.58996605873108,47.63826547554641,1739502675.2999666,35.58996605873108,8.212054504465192,1739502675.2999694,35.58996605873108,60.79765229866976,1739502675.299972,35.58996605873108,44.25274368166663,1739502675.2999735,35.58996605873108,7.162599792959142,1739502675.2999752,35.58996605873108,-2.8410023559160833,1739502675.2999763,35.58996605873108,1.1939050576869943,1739502675.299978,35.58996605873108,0.6108,1739502675.2999792,35.58996605873108,0.9619110326216127,1739502675.2999809,35.58996605873108,0.0,1739502675.299982,35.58996605873108,0.008439812643701416,1739502675.2999835,35.58996605873108,3.0986262620762934,1739502675.299985,35.58996605873108,0.9534712199779113 +1739502675.3203726,35.60996603965759,47.53338156468397,1739502675.3203745,35.60996603965759,8.215245829038127,1739502675.320377,35.60996603965759,60.933631721254116,1739502675.3203797,35.60996603965759,44.165525456379235,1739502675.320381,35.60996603965759,7.055711049617977,1739502675.3203824,35.60996603965759,-2.8100095814651826,1739502675.3203838,35.60996603965759,1.2111419855006904,1739502675.320385,35.60996603965759,0.6108,1739502675.320386,35.60996603965759,0.9487377552704396,1739502675.3203876,35.60996603965759,0.0,1739502675.3203886,35.60996603965759,-0.012182945403676503,1739502675.32039,35.60996603965759,3.12622795101884,1739502675.3203914,35.60996603965759,0.9544760845588909 +1739502675.3399017,35.629966020584106,47.53338156468397,1739502675.3399045,35.629966020584106,8.215245829038127,1739502675.3399086,35.629966020584106,60.933631721254116,1739502675.3399117,35.629966020584106,44.165525456379235,1739502675.339913,35.629966020584106,7.055711049617977,1739502675.3399148,35.629966020584106,-2.8100095814651826,1739502675.339916,35.629966020584106,1.2111419855006904,1739502675.3399177,35.629966020584106,0.6108,1739502675.3399189,35.629966020584106,0.9487377552704396,1739502675.3399203,35.629966020584106,0.0,1739502675.339922,35.629966020584106,-0.005738329288451305,1739502675.3399234,35.629966020584106,3.12622795101884,1739502675.339925,35.629966020584106,0.9544760845588909 +1739502675.3598201,35.64996600151062,47.53338156468397,1739502675.3598228,35.64996600151062,8.215245829038127,1739502675.3598256,35.64996600151062,60.933631721254116,1739502675.3598285,35.64996600151062,44.165525456379235,1739502675.35983,35.64996600151062,7.055711049617977,1739502675.3598316,35.64996600151062,-2.8100095814651826,1739502675.359833,35.64996600151062,1.2111419855006904,1739502675.3598344,35.64996600151062,0.6108,1739502675.3598356,35.64996600151062,0.9487377552704396,1739502675.3598375,35.64996600151062,0.0,1739502675.3598387,35.64996600151062,-0.005738329288451305,1739502675.35984,35.64996600151062,3.12622795101884,1739502675.3598416,35.64996600151062,0.9544760845588909 +1739502675.3798156,35.669965982437134,47.53338156468397,1739502675.3798184,35.669965982437134,8.215245829038127,1739502675.3798225,35.669965982437134,60.933631721254116,1739502675.3798254,35.669965982437134,44.165525456379235,1739502675.3798268,35.669965982437134,7.055711049617977,1739502675.3798285,35.669965982437134,-2.8100095814651826,1739502675.3798301,35.669965982437134,1.2111419855006904,1739502675.3798316,35.669965982437134,0.6108,1739502675.3798327,35.669965982437134,0.9487377552704396,1739502675.3798344,35.669965982437134,0.0,1739502675.3798358,35.669965982437134,-0.005738329288451305,1739502675.3798375,35.669965982437134,3.12622795101884,1739502675.379839,35.669965982437134,0.9544760845588909 +1739502675.3998275,35.68996596336365,47.53338156468397,1739502675.3998303,35.68996596336365,8.215245829038127,1739502675.3998337,35.68996596336365,60.933631721254116,1739502675.3998363,35.68996596336365,44.165525456379235,1739502675.3998377,35.68996596336365,7.055711049617977,1739502675.3998394,35.68996596336365,-2.8100095814651826,1739502675.3998408,35.68996596336365,1.2111419855006904,1739502675.3998423,35.68996596336365,0.6108,1739502675.3998437,35.68996596336365,0.9487377552704396,1739502675.3998451,35.68996596336365,0.0,1739502675.3998466,35.68996596336365,-0.005738329288451305,1739502675.399848,35.68996596336365,3.12622795101884,1739502675.3998492,35.68996596336365,0.9544760845588909 +1739502675.4198072,35.70996594429016,47.42842127512275,1739502675.4198098,35.70996594429016,8.215541832539603,1739502675.4198127,35.70996594429016,61.015490826147015,1739502675.4198155,35.70996594429016,44.11705235069397,1739502675.419817,35.70996594429016,6.991284769909709,1739502675.4198184,35.70996594429016,-2.787464953545998,1739502675.41982,35.70996594429016,1.183645236191911,1739502675.4198215,35.70996594429016,0.6108,1739502675.419823,35.70996594429016,0.9698387512973119,1739502675.4198244,35.70996594429016,0.0,1739502675.4198256,35.70996594429016,0.02585158294586669,1739502675.419827,35.70996594429016,3.153829639961387,1739502675.4198284,35.70996594429016,0.9538590223971615 +1739502675.4399621,35.729965925216675,47.42842127512275,1739502675.439965,35.729965925216675,8.215541832539603,1739502675.4399683,35.729965925216675,61.015490826147015,1739502675.439971,35.729965925216675,44.11705235069397,1739502675.4399726,35.729965925216675,6.991284769909709,1739502675.4399743,35.729965925216675,-2.787464953545998,1739502675.4399757,35.729965925216675,1.183645236191911,1739502675.4399772,35.729965925216675,0.6108,1739502675.4399786,35.729965925216675,0.9698387512973119,1739502675.4399803,35.729965925216675,0.0,1739502675.439982,35.729965925216675,0.015979728900150425,1739502675.4399831,35.729965925216675,3.153829639961387,1739502675.4399846,35.729965925216675,0.9538590223971615 +1739502675.4598355,35.74996590614319,47.42842127512275,1739502675.4598382,35.74996590614319,8.215541832539603,1739502675.4598417,35.74996590614319,61.015490826147015,1739502675.4598444,35.74996590614319,44.11705235069397,1739502675.4598458,35.74996590614319,6.991284769909709,1739502675.4598477,35.74996590614319,-2.787464953545998,1739502675.4598489,35.74996590614319,1.183645236191911,1739502675.4598505,35.74996590614319,0.6108,1739502675.4598517,35.74996590614319,0.9698387512973119,1739502675.4598534,35.74996590614319,0.0,1739502675.4598546,35.74996590614319,0.015979728900150425,1739502675.459856,35.74996590614319,3.153829639961387,1739502675.4598575,35.74996590614319,0.9538590223971615 +1739502675.4801157,35.7699658870697,47.42842127512275,1739502675.4801178,35.7699658870697,8.215541832539603,1739502675.4801204,35.7699658870697,61.015490826147015,1739502675.480123,35.7699658870697,44.11705235069397,1739502675.4801245,35.7699658870697,6.991284769909709,1739502675.480126,35.7699658870697,-2.787464953545998,1739502675.4801273,35.7699658870697,1.183645236191911,1739502675.4801288,35.7699658870697,0.6108,1739502675.4801297,35.7699658870697,0.9698387512973119,1739502675.4801314,35.7699658870697,0.0,1739502675.4801326,35.7699658870697,0.015979728900150425,1739502675.4801338,35.7699658870697,3.153829639961387,1739502675.4801352,35.7699658870697,0.9538590223971615 +1739502675.49984,35.789965867996216,47.42842127512275,1739502675.4998431,35.789965867996216,8.215541832539603,1739502675.499846,35.789965867996216,61.015490826147015,1739502675.4998486,35.789965867996216,44.11705235069397,1739502675.4998503,35.789965867996216,6.991284769909709,1739502675.4998517,35.789965867996216,-2.787464953545998,1739502675.4998531,35.789965867996216,1.183645236191911,1739502675.4998546,35.789965867996216,0.6108,1739502675.4998555,35.789965867996216,0.9698387512973119,1739502675.4998572,35.789965867996216,0.0,1739502675.4998584,35.789965867996216,0.015979728900150425,1739502675.49986,35.789965867996216,3.153829639961387,1739502675.4998612,35.789965867996216,0.9538590223971615 +1739502675.5197535,35.80996584892273,47.42842127512275,1739502675.519756,35.80996584892273,8.215541832539603,1739502675.5197592,35.80996584892273,61.015490826147015,1739502675.5197623,35.80996584892273,44.11705235069397,1739502675.5197635,35.80996584892273,6.991284769909709,1739502675.5197651,35.80996584892273,-2.787464953545998,1739502675.5197668,35.80996584892273,1.183645236191911,1739502675.519768,35.80996584892273,0.6108,1739502675.5197694,35.80996584892273,0.9698387512973119,1739502675.5197709,35.80996584892273,0.0,1739502675.519772,35.80996584892273,0.015979728900150425,1739502675.519774,35.80996584892273,3.153829639961387,1739502675.5197754,35.80996584892273,0.9538590223971615 +1739502675.5398757,35.82996582984924,47.32342594553087,1739502675.5398786,35.82996582984924,8.21293870433291,1739502675.5398822,35.82996582984924,61.168374994439546,1739502675.5398853,35.82996582984924,44.025137618603495,1739502675.539887,35.82996582984924,6.864288559466817,1739502675.5398884,35.82996582984924,-2.7534426688569815,1739502675.5398898,35.82996582984924,1.216215368838034,1739502675.5398915,35.82996582984924,0.6108,1739502675.5398927,35.82996582984924,0.9448949107797397,1739502675.5398946,35.82996582984924,0.0,1739502675.5398958,35.82996582984924,-0.023135477023609394,1739502675.5398977,35.82996582984924,3.1814313289039338,1739502675.5398989,35.82996582984924,0.9558068779378166 +1739502675.5599067,35.84996581077576,47.32342594553087,1739502675.5599096,35.84996581077576,8.21293870433291,1739502675.5599124,35.84996581077576,61.168374994439546,1739502675.5599153,35.84996581077576,44.025137618603495,1739502675.5599165,35.84996581077576,6.864288559466817,1739502675.5599184,35.84996581077576,-2.7534426688569815,1739502675.5599196,35.84996581077576,1.216215368838034,1739502675.5599213,35.84996581077576,0.6108,1739502675.5599225,35.84996581077576,0.9448949107797397,1739502675.559924,35.84996581077576,0.0,1739502675.5599253,35.84996581077576,-0.010911967158076852,1739502675.5599265,35.84996581077576,3.1814313289039338,1739502675.5599282,35.84996581077576,0.9558068779378166 +1739502675.5797951,35.86996579170227,47.32342594553087,1739502675.579798,35.86996579170227,8.21293870433291,1739502675.5798013,35.86996579170227,61.168374994439546,1739502675.5798044,35.86996579170227,44.025137618603495,1739502675.5798056,35.86996579170227,6.864288559466817,1739502675.5798075,35.86996579170227,-2.7534426688569815,1739502675.5798087,35.86996579170227,1.216215368838034,1739502675.5798104,35.86996579170227,0.6108,1739502675.579812,35.86996579170227,0.9448949107797397,1739502675.5798137,35.86996579170227,0.0,1739502675.5798151,35.86996579170227,-0.010911967158076852,1739502675.5798168,35.86996579170227,3.1814313289039338,1739502675.5798182,35.86996579170227,0.9558068779378166 +1739502675.599827,35.889965772628784,47.32342594553087,1739502675.59983,35.889965772628784,8.21293870433291,1739502675.599833,35.889965772628784,61.168374994439546,1739502675.5998359,35.889965772628784,44.025137618603495,1739502675.5998373,35.889965772628784,6.864288559466817,1739502675.599839,35.889965772628784,-2.7534426688569815,1739502675.5998402,35.889965772628784,1.216215368838034,1739502675.5998416,35.889965772628784,0.6108,1739502675.5998428,35.889965772628784,0.9448949107797397,1739502675.5998445,35.889965772628784,0.0,1739502675.5998456,35.889965772628784,-0.010911967158076852,1739502675.599847,35.889965772628784,3.1814313289039338,1739502675.5998485,35.889965772628784,0.9558068779378166 +1739502675.6198413,35.9099657535553,47.32342594553087,1739502675.6198437,35.9099657535553,8.21293870433291,1739502675.6198466,35.9099657535553,61.168374994439546,1739502675.6198494,35.9099657535553,44.025137618603495,1739502675.6198506,35.9099657535553,6.864288559466817,1739502675.6198525,35.9099657535553,-2.7534426688569815,1739502675.619854,35.9099657535553,1.216215368838034,1739502675.6198556,35.9099657535553,0.6108,1739502675.6198568,35.9099657535553,0.9448949107797397,1739502675.6198585,35.9099657535553,0.0,1739502675.6198597,35.9099657535553,-0.010911967158076852,1739502675.6198614,35.9099657535553,3.1814313289039338,1739502675.6198626,35.9099657535553,0.9558068779378166 +1739502675.6399014,35.92996573448181,47.21848857152962,1739502675.639904,35.92996573448181,8.207436868498162,1739502675.639907,35.92996573448181,61.249371876358836,1739502675.63991,35.92996573448181,43.98077788508968,1739502675.6399114,35.92996573448181,6.799356287699769,1739502675.6399128,35.92996573448181,-2.731366536351358,1739502675.6399143,35.92996573448181,1.1866927690997955,1739502675.6399157,35.92996573448181,0.6108,1739502675.6399171,35.92996573448181,0.9674771388957593,1739502675.6399186,35.92996573448181,0.0,1739502675.6399198,35.92996573448181,0.023641811437908902,1739502675.6399214,35.92996573448181,3.2090330178464805,1739502675.639923,35.92996573448181,0.9546333903488576 +1739502675.6598556,35.949965715408325,47.21848857152962,1739502675.6598582,35.949965715408325,8.207436868498162,1739502675.6598613,35.949965715408325,61.249371876358836,1739502675.659864,35.949965715408325,43.98077788508968,1739502675.6598656,35.949965715408325,6.799356287699769,1739502675.659867,35.949965715408325,-2.731366536351358,1739502675.6598687,35.949965715408325,1.1866927690997955,1739502675.65987,35.949965715408325,0.6108,1739502675.6598713,35.949965715408325,0.9674771388957593,1739502675.6598728,35.949965715408325,0.0,1739502675.659874,35.949965715408325,0.012843748546901623,1739502675.6598756,35.949965715408325,3.2090330178464805,1739502675.659877,35.949965715408325,0.9546333903488576 +1739502675.6798182,35.96996569633484,47.21848857152962,1739502675.6798208,35.96996569633484,8.207436868498162,1739502675.6798239,35.96996569633484,61.249371876358836,1739502675.6798265,35.96996569633484,43.98077788508968,1739502675.679828,35.96996569633484,6.799356287699769,1739502675.6798296,35.96996569633484,-2.731366536351358,1739502675.6798308,35.96996569633484,1.1866927690997955,1739502675.6798322,35.96996569633484,0.6108,1739502675.6798334,35.96996569633484,0.9674771388957593,1739502675.679835,35.96996569633484,0.0,1739502675.6798365,35.96996569633484,0.012843748546901623,1739502675.6798377,35.96996569633484,3.2090330178464805,1739502675.6798394,35.96996569633484,0.9546333903488576 +1739502675.6998887,35.98996567726135,47.21848857152962,1739502675.6998918,35.98996567726135,8.207436868498162,1739502675.6998954,35.98996567726135,61.249371876358836,1739502675.6998987,35.98996567726135,43.98077788508968,1739502675.6999002,35.98996567726135,6.799356287699769,1739502675.6999023,35.98996567726135,-2.731366536351358,1739502675.6999035,35.98996567726135,1.1866927690997955,1739502675.699905,35.98996567726135,0.6108,1739502675.6999066,35.98996567726135,0.9674771388957593,1739502675.699908,35.98996567726135,0.0,1739502675.6999097,35.98996567726135,0.012843748546901623,1739502675.6999109,35.98996567726135,3.2090330178464805,1739502675.6999125,35.98996567726135,0.9546333903488576 +1739502675.7199495,36.009965658187866,47.21848857152962,1739502675.719952,36.009965658187866,8.207436868498162,1739502675.7199552,36.009965658187866,61.249371876358836,1739502675.7199578,36.009965658187866,43.98077788508968,1739502675.7199593,36.009965658187866,6.799356287699769,1739502675.719961,36.009965658187866,-2.731366536351358,1739502675.7199624,36.009965658187866,1.1866927690997955,1739502675.7199636,36.009965658187866,0.6108,1739502675.719965,36.009965658187866,0.9674771388957593,1739502675.7199667,36.009965658187866,0.0,1739502675.7199678,36.009965658187866,0.012843748546901623,1739502675.7199693,36.009965658187866,3.2090330178464805,1739502675.7199705,36.009965658187866,0.9546333903488576 +1739502675.7403517,36.02996563911438,47.21848857152962,1739502675.7403538,36.02996563911438,8.207436868498162,1739502675.7403567,36.02996563911438,61.249371876358836,1739502675.7403593,36.02996563911438,43.98077788508968,1739502675.740361,36.02996563911438,6.799356287699769,1739502675.7403624,36.02996563911438,-2.731366536351358,1739502675.7403638,36.02996563911438,1.1866927690997955,1739502675.740365,36.02996563911438,0.6108,1739502675.7403662,36.02996563911438,0.9674771388957593,1739502675.740368,36.02996563911438,0.0,1739502675.7403693,36.02996563911438,0.012843748546901623,1739502675.7403708,36.02996563911438,3.2090330178464805,1739502675.7403722,36.02996563911438,0.9546333903488576 +1739502675.7598553,36.049965620040894,47.11372730746967,1739502675.7598581,36.049965620040894,8.19903906426047,1739502675.7598615,36.049965620040894,61.40287772249783,1739502675.7598643,36.049965620040894,43.897096629478646,1739502675.7598655,36.049965620040894,6.666827402741698,1739502675.7598674,36.049965620040894,-2.697051108157709,1739502675.7598689,36.049965620040894,1.2200415033486023,1739502675.7598703,36.049965620040894,0.6108,1739502675.7598715,36.049965620040894,0.9420070966789182,1739502675.7598734,36.049965620040894,0.0,1739502675.7598746,36.049965620040894,-0.02656358077687858,1739502675.7598758,36.049965620040894,3.2366347067890273,1739502675.7598772,36.049965620040894,0.9562558789679044 +1739502675.7798898,36.06996560096741,47.11372730746967,1739502675.7798924,36.06996560096741,8.19903906426047,1739502675.7798958,36.06996560096741,61.40287772249783,1739502675.779899,36.06996560096741,43.897096629478646,1739502675.7799003,36.06996560096741,6.666827402741698,1739502675.779902,36.06996560096741,-2.697051108157709,1739502675.7799037,36.06996560096741,1.2200415033486023,1739502675.7799053,36.06996560096741,0.6108,1739502675.7799063,36.06996560096741,0.9420070966789182,1739502675.7799082,36.06996560096741,0.0,1739502675.7799096,36.06996560096741,-0.014248782288986184,1739502675.7799113,36.06996560096741,3.2366347067890273,1739502675.7799127,36.06996560096741,0.9562558789679044 +1739502675.7998729,36.08996558189392,47.11372730746967,1739502675.7998753,36.08996558189392,8.19903906426047,1739502675.7998784,36.08996558189392,61.40287772249783,1739502675.7998812,36.08996558189392,43.897096629478646,1739502675.7998827,36.08996558189392,6.666827402741698,1739502675.7998846,36.08996558189392,-2.697051108157709,1739502675.799886,36.08996558189392,1.2200415033486023,1739502675.7998874,36.08996558189392,0.6108,1739502675.7998886,36.08996558189392,0.9420070966789182,1739502675.7998903,36.08996558189392,0.0,1739502675.799892,36.08996558189392,-0.014248782288986184,1739502675.7998931,36.08996558189392,3.2366347067890273,1739502675.7998948,36.08996558189392,0.9562558789679044 +1739502675.8198974,36.109965562820435,47.11372730746967,1739502675.8199005,36.109965562820435,8.19903906426047,1739502675.8199034,36.109965562820435,61.40287772249783,1739502675.8199062,36.109965562820435,43.897096629478646,1739502675.8199077,36.109965562820435,6.666827402741698,1739502675.819909,36.109965562820435,-2.697051108157709,1739502675.8199108,36.109965562820435,1.2200415033486023,1739502675.819912,36.109965562820435,0.6108,1739502675.8199131,36.109965562820435,0.9420070966789182,1739502675.819915,36.109965562820435,0.0,1739502675.8199193,36.109965562820435,-0.014248782288986184,1739502675.8199224,36.109965562820435,3.2366347067890273,1739502675.8199246,36.109965562820435,0.9562558789679044 +1739502675.8397663,36.12996554374695,47.11372730746967,1739502675.839769,36.12996554374695,8.19903906426047,1739502675.8397722,36.12996554374695,61.40287772249783,1739502675.8397753,36.12996554374695,43.897096629478646,1739502675.8397765,36.12996554374695,6.666827402741698,1739502675.8397782,36.12996554374695,-2.697051108157709,1739502675.8397799,36.12996554374695,1.2200415033486023,1739502675.8397813,36.12996554374695,0.6108,1739502675.8397827,36.12996554374695,0.9420070966789182,1739502675.8397841,36.12996554374695,0.0,1739502675.8397858,36.12996554374695,-0.014248782288986184,1739502675.8397872,36.12996554374695,3.2366347067890273,1739502675.8397884,36.12996554374695,0.9562558789679044 +1739502675.8598993,36.14996552467346,47.00922238001774,1739502675.8599024,36.14996552467346,8.187752401124227,1739502675.8599055,36.14996552467346,61.483724833739466,1739502675.859908,36.14996552467346,43.85764147991003,1739502675.8599095,36.14996552467346,6.599813965560053,1739502675.8599114,36.14996552467346,-2.674866146397036,1739502675.8599126,36.14996552467346,1.1904574924831264,1739502675.8599143,36.14996552467346,0.6108,1739502675.8599155,36.14996552467346,0.9645676953489601,1739502675.8599174,36.14996552467346,0.0,1739502675.8599186,36.14996552467346,0.020804998705974763,1739502675.8599198,36.14996552467346,3.264236395731574,1739502675.8599215,36.14996552467346,0.9547170103861184 +1739502675.8813334,36.169965505599976,47.00922238001774,1739502675.881336,36.169965505599976,8.187752401124227,1739502675.881339,36.169965505599976,61.483724833739466,1739502675.881342,36.169965505599976,43.85764147991003,1739502675.8813436,36.169965505599976,6.599813965560053,1739502675.881345,36.169965505599976,-2.674866146397036,1739502675.8813465,36.169965505599976,1.1904574924831264,1739502675.881348,36.169965505599976,0.6108,1739502675.8813493,36.169965505599976,0.9645676953489601,1739502675.8813512,36.169965505599976,0.0,1739502675.8813524,36.169965505599976,0.009850684962841694,1739502675.881354,36.169965505599976,3.264236395731574,1739502675.8813558,36.169965505599976,0.9547170103861184 +1739502675.8998635,36.18996548652649,47.00922238001774,1739502675.8998663,36.18996548652649,8.187752401124227,1739502675.8998692,36.18996548652649,61.483724833739466,1739502675.899872,36.18996548652649,43.85764147991003,1739502675.8998733,36.18996548652649,6.599813965560053,1739502675.8998752,36.18996548652649,-2.674866146397036,1739502675.8998764,36.18996548652649,1.1904574924831264,1739502675.8998778,36.18996548652649,0.6108,1739502675.899879,36.18996548652649,0.9645676953489601,1739502675.8998806,36.18996548652649,0.0,1739502675.899882,36.18996548652649,0.009850684962841694,1739502675.8998835,36.18996548652649,3.264236395731574,1739502675.8998847,36.18996548652649,0.9547170103861184 +1739502675.9198587,36.209965467453,47.00922238001774,1739502675.9198616,36.209965467453,8.187752401124227,1739502675.9198647,36.209965467453,61.483724833739466,1739502675.9198673,36.209965467453,43.85764147991003,1739502675.9198687,36.209965467453,6.599813965560053,1739502675.9198704,36.209965467453,-2.674866146397036,1739502675.9198718,36.209965467453,1.1904574924831264,1739502675.919873,36.209965467453,0.6108,1739502675.9198747,36.209965467453,0.9645676953489601,1739502675.919876,36.209965467453,0.0,1739502675.9198773,36.209965467453,0.009850684962841694,1739502675.919879,36.209965467453,3.264236395731574,1739502675.9198802,36.209965467453,0.9547170103861184 +1739502675.9399645,36.22996544837952,47.00922238001774,1739502675.9399672,36.22996544837952,8.187752401124227,1739502675.939971,36.22996544837952,61.483724833739466,1739502675.9399743,36.22996544837952,43.85764147991003,1739502675.9399757,36.22996544837952,6.599813965560053,1739502675.9399776,36.22996544837952,-2.674866146397036,1739502675.9399793,36.22996544837952,1.1904574924831264,1739502675.9399807,36.22996544837952,0.6108,1739502675.9399822,36.22996544837952,0.9645676953489601,1739502675.939984,36.22996544837952,0.0,1739502675.9399858,36.22996544837952,0.009850684962841694,1739502675.9399874,36.22996544837952,3.264236395731574,1739502675.9399889,36.22996544837952,0.9547170103861184 +1739502675.959969,36.24996542930603,47.00922238001774,1739502675.959972,36.24996542930603,8.187752401124227,1739502675.959975,36.24996542930603,61.483724833739466,1739502675.9599779,36.24996542930603,43.85764147991003,1739502675.9599793,36.24996542930603,6.599813965560053,1739502675.9599812,36.24996542930603,-2.674866146397036,1739502675.9599829,36.24996542930603,1.1904574924831264,1739502675.9599843,36.24996542930603,0.6108,1739502675.959986,36.24996542930603,0.9645676953489601,1739502675.9599876,36.24996542930603,0.0,1739502675.959989,36.24996542930603,0.009850684962841694,1739502675.9599907,36.24996542930603,3.264236395731574,1739502675.9599924,36.24996542930603,0.9547170103861184 +1739502675.9802523,36.269965410232544,46.90509091163594,1739502675.9802547,36.269965410232544,8.173588166149909,1739502675.9802577,36.269965410232544,61.558844750807026,1739502675.9802608,36.269965410232544,43.81893420614589,1739502675.9802625,36.269965410232544,6.532425829356154,1739502675.9802642,36.269965410232544,-2.652843953449913,1739502675.9802654,36.269965410232544,1.160735197167348,1739502675.980267,36.269965410232544,0.6108,1739502675.9802685,36.269965410232544,0.9877778784824018,1739502675.9802704,36.269965410232544,0.0,1739502675.9802716,36.269965410232544,0.04172370057680495,1739502675.9802732,36.269965410232544,3.291838084674121,1739502675.9802747,36.269965410232544,0.9560145018154577 +1739502675.999868,36.28996539115906,46.90509091163594,1739502675.9998705,36.28996539115906,8.173588166149909,1739502675.9998736,36.28996539115906,61.558844750807026,1739502675.9998763,36.28996539115906,43.81893420614589,1739502675.999878,36.28996539115906,6.532425829356154,1739502675.9998796,36.28996539115906,-2.652843953449913,1739502675.9998813,36.28996539115906,1.160735197167348,1739502675.999883,36.28996539115906,0.6108,1739502675.9998846,36.28996539115906,0.9877778784824018,1739502675.999886,36.28996539115906,0.0,1739502675.9998877,36.28996539115906,0.031763376666944176,1739502675.9998891,36.28996539115906,3.291838084674121,1739502675.9998908,36.28996539115906,0.9560145018154577 +1739502676.0197716,36.30996537208557,46.90509091163594,1739502676.019774,36.30996537208557,8.173588166149909,1739502676.019777,36.30996537208557,61.558844750807026,1739502676.01978,36.30996537208557,43.81893420614589,1739502676.019781,36.30996537208557,6.532425829356154,1739502676.0197833,36.30996537208557,-2.652843953449913,1739502676.0197845,36.30996537208557,1.160735197167348,1739502676.019786,36.30996537208557,0.6108,1739502676.0197873,36.30996537208557,0.9877778784824018,1739502676.019789,36.30996537208557,0.0,1739502676.0197906,36.30996537208557,0.031763376666944176,1739502676.019792,36.30996537208557,3.291838084674121,1739502676.0197935,36.30996537208557,0.9560145018154577 +1739502676.039995,36.329965353012085,46.90509091163594,1739502676.0399976,36.329965353012085,8.173588166149909,1739502676.040001,36.329965353012085,61.558844750807026,1739502676.040004,36.329965353012085,43.81893420614589,1739502676.0400057,36.329965353012085,6.532425829356154,1739502676.0400074,36.329965353012085,-2.652843953449913,1739502676.040009,36.329965353012085,1.160735197167348,1739502676.0400105,36.329965353012085,0.6108,1739502676.040012,36.329965353012085,0.9877778784824018,1739502676.0400136,36.329965353012085,0.0,1739502676.0400152,36.329965353012085,0.031763376666944176,1739502676.0400167,36.329965353012085,3.291838084674121,1739502676.0400178,36.329965353012085,0.9560145018154577 +1739502676.0597534,36.3499653339386,46.90509091163594,1739502676.059756,36.3499653339386,8.173588166149909,1739502676.0597594,36.3499653339386,61.558844750807026,1739502676.0597625,36.3499653339386,43.81893420614589,1739502676.059764,36.3499653339386,6.532425829356154,1739502676.0597663,36.3499653339386,-2.652843953449913,1739502676.059768,36.3499653339386,1.160735197167348,1739502676.0597694,36.3499653339386,0.6108,1739502676.0597708,36.3499653339386,0.9877778784824018,1739502676.0597727,36.3499653339386,0.0,1739502676.059774,36.3499653339386,0.031763376666944176,1739502676.0597758,36.3499653339386,3.291838084674121,1739502676.0597773,36.3499653339386,0.9560145018154577 +1739502676.079968,36.36996531486511,46.80115605675843,1739502676.0799706,36.36996531486511,8.156516462806595,1739502676.079974,36.36996531486511,61.56054185189175,1739502676.0799768,36.36996531486511,43.81478006687004,1739502676.0799782,36.36996531486511,6.524872848854623,1739502676.0799801,36.36996531486511,-2.641546499194468,1739502676.0799816,36.36996531486511,1.0775844906351746,1739502676.079983,36.36996531486511,0.6108,1739502676.0799847,36.36996531486511,1.0557201485989085,1739502676.0799863,36.36996531486511,0.0,1739502676.079988,36.36996531486511,0.12555368973732925,1739502676.0799897,36.36996531486511,3.3194397736166676,1739502676.079991,36.36996531486511,0.9594759509128751 +1739502676.099766,36.389965295791626,46.80115605675843,1739502676.0997686,36.389965295791626,8.156516462806595,1739502676.0997717,36.389965295791626,61.56054185189175,1739502676.0997748,36.389965295791626,43.81478006687004,1739502676.0997763,36.389965295791626,6.524872848854623,1739502676.099778,36.389965295791626,-2.641546499194468,1739502676.0997798,36.389965295791626,1.0775844906351746,1739502676.0997813,36.389965295791626,0.6108,1739502676.099783,36.389965295791626,1.0557201485989085,1739502676.0997844,36.389965295791626,0.0,1739502676.099786,36.389965295791626,0.09624419768603343,1739502676.0997877,36.389965295791626,3.3194397736166676,1739502676.0997894,36.389965295791626,0.9594759509128751 +1739502676.1196325,36.40996527671814,46.80115605675843,1739502676.1196344,36.40996527671814,8.156516462806595,1739502676.1196375,36.40996527671814,61.56054185189175,1739502676.1196404,36.40996527671814,43.81478006687004,1739502676.1196415,36.40996527671814,6.524872848854623,1739502676.1196434,36.40996527671814,-2.641546499194468,1739502676.1196449,36.40996527671814,1.0775844906351746,1739502676.1196465,36.40996527671814,0.6108,1739502676.119648,36.40996527671814,1.0557201485989085,1739502676.1196496,36.40996527671814,0.0,1739502676.1196508,36.40996527671814,0.09624419768603343,1739502676.1196523,36.40996527671814,3.3194397736166676,1739502676.119654,36.40996527671814,0.9594759509128751 +1739502676.1403165,36.42996525764465,46.80115605675843,1739502676.14032,36.42996525764465,8.156516462806595,1739502676.140324,36.42996525764465,61.56054185189175,1739502676.1403277,36.42996525764465,43.81478006687004,1739502676.1403298,36.42996525764465,6.524872848854623,1739502676.140332,36.42996525764465,-2.641546499194468,1739502676.140334,36.42996525764465,1.0775844906351746,1739502676.1403356,36.42996525764465,0.6108,1739502676.1403375,36.42996525764465,1.0557201485989085,1739502676.1403394,36.42996525764465,0.0,1739502676.1403413,36.42996525764465,0.09624419768603343,1739502676.1403437,36.42996525764465,3.3194397736166676,1739502676.1403453,36.42996525764465,0.9594759509128751 +1739502676.1601727,36.44996523857117,46.80115605675843,1739502676.1601758,36.44996523857117,8.156516462806595,1739502676.1601796,36.44996523857117,61.56054185189175,1739502676.1601832,36.44996523857117,43.81478006687004,1739502676.1601849,36.44996523857117,6.524872848854623,1739502676.1601872,36.44996523857117,-2.641546499194468,1739502676.160189,36.44996523857117,1.0775844906351746,1739502676.1601908,36.44996523857117,0.6108,1739502676.1601923,36.44996523857117,1.0557201485989085,1739502676.1601946,36.44996523857117,0.0,1739502676.160196,36.44996523857117,0.09624419768603343,1739502676.1601982,36.44996523857117,3.3194397736166676,1739502676.1601996,36.44996523857117,0.9594759509128751 +1739502676.1802726,36.46996521949768,46.80115605675843,1739502676.1802766,36.46996521949768,8.156516462806595,1739502676.1802807,36.46996521949768,61.56054185189175,1739502676.180285,36.46996521949768,43.81478006687004,1739502676.1802866,36.46996521949768,6.524872848854623,1739502676.180289,36.46996521949768,-2.641546499194468,1739502676.1802907,36.46996521949768,1.0775844906351746,1739502676.1802926,36.46996521949768,0.6108,1739502676.180294,36.46996521949768,1.0557201485989085,1739502676.1802962,36.46996521949768,0.0,1739502676.180298,36.46996521949768,0.09624419768603343,1739502676.1803002,36.46996521949768,3.3194397736166676,1739502676.1803021,36.46996521949768,0.9594759509128751 +1739502676.2002182,36.489965200424194,46.69695144645333,1739502676.2002213,36.489965200424194,8.136430541024437,1739502676.2002249,36.489965200424194,61.562249297500195,1739502676.2002285,36.489965200424194,43.80322718118541,1739502676.2002301,36.489965200424194,6.503867602155292,1739502676.2002323,36.489965200424194,-2.6279327354969975,1739502676.2002342,36.489965200424194,1.0078906556283422,1739502676.200236,36.489965200424194,0.6108,1739502676.2002375,36.489965200424194,1.1162537440906268,1739502676.2002397,36.489965200424194,0.0,1739502676.2002413,36.489965200424194,0.1681001849501392,1739502676.2002432,36.489965200424194,3.3470414625592144,1739502676.200245,36.489965200424194,0.970608569883173 +1739502676.2203023,36.50996518135071,46.69695144645333,1739502676.2203054,36.50996518135071,8.136430541024437,1739502676.220309,36.50996518135071,61.562249297500195,1739502676.2203126,36.50996518135071,43.80322718118541,1739502676.2203143,36.50996518135071,6.503867602155292,1739502676.2203166,36.50996518135071,-2.6279327354969975,1739502676.2203186,36.50996518135071,1.0078906556283422,1739502676.2203202,36.50996518135071,0.6108,1739502676.220322,36.50996518135071,1.1162537440906268,1739502676.2203238,36.50996518135071,0.0,1739502676.220326,36.50996518135071,0.14564517420745382,1739502676.2203276,36.50996518135071,3.3470414625592144,1739502676.2203295,36.50996518135071,0.970608569883173 +1739502676.240314,36.52996516227722,46.69695144645333,1739502676.2403176,36.52996516227722,8.136430541024437,1739502676.2403219,36.52996516227722,61.562249297500195,1739502676.2403257,36.52996516227722,43.80322718118541,1739502676.2403274,36.52996516227722,6.503867602155292,1739502676.2403295,36.52996516227722,-2.6279327354969975,1739502676.2403312,36.52996516227722,1.0078906556283422,1739502676.240333,36.52996516227722,0.6108,1739502676.2403345,36.52996516227722,1.1162537440906268,1739502676.240337,36.52996516227722,0.0,1739502676.240339,36.52996516227722,0.14564517420745382,1739502676.2403407,36.52996516227722,3.3470414625592144,1739502676.2403426,36.52996516227722,0.970608569883173 +1739502676.2602322,36.549965143203735,46.69695144645333,1739502676.2602355,36.549965143203735,8.136430541024437,1739502676.2602394,36.549965143203735,61.562249297500195,1739502676.260243,36.549965143203735,43.80322718118541,1739502676.2602448,36.549965143203735,6.503867602155292,1739502676.260247,36.549965143203735,-2.6279327354969975,1739502676.260249,36.549965143203735,1.0078906556283422,1739502676.2602506,36.549965143203735,0.6108,1739502676.2602522,36.549965143203735,1.1162537440906268,1739502676.2602541,36.549965143203735,0.0,1739502676.2602558,36.549965143203735,0.14564517420745382,1739502676.2602577,36.549965143203735,3.3470414625592144,1739502676.2602596,36.549965143203735,0.970608569883173 +1739502676.28029,36.56996512413025,46.69695144645333,1739502676.2802935,36.56996512413025,8.136430541024437,1739502676.2802982,36.56996512413025,61.562249297500195,1739502676.2803016,36.56996512413025,43.80322718118541,1739502676.2803035,36.56996512413025,6.503867602155292,1739502676.2803056,36.56996512413025,-2.6279327354969975,1739502676.280308,36.56996512413025,1.0078906556283422,1739502676.2803097,36.56996512413025,0.6108,1739502676.2803116,36.56996512413025,1.1162537440906268,1739502676.2803135,36.56996512413025,0.0,1739502676.2803154,36.56996512413025,0.14564517420745382,1739502676.280317,36.56996512413025,3.3470414625592144,1739502676.2803192,36.56996512413025,0.970608569883173 +1739502676.3002527,36.58996510505676,46.591946735567966,1739502676.300256,36.58996510505676,8.113166246956236,1739502676.3002596,36.58996510505676,61.95760351995722,1739502676.3002632,36.58996510505676,43.61371537293339,1739502676.300265,36.58996510505676,6.121199010716805,1739502676.300267,36.58996510505676,-2.552085326171029,1739502676.300269,36.58996510505676,1.250304749179066,1739502676.3002706,36.58996510505676,0.6108,1739502676.3002725,36.58996510505676,0.919474408343578,1739502676.3002744,36.58996510505676,0.0,1739502676.3002763,36.58996510505676,-0.16372647042330712,1739502676.300278,36.58996510505676,3.374643151501761,1739502676.30028,36.58996510505676,0.9865221764322755 +1739502676.320241,36.609965085983276,46.591946735567966,1739502676.320244,36.609965085983276,8.113166246956236,1739502676.3202481,36.609965085983276,61.95760351995722,1739502676.3202517,36.609965085983276,43.61371537293339,1739502676.3202531,36.609965085983276,6.121199010716805,1739502676.3202555,36.609965085983276,-2.552085326171029,1739502676.3202574,36.609965085983276,1.250304749179066,1739502676.3202593,36.609965085983276,0.6108,1739502676.3202608,36.609965085983276,0.919474408343578,1739502676.3202631,36.609965085983276,0.0,1739502676.320265,36.609965085983276,-0.0670477680886975,1739502676.3202667,36.609965085983276,3.374643151501761,1739502676.3202684,36.609965085983276,0.9865221764322755 +1739502676.3403246,36.62996506690979,46.591946735567966,1739502676.340328,36.62996506690979,8.113166246956236,1739502676.3403323,36.62996506690979,61.95760351995722,1739502676.340336,36.62996506690979,43.61371537293339,1739502676.3403382,36.62996506690979,6.121199010716805,1739502676.3403401,36.62996506690979,-2.552085326171029,1739502676.340342,36.62996506690979,1.250304749179066,1739502676.3403437,36.62996506690979,0.6108,1739502676.3403456,36.62996506690979,0.919474408343578,1739502676.340348,36.62996506690979,0.0,1739502676.34035,36.62996506690979,-0.0670477680886975,1739502676.3403525,36.62996506690979,3.374643151501761,1739502676.3403542,36.62996506690979,0.9865221764322755 +1739502676.3602319,36.649965047836304,46.591946735567966,1739502676.3602355,36.649965047836304,8.113166246956236,1739502676.360239,36.649965047836304,61.95760351995722,1739502676.3602426,36.649965047836304,43.61371537293339,1739502676.3602445,36.649965047836304,6.121199010716805,1739502676.360247,36.649965047836304,-2.552085326171029,1739502676.3602486,36.649965047836304,1.250304749179066,1739502676.3602505,36.649965047836304,0.6108,1739502676.3602521,36.649965047836304,0.919474408343578,1739502676.3602543,36.649965047836304,0.0,1739502676.360256,36.649965047836304,-0.0670477680886975,1739502676.3602579,36.649965047836304,3.374643151501761,1739502676.3602595,36.649965047836304,0.9865221764322755 +1739502676.3803108,36.66996502876282,46.591946735567966,1739502676.3803139,36.66996502876282,8.113166246956236,1739502676.380318,36.66996502876282,61.95760351995722,1739502676.3803215,36.66996502876282,43.61371537293339,1739502676.3803234,36.66996502876282,6.121199010716805,1739502676.3803258,36.66996502876282,-2.552085326171029,1739502676.3803277,36.66996502876282,1.250304749179066,1739502676.3803294,36.66996502876282,0.6108,1739502676.380331,36.66996502876282,0.919474408343578,1739502676.3803334,36.66996502876282,0.0,1739502676.3803349,36.66996502876282,-0.0670477680886975,1739502676.380337,36.66996502876282,3.374643151501761,1739502676.3803387,36.66996502876282,0.9865221764322755 +1739502676.4002166,36.68996500968933,46.591946735567966,1739502676.4002197,36.68996500968933,8.113166246956236,1739502676.4002237,36.68996500968933,61.95760351995722,1739502676.400227,36.68996500968933,43.61371537293339,1739502676.400229,36.68996500968933,6.121199010716805,1739502676.400231,36.68996500968933,-2.552085326171029,1739502676.4002328,36.68996500968933,1.250304749179066,1739502676.4002345,36.68996500968933,0.6108,1739502676.4002361,36.68996500968933,0.919474408343578,1739502676.400238,36.68996500968933,0.0,1739502676.4002397,36.68996500968933,-0.0670477680886975,1739502676.4002416,36.68996500968933,3.374643151501761,1739502676.4002435,36.68996500968933,0.9865221764322755 +1739502676.4204345,36.709964990615845,46.487398099349186,1739502676.4204392,36.709964990615845,8.086963012010914,1739502676.4204457,36.709964990615845,62.11549524019325,1739502676.4204526,36.709964990615845,43.56224857574762,1739502676.4204564,36.709964990615845,5.995789948591922,1739502676.4204614,36.709964990615845,-2.520940223706909,1739502676.4204657,36.709964990615845,1.2666951270831008,1739502676.4204702,36.709964990615845,0.6108,1739502676.4204745,36.709964990615845,0.9074966813246742,1739502676.4204793,36.709964990615845,0.0,1739502676.4204836,36.709964990615845,-0.06823064234150641,1739502676.420488,36.709964990615845,3.402244840444308,1739502676.4204931,36.709964990615845,0.9753576752198174 +1739502676.4418557,36.72996497154236,46.487398099349186,1739502676.4418588,36.72996497154236,8.086963012010914,1739502676.4418623,36.72996497154236,62.11549524019325,1739502676.441866,36.72996497154236,43.56224857574762,1739502676.4418676,36.72996497154236,5.995789948591922,1739502676.4418695,36.72996497154236,-2.520940223706909,1739502676.4418714,36.72996497154236,1.2666951270831008,1739502676.441873,36.72996497154236,0.6108,1739502676.4418747,36.72996497154236,0.9074966813246742,1739502676.4418764,36.72996497154236,0.0,1739502676.441878,36.72996497154236,-0.06786099389514322,1739502676.44188,36.72996497154236,3.402244840444308,1739502676.441882,36.72996497154236,0.9753576752198174 +1739502676.460308,36.74996495246887,46.487398099349186,1739502676.4603114,36.74996495246887,8.086963012010914,1739502676.460315,36.74996495246887,62.11549524019325,1739502676.4603186,36.74996495246887,43.56224857574762,1739502676.4603205,36.74996495246887,5.995789948591922,1739502676.4603226,36.74996495246887,-2.520940223706909,1739502676.4603243,36.74996495246887,1.2666951270831008,1739502676.4603262,36.74996495246887,0.6108,1739502676.4603279,36.74996495246887,0.9074966813246742,1739502676.4603302,36.74996495246887,0.0,1739502676.460332,36.74996495246887,-0.06786099389514322,1739502676.4603338,36.74996495246887,3.402244840444308,1739502676.4603353,36.74996495246887,0.9753576752198174 +1739502676.480434,36.769964933395386,46.487398099349186,1739502676.4804375,36.769964933395386,8.086963012010914,1739502676.4804423,36.769964933395386,62.11549524019325,1739502676.480446,36.769964933395386,43.56224857574762,1739502676.480448,36.769964933395386,5.995789948591922,1739502676.4804504,36.769964933395386,-2.520940223706909,1739502676.4804525,36.769964933395386,1.2666951270831008,1739502676.4804544,36.769964933395386,0.6108,1739502676.480456,36.769964933395386,0.9074966813246742,1739502676.4804583,36.769964933395386,0.0,1739502676.48046,36.769964933395386,-0.06786099389514322,1739502676.4804618,36.769964933395386,3.402244840444308,1739502676.4804635,36.769964933395386,0.9753576752198174 +1739502676.500207,36.7899649143219,46.487398099349186,1739502676.5002096,36.7899649143219,8.086963012010914,1739502676.5002139,36.7899649143219,62.11549524019325,1739502676.5002177,36.7899649143219,43.56224857574762,1739502676.5002193,36.7899649143219,5.995789948591922,1739502676.5002217,36.7899649143219,-2.520940223706909,1739502676.5002234,36.7899649143219,1.2666951270831008,1739502676.5002253,36.7899649143219,0.6108,1739502676.500227,36.7899649143219,0.9074966813246742,1739502676.5002291,36.7899649143219,0.0,1739502676.5002313,36.7899649143219,-0.06786099389514322,1739502676.500233,36.7899649143219,3.402244840444308,1739502676.5002348,36.7899649143219,0.9753576752198174 +1739502676.5202446,36.80996489524841,46.38444827017854,1739502676.5202482,36.80996489524841,8.058117936436949,1739502676.520252,36.80996489524841,62.1987829627189,1739502676.5202553,36.80996489524841,43.53743209081478,1739502676.520257,36.80996489524841,5.9320299607829785,1739502676.5202594,36.80996489524841,-2.5001570578252843,1739502676.520261,36.80996489524841,1.2290235393050624,1739502676.520263,36.80996489524841,0.6108,1739502676.5202644,36.80996489524841,0.9352624446913691,1739502676.5202665,36.80996489524841,0.0,1739502676.520268,36.80996489524841,-0.01666656919056655,1739502676.52027,36.80996489524841,3.4298465293868547,1739502676.5202718,36.80996489524841,0.9679272820913979 +1739502676.5403638,36.82996487617493,46.38444827017854,1739502676.5403671,36.82996487617493,8.058117936436949,1739502676.5403736,36.82996487617493,62.1987829627189,1739502676.5403774,36.82996487617493,43.53743209081478,1739502676.540379,36.82996487617493,5.9320299607829785,1739502676.5403817,36.82996487617493,-2.5001570578252843,1739502676.5403838,36.82996487617493,1.2290235393050624,1739502676.5403855,36.82996487617493,0.6108,1739502676.5403876,36.82996487617493,0.9352624446913691,1739502676.5403895,36.82996487617493,0.0,1739502676.540392,36.82996487617493,-0.03266483740002879,1739502676.540394,36.82996487617493,3.4298465293868547,1739502676.5403957,36.82996487617493,0.9679272820913979 +1739502676.5603824,36.84996485710144,46.38444827017854,1739502676.560386,36.84996485710144,8.058117936436949,1739502676.5603895,36.84996485710144,62.1987829627189,1739502676.5603938,36.84996485710144,43.53743209081478,1739502676.5603955,36.84996485710144,5.9320299607829785,1739502676.5603976,36.84996485710144,-2.5001570578252843,1739502676.5603993,36.84996485710144,1.2290235393050624,1739502676.5604014,36.84996485710144,0.6108,1739502676.5604029,36.84996485710144,0.9352624446913691,1739502676.560405,36.84996485710144,0.0,1739502676.5604067,36.84996485710144,-0.03266483740002879,1739502676.5604086,36.84996485710144,3.4298465293868547,1739502676.5604107,36.84996485710144,0.9679272820913979 +1739502676.5804985,36.869964838027954,46.38444827017854,1739502676.580502,36.869964838027954,8.058117936436949,1739502676.5805058,36.869964838027954,62.1987829627189,1739502676.5805094,36.869964838027954,43.53743209081478,1739502676.580511,36.869964838027954,5.9320299607829785,1739502676.580513,36.869964838027954,-2.5001570578252843,1739502676.5805151,36.869964838027954,1.2290235393050624,1739502676.580517,36.869964838027954,0.6108,1739502676.580519,36.869964838027954,0.9352624446913691,1739502676.5805209,36.869964838027954,0.0,1739502676.5805228,36.869964838027954,-0.03266483740002879,1739502676.5805247,36.869964838027954,3.4298465293868547,1739502676.5805266,36.869964838027954,0.9679272820913979 +1739502676.600218,36.88996481895447,46.38444827017854,1739502676.6002216,36.88996481895447,8.058117936436949,1739502676.6002252,36.88996481895447,62.1987829627189,1739502676.6002285,36.88996481895447,43.53743209081478,1739502676.6002305,36.88996481895447,5.9320299607829785,1739502676.6002324,36.88996481895447,-2.5001570578252843,1739502676.6002343,36.88996481895447,1.2290235393050624,1739502676.600236,36.88996481895447,0.6108,1739502676.6002376,36.88996481895447,0.9352624446913691,1739502676.6002395,36.88996481895447,0.0,1739502676.6002414,36.88996481895447,-0.03266483740002879,1739502676.6002436,36.88996481895447,3.4298465293868547,1739502676.6002452,36.88996481895447,0.9679272820913979 +1739502676.6202211,36.90996479988098,46.38444827017854,1739502676.6202254,36.90996479988098,8.058117936436949,1739502676.6202304,36.90996479988098,62.1987829627189,1739502676.6202352,36.90996479988098,43.53743209081478,1739502676.620239,36.90996479988098,5.9320299607829785,1739502676.620242,36.90996479988098,-2.5001570578252843,1739502676.6202447,36.90996479988098,1.2290235393050624,1739502676.6202476,36.90996479988098,0.6108,1739502676.6202497,36.90996479988098,0.9352624446913691,1739502676.6202524,36.90996479988098,0.0,1739502676.6202548,36.90996479988098,-0.03266483740002879,1739502676.6202576,36.90996479988098,3.4298465293868547,1739502676.62026,36.90996479988098,0.9679272820913979 +1739502676.640393,36.929964780807495,46.28290212407345,1739502676.6403968,36.929964780807495,8.026617871857878,1739502676.6404011,36.929964780807495,62.37632748007546,1739502676.6404052,36.929964780807495,43.479100465975264,1739502676.6404073,36.929964780807495,5.77128465359659,1739502676.6404097,36.929964780807495,-2.464184245953796,1739502676.6404116,36.929964780807495,1.27281963558515,1739502676.6404135,36.929964780807495,0.6108,1739502676.640415,36.929964780807495,0.9030611793933786,1739502676.6404173,36.929964780807495,0.0,1739502676.6404197,36.929964780807495,-0.07475710926469913,1739502676.6404219,36.929964780807495,3.4574482183294015,1739502676.640424,36.929964780807495,0.9646644450760363 +1739502676.6603975,36.94996476173401,46.28290212407345,1739502676.6604009,36.94996476173401,8.026617871857878,1739502676.660405,36.94996476173401,62.37632748007546,1739502676.6604083,36.94996476173401,43.479100465975264,1739502676.6604102,36.94996476173401,5.77128465359659,1739502676.6604128,36.94996476173401,-2.464184245953796,1739502676.6604145,36.94996476173401,1.27281963558515,1739502676.6604164,36.94996476173401,0.6108,1739502676.660418,36.94996476173401,0.9030611793933786,1739502676.66042,36.94996476173401,0.0,1739502676.6604218,36.94996476173401,-0.061603265682657726,1739502676.660424,36.94996476173401,3.4574482183294015,1739502676.6604257,36.94996476173401,0.9646644450760363 +1739502676.6803155,36.96996474266052,46.28290212407345,1739502676.6803184,36.96996474266052,8.026617871857878,1739502676.6803224,36.96996474266052,62.37632748007546,1739502676.680326,36.96996474266052,43.479100465975264,1739502676.6803277,36.96996474266052,5.77128465359659,1739502676.68033,36.96996474266052,-2.464184245953796,1739502676.6803317,36.96996474266052,1.27281963558515,1739502676.6803336,36.96996474266052,0.6108,1739502676.6803353,36.96996474266052,0.9030611793933786,1739502676.6803374,36.96996474266052,0.0,1739502676.680339,36.96996474266052,-0.061603265682657726,1739502676.680341,36.96996474266052,3.4574482183294015,1739502676.6803432,36.96996474266052,0.9646644450760363 +1739502676.7002158,36.989964723587036,46.28290212407345,1739502676.7002194,36.989964723587036,8.026617871857878,1739502676.7002234,36.989964723587036,62.37632748007546,1739502676.700227,36.989964723587036,43.479100465975264,1739502676.700229,36.989964723587036,5.77128465359659,1739502676.700231,36.989964723587036,-2.464184245953796,1739502676.700233,36.989964723587036,1.27281963558515,1739502676.7002347,36.989964723587036,0.6108,1739502676.7002366,36.989964723587036,0.9030611793933786,1739502676.7002387,36.989964723587036,0.0,1739502676.7002404,36.989964723587036,-0.061603265682657726,1739502676.7002423,36.989964723587036,3.4574482183294015,1739502676.700244,36.989964723587036,0.9646644450760363 +1739502676.720341,37.00996470451355,46.28290212407345,1739502676.720344,37.00996470451355,8.026617871857878,1739502676.720348,37.00996470451355,62.37632748007546,1739502676.7203515,37.00996470451355,43.479100465975264,1739502676.7203534,37.00996470451355,5.77128465359659,1739502676.7203553,37.00996470451355,-2.464184245953796,1739502676.7203572,37.00996470451355,1.27281963558515,1739502676.7203588,37.00996470451355,0.6108,1739502676.7203608,37.00996470451355,0.9030611793933786,1739502676.7203627,37.00996470451355,0.0,1739502676.7203646,37.00996470451355,-0.061603265682657726,1739502676.7203662,37.00996470451355,3.4574482183294015,1739502676.7203681,37.00996470451355,0.9646644450760363 +1739502676.740374,37.02996468544006,46.18277605395547,1739502676.7403774,37.02996468544006,7.992502727895685,1739502676.7403817,37.02996468544006,62.39211689801623,1739502676.7403853,37.02996468544006,43.47832175690139,1739502676.7403867,37.02996468544006,5.769078311220603,1739502676.7403896,37.02996468544006,-2.4535001980798077,1739502676.7403915,37.02996468544006,1.1828577908331324,1739502676.7403932,37.02996468544006,0.6108,1739502676.740395,37.02996468544006,0.9704498997942981,1739502676.740397,37.02996468544006,0.0,1739502676.740399,37.02996468544006,0.04619831492752578,1739502676.7404006,37.02996468544006,3.4850499072719483,1739502676.7404025,37.02996468544006,0.9579396008950392 +1739502676.7602592,37.04996466636658,46.18277605395547,1739502676.7602625,37.04996466636658,7.992502727895685,1739502676.7602663,37.04996466636658,62.39211689801623,1739502676.7602696,37.04996466636658,43.47832175690139,1739502676.7602713,37.04996466636658,5.769078311220603,1739502676.760274,37.04996466636658,-2.4535001980798077,1739502676.7602756,37.04996466636658,1.1828577908331324,1739502676.7602775,37.04996466636658,0.6108,1739502676.760279,37.04996466636658,0.9704498997942981,1739502676.760281,37.04996466636658,0.0,1739502676.7602825,37.04996466636658,0.01251029889925892,1739502676.7602847,37.04996466636658,3.4850499072719483,1739502676.760286,37.04996466636658,0.9579396008950392 +1739502676.7803524,37.06996464729309,46.18277605395547,1739502676.7803557,37.06996464729309,7.992502727895685,1739502676.7803597,37.06996464729309,62.39211689801623,1739502676.7803633,37.06996464729309,43.47832175690139,1739502676.780365,37.06996464729309,5.769078311220603,1739502676.7803679,37.06996464729309,-2.4535001980798077,1739502676.78037,37.06996464729309,1.1828577908331324,1739502676.7803717,37.06996464729309,0.6108,1739502676.7803733,37.06996464729309,0.9704498997942981,1739502676.7803755,37.06996464729309,0.0,1739502676.7803771,37.06996464729309,0.01251029889925892,1739502676.7803788,37.06996464729309,3.4850499072719483,1739502676.7803807,37.06996464729309,0.9579396008950392 +1739502676.8002002,37.089964628219604,46.18277605395547,1739502676.8002076,37.089964628219604,7.992502727895685,1739502676.8002138,37.089964628219604,62.39211689801623,1739502676.8002176,37.089964628219604,43.47832175690139,1739502676.80022,37.089964628219604,5.769078311220603,1739502676.8002243,37.089964628219604,-2.4535001980798077,1739502676.800228,37.089964628219604,1.1828577908331324,1739502676.800232,37.089964628219604,0.6108,1739502676.800234,37.089964628219604,0.9704498997942981,1739502676.8002365,37.089964628219604,0.0,1739502676.8002398,37.089964628219604,0.01251029889925892,1739502676.8002508,37.089964628219604,3.4850499072719483,1739502676.800255,37.089964628219604,0.9579396008950392 +1739502676.820225,37.10996460914612,46.18277605395547,1739502676.8202283,37.10996460914612,7.992502727895685,1739502676.8202324,37.10996460914612,62.39211689801623,1739502676.8202357,37.10996460914612,43.47832175690139,1739502676.8202376,37.10996460914612,5.769078311220603,1739502676.8202398,37.10996460914612,-2.4535001980798077,1739502676.8202415,37.10996460914612,1.1828577908331324,1739502676.8202431,37.10996460914612,0.6108,1739502676.820245,37.10996460914612,0.9704498997942981,1739502676.8202467,37.10996460914612,0.0,1739502676.8202486,37.10996460914612,0.01251029889925892,1739502676.8202503,37.10996460914612,3.4850499072719483,1739502676.8202522,37.10996460914612,0.9579396008950392 +1739502676.840333,37.12996459007263,46.18277605395547,1739502676.8403368,37.12996459007263,7.992502727895685,1739502676.8403413,37.12996459007263,62.39211689801623,1739502676.8403451,37.12996459007263,43.47832175690139,1739502676.8403468,37.12996459007263,5.769078311220603,1739502676.8403494,37.12996459007263,-2.4535001980798077,1739502676.8403513,37.12996459007263,1.1828577908331324,1739502676.840353,37.12996459007263,0.6108,1739502676.8403544,37.12996459007263,0.9704498997942981,1739502676.8403566,37.12996459007263,0.0,1739502676.8403587,37.12996459007263,0.01251029889925892,1739502676.8403604,37.12996459007263,3.4850499072719483,1739502676.8403625,37.12996459007263,0.9579396008950392 +1739502676.8603387,37.149964570999146,46.08388899822574,1739502676.8603423,37.149964570999146,7.9557313872645405,1739502676.860346,37.149964570999146,62.56634479225655,1739502676.8603497,37.149964570999146,43.42345768697836,1739502676.8603516,37.149964570999146,5.599449342098141,1739502676.8603537,37.149964570999146,-2.416747568419496,1739502676.8603556,37.149964570999146,1.2312435903874428,1739502676.8603573,37.149964570999146,0.6108,1739502676.8603592,37.149964570999146,0.9336028545554426,1739502676.8603609,37.149964570999146,0.0,1739502676.8603628,37.149964570999146,-0.04405375308936546,1739502676.8603644,37.149964570999146,3.512651596214495,1739502676.8603663,37.149964570999146,0.959980329808892 +1739502676.8803277,37.16996455192566,46.08388899822574,1739502676.8803313,37.16996455192566,7.9557313872645405,1739502676.8803356,37.16996455192566,62.56634479225655,1739502676.8803394,37.16996455192566,43.42345768697836,1739502676.880341,37.16996455192566,5.599449342098141,1739502676.8803432,37.16996455192566,-2.416747568419496,1739502676.8803456,37.16996455192566,1.2312435903874428,1739502676.8803475,37.16996455192566,0.6108,1739502676.880349,37.16996455192566,0.9336028545554426,1739502676.8803513,37.16996455192566,0.0,1739502676.880353,37.16996455192566,-0.026377475253449467,1739502676.880355,37.16996455192566,3.512651596214495,1739502676.8803566,37.16996455192566,0.959980329808892 +1739502676.9002414,37.18996453285217,46.08388899822574,1739502676.9002452,37.18996453285217,7.9557313872645405,1739502676.9002488,37.18996453285217,62.56634479225655,1739502676.9002523,37.18996453285217,43.42345768697836,1739502676.9002542,37.18996453285217,5.599449342098141,1739502676.9002562,37.18996453285217,-2.416747568419496,1739502676.9002583,37.18996453285217,1.2312435903874428,1739502676.9002602,37.18996453285217,0.6108,1739502676.9002616,37.18996453285217,0.9336028545554426,1739502676.900264,37.18996453285217,0.0,1739502676.9002657,37.18996453285217,-0.026377475253449467,1739502676.9002676,37.18996453285217,3.512651596214495,1739502676.9002693,37.18996453285217,0.959980329808892 +1739502676.9202838,37.20996451377869,46.08388899822574,1739502676.9202878,37.20996451377869,7.9557313872645405,1739502676.9202914,37.20996451377869,62.56634479225655,1739502676.9202952,37.20996451377869,43.42345768697836,1739502676.920297,37.20996451377869,5.599449342098141,1739502676.920299,37.20996451377869,-2.416747568419496,1739502676.9203012,37.20996451377869,1.2312435903874428,1739502676.9203029,37.20996451377869,0.6108,1739502676.9203045,37.20996451377869,0.9336028545554426,1739502676.9203067,37.20996451377869,0.0,1739502676.9203086,37.20996451377869,-0.026377475253449467,1739502676.9203105,37.20996451377869,3.512651596214495,1739502676.9203124,37.20996451377869,0.959980329808892 +1739502676.9403033,37.2299644947052,46.08388899822574,1739502676.9403062,37.2299644947052,7.9557313872645405,1739502676.9403098,37.2299644947052,62.56634479225655,1739502676.9403126,37.2299644947052,43.42345768697836,1739502676.940314,37.2299644947052,5.599449342098141,1739502676.940316,37.2299644947052,-2.416747568419496,1739502676.9403176,37.2299644947052,1.2312435903874428,1739502676.940319,37.2299644947052,0.6108,1739502676.9403205,37.2299644947052,0.9336028545554426,1739502676.9403222,37.2299644947052,0.0,1739502676.9403236,37.2299644947052,-0.026377475253449467,1739502676.940325,37.2299644947052,3.512651596214495,1739502676.9403267,37.2299644947052,0.959980329808892 +1739502676.9596524,37.249964475631714,45.98609488572707,1739502676.9596543,37.249964475631714,7.9162626056146355,1739502676.9596574,37.249964475631714,62.69518662100846,1739502676.95966,37.249964475631714,43.389349328072605,1739502676.9596615,37.249964475631714,5.481163147267715,1739502676.9596632,37.249964475631714,-2.3883080643229615,1739502676.9596643,37.249964475631714,1.2361272064192776,1739502676.9596658,37.249964475631714,0.6108,1739502676.959667,37.249964475631714,0.9299624841601262,1739502676.9596684,37.249964475631714,0.0,1739502676.9596698,37.249964475631714,-0.02751522903594989,1739502676.9596713,37.249964475631714,3.540253285157042,1739502676.9596727,37.249964475631714,0.957122164905929 +1739502676.979701,37.26996445655823,45.98609488572707,1739502676.9797032,37.26996445655823,7.9162626056146355,1739502676.979706,37.26996445655823,62.69518662100846,1739502676.979709,37.26996445655823,43.389349328072605,1739502676.97971,37.26996445655823,5.481163147267715,1739502676.9797118,37.26996445655823,-2.3883080643229615,1739502676.9797132,37.26996445655823,1.2361272064192776,1739502676.9797146,37.26996445655823,0.6108,1739502676.9797158,37.26996445655823,0.9299624841601262,1739502676.9797175,37.26996445655823,0.0,1739502676.9797187,37.26996445655823,-0.027159680745802883,1739502676.97972,37.26996445655823,3.540253285157042,1739502676.9797215,37.26996445655823,0.957122164905929 +1739502676.9997678,37.28996443748474,45.98609488572707,1739502676.9997704,37.28996443748474,7.9162626056146355,1739502676.9997745,37.28996443748474,62.69518662100846,1739502676.9997773,37.28996443748474,43.389349328072605,1739502676.9997785,37.28996443748474,5.481163147267715,1739502676.9997804,37.28996443748474,-2.3883080643229615,1739502676.9997816,37.28996443748474,1.2361272064192776,1739502676.9997833,37.28996443748474,0.6108,1739502676.9997845,37.28996443748474,0.9299624841601262,1739502676.999786,37.28996443748474,0.0,1739502676.9997873,37.28996443748474,-0.027159680745802883,1739502676.9997888,37.28996443748474,3.540253285157042,1739502676.9997902,37.28996443748474,0.957122164905929 +1739502677.0195487,37.309964418411255,45.98609488572707,1739502677.0195508,37.309964418411255,7.9162626056146355,1739502677.019554,37.309964418411255,62.69518662100846,1739502677.0195563,37.309964418411255,43.389349328072605,1739502677.0195577,37.309964418411255,5.481163147267715,1739502677.0195591,37.309964418411255,-2.3883080643229615,1739502677.019561,37.309964418411255,1.2361272064192776,1739502677.0195622,37.309964418411255,0.6108,1739502677.0195634,37.309964418411255,0.9299624841601262,1739502677.0195649,37.309964418411255,0.0,1739502677.019566,37.309964418411255,-0.027159680745802883,1739502677.0195677,37.309964418411255,3.540253285157042,1739502677.019569,37.309964418411255,0.957122164905929 +1739502677.0396786,37.32996439933777,45.98609488572707,1739502677.039681,37.32996439933777,7.9162626056146355,1739502677.0396838,37.32996439933777,62.69518662100846,1739502677.0396864,37.32996439933777,43.389349328072605,1739502677.0396876,37.32996439933777,5.481163147267715,1739502677.0396893,37.32996439933777,-2.3883080643229615,1739502677.0396905,37.32996439933777,1.2361272064192776,1739502677.039692,37.32996439933777,0.6108,1739502677.039693,37.32996439933777,0.9299624841601262,1739502677.0396945,37.32996439933777,0.0,1739502677.039696,37.32996439933777,-0.027159680745802883,1739502677.0396972,37.32996439933777,3.540253285157042,1739502677.0396984,37.32996439933777,0.957122164905929 +1739502677.059578,37.34996438026428,45.98609488572707,1739502677.0595798,37.34996438026428,7.9162626056146355,1739502677.0595827,37.34996438026428,62.69518662100846,1739502677.059585,37.34996438026428,43.389349328072605,1739502677.0595865,37.34996438026428,5.481163147267715,1739502677.0595882,37.34996438026428,-2.3883080643229615,1739502677.0595894,37.34996438026428,1.2361272064192776,1739502677.0595908,37.34996438026428,0.6108,1739502677.059592,37.34996438026428,0.9299624841601262,1739502677.0595934,37.34996438026428,0.0,1739502677.059595,37.34996438026428,-0.027159680745802883,1739502677.0595963,37.34996438026428,3.540253285157042,1739502677.0595975,37.34996438026428,0.957122164905929 +1739502677.0797997,37.369964361190796,45.88972796501033,1739502677.0798018,37.369964361190796,7.874241008266301,1739502677.0798047,37.369964361190796,62.860767112777395,1739502677.079807,37.369964361190796,43.348748081030486,1739502677.0798082,37.369964361190796,5.3268053038643135,1739502677.0798101,37.369964361190796,-2.354925761872872,1739502677.0798113,37.369964361190796,1.2688646942390691,1739502677.0798125,37.369964361190796,0.6108,1739502677.079814,37.369964361190796,0.9059229474531123,1739502677.0798154,37.369964361190796,0.0,1739502677.0798168,37.369964361190796,-0.057785452156010615,1739502677.079818,37.369964361190796,3.5678549740995886,1739502677.0798192,37.369964361190796,0.954137839768485 +1739502677.0997696,37.38996434211731,45.88972796501033,1739502677.0997722,37.38996434211731,7.874241008266301,1739502677.0997753,37.38996434211731,62.860767112777395,1739502677.0997777,37.38996434211731,43.348748081030486,1739502677.0997791,37.38996434211731,5.3268053038643135,1739502677.0997808,37.38996434211731,-2.354925761872872,1739502677.0997822,37.38996434211731,1.2688646942390691,1739502677.0997834,37.38996434211731,0.6108,1739502677.0997846,37.38996434211731,0.9059229474531123,1739502677.0997863,37.38996434211731,0.0,1739502677.0997872,37.38996434211731,-0.04821489231537268,1739502677.0997891,37.38996434211731,3.5678549740995886,1739502677.09979,37.38996434211731,0.954137839768485 +1739502677.1195667,37.40996432304382,45.88972796501033,1739502677.1195686,37.40996432304382,7.874241008266301,1739502677.1195712,37.40996432304382,62.860767112777395,1739502677.1195738,37.40996432304382,43.348748081030486,1739502677.1195755,37.40996432304382,5.3268053038643135,1739502677.1195772,37.40996432304382,-2.354925761872872,1739502677.1195784,37.40996432304382,1.2688646942390691,1739502677.1195796,37.40996432304382,0.6108,1739502677.1195807,37.40996432304382,0.9059229474531123,1739502677.1195822,37.40996432304382,0.0,1739502677.1195836,37.40996432304382,-0.04821489231537268,1739502677.1195848,37.40996432304382,3.5678549740995886,1739502677.119586,37.40996432304382,0.954137839768485 +1739502677.1401262,37.42996430397034,45.88972796501033,1739502677.1401289,37.42996430397034,7.874241008266301,1739502677.1401322,37.42996430397034,62.860767112777395,1739502677.1401355,37.42996430397034,43.348748081030486,1739502677.140137,37.42996430397034,5.3268053038643135,1739502677.140139,37.42996430397034,-2.354925761872872,1739502677.1401405,37.42996430397034,1.2688646942390691,1739502677.140142,37.42996430397034,0.6108,1739502677.1401436,37.42996430397034,0.9059229474531123,1739502677.1401453,37.42996430397034,0.0,1739502677.140147,37.42996430397034,-0.04821489231537268,1739502677.1401484,37.42996430397034,3.5678549740995886,1739502677.14015,37.42996430397034,0.954137839768485 +1739502677.159864,37.44996428489685,45.88972796501033,1739502677.1598666,37.44996428489685,7.874241008266301,1739502677.15987,37.44996428489685,62.860767112777395,1739502677.159873,37.44996428489685,43.348748081030486,1739502677.159875,37.44996428489685,5.3268053038643135,1739502677.1598766,37.44996428489685,-2.354925761872872,1739502677.1598783,37.44996428489685,1.2688646942390691,1739502677.1598802,37.44996428489685,0.6108,1739502677.1598814,37.44996428489685,0.9059229474531123,1739502677.1598833,37.44996428489685,0.0,1739502677.1598847,37.44996428489685,-0.04821489231537268,1739502677.1598866,37.44996428489685,3.5678549740995886,1739502677.159888,37.44996428489685,0.954137839768485 +1739502677.180181,37.469964265823364,45.794953885458895,1739502677.180184,37.469964265823364,7.829762577743626,1739502677.1801875,37.469964265823364,62.94891159316861,1739502677.1801908,37.469964265823364,43.33141842798152,1739502677.1801922,37.469964265823364,5.251154557357217,1739502677.1801944,37.469964265823364,-2.333376299651488,1739502677.180196,37.469964265823364,1.237432439340549,1739502677.1801977,37.469964265823364,0.6108,1739502677.1801994,37.469964265823364,0.9289919368445353,1739502677.1802013,37.469964265823364,0.0,1739502677.1802025,37.469964265823364,-0.007002524481241959,1739502677.1802044,37.469964265823364,3.5954566630421354,1739502677.180206,37.469964265823364,0.9488733347179905 +1739502677.1998608,37.48996424674988,45.794953885458895,1739502677.199863,37.48996424674988,7.829762577743626,1739502677.1998663,37.48996424674988,62.94891159316861,1739502677.1998694,37.48996424674988,43.33141842798152,1739502677.199871,37.48996424674988,5.251154557357217,1739502677.1998732,37.48996424674988,-2.333376299651488,1739502677.1998749,37.48996424674988,1.237432439340549,1739502677.1998763,37.48996424674988,0.6108,1739502677.199878,37.48996424674988,0.9289919368445353,1739502677.1998796,37.48996424674988,0.0,1739502677.199881,37.48996424674988,-0.01988139787345522,1739502677.1998825,37.48996424674988,3.5954566630421354,1739502677.199884,37.48996424674988,0.9488733347179905 +1739502677.2199578,37.50996422767639,45.794953885458895,1739502677.2199602,37.50996422767639,7.829762577743626,1739502677.2199636,37.50996422767639,62.94891159316861,1739502677.2199667,37.50996422767639,43.33141842798152,1739502677.2199683,37.50996422767639,5.251154557357217,1739502677.21997,37.50996422767639,-2.333376299651488,1739502677.2199717,37.50996422767639,1.237432439340549,1739502677.219973,37.50996422767639,0.6108,1739502677.2199748,37.50996422767639,0.9289919368445353,1739502677.2199762,37.50996422767639,0.0,1739502677.2199776,37.50996422767639,-0.01988139787345522,1739502677.2199793,37.50996422767639,3.5954566630421354,1739502677.219981,37.50996422767639,0.9488733347179905 +1739502677.2401152,37.529964208602905,45.794953885458895,1739502677.2401183,37.529964208602905,7.829762577743626,1739502677.2401216,37.529964208602905,62.94891159316861,1739502677.240125,37.529964208602905,43.33141842798152,1739502677.2401264,37.529964208602905,5.251154557357217,1739502677.2401285,37.529964208602905,-2.333376299651488,1739502677.24013,37.529964208602905,1.237432439340549,1739502677.2401316,37.529964208602905,0.6108,1739502677.240133,37.529964208602905,0.9289919368445353,1739502677.240135,37.529964208602905,0.0,1739502677.2401364,37.529964208602905,-0.01988139787345522,1739502677.240138,37.529964208602905,3.5954566630421354,1739502677.2401397,37.529964208602905,0.9488733347179905 +1739502677.2598574,37.54996418952942,45.794953885458895,1739502677.25986,37.54996418952942,7.829762577743626,1739502677.2598634,37.54996418952942,62.94891159316861,1739502677.2598665,37.54996418952942,43.33141842798152,1739502677.259868,37.54996418952942,5.251154557357217,1739502677.2598698,37.54996418952942,-2.333376299651488,1739502677.2598715,37.54996418952942,1.237432439340549,1739502677.259873,37.54996418952942,0.6108,1739502677.2598743,37.54996418952942,0.9289919368445353,1739502677.259876,37.54996418952942,0.0,1739502677.2598777,37.54996418952942,-0.01988139787345522,1739502677.259879,37.54996418952942,3.5954566630421354,1739502677.2598808,37.54996418952942,0.9488733347179905 +1739502677.2801123,37.56996417045593,45.794953885458895,1739502677.2801151,37.56996417045593,7.829762577743626,1739502677.2801187,37.56996417045593,62.94891159316861,1739502677.280122,37.56996417045593,43.33141842798152,1739502677.2801237,37.56996417045593,5.251154557357217,1739502677.2801254,37.56996417045593,-2.333376299651488,1739502677.2801273,37.56996417045593,1.237432439340549,1739502677.2801287,37.56996417045593,0.6108,1739502677.2801304,37.56996417045593,0.9289919368445353,1739502677.280132,37.56996417045593,0.0,1739502677.2801337,37.56996417045593,-0.01988139787345522,1739502677.2801356,37.56996417045593,3.5954566630421354,1739502677.2801373,37.56996417045593,0.9488733347179905 +1739502677.2999742,37.589964151382446,45.70180478487369,1739502677.2999766,37.589964151382446,7.782866474232145,1739502677.29998,37.589964151382446,63.03877323825347,1739502677.299983,37.589964151382446,43.313209495600745,1739502677.2999847,37.589964151382446,5.167092170988236,1739502677.2999866,37.589964151382446,-2.3108295056600836,1739502677.2999883,37.589964151382446,1.2122978911748021,1739502677.2999897,37.589964151382446,0.6108,1739502677.2999914,37.589964151382446,0.9478608397019519,1739502677.299993,37.589964151382446,0.0,1739502677.2999945,37.589964151382446,0.010362154629471567,1739502677.299996,37.589964151382446,3.623058351984682,1739502677.2999973,37.589964151382446,0.9469498014262797 +1739502677.3199475,37.60996413230896,45.70180478487369,1739502677.3199506,37.60996413230896,7.782866474232145,1739502677.319954,37.60996413230896,63.03877323825347,1739502677.319957,37.60996413230896,43.313209495600745,1739502677.3199584,37.60996413230896,5.167092170988236,1739502677.3199604,37.60996413230896,-2.3108295056600836,1739502677.319962,37.60996413230896,1.2122978911748021,1739502677.3199637,37.60996413230896,0.6108,1739502677.319965,37.60996413230896,0.9478608397019519,1739502677.3199668,37.60996413230896,0.0,1739502677.3199682,37.60996413230896,0.0009110382756721824,1739502677.31997,37.60996413230896,3.623058351984682,1739502677.3199716,37.60996413230896,0.9469498014262797 +1739502677.3401675,37.629964113235474,45.70180478487369,1739502677.3401704,37.629964113235474,7.782866474232145,1739502677.3401742,37.629964113235474,63.03877323825347,1739502677.3401778,37.629964113235474,43.313209495600745,1739502677.3401794,37.629964113235474,5.167092170988236,1739502677.3401816,37.629964113235474,-2.3108295056600836,1739502677.340183,37.629964113235474,1.2122978911748021,1739502677.340185,37.629964113235474,0.6108,1739502677.3401864,37.629964113235474,0.9478608397019519,1739502677.3401883,37.629964113235474,0.0,1739502677.3401897,37.629964113235474,0.0009110382756721824,1739502677.3401916,37.629964113235474,3.623058351984682,1739502677.340193,37.629964113235474,0.9469498014262797 +1739502677.3598816,37.64996409416199,45.70180478487369,1739502677.3598845,37.64996409416199,7.782866474232145,1739502677.3598876,37.64996409416199,63.03877323825347,1739502677.3598907,37.64996409416199,43.313209495600745,1739502677.3598921,37.64996409416199,5.167092170988236,1739502677.3598943,37.64996409416199,-2.3108295056600836,1739502677.3598957,37.64996409416199,1.2122978911748021,1739502677.3598974,37.64996409416199,0.6108,1739502677.3598988,37.64996409416199,0.9478608397019519,1739502677.3599007,37.64996409416199,0.0,1739502677.3599021,37.64996409416199,0.0009110382756721824,1739502677.3599038,37.64996409416199,3.623058351984682,1739502677.3599052,37.64996409416199,0.9469498014262797 +1739502677.3800929,37.6699640750885,45.70180478487369,1739502677.380096,37.6699640750885,7.782866474232145,1739502677.3800993,37.6699640750885,63.03877323825347,1739502677.3801024,37.6699640750885,43.313209495600745,1739502677.3801038,37.6699640750885,5.167092170988236,1739502677.3801057,37.6699640750885,-2.3108295056600836,1739502677.3801074,37.6699640750885,1.2122978911748021,1739502677.380109,37.6699640750885,0.6108,1739502677.3801105,37.6699640750885,0.9478608397019519,1739502677.3801124,37.6699640750885,0.0,1739502677.3801136,37.6699640750885,0.0009110382756721824,1739502677.3801155,37.6699640750885,3.623058351984682,1739502677.380117,37.6699640750885,0.9469498014262797 +1739502677.4003246,37.689964056015015,45.61009698857563,1739502677.4003272,37.689964056015015,7.733476951042066,1739502677.4003305,37.689964056015015,63.20649040184432,1739502677.4003336,37.689964056015015,43.28071436478042,1739502677.400335,37.689964056015015,5.002388161727871,1739502677.4003372,37.689964056015015,-2.276979424613886,1739502677.4003386,37.689964056015015,1.24952997333673,1739502677.4003403,37.689964056015015,0.6108,1739502677.4003415,37.689964056015015,0.9200444942482262,1739502677.4003432,37.689964056015015,0.0,1739502677.4003448,37.689964056015015,-0.03966927116711755,1739502677.4003463,37.689964056015015,3.650660040927229,1739502677.400348,37.689964056015015,0.9470324103999277 +1739502677.420406,37.70996403694153,45.61009698857563,1739502677.4204087,37.70996403694153,7.733476951042066,1739502677.420412,37.70996403694153,63.20649040184432,1739502677.4204152,37.70996403694153,43.28071436478042,1739502677.4204168,37.70996403694153,5.002388161727871,1739502677.420419,37.70996403694153,-2.276979424613886,1739502677.4204204,37.70996403694153,1.24952997333673,1739502677.420422,37.70996403694153,0.6108,1739502677.4204235,37.70996403694153,0.9200444942482262,1739502677.4204252,37.70996403694153,0.0,1739502677.4204266,37.70996403694153,-0.026987916151701485,1739502677.4204283,37.70996403694153,3.650660040927229,1739502677.4204297,37.70996403694153,0.9470324103999277 +1739502677.440139,37.72996401786804,45.61009698857563,1739502677.4401422,37.72996401786804,7.733476951042066,1739502677.440146,37.72996401786804,63.20649040184432,1739502677.440149,37.72996401786804,43.28071436478042,1739502677.4401505,37.72996401786804,5.002388161727871,1739502677.440153,37.72996401786804,-2.276979424613886,1739502677.4401543,37.72996401786804,1.24952997333673,1739502677.440156,37.72996401786804,0.6108,1739502677.4401572,37.72996401786804,0.9200444942482262,1739502677.440159,37.72996401786804,0.0,1739502677.4401605,37.72996401786804,-0.026987916151701485,1739502677.4401627,37.72996401786804,3.650660040927229,1739502677.4401639,37.72996401786804,0.9470324103999277 +1739502677.4598315,37.749963998794556,45.61009698857563,1739502677.459834,37.749963998794556,7.733476951042066,1739502677.4598374,37.749963998794556,63.20649040184432,1739502677.4598405,37.749963998794556,43.28071436478042,1739502677.4598422,37.749963998794556,5.002388161727871,1739502677.459844,37.749963998794556,-2.276979424613886,1739502677.4598455,37.749963998794556,1.24952997333673,1739502677.4598472,37.749963998794556,0.6108,1739502677.4598484,37.749963998794556,0.9200444942482262,1739502677.4598503,37.749963998794556,0.0,1739502677.4598517,37.749963998794556,-0.026987916151701485,1739502677.4598536,37.749963998794556,3.650660040927229,1739502677.459855,37.749963998794556,0.9470324103999277 +1739502677.4802566,37.76996397972107,45.61009698857563,1739502677.4802597,37.76996397972107,7.733476951042066,1739502677.4802632,37.76996397972107,63.20649040184432,1739502677.4802663,37.76996397972107,43.28071436478042,1739502677.4802682,37.76996397972107,5.002388161727871,1739502677.4802701,37.76996397972107,-2.276979424613886,1739502677.4802718,37.76996397972107,1.24952997333673,1739502677.4802735,37.76996397972107,0.6108,1739502677.480275,37.76996397972107,0.9200444942482262,1739502677.4802768,37.76996397972107,0.0,1739502677.480278,37.76996397972107,-0.026987916151701485,1739502677.48028,37.76996397972107,3.650660040927229,1739502677.4802814,37.76996397972107,0.9470324103999277 +1739502677.4998257,37.78996396064758,45.61009698857563,1739502677.4998279,37.78996396064758,7.733476951042066,1739502677.4998312,37.78996396064758,63.20649040184432,1739502677.4998343,37.78996396064758,43.28071436478042,1739502677.499836,37.78996396064758,5.002388161727871,1739502677.4998376,37.78996396064758,-2.276979424613886,1739502677.4998393,37.78996396064758,1.24952997333673,1739502677.4998407,37.78996396064758,0.6108,1739502677.4998424,37.78996396064758,0.9200444942482262,1739502677.4998438,37.78996396064758,0.0,1739502677.4998453,37.78996396064758,-0.026987916151701485,1739502677.499847,37.78996396064758,3.650660040927229,1739502677.4998484,37.78996396064758,0.9470324103999277 +1739502677.5199118,37.8099639415741,45.519928516168946,1739502677.5199142,37.8099639415741,7.68165745952173,1739502677.5199175,37.8099639415741,63.23935091550466,1739502677.5199206,37.8099639415741,43.27566783834843,1739502677.5199223,37.8099639415741,4.976434597220501,1739502677.5199242,37.8099639415741,-2.2633289810494537,1739502677.5199256,37.8099639415741,1.1774760449222392,1739502677.519927,37.8099639415741,0.6108,1739502677.5199287,37.8099639415741,0.9746370788838833,1739502677.5199301,37.8099639415741,0.0,1739502677.5199316,37.8099639415741,0.05708922586142293,1739502677.5199332,37.8099639415741,3.6782617298697757,1739502677.5199347,37.8099639415741,0.9438219771282199 +1739502677.5402641,37.82996392250061,45.519928516168946,1739502677.5402687,37.82996392250061,7.68165745952173,1739502677.5402727,37.82996392250061,63.23935091550466,1739502677.5402763,37.82996392250061,43.27566783834843,1739502677.540278,37.82996392250061,4.976434597220501,1739502677.5402803,37.82996392250061,-2.2633289810494537,1739502677.540282,37.82996392250061,1.1774760449222392,1739502677.540284,37.82996392250061,0.6108,1739502677.5402856,37.82996392250061,0.9746370788838833,1739502677.5402877,37.82996392250061,0.0,1739502677.5402892,37.82996392250061,0.030815101755663377,1739502677.5402913,37.82996392250061,3.6782617298697757,1739502677.5402932,37.82996392250061,0.9438219771282199 +1739502677.5603395,37.849963903427124,45.519928516168946,1739502677.5603428,37.849963903427124,7.68165745952173,1739502677.5603464,37.849963903427124,63.23935091550466,1739502677.56035,37.849963903427124,43.27566783834843,1739502677.5603514,37.849963903427124,4.976434597220501,1739502677.560354,37.849963903427124,-2.2633289810494537,1739502677.5603561,37.849963903427124,1.1774760449222392,1739502677.5603576,37.849963903427124,0.6108,1739502677.5603595,37.849963903427124,0.9746370788838833,1739502677.5603611,37.849963903427124,0.0,1739502677.560363,37.849963903427124,0.030815101755663377,1739502677.5603647,37.849963903427124,3.6782617298697757,1739502677.5603666,37.849963903427124,0.9438219771282199 +1739502677.5804234,37.86996388435364,45.519928516168946,1739502677.5804267,37.86996388435364,7.68165745952173,1739502677.5804305,37.86996388435364,63.23935091550466,1739502677.580434,37.86996388435364,43.27566783834843,1739502677.580436,37.86996388435364,4.976434597220501,1739502677.580438,37.86996388435364,-2.2633289810494537,1739502677.5804398,37.86996388435364,1.1774760449222392,1739502677.5804417,37.86996388435364,0.6108,1739502677.5804434,37.86996388435364,0.9746370788838833,1739502677.5804455,37.86996388435364,0.0,1739502677.580447,37.86996388435364,0.030815101755663377,1739502677.5804489,37.86996388435364,3.6782617298697757,1739502677.5804508,37.86996388435364,0.9438219771282199 +1739502677.6001403,37.88996386528015,45.519928516168946,1739502677.6001437,37.88996386528015,7.68165745952173,1739502677.6001475,37.88996386528015,63.23935091550466,1739502677.6001508,37.88996386528015,43.27566783834843,1739502677.6001527,37.88996386528015,4.976434597220501,1739502677.6001549,37.88996386528015,-2.2633289810494537,1739502677.6001568,37.88996386528015,1.1774760449222392,1739502677.6001582,37.88996386528015,0.6108,1739502677.6001596,37.88996386528015,0.9746370788838833,1739502677.6001618,37.88996386528015,0.0,1739502677.6001632,37.88996386528015,0.030815101755663377,1739502677.6001651,37.88996386528015,3.6782617298697757,1739502677.6001668,37.88996386528015,0.9438219771282199 +1739502677.620377,37.909963846206665,45.43124648190866,1739502677.6203804,37.909963846206665,7.627380671245348,1739502677.6203842,37.909963846206665,63.447489784512214,1739502677.620388,37.909963846206665,43.23603616667843,1739502677.62039,37.909963846206665,4.765328857203361,1739502677.6203918,37.909963846206665,-2.2250926004304383,1739502677.6203938,37.909963846206665,1.2443751912192806,1739502677.6203954,37.909963846206665,0.6108,1739502677.620397,37.909963846206665,0.9238464312479788,1739502677.6203988,37.909963846206665,0.0,1739502677.6204007,37.909963846206665,-0.047903766700485725,1739502677.6204023,37.909963846206665,3.7058634188123225,1739502677.620404,37.909963846206665,0.9471505354271224 +1739502677.6402447,37.92996382713318,45.43124648190866,1739502677.6402483,37.92996382713318,7.627380671245348,1739502677.6402524,37.92996382713318,63.447489784512214,1739502677.6402557,37.92996382713318,43.23603616667843,1739502677.6402578,37.92996382713318,4.765328857203361,1739502677.6402597,37.92996382713318,-2.2250926004304383,1739502677.6402617,37.92996382713318,1.2443751912192806,1739502677.640263,37.92996382713318,0.6108,1739502677.6402647,37.92996382713318,0.9238464312479788,1739502677.6402667,37.92996382713318,0.0,1739502677.6402683,37.92996382713318,-0.023304104179143525,1739502677.64027,37.92996382713318,3.7058634188123225,1739502677.640272,37.92996382713318,0.9471505354271224 +1739502677.6603105,37.94996380805969,45.43124648190866,1739502677.660314,37.94996380805969,7.627380671245348,1739502677.6603177,37.94996380805969,63.447489784512214,1739502677.660321,37.94996380805969,43.23603616667843,1739502677.660323,37.94996380805969,4.765328857203361,1739502677.6603248,37.94996380805969,-2.2250926004304383,1739502677.6603265,37.94996380805969,1.2443751912192806,1739502677.6603281,37.94996380805969,0.6108,1739502677.6603298,37.94996380805969,0.9238464312479788,1739502677.6603317,37.94996380805969,0.0,1739502677.6603334,37.94996380805969,-0.023304104179143525,1739502677.660335,37.94996380805969,3.7058634188123225,1739502677.660337,37.94996380805969,0.9471505354271224 +1739502677.680254,37.969963788986206,45.43124648190866,1739502677.680257,37.969963788986206,7.627380671245348,1739502677.6802611,37.969963788986206,63.447489784512214,1739502677.6802647,37.969963788986206,43.23603616667843,1739502677.6802664,37.969963788986206,4.765328857203361,1739502677.6802685,37.969963788986206,-2.2250926004304383,1739502677.680271,37.969963788986206,1.2443751912192806,1739502677.6802726,37.969963788986206,0.6108,1739502677.6802742,37.969963788986206,0.9238464312479788,1739502677.6802764,37.969963788986206,0.0,1739502677.680278,37.969963788986206,-0.023304104179143525,1739502677.6802797,37.969963788986206,3.7058634188123225,1739502677.6802819,37.969963788986206,0.9471505354271224 +1739502677.7003586,37.98996376991272,45.43124648190866,1739502677.700362,37.98996376991272,7.627380671245348,1739502677.7003658,37.98996376991272,63.447489784512214,1739502677.7003694,37.98996376991272,43.23603616667843,1739502677.7003713,37.98996376991272,4.765328857203361,1739502677.7003736,37.98996376991272,-2.2250926004304383,1739502677.7003756,37.98996376991272,1.2443751912192806,1739502677.7003772,37.98996376991272,0.6108,1739502677.700379,37.98996376991272,0.9238464312479788,1739502677.700381,37.98996376991272,0.0,1739502677.7003825,37.98996376991272,-0.023304104179143525,1739502677.7003841,37.98996376991272,3.7058634188123225,1739502677.700386,37.98996376991272,0.9471505354271224 +1739502677.7204614,38.00996375083923,45.43124648190866,1739502677.7204645,38.00996375083923,7.627380671245348,1739502677.720468,38.00996375083923,63.447489784512214,1739502677.7204714,38.00996375083923,43.23603616667843,1739502677.720473,38.00996375083923,4.765328857203361,1739502677.7204752,38.00996375083923,-2.2250926004304383,1739502677.7204769,38.00996375083923,1.2443751912192806,1739502677.7204788,38.00996375083923,0.6108,1739502677.7204802,38.00996375083923,0.9238464312479788,1739502677.7204823,38.00996375083923,0.0,1739502677.7204838,38.00996375083923,-0.023304104179143525,1739502677.7204857,38.00996375083923,3.7058634188123225,1739502677.720487,38.00996375083923,0.9471505354271224 +1739502677.7403598,38.02996373176575,45.3440656423518,1739502677.7403626,38.02996373176575,7.5706591912697245,1739502677.7403662,38.02996373176575,63.54991490345318,1739502677.74037,38.02996373176575,43.21861586850282,1739502677.7403717,38.02996373176575,4.670582636092972,1739502677.740374,38.02996373176575,-2.2032596476551403,1739502677.7403755,38.02996373176575,1.220943855097649,1739502677.740378,38.02996373176575,0.6108,1739502677.7403796,38.02996373176575,0.9413273246647823,1739502677.7403817,38.02996373176575,0.0,1739502677.7403831,38.02996373176575,0.006549447143333295,1739502677.7403855,38.02996373176575,3.7334651077548693,1739502677.740387,38.02996373176575,0.94410711842645 +1739502677.760317,38.04996371269226,45.3440656423518,1739502677.7603207,38.04996371269226,7.5706591912697245,1739502677.7603242,38.04996371269226,63.54991490345318,1739502677.760328,38.04996371269226,43.21861586850282,1739502677.7603295,38.04996371269226,4.670582636092972,1739502677.7603319,38.04996371269226,-2.2032596476551403,1739502677.7603335,38.04996371269226,1.220943855097649,1739502677.7603352,38.04996371269226,0.6108,1739502677.7603369,38.04996371269226,0.9413273246647823,1739502677.7603388,38.04996371269226,0.0,1739502677.7603405,38.04996371269226,-0.0027797937616677038,1739502677.7603421,38.04996371269226,3.7334651077548693,1739502677.7603443,38.04996371269226,0.94410711842645 +1739502677.7805278,38.069963693618774,45.3440656423518,1739502677.7805312,38.069963693618774,7.5706591912697245,1739502677.7805352,38.069963693618774,63.54991490345318,1739502677.7805386,38.069963693618774,43.21861586850282,1739502677.7805405,38.069963693618774,4.670582636092972,1739502677.780543,38.069963693618774,-2.2032596476551403,1739502677.7805448,38.069963693618774,1.220943855097649,1739502677.7805467,38.069963693618774,0.6108,1739502677.7805483,38.069963693618774,0.9413273246647823,1739502677.7805505,38.069963693618774,0.0,1739502677.7805521,38.069963693618774,-0.0027797937616677038,1739502677.780554,38.069963693618774,3.7334651077548693,1739502677.7805557,38.069963693618774,0.94410711842645 +1739502677.8003547,38.08996367454529,45.3440656423518,1739502677.8003578,38.08996367454529,7.5706591912697245,1739502677.8003614,38.08996367454529,63.54991490345318,1739502677.800365,38.08996367454529,43.21861586850282,1739502677.8003669,38.08996367454529,4.670582636092972,1739502677.8003688,38.08996367454529,-2.2032596476551403,1739502677.8003707,38.08996367454529,1.220943855097649,1739502677.8003724,38.08996367454529,0.6108,1739502677.800374,38.08996367454529,0.9413273246647823,1739502677.8003762,38.08996367454529,0.0,1739502677.8003776,38.08996367454529,-0.0027797937616677038,1739502677.8003793,38.08996367454529,3.7334651077548693,1739502677.8003812,38.08996367454529,0.94410711842645 +1739502677.8203034,38.1099636554718,45.3440656423518,1739502677.820307,38.1099636554718,7.5706591912697245,1739502677.8203106,38.1099636554718,63.54991490345318,1739502677.820314,38.1099636554718,43.21861586850282,1739502677.8203156,38.1099636554718,4.670582636092972,1739502677.820318,38.1099636554718,-2.2032596476551403,1739502677.8203197,38.1099636554718,1.220943855097649,1739502677.8203213,38.1099636554718,0.6108,1739502677.8203228,38.1099636554718,0.9413273246647823,1739502677.820325,38.1099636554718,0.0,1739502677.8203263,38.1099636554718,-0.0027797937616677038,1739502677.8203282,38.1099636554718,3.7334651077548693,1739502677.82033,38.1099636554718,0.94410711842645 +1739502677.8403723,38.129963636398315,45.25863187194749,1739502677.840376,38.129963636398315,7.51165499189019,1739502677.8403795,38.129963636398315,63.63700024849922,1739502677.840383,38.129963636398315,43.2029795266888,1739502677.8403847,38.129963636398315,4.585567806254605,1739502677.8403873,38.129963636398315,-2.1832155864961202,1739502677.840389,38.129963636398315,1.188846694152971,1739502677.8403907,38.129963636398315,0.6108,1739502677.8403924,38.129963636398315,0.9658114757950209,1739502677.8403943,38.129963636398315,0.0,1739502677.840396,38.129963636398315,0.03330041067586707,1739502677.8403978,38.129963636398315,3.761066796697416,1739502677.8403995,38.129963636398315,0.9437861363983963 +1739502677.860163,38.14996361732483,45.25863187194749,1739502677.8601663,38.14996361732483,7.51165499189019,1739502677.8601701,38.14996361732483,63.63700024849922,1739502677.860174,38.14996361732483,43.2029795266888,1739502677.8601754,38.14996361732483,4.585567806254605,1739502677.860178,38.14996361732483,-2.1832155864961202,1739502677.8601797,38.14996361732483,1.188846694152971,1739502677.8601816,38.14996361732483,0.6108,1739502677.860183,38.14996361732483,0.9658114757950209,1739502677.860185,38.14996361732483,0.0,1739502677.8601866,38.14996361732483,0.022025339396624655,1739502677.8601885,38.14996361732483,3.761066796697416,1739502677.86019,38.14996361732483,0.9437861363983963 +1739502677.8802657,38.16996359825134,45.25863187194749,1739502677.8802693,38.16996359825134,7.51165499189019,1739502677.8802736,38.16996359825134,63.63700024849922,1739502677.8802774,38.16996359825134,43.2029795266888,1739502677.8802795,38.16996359825134,4.585567806254605,1739502677.880282,38.16996359825134,-2.1832155864961202,1739502677.8802836,38.16996359825134,1.188846694152971,1739502677.8802855,38.16996359825134,0.6108,1739502677.880287,38.16996359825134,0.9658114757950209,1739502677.880289,38.16996359825134,0.0,1739502677.8802907,38.16996359825134,0.022025339396624655,1739502677.8802931,38.16996359825134,3.761066796697416,1739502677.8802953,38.16996359825134,0.9437861363983963 +1739502677.9001458,38.189963579177856,45.25863187194749,1739502677.9001482,38.189963579177856,7.51165499189019,1739502677.9001517,38.189963579177856,63.63700024849922,1739502677.900155,38.189963579177856,43.2029795266888,1739502677.900157,38.189963579177856,4.585567806254605,1739502677.900159,38.189963579177856,-2.1832155864961202,1739502677.900161,38.189963579177856,1.188846694152971,1739502677.9001625,38.189963579177856,0.6108,1739502677.9001641,38.189963579177856,0.9658114757950209,1739502677.900166,38.189963579177856,0.0,1739502677.9001677,38.189963579177856,0.022025339396624655,1739502677.9001696,38.189963579177856,3.761066796697416,1739502677.9001713,38.189963579177856,0.9437861363983963 +1739502677.920103,38.20996356010437,45.25863187194749,1739502677.9201062,38.20996356010437,7.51165499189019,1739502677.9201097,38.20996356010437,63.63700024849922,1739502677.920113,38.20996356010437,43.2029795266888,1739502677.920115,38.20996356010437,4.585567806254605,1739502677.920117,38.20996356010437,-2.1832155864961202,1739502677.920119,38.20996356010437,1.188846694152971,1739502677.9201207,38.20996356010437,0.6108,1739502677.9201224,38.20996356010437,0.9658114757950209,1739502677.920124,38.20996356010437,0.0,1739502677.9201257,38.20996356010437,0.022025339396624655,1739502677.9201274,38.20996356010437,3.761066796697416,1739502677.9201293,38.20996356010437,0.9437861363983963 +1739502677.9403713,38.229963541030884,45.25863187194749,1739502677.9403753,38.229963541030884,7.51165499189019,1739502677.9403796,38.229963541030884,63.63700024849922,1739502677.9403834,38.229963541030884,43.2029795266888,1739502677.940386,38.229963541030884,4.585567806254605,1739502677.940389,38.229963541030884,-2.1832155864961202,1739502677.9403906,38.229963541030884,1.188846694152971,1739502677.9403925,38.229963541030884,0.6108,1739502677.940394,38.229963541030884,0.9658114757950209,1739502677.940396,38.229963541030884,0.0,1739502677.940398,38.229963541030884,0.022025339396624655,1739502677.9404,38.229963541030884,3.761066796697416,1739502677.9404016,38.229963541030884,0.9437861363983963 +1739502677.960295,38.2499635219574,45.17475729688604,1739502677.9602978,38.2499635219574,7.450240078634442,1739502677.9603016,38.2499635219574,63.722903347143486,1739502677.960305,38.2499635219574,43.18661249414505,1739502677.9603066,38.2499635219574,4.4958687177977845,1739502677.9603088,38.2499635219574,-2.163136463349281,1739502677.9603107,38.2499635219574,1.158580463251147,1739502677.9603126,38.2499635219574,0.6108,1739502677.960314,38.2499635219574,0.9894820656855484,1739502677.9603162,38.2499635219574,0.0,1739502677.9603176,38.2499635219574,0.05261749555495872,1739502677.9603195,38.2499635219574,3.788668485639963,1739502677.9603212,38.2499635219574,0.9464246251981296 +1739502677.9802713,38.26996350288391,45.17475729688604,1739502677.9802742,38.26996350288391,7.450240078634442,1739502677.9802778,38.26996350288391,63.722903347143486,1739502677.980281,38.26996350288391,43.18661249414505,1739502677.9802828,38.26996350288391,4.4958687177977845,1739502677.980285,38.26996350288391,-2.163136463349281,1739502677.9802868,38.26996350288391,1.158580463251147,1739502677.9802883,38.26996350288391,0.6108,1739502677.9802897,38.26996350288391,0.9894820656855484,1739502677.9802918,38.26996350288391,0.0,1739502677.9802938,38.26996350288391,0.043057440487418774,1739502677.9802952,38.26996350288391,3.788668485639963,1739502677.9802969,38.26996350288391,0.9464246251981296 +1739502678.0001473,38.289963483810425,45.17475729688604,1739502678.0001504,38.289963483810425,7.450240078634442,1739502678.0001543,38.289963483810425,63.722903347143486,1739502678.0001576,38.289963483810425,43.18661249414505,1739502678.0001597,38.289963483810425,4.4958687177977845,1739502678.0001621,38.289963483810425,-2.163136463349281,1739502678.0001638,38.289963483810425,1.158580463251147,1739502678.0001655,38.289963483810425,0.6108,1739502678.0001671,38.289963483810425,0.9894820656855484,1739502678.0001693,38.289963483810425,0.0,1739502678.0001707,38.289963483810425,0.043057440487418774,1739502678.0001726,38.289963483810425,3.788668485639963,1739502678.0001743,38.289963483810425,0.9464246251981296 +1739502678.0200748,38.30996346473694,45.17475729688604,1739502678.0200775,38.30996346473694,7.450240078634442,1739502678.0200815,38.30996346473694,63.722903347143486,1739502678.0200846,38.30996346473694,43.18661249414505,1739502678.0200868,38.30996346473694,4.4958687177977845,1739502678.020089,38.30996346473694,-2.163136463349281,1739502678.0200903,38.30996346473694,1.158580463251147,1739502678.0200922,38.30996346473694,0.6108,1739502678.0200937,38.30996346473694,0.9894820656855484,1739502678.0200958,38.30996346473694,0.0,1739502678.0200975,38.30996346473694,0.043057440487418774,1739502678.0200994,38.30996346473694,3.788668485639963,1739502678.020101,38.30996346473694,0.9464246251981296 +1739502678.0402737,38.32996344566345,45.17475729688604,1739502678.040277,38.32996344566345,7.450240078634442,1739502678.0402813,38.32996344566345,63.722903347143486,1739502678.0402846,38.32996344566345,43.18661249414505,1739502678.0402865,38.32996344566345,4.4958687177977845,1739502678.0402887,38.32996344566345,-2.163136463349281,1739502678.040291,38.32996344566345,1.158580463251147,1739502678.040293,38.32996344566345,0.6108,1739502678.040295,38.32996344566345,0.9894820656855484,1739502678.040297,38.32996344566345,0.0,1739502678.0402985,38.32996344566345,0.043057440487418774,1739502678.0403008,38.32996344566345,3.788668485639963,1739502678.0403025,38.32996344566345,0.9464246251981296 +1739502678.0602403,38.349963426589966,45.09231017500992,1739502678.0602431,38.349963426589966,7.386300847951501,1739502678.060247,38.349963426589966,63.88557802433963,1739502678.0602505,38.349963426589966,43.155131387764214,1739502678.0602522,38.349963426589966,4.326700734742485,1739502678.0602546,38.349963426589966,-2.1352332222091572,1739502678.0602562,38.349963426589966,1.1792174550468124,1739502678.0602584,38.349963426589966,0.6108,1739502678.0602598,38.349963426589966,0.9732802299339691,1739502678.0602617,38.349963426589966,0.0,1739502678.0602634,38.349963426589966,0.012655598583144648,1739502678.0602653,38.349963426589966,3.8162701745825096,1739502678.0602667,38.349963426589966,0.951124049526672 +1739502678.0802968,38.36996340751648,45.09231017500992,1739502678.0803003,38.36996340751648,7.386300847951501,1739502678.0803049,38.36996340751648,63.88557802433963,1739502678.0803087,38.36996340751648,43.155131387764214,1739502678.0803106,38.36996340751648,4.326700734742485,1739502678.0803125,38.36996340751648,-2.1352332222091572,1739502678.0803146,38.36996340751648,1.1792174550468124,1739502678.080316,38.36996340751648,0.6108,1739502678.080318,38.36996340751648,0.9732802299339691,1739502678.0803204,38.36996340751648,0.0,1739502678.080322,38.36996340751648,0.022156180407297166,1739502678.080324,38.36996340751648,3.8162701745825096,1739502678.0803256,38.36996340751648,0.951124049526672 +1739502678.1001272,38.38996338844299,45.09231017500992,1739502678.1001306,38.38996338844299,7.386300847951501,1739502678.1001341,38.38996338844299,63.88557802433963,1739502678.1001377,38.38996338844299,43.155131387764214,1739502678.1001396,38.38996338844299,4.326700734742485,1739502678.1001415,38.38996338844299,-2.1352332222091572,1739502678.1001437,38.38996338844299,1.1792174550468124,1739502678.100145,38.38996338844299,0.6108,1739502678.100147,38.38996338844299,0.9732802299339691,1739502678.1001487,38.38996338844299,0.0,1739502678.1001503,38.38996338844299,0.022156180407297166,1739502678.100152,38.38996338844299,3.8162701745825096,1739502678.100154,38.38996338844299,0.951124049526672 +1739502678.1202908,38.40996336936951,45.09231017500992,1739502678.120294,38.40996336936951,7.386300847951501,1739502678.1202977,38.40996336936951,63.88557802433963,1739502678.120301,38.40996336936951,43.155131387764214,1739502678.1203032,38.40996336936951,4.326700734742485,1739502678.1203048,38.40996336936951,-2.1352332222091572,1739502678.1203067,38.40996336936951,1.1792174550468124,1739502678.1203084,38.40996336936951,0.6108,1739502678.12031,38.40996336936951,0.9732802299339691,1739502678.120312,38.40996336936951,0.0,1739502678.1203136,38.40996336936951,0.022156180407297166,1739502678.1203153,38.40996336936951,3.8162701745825096,1739502678.1203172,38.40996336936951,0.951124049526672 +1739502678.1403484,38.42996335029602,45.09231017500992,1739502678.1403518,38.42996335029602,7.386300847951501,1739502678.1403556,38.42996335029602,63.88557802433963,1739502678.1403592,38.42996335029602,43.155131387764214,1739502678.1403606,38.42996335029602,4.326700734742485,1739502678.140363,38.42996335029602,-2.1352332222091572,1739502678.140365,38.42996335029602,1.1792174550468124,1739502678.1403668,38.42996335029602,0.6108,1739502678.1403682,38.42996335029602,0.9732802299339691,1739502678.1403701,38.42996335029602,0.0,1739502678.140372,38.42996335029602,0.022156180407297166,1739502678.1403737,38.42996335029602,3.8162701745825096,1739502678.140376,38.42996335029602,0.951124049526672 +1739502678.160153,38.449963331222534,45.09231017500992,1739502678.1601555,38.449963331222534,7.386300847951501,1739502678.1601596,38.449963331222534,63.88557802433963,1739502678.160163,38.449963331222534,43.155131387764214,1739502678.1601646,38.449963331222534,4.326700734742485,1739502678.1601667,38.449963331222534,-2.1352332222091572,1739502678.1601684,38.449963331222534,1.1792174550468124,1739502678.1601703,38.449963331222534,0.6108,1739502678.1601717,38.449963331222534,0.9732802299339691,1739502678.160174,38.449963331222534,0.0,1739502678.1601753,38.449963331222534,0.022156180407297166,1739502678.1601772,38.449963331222534,3.8162701745825096,1739502678.160179,38.449963331222534,0.951124049526672 +1739502678.1804016,38.46996331214905,45.0113578503601,1739502678.1804051,38.46996331214905,7.319864198681184,1739502678.1804092,38.46996331214905,63.97192679032444,1739502678.180413,38.46996331214905,43.138155229383514,1739502678.1804147,38.46996331214905,4.237473348754041,1739502678.1804173,38.46996331214905,-2.1168663483946544,1739502678.180419,38.46996331214905,1.142997985961035,1739502678.1804209,38.46996331214905,0.6108,1739502678.1804223,38.46996331214905,1.0018941347164771,1739502678.1804245,38.46996331214905,0.0,1739502678.1804264,38.46996331214905,0.06051821275000889,1739502678.180428,38.46996331214905,3.8438718635250564,1739502678.18043,38.46996331214905,0.9533640649336047 +1739502678.200309,38.48996329307556,45.0113578503601,1739502678.2003126,38.48996329307556,7.319864198681184,1739502678.200317,38.48996329307556,63.97192679032444,1739502678.2003205,38.48996329307556,43.138155229383514,1739502678.2003229,38.48996329307556,4.237473348754041,1739502678.200325,38.48996329307556,-2.1168663483946544,1739502678.200327,38.48996329307556,1.142997985961035,1739502678.2003286,38.48996329307556,0.6108,1739502678.2003303,38.48996329307556,1.0018941347164771,1739502678.2003326,38.48996329307556,0.0,1739502678.2003343,38.48996329307556,0.04853006978287244,1739502678.2003362,38.48996329307556,3.8438718635250564,1739502678.200338,38.48996329307556,0.9533640649336047 +1739502678.2202928,38.509963274002075,45.0113578503601,1739502678.2202957,38.509963274002075,7.319864198681184,1739502678.2202995,38.509963274002075,63.97192679032444,1739502678.2203028,38.509963274002075,43.138155229383514,1739502678.2203045,38.509963274002075,4.237473348754041,1739502678.2203064,38.509963274002075,-2.1168663483946544,1739502678.2203083,38.509963274002075,1.142997985961035,1739502678.2203097,38.509963274002075,0.6108,1739502678.2203116,38.509963274002075,1.0018941347164771,1739502678.2203133,38.509963274002075,0.0,1739502678.220315,38.509963274002075,0.04853006978287244,1739502678.2203166,38.509963274002075,3.8438718635250564,1739502678.2203183,38.509963274002075,0.9533640649336047 +1739502678.2404375,38.52996325492859,45.0113578503601,1739502678.2404408,38.52996325492859,7.319864198681184,1739502678.2404451,38.52996325492859,63.97192679032444,1739502678.2404487,38.52996325492859,43.138155229383514,1739502678.2404506,38.52996325492859,4.237473348754041,1739502678.2404528,38.52996325492859,-2.1168663483946544,1739502678.2404544,38.52996325492859,1.142997985961035,1739502678.2404563,38.52996325492859,0.6108,1739502678.2404587,38.52996325492859,1.0018941347164771,1739502678.2404616,38.52996325492859,0.0,1739502678.240463,38.52996325492859,0.04853006978287244,1739502678.240465,38.52996325492859,3.8438718635250564,1739502678.2404666,38.52996325492859,0.9533640649336047 +1739502678.260136,38.5499632358551,45.0113578503601,1739502678.260139,38.5499632358551,7.319864198681184,1739502678.2601428,38.5499632358551,63.97192679032444,1739502678.2601461,38.5499632358551,43.138155229383514,1739502678.2601483,38.5499632358551,4.237473348754041,1739502678.2601502,38.5499632358551,-2.1168663483946544,1739502678.2601523,38.5499632358551,1.142997985961035,1739502678.2601538,38.5499632358551,0.6108,1739502678.2601554,38.5499632358551,1.0018941347164771,1739502678.260158,38.5499632358551,0.0,1739502678.2601595,38.5499632358551,0.04853006978287244,1739502678.2601612,38.5499632358551,3.8438718635250564,1739502678.260163,38.5499632358551,0.9533640649336047 +1739502678.2802935,38.569963216781616,44.93196604184634,1739502678.2802966,38.569963216781616,7.250953946143964,1739502678.280301,38.569963216781616,64.07675856528029,1739502678.2803044,38.569963216781616,43.115919819353536,1739502678.280306,38.569963216781616,4.124214074186892,1739502678.2803087,38.569963216781616,-2.0969870744405075,1739502678.2803106,38.569963216781616,1.1193099430767386,1739502678.2803125,38.569963216781616,0.6108,1739502678.2803147,38.569963216781616,1.0210615050855307,1739502678.2803164,38.569963216781616,0.0,1739502678.280318,38.569963216781616,0.06870835727131995,1739502678.28032,38.569963216781616,3.871473552467603,1739502678.2803218,38.569963216781616,0.9586588667887022 +1739502678.300298,38.58996319770813,44.93196604184634,1739502678.300301,38.58996319770813,7.250953946143964,1739502678.3003047,38.58996319770813,64.07675856528029,1739502678.3003085,38.58996319770813,43.115919819353536,1739502678.3003104,38.58996319770813,4.124214074186892,1739502678.3003123,38.58996319770813,-2.0969870744405075,1739502678.3003142,38.58996319770813,1.1193099430767386,1739502678.3003159,38.58996319770813,0.6108,1739502678.3003175,38.58996319770813,1.0210615050855307,1739502678.3003194,38.58996319770813,0.0,1739502678.300321,38.58996319770813,0.06240263829682857,1739502678.300323,38.58996319770813,3.871473552467603,1739502678.300325,38.58996319770813,0.9586588667887022 +1739502678.3201733,38.609963178634644,44.93196604184634,1739502678.3201768,38.609963178634644,7.250953946143964,1739502678.3201807,38.609963178634644,64.07675856528029,1739502678.320184,38.609963178634644,43.115919819353536,1739502678.320186,38.609963178634644,4.124214074186892,1739502678.320188,38.609963178634644,-2.0969870744405075,1739502678.32019,38.609963178634644,1.1193099430767386,1739502678.3201919,38.609963178634644,0.6108,1739502678.3201933,38.609963178634644,1.0210615050855307,1739502678.320195,38.609963178634644,0.0,1739502678.3201966,38.609963178634644,0.06240263829682857,1739502678.3201983,38.609963178634644,3.871473552467603,1739502678.3202002,38.609963178634644,0.9586588667887022 +1739502678.3403125,38.62996315956116,44.93196604184634,1739502678.340316,38.62996315956116,7.250953946143964,1739502678.34032,38.62996315956116,64.07675856528029,1739502678.3403237,38.62996315956116,43.115919819353536,1739502678.3403254,38.62996315956116,4.124214074186892,1739502678.3403277,38.62996315956116,-2.0969870744405075,1739502678.3403294,38.62996315956116,1.1193099430767386,1739502678.3403313,38.62996315956116,0.6108,1739502678.340333,38.62996315956116,1.0210615050855307,1739502678.3403351,38.62996315956116,0.0,1739502678.3403368,38.62996315956116,0.06240263829682857,1739502678.340339,38.62996315956116,3.871473552467603,1739502678.3403409,38.62996315956116,0.9586588667887022 +1739502678.3601775,38.64996314048767,44.93196604184634,1739502678.3601809,38.64996314048767,7.250953946143964,1739502678.3601844,38.64996314048767,64.07675856528029,1739502678.3601875,38.64996314048767,43.115919819353536,1739502678.3601894,38.64996314048767,4.124214074186892,1739502678.3601916,38.64996314048767,-2.0969870744405075,1739502678.3601933,38.64996314048767,1.1193099430767386,1739502678.3601952,38.64996314048767,0.6108,1739502678.3601966,38.64996314048767,1.0210615050855307,1739502678.3601987,38.64996314048767,0.0,1739502678.3602002,38.64996314048767,0.06240263829682857,1739502678.360202,38.64996314048767,3.871473552467603,1739502678.3602037,38.64996314048767,0.9586588667887022 +1739502678.3803084,38.669963121414185,44.93196604184634,1739502678.380312,38.669963121414185,7.250953946143964,1739502678.3803163,38.669963121414185,64.07675856528029,1739502678.38032,38.669963121414185,43.115919819353536,1739502678.3803217,38.669963121414185,4.124214074186892,1739502678.380324,38.669963121414185,-2.0969870744405075,1739502678.3803256,38.669963121414185,1.1193099430767386,1739502678.3803277,38.669963121414185,0.6108,1739502678.3803291,38.669963121414185,1.0210615050855307,1739502678.3803313,38.669963121414185,0.0,1739502678.380333,38.669963121414185,0.06240263829682857,1739502678.3803349,38.669963121414185,3.871473552467603,1739502678.380337,38.669963121414185,0.9586588667887022 +1739502678.4003775,38.6899631023407,44.854007976535186,1739502678.4003808,38.6899631023407,7.179421154030781,1739502678.4003844,38.6899631023407,64.09210386662248,1739502678.400388,38.6899631023407,43.11027174211225,1739502678.40039,38.6899631023407,4.095487226659114,1739502678.4003918,38.6899631023407,-2.08540567923098,1739502678.4003937,38.6899631023407,1.0425760721607849,1739502678.4003952,38.6899631023407,0.6108,1739502678.4003968,38.6899631023407,1.0857053567374333,1739502678.4003987,38.6899631023407,0.0,1739502678.4004006,38.6899631023407,0.1462979086493505,1739502678.4004025,38.6899631023407,3.89907524141015,1739502678.4004042,38.6899631023407,0.9656247372626402 +1739502678.425017,38.70996308326721,44.854007976535186,1739502678.4250255,38.70996308326721,7.179421154030781,1739502678.425036,38.70996308326721,64.09210386662248,1739502678.425046,38.70996308326721,43.11027174211225,1739502678.425051,38.70996308326721,4.095487226659114,1739502678.4250572,38.70996308326721,-2.08540567923098,1739502678.4250624,38.70996308326721,1.0425760721607849,1739502678.4250672,38.70996308326721,0.6108,1739502678.4250717,38.70996308326721,1.0857053567374333,1739502678.4250772,38.70996308326721,0.0,1739502678.4250822,38.70996308326721,0.1200806194747931,1739502678.4250875,38.70996308326721,3.89907524141015,1739502678.4250927,38.70996308326721,0.9656247372626402 +1739502678.4421983,38.729963064193726,44.854007976535186,1739502678.442202,38.729963064193726,7.179421154030781,1739502678.4422064,38.729963064193726,64.09210386662248,1739502678.4422116,38.729963064193726,43.11027174211225,1739502678.4422145,38.729963064193726,4.095487226659114,1739502678.4422412,38.729963064193726,-2.08540567923098,1739502678.4422455,38.729963064193726,1.0425760721607849,1739502678.4422483,38.729963064193726,0.6108,1739502678.4422517,38.729963064193726,1.0857053567374333,1739502678.4422555,38.729963064193726,0.0,1739502678.4422586,38.729963064193726,0.1200806194747931,1739502678.4422622,38.729963064193726,3.89907524141015,1739502678.4422655,38.729963064193726,0.9656247372626402 +1739502678.461519,38.74996304512024,44.854007976535186,1739502678.4615223,38.74996304512024,7.179421154030781,1739502678.4615266,38.74996304512024,64.09210386662248,1739502678.4615316,38.74996304512024,43.11027174211225,1739502678.4615343,38.74996304512024,4.095487226659114,1739502678.461538,38.74996304512024,-2.08540567923098,1739502678.4615412,38.74996304512024,1.0425760721607849,1739502678.4615445,38.74996304512024,0.6108,1739502678.4615476,38.74996304512024,1.0857053567374333,1739502678.461551,38.74996304512024,0.0,1739502678.4615543,38.74996304512024,0.1200806194747931,1739502678.4615574,38.74996304512024,3.89907524141015,1739502678.4615607,38.74996304512024,0.9656247372626402 +1739502678.4812365,38.76996302604675,44.854007976535186,1739502678.481239,38.76996302604675,7.179421154030781,1739502678.481242,38.76996302604675,64.09210386662248,1739502678.4812443,38.76996302604675,43.11027174211225,1739502678.4812458,38.76996302604675,4.095487226659114,1739502678.4812474,38.76996302604675,-2.08540567923098,1739502678.4812489,38.76996302604675,1.0425760721607849,1739502678.48125,38.76996302604675,0.6108,1739502678.481251,38.76996302604675,1.0857053567374333,1739502678.4812524,38.76996302604675,0.0,1739502678.4812536,38.76996302604675,0.1200806194747931,1739502678.4812548,38.76996302604675,3.89907524141015,1739502678.4812565,38.76996302604675,0.9656247372626402 +1739502678.5046632,38.78996300697327,44.77729588381564,1739502678.5046678,38.78996300697327,7.105026885556137,1739502678.5046961,38.78996300697327,64.36909755025987,1739502678.5047019,38.78996300697327,43.04695361563633,1739502678.504705,38.78996300697327,3.7989709801651452,1739502678.5047085,38.78996300697327,-2.052976962829182,1739502678.5047119,38.78996300697327,1.1153155786375397,1739502678.5047154,38.78996300697327,0.6067548794964923,1739502678.5047188,38.78996300697327,1.024329517170102,1739502678.504722,38.78996300697327,0.0,1739502678.5047252,38.78996300697327,0.011742184732238523,1739502678.5047283,38.78996300697327,3.9266769303526967,1739502678.5047314,38.78996300697327,0.9787315493832339 +1739502678.5235138,38.80996298789978,44.77729588381564,1739502678.5235186,38.80996298789978,7.105026885556137,1739502678.5235233,38.80996298789978,64.36909755025987,1739502678.523529,38.80996298789978,43.04695361563633,1739502678.523532,38.80996298789978,3.7989709801651452,1739502678.5235357,38.80996298789978,-2.052976962829182,1739502678.5235388,38.80996298789978,1.1153155786375397,1739502678.5235417,38.80996298789978,0.6067548794964923,1739502678.523545,38.80996298789978,1.024329517170102,1739502678.5235484,38.80996298789978,0.0,1739502678.5235517,38.80996298789978,0.04559796778686798,1739502678.5235548,38.80996298789978,3.9266769303526967,1739502678.5235584,38.80996298789978,0.9787315493832339 +1739502678.541807,38.829962968826294,44.77729588381564,1739502678.541812,38.829962968826294,7.105026885556137,1739502678.5418172,38.829962968826294,64.36909755025987,1739502678.5418224,38.829962968826294,43.04695361563633,1739502678.5418262,38.829962968826294,3.7989709801651452,1739502678.54183,38.829962968826294,-2.052976962829182,1739502678.5418339,38.829962968826294,1.1153155786375397,1739502678.541837,38.829962968826294,0.6067548794964923,1739502678.54184,38.829962968826294,1.024329517170102,1739502678.541844,38.829962968826294,0.0,1739502678.5418472,38.829962968826294,0.04559796778686798,1739502678.5418506,38.829962968826294,3.9266769303526967,1739502678.5418544,38.829962968826294,0.9787315493832339 +1739502678.5618002,38.84996294975281,44.77729588381564,1739502678.5618033,38.84996294975281,7.105026885556137,1739502678.5618074,38.84996294975281,64.36909755025987,1739502678.5618122,38.84996294975281,43.04695361563633,1739502678.5618148,38.84996294975281,3.7989709801651452,1739502678.5618181,38.84996294975281,-2.052976962829182,1739502678.5618212,38.84996294975281,1.1153155786375397,1739502678.5618243,38.84996294975281,0.6067548794964923,1739502678.5618274,38.84996294975281,1.024329517170102,1739502678.5618303,38.84996294975281,0.0,1739502678.5618334,38.84996294975281,0.04559796778686798,1739502678.5618365,38.84996294975281,3.9266769303526967,1739502678.5618396,38.84996294975281,0.9787315493832339 +1739502678.5825083,38.86996293067932,44.77729588381564,1739502678.5825117,38.86996293067932,7.105026885556137,1739502678.582516,38.86996293067932,64.36909755025987,1739502678.5825205,38.86996293067932,43.04695361563633,1739502678.5825236,38.86996293067932,3.7989709801651452,1739502678.582527,38.86996293067932,-2.052976962829182,1739502678.58253,38.86996293067932,1.1153155786375397,1739502678.5825331,38.86996293067932,0.6067548794964923,1739502678.5825362,38.86996293067932,1.024329517170102,1739502678.5825396,38.86996293067932,0.0,1739502678.5825427,38.86996293067932,0.04559796778686798,1739502678.5825458,38.86996293067932,3.9266769303526967,1739502678.5825486,38.86996293067932,0.9787315493832339 +1739502678.6019874,38.889962911605835,44.77729588381564,1739502678.6019893,38.889962911605835,7.105026885556137,1739502678.6019921,38.889962911605835,64.36909755025987,1739502678.6019948,38.889962911605835,43.04695361563633,1739502678.601996,38.889962911605835,3.7989709801651452,1739502678.6019976,38.889962911605835,-2.052976962829182,1739502678.6019988,38.889962911605835,1.1153155786375397,1739502678.6019998,38.889962911605835,0.6067548794964923,1739502678.6020012,38.889962911605835,1.024329517170102,1739502678.6020024,38.889962911605835,0.0,1739502678.6020038,38.889962911605835,0.04559796778686798,1739502678.602005,38.889962911605835,3.9266769303526967,1739502678.6020064,38.889962911605835,0.9787315493832339 +1739502678.6217234,38.90996289253235,44.70197851453948,1739502678.621726,38.90996289253235,7.027842360976964,1739502678.6217287,38.90996289253235,64.45014451946166,1739502678.6217313,38.90996289253235,43.02768086163712,1739502678.6217327,38.90996289253235,3.7113675528959944,1739502678.6217341,38.90996289253235,-2.0383104798643155,1739502678.6217353,38.90996289253235,1.064475351710482,1739502678.6217365,38.90996289253235,0.5847848803623967,1739502678.6217377,38.90996289253235,1.0668500737588258,1739502678.6217391,38.90996289253235,0.0,1739502678.6217406,38.90996289253235,0.10115413095561036,1739502678.6217418,38.90996289253235,3.9542786192952435,1739502678.6217432,38.90996289253235,0.9830572551764108 +1739502678.6396658,38.92996287345886,44.70197851453948,1739502678.6396685,38.92996287345886,7.027842360976964,1739502678.6396718,38.92996287345886,64.45014451946166,1739502678.6396744,38.92996287345886,43.02768086163712,1739502678.6396759,38.92996287345886,3.7113675528959944,1739502678.6396782,38.92996287345886,-2.0383104798643155,1739502678.6396797,38.92996287345886,1.064475351710482,1739502678.639681,38.92996287345886,0.5847848803623967,1739502678.639682,38.92996287345886,1.0668500737588258,1739502678.6396835,38.92996287345886,0.0,1739502678.6396856,38.92996287345886,0.08379281858241494,1739502678.639687,38.92996287345886,3.9542786192952435,1739502678.6396885,38.92996287345886,0.9830572551764108 +1739502678.659717,38.949962854385376,44.70197851453948,1739502678.6597195,38.949962854385376,7.027842360976964,1739502678.6597223,38.949962854385376,64.45014451946166,1739502678.659725,38.949962854385376,43.02768086163712,1739502678.6597264,38.949962854385376,3.7113675528959944,1739502678.659728,38.949962854385376,-2.0383104798643155,1739502678.6597295,38.949962854385376,1.064475351710482,1739502678.6597307,38.949962854385376,0.5847848803623967,1739502678.6597319,38.949962854385376,1.0668500737588258,1739502678.6597333,38.949962854385376,0.0,1739502678.6597345,38.949962854385376,0.08379281858241494,1739502678.6597362,38.949962854385376,3.9542786192952435,1739502678.6597373,38.949962854385376,0.9830572551764108 +1739502678.679941,38.96996283531189,44.70197851453948,1739502678.6799433,38.96996283531189,7.027842360976964,1739502678.6799464,38.96996283531189,64.45014451946166,1739502678.6799493,38.96996283531189,43.02768086163712,1739502678.679951,38.96996283531189,3.7113675528959944,1739502678.6799524,38.96996283531189,-2.0383104798643155,1739502678.6799538,38.96996283531189,1.064475351710482,1739502678.6799555,38.96996283531189,0.5847848803623967,1739502678.6799564,38.96996283531189,1.0668500737588258,1739502678.6799583,38.96996283531189,0.0,1739502678.6799595,38.96996283531189,0.08379281858241494,1739502678.6799612,38.96996283531189,3.9542786192952435,1739502678.6799626,38.96996283531189,0.9830572551764108 +1739502678.6997433,38.9899628162384,44.70197851453948,1739502678.6997457,38.9899628162384,7.027842360976964,1739502678.6997485,38.9899628162384,64.45014451946166,1739502678.6997514,38.9899628162384,43.02768086163712,1739502678.6997528,38.9899628162384,3.7113675528959944,1739502678.6997547,38.9899628162384,-2.0383104798643155,1739502678.6997561,38.9899628162384,1.064475351710482,1739502678.6997576,38.9899628162384,0.5847848803623967,1739502678.6997588,38.9899628162384,1.0668500737588258,1739502678.6997604,38.9899628162384,0.0,1739502678.6997619,38.9899628162384,0.08379281858241494,1739502678.6997633,38.9899628162384,3.9542786192952435,1739502678.6997647,38.9899628162384,0.9830572551764108 +1739502678.719833,39.00996279716492,44.62831844111934,1739502678.7198353,39.00996279716492,6.948063643706952,1739502678.7198381,39.00996279716492,64.60117546488465,1739502678.7198408,39.00996279716492,42.98960237800876,1739502678.7198422,39.00996279716492,3.5463987354025424,1739502678.7198439,39.00996279716492,-2.0197290411962947,1739502678.7198453,39.00996279716492,1.0491829185441024,1739502678.719847,39.00996279716492,0.5586401962541434,1739502678.7198482,39.00996279716492,1.0799820245245575,1739502678.7198498,39.00996279716492,0.0,1739502678.719851,39.00996279716492,0.08958760615854328,1739502678.7198524,39.00996279716492,3.9818803082377903,1739502678.719854,39.00996279716492,0.9922052906708547 +1739502678.7400105,39.02996277809143,44.62831844111934,1739502678.7400136,39.02996277809143,6.948063643706952,1739502678.7400167,39.02996277809143,64.60117546488465,1739502678.7400196,39.02996277809143,42.98960237800876,1739502678.7400208,39.02996277809143,3.5463987354025424,1739502678.7400224,39.02996277809143,-2.0197290411962947,1739502678.740024,39.02996277809143,1.0491829185441024,1739502678.7400255,39.02996277809143,0.5586401962541434,1739502678.740027,39.02996277809143,1.0799820245245575,1739502678.7400284,39.02996277809143,0.0,1739502678.74003,39.02996277809143,0.08777673385370277,1739502678.7400315,39.02996277809143,3.9818803082377903,1739502678.740033,39.02996277809143,0.9922052906708547 +1739502678.7597136,39.049962759017944,44.62831844111934,1739502678.7597158,39.049962759017944,6.948063643706952,1739502678.7597187,39.049962759017944,64.60117546488465,1739502678.7597215,39.049962759017944,42.98960237800876,1739502678.759723,39.049962759017944,3.5463987354025424,1739502678.7597249,39.049962759017944,-2.0197290411962947,1739502678.759726,39.049962759017944,1.0491829185441024,1739502678.7597277,39.049962759017944,0.5586401962541434,1739502678.759729,39.049962759017944,1.0799820245245575,1739502678.7597306,39.049962759017944,0.0,1739502678.759732,39.049962759017944,0.08777673385370277,1739502678.7597332,39.049962759017944,3.9818803082377903,1739502678.7597349,39.049962759017944,0.9922052906708547 +1739502678.7799876,39.06996273994446,44.62831844111934,1739502678.7799904,39.06996273994446,6.948063643706952,1739502678.7799935,39.06996273994446,64.60117546488465,1739502678.7799969,39.06996273994446,42.98960237800876,1739502678.7799983,39.06996273994446,3.5463987354025424,1739502678.78,39.06996273994446,-2.0197290411962947,1739502678.7800016,39.06996273994446,1.0491829185441024,1739502678.780003,39.06996273994446,0.5586401962541434,1739502678.7800043,39.06996273994446,1.0799820245245575,1739502678.780006,39.06996273994446,0.0,1739502678.7800074,39.06996273994446,0.08777673385370277,1739502678.7800088,39.06996273994446,3.9818803082377903,1739502678.7800102,39.06996273994446,0.9922052906708547 +1739502678.7999284,39.08996272087097,44.62831844111934,1739502678.7999308,39.08996272087097,6.948063643706952,1739502678.799934,39.08996272087097,64.60117546488465,1739502678.7999372,39.08996272087097,42.98960237800876,1739502678.7999392,39.08996272087097,3.5463987354025424,1739502678.799941,39.08996272087097,-2.0197290411962947,1739502678.799943,39.08996272087097,1.0491829185441024,1739502678.7999446,39.08996272087097,0.5586401962541434,1739502678.7999463,39.08996272087097,1.0799820245245575,1739502678.799948,39.08996272087097,0.0,1739502678.79995,39.08996272087097,0.08777673385370277,1739502678.7999513,39.08996272087097,3.9818803082377903,1739502678.7999532,39.08996272087097,0.9922052906708547 +1739502678.8302166,39.109962701797485,44.62831844111934,1739502678.8302236,39.109962701797485,6.948063643706952,1739502678.8302329,39.109962701797485,64.60117546488465,1739502678.830243,39.109962701797485,42.98960237800876,1739502678.830249,39.109962701797485,3.5463987354025424,1739502678.8302565,39.109962701797485,-2.0197290411962947,1739502678.8302631,39.109962701797485,1.0491829185441024,1739502678.8302698,39.109962701797485,0.5586401962541434,1739502678.8302765,39.109962701797485,1.0799820245245575,1739502678.8302834,39.109962701797485,0.0,1739502678.83029,39.109962701797485,0.08777673385370277,1739502678.830297,39.109962701797485,3.9818803082377903,1739502678.830304,39.109962701797485,0.9922052906708547 +1739502678.8451955,39.129962682724,44.556203743968034,1739502678.8451993,39.129962682724,6.865498744781602,1739502678.8452048,39.129962682724,64.60949784918272,1739502678.8452108,39.129962682724,42.98272911043931,1739502678.8452141,39.129962682724,3.5196291669741404,1739502678.845219,39.129962682724,-2.0103814103267355,1739502678.845223,39.129962682724,0.9623903877435694,1739502678.8452268,39.129962682724,0.5349163829507128,1739502678.8452306,39.129962682724,1.157634179042974,1739502678.8452346,39.129962682724,0.0,1739502678.8452387,39.129962682724,0.1866777291380962,1739502678.845243,39.129962682724,4.009481997180338,1739502678.845247,39.129962682724,1.0018630311951846 +1739502678.864088,39.14996266365051,44.556203743968034,1739502678.8640916,39.14996266365051,6.865498744781602,1739502678.8640957,39.14996266365051,64.60949784918272,1739502678.8641005,39.14996266365051,42.98272911043931,1739502678.864103,39.14996266365051,3.5196291669741404,1739502678.8641064,39.14996266365051,-2.0103814103267355,1739502678.8641095,39.14996266365051,0.9623903877435694,1739502678.864113,39.14996266365051,0.5349163829507128,1739502678.8641162,39.14996266365051,1.157634179042974,1739502678.8641193,39.14996266365051,0.0,1739502678.8641224,39.14996266365051,0.15577114784778945,1739502678.8641257,39.14996266365051,4.009481997180338,1739502678.8641288,39.14996266365051,1.0018630311951846 +1739502678.883684,39.169962644577026,44.556203743968034,1739502678.8836873,39.169962644577026,6.865498744781602,1739502678.8836915,39.169962644577026,64.60949784918272,1739502678.883696,39.169962644577026,42.98272911043931,1739502678.8836987,39.169962644577026,3.5196291669741404,1739502678.8837023,39.169962644577026,-2.0103814103267355,1739502678.8837054,39.169962644577026,0.9623903877435694,1739502678.8837085,39.169962644577026,0.5349163829507128,1739502678.8837116,39.169962644577026,1.157634179042974,1739502678.8837147,39.169962644577026,0.0,1739502678.8837175,39.169962644577026,0.15577114784778945,1739502678.8837209,39.169962644577026,4.009481997180338,1739502678.883724,39.169962644577026,1.0018630311951846 +1739502678.9025915,39.18996262550354,44.556203743968034,1739502678.9025936,39.18996262550354,6.865498744781602,1739502678.902596,39.18996262550354,64.60949784918272,1739502678.9025986,39.18996262550354,42.98272911043931,1739502678.9026,39.18996262550354,3.5196291669741404,1739502678.9026015,39.18996262550354,-2.0103814103267355,1739502678.9026027,39.18996262550354,0.9623903877435694,1739502678.902604,39.18996262550354,0.5349163829507128,1739502678.902605,39.18996262550354,1.157634179042974,1739502678.9026065,39.18996262550354,0.0,1739502678.902608,39.18996262550354,0.15577114784778945,1739502678.902609,39.18996262550354,4.009481997180338,1739502678.9026105,39.18996262550354,1.0018630311951846 +1739502678.921822,39.209962606430054,44.556203743968034,1739502678.921824,39.209962606430054,6.865498744781602,1739502678.9218268,39.209962606430054,64.60949784918272,1739502678.9218295,39.209962606430054,42.98272911043931,1739502678.9218307,39.209962606430054,3.5196291669741404,1739502678.921832,39.209962606430054,-2.0103814103267355,1739502678.9218335,39.209962606430054,0.9623903877435694,1739502678.9218347,39.209962606430054,0.5349163829507128,1739502678.9218361,39.209962606430054,1.157634179042974,1739502678.9218373,39.209962606430054,0.0,1739502678.9218385,39.209962606430054,0.15577114784778945,1739502678.92184,39.209962606430054,4.009481997180338,1739502678.9218411,39.209962606430054,1.0018630311951846 +1739502678.9419553,39.22996258735657,44.48549491926457,1739502678.941958,39.22996258735657,6.779882060165891,1739502678.9419613,39.22996258735657,64.82418496013082,1739502678.9419637,39.22996258735657,42.91822290311661,1739502678.941965,39.22996258735657,3.2794469204240104,1739502678.9419668,39.22996258735657,-1.9917661972079124,1739502678.9419684,39.22996258735657,0.9649656367332045,1739502678.9419696,39.22996258735657,0.49916548171349484,1739502678.9419706,39.22996258735657,1.1552516770999997,1739502678.9419723,39.22996258735657,0.0,1739502678.9419734,39.22996258735657,0.1275676254129947,1739502678.941975,39.22996258735657,4.03708368612289,1739502678.9419765,39.22996258735657,1.0188704451474808 +1739502678.9615278,39.24996256828308,44.48549491926457,1739502678.96153,39.24996256828308,6.779882060165891,1739502678.9615326,39.24996256828308,64.82418496013082,1739502678.9615352,39.24996256828308,42.91822290311661,1739502678.9615364,39.24996256828308,3.2794469204240104,1739502678.9615386,39.24996256828308,-1.9917661972079124,1739502678.9615397,39.24996256828308,0.9649656367332045,1739502678.9615412,39.24996256828308,0.49916548171349484,1739502678.9615424,39.24996256828308,1.1552516770999997,1739502678.961544,39.24996256828308,0.0,1739502678.9615452,39.24996256828308,0.13638123195251883,1739502678.9615464,39.24996256828308,4.03708368612289,1739502678.961548,39.24996256828308,1.0188704451474808 +1739502678.9815943,39.269962549209595,44.48549491926457,1739502678.9815965,39.269962549209595,6.779882060165891,1739502678.9815993,39.269962549209595,64.82418496013082,1739502678.9816017,39.269962549209595,42.91822290311661,1739502678.9816031,39.269962549209595,3.2794469204240104,1739502678.9816048,39.269962549209595,-1.9917661972079124,1739502678.9816062,39.269962549209595,0.9649656367332045,1739502678.9816074,39.269962549209595,0.49916548171349484,1739502678.9816086,39.269962549209595,1.1552516770999997,1739502678.9816103,39.269962549209595,0.0,1739502678.9816115,39.269962549209595,0.13638123195251883,1739502678.9816127,39.269962549209595,4.03708368612289,1739502678.981614,39.269962549209595,1.0188704451474808 +1739502679.0018792,39.28996253013611,44.48549491926457,1739502679.0018816,39.28996253013611,6.779882060165891,1739502679.0018842,39.28996253013611,64.82418496013082,1739502679.001887,39.28996253013611,42.91822290311661,1739502679.0018883,39.28996253013611,3.2794469204240104,1739502679.00189,39.28996253013611,-1.9917661972079124,1739502679.0018914,39.28996253013611,0.9649656367332045,1739502679.0018926,39.28996253013611,0.49916548171349484,1739502679.001894,39.28996253013611,1.1552516770999997,1739502679.0018954,39.28996253013611,0.0,1739502679.0018966,39.28996253013611,0.13638123195251883,1739502679.001898,39.28996253013611,4.03708368612289,1739502679.0018995,39.28996253013611,1.0188704451474808 +1739502679.0215976,39.30996251106262,44.48549491926457,1739502679.0216,39.30996251106262,6.779882060165891,1739502679.021603,39.30996251106262,64.82418496013082,1739502679.021606,39.30996251106262,42.91822290311661,1739502679.0216074,39.30996251106262,3.2794469204240104,1739502679.0216093,39.30996251106262,-1.9917661972079124,1739502679.0216105,39.30996251106262,0.9649656367332045,1739502679.021612,39.30996251106262,0.49916548171349484,1739502679.0216134,39.30996251106262,1.1552516770999997,1739502679.0216148,39.30996251106262,0.0,1739502679.0216165,39.30996251106262,0.13638123195251883,1739502679.0216177,39.30996251106262,4.03708368612289,1739502679.021619,39.30996251106262,1.0188704451474808 +1739502679.0416667,39.329962491989136,44.48549491926457,1739502679.041669,39.329962491989136,6.779882060165891,1739502679.041672,39.329962491989136,64.82418496013082,1739502679.0416746,39.329962491989136,42.91822290311661,1739502679.041676,39.329962491989136,3.2794469204240104,1739502679.0416777,39.329962491989136,-1.9917661972079124,1739502679.0416791,39.329962491989136,0.9649656367332045,1739502679.0416806,39.329962491989136,0.49916548171349484,1739502679.0416818,39.329962491989136,1.1552516770999997,1739502679.0416834,39.329962491989136,0.0,1739502679.041685,39.329962491989136,0.13638123195251883,1739502679.0416863,39.329962491989136,4.03708368612289,1739502679.041688,39.329962491989136,1.0188704451474808 +1739502679.0615776,39.34996247291565,44.41607124987378,1739502679.0615797,39.34996247291565,6.690971206073019,1739502679.061583,39.34996247291565,64.97164985768009,1739502679.061586,39.34996247291565,42.86734013220335,1739502679.061587,39.34996247291565,3.109914001898209,1739502679.0615888,39.34996247291565,-1.9789844446220828,1739502679.0615902,39.34996247291565,0.9285096918474474,1739502679.0615919,39.34996247291565,0.4646945585883585,1739502679.061593,39.34996247291565,1.1894404404133723,1739502679.0615947,39.34996247291565,0.0,1739502679.061596,39.34996247291565,0.16462076339896553,1739502679.0615973,39.34996247291565,4.063913919626914,1739502679.061599,39.34996247291565,1.03364453637745 +1739502679.0815644,39.36996245384216,44.41607124987378,1739502679.0815668,39.36996245384216,6.690971206073019,1739502679.0815694,39.36996245384216,64.97164985768009,1739502679.0815725,39.36996245384216,42.86734013220335,1739502679.081574,39.36996245384216,3.109914001898209,1739502679.0815756,39.36996245384216,-1.9789844446220828,1739502679.0815773,39.36996245384216,0.9285096918474474,1739502679.0815785,39.36996245384216,0.4646945585883585,1739502679.0815797,39.36996245384216,1.1894404404133723,1739502679.0815814,39.36996245384216,0.0,1739502679.0815825,39.36996245384216,0.15579590403592225,1739502679.0815842,39.36996245384216,4.063913919626914,1739502679.0815854,39.36996245384216,1.03364453637745 +1739502679.1018207,39.38996243476868,44.41607124987378,1739502679.101823,39.38996243476868,6.690971206073019,1739502679.101826,39.38996243476868,64.97164985768009,1739502679.1018288,39.38996243476868,42.86734013220335,1739502679.1018305,39.38996243476868,3.109914001898209,1739502679.1018322,39.38996243476868,-1.9789844446220828,1739502679.1018336,39.38996243476868,0.9285096918474474,1739502679.101835,39.38996243476868,0.4646945585883585,1739502679.1018362,39.38996243476868,1.1894404404133723,1739502679.1018379,39.38996243476868,0.0,1739502679.101839,39.38996243476868,0.15579590403592225,1739502679.1018405,39.38996243476868,4.063913919626914,1739502679.1018422,39.38996243476868,1.03364453637745 +1739502679.1215293,39.40996241569519,44.41607124987378,1739502679.1215317,39.40996241569519,6.690971206073019,1739502679.1215343,39.40996241569519,64.97164985768009,1739502679.1215374,39.40996241569519,42.86734013220335,1739502679.1215389,39.40996241569519,3.109914001898209,1739502679.1215405,39.40996241569519,-1.9789844446220828,1739502679.1215422,39.40996241569519,0.9285096918474474,1739502679.1215436,39.40996241569519,0.4646945585883585,1739502679.121545,39.40996241569519,1.1894404404133723,1739502679.1215465,39.40996241569519,0.0,1739502679.1215477,39.40996241569519,0.15579590403592225,1739502679.1215491,39.40996241569519,4.063913919626914,1739502679.1215506,39.40996241569519,1.03364453637745 +1739502679.1416254,39.429962396621704,44.41607124987378,1739502679.1416276,39.429962396621704,6.690971206073019,1739502679.1416306,39.429962396621704,64.97164985768009,1739502679.1416335,39.429962396621704,42.86734013220335,1739502679.1416352,39.429962396621704,3.109914001898209,1739502679.1416366,39.429962396621704,-1.9789844446220828,1739502679.141638,39.429962396621704,0.9285096918474474,1739502679.1416395,39.429962396621704,0.4646945585883585,1739502679.1416407,39.429962396621704,1.1894404404133723,1739502679.1416426,39.429962396621704,0.0,1739502679.1416438,39.429962396621704,0.15579590403592225,1739502679.1416452,39.429962396621704,4.063913919626914,1739502679.1416469,39.429962396621704,1.03364453637745 +1739502679.1616364,39.44996237754822,44.34795274867498,1739502679.1616387,39.44996237754822,6.598878849228061,1739502679.1616414,39.44996237754822,65.11532788649832,1739502679.1616442,39.44996237754822,42.811584274066625,1739502679.1616457,39.44996237754822,2.9411070102468524,1739502679.1616473,39.44996237754822,-1.968448557477314,1739502679.161649,39.44996237754822,0.8875989975458408,1739502679.1616502,39.44996237754822,0.4301211469891629,1739502679.1616514,39.44996237754822,1.2290131543690526,1739502679.1616533,39.44996237754822,0.0,1739502679.1616545,39.44996237754822,0.18855718196866073,1739502679.1616561,39.44996237754822,4.089100089785886,1739502679.1616576,39.44996237754822,1.050693878466867 +1739502679.1816144,39.46996235847473,44.34795274867498,1739502679.1816168,39.46996235847473,6.598878849228061,1739502679.1816196,39.46996235847473,65.11532788649832,1739502679.1816227,39.46996235847473,42.811584274066625,1739502679.1816242,39.46996235847473,2.9411070102468524,1739502679.1816258,39.46996235847473,-1.968448557477314,1739502679.1816273,39.46996235847473,0.8875989975458408,1739502679.1816287,39.46996235847473,0.4301211469891629,1739502679.18163,39.46996235847473,1.2290131543690526,1739502679.181632,39.46996235847473,0.0,1739502679.1816332,39.46996235847473,0.17831927590218566,1739502679.1816351,39.46996235847473,4.089100089785886,1739502679.1816363,39.46996235847473,1.050693878466867 +1739502679.2016683,39.489962339401245,44.34795274867498,1739502679.2016706,39.489962339401245,6.598878849228061,1739502679.2016737,39.489962339401245,65.11532788649832,1739502679.2016766,39.489962339401245,42.811584274066625,1739502679.2016778,39.489962339401245,2.9411070102468524,1739502679.2016795,39.489962339401245,-1.968448557477314,1739502679.201681,39.489962339401245,0.8875989975458408,1739502679.2016823,39.489962339401245,0.4301211469891629,1739502679.2016838,39.489962339401245,1.2290131543690526,1739502679.2016854,39.489962339401245,0.0,1739502679.2016869,39.489962339401245,0.17831927590218566,1739502679.2016883,39.489962339401245,4.089100089785886,1739502679.2016895,39.489962339401245,1.050693878466867 +1739502679.228569,39.50996232032776,44.34795274867498,1739502679.2285786,39.50996232032776,6.598878849228061,1739502679.2285903,39.50996232032776,65.11532788649832,1739502679.2286007,39.50996232032776,42.811584274066625,1739502679.2286067,39.50996232032776,2.9411070102468524,1739502679.228613,39.50996232032776,-1.968448557477314,1739502679.228618,39.50996232032776,0.8875989975458408,1739502679.228623,39.50996232032776,0.4301211469891629,1739502679.2286282,39.50996232032776,1.2290131543690526,1739502679.2286346,39.50996232032776,0.0,1739502679.2286396,39.50996232032776,0.17831927590218566,1739502679.2286453,39.50996232032776,4.089100089785886,1739502679.2286506,39.50996232032776,1.050693878466867 +1739502679.250117,39.52996230125427,44.34795274867498,1739502679.2501266,39.52996230125427,6.598878849228061,1739502679.250138,39.52996230125427,65.11532788649832,1739502679.2501533,39.52996230125427,42.811584274066625,1739502679.250157,39.52996230125427,2.9411070102468524,1739502679.250161,39.52996230125427,-1.968448557477314,1739502679.2501643,39.52996230125427,0.8875989975458408,1739502679.250167,39.52996230125427,0.4301211469891629,1739502679.2501695,39.52996230125427,1.2290131543690526,1739502679.2501726,39.52996230125427,0.0,1739502679.2501752,39.52996230125427,0.17831927590218566,1739502679.250178,39.52996230125427,4.089100089785886,1739502679.250181,39.52996230125427,1.050693878466867 +1739502679.2658246,39.549962282180786,44.34795274867498,1739502679.2658281,39.549962282180786,6.598878849228061,1739502679.2658327,39.549962282180786,65.11532788649832,1739502679.265837,39.549962282180786,42.811584274066625,1739502679.265839,39.549962282180786,2.9411070102468524,1739502679.2658417,39.549962282180786,-1.968448557477314,1739502679.2658436,39.549962282180786,0.8875989975458408,1739502679.2658458,39.549962282180786,0.4301211469891629,1739502679.265848,39.549962282180786,1.2290131543690526,1739502679.26585,39.549962282180786,0.0,1739502679.2658522,39.549962282180786,0.17831927590218566,1739502679.2658544,39.549962282180786,4.089100089785886,1739502679.2658565,39.549962282180786,1.050693878466867 +1739502679.2883806,39.5699622631073,44.280945116959785,1739502679.2883844,39.5699622631073,6.503490517874942,1739502679.28839,39.5699622631073,65.2064656209765,1739502679.2883961,39.5699622631073,42.76916038414714,1739502679.2883995,39.5699622631073,2.8175578031019493,1739502679.288404,39.5699622631073,-1.960021832343225,1739502679.2884078,39.5699622631073,0.8321370375206173,1739502679.2884119,39.5699622631073,0.4002651553896347,1739502679.2884157,39.5699622631073,1.2847717830791086,1739502679.2884197,39.5699622631073,0.0,1739502679.288424,39.5699622631073,0.23069711285818284,1739502679.288428,39.5699622631073,4.112739951095686,1739502679.2884321,39.5699622631073,1.0704427550014275 +1739502679.3071697,39.58996224403381,44.280945116959785,1739502679.307174,39.58996224403381,6.503490517874942,1739502679.3071785,39.58996224403381,65.2064656209765,1739502679.3071835,39.58996224403381,42.76916038414714,1739502679.3071861,39.58996224403381,2.8175578031019493,1739502679.3071902,39.58996224403381,-1.960021832343225,1739502679.3071935,39.58996224403381,0.8321370375206173,1739502679.3071966,39.58996224403381,0.4002651553896347,1739502679.3072,39.58996224403381,1.2847717830791086,1739502679.3072035,39.58996224403381,0.0,1739502679.3072069,39.58996224403381,0.21432902807768106,1739502679.3072104,39.58996224403381,4.112739951095686,1739502679.3072138,39.58996224403381,1.0704427550014275 +1739502679.326848,39.60996222496033,44.280945116959785,1739502679.3268523,39.60996222496033,6.503490517874942,1739502679.3268573,39.60996222496033,65.2064656209765,1739502679.3268626,39.60996222496033,42.76916038414714,1739502679.3268654,39.60996222496033,2.8175578031019493,1739502679.3268692,39.60996222496033,-1.960021832343225,1739502679.3268726,39.60996222496033,0.8321370375206173,1739502679.3268762,39.60996222496033,0.4002651553896347,1739502679.3268795,39.60996222496033,1.2847717830791086,1739502679.326883,39.60996222496033,0.0,1739502679.3268867,39.60996222496033,0.21432902807768106,1739502679.3269143,39.60996222496033,4.112739951095686,1739502679.3269176,39.60996222496033,1.0704427550014275 +1739502679.3451684,39.62996220588684,44.280945116959785,1739502679.3451712,39.62996220588684,6.503490517874942,1739502679.345174,39.62996220588684,65.2064656209765,1739502679.345177,39.62996220588684,42.76916038414714,1739502679.3451781,39.62996220588684,2.8175578031019493,1739502679.3451796,39.62996220588684,-1.960021832343225,1739502679.3451812,39.62996220588684,0.8321370375206173,1739502679.3451824,39.62996220588684,0.4002651553896347,1739502679.3451834,39.62996220588684,1.2847717830791086,1739502679.3451853,39.62996220588684,0.0,1739502679.3451865,39.62996220588684,0.21432902807768106,1739502679.345188,39.62996220588684,4.112739951095686,1739502679.345189,39.62996220588684,1.0704427550014275 +1739502679.365061,39.649962186813354,44.280945116959785,1739502679.3650637,39.649962186813354,6.503490517874942,1739502679.3650665,39.649962186813354,65.2064656209765,1739502679.3650692,39.649962186813354,42.76916038414714,1739502679.3650703,39.649962186813354,2.8175578031019493,1739502679.365072,39.649962186813354,-1.960021832343225,1739502679.3650734,39.649962186813354,0.8321370375206173,1739502679.3650746,39.649962186813354,0.4002651553896347,1739502679.3650758,39.649962186813354,1.2847717830791086,1739502679.3650773,39.649962186813354,0.0,1739502679.3650784,39.649962186813354,0.21432902807768106,1739502679.3650799,39.649962186813354,4.112739951095686,1739502679.365081,39.649962186813354,1.0704427550014275 +1739502679.3849998,39.66996216773987,44.21484464058674,1739502679.3850029,39.66996216773987,6.4046419893506155,1739502679.3850057,39.66996216773987,65.33076129102716,1739502679.3850083,39.66996216773987,42.710911036533425,1739502679.3850102,39.66996216773987,2.6566134801643426,1739502679.3850117,39.66996216773987,-1.9523883661303614,1739502679.3850133,39.66996216773987,0.7860297324898056,1739502679.3850145,39.66996216773987,0.3682726082234923,1739502679.3850155,39.66996216773987,1.3330465287581212,1739502679.3850172,39.66996216773987,0.0,1739502679.3850183,39.66996216773987,0.2504437181338079,1739502679.3850195,39.66996216773987,4.134912873671614,1739502679.385021,39.66996216773987,1.0938886586664316 +1739502679.4046006,39.68996214866638,44.21484464058674,1739502679.4046025,39.68996214866638,6.4046419893506155,1739502679.4046054,39.68996214866638,65.33076129102716,1739502679.404608,39.68996214866638,42.710911036533425,1739502679.4046092,39.68996214866638,2.6566134801643426,1739502679.404611,39.68996214866638,-1.9523883661303614,1739502679.4046125,39.68996214866638,0.7860297324898056,1739502679.4046142,39.68996214866638,0.3682726082234923,1739502679.4046154,39.68996214866638,1.3330465287581212,1739502679.404617,39.68996214866638,0.0,1739502679.4046183,39.68996214866638,0.23915787009168965,1739502679.4046195,39.68996214866638,4.134912873671614,1739502679.4046211,39.68996214866638,1.0938886586664316 +1739502679.4246073,39.709962129592896,44.21484464058674,1739502679.4246092,39.709962129592896,6.4046419893506155,1739502679.424612,39.709962129592896,65.33076129102716,1739502679.4246147,39.709962129592896,42.710911036533425,1739502679.4246159,39.709962129592896,2.6566134801643426,1739502679.4246175,39.709962129592896,-1.9523883661303614,1739502679.4246187,39.709962129592896,0.7860297324898056,1739502679.42462,39.709962129592896,0.3682726082234923,1739502679.4246213,39.709962129592896,1.3330465287581212,1739502679.4246225,39.709962129592896,0.0,1739502679.424624,39.709962129592896,0.23915787009168965,1739502679.4246252,39.709962129592896,4.134912873671614,1739502679.4246266,39.709962129592896,1.0938886586664316 +1739502679.4573262,39.72996211051941,44.21484464058674,1739502679.4573352,39.72996211051941,6.4046419893506155,1739502679.4573457,39.72996211051941,65.33076129102716,1739502679.4573557,39.72996211051941,42.710911036533425,1739502679.4573607,39.72996211051941,2.6566134801643426,1739502679.4573667,39.72996211051941,-1.9523883661303614,1739502679.457372,39.72996211051941,0.7860297324898056,1739502679.4573765,39.72996211051941,0.3682726082234923,1739502679.4573815,39.72996211051941,1.3330465287581212,1739502679.457387,39.72996211051941,0.0,1739502679.4573922,39.72996211051941,0.23915787009168965,1739502679.4573972,39.72996211051941,4.134912873671614,1739502679.4574025,39.72996211051941,1.0938886586664316 +1739502679.4742737,39.74996209144592,44.21484464058674,1739502679.4742806,39.74996209144592,6.4046419893506155,1739502679.4742897,39.74996209144592,65.33076129102716,1739502679.4743001,39.74996209144592,42.710911036533425,1739502679.474306,39.74996209144592,2.6566134801643426,1739502679.4743135,39.74996209144592,-1.9523883661303614,1739502679.4743202,39.74996209144592,0.7860297324898056,1739502679.4743268,39.74996209144592,0.3682726082234923,1739502679.4743335,39.74996209144592,1.3330465287581212,1739502679.4743404,39.74996209144592,0.0,1739502679.4743474,39.74996209144592,0.23915787009168965,1739502679.4743543,39.74996209144592,4.134912873671614,1739502679.4743612,39.74996209144592,1.0938886586664316 +1739502679.4896135,39.76996207237244,44.21484464058674,1739502679.4896178,39.76996207237244,6.4046419893506155,1739502679.4896233,39.76996207237244,65.33076129102716,1739502679.4896295,39.76996207237244,42.710911036533425,1739502679.4896328,39.76996207237244,2.6566134801643426,1739502679.4896371,39.76996207237244,-1.9523883661303614,1739502679.4896412,39.76996207237244,0.7860297324898056,1739502679.4896452,39.76996207237244,0.3682726082234923,1739502679.489649,39.76996207237244,1.3330465287581212,1739502679.4896533,39.76996207237244,0.0,1739502679.4896574,39.76996207237244,0.23915787009168965,1739502679.4896615,39.76996207237244,4.134912873671614,1739502679.4896655,39.76996207237244,1.0938886586664316 +1739502679.5267217,39.79996204376221,44.149430954311306,1739502679.526725,39.79996204376221,6.302109489451567,1739502679.5267298,39.79996204376221,65.46786032304153,1739502679.5267346,39.79996204376221,42.640188741608455,1739502679.5267375,39.79996204376221,2.4811167215910537,1739502679.5267413,39.79996204376221,-1.9469736376259628,1739502679.5267446,39.79996204376221,0.7376083954694466,1739502679.526748,39.79996204376221,0.3342481598673533,1739502679.5267513,39.79996204376221,1.3856980439140945,1739502679.5267546,39.79996204376221,0.0,1739502679.526758,39.79996204376221,0.2778338998312451,1739502679.5267613,39.79996204376221,4.155690003732978,1739502679.5267649,39.79996204376221,1.1199504113008347 +1739502679.5474083,39.81996202468872,44.149430954311306,1739502679.5474117,39.81996202468872,6.302109489451567,1739502679.5474162,39.81996202468872,65.46786032304153,1739502679.5474215,39.81996202468872,42.640188741608455,1739502679.547424,39.81996202468872,2.4811167215910537,1739502679.5474277,39.81996202468872,-1.9469736376259628,1739502679.547431,39.81996202468872,0.7376083954694466,1739502679.5474343,39.81996202468872,0.3342481598673533,1739502679.5474374,39.81996202468872,1.3856980439140945,1739502679.5474412,39.81996202468872,0.0,1739502679.547444,39.81996202468872,0.26574763261325973,1739502679.5474474,39.81996202468872,4.155690003732978,1739502679.5474508,39.81996202468872,1.1199504113008347 +1739502679.5669975,39.839962005615234,44.149430954311306,1739502679.5670016,39.839962005615234,6.302109489451567,1739502679.5670063,39.839962005615234,65.46786032304153,1739502679.567028,39.839962005615234,42.640188741608455,1739502679.5670307,39.839962005615234,2.4811167215910537,1739502679.5670347,39.839962005615234,-1.9469736376259628,1739502679.5670376,39.839962005615234,0.7376083954694466,1739502679.567041,39.839962005615234,0.3342481598673533,1739502679.5670443,39.839962005615234,1.3856980439140945,1739502679.5670507,39.839962005615234,0.0,1739502679.567054,39.839962005615234,0.26574763261325973,1739502679.5670574,39.839962005615234,4.155690003732978,1739502679.567061,39.839962005615234,1.1199504113008347 +1739502679.5869443,39.85996198654175,44.149430954311306,1739502679.586948,39.85996198654175,6.302109489451567,1739502679.5869763,39.85996198654175,65.46786032304153,1739502679.5869813,39.85996198654175,42.640188741608455,1739502679.5869842,39.85996198654175,2.4811167215910537,1739502679.5869877,39.85996198654175,-1.9469736376259628,1739502679.586991,39.85996198654175,0.7376083954694466,1739502679.5869944,39.85996198654175,0.3342481598673533,1739502679.5869977,39.85996198654175,1.3856980439140945,1739502679.5870013,39.85996198654175,0.0,1739502679.5870044,39.85996198654175,0.26574763261325973,1739502679.587008,39.85996198654175,4.155690003732978,1739502679.5870113,39.85996198654175,1.1199504113008347 +1739502679.606858,39.87996196746826,44.149430954311306,1739502679.6068618,39.87996196746826,6.302109489451567,1739502679.6068664,39.87996196746826,65.46786032304153,1739502679.6068716,39.87996196746826,42.640188741608455,1739502679.606893,39.87996196746826,2.4811167215910537,1739502679.6068969,39.87996196746826,-1.9469736376259628,1739502679.6069002,39.87996196746826,0.7376083954694466,1739502679.6069038,39.87996196746826,0.3342481598673533,1739502679.6069071,39.87996196746826,1.3856980439140945,1739502679.6069107,39.87996196746826,0.0,1739502679.6069143,39.87996196746826,0.26574763261325973,1739502679.6069176,39.87996196746826,4.155690003732978,1739502679.6069212,39.87996196746826,1.1199504113008347 +1739502679.6271753,39.899961948394775,44.084539466149295,1739502679.627179,39.899961948394775,6.195723217903817,1739502679.6271837,39.899961948394775,65.55889049941742,1739502679.6271887,39.899961948394775,42.57994041150022,1739502679.6271915,39.899961948394775,2.345256987600516,1739502679.6271951,39.899961948394775,-1.9433098389052585,1739502679.6271985,39.899961948394775,0.6779590321677863,1739502679.6272018,39.899961948394775,0.3036256990790963,1739502679.627205,39.899961948394775,1.4534259680418935,1739502679.6272085,39.899961948394775,0.0,1739502679.6272118,39.899961948394775,0.32236817438421744,1739502679.6272151,39.899961948394775,4.175135197863339,1739502679.6272185,39.899961948394775,1.1487517245621455 +1739502679.6445367,39.91996192932129,44.084539466149295,1739502679.6445389,39.91996192932129,6.195723217903817,1739502679.6445417,39.91996192932129,65.55889049941742,1739502679.6445444,39.91996192932129,42.57994041150022,1739502679.6445453,39.91996192932129,2.345256987600516,1739502679.644547,39.91996192932129,-1.9433098389052585,1739502679.6445484,39.91996192932129,0.6779590321677863,1739502679.6445498,39.91996192932129,0.3036256990790963,1739502679.6445513,39.91996192932129,1.4534259680418935,1739502679.6445527,39.91996192932129,0.0,1739502679.644554,39.91996192932129,0.30467424347974803,1739502679.6445553,39.91996192932129,4.175135197863339,1739502679.6445568,39.91996192932129,1.1487517245621455 +1739502679.6647253,39.9399619102478,44.084539466149295,1739502679.6647294,39.9399619102478,6.195723217903817,1739502679.6647346,39.9399619102478,65.55889049941742,1739502679.6647403,39.9399619102478,42.57994041150022,1739502679.6647437,39.9399619102478,2.345256987600516,1739502679.6647608,39.9399619102478,-1.9433098389052585,1739502679.6647644,39.9399619102478,0.6779590321677863,1739502679.664768,39.9399619102478,0.3036256990790963,1739502679.6647713,39.9399619102478,1.4534259680418935,1739502679.664775,39.9399619102478,0.0,1739502679.6647787,39.9399619102478,0.30467424347974803,1739502679.6647823,39.9399619102478,4.175135197863339,1739502679.6647859,39.9399619102478,1.1487517245621455 +1739502679.685028,39.959961891174316,44.084539466149295,1739502679.6850307,39.959961891174316,6.195723217903817,1739502679.6850336,39.959961891174316,65.55889049941742,1739502679.685036,39.959961891174316,42.57994041150022,1739502679.6850374,39.959961891174316,2.345256987600516,1739502679.685039,39.959961891174316,-1.9433098389052585,1739502679.685041,39.959961891174316,0.6779590321677863,1739502679.6850421,39.959961891174316,0.3036256990790963,1739502679.685043,39.959961891174316,1.4534259680418935,1739502679.6850448,39.959961891174316,0.0,1739502679.685046,39.959961891174316,0.30467424347974803,1739502679.6850476,39.959961891174316,4.175135197863339,1739502679.6850488,39.959961891174316,1.1487517245621455 +1739502679.704584,39.97996187210083,44.084539466149295,1739502679.704586,39.97996187210083,6.195723217903817,1739502679.7045887,39.97996187210083,65.55889049941742,1739502679.704591,39.97996187210083,42.57994041150022,1739502679.7045925,39.97996187210083,2.345256987600516,1739502679.704594,39.97996187210083,-1.9433098389052585,1739502679.704595,39.97996187210083,0.6779590321677863,1739502679.7045968,39.97996187210083,0.3036256990790963,1739502679.7045977,39.97996187210083,1.4534259680418935,1739502679.7045994,39.97996187210083,0.0,1739502679.7046006,39.97996187210083,0.30467424347974803,1739502679.7046018,39.97996187210083,4.175135197863339,1739502679.7046032,39.97996187210083,1.1487517245621455 +1739502679.724856,39.999961853027344,44.019947492129425,1739502679.7248583,39.999961853027344,6.085190281307652,1739502679.7248614,39.999961853027344,65.73470666531047,1739502679.7248642,39.999961853027344,42.46852556287881,1739502679.7248654,39.999961853027344,2.12994601318186,1739502679.7248673,39.999961853027344,-1.94459890762032,1739502679.7248688,39.999961853027344,0.6150566147541952,1739502679.7248702,39.999961853027344,0.26102396100594694,1739502679.7248714,39.999961853027344,1.5284366873594344,1739502679.7248747,39.999961853027344,0.0,1739502679.7248785,39.999961853027344,0.3652916442114812,1739502679.7248821,39.999961853027344,4.1933100965130095,1739502679.724887,39.999961853027344,1.1820879932965858 +1739502679.7450838,40.01996183395386,44.019947492129425,1739502679.7450867,40.01996183395386,6.085190281307652,1739502679.7450898,40.01996183395386,65.73470666531047,1739502679.7450926,40.01996183395386,42.46852556287881,1739502679.7450938,40.01996183395386,2.12994601318186,1739502679.7450957,40.01996183395386,-1.94459890762032,1739502679.7450972,40.01996183395386,0.6150566147541952,1739502679.7450986,40.01996183395386,0.26102396100594694,1739502679.7451,40.01996183395386,1.5284366873594344,1739502679.7451015,40.01996183395386,0.0,1739502679.7451031,40.01996183395386,0.3463486940628486,1739502679.7451046,40.01996183395386,4.1933100965130095,1739502679.7451062,40.01996183395386,1.1820879932965858 +1739502679.765,40.03996181488037,44.019947492129425,1739502679.7650025,40.03996181488037,6.085190281307652,1739502679.7650056,40.03996181488037,65.73470666531047,1739502679.7650084,40.03996181488037,42.46852556287881,1739502679.7650096,40.03996181488037,2.12994601318186,1739502679.7650115,40.03996181488037,-1.94459890762032,1739502679.7650127,40.03996181488037,0.6150566147541952,1739502679.7650142,40.03996181488037,0.26102396100594694,1739502679.7650156,40.03996181488037,1.5284366873594344,1739502679.7650173,40.03996181488037,0.0,1739502679.765019,40.03996181488037,0.3463486940628486,1739502679.7650201,40.03996181488037,4.1933100965130095,1739502679.7650218,40.03996181488037,1.1820879932965858 +1739502679.7850776,40.059961795806885,44.019947492129425,1739502679.7850814,40.059961795806885,6.085190281307652,1739502679.7850864,40.059961795806885,65.73470666531047,1739502679.7850926,40.059961795806885,42.46852556287881,1739502679.785096,40.059961795806885,2.12994601318186,1739502679.7851,40.059961795806885,-1.94459890762032,1739502679.7851043,40.059961795806885,0.6150566147541952,1739502679.7851083,40.059961795806885,0.26102396100594694,1739502679.7851121,40.059961795806885,1.5284366873594344,1739502679.785116,40.059961795806885,0.0,1739502679.7851198,40.059961795806885,0.3463486940628486,1739502679.7851238,40.059961795806885,4.1933100965130095,1739502679.7851279,40.059961795806885,1.1820879932965858 +1739502679.8063142,40.0799617767334,44.019947492129425,1739502679.8063183,40.0799617767334,6.085190281307652,1739502679.806323,40.0799617767334,65.73470666531047,1739502679.8063276,40.0799617767334,42.46852556287881,1739502679.8063295,40.0799617767334,2.12994601318186,1739502679.806332,40.0799617767334,-1.94459890762032,1739502679.8063345,40.0799617767334,0.6150566147541952,1739502679.8063369,40.0799617767334,0.26102396100594694,1739502679.8063385,40.0799617767334,1.5284366873594344,1739502679.8063416,40.0799617767334,0.0,1739502679.8063438,40.0799617767334,0.3463486940628486,1739502679.806346,40.0799617767334,4.1933100965130095,1739502679.8063483,40.0799617767334,1.1820879932965858 +1739502679.825897,40.09996175765991,44.019947492129425,1739502679.825901,40.09996175765991,6.085190281307652,1739502679.8259053,40.09996175765991,65.73470666531047,1739502679.8259096,40.09996175765991,42.46852556287881,1739502679.8259118,40.09996175765991,2.12994601318186,1739502679.8259144,40.09996175765991,-1.94459890762032,1739502679.8259165,40.09996175765991,0.6150566147541952,1739502679.8259187,40.09996175765991,0.26102396100594694,1739502679.8259208,40.09996175765991,1.5284366873594344,1739502679.8259234,40.09996175765991,0.0,1739502679.8259256,40.09996175765991,0.3463486940628486,1739502679.8259277,40.09996175765991,4.1933100965130095,1739502679.8259304,40.09996175765991,1.1820879932965858 +1739502679.8468301,40.119961738586426,43.95540742551599,1739502679.8468356,40.119961738586426,5.970139591604212,1739502679.846842,40.119961738586426,65.9231168476777,1739502679.8468494,40.119961738586426,42.33403180508694,1739502679.8468559,40.119961738586426,1.9026214079937578,1739502679.8468635,40.119961738586426,-1.9501085629782808,1739502679.84687,40.119961738586426,0.5363864530174463,1739502679.8468764,40.119961738586426,0.21448421975772125,1739502679.8468833,40.119961738586426,1.6277221271772537,1739502679.84689,40.119961738586426,0.0,1739502679.846897,40.119961738586426,0.4356417562616662,1739502679.8469038,40.119961738586426,4.210271036133182,1739502679.846911,40.119961738586426,1.2199844711480718 +1739502679.8658552,40.13996171951294,43.95540742551599,1739502679.8658586,40.13996171951294,5.970139591604212,1739502679.8658626,40.13996171951294,65.9231168476777,1739502679.8658662,40.13996171951294,42.33403180508694,1739502679.8658683,40.13996171951294,1.9026214079937578,1739502679.8658705,40.13996171951294,-1.9501085629782808,1739502679.8658724,40.13996171951294,0.5363864530174463,1739502679.8658743,40.13996171951294,0.21448421975772125,1739502679.8658757,40.13996171951294,1.6277221271772537,1739502679.865878,40.13996171951294,0.0,1739502679.8658798,40.13996171951294,0.4077376560291819,1739502679.865882,40.13996171951294,4.210271036133182,1739502679.8658836,40.13996171951294,1.2199844711480718 +1739502679.8855324,40.15996170043945,43.95540742551599,1739502679.8855355,40.15996170043945,5.970139591604212,1739502679.8855395,40.15996170043945,65.9231168476777,1739502679.885543,40.15996170043945,42.33403180508694,1739502679.885545,40.15996170043945,1.9026214079937578,1739502679.8855472,40.15996170043945,-1.9501085629782808,1739502679.8855493,40.15996170043945,0.5363864530174463,1739502679.8855512,40.15996170043945,0.21448421975772125,1739502679.8855526,40.15996170043945,1.6277221271772537,1739502679.8855553,40.15996170043945,0.0,1739502679.885557,40.15996170043945,0.4077376560291819,1739502679.8855588,40.15996170043945,4.210271036133182,1739502679.8855608,40.15996170043945,1.2199844711480718 +1739502679.905727,40.17996168136597,43.95540742551599,1739502679.90573,40.17996168136597,5.970139591604212,1739502679.905734,40.17996168136597,65.9231168476777,1739502679.9057379,40.17996168136597,42.33403180508694,1739502679.9057398,40.17996168136597,1.9026214079937578,1739502679.9057422,40.17996168136597,-1.9501085629782808,1739502679.9057438,40.17996168136597,0.5363864530174463,1739502679.905746,40.17996168136597,0.21448421975772125,1739502679.9057477,40.17996168136597,1.6277221271772537,1739502679.90575,40.17996168136597,0.0,1739502679.9057517,40.17996168136597,0.4077376560291819,1739502679.9057536,40.17996168136597,4.210271036133182,1739502679.9057558,40.17996168136597,1.2199844711480718 +1739502679.9253938,40.19996166229248,43.95540742551599,1739502679.925397,40.19996166229248,5.970139591604212,1739502679.9254007,40.19996166229248,65.9231168476777,1739502679.9254043,40.19996166229248,42.33403180508694,1739502679.9254062,40.19996166229248,1.9026214079937578,1739502679.9254088,40.19996166229248,-1.9501085629782808,1739502679.9254107,40.19996166229248,0.5363864530174463,1739502679.9254127,40.19996166229248,0.21448421975772125,1739502679.925414,40.19996166229248,1.6277221271772537,1739502679.9254165,40.19996166229248,0.0,1739502679.9254181,40.19996166229248,0.4077376560291819,1739502679.92542,40.19996166229248,4.210271036133182,1739502679.9254217,40.19996166229248,1.2199844711480718 +1739502679.945784,40.219961643218994,43.89065927590672,1739502679.9457874,40.219961643218994,5.850138539193511,1739502679.9457917,40.219961643218994,65.98983010691589,1739502679.9457953,40.219961643218994,42.24965573462951,1739502679.9457972,40.219961643218994,1.7730304401320927,1739502679.9457996,40.219961643218994,-1.953449163318698,1739502679.9458015,40.219961643218994,0.4547810084718916,1739502679.9458032,40.219961643218994,0.1806042298411432,1739502679.9458048,40.219961643218994,1.7375323640881235,1739502679.9458072,40.219961643218994,0.0,1739502679.945809,40.219961643218994,0.5035137306790473,1739502679.945811,40.219961643218994,4.226072811269136,1739502679.9458127,40.219961643218994,1.2639486763608245 +1739502679.9655688,40.23996162414551,43.89065927590672,1739502679.9655719,40.23996162414551,5.850138539193511,1739502679.9655762,40.23996162414551,65.98983010691589,1739502679.9655797,40.23996162414551,42.24965573462951,1739502679.965582,40.23996162414551,1.7730304401320927,1739502679.965584,40.23996162414551,-1.953449163318698,1739502679.965586,40.23996162414551,0.4547810084718916,1739502679.9655876,40.23996162414551,0.1806042298411432,1739502679.9655895,40.23996162414551,1.7375323640881235,1739502679.9655917,40.23996162414551,0.0,1739502679.965593,40.23996162414551,0.473583687727299,1739502679.9655952,40.23996162414551,4.226072811269136,1739502679.965597,40.23996162414551,1.2639486763608245 +1739502679.9856591,40.25996160507202,43.89065927590672,1739502679.9856622,40.25996160507202,5.850138539193511,1739502679.9856663,40.25996160507202,65.98983010691589,1739502679.9856699,40.25996160507202,42.24965573462951,1739502679.985672,40.25996160507202,1.7730304401320927,1739502679.9856741,40.25996160507202,-1.953449163318698,1739502679.985676,40.25996160507202,0.4547810084718916,1739502679.9856777,40.25996160507202,0.1806042298411432,1739502679.9856794,40.25996160507202,1.7375323640881235,1739502679.9856813,40.25996160507202,0.0,1739502679.9856832,40.25996160507202,0.473583687727299,1739502679.985685,40.25996160507202,4.226072811269136,1739502679.985687,40.25996160507202,1.2639486763608245 +1739502680.0054889,40.279961585998535,43.89065927590672,1739502680.0054927,40.279961585998535,5.850138539193511,1739502680.0054967,40.279961585998535,65.98983010691589,1739502680.0055003,40.279961585998535,42.24965573462951,1739502680.0055022,40.279961585998535,1.7730304401320927,1739502680.0055046,40.279961585998535,-1.953449163318698,1739502680.0055063,40.279961585998535,0.4547810084718916,1739502680.0055084,40.279961585998535,0.1806042298411432,1739502680.0055099,40.279961585998535,1.7375323640881235,1739502680.005512,40.279961585998535,0.0,1739502680.0055137,40.279961585998535,0.473583687727299,1739502680.0055158,40.279961585998535,4.226072811269136,1739502680.0055175,40.279961585998535,1.2639486763608245 +1739502680.0256047,40.29996156692505,43.89065927590672,1739502680.0256076,40.29996156692505,5.850138539193511,1739502680.0256112,40.29996156692505,65.98983010691589,1739502680.0256152,40.29996156692505,42.24965573462951,1739502680.0256171,40.29996156692505,1.7730304401320927,1739502680.0256193,40.29996156692505,-1.953449163318698,1739502680.0256212,40.29996156692505,0.4547810084718916,1739502680.0256228,40.29996156692505,0.1806042298411432,1739502680.0256245,40.29996156692505,1.7375323640881235,1739502680.0256267,40.29996156692505,0.0,1739502680.0256283,40.29996156692505,0.473583687727299,1739502680.0256305,40.29996156692505,4.226072811269136,1739502680.0256321,40.29996156692505,1.2639486763608245 +1739502680.0459123,40.31996154785156,43.89065927590672,1739502680.0459158,40.31996154785156,5.850138539193511,1739502680.04592,40.31996154785156,65.98983010691589,1739502680.045924,40.31996154785156,42.24965573462951,1739502680.0459259,40.31996154785156,1.7730304401320927,1739502680.0459282,40.31996154785156,-1.953449163318698,1739502680.0459301,40.31996154785156,0.4547810084718916,1739502680.045932,40.31996154785156,0.1806042298411432,1739502680.0459337,40.31996154785156,1.7375323640881235,1739502680.0459359,40.31996154785156,0.0,1739502680.0459378,40.31996154785156,0.473583687727299,1739502680.0459394,40.31996154785156,4.226072811269136,1739502680.0459416,40.31996154785156,1.2639486763608245 +1739502680.0655432,40.339961528778076,43.82532810826379,1739502680.0655463,40.339961528778076,5.724495040791501,1739502680.0655503,40.339961528778076,66.11442593428217,1739502680.0655537,40.339961528778076,42.11699661178501,1739502680.0655556,40.339961528778076,1.5873801846419333,1739502680.0655577,40.339961528778076,-1.9623978065485206,1739502680.0655596,40.339961528778076,0.35778151009390585,1739502680.0655613,40.339961528778076,0.13705870601304496,1739502680.065563,40.339961528778076,1.877733611473321,1739502680.0655649,40.339961528778076,0.0,1739502680.0655668,40.339961528778076,0.602158163607095,1739502680.0655687,40.339961528778076,4.240767900659373,1739502680.0655706,40.339961528778076,1.3157549979224281 +1739502680.0854502,40.35996150970459,43.82532810826379,1739502680.0854533,40.35996150970459,5.724495040791501,1739502680.085457,40.35996150970459,66.11442593428217,1739502680.0854607,40.35996150970459,42.11699661178501,1739502680.0854626,40.35996150970459,1.5873801846419333,1739502680.0854647,40.35996150970459,-1.9623978065485206,1739502680.0854666,40.35996150970459,0.35778151009390585,1739502680.0854685,40.35996150970459,0.13705870601304496,1739502680.0854702,40.35996150970459,1.877733611473321,1739502680.0854723,40.35996150970459,0.0,1739502680.085474,40.35996150970459,0.5619786135508928,1739502680.0854762,40.35996150970459,4.240767900659373,1739502680.0854778,40.35996150970459,1.3157549979224281 +1739502680.105753,40.3799614906311,43.82532810826379,1739502680.105756,40.3799614906311,5.724495040791501,1739502680.1057606,40.3799614906311,66.11442593428217,1739502680.1057649,40.3799614906311,42.11699661178501,1739502680.105767,40.3799614906311,1.5873801846419333,1739502680.1057696,40.3799614906311,-1.9623978065485206,1739502680.1057723,40.3799614906311,0.35778151009390585,1739502680.1057746,40.3799614906311,0.13705870601304496,1739502680.1057768,40.3799614906311,1.877733611473321,1739502680.1057794,40.3799614906311,0.0,1739502680.1057816,40.3799614906311,0.5619786135508928,1739502680.1057837,40.3799614906311,4.240767900659373,1739502680.1057863,40.3799614906311,1.3157549979224281 +1739502680.125585,40.39996147155762,43.82532810826379,1739502680.1255884,40.39996147155762,5.724495040791501,1739502680.1255925,40.39996147155762,66.11442593428217,1739502680.125596,40.39996147155762,42.11699661178501,1739502680.125598,40.39996147155762,1.5873801846419333,1739502680.1256003,40.39996147155762,-1.9623978065485206,1739502680.125602,40.39996147155762,0.35778151009390585,1739502680.1256042,40.39996147155762,0.13705870601304496,1739502680.1256056,40.39996147155762,1.877733611473321,1739502680.125608,40.39996147155762,0.0,1739502680.1256096,40.39996147155762,0.5619786135508928,1739502680.1256115,40.39996147155762,4.240767900659373,1739502680.1256135,40.39996147155762,1.3157549979224281 +1739502680.145691,40.41996145248413,43.82532810826379,1739502680.145694,40.41996145248413,5.724495040791501,1739502680.1456983,40.41996145248413,66.11442593428217,1739502680.1457021,40.41996145248413,42.11699661178501,1739502680.145704,40.41996145248413,1.5873801846419333,1739502680.1457062,40.41996145248413,-1.9623978065485206,1739502680.145708,40.41996145248413,0.35778151009390585,1739502680.1457098,40.41996145248413,0.13705870601304496,1739502680.1457117,40.41996145248413,1.877733611473321,1739502680.1457138,40.41996145248413,0.0,1739502680.1457155,40.41996145248413,0.5619786135508928,1739502680.1457176,40.41996145248413,4.240767900659373,1739502680.1457195,40.41996145248413,1.3157549979224281 +1739502680.1655152,40.439961433410645,43.75905758466241,1739502680.165518,40.439961433410645,5.592495810161582,1739502680.1655219,40.439961433410645,66.32918276969377,1739502680.1655254,40.439961433410645,41.89921265442837,1739502680.1655273,40.439961433410645,1.3319355315816626,1739502680.1655295,40.439961433410645,-1.9823888747319083,1739502680.1655314,40.439961433410645,0.2156224075881395,1739502680.165533,40.439961433410645,0.07660865776554665,1739502680.165535,40.439961433410645,2.103900085365336,1739502680.165537,40.439961433410645,0.0,1739502680.1655385,40.439961433410645,0.8028796279937307,1739502680.1655407,40.439961433410645,4.254397465591249,1739502680.1655424,40.439961433410645,1.3763020737434661 +1739502680.1854432,40.45996141433716,43.75905758466241,1739502680.1854463,40.45996141433716,5.592495810161582,1739502680.1854506,40.45996141433716,66.32918276969377,1739502680.1854541,40.45996141433716,41.89921265442837,1739502680.1854558,40.45996141433716,1.3319355315816626,1739502680.1854582,40.45996141433716,-1.9823888747319083,1739502680.1854603,40.45996141433716,0.2156224075881395,1739502680.1854618,40.45996141433716,0.07660865776554665,1739502680.1854637,40.45996141433716,2.103900085365336,1739502680.1854656,40.45996141433716,0.0,1739502680.1854672,40.45996141433716,0.7275980116218699,1739502680.1854692,40.45996141433716,4.254397465591249,1739502680.185471,40.45996141433716,1.3763020737434661 +1739502680.2058008,40.47996139526367,43.75905758466241,1739502680.205804,40.47996139526367,5.592495810161582,1739502680.2058082,40.47996139526367,66.32918276969377,1739502680.205812,40.47996139526367,41.89921265442837,1739502680.2058136,40.47996139526367,1.3319355315816626,1739502680.2058158,40.47996139526367,-1.9823888747319083,1739502680.205818,40.47996139526367,0.2156224075881395,1739502680.2058196,40.47996139526367,0.07660865776554665,1739502680.2058215,40.47996139526367,2.103900085365336,1739502680.2058234,40.47996139526367,0.0,1739502680.2058253,40.47996139526367,0.7275980116218699,1739502680.2058272,40.47996139526367,4.254397465591249,1739502680.2058294,40.47996139526367,1.3763020737434661 +1739502680.2256246,40.499961376190186,43.75905758466241,1739502680.2256286,40.499961376190186,5.592495810161582,1739502680.2256334,40.499961376190186,66.32918276969377,1739502680.2256374,40.499961376190186,41.89921265442837,1739502680.2256393,40.499961376190186,1.3319355315816626,1739502680.225642,40.499961376190186,-1.9823888747319083,1739502680.2256439,40.499961376190186,0.2156224075881395,1739502680.2256458,40.499961376190186,0.07660865776554665,1739502680.2256477,40.499961376190186,2.103900085365336,1739502680.2256498,40.499961376190186,0.0,1739502680.2256517,40.499961376190186,0.7275980116218699,1739502680.2256536,40.499961376190186,4.254397465591249,1739502680.2256558,40.499961376190186,1.3763020737434661 +1739502680.2458315,40.5199613571167,43.75905758466241,1739502680.2458353,40.5199613571167,5.592495810161582,1739502680.2458394,40.5199613571167,66.32918276969377,1739502680.2458434,40.5199613571167,41.89921265442837,1739502680.2458453,40.5199613571167,1.3319355315816626,1739502680.2458475,40.5199613571167,-1.9823888747319083,1739502680.2458496,40.5199613571167,0.2156224075881395,1739502680.2458513,40.5199613571167,0.07660865776554665,1739502680.2458532,40.5199613571167,2.103900085365336,1739502680.2458553,40.5199613571167,0.0,1739502680.245857,40.5199613571167,0.7275980116218699,1739502680.2458591,40.5199613571167,4.254397465591249,1739502680.2458608,40.5199613571167,1.3763020737434661 +1739502680.2656543,40.53996133804321,43.75905758466241,1739502680.2656574,40.53996133804321,5.592495810161582,1739502680.2656612,40.53996133804321,66.32918276969377,1739502680.265665,40.53996133804321,41.89921265442837,1739502680.2656667,40.53996133804321,1.3319355315816626,1739502680.265669,40.53996133804321,-1.9823888747319083,1739502680.265671,40.53996133804321,0.2156224075881395,1739502680.2656727,40.53996133804321,0.07660865776554665,1739502680.2656746,40.53996133804321,2.103900085365336,1739502680.2656765,40.53996133804321,0.0,1739502680.2656784,40.53996133804321,0.7275980116218699,1739502680.2656806,40.53996133804321,4.254397465591249,1739502680.2656827,40.53996133804321,1.3763020737434661 +1739502680.2856028,40.55996131896973,43.69119289521759,1739502680.2856061,40.55996131896973,5.452761420004242,1739502680.28561,40.55996131896973,66.4168617148449,1739502680.2856135,40.55996131896973,41.724686871484636,1739502680.2856154,40.55996131896973,1.1576244286223973,1739502680.2856178,40.55996131896973,-2.0001547860478803,1739502680.2856197,40.55996131896973,0.07567780449329715,1739502680.2856214,40.55996131896973,0.026044449065603457,1739502680.285623,40.55996131896973,2.3531350155646495,1739502680.285625,40.55996131896973,0.0,1739502680.285627,40.55996131896973,0.9744410648710566,1739502680.285629,40.55996131896973,4.267009681493933,1739502680.2856307,40.55996131896973,1.4558324554099087 +1739502680.305732,40.57996129989624,43.69119289521759,1739502680.3057353,40.57996129989624,5.452761420004242,1739502680.3057394,40.57996129989624,66.4168617148449,1739502680.3057432,40.57996129989624,41.724686871484636,1739502680.3057451,40.57996129989624,1.1576244286223973,1739502680.3057475,40.57996129989624,-2.0001547860478803,1739502680.3057494,40.57996129989624,0.07567780449329715,1739502680.3057516,40.57996129989624,0.026044449065603457,1739502680.305753,40.57996129989624,2.3531350155646495,1739502680.3057551,40.57996129989624,0.0,1739502680.305757,40.57996129989624,0.8973025601547409,1739502680.305759,40.57996129989624,4.267009681493933,1739502680.305761,40.57996129989624,1.4558324554099087 +1739502680.325508,40.599961280822754,43.69119289521759,1739502680.325511,40.599961280822754,5.452761420004242,1739502680.3255148,40.599961280822754,66.4168617148449,1739502680.3255186,40.599961280822754,41.724686871484636,1739502680.3255203,40.599961280822754,1.1576244286223973,1739502680.3255227,40.599961280822754,-2.0001547860478803,1739502680.3255246,40.599961280822754,0.07567780449329715,1739502680.3255262,40.599961280822754,0.026044449065603457,1739502680.3255281,40.599961280822754,2.3531350155646495,1739502680.32553,40.599961280822754,0.0,1739502680.325532,40.599961280822754,0.8973025601547409,1739502680.3255339,40.599961280822754,4.267009681493933,1739502680.3255358,40.599961280822754,1.4558324554099087 +1739502680.3456142,40.61996126174927,43.69119289521759,1739502680.345618,40.61996126174927,5.452761420004242,1739502680.3456223,40.61996126174927,66.4168617148449,1739502680.3456259,40.61996126174927,41.724686871484636,1739502680.345628,40.61996126174927,1.1576244286223973,1739502680.3456302,40.61996126174927,-2.0001547860478803,1739502680.3456326,40.61996126174927,0.07567780449329715,1739502680.3456342,40.61996126174927,0.026044449065603457,1739502680.3456361,40.61996126174927,2.3531350155646495,1739502680.3456388,40.61996126174927,0.0,1739502680.3456404,40.61996126174927,0.8973025601547409,1739502680.3456426,40.61996126174927,4.267009681493933,1739502680.3456445,40.61996126174927,1.4558324554099087 +1739502680.3652053,40.63996124267578,43.69119289521759,1739502680.3652086,40.63996124267578,5.452761420004242,1739502680.3652124,40.63996124267578,66.4168617148449,1739502680.365216,40.63996124267578,41.724686871484636,1739502680.3652184,40.63996124267578,1.1576244286223973,1739502680.3652205,40.63996124267578,-2.0001547860478803,1739502680.3652225,40.63996124267578,0.07567780449329715,1739502680.3652241,40.63996124267578,0.026044449065603457,1739502680.365226,40.63996124267578,2.3531350155646495,1739502680.365228,40.63996124267578,0.0,1739502680.3652298,40.63996124267578,0.8973025601547409,1739502680.3652315,40.63996124267578,4.267009681493933,1739502680.3652337,40.63996124267578,1.4558324554099087 +1739502680.387729,40.659961223602295,43.62098625293405,1739502680.387734,40.659961223602295,5.303612723936526,1739502680.38774,40.659961223602295,66.6535665591532,1739502680.387746,40.659961223602295,41.39271084132243,1739502680.3877497,40.659961223602295,0.8856506009445924,1739502680.387754,40.659961223602295,-2.037931629886639,1739502680.3877578,40.659961223602295,-0.165213627114184,1739502680.3877618,40.659961223602295,-0.05181894951529288,1739502680.3877661,40.659961223602295,2.19047809929551,1739502680.3877702,40.659961223602295,0.0,1739502680.3877742,40.659961223602295,0.5205619148564565,1739502680.3877783,40.659961223602295,4.278649254254395,1739502680.3877828,40.659961223602295,1.5521846555925343 +1739502680.4052622,40.67996120452881,43.62098625293405,1739502680.4052649,40.67996120452881,5.303612723936526,1739502680.4052677,40.67996120452881,66.6535665591532,1739502680.4052706,40.67996120452881,41.39271084132243,1739502680.405272,40.67996120452881,0.8856506009445924,1739502680.4052737,40.67996120452881,-2.037931629886639,1739502680.4052749,40.67996120452881,-0.165213627114184,1739502680.4052763,40.67996120452881,-0.05181894951529288,1739502680.4052777,40.67996120452881,2.19047809929551,1739502680.4052792,40.67996120452881,0.0,1739502680.4052806,40.67996120452881,0.6382934437029759,1739502680.405282,40.67996120452881,4.278649254254395,1739502680.4052837,40.67996120452881,1.5521846555925343 +1739502680.4249346,40.69996118545532,43.62098625293405,1739502680.4249375,40.69996118545532,5.303612723936526,1739502680.4249408,40.69996118545532,66.6535665591532,1739502680.4249434,40.69996118545532,41.39271084132243,1739502680.4249449,40.69996118545532,0.8856506009445924,1739502680.4249465,40.69996118545532,-2.037931629886639,1739502680.424948,40.69996118545532,-0.165213627114184,1739502680.4249492,40.69996118545532,-0.05181894951529288,1739502680.4249506,40.69996118545532,2.19047809929551,1739502680.424952,40.69996118545532,0.0,1739502680.4249535,40.69996118545532,0.6382934437029759,1739502680.424955,40.69996118545532,4.278649254254395,1739502680.4249563,40.69996118545532,1.5521846555925343 +1739502680.444521,40.719961166381836,43.62098625293405,1739502680.4445233,40.719961166381836,5.303612723936526,1739502680.4445262,40.719961166381836,66.6535665591532,1739502680.4445286,40.719961166381836,41.39271084132243,1739502680.44453,40.719961166381836,0.8856506009445924,1739502680.4445317,40.719961166381836,-2.037931629886639,1739502680.4445336,40.719961166381836,-0.165213627114184,1739502680.4445348,40.719961166381836,-0.05181894951529288,1739502680.444536,40.719961166381836,2.19047809929551,1739502680.4445376,40.719961166381836,0.0,1739502680.4445388,40.719961166381836,0.6382934437029759,1739502680.4445403,40.719961166381836,4.278649254254395,1739502680.4445415,40.719961166381836,1.5521846555925343 +1739502680.464714,40.73996114730835,43.62098625293405,1739502680.4647164,40.73996114730835,5.303612723936526,1739502680.4647195,40.73996114730835,66.6535665591532,1739502680.4647224,40.73996114730835,41.39271084132243,1739502680.4647238,40.73996114730835,0.8856506009445924,1739502680.4647255,40.73996114730835,-2.037931629886639,1739502680.4647267,40.73996114730835,-0.165213627114184,1739502680.4647284,40.73996114730835,-0.05181894951529288,1739502680.4647295,40.73996114730835,2.19047809929551,1739502680.4647489,40.73996114730835,0.0,1739502680.46475,40.73996114730835,0.6382934437029759,1739502680.4647512,40.73996114730835,4.278649254254395,1739502680.464753,40.73996114730835,1.5521846555925343 +1739502680.4849668,40.75996112823486,43.62098625293405,1739502680.484969,40.75996112823486,5.303612723936526,1739502680.4849718,40.75996112823486,66.6535665591532,1739502680.4849746,40.75996112823486,41.39271084132243,1739502680.4849758,40.75996112823486,0.8856506009445924,1739502680.4849775,40.75996112823486,-2.037931629886639,1739502680.484979,40.75996112823486,-0.165213627114184,1739502680.4849806,40.75996112823486,-0.05181894951529288,1739502680.4849818,40.75996112823486,2.19047809929551,1739502680.4849832,40.75996112823486,0.0,1739502680.4849846,40.75996112823486,0.6382934437029759,1739502680.4849858,40.75996112823486,4.278649254254395,1739502680.4849875,40.75996112823486,1.5521846555925343 +1739502680.504906,40.77996110916138,43.54867757999823,1739502680.5049086,40.77996110916138,5.145431621012044,1739502680.5049117,40.77996110916138,66.89953670712414,1739502680.5049148,40.77996110916138,41.075507614180346,1739502680.5049162,40.77996110916138,0.6788964864947077,1739502680.5049179,40.77996110916138,-2.0764842651809037,1739502680.5049193,40.77996110916138,-0.42143969748874155,1739502680.5049205,40.77996110916138,-0.12409835637520397,1739502680.5049222,40.77996110916138,1.7845012668796068,1739502680.5049236,40.77996110916138,0.0,1739502680.504925,40.77996110916138,-0.048830677608906525,1739502680.5049264,40.77996110916138,4.289340691627053,1739502680.5049276,40.77996110916138,1.6186055157929324 +1739502680.524664,40.79996109008789,43.54867757999823,1739502680.5246663,40.79996109008789,5.145431621012044,1739502680.5246692,40.79996109008789,66.89953670712414,1739502680.5246844,40.79996109008789,41.075507614180346,1739502680.524689,40.79996109008789,0.6788964864947077,1739502680.5246942,40.79996109008789,-2.0764842651809037,1739502680.5246987,40.79996109008789,-0.42143969748874155,1739502680.5247028,40.79996109008789,-0.12409835637520397,1739502680.5247066,40.79996109008789,1.7845012668796068,1739502680.5247107,40.79996109008789,0.0,1739502680.5247145,40.79996109008789,0.16589575108667431,1739502680.5247185,40.79996109008789,4.289340691627053,1739502680.5247226,40.79996109008789,1.6186055157929324 +1739502680.5450573,40.819961071014404,43.54867757999823,1739502680.54506,40.819961071014404,5.145431621012044,1739502680.5450633,40.819961071014404,66.89953670712414,1739502680.5450664,40.819961071014404,41.075507614180346,1739502680.545068,40.819961071014404,0.6788964864947077,1739502680.54507,40.819961071014404,-2.0764842651809037,1739502680.5450716,40.819961071014404,-0.42143969748874155,1739502680.5450733,40.819961071014404,-0.12409835637520397,1739502680.5450745,40.819961071014404,1.7845012668796068,1739502680.5450761,40.819961071014404,0.0,1739502680.5450778,40.819961071014404,0.16589575108667431,1739502680.5450795,40.819961071014404,4.289340691627053,1739502680.5450814,40.819961071014404,1.6186055157929324 +1739502680.5653858,40.83996105194092,43.54867757999823,1739502680.565389,40.83996105194092,5.145431621012044,1739502680.5653927,40.83996105194092,66.89953670712414,1739502680.5653963,40.83996105194092,41.075507614180346,1739502680.565398,40.83996105194092,0.6788964864947077,1739502680.5654004,40.83996105194092,-2.0764842651809037,1739502680.565402,40.83996105194092,-0.42143969748874155,1739502680.5654037,40.83996105194092,-0.12409835637520397,1739502680.5654054,40.83996105194092,1.7845012668796068,1739502680.5654075,40.83996105194092,0.0,1739502680.5654092,40.83996105194092,0.16589575108667431,1739502680.565411,40.83996105194092,4.289340691627053,1739502680.5654128,40.83996105194092,1.6186055157929324 +1739502680.5853577,40.85996103286743,43.54867757999823,1739502680.5853605,40.85996103286743,5.145431621012044,1739502680.5853646,40.85996103286743,66.89953670712414,1739502680.585368,40.85996103286743,41.075507614180346,1739502680.5853696,40.85996103286743,0.6788964864947077,1739502680.585372,40.85996103286743,-2.0764842651809037,1739502680.5853736,40.85996103286743,-0.42143969748874155,1739502680.5853755,40.85996103286743,-0.12409835637520397,1739502680.585377,40.85996103286743,1.7845012668796068,1739502680.5853791,40.85996103286743,0.0,1739502680.5853806,40.85996103286743,0.16589575108667431,1739502680.5853825,40.85996103286743,4.289340691627053,1739502680.5853844,40.85996103286743,1.6186055157929324 +1739502680.6056633,40.879961013793945,43.47565661434227,1739502680.6056664,40.879961013793945,4.981270551737543,1739502680.60567,40.879961013793945,67.03122766164026,1739502680.6056736,40.879961013793945,40.91558781424563,1739502680.6056752,40.879961013793945,0.5914398266275426,1739502680.6056774,40.879961013793945,-2.0987576073749072,1739502680.605679,40.879961013793945,-0.5813373298690442,1739502680.6056812,40.879961013793945,-0.17269363218323736,1739502680.6056826,40.879961013793945,1.570228056893437,1739502680.6056848,40.879961013793945,0.0,1739502680.6056864,40.879961013793945,-0.1825842228256523,1739502680.6056886,40.879961013793945,4.29907491384199,1739502680.6056905,40.879961013793945,1.6439122164710418 +1739502680.6254153,40.89996099472046,43.47565661434227,1739502680.6254182,40.89996099472046,4.981270551737543,1739502680.6254222,40.89996099472046,67.03122766164026,1739502680.6254258,40.89996099472046,40.91558781424563,1739502680.6254275,40.89996099472046,0.5914398266275426,1739502680.6254299,40.89996099472046,-2.0987576073749072,1739502680.6254315,40.89996099472046,-0.5813373298690442,1739502680.6254332,40.89996099472046,-0.17269363218323736,1739502680.6254349,40.89996099472046,1.570228056893437,1739502680.625437,40.89996099472046,0.0,1739502680.6254387,40.89996099472046,-0.07368415957760477,1739502680.6254406,40.89996099472046,4.29907491384199,1739502680.6254425,40.89996099472046,1.6439122164710418 +1739502680.6454177,40.91996097564697,43.47565661434227,1739502680.645421,40.91996097564697,4.981270551737543,1739502680.645425,40.91996097564697,67.03122766164026,1739502680.6454287,40.91996097564697,40.91558781424563,1739502680.6454306,40.91996097564697,0.5914398266275426,1739502680.645433,40.91996097564697,-2.0987576073749072,1739502680.6454346,40.91996097564697,-0.5813373298690442,1739502680.6454365,40.91996097564697,-0.17269363218323736,1739502680.6454382,40.91996097564697,1.570228056893437,1739502680.6454403,40.91996097564697,0.0,1739502680.6454418,40.91996097564697,-0.07368415957760477,1739502680.645444,40.91996097564697,4.29907491384199,1739502680.6454456,40.91996097564697,1.6439122164710418 +1739502680.6653914,40.939960956573486,43.47565661434227,1739502680.665394,40.939960956573486,4.981270551737543,1739502680.6653984,40.939960956573486,67.03122766164026,1739502680.665402,40.939960956573486,40.91558781424563,1739502680.6654034,40.939960956573486,0.5914398266275426,1739502680.665406,40.939960956573486,-2.0987576073749072,1739502680.6654077,40.939960956573486,-0.5813373298690442,1739502680.6654096,40.939960956573486,-0.17269363218323736,1739502680.665411,40.939960956573486,1.570228056893437,1739502680.6654131,40.939960956573486,0.0,1739502680.6654148,40.939960956573486,-0.07368415957760477,1739502680.6654167,40.939960956573486,4.29907491384199,1739502680.6654189,40.939960956573486,1.6439122164710418 +1739502680.6853511,40.9599609375,43.47565661434227,1739502680.6853545,40.9599609375,4.981270551737543,1739502680.6853583,40.9599609375,67.03122766164026,1739502680.6853619,40.9599609375,40.91558781424563,1739502680.6853635,40.9599609375,0.5914398266275426,1739502680.6853657,40.9599609375,-2.0987576073749072,1739502680.6853676,40.9599609375,-0.5813373298690442,1739502680.6853693,40.9599609375,-0.17269363218323736,1739502680.685371,40.9599609375,1.570228056893437,1739502680.6853728,40.9599609375,0.0,1739502680.6853747,40.9599609375,-0.07368415957760477,1739502680.6853764,40.9599609375,4.29907491384199,1739502680.6853783,40.9599609375,1.6439122164710418 +1739502680.7056446,40.979960918426514,43.47565661434227,1739502680.705648,40.979960918426514,4.981270551737543,1739502680.705652,40.979960918426514,67.03122766164026,1739502680.7056556,40.979960918426514,40.91558781424563,1739502680.7056572,40.979960918426514,0.5914398266275426,1739502680.7056596,40.979960918426514,-2.0987576073749072,1739502680.7056615,40.979960918426514,-0.5813373298690442,1739502680.7056632,40.979960918426514,-0.17269363218323736,1739502680.705665,40.979960918426514,1.570228056893437,1739502680.705667,40.979960918426514,0.0,1739502680.7056687,40.979960918426514,-0.07368415957760477,1739502680.7056706,40.979960918426514,4.29907491384199,1739502680.7056727,40.979960918426514,1.6439122164710418 +1739502680.7254367,40.99996089935303,43.40383916445726,1739502680.72544,40.99996089935303,4.815697594816973,1739502680.7254436,40.99996089935303,67.03605721872654,1739502680.7254472,40.99996089935303,40.92528711691458,1739502680.7254488,40.99996089935303,0.5964760030133427,1739502680.7254512,40.99996089935303,-2.101931545683271,1739502680.725453,40.99996089935303,-0.6176923579006497,1739502680.7254546,40.99996089935303,-0.19782790001947298,1739502680.7254562,40.99996089935303,1.5252172295989825,1739502680.7254584,40.99996089935303,0.0,1739502680.7254603,40.99996089935303,-0.1276938174570042,1739502680.725462,40.99996089935303,4.307821929558391,1739502680.725464,40.99996089935303,1.6360330179025762 +1739502680.7457163,41.01996088027954,43.40383916445726,1739502680.7457192,41.01996088027954,4.815697594816973,1739502680.7457232,41.01996088027954,67.03605721872654,1739502680.7457268,41.01996088027954,40.92528711691458,1739502680.7457287,41.01996088027954,0.5964760030133427,1739502680.7457309,41.01996088027954,-2.101931545683271,1739502680.7457325,41.01996088027954,-0.6176923579006497,1739502680.7457345,41.01996088027954,-0.19782790001947298,1739502680.745736,41.01996088027954,1.5252172295989825,1739502680.745738,41.01996088027954,0.0,1739502680.7457397,41.01996088027954,-0.11081578830359362,1739502680.7457418,41.01996088027954,4.307821929558391,1739502680.7457435,41.01996088027954,1.6360330179025762 +1739502680.7652597,41.039960861206055,43.40383916445726,1739502680.765263,41.039960861206055,4.815697594816973,1739502680.7652667,41.039960861206055,67.03605721872654,1739502680.7652705,41.039960861206055,40.92528711691458,1739502680.7652724,41.039960861206055,0.5964760030133427,1739502680.7652745,41.039960861206055,-2.101931545683271,1739502680.7652764,41.039960861206055,-0.6176923579006497,1739502680.7652786,41.039960861206055,-0.19782790001947298,1739502680.76528,41.039960861206055,1.5252172295989825,1739502680.7652822,41.039960861206055,0.0,1739502680.7652836,41.039960861206055,-0.11081578830359362,1739502680.7652857,41.039960861206055,4.307821929558391,1739502680.7652874,41.039960861206055,1.6360330179025762 +1739502680.7849746,41.05996084213257,43.40383916445726,1739502680.7849774,41.05996084213257,4.815697594816973,1739502680.7849805,41.05996084213257,67.03605721872654,1739502680.7849832,41.05996084213257,40.92528711691458,1739502680.7849844,41.05996084213257,0.5964760030133427,1739502680.7849867,41.05996084213257,-2.101931545683271,1739502680.784988,41.05996084213257,-0.6176923579006497,1739502680.784989,41.05996084213257,-0.19782790001947298,1739502680.7849905,41.05996084213257,1.5252172295989825,1739502680.784992,41.05996084213257,0.0,1739502680.784994,41.05996084213257,-0.11081578830359362,1739502680.784995,41.05996084213257,4.307821929558391,1739502680.7849965,41.05996084213257,1.6360330179025762 +1739502680.8046472,41.07996082305908,43.40383916445726,1739502680.8046494,41.07996082305908,4.815697594816973,1739502680.804652,41.07996082305908,67.03605721872654,1739502680.8046546,41.07996082305908,40.92528711691458,1739502680.8046558,41.07996082305908,0.5964760030133427,1739502680.8046577,41.07996082305908,-2.101931545683271,1739502680.804659,41.07996082305908,-0.6176923579006497,1739502680.8046603,41.07996082305908,-0.19782790001947298,1739502680.8046615,41.07996082305908,1.5252172295989825,1739502680.804663,41.07996082305908,0.0,1739502680.8046644,41.07996082305908,-0.11081578830359362,1739502680.8046658,41.07996082305908,4.307821929558391,1739502680.8046672,41.07996082305908,1.6360330179025762 +1739502680.8248827,41.099960803985596,43.33381696021285,1739502680.8248847,41.099960803985596,4.650525604353186,1739502680.8248878,41.099960803985596,67.04086697349028,1739502680.8248906,41.099960803985596,40.941830608385715,1739502680.8248925,41.099960803985596,0.6050658928156597,1739502680.8248942,41.099960803985596,-2.104776996341631,1739502680.8248954,41.099960803985596,-0.6425849005217806,1739502680.8248968,41.099960803985596,-0.22302173079571705,1739502680.824898,41.099960803985596,1.4951444308742827,1739502680.8249002,41.099960803985596,0.0,1739502680.8249016,41.099960803985596,-0.13750321917659447,1739502680.8249032,41.099960803985596,4.315566365104971,1739502680.8249047,41.099960803985596,1.6243078224350473 +1739502680.845259,41.11996078491211,43.33381696021285,1739502680.845262,41.11996078491211,4.650525604353186,1739502680.8452656,41.11996078491211,67.04086697349028,1739502680.8452687,41.11996078491211,40.941830608385715,1739502680.8452709,41.11996078491211,0.6050658928156597,1739502680.8452728,41.11996078491211,-2.104776996341631,1739502680.8452747,41.11996078491211,-0.6425849005217806,1739502680.8452764,41.11996078491211,-0.22302173079571705,1739502680.845278,41.11996078491211,1.4951444308742827,1739502680.84528,41.11996078491211,0.0,1739502680.8452816,41.11996078491211,-0.12916339156076462,1739502680.8452833,41.11996078491211,4.315566365104971,1739502680.8452852,41.11996078491211,1.6243078224350473 +1739502680.8657105,41.13996076583862,43.33381696021285,1739502680.8657138,41.13996076583862,4.650525604353186,1739502680.8657184,41.13996076583862,67.04086697349028,1739502680.8657222,41.13996076583862,40.941830608385715,1739502680.865724,41.13996076583862,0.6050658928156597,1739502680.8657262,41.13996076583862,-2.104776996341631,1739502680.8657281,41.13996076583862,-0.6425849005217806,1739502680.86573,41.13996076583862,-0.22302173079571705,1739502680.8657315,41.13996076583862,1.4951444308742827,1739502680.8657339,41.13996076583862,0.0,1739502680.8657358,41.13996076583862,-0.12916339156076462,1739502680.8657374,41.13996076583862,4.315566365104971,1739502680.8657396,41.13996076583862,1.6243078224350473 +1739502680.8855896,41.15996074676514,43.33381696021285,1739502680.8855925,41.15996074676514,4.650525604353186,1739502680.8855968,41.15996074676514,67.04086697349028,1739502680.8856003,41.15996074676514,40.941830608385715,1739502680.885602,41.15996074676514,0.6050658928156597,1739502680.8856046,41.15996074676514,-2.104776996341631,1739502680.8856063,41.15996074676514,-0.6425849005217806,1739502680.8856082,41.15996074676514,-0.22302173079571705,1739502680.8856099,41.15996074676514,1.4951444308742827,1739502680.8856122,41.15996074676514,0.0,1739502680.8856142,41.15996074676514,-0.12916339156076462,1739502680.885616,41.15996074676514,4.315566365104971,1739502680.8856182,41.15996074676514,1.6243078224350473 +1739502680.905721,41.17996072769165,43.33381696021285,1739502680.9057245,41.17996072769165,4.650525604353186,1739502680.9057283,41.17996072769165,67.04086697349028,1739502680.9057322,41.17996072769165,40.941830608385715,1739502680.9057338,41.17996072769165,0.6050658928156597,1739502680.9057364,41.17996072769165,-2.104776996341631,1739502680.9057386,41.17996072769165,-0.6425849005217806,1739502680.9057403,41.17996072769165,-0.22302173079571705,1739502680.9057422,41.17996072769165,1.4951444308742827,1739502680.905744,41.17996072769165,0.0,1739502680.905746,41.17996072769165,-0.12916339156076462,1739502680.9057481,41.17996072769165,4.315566365104971,1739502680.9057503,41.17996072769165,1.6243078224350473 +1739502680.9256172,41.199960708618164,43.33381696021285,1739502680.9256208,41.199960708618164,4.650525604353186,1739502680.9256246,41.199960708618164,67.04086697349028,1739502680.9256284,41.199960708618164,40.941830608385715,1739502680.9256306,41.199960708618164,0.6050658928156597,1739502680.9256327,41.199960708618164,-2.104776996341631,1739502680.9256349,41.199960708618164,-0.6425849005217806,1739502680.9256365,41.199960708618164,-0.22302173079571705,1739502680.9256384,41.199960708618164,1.4951444308742827,1739502680.9256408,41.199960708618164,0.0,1739502680.9256425,41.199960708618164,-0.12916339156076462,1739502680.9256446,41.199960708618164,4.315566365104971,1739502680.9256463,41.199960708618164,1.6243078224350473 +1739502680.9457893,41.21996068954468,43.26554903788969,1739502680.9457934,41.21996068954468,4.4861698697564005,1739502680.9457974,41.21996068954468,67.40100505017455,1739502680.9458015,41.21996068954468,40.64079566198971,1739502680.9458034,41.21996068954468,0.4656482183172033,1739502680.945806,41.21996068954468,-2.149164748366473,1739502680.945808,41.21996068954468,-0.8986787848935566,1739502680.9458098,41.21996068954468,-0.29839075689031586,1739502680.9458117,41.21996068954468,1.218167528750256,1739502680.9458137,41.21996068954468,0.0,1739502680.9458158,41.21996068954468,-0.5114955234685237,1739502680.945818,41.21996068954468,4.322299161128889,1739502680.9458199,41.21996068954468,1.6101841826611536 +1739502680.96551,41.23996067047119,43.26554903788969,1739502680.9655132,41.23996067047119,4.4861698697564005,1739502680.9655173,41.23996067047119,67.40100505017455,1739502680.9655213,41.23996067047119,40.64079566198971,1739502680.9655235,41.23996067047119,0.4656482183172033,1739502680.9655259,41.23996067047119,-2.149164748366473,1739502680.9655278,41.23996067047119,-0.8986787848935566,1739502680.9655294,41.23996067047119,-0.29839075689031586,1739502680.965531,41.23996067047119,1.218167528750256,1739502680.9655335,41.23996067047119,0.0,1739502680.9655352,41.23996067047119,-0.3920166539108976,1739502680.965537,41.23996067047119,4.322299161128889,1739502680.9655392,41.23996067047119,1.6101841826611536 +1739502680.9854646,41.259960651397705,43.26554903788969,1739502680.9854677,41.259960651397705,4.4861698697564005,1739502680.9854717,41.259960651397705,67.40100505017455,1739502680.9854755,41.259960651397705,40.64079566198971,1739502680.9854777,41.259960651397705,0.4656482183172033,1739502680.9854798,41.259960651397705,-2.149164748366473,1739502680.9854822,41.259960651397705,-0.8986787848935566,1739502680.9854841,41.259960651397705,-0.29839075689031586,1739502680.9854858,41.259960651397705,1.218167528750256,1739502680.985488,41.259960651397705,0.0,1739502680.9854896,41.259960651397705,-0.3920166539108976,1739502680.9854918,41.259960651397705,4.322299161128889,1739502680.9854937,41.259960651397705,1.6101841826611536 +1739502681.005797,41.27996063232422,43.26554903788969,1739502681.0058005,41.27996063232422,4.4861698697564005,1739502681.0058045,41.27996063232422,67.40100505017455,1739502681.0058084,41.27996063232422,40.64079566198971,1739502681.0058105,41.27996063232422,0.4656482183172033,1739502681.0058126,41.27996063232422,-2.149164748366473,1739502681.0058148,41.27996063232422,-0.8986787848935566,1739502681.0058165,41.27996063232422,-0.29839075689031586,1739502681.0058184,41.27996063232422,1.218167528750256,1739502681.0058208,41.27996063232422,0.0,1739502681.0058224,41.27996063232422,-0.3920166539108976,1739502681.0058246,41.27996063232422,4.322299161128889,1739502681.0058265,41.27996063232422,1.6101841826611536 +1739502681.0252953,41.29996061325073,43.26554903788969,1739502681.0252986,41.29996061325073,4.4861698697564005,1739502681.025303,41.29996061325073,67.40100505017455,1739502681.025307,41.29996061325073,40.64079566198971,1739502681.0253086,41.29996061325073,0.4656482183172033,1739502681.025311,41.29996061325073,-2.149164748366473,1739502681.0253127,41.29996061325073,-0.8986787848935566,1739502681.0253146,41.29996061325073,-0.29839075689031586,1739502681.0253162,41.29996061325073,1.218167528750256,1739502681.0253186,41.29996061325073,0.0,1739502681.0253208,41.29996061325073,-0.3920166539108976,1739502681.0253227,41.29996061325073,4.322299161128889,1739502681.0253246,41.29996061325073,1.6101841826611536 +1739502681.0458724,41.319960594177246,43.199256158678075,1739502681.045876,41.319960594177246,4.3237047370920365,1739502681.0458803,41.319960594177246,67.41388927742146,1739502681.0458841,41.319960594177246,40.691904895719276,1739502681.0458863,41.319960594177246,0.48683295639169855,1739502681.0458884,41.319960594177246,-2.149619953358518,1739502681.0458903,41.319960594177246,-0.8855914871577935,1739502681.0458922,41.319960594177246,-0.322496011267461,1739502681.045894,41.319960594177246,1.2309885455313305,1739502681.0458963,41.319960594177246,0.0,1739502681.045898,41.319960594177246,-0.3237603670175679,1739502681.0459,41.319960594177246,4.32800145057792,1739502681.045902,41.319960594177246,1.5760790161881697 +1739502681.065304,41.33996057510376,43.199256158678075,1739502681.0653074,41.33996057510376,4.3237047370920365,1739502681.0653114,41.33996057510376,67.41388927742146,1739502681.0653152,41.33996057510376,40.691904895719276,1739502681.0653172,41.33996057510376,0.48683295639169855,1739502681.0653195,41.33996057510376,-2.149619953358518,1739502681.0653214,41.33996057510376,-0.8855914871577935,1739502681.0653234,41.33996057510376,-0.322496011267461,1739502681.065325,41.33996057510376,1.2309885455313305,1739502681.0653272,41.33996057510376,0.0,1739502681.065329,41.33996057510376,-0.3450904706568392,1739502681.0653312,41.33996057510376,4.32800145057792,1739502681.0653334,41.33996057510376,1.5760790161881697 +1739502681.092999,41.35996055603027,43.199256158678075,1739502681.0930076,41.35996055603027,4.3237047370920365,1739502681.0930197,41.35996055603027,67.41388927742146,1739502681.0930297,41.35996055603027,40.691904895719276,1739502681.0930343,41.35996055603027,0.48683295639169855,1739502681.0930405,41.35996055603027,-2.149619953358518,1739502681.0930452,41.35996055603027,-0.8855914871577935,1739502681.0930498,41.35996055603027,-0.322496011267461,1739502681.0930548,41.35996055603027,1.2309885455313305,1739502681.09306,41.35996055603027,0.0,1739502681.093065,41.35996055603027,-0.3450904706568392,1739502681.0930698,41.35996055603027,4.32800145057792,1739502681.093075,41.35996055603027,1.5760790161881697 +1739502681.1234312,41.389960527420044,43.199256158678075,1739502681.123439,41.389960527420044,4.3237047370920365,1739502681.123449,41.389960527420044,67.41388927742146,1739502681.1234596,41.389960527420044,40.691904895719276,1739502681.1234648,41.389960527420044,0.48683295639169855,1739502681.1234708,41.389960527420044,-2.149619953358518,1739502681.1234763,41.389960527420044,-0.8855914871577935,1739502681.123481,41.389960527420044,-0.322496011267461,1739502681.123486,41.389960527420044,1.2309885455313305,1739502681.1234918,41.389960527420044,0.0,1739502681.1234965,41.389960527420044,-0.3450904706568392,1739502681.1235018,41.389960527420044,4.32800145057792,1739502681.123507,41.389960527420044,1.5760790161881697 +1739502681.1468096,41.40996050834656,43.199256158678075,1739502681.1468189,41.40996050834656,4.3237047370920365,1739502681.1468298,41.40996050834656,67.41388927742146,1739502681.1468396,41.40996050834656,40.691904895719276,1739502681.1468444,41.40996050834656,0.48683295639169855,1739502681.1468503,41.40996050834656,-2.149619953358518,1739502681.146855,41.40996050834656,-0.8855914871577935,1739502681.14686,41.40996050834656,-0.322496011267461,1739502681.1468647,41.40996050834656,1.2309885455313305,1739502681.1468704,41.40996050834656,0.0,1739502681.1468751,41.40996050834656,-0.3450904706568392,1739502681.1468801,41.40996050834656,4.32800145057792,1739502681.1468856,41.40996050834656,1.5760790161881697 +1739502681.1813176,41.449960470199585,43.135217579243886,1739502681.1813223,41.449960470199585,4.164391114185152,1739502681.1813278,41.449960470199585,67.42651098704923,1739502681.181333,41.449960470199585,40.741302228455844,1739502681.1813354,41.449960470199585,0.5083991798406686,1739502681.1813388,41.449960470199585,-2.1505330983045248,1739502681.1813421,41.449960470199585,-0.8681271292782405,1739502681.1813447,41.449960470199585,-0.3475584301371821,1739502681.1813474,41.449960470199585,1.248307992611735,1739502681.1813505,41.449960470199585,0.0,1739502681.1813533,41.449960470199585,-0.27151248584066157,1739502681.181356,41.449960470199585,4.332637600100819,1739502681.1813588,41.449960470199585,1.5428136137829265 +1739502681.200146,41.479960441589355,43.135217579243886,1739502681.200149,41.479960441589355,4.164391114185152,1739502681.2001526,41.479960441589355,67.42651098704923,1739502681.2001557,41.479960441589355,40.741302228455844,1739502681.2001572,41.479960441589355,0.5083991798406686,1739502681.2001593,41.479960441589355,-2.1505330983045248,1739502681.2001607,41.479960441589355,-0.8681271292782405,1739502681.2001626,41.479960441589355,-0.3475584301371821,1739502681.200164,41.479960441589355,1.248307992611735,1739502681.200166,41.479960441589355,0.0,1739502681.2001674,41.479960441589355,-0.2945056211711914,1739502681.2001693,41.479960441589355,4.332637600100819,1739502681.200171,41.479960441589355,1.5428136137829265 +1739502681.2192035,41.49996042251587,43.135217579243886,1739502681.2192063,41.49996042251587,4.164391114185152,1739502681.2192094,41.49996042251587,67.42651098704923,1739502681.2192123,41.49996042251587,40.741302228455844,1739502681.2192135,41.49996042251587,0.5083991798406686,1739502681.2192154,41.49996042251587,-2.1505330983045248,1739502681.2192168,41.49996042251587,-0.8681271292782405,1739502681.2192183,41.49996042251587,-0.3475584301371821,1739502681.2192194,41.49996042251587,1.248307992611735,1739502681.2192209,41.49996042251587,0.0,1739502681.2192223,41.49996042251587,-0.2945056211711914,1739502681.2192237,41.49996042251587,4.332637600100819,1739502681.2192254,41.49996042251587,1.5428136137829265 +1739502681.2396955,41.51996040344238,43.135217579243886,1739502681.2396986,41.51996040344238,4.164391114185152,1739502681.2397015,41.51996040344238,67.42651098704923,1739502681.2397046,41.51996040344238,40.741302228455844,1739502681.2397058,41.51996040344238,0.5083991798406686,1739502681.2397077,41.51996040344238,-2.1505330983045248,1739502681.239709,41.51996040344238,-0.8681271292782405,1739502681.2397106,41.51996040344238,-0.3475584301371821,1739502681.2397118,41.51996040344238,1.248307992611735,1739502681.2397132,41.51996040344238,0.0,1739502681.2397146,41.51996040344238,-0.2945056211711914,1739502681.239716,41.51996040344238,4.332637600100819,1739502681.2397177,41.51996040344238,1.5428136137829265 +1739502681.2588277,41.5399603843689,43.07318573034666,1739502681.2588305,41.5399603843689,4.008200158137457,1739502681.2588334,41.5399603843689,67.46907941349103,1739502681.258836,41.5399603843689,40.76251227236112,1739502681.2588372,41.5399603843689,0.5182186446116313,1739502681.2588391,41.5399603843689,-2.155622098727374,1739502681.2588403,41.5399603843689,-0.8669326939319677,1739502681.2588418,41.5399603843689,-0.37802938440756595,1739502681.258843,41.5399603843689,1.249501381242684,1739502681.2588444,41.5399603843689,0.0,1739502681.2588458,41.5399603843689,-0.2448125116539764,1739502681.2588472,41.5399603843689,4.336196541187949,1739502681.2588484,41.5399603843689,1.509842999802466 +1739502681.281232,41.55996036529541,43.07318573034666,1739502681.281236,41.55996036529541,4.008200158137457,1739502681.2812405,41.55996036529541,67.46907941349103,1739502681.2812457,41.55996036529541,40.76251227236112,1739502681.2812486,41.55996036529541,0.5182186446116313,1739502681.2812521,41.55996036529541,-2.155622098727374,1739502681.2812555,41.55996036529541,-0.8669326939319677,1739502681.2812586,41.55996036529541,-0.37802938440756595,1739502681.281262,41.55996036529541,1.249501381242684,1739502681.2812653,41.55996036529541,0.0,1739502681.2812681,41.55996036529541,-0.260341618559782,1739502681.2812715,41.55996036529541,4.336196541187949,1739502681.281275,41.55996036529541,1.509842999802466 +1739502681.2986667,41.579960346221924,43.07318573034666,1739502681.2986696,41.579960346221924,4.008200158137457,1739502681.298673,41.579960346221924,67.46907941349103,1739502681.2986755,41.579960346221924,40.76251227236112,1739502681.298677,41.579960346221924,0.5182186446116313,1739502681.2986786,41.579960346221924,-2.155622098727374,1739502681.29868,41.579960346221924,-0.8669326939319677,1739502681.2986813,41.579960346221924,-0.37802938440756595,1739502681.2986827,41.579960346221924,1.249501381242684,1739502681.2986841,41.579960346221924,0.0,1739502681.2986856,41.579960346221924,-0.260341618559782,1739502681.2986867,41.579960346221924,4.336196541187949,1739502681.2986882,41.579960346221924,1.509842999802466 +1739502681.318616,41.59996032714844,43.07318573034666,1739502681.318618,41.59996032714844,4.008200158137457,1739502681.3186212,41.59996032714844,67.46907941349103,1739502681.3186238,41.59996032714844,40.76251227236112,1739502681.318625,41.59996032714844,0.5182186446116313,1739502681.3186269,41.59996032714844,-2.155622098727374,1739502681.318628,41.59996032714844,-0.8669326939319677,1739502681.3186293,41.59996032714844,-0.37802938440756595,1739502681.3186307,41.59996032714844,1.249501381242684,1739502681.3186324,41.59996032714844,0.0,1739502681.3186338,41.59996032714844,-0.260341618559782,1739502681.3186352,41.59996032714844,4.336196541187949,1739502681.3186367,41.59996032714844,1.509842999802466 +1739502681.3390498,41.61996030807495,43.07318573034666,1739502681.339053,41.61996030807495,4.008200158137457,1739502681.339056,41.61996030807495,67.46907941349103,1739502681.339059,41.61996030807495,40.76251227236112,1739502681.3390605,41.61996030807495,0.5182186446116313,1739502681.3390622,41.61996030807495,-2.155622098727374,1739502681.3390641,41.61996030807495,-0.8669326939319677,1739502681.3390656,41.61996030807495,-0.37802938440756595,1739502681.339067,41.61996030807495,1.249501381242684,1739502681.3390687,41.61996030807495,0.0,1739502681.3390698,41.61996030807495,-0.260341618559782,1739502681.3390718,41.61996030807495,4.336196541187949,1739502681.3390732,41.61996030807495,1.509842999802466 +1739502681.3588855,41.639960289001465,43.07318573034666,1739502681.3588884,41.639960289001465,4.008200158137457,1739502681.3588917,41.639960289001465,67.46907941349103,1739502681.3588943,41.639960289001465,40.76251227236112,1739502681.3588958,41.639960289001465,0.5182186446116313,1739502681.3588974,41.639960289001465,-2.155622098727374,1739502681.3588986,41.639960289001465,-0.8669326939319677,1739502681.3589,41.639960289001465,-0.37802938440756595,1739502681.3589013,41.639960289001465,1.249501381242684,1739502681.3589034,41.639960289001465,0.0,1739502681.3589046,41.639960289001465,-0.260341618559782,1739502681.358906,41.639960289001465,4.336196541187949,1739502681.3589077,41.639960289001465,1.509842999802466 +1739502681.3787925,41.65996026992798,43.01295574145203,1739502681.3787951,41.65996026992798,3.855181052824962,1739502681.378799,41.65996026992798,67.47155539003741,1739502681.3788016,41.65996026992798,40.819578914980625,1739502681.378803,41.65996026992798,0.5446383865651034,1739502681.3788047,41.65996026992798,-2.155938639115837,1739502681.3788064,41.65996026992798,-0.8333209621660153,1739502681.3788075,41.65996026992798,-0.40336414659146713,1739502681.3788087,41.65996026992798,1.2835555007825084,1739502681.3788104,41.65996026992798,0.0,1739502681.3788116,41.65996026992798,-0.16327259940423616,1739502681.3788133,41.65996026992798,4.338657978803536,1739502681.3788145,41.65996026992798,1.4771621885614308 +1739502681.3988461,41.67996025085449,43.01295574145203,1739502681.3988488,41.67996025085449,3.855181052824962,1739502681.3988516,41.67996025085449,67.47155539003741,1739502681.3988545,41.67996025085449,40.819578914980625,1739502681.398856,41.67996025085449,0.5446383865651034,1739502681.3988574,41.67996025085449,-2.155938639115837,1739502681.3988588,41.67996025085449,-0.8333209621660153,1739502681.39886,41.67996025085449,-0.40336414659146713,1739502681.3988614,41.67996025085449,1.2835555007825084,1739502681.3988628,41.67996025085449,0.0,1739502681.398864,41.67996025085449,-0.19360668777892243,1739502681.3988657,41.67996025085449,4.338657978803536,1739502681.398867,41.67996025085449,1.4771621885614308 +1739502681.4191043,41.699960231781006,43.01295574145203,1739502681.4191062,41.699960231781006,3.855181052824962,1739502681.419109,41.699960231781006,67.47155539003741,1739502681.4191117,41.699960231781006,40.819578914980625,1739502681.419113,41.699960231781006,0.5446383865651034,1739502681.4191146,41.699960231781006,-2.155938639115837,1739502681.4191158,41.699960231781006,-0.8333209621660153,1739502681.419117,41.699960231781006,-0.40336414659146713,1739502681.4191184,41.699960231781006,1.2835555007825084,1739502681.4191198,41.699960231781006,0.0,1739502681.4191213,41.699960231781006,-0.19360668777892243,1739502681.4191225,41.699960231781006,4.338657978803536,1739502681.4191236,41.699960231781006,1.4771621885614308 +1739502681.438596,41.71996021270752,43.01295574145203,1739502681.4385986,41.71996021270752,3.855181052824962,1739502681.4386024,41.71996021270752,67.47155539003741,1739502681.438605,41.71996021270752,40.819578914980625,1739502681.4386063,41.71996021270752,0.5446383865651034,1739502681.4386086,41.71996021270752,-2.155938639115837,1739502681.43861,41.71996021270752,-0.8333209621660153,1739502681.4386117,41.71996021270752,-0.40336414659146713,1739502681.438613,41.71996021270752,1.2835555007825084,1739502681.4386146,41.71996021270752,0.0,1739502681.4386158,41.71996021270752,-0.19360668777892243,1739502681.4386172,41.71996021270752,4.338657978803536,1739502681.438619,41.71996021270752,1.4771621885614308 +1739502681.4586883,41.73996019363403,43.01295574145203,1739502681.4586911,41.73996019363403,3.855181052824962,1739502681.4586942,41.73996019363403,67.47155539003741,1739502681.4586966,41.73996019363403,40.819578914980625,1739502681.458698,41.73996019363403,0.5446383865651034,1739502681.4586997,41.73996019363403,-2.155938639115837,1739502681.4587014,41.73996019363403,-0.8333209621660153,1739502681.4587026,41.73996019363403,-0.40336414659146713,1739502681.4587038,41.73996019363403,1.2835555007825084,1739502681.4587054,41.73996019363403,0.0,1739502681.4587066,41.73996019363403,-0.19360668777892243,1739502681.4587083,41.73996019363403,4.338657978803536,1739502681.45871,41.73996019363403,1.4771621885614308 +1739502681.4789596,41.75996017456055,42.95414466181501,1739502681.4789624,41.75996017456055,3.7049039016101837,1739502681.4789658,41.75996017456055,68.27914949115363,1739502681.4789689,41.75996017456055,40.10495806850803,1739502681.47897,41.75996017456055,0.2753781765883212,1739502681.4789722,41.75996017456055,-2.2640267233198945,1739502681.4789736,41.75996017456055,-1.4061153603287375,1739502681.4789753,41.75996017456055,-0.5373980544903364,1739502681.4789765,41.75996017456055,0.8117185953072014,1739502681.4789784,41.75996017456055,0.0,1739502681.4789798,41.75996017456055,-0.8484643128317292,1739502681.4789815,41.75996017456055,4.340003369734488,1739502681.478983,41.75996017456055,1.4555397661354288 +1739502681.4994926,41.77996015548706,42.95414466181501,1739502681.4994955,41.77996015548706,3.7049039016101837,1739502681.499499,41.77996015548706,68.27914949115363,1739502681.4995024,41.77996015548706,40.10495806850803,1739502681.499504,41.77996015548706,0.2753781765883212,1739502681.4995062,41.77996015548706,-2.2640267233198945,1739502681.499508,41.77996015548706,-1.4061153603287375,1739502681.4995098,41.77996015548706,-0.5373980544903364,1739502681.4995112,41.77996015548706,0.8117185953072014,1739502681.4995134,41.77996015548706,0.0,1739502681.499515,41.77996015548706,-0.6438211708282274,1739502681.499517,41.77996015548706,4.340003369734488,1739502681.4995184,41.77996015548706,1.4555397661354288 +1739502681.5191967,41.799960136413574,42.95414466181501,1739502681.5192,41.799960136413574,3.7049039016101837,1739502681.519204,41.799960136413574,68.27914949115363,1739502681.5192077,41.799960136413574,40.10495806850803,1739502681.5192094,41.799960136413574,0.2753781765883212,1739502681.519212,41.799960136413574,-2.2640267233198945,1739502681.519214,41.799960136413574,-1.4061153603287375,1739502681.5192158,41.799960136413574,-0.5373980544903364,1739502681.5192177,41.799960136413574,0.8117185953072014,1739502681.5192196,41.799960136413574,0.0,1739502681.5192213,41.799960136413574,-0.6438211708282274,1739502681.5192232,41.799960136413574,4.340003369734488,1739502681.5192251,41.799960136413574,1.4555397661354288 +1739502681.539393,41.81996011734009,42.95414466181501,1739502681.5393958,41.81996011734009,3.7049039016101837,1739502681.5393994,41.81996011734009,68.27914949115363,1739502681.5394027,41.81996011734009,40.10495806850803,1739502681.5394046,41.81996011734009,0.2753781765883212,1739502681.5394065,41.81996011734009,-2.2640267233198945,1739502681.5394084,41.81996011734009,-1.4061153603287375,1739502681.53941,41.81996011734009,-0.5373980544903364,1739502681.5394118,41.81996011734009,0.8117185953072014,1739502681.5394137,41.81996011734009,0.0,1739502681.5394156,41.81996011734009,-0.6438211708282274,1739502681.5394173,41.81996011734009,4.340003369734488,1739502681.5394194,41.81996011734009,1.4555397661354288 +1739502681.5592508,41.8399600982666,42.95414466181501,1739502681.5592716,41.8399600982666,3.7049039016101837,1739502681.559277,41.8399600982666,68.27914949115363,1739502681.5592828,41.8399600982666,40.10495806850803,1739502681.5592866,41.8399600982666,0.2753781765883212,1739502681.5592897,41.8399600982666,-2.2640267233198945,1739502681.5593023,41.8399600982666,-1.4061153603287375,1739502681.5593047,41.8399600982666,-0.5373980544903364,1739502681.5593064,41.8399600982666,0.8117185953072014,1739502681.5593102,41.8399600982666,0.0,1739502681.5593212,41.8399600982666,-0.6438211708282274,1739502681.5593245,41.8399600982666,4.340003369734488,1739502681.559328,41.8399600982666,1.4555397661354288 +1739502681.5792365,41.859960079193115,42.95414466181501,1739502681.57924,41.859960079193115,3.7049039016101837,1739502681.5792437,41.859960079193115,68.27914949115363,1739502681.5792475,41.859960079193115,40.10495806850803,1739502681.5792491,41.859960079193115,0.2753781765883212,1739502681.5792515,41.859960079193115,-2.2640267233198945,1739502681.5792532,41.859960079193115,-1.4061153603287375,1739502681.579255,41.859960079193115,-0.5373980544903364,1739502681.5792568,41.859960079193115,0.8117185953072014,1739502681.579259,41.859960079193115,0.0,1739502681.5792603,41.859960079193115,-0.6438211708282274,1739502681.5792623,41.859960079193115,4.340003369734488,1739502681.579264,41.859960079193115,1.4555397661354288 +1739502681.5991635,41.87996006011963,42.89734261908269,1739502681.5991666,41.87996006011963,3.559409600818748,1739502681.5991704,41.87996006011963,68.28185010243801,1739502681.5991743,41.87996006011963,40.24477790319495,1739502681.599176,41.87996006011963,0.3191289290223857,1739502681.599178,41.87996006011963,-2.2567893934420646,1739502681.59918,41.87996006011963,-1.292469253614125,1739502681.599182,41.87996006011963,-0.5594826619231604,1739502681.5991833,41.87996006011963,0.8889763284241763,1739502681.5991855,41.87996006011963,0.0,1739502681.5991871,41.87996006011963,-0.4229299283232433,1739502681.599189,41.87996006011963,4.3401653135963665,1739502681.5991907,41.87996006011963,1.380934815288877 +1739502681.6192114,41.89996004104614,42.89734261908269,1739502681.6192148,41.89996004104614,3.559409600818748,1739502681.6192193,41.89996004104614,68.28185010243801,1739502681.6192229,41.89996004104614,40.24477790319495,1739502681.619225,41.89996004104614,0.3191289290223857,1739502681.6192274,41.89996004104614,-2.2567893934420646,1739502681.619229,41.89996004104614,-1.292469253614125,1739502681.619231,41.89996004104614,-0.5594826619231604,1739502681.6192327,41.89996004104614,0.8889763284241763,1739502681.619235,41.89996004104614,0.0,1739502681.6192372,41.89996004104614,-0.4919584868647007,1739502681.6192389,41.89996004104614,4.3401653135963665,1739502681.6192408,41.89996004104614,1.380934815288877 +1739502681.6392558,41.919960021972656,42.89734261908269,1739502681.6392589,41.919960021972656,3.559409600818748,1739502681.6392627,41.919960021972656,68.28185010243801,1739502681.6392663,41.919960021972656,40.24477790319495,1739502681.639268,41.919960021972656,0.3191289290223857,1739502681.63927,41.919960021972656,-2.2567893934420646,1739502681.639272,41.919960021972656,-1.292469253614125,1739502681.6392736,41.919960021972656,-0.5594826619231604,1739502681.6392753,41.919960021972656,0.8889763284241763,1739502681.6392772,41.919960021972656,0.0,1739502681.6392791,41.919960021972656,-0.4919584868647007,1739502681.639281,41.919960021972656,4.3401653135963665,1739502681.639283,41.919960021972656,1.380934815288877 +1739502681.6592524,41.93996000289917,42.89734261908269,1739502681.6592555,41.93996000289917,3.559409600818748,1739502681.6592593,41.93996000289917,68.28185010243801,1739502681.6592631,41.93996000289917,40.24477790319495,1739502681.659265,41.93996000289917,0.3191289290223857,1739502681.6592672,41.93996000289917,-2.2567893934420646,1739502681.6592689,41.93996000289917,-1.292469253614125,1739502681.6592708,41.93996000289917,-0.5594826619231604,1739502681.6592722,41.93996000289917,0.8889763284241763,1739502681.6592743,41.93996000289917,0.0,1739502681.659276,41.93996000289917,-0.4919584868647007,1739502681.659278,41.93996000289917,4.3401653135963665,1739502681.6592796,41.93996000289917,1.380934815288877 +1739502681.6794488,41.959959983825684,42.89734261908269,1739502681.6794517,41.959959983825684,3.559409600818748,1739502681.6794553,41.959959983825684,68.28185010243801,1739502681.6794589,41.959959983825684,40.24477790319495,1739502681.6794605,41.959959983825684,0.3191289290223857,1739502681.6794627,41.959959983825684,-2.2567893934420646,1739502681.6794643,41.959959983825684,-1.292469253614125,1739502681.6794662,41.959959983825684,-0.5594826619231604,1739502681.6794677,41.959959983825684,0.8889763284241763,1739502681.6794698,41.959959983825684,0.0,1739502681.6794713,41.959959983825684,-0.4919584868647007,1739502681.6794734,41.959959983825684,4.3401653135963665,1739502681.6794748,41.959959983825684,1.380934815288877 +1739502681.6997323,41.9799599647522,42.84303533288678,1739502681.699736,41.9799599647522,3.4204713203572474,1739502681.69974,41.9799599647522,68.70435562471584,1739502681.6997437,41.9799599647522,39.94331340741879,1739502681.6997452,41.9799599647522,0.22952961728722776,1739502681.6997478,41.9799599647522,-2.3084167485095697,1739502681.6997495,41.9799599647522,-1.5362238867525442,1739502681.6997514,41.9799599647522,-0.6108,1739502681.699753,41.9799599647522,0.7314778219833772,1739502681.699755,41.9799599647522,0.0,1739502681.699757,41.9799599647522,-0.6425247733748723,1739502681.6997588,41.9799599647522,4.339067596757311,1739502681.6997607,41.9799599647522,1.3269505999741287 +1739502681.719181,41.99995994567871,42.84303533288678,1739502681.719184,41.99995994567871,3.4204713203572474,1739502681.7191873,41.99995994567871,68.70435562471584,1739502681.7191904,41.99995994567871,39.94331340741879,1739502681.719192,41.99995994567871,0.22952961728722776,1739502681.719194,41.99995994567871,-2.3084167485095697,1739502681.7191954,41.99995994567871,-1.5362238867525442,1739502681.7191973,41.99995994567871,-0.6108,1739502681.7191985,41.99995994567871,0.7314778219833772,1739502681.7192004,41.99995994567871,0.0,1739502681.7192018,41.99995994567871,-0.5954727779907515,1739502681.7192035,41.99995994567871,4.339067596757311,1739502681.7192051,41.99995994567871,1.3269505999741287 +1739502681.7390282,42.019959926605225,42.84303533288678,1739502681.7390306,42.019959926605225,3.4204713203572474,1739502681.7390335,42.019959926605225,68.70435562471584,1739502681.739036,42.019959926605225,39.94331340741879,1739502681.7390378,42.019959926605225,0.22952961728722776,1739502681.7390392,42.019959926605225,-2.3084167485095697,1739502681.7390406,42.019959926605225,-1.5362238867525442,1739502681.739042,42.019959926605225,-0.6108,1739502681.739043,42.019959926605225,0.7314778219833772,1739502681.7390447,42.019959926605225,0.0,1739502681.7390459,42.019959926605225,-0.5954727779907515,1739502681.7390475,42.019959926605225,4.339067596757311,1739502681.739049,42.019959926605225,1.3269505999741287 +1739502681.7586625,42.03995990753174,42.84303533288678,1739502681.7586656,42.03995990753174,3.4204713203572474,1739502681.7586694,42.03995990753174,68.70435562471584,1739502681.7586722,42.03995990753174,39.94331340741879,1739502681.7586737,42.03995990753174,0.22952961728722776,1739502681.7586753,42.03995990753174,-2.3084167485095697,1739502681.758677,42.03995990753174,-1.5362238867525442,1739502681.7586782,42.03995990753174,-0.6108,1739502681.7586796,42.03995990753174,0.7314778219833772,1739502681.7586813,42.03995990753174,0.0,1739502681.7586827,42.03995990753174,-0.5954727779907515,1739502681.7586842,42.03995990753174,4.339067596757311,1739502681.7586856,42.03995990753174,1.3269505999741287 +1739502681.7787676,42.05995988845825,42.84303533288678,1739502681.778771,42.05995988845825,3.4204713203572474,1739502681.7787745,42.05995988845825,68.70435562471584,1739502681.7787774,42.05995988845825,39.94331340741879,1739502681.7787786,42.05995988845825,0.22952961728722776,1739502681.7787805,42.05995988845825,-2.3084167485095697,1739502681.778782,42.05995988845825,-1.5362238867525442,1739502681.7787833,42.05995988845825,-0.6108,1739502681.7787845,42.05995988845825,0.7314778219833772,1739502681.7787864,42.05995988845825,0.0,1739502681.7787876,42.05995988845825,-0.5954727779907515,1739502681.778789,42.05995988845825,4.339067596757311,1739502681.7787907,42.05995988845825,1.3269505999741287 +1739502681.7987773,42.079959869384766,42.84303533288678,1739502681.7987797,42.079959869384766,3.4204713203572474,1739502681.7987828,42.079959869384766,68.70435562471584,1739502681.7987852,42.079959869384766,39.94331340741879,1739502681.7987869,42.079959869384766,0.22952961728722776,1739502681.7987885,42.079959869384766,-2.3084167485095697,1739502681.7987902,42.079959869384766,-1.5362238867525442,1739502681.7987914,42.079959869384766,-0.6108,1739502681.7987924,42.079959869384766,0.7314778219833772,1739502681.798794,42.079959869384766,0.0,1739502681.7987952,42.079959869384766,-0.5954727779907515,1739502681.798797,42.079959869384766,4.339067596757311,1739502681.7987983,42.079959869384766,1.3269505999741287 +1739502681.8186681,42.09995985031128,42.790895977750374,1739502681.8186707,42.09995985031128,3.2877367232804158,1739502681.818674,42.09995985031128,68.86843204714204,1739502681.8186772,42.09995985031128,39.9126092982924,1739502681.8186786,42.09995985031128,0.2216523245731002,1739502681.8186803,42.09995985031128,-2.3246124650084004,1739502681.818682,42.09995985031128,-1.5524274451388824,1739502681.8186834,42.09995985031128,-0.6108,1739502681.8186848,42.09995985031128,0.722056979493667,1739502681.8186867,42.09995985031128,0.0,1739502681.818688,42.09995985031128,-0.5129030054099115,1739502681.8186896,42.09995985031128,4.336667922003423,1739502681.818691,42.09995985031128,1.2607630557529026 +1739502681.8392112,42.11995983123779,42.790895977750374,1739502681.8392134,42.11995983123779,3.2877367232804158,1739502681.8392167,42.11995983123779,68.86843204714204,1739502681.839219,42.11995983123779,39.9126092982924,1739502681.8392208,42.11995983123779,0.2216523245731002,1739502681.8392224,42.11995983123779,-2.3246124650084004,1739502681.8392239,42.11995983123779,-1.5524274451388824,1739502681.839225,42.11995983123779,-0.6108,1739502681.8392265,42.11995983123779,0.722056979493667,1739502681.8392282,42.11995983123779,0.0,1739502681.8392293,42.11995983123779,-0.5387060762592356,1739502681.8392308,42.11995983123779,4.336667922003423,1739502681.839232,42.11995983123779,1.2607630557529026 +1739502681.8595712,42.13995981216431,42.790895977750374,1739502681.8595748,42.13995981216431,3.2877367232804158,1739502681.8595781,42.13995981216431,68.86843204714204,1739502681.8595812,42.13995981216431,39.9126092982924,1739502681.859583,42.13995981216431,0.2216523245731002,1739502681.859585,42.13995981216431,-2.3246124650084004,1739502681.8595865,42.13995981216431,-1.5524274451388824,1739502681.859588,42.13995981216431,-0.6108,1739502681.859589,42.13995981216431,0.722056979493667,1739502681.859591,42.13995981216431,0.0,1739502681.8595924,42.13995981216431,-0.5387060762592356,1739502681.8595936,42.13995981216431,4.336667922003423,1739502681.8595953,42.13995981216431,1.2607630557529026 +1739502681.878831,42.15995979309082,42.790895977750374,1739502681.8788338,42.15995979309082,3.2877367232804158,1739502681.878837,42.15995979309082,68.86843204714204,1739502681.8788397,42.15995979309082,39.9126092982924,1739502681.8788414,42.15995979309082,0.2216523245731002,1739502681.878843,42.15995979309082,-2.3246124650084004,1739502681.878845,42.15995979309082,-1.5524274451388824,1739502681.8788466,42.15995979309082,-0.6108,1739502681.8788483,42.15995979309082,0.722056979493667,1739502681.8788497,42.15995979309082,0.0,1739502681.8788512,42.15995979309082,-0.5387060762592356,1739502681.8788526,42.15995979309082,4.336667922003423,1739502681.8788538,42.15995979309082,1.2607630557529026 +1739502681.8988597,42.179959774017334,42.790895977750374,1739502681.8988621,42.179959774017334,3.2877367232804158,1739502681.898865,42.179959774017334,68.86843204714204,1739502681.8988676,42.179959774017334,39.9126092982924,1739502681.898869,42.179959774017334,0.2216523245731002,1739502681.8988707,42.179959774017334,-2.3246124650084004,1739502681.8988724,42.179959774017334,-1.5524274451388824,1739502681.8988736,42.179959774017334,-0.6108,1739502681.898875,42.179959774017334,0.722056979493667,1739502681.8988764,42.179959774017334,0.0,1739502681.8988776,42.179959774017334,-0.5387060762592356,1739502681.8988793,42.179959774017334,4.336667922003423,1739502681.8988807,42.179959774017334,1.2607630557529026 +1739502681.9189558,42.19995975494385,42.7408958853888,1739502681.9189582,42.19995975494385,3.161562816098746,1739502681.9189608,42.19995975494385,68.9551784645873,1739502681.9189637,42.19995975494385,39.9429546710575,1739502681.9189653,42.19995975494385,0.22942634469836984,1739502681.9189668,42.19995975494385,-2.3327793222924567,1739502681.9189684,42.19995975494385,-1.5127952544529952,1739502681.9189699,42.19995975494385,-0.6108,1739502681.918971,42.19995975494385,0.7453171312201596,1739502681.9189732,42.19995975494385,0.0,1739502681.9189744,42.19995975494385,-0.41900076831441657,1739502681.9189758,42.19995975494385,4.332930317907047,1739502681.9189773,42.19995975494385,1.2017258327938845 +1739502681.9393947,42.21995973587036,42.7408958853888,1739502681.9393973,42.21995973587036,3.161562816098746,1739502681.9394007,42.21995973587036,68.9551784645873,1739502681.9394035,42.21995973587036,39.9429546710575,1739502681.9394047,42.21995973587036,0.22942634469836984,1739502681.9394066,42.21995973587036,-2.3327793222924567,1739502681.939408,42.21995973587036,-1.5127952544529952,1739502681.9394097,42.21995973587036,-0.6108,1739502681.939411,42.21995973587036,0.7453171312201596,1739502681.9394128,42.21995973587036,0.0,1739502681.9394143,42.21995973587036,-0.4564087015737248,1739502681.9394155,42.21995973587036,4.332930317907047,1739502681.9394171,42.21995973587036,1.2017258327938845 +1739502681.958976,42.239959716796875,42.7408958853888,1739502681.9589787,42.239959716796875,3.161562816098746,1739502681.958982,42.239959716796875,68.9551784645873,1739502681.9589849,42.239959716796875,39.9429546710575,1739502681.9589863,42.239959716796875,0.22942634469836984,1739502681.9589882,42.239959716796875,-2.3327793222924567,1739502681.9589899,42.239959716796875,-1.5127952544529952,1739502681.958991,42.239959716796875,-0.6108,1739502681.9589927,42.239959716796875,0.7453171312201596,1739502681.9589942,42.239959716796875,0.0,1739502681.9589958,42.239959716796875,-0.4564087015737248,1739502681.9589975,42.239959716796875,4.332930317907047,1739502681.9589992,42.239959716796875,1.2017258327938845 +1739502681.978933,42.25995969772339,42.7408958853888,1739502681.9789367,42.25995969772339,3.161562816098746,1739502681.9789405,42.25995969772339,68.9551784645873,1739502681.9789438,42.25995969772339,39.9429546710575,1739502681.9789453,42.25995969772339,0.22942634469836984,1739502681.9789476,42.25995969772339,-2.3327793222924567,1739502681.9789493,42.25995969772339,-1.5127952544529952,1739502681.978951,42.25995969772339,-0.6108,1739502681.9789524,42.25995969772339,0.7453171312201596,1739502681.9789543,42.25995969772339,0.0,1739502681.9789555,42.25995969772339,-0.4564087015737248,1739502681.9789574,42.25995969772339,4.332930317907047,1739502681.9789586,42.25995969772339,1.2017258327938845 +1739502681.9991128,42.2799596786499,42.7408958853888,1739502681.9991155,42.2799596786499,3.161562816098746,1739502681.9991188,42.2799596786499,68.9551784645873,1739502681.999122,42.2799596786499,39.9429546710575,1739502681.9991236,42.2799596786499,0.22942634469836984,1739502681.9991252,42.2799596786499,-2.3327793222924567,1739502681.9991267,42.2799596786499,-1.5127952544529952,1739502681.9991283,42.2799596786499,-0.6108,1739502681.9991295,42.2799596786499,0.7453171312201596,1739502681.9991314,42.2799596786499,0.0,1739502681.9991326,42.2799596786499,-0.4564087015737248,1739502681.9991345,42.2799596786499,4.332930317907047,1739502681.999136,42.2799596786499,1.2017258327938845 +1739502682.018873,42.299959659576416,42.7408958853888,1739502682.018877,42.299959659576416,3.161562816098746,1739502682.0188806,42.299959659576416,68.9551784645873,1739502682.0188844,42.299959659576416,39.9429546710575,1739502682.018886,42.299959659576416,0.22942634469836984,1739502682.0188882,42.299959659576416,-2.3327793222924567,1739502682.01889,42.299959659576416,-1.5127952544529952,1739502682.0188916,42.299959659576416,-0.6108,1739502682.018893,42.299959659576416,0.7453171312201596,1739502682.0188951,42.299959659576416,0.0,1739502682.0188966,42.299959659576416,-0.4564087015737248,1739502682.0188982,42.299959659576416,4.332930317907047,1739502682.0189004,42.299959659576416,1.2017258327938845 +1739502682.0392594,42.31995964050293,42.692569220431736,1739502682.0392616,42.31995964050293,3.041142232904061,1739502682.039265,42.31995964050293,69.11120795870492,1739502682.0392678,42.31995964050293,39.887243251212894,1739502682.0392694,42.31995964050293,0.21531081280322406,1739502682.039271,42.31995964050293,-2.352553078874743,1739502682.0392728,42.31995964050293,-1.540388864314363,1739502682.0392742,42.31995964050293,-0.6108,1739502682.0392754,42.31995964050293,0.7290446069764669,1739502682.0392773,42.31995964050293,0.0,1739502682.0392785,42.31995964050293,-0.4084016368634655,1739502682.0392804,42.31995964050293,4.327847551997605,1739502682.0392816,42.31995964050293,1.1524484613981087 +1739502682.0593514,42.33995962142944,42.692569220431736,1739502682.059354,42.33995962142944,3.041142232904061,1739502682.0593574,42.33995962142944,69.11120795870492,1739502682.0593603,42.33995962142944,39.887243251212894,1739502682.0593617,42.33995962142944,0.21531081280322406,1739502682.059364,42.33995962142944,-2.352553078874743,1739502682.0593657,42.33995962142944,-1.540388864314363,1739502682.0593672,42.33995962142944,-0.6108,1739502682.0593686,42.33995962142944,0.7290446069764669,1739502682.0593703,42.33995962142944,0.0,1739502682.0593717,42.33995962142944,-0.42340385442164186,1739502682.0593734,42.33995962142944,4.327847551997605,1739502682.0593748,42.33995962142944,1.1524484613981087 +1739502682.0819237,42.35995960235596,42.692569220431736,1739502682.0819278,42.35995960235596,3.041142232904061,1739502682.0819328,42.35995960235596,69.11120795870492,1739502682.0819387,42.35995960235596,39.887243251212894,1739502682.0819418,42.35995960235596,0.21531081280322406,1739502682.0819461,42.35995960235596,-2.352553078874743,1739502682.0819497,42.35995960235596,-1.540388864314363,1739502682.0819535,42.35995960235596,-0.6108,1739502682.081957,42.35995960235596,0.7290446069764669,1739502682.081961,42.35995960235596,0.0,1739502682.0819647,42.35995960235596,-0.42340385442164186,1739502682.0819685,42.35995960235596,4.327847551997605,1739502682.0819726,42.35995960235596,1.1524484613981087 +1739502682.0992446,42.37995958328247,42.692569220431736,1739502682.0992467,42.37995958328247,3.041142232904061,1739502682.09925,42.37995958328247,69.11120795870492,1739502682.0992532,42.37995958328247,39.887243251212894,1739502682.0992546,42.37995958328247,0.21531081280322406,1739502682.0992563,42.37995958328247,-2.352553078874743,1739502682.0992577,42.37995958328247,-1.540388864314363,1739502682.0992591,42.37995958328247,-0.6108,1739502682.0992603,42.37995958328247,0.7290446069764669,1739502682.0992622,42.37995958328247,0.0,1739502682.0992637,42.37995958328247,-0.42340385442164186,1739502682.099265,42.37995958328247,4.327847551997605,1739502682.0992665,42.37995958328247,1.1524484613981087 +1739502682.1194477,42.399959564208984,42.692569220431736,1739502682.119452,42.399959564208984,3.041142232904061,1739502682.1194563,42.399959564208984,69.11120795870492,1739502682.1194594,42.399959564208984,39.887243251212894,1739502682.1194608,42.399959564208984,0.21531081280322406,1739502682.1194627,42.399959564208984,-2.352553078874743,1739502682.1194644,42.399959564208984,-1.540388864314363,1739502682.1194665,42.399959564208984,-0.6108,1739502682.119468,42.399959564208984,0.7290446069764669,1739502682.11947,42.399959564208984,0.0,1739502682.1194713,42.399959564208984,-0.42340385442164186,1739502682.1194732,42.399959564208984,4.327847551997605,1739502682.1194746,42.399959564208984,1.1524484613981087 +1739502682.1393003,42.4199595451355,42.64556500541736,1739502682.139303,42.4199595451355,2.9259193043541565,1739502682.139306,42.4199595451355,69.11317132370824,1739502682.1393087,42.4199595451355,39.975012325649224,1739502682.1393104,42.4199595451355,0.23865506344447426,1739502682.1393123,42.4199595451355,-2.353075401355433,1739502682.139314,42.4199595451355,-1.4449227795801929,1739502682.1393154,42.4199595451355,-0.6108,1739502682.1393168,42.4199595451355,0.7869052027255286,1739502682.1393185,42.4199595451355,0.0,1739502682.13932,42.4199595451355,-0.2717536992884376,1739502682.1393213,42.4199595451355,4.3214097260357205,1739502682.139323,42.4199595451355,1.1060496065648597 +1739502682.1589298,42.43995952606201,42.64556500541736,1739502682.1589324,42.43995952606201,2.9259193043541565,1739502682.1589358,42.43995952606201,69.11317132370824,1739502682.1589386,42.43995952606201,39.975012325649224,1739502682.1589403,42.43995952606201,0.23865506344447426,1739502682.1589422,42.43995952606201,-2.353075401355433,1739502682.1589437,42.43995952606201,-1.4449227795801929,1739502682.1589453,42.43995952606201,-0.6108,1739502682.1589465,42.43995952606201,0.7869052027255286,1739502682.1589484,42.43995952606201,0.0,1739502682.1589496,42.43995952606201,-0.3191444038393312,1739502682.1589513,42.43995952606201,4.3214097260357205,1739502682.158953,42.43995952606201,1.1060496065648597 +1739502682.179307,42.459959506988525,42.64556500541736,1739502682.1793103,42.459959506988525,2.9259193043541565,1739502682.1793146,42.459959506988525,69.11317132370824,1739502682.1793182,42.459959506988525,39.975012325649224,1739502682.17932,42.459959506988525,0.23865506344447426,1739502682.1793218,42.459959506988525,-2.353075401355433,1739502682.1793237,42.459959506988525,-1.4449227795801929,1739502682.1793253,42.459959506988525,-0.6108,1739502682.1793272,42.459959506988525,0.7869052027255286,1739502682.179329,42.459959506988525,0.0,1739502682.1793306,42.459959506988525,-0.3191444038393312,1739502682.1793323,42.459959506988525,4.3214097260357205,1739502682.179334,42.459959506988525,1.1060496065648597 +1739502682.1992002,42.47995948791504,42.64556500541736,1739502682.1992028,42.47995948791504,2.9259193043541565,1739502682.199206,42.47995948791504,69.11317132370824,1739502682.1992092,42.47995948791504,39.975012325649224,1739502682.1992106,42.47995948791504,0.23865506344447426,1739502682.1992126,42.47995948791504,-2.353075401355433,1739502682.199214,42.47995948791504,-1.4449227795801929,1739502682.1992157,42.47995948791504,-0.6108,1739502682.1992168,42.47995948791504,0.7869052027255286,1739502682.1992185,42.47995948791504,0.0,1739502682.19922,42.47995948791504,-0.3191444038393312,1739502682.1992216,42.47995948791504,4.3214097260357205,1739502682.199223,42.47995948791504,1.1060496065648597 +1739502682.2197855,42.49995946884155,42.64556500541736,1739502682.2197883,42.49995946884155,2.9259193043541565,1739502682.219792,42.49995946884155,69.11317132370824,1739502682.219795,42.49995946884155,39.975012325649224,1739502682.2197964,42.49995946884155,0.23865506344447426,1739502682.2197986,42.49995946884155,-2.353075401355433,1739502682.2198,42.49995946884155,-1.4449227795801929,1739502682.2198017,42.49995946884155,-0.6108,1739502682.2198029,42.49995946884155,0.7869052027255286,1739502682.2198048,42.49995946884155,0.0,1739502682.2198062,42.49995946884155,-0.3191444038393312,1739502682.219808,42.49995946884155,4.3214097260357205,1739502682.2198095,42.49995946884155,1.1060496065648597 +1739502682.2396636,42.519959449768066,42.64556500541736,1739502682.239666,42.519959449768066,2.9259193043541565,1739502682.2396693,42.519959449768066,69.11317132370824,1739502682.239672,42.519959449768066,39.975012325649224,1739502682.2396736,42.519959449768066,0.23865506344447426,1739502682.2396753,42.519959449768066,-2.353075401355433,1739502682.239677,42.519959449768066,-1.4449227795801929,1739502682.2396786,42.519959449768066,-0.6108,1739502682.23968,42.519959449768066,0.7869052027255286,1739502682.2396817,42.519959449768066,0.0,1739502682.2396832,42.519959449768066,-0.3191444038393312,1739502682.2396846,42.519959449768066,4.3214097260357205,1739502682.2396865,42.519959449768066,1.1060496065648597 +1739502682.2590213,42.53995943069458,42.59937923100498,1739502682.259024,42.53995943069458,2.814950095671179,1739502682.259027,42.53995943069458,69.27686164629493,1739502682.25903,42.53995943069458,39.873458195643,1739502682.2590315,42.53995943069458,0.2118645489107514,1739502682.2590334,42.53995943069458,-2.379240763208871,1739502682.2590349,42.53995943069458,-1.5012527630215402,1739502682.2590363,42.53995943069458,-0.6108,1739502682.2590377,42.53995943069458,0.7522312578712508,1739502682.2590394,42.53995943069458,0.0,1739502682.2590408,42.53995943069458,-0.32692711294237436,1739502682.2590423,42.53995943069458,4.313604198251807,1739502682.259044,42.53995943069458,1.0767262726243163 +1739502682.2792416,42.559959411621094,42.59937923100498,1739502682.279245,42.559959411621094,2.814950095671179,1739502682.2792482,42.559959411621094,69.27686164629493,1739502682.2792518,42.559959411621094,39.873458195643,1739502682.2792532,42.559959411621094,0.2118645489107514,1739502682.2792552,42.559959411621094,-2.379240763208871,1739502682.2792566,42.559959411621094,-1.5012527630215402,1739502682.279258,42.559959411621094,-0.6108,1739502682.2792594,42.559959411621094,0.7522312578712508,1739502682.2792614,42.559959411621094,0.0,1739502682.279263,42.559959411621094,-0.3244950147530655,1739502682.279265,42.559959411621094,4.313604198251807,1739502682.2792666,42.559959411621094,1.0767262726243163 +1739502682.2993538,42.57995939254761,42.59937923100498,1739502682.2993567,42.57995939254761,2.814950095671179,1739502682.2993596,42.57995939254761,69.27686164629493,1739502682.299363,42.57995939254761,39.873458195643,1739502682.2993643,42.57995939254761,0.2118645489107514,1739502682.2993662,42.57995939254761,-2.379240763208871,1739502682.2993677,42.57995939254761,-1.5012527630215402,1739502682.2993693,42.57995939254761,-0.6108,1739502682.2993708,42.57995939254761,0.7522312578712508,1739502682.2993724,42.57995939254761,0.0,1739502682.2993739,42.57995939254761,-0.3244950147530655,1739502682.2993755,42.57995939254761,4.313604198251807,1739502682.2993772,42.57995939254761,1.0767262726243163 +1739502682.319273,42.59995937347412,42.59937923100498,1739502682.3192763,42.59995937347412,2.814950095671179,1739502682.3192801,42.59995937347412,69.27686164629493,1739502682.3192832,42.59995937347412,39.873458195643,1739502682.3192847,42.59995937347412,0.2118645489107514,1739502682.3192866,42.59995937347412,-2.379240763208871,1739502682.319288,42.59995937347412,-1.5012527630215402,1739502682.31929,42.59995937347412,-0.6108,1739502682.3192914,42.59995937347412,0.7522312578712508,1739502682.3192935,42.59995937347412,0.0,1739502682.3192952,42.59995937347412,-0.3244950147530655,1739502682.319297,42.59995937347412,4.313604198251807,1739502682.3192987,42.59995937347412,1.0767262726243163 +1739502682.3393953,42.619959354400635,42.59937923100498,1739502682.3393977,42.619959354400635,2.814950095671179,1739502682.3394012,42.619959354400635,69.27686164629493,1739502682.3394043,42.619959354400635,39.873458195643,1739502682.3394055,42.619959354400635,0.2118645489107514,1739502682.3394074,42.619959354400635,-2.379240763208871,1739502682.339409,42.619959354400635,-1.5012527630215402,1739502682.3394108,42.619959354400635,-0.6108,1739502682.3394122,42.619959354400635,0.7522312578712508,1739502682.3394141,42.619959354400635,0.0,1739502682.3394153,42.619959354400635,-0.3244950147530655,1739502682.339417,42.619959354400635,4.313604198251807,1739502682.3394186,42.619959354400635,1.0767262726243163 +1739502682.3597093,42.63995933532715,42.55351971062796,1739502682.3597128,42.63995933532715,2.7073310108479145,1739502682.3597167,42.63995933532715,69.49298906302849,1739502682.3597198,42.63995933532715,39.719872955558905,1739502682.3597212,42.63995933532715,0.17510655873111608,1739502682.3597233,42.63995933532715,-2.412309488613126,1739502682.3597248,42.63995933532715,-1.596420118541001,1739502682.359727,42.63995933532715,-0.6108,1739502682.359728,42.63995933532715,0.6970867855708064,1739502682.3597302,42.63995933532715,0.0,1739502682.3597317,42.63995933532715,-0.3623875958293445,1739502682.3597336,42.63995933532715,4.304415482793127,1739502682.3597353,42.63995933532715,1.047632942049961 +1739502682.3789208,42.65995931625366,42.55351971062796,1739502682.378924,42.65995931625366,2.7073310108479145,1739502682.378927,42.65995931625366,69.49298906302849,1739502682.37893,42.65995931625366,39.719872955558905,1739502682.378932,42.65995931625366,0.17510655873111608,1739502682.3789337,42.65995931625366,-2.412309488613126,1739502682.3789356,42.65995931625366,-1.596420118541001,1739502682.3789372,42.65995931625366,-0.6108,1739502682.378939,42.65995931625366,0.6970867855708064,1739502682.3789403,42.65995931625366,0.0,1739502682.378942,42.65995931625366,-0.35054615647915466,1739502682.3789437,42.65995931625366,4.304415482793127,1739502682.3789454,42.65995931625366,1.047632942049961 +1739502682.4002059,42.679959297180176,42.55351971062796,1739502682.4002087,42.679959297180176,2.7073310108479145,1739502682.4002118,42.679959297180176,69.49298906302849,1739502682.4002147,42.679959297180176,39.719872955558905,1739502682.4002163,42.679959297180176,0.17510655873111608,1739502682.4002185,42.679959297180176,-2.412309488613126,1739502682.40022,42.679959297180176,-1.596420118541001,1739502682.4002213,42.679959297180176,-0.6108,1739502682.400223,42.679959297180176,0.6970867855708064,1739502682.4002247,42.679959297180176,0.0,1739502682.400226,42.679959297180176,-0.35054615647915466,1739502682.4002278,42.679959297180176,4.304415482793127,1739502682.4002295,42.679959297180176,1.047632942049961 +1739502682.419499,42.69995927810669,42.55351971062796,1739502682.4195018,42.69995927810669,2.7073310108479145,1739502682.419505,42.69995927810669,69.49298906302849,1739502682.4195077,42.69995927810669,39.719872955558905,1739502682.4195092,42.69995927810669,0.17510655873111608,1739502682.4195108,42.69995927810669,-2.412309488613126,1739502682.4195123,42.69995927810669,-1.596420118541001,1739502682.4195137,42.69995927810669,-0.6108,1739502682.419515,42.69995927810669,0.6970867855708064,1739502682.4195163,42.69995927810669,0.0,1739502682.4195178,42.69995927810669,-0.35054615647915466,1739502682.4195192,42.69995927810669,4.304415482793127,1739502682.4195206,42.69995927810669,1.047632942049961 +1739502682.4396334,42.7199592590332,42.55351971062796,1739502682.4396358,42.7199592590332,2.7073310108479145,1739502682.4396389,42.7199592590332,69.49298906302849,1739502682.4396412,42.7199592590332,39.719872955558905,1739502682.439643,42.7199592590332,0.17510655873111608,1739502682.4396446,42.7199592590332,-2.412309488613126,1739502682.439646,42.7199592590332,-1.596420118541001,1739502682.4396472,42.7199592590332,-0.6108,1739502682.4396486,42.7199592590332,0.6970867855708064,1739502682.4396498,42.7199592590332,0.0,1739502682.4396513,42.7199592590332,-0.35054615647915466,1739502682.4396527,42.7199592590332,4.304415482793127,1739502682.4396539,42.7199592590332,1.047632942049961 +1739502682.459251,42.73995923995972,42.55351971062796,1739502682.4592533,42.73995923995972,2.7073310108479145,1739502682.4592562,42.73995923995972,69.49298906302849,1739502682.459259,42.73995923995972,39.719872955558905,1739502682.4592605,42.73995923995972,0.17510655873111608,1739502682.4592621,42.73995923995972,-2.412309488613126,1739502682.4592636,42.73995923995972,-1.596420118541001,1739502682.4592648,42.73995923995972,-0.6108,1739502682.459266,42.73995923995972,0.6970867855708064,1739502682.459268,42.73995923995972,0.0,1739502682.4592693,42.73995923995972,-0.35054615647915466,1739502682.4592707,42.73995923995972,4.304415482793127,1739502682.4592721,42.73995923995972,1.047632942049961 +1739502682.4790957,42.75995922088623,42.50788445645159,1739502682.4790983,42.75995922088623,2.603088828733065,1739502682.4791012,42.75995922088623,69.63606825417686,1739502682.4791038,42.75995922088623,39.63654945991781,1739502682.4791052,42.75995922088623,0.15667619802719224,1739502682.479107,42.75995922088623,-2.435931525907354,1739502682.4791083,42.75995922088623,-1.6291217398835542,1739502682.4791095,42.75995922088623,-0.6108,1739502682.4791112,42.75995922088623,0.679086572172807,1739502682.4791126,42.75995922088623,0.0,1739502682.4791143,42.75995922088623,-0.3347399445189085,1739502682.4791155,42.75995922088623,4.2938251246562,1739502682.4791172,42.75995922088623,1.0187659611678446 +1739502682.4992154,42.779959201812744,42.50788445645159,1739502682.499218,42.779959201812744,2.603088828733065,1739502682.4992208,42.779959201812744,69.63606825417686,1739502682.4992232,42.779959201812744,39.63654945991781,1739502682.499225,42.779959201812744,0.15667619802719224,1739502682.4992263,42.779959201812744,-2.435931525907354,1739502682.4992278,42.779959201812744,-1.6291217398835542,1739502682.4992292,42.779959201812744,-0.6108,1739502682.4992304,42.779959201812744,0.679086572172807,1739502682.499232,42.779959201812744,0.0,1739502682.4992335,42.779959201812744,-0.3396793889950376,1739502682.499235,42.779959201812744,4.2938251246562,1739502682.4992363,42.779959201812744,1.0187659611678446 +1739502682.518765,42.79995918273926,42.50788445645159,1739502682.5187676,42.79995918273926,2.603088828733065,1739502682.5187707,42.79995918273926,69.63606825417686,1739502682.5187738,42.79995918273926,39.63654945991781,1739502682.5187752,42.79995918273926,0.15667619802719224,1739502682.518777,42.79995918273926,-2.435931525907354,1739502682.5187783,42.79995918273926,-1.6291217398835542,1739502682.51878,42.79995918273926,-0.6108,1739502682.5187812,42.79995918273926,0.679086572172807,1739502682.518783,42.79995918273926,0.0,1739502682.5187843,42.79995918273926,-0.3396793889950376,1739502682.5187857,42.79995918273926,4.2938251246562,1739502682.5187874,42.79995918273926,1.0187659611678446 +1739502682.5392053,42.81995916366577,42.50788445645159,1739502682.539208,42.81995916366577,2.603088828733065,1739502682.539211,42.81995916366577,69.63606825417686,1739502682.5392141,42.81995916366577,39.63654945991781,1739502682.5392156,42.81995916366577,0.15667619802719224,1739502682.5392175,42.81995916366577,-2.435931525907354,1739502682.539219,42.81995916366577,-1.6291217398835542,1739502682.5392206,42.81995916366577,-0.6108,1739502682.5392218,42.81995916366577,0.679086572172807,1739502682.5392237,42.81995916366577,0.0,1739502682.539225,42.81995916366577,-0.3396793889950376,1739502682.5392265,42.81995916366577,4.2938251246562,1739502682.5392282,42.81995916366577,1.0187659611678446 +1739502682.559039,42.839959144592285,42.50788445645159,1739502682.5590422,42.839959144592285,2.603088828733065,1739502682.559046,42.839959144592285,69.63606825417686,1739502682.5590491,42.839959144592285,39.63654945991781,1739502682.559051,42.839959144592285,0.15667619802719224,1739502682.5590527,42.839959144592285,-2.435931525907354,1739502682.5590544,42.839959144592285,-1.6291217398835542,1739502682.5590558,42.839959144592285,-0.6108,1739502682.5590575,42.839959144592285,0.679086572172807,1739502682.5590594,42.839959144592285,0.0,1739502682.559061,42.839959144592285,-0.3396793889950376,1739502682.5590625,42.839959144592285,4.2938251246562,1739502682.5590641,42.839959144592285,1.0187659611678446 +1739502682.5791385,42.8599591255188,42.46238279099186,1739502682.5791414,42.8599591255188,2.50225005188212,1739502682.5791447,42.8599591255188,69.70946059426768,1739502682.5791476,42.8599591255188,39.62081523467361,1739502682.579149,42.8599591255188,0.15324542710928277,1739502682.5791512,42.8599591255188,-2.450806858702237,1739502682.5791523,42.8599591255188,-1.6017389533628854,1739502682.579154,42.8599591255188,-0.6108,1739502682.5791554,42.8599591255188,0.6941269356425978,1739502682.5791574,42.8599591255188,0.0,1739502682.5791585,42.8599591255188,-0.27613816756094983,1739502682.57916,42.8599591255188,4.281811547917533,1739502682.5791616,42.8599591255188,0.9901217479207308 +1739502682.599435,42.87995910644531,42.46238279099186,1739502682.5994375,42.87995910644531,2.50225005188212,1739502682.5994408,42.87995910644531,69.70946059426768,1739502682.599444,42.87995910644531,39.62081523467361,1739502682.5994456,42.87995910644531,0.15324542710928277,1739502682.5994473,42.87995910644531,-2.450806858702237,1739502682.599449,42.87995910644531,-1.6017389533628854,1739502682.5994503,42.87995910644531,-0.6108,1739502682.599452,42.87995910644531,0.6941269356425978,1739502682.5994534,42.87995910644531,0.0,1739502682.5994549,42.87995910644531,-0.29599481227813307,1739502682.5994565,42.87995910644531,4.281811547917533,1739502682.599458,42.87995910644531,0.9901217479207308 +1739502682.6190693,42.899959087371826,42.46238279099186,1739502682.6190722,42.899959087371826,2.50225005188212,1739502682.6190755,42.899959087371826,69.70946059426768,1739502682.6190789,42.899959087371826,39.62081523467361,1739502682.6190805,42.899959087371826,0.15324542710928277,1739502682.6190822,42.899959087371826,-2.450806858702237,1739502682.619084,42.899959087371826,-1.6017389533628854,1739502682.619085,42.899959087371826,-0.6108,1739502682.6190865,42.899959087371826,0.6941269356425978,1739502682.6190884,42.899959087371826,0.0,1739502682.6190898,42.899959087371826,-0.29599481227813307,1739502682.6190915,42.899959087371826,4.281811547917533,1739502682.619093,42.899959087371826,0.9901217479207308 +1739502682.6389377,42.91995906829834,42.46238279099186,1739502682.63894,42.91995906829834,2.50225005188212,1739502682.6389434,42.91995906829834,69.70946059426768,1739502682.6389463,42.91995906829834,39.62081523467361,1739502682.6389477,42.91995906829834,0.15324542710928277,1739502682.6389496,42.91995906829834,-2.450806858702237,1739502682.638951,42.91995906829834,-1.6017389533628854,1739502682.6389525,42.91995906829834,-0.6108,1739502682.638954,42.91995906829834,0.6941269356425978,1739502682.6389556,42.91995906829834,0.0,1739502682.638957,42.91995906829834,-0.29599481227813307,1739502682.6389587,42.91995906829834,4.281811547917533,1739502682.6389601,42.91995906829834,0.9901217479207308 +1739502682.659136,42.93995904922485,42.46238279099186,1739502682.6591392,42.93995904922485,2.50225005188212,1739502682.6591423,42.93995904922485,69.70946059426768,1739502682.659145,42.93995904922485,39.62081523467361,1739502682.6591468,42.93995904922485,0.15324542710928277,1739502682.6591485,42.93995904922485,-2.450806858702237,1739502682.6591504,42.93995904922485,-1.6017389533628854,1739502682.6591518,42.93995904922485,-0.6108,1739502682.6591535,42.93995904922485,0.6941269356425978,1739502682.659155,42.93995904922485,0.0,1739502682.6591566,42.93995904922485,-0.29599481227813307,1739502682.659158,42.93995904922485,4.281811547917533,1739502682.6591597,42.93995904922485,0.9901217479207308 +1739502682.6791584,42.95995903015137,42.46238279099186,1739502682.6791613,42.95995903015137,2.50225005188212,1739502682.6791646,42.95995903015137,69.70946059426768,1739502682.6791677,42.95995903015137,39.62081523467361,1739502682.6791692,42.95995903015137,0.15324542710928277,1739502682.679171,42.95995903015137,-2.450806858702237,1739502682.6791725,42.95995903015137,-1.6017389533628854,1739502682.6791742,42.95995903015137,-0.6108,1739502682.6791754,42.95995903015137,0.6941269356425978,1739502682.6791773,42.95995903015137,0.0,1739502682.6791785,42.95995903015137,-0.29599481227813307,1739502682.6791804,42.95995903015137,4.281811547917533,1739502682.6791818,42.95995903015137,0.9901217479207308 +1739502682.7004185,42.97995901107788,42.41693526074779,1739502682.700421,42.97995901107788,2.4048411884956975,1739502682.7004247,42.97995901107788,69.78299973746775,1739502682.7004278,42.97995901107788,39.604509132238675,1739502682.7004297,42.97995901107788,0.14968996116482375,1739502682.7004316,42.97995901107788,-2.4657230924684495,1739502682.7004333,42.97995901107788,-1.5708966888381117,1739502682.700435,42.97995901107788,-0.6108,1739502682.7004368,42.97995901107788,0.7114667326428291,1739502682.7004385,42.97995901107788,0.0,1739502682.7004402,42.97995901107788,-0.2294278762971455,1739502682.7004418,42.97995901107788,4.2683498745449375,1739502682.7004437,42.97995901107788,0.961696790073006 +1739502682.7192457,42.999958992004395,42.41693526074779,1739502682.7192495,42.999958992004395,2.4048411884956975,1739502682.7192528,42.999958992004395,69.78299973746775,1739502682.7192562,42.999958992004395,39.604509132238675,1739502682.7192576,42.999958992004395,0.14968996116482375,1739502682.7192597,42.999958992004395,-2.4657230924684495,1739502682.7192614,42.999958992004395,-1.5708966888381117,1739502682.719263,42.999958992004395,-0.6108,1739502682.7192645,42.999958992004395,0.7114667326428291,1739502682.7192664,42.999958992004395,0.0,1739502682.7192678,42.999958992004395,-0.2502300574301769,1739502682.7192695,42.999958992004395,4.2683498745449375,1739502682.7192714,42.999958992004395,0.961696790073006 +1739502682.739315,43.01995897293091,42.41693526074779,1739502682.7393177,43.01995897293091,2.4048411884956975,1739502682.739321,43.01995897293091,69.78299973746775,1739502682.7393243,43.01995897293091,39.604509132238675,1739502682.7393262,43.01995897293091,0.14968996116482375,1739502682.7393281,43.01995897293091,-2.4657230924684495,1739502682.7393298,43.01995897293091,-1.5708966888381117,1739502682.7393312,43.01995897293091,-0.6108,1739502682.739333,43.01995897293091,0.7114667326428291,1739502682.7393348,43.01995897293091,0.0,1739502682.7393365,43.01995897293091,-0.2502300574301769,1739502682.7393382,43.01995897293091,4.2683498745449375,1739502682.73934,43.01995897293091,0.961696790073006 +1739502682.759291,43.03995895385742,42.41693526074779,1739502682.7592943,43.03995895385742,2.4048411884956975,1739502682.759298,43.03995895385742,69.78299973746775,1739502682.7593017,43.03995895385742,39.604509132238675,1739502682.759303,43.03995895385742,0.14968996116482375,1739502682.7593055,43.03995895385742,-2.4657230924684495,1739502682.7593071,43.03995895385742,-1.5708966888381117,1739502682.7593088,43.03995895385742,-0.6108,1739502682.7593105,43.03995895385742,0.7114667326428291,1739502682.7593126,43.03995895385742,0.0,1739502682.7593145,43.03995895385742,-0.2502300574301769,1739502682.759316,43.03995895385742,4.2683498745449375,1739502682.7593179,43.03995895385742,0.961696790073006 +1739502682.7792158,43.059958934783936,42.41693526074779,1739502682.7792218,43.059958934783936,2.4048411884956975,1739502682.7792287,43.059958934783936,69.78299973746775,1739502682.7792366,43.059958934783936,39.604509132238675,1739502682.7792408,43.059958934783936,0.14968996116482375,1739502682.7792473,43.059958934783936,-2.4657230924684495,1739502682.7792525,43.059958934783936,-1.5708966888381117,1739502682.7792578,43.059958934783936,-0.6108,1739502682.779263,43.059958934783936,0.7114667326428291,1739502682.7792683,43.059958934783936,0.0,1739502682.7792735,43.059958934783936,-0.2502300574301769,1739502682.7792785,43.059958934783936,4.2683498745449375,1739502682.7792835,43.059958934783936,0.961696790073006 +1739502682.7997253,43.07995891571045,42.371473581054296,1739502682.799728,43.07995891571045,2.310888970568799,1739502682.7997315,43.07995891571045,69.87378518472171,1739502682.7997348,43.07995891571045,39.57088113851196,1739502682.7997363,43.07995891571045,0.14260811944314963,1739502682.7997384,43.07995891571045,-2.482768701472569,1739502682.79974,43.07995891571045,-1.5501314978900531,1739502682.7997417,43.07995891571045,-0.6108,1739502682.7997432,43.07995891571045,0.7233844420224937,1739502682.7997453,43.07995891571045,0.0,1739502682.7997468,43.07995891571045,-0.19186370405915099,1739502682.7997484,43.07995891571045,4.253411710455373,1739502682.7997503,43.07995891571045,0.9334876434688367 +1739502682.8196,43.09995889663696,42.371473581054296,1739502682.8196032,43.09995889663696,2.310888970568799,1739502682.819607,43.09995889663696,69.87378518472171,1739502682.8196106,43.09995889663696,39.57088113851196,1739502682.8196125,43.09995889663696,0.14260811944314963,1739502682.8196146,43.09995889663696,-2.482768701472569,1739502682.8196166,43.09995889663696,-1.5501314978900531,1739502682.8196182,43.09995889663696,-0.6108,1739502682.8196201,43.09995889663696,0.7233844420224937,1739502682.8196235,43.09995889663696,0.0,1739502682.8196251,43.09995889663696,-0.21010320144634298,1739502682.819627,43.09995889663696,4.253411710455373,1739502682.8196287,43.09995889663696,0.9334876434688367 +1739502682.8392508,43.11995887756348,42.371473581054296,1739502682.8392534,43.11995887756348,2.310888970568799,1739502682.8392572,43.11995887756348,69.87378518472171,1739502682.8392608,43.11995887756348,39.57088113851196,1739502682.8392625,43.11995887756348,0.14260811944314963,1739502682.8392644,43.11995887756348,-2.482768701472569,1739502682.8392663,43.11995887756348,-1.5501314978900531,1739502682.8392677,43.11995887756348,-0.6108,1739502682.8392694,43.11995887756348,0.7233844420224937,1739502682.8392718,43.11995887756348,0.0,1739502682.8392732,43.11995887756348,-0.21010320144634298,1739502682.8392751,43.11995887756348,4.253411710455373,1739502682.8392768,43.11995887756348,0.9334876434688367 +1739502682.8591137,43.13995885848999,42.371473581054296,1739502682.8591173,43.13995885848999,2.310888970568799,1739502682.859121,43.13995885848999,69.87378518472171,1739502682.8591244,43.13995885848999,39.57088113851196,1739502682.8591263,43.13995885848999,0.14260811944314963,1739502682.8591282,43.13995885848999,-2.482768701472569,1739502682.8591301,43.13995885848999,-1.5501314978900531,1739502682.8591316,43.13995885848999,-0.6108,1739502682.8591335,43.13995885848999,0.7233844420224937,1739502682.8591352,43.13995885848999,0.0,1739502682.859137,43.13995885848999,-0.21010320144634298,1739502682.8591387,43.13995885848999,4.253411710455373,1739502682.8591406,43.13995885848999,0.9334876434688367 +1739502682.8791544,43.159958839416504,42.371473581054296,1739502682.879158,43.159958839416504,2.310888970568799,1739502682.879162,43.159958839416504,69.87378518472171,1739502682.8791656,43.159958839416504,39.57088113851196,1739502682.8791676,43.159958839416504,0.14260811944314963,1739502682.8791697,43.159958839416504,-2.482768701472569,1739502682.8791716,43.159958839416504,-1.5501314978900531,1739502682.8791733,43.159958839416504,-0.6108,1739502682.879175,43.159958839416504,0.7233844420224937,1739502682.8791769,43.159958839416504,0.0,1739502682.8791792,43.159958839416504,-0.21010320144634298,1739502682.8791811,43.159958839416504,4.253411710455373,1739502682.8791828,43.159958839416504,0.9334876434688367 +1739502682.8998616,43.17995882034302,42.371473581054296,1739502682.8998644,43.17995882034302,2.310888970568799,1739502682.899868,43.17995882034302,69.87378518472171,1739502682.8998716,43.17995882034302,39.57088113851196,1739502682.899873,43.17995882034302,0.14260811944314963,1739502682.8998752,43.17995882034302,-2.482768701472569,1739502682.8998768,43.17995882034302,-1.5501314978900531,1739502682.8998785,43.17995882034302,-0.6108,1739502682.89988,43.17995882034302,0.7233844420224937,1739502682.899882,43.17995882034302,0.0,1739502682.8998835,43.17995882034302,-0.21010320144634298,1739502682.8998854,43.17995882034302,4.253411710455373,1739502682.899887,43.17995882034302,0.9334876434688367 +1739502682.919412,43.19995880126953,42.325940612849635,1739502682.9194148,43.19995880126953,2.220420509127849,1739502682.919418,43.19995880126953,70.0510394031479,1739502682.9194214,43.19995880126953,39.452070260548275,1739502682.9194229,43.19995880126953,0.11840549002526943,1739502682.919425,43.19995880126953,-2.5100871867317176,1739502682.919427,43.19995880126953,-1.5930294239392788,1739502682.9194286,43.19995880126953,-0.6108,1739502682.9194303,43.19995880126953,0.6989802391795957,1739502682.919432,43.19995880126953,0.0,1739502682.9194334,43.19995880126953,-0.2048777303847483,1739502682.9194353,43.19995880126953,4.236964894760447,1739502682.9194372,43.19995880126953,0.9054909303417449 +1739502682.9398148,43.219958782196045,42.325940612849635,1739502682.9398177,43.219958782196045,2.220420509127849,1739502682.9398212,43.219958782196045,70.0510394031479,1739502682.9398246,43.219958782196045,39.452070260548275,1739502682.9398263,43.219958782196045,0.11840549002526943,1739502682.9398282,43.219958782196045,-2.5100871867317176,1739502682.93983,43.219958782196045,-1.5930294239392788,1739502682.9398315,43.219958782196045,-0.6108,1739502682.9398332,43.219958782196045,0.6989802391795957,1739502682.9398348,43.219958782196045,0.0,1739502682.9398365,43.219958782196045,-0.20651069116214915,1739502682.9398382,43.219958782196045,4.236964894760447,1739502682.9398398,43.219958782196045,0.9054909303417449 +1739502682.9594123,43.23995876312256,42.325940612849635,1739502682.9594152,43.23995876312256,2.220420509127849,1739502682.9594195,43.23995876312256,70.0510394031479,1739502682.9594228,43.23995876312256,39.452070260548275,1739502682.9594247,43.23995876312256,0.11840549002526943,1739502682.9594269,43.23995876312256,-2.5100871867317176,1739502682.9594288,43.23995876312256,-1.5930294239392788,1739502682.9594305,43.23995876312256,-0.6108,1739502682.959432,43.23995876312256,0.6989802391795957,1739502682.9594343,43.23995876312256,0.0,1739502682.959436,43.23995876312256,-0.20651069116214915,1739502682.9594383,43.23995876312256,4.236964894760447,1739502682.9594402,43.23995876312256,0.9054909303417449 +1739502682.9797864,43.25995874404907,42.325940612849635,1739502682.9797897,43.25995874404907,2.220420509127849,1739502682.9797943,43.25995874404907,70.0510394031479,1739502682.9797978,43.25995874404907,39.452070260548275,1739502682.9797993,43.25995874404907,0.11840549002526943,1739502682.9798014,43.25995874404907,-2.5100871867317176,1739502682.979803,43.25995874404907,-1.5930294239392788,1739502682.979805,43.25995874404907,-0.6108,1739502682.9798064,43.25995874404907,0.6989802391795957,1739502682.979809,43.25995874404907,0.0,1739502682.9798107,43.25995874404907,-0.20651069116214915,1739502682.9798129,43.25995874404907,4.236964894760447,1739502682.979815,43.25995874404907,0.9054909303417449 +1739502682.9994934,43.279958724975586,42.325940612849635,1739502682.9994965,43.279958724975586,2.220420509127849,1739502682.9994998,43.279958724975586,70.0510394031479,1739502682.9995031,43.279958724975586,39.452070260548275,1739502682.9995046,43.279958724975586,0.11840549002526943,1739502682.9995065,43.279958724975586,-2.5100871867317176,1739502682.9995081,43.279958724975586,-1.5930294239392788,1739502682.9995098,43.279958724975586,-0.6108,1739502682.999511,43.279958724975586,0.6989802391795957,1739502682.9995131,43.279958724975586,0.0,1739502682.9995146,43.279958724975586,-0.20651069116214915,1739502682.9995167,43.279958724975586,4.236964894760447,1739502682.9995182,43.279958724975586,0.9054909303417449 +1739502683.0192904,43.2999587059021,42.280290371822886,1739502683.019294,43.2999587059021,2.1334633866650874,1739502683.0192978,43.2999587059021,70.05499590725464,1739502683.0193012,43.2999587059021,39.50258258212052,1739502683.0193028,43.2999587059021,0.1290025185433429,1739502683.0193052,43.2999587059021,-2.5165008150804873,1739502683.019307,43.2999587059021,-1.4969964543827776,1739502683.0193088,43.2999587059021,-0.6108,1739502683.0193102,43.2999587059021,0.7547970063602,1739502683.0193126,43.2999587059021,0.0,1739502683.0193143,43.2999587059021,-0.08490431332274723,1739502683.019316,43.2999587059021,4.218973207279142,1739502683.019318,43.2999587059021,0.8777033376738249 +1739502683.0395029,43.31995868682861,42.280290371822886,1739502683.039506,43.31995868682861,2.1334633866650874,1739502683.0395098,43.31995868682861,70.05499590725464,1739502683.0395129,43.31995868682861,39.50258258212052,1739502683.0395145,43.31995868682861,0.1290025185433429,1739502683.0395164,43.31995868682861,-2.5165008150804873,1739502683.039518,43.31995868682861,-1.4969964543827776,1739502683.03952,43.31995868682861,-0.6108,1739502683.0395212,43.31995868682861,0.7547970063602,1739502683.0395234,43.31995868682861,0.0,1739502683.0395248,43.31995868682861,-0.12290633131362494,1739502683.0395267,43.31995868682861,4.218973207279142,1739502683.0395281,43.31995868682861,0.8777033376738249 +1739502683.0592213,43.33995866775513,42.280290371822886,1739502683.0592244,43.33995866775513,2.1334633866650874,1739502683.059228,43.33995866775513,70.05499590725464,1739502683.0592313,43.33995866775513,39.50258258212052,1739502683.0592327,43.33995866775513,0.1290025185433429,1739502683.0592349,43.33995866775513,-2.5165008150804873,1739502683.0592365,43.33995866775513,-1.4969964543827776,1739502683.0592384,43.33995866775513,-0.6108,1739502683.0592399,43.33995866775513,0.7547970063602,1739502683.0592422,43.33995866775513,0.0,1739502683.0592437,43.33995866775513,-0.12290633131362494,1739502683.0592456,43.33995866775513,4.218973207279142,1739502683.0592473,43.33995866775513,0.8777033376738249 +1739502683.0794032,43.35995864868164,42.280290371822886,1739502683.0794065,43.35995864868164,2.1334633866650874,1739502683.0794108,43.35995864868164,70.05499590725464,1739502683.0794141,43.35995864868164,39.50258258212052,1739502683.0794158,43.35995864868164,0.1290025185433429,1739502683.079418,43.35995864868164,-2.5165008150804873,1739502683.0794196,43.35995864868164,-1.4969964543827776,1739502683.0794215,43.35995864868164,-0.6108,1739502683.079423,43.35995864868164,0.7547970063602,1739502683.0794253,43.35995864868164,0.0,1739502683.0794272,43.35995864868164,-0.12290633131362494,1739502683.0794291,43.35995864868164,4.218973207279142,1739502683.0794308,43.35995864868164,0.8777033376738249 +1739502683.0995703,43.379958629608154,42.280290371822886,1739502683.0995727,43.379958629608154,2.1334633866650874,1739502683.0995765,43.379958629608154,70.05499590725464,1739502683.0995796,43.379958629608154,39.50258258212052,1739502683.0995815,43.379958629608154,0.1290025185433429,1739502683.0995836,43.379958629608154,-2.5165008150804873,1739502683.0995853,43.379958629608154,-1.4969964543827776,1739502683.0995867,43.379958629608154,-0.6108,1739502683.0995884,43.379958629608154,0.7547970063602,1739502683.0995903,43.379958629608154,0.0,1739502683.099592,43.379958629608154,-0.12290633131362494,1739502683.0995936,43.379958629608154,4.218973207279142,1739502683.0995953,43.379958629608154,0.8777033376738249 +1739502683.1191707,43.39995861053467,42.280290371822886,1739502683.1191735,43.39995861053467,2.1334633866650874,1739502683.1191778,43.39995861053467,70.05499590725464,1739502683.1191812,43.39995861053467,39.50258258212052,1739502683.1191828,43.39995861053467,0.1290025185433429,1739502683.1191852,43.39995861053467,-2.5165008150804873,1739502683.1191866,43.39995861053467,-1.4969964543827776,1739502683.1191885,43.39995861053467,-0.6108,1739502683.11919,43.39995861053467,0.7547970063602,1739502683.1191921,43.39995861053467,0.0,1739502683.1191936,43.39995861053467,-0.12290633131362494,1739502683.1191955,43.39995861053467,4.218973207279142,1739502683.1191971,43.39995861053467,0.8777033376738249 +1739502683.1397052,43.41995859146118,42.23411116520935,1739502683.1397078,43.41995859146118,2.0493647198407343,1739502683.1397111,43.41995859146118,70.25094854922669,1739502683.1397145,43.41995859146118,39.33529405350185,1739502683.1397161,43.41995859146118,0.09605513503159689,1739502683.1397178,43.41995859146118,-2.5486472844135113,1739502683.1397197,43.41995859146118,-1.5670207296011813,1739502683.1397212,43.41995859146118,-0.6108,1739502683.1397226,43.41995859146118,0.7136762493144442,1739502683.1397245,43.41995859146118,0.0,1739502683.1397262,43.41995859146118,-0.16421799772234927,1739502683.139728,43.41995859146118,4.199396028363092,1739502683.1397297,43.41995859146118,0.8649843428196743 +1739502683.1591256,43.439958572387695,42.23411116520935,1739502683.1591287,43.439958572387695,2.0493647198407343,1739502683.1591327,43.439958572387695,70.25094854922669,1739502683.1591363,43.439958572387695,39.33529405350185,1739502683.1591377,43.439958572387695,0.09605513503159689,1739502683.15914,43.439958572387695,-2.5486472844135113,1739502683.1591423,43.439958572387695,-1.5670207296011813,1739502683.1591437,43.439958572387695,-0.6108,1739502683.159145,43.439958572387695,0.7136762493144442,1739502683.1591473,43.439958572387695,0.0,1739502683.1591492,43.439958572387695,-0.1513080935052301,1739502683.1591506,43.439958572387695,4.199396028363092,1739502683.1591523,43.439958572387695,0.8649843428196743 +1739502683.1791706,43.45995855331421,42.23411116520935,1739502683.1791737,43.45995855331421,2.0493647198407343,1739502683.1791773,43.45995855331421,70.25094854922669,1739502683.1791804,43.45995855331421,39.33529405350185,1739502683.179182,43.45995855331421,0.09605513503159689,1739502683.1791842,43.45995855331421,-2.5486472844135113,1739502683.1791856,43.45995855331421,-1.5670207296011813,1739502683.1791873,43.45995855331421,-0.6108,1739502683.179189,43.45995855331421,0.7136762493144442,1739502683.1791909,43.45995855331421,0.0,1739502683.1791923,43.45995855331421,-0.1513080935052301,1739502683.1791942,43.45995855331421,4.199396028363092,1739502683.179196,43.45995855331421,0.8649843428196743 +1739502683.1997597,43.47995853424072,42.23411116520935,1739502683.1997626,43.47995853424072,2.0493647198407343,1739502683.199766,43.47995853424072,70.25094854922669,1739502683.1997693,43.47995853424072,39.33529405350185,1739502683.199771,43.47995853424072,0.09605513503159689,1739502683.1997728,43.47995853424072,-2.5486472844135113,1739502683.1997745,43.47995853424072,-1.5670207296011813,1739502683.1997762,43.47995853424072,-0.6108,1739502683.1997776,43.47995853424072,0.7136762493144442,1739502683.1997793,43.47995853424072,0.0,1739502683.1997812,43.47995853424072,-0.1513080935052301,1739502683.1997826,43.47995853424072,4.199396028363092,1739502683.1997843,43.47995853424072,0.8649843428196743 +1739502683.2193215,43.499958515167236,42.23411116520935,1739502683.2193244,43.499958515167236,2.0493647198407343,1739502683.2193282,43.499958515167236,70.25094854922669,1739502683.2193315,43.499958515167236,39.33529405350185,1739502683.2193334,43.499958515167236,0.09605513503159689,1739502683.2193353,43.499958515167236,-2.5486472844135113,1739502683.2193372,43.499958515167236,-1.5670207296011813,1739502683.219339,43.499958515167236,-0.6108,1739502683.2193406,43.499958515167236,0.7136762493144442,1739502683.2193422,43.499958515167236,0.0,1739502683.219344,43.499958515167236,-0.1513080935052301,1739502683.2193456,43.499958515167236,4.199396028363092,1739502683.2193475,43.499958515167236,0.8649843428196743 +1739502683.2400305,43.51995849609375,42.1872560304227,1739502683.240033,43.51995849609375,1.9679918604176265,1739502683.2400367,43.51995849609375,70.37869054360104,1739502683.2400398,43.51995849609375,39.26123687682892,1739502683.2400415,43.51995849609375,0.08231254661240535,1739502683.2400432,43.51995849609375,-2.5691274003472127,1739502683.240045,43.51995849609375,-1.5582532567841996,1739502683.2400465,43.51995849609375,-0.6108,1739502683.2400482,43.51995849609375,0.7186995550921622,1739502683.2400498,43.51995849609375,0.0,1739502683.2400515,43.51995849609375,-0.10587806800667052,1739502683.240053,43.51995849609375,4.178187943827709,1739502683.2400546,43.51995849609375,0.8387745153753405 +1739502683.2594428,43.539958477020264,42.1872560304227,1739502683.259446,43.539958477020264,1.9679918604176265,1739502683.2594502,43.539958477020264,70.37869054360104,1739502683.2594538,43.539958477020264,39.26123687682892,1739502683.2594552,43.539958477020264,0.08231254661240535,1739502683.2594576,43.539958477020264,-2.5691274003472127,1739502683.259459,43.539958477020264,-1.5582532567841996,1739502683.259461,43.539958477020264,-0.6108,1739502683.2594624,43.539958477020264,0.7186995550921622,1739502683.2594643,43.539958477020264,0.0,1739502683.2594657,43.539958477020264,-0.12007496028317832,1739502683.2594676,43.539958477020264,4.178187943827709,1739502683.2594693,43.539958477020264,0.8387745153753405 +1739502683.2794943,43.55995845794678,42.1872560304227,1739502683.2794974,43.55995845794678,1.9679918604176265,1739502683.2795024,43.55995845794678,70.37869054360104,1739502683.2795057,43.55995845794678,39.26123687682892,1739502683.2795074,43.55995845794678,0.08231254661240535,1739502683.2795095,43.55995845794678,-2.5691274003472127,1739502683.2795115,43.55995845794678,-1.5582532567841996,1739502683.2795131,43.55995845794678,-0.6108,1739502683.2795148,43.55995845794678,0.7186995550921622,1739502683.2795167,43.55995845794678,0.0,1739502683.2795184,43.55995845794678,-0.12007496028317832,1739502683.2795215,43.55995845794678,4.178187943827709,1739502683.2795231,43.55995845794678,0.8387745153753405 +1739502683.2998116,43.57995843887329,42.1872560304227,1739502683.2998145,43.57995843887329,1.9679918604176265,1739502683.299818,43.57995843887329,70.37869054360104,1739502683.2998216,43.57995843887329,39.26123687682892,1739502683.2998233,43.57995843887329,0.08231254661240535,1739502683.2998254,43.57995843887329,-2.5691274003472127,1739502683.2998269,43.57995843887329,-1.5582532567841996,1739502683.2998285,43.57995843887329,-0.6108,1739502683.29983,43.57995843887329,0.7186995550921622,1739502683.2998319,43.57995843887329,0.0,1739502683.2998335,43.57995843887329,-0.12007496028317832,1739502683.2998352,43.57995843887329,4.178187943827709,1739502683.2998369,43.57995843887329,0.8387745153753405 +1739502683.3193543,43.599958419799805,42.1872560304227,1739502683.3193574,43.599958419799805,1.9679918604176265,1739502683.3193614,43.599958419799805,70.37869054360104,1739502683.3193648,43.599958419799805,39.26123687682892,1739502683.3193667,43.599958419799805,0.08231254661240535,1739502683.3193686,43.599958419799805,-2.5691274003472127,1739502683.3193705,43.599958419799805,-1.5582532567841996,1739502683.3193722,43.599958419799805,-0.6108,1739502683.319375,43.599958419799805,0.7186995550921622,1739502683.3193772,43.599958419799805,0.0,1739502683.3193789,43.599958419799805,-0.12007496028317832,1739502683.3193808,43.599958419799805,4.178187943827709,1739502683.3193824,43.599958419799805,0.8387745153753405 +1739502683.339873,43.61995840072632,42.1872560304227,1739502683.339876,43.61995840072632,1.9679918604176265,1739502683.3398793,43.61995840072632,70.37869054360104,1739502683.3398826,43.61995840072632,39.26123687682892,1739502683.3398843,43.61995840072632,0.08231254661240535,1739502683.3398864,43.61995840072632,-2.5691274003472127,1739502683.3398879,43.61995840072632,-1.5582532567841996,1739502683.3398895,43.61995840072632,-0.6108,1739502683.339891,43.61995840072632,0.7186995550921622,1739502683.339893,43.61995840072632,0.0,1739502683.3398945,43.61995840072632,-0.12007496028317832,1739502683.3398962,43.61995840072632,4.178187943827709,1739502683.3398979,43.61995840072632,0.8387745153753405 +1739502683.3593462,43.63995838165283,42.139797136358645,1739502683.359349,43.63995838165283,1.889608830573974,1739502683.359352,43.63995838165283,70.44484749950819,1739502683.3593554,43.63995838165283,39.221434354768334,1739502683.359357,43.63995838165283,0.07543309835502113,1739502683.3593593,43.63995838165283,-2.585412007726218,1739502683.3593607,43.63995838165283,-1.517908068800869,1739502683.3593624,43.63995838165283,-0.6108,1739502683.3593638,43.63995838165283,0.7422748228670277,1739502683.3593657,43.63995838165283,0.0,1739502683.3593671,43.63995838165283,-0.06704598144802526,1739502683.359369,43.63995838165283,4.155298286254579,1739502683.3593705,43.63995838165283,0.8258923710662042 +1739502683.379229,43.659958362579346,42.139797136358645,1739502683.3792324,43.659958362579346,1.889608830573974,1739502683.3792365,43.659958362579346,70.44484749950819,1739502683.3792398,43.659958362579346,39.221434354768334,1739502683.3792412,43.659958362579346,0.07543309835502113,1739502683.3792436,43.659958362579346,-2.585412007726218,1739502683.3792453,43.659958362579346,-1.517908068800869,1739502683.379247,43.659958362579346,-0.6108,1739502683.3792484,43.659958362579346,0.7422748228670277,1739502683.3792508,43.659958362579346,0.0,1739502683.3792524,43.659958362579346,-0.08361754819917644,1739502683.3792543,43.659958362579346,4.155298286254579,1739502683.3792558,43.659958362579346,0.8258923710662042 +1739502683.3995545,43.67995834350586,42.139797136358645,1739502683.3995574,43.67995834350586,1.889608830573974,1739502683.3995607,43.67995834350586,70.44484749950819,1739502683.399564,43.67995834350586,39.221434354768334,1739502683.399566,43.67995834350586,0.07543309835502113,1739502683.3995678,43.67995834350586,-2.585412007726218,1739502683.3995695,43.67995834350586,-1.517908068800869,1739502683.399571,43.67995834350586,-0.6108,1739502683.3995724,43.67995834350586,0.7422748228670277,1739502683.3995743,43.67995834350586,0.0,1739502683.399576,43.67995834350586,-0.08361754819917644,1739502683.3995779,43.67995834350586,4.155298286254579,1739502683.3995798,43.67995834350586,0.8258923710662042 +1739502683.4191577,43.69995832443237,42.139797136358645,1739502683.4191613,43.69995832443237,1.889608830573974,1739502683.4191663,43.69995832443237,70.44484749950819,1739502683.4191694,43.69995832443237,39.221434354768334,1739502683.4191716,43.69995832443237,0.07543309835502113,1739502683.4191742,43.69995832443237,-2.585412007726218,1739502683.4191756,43.69995832443237,-1.517908068800869,1739502683.4191775,43.69995832443237,-0.6108,1739502683.419179,43.69995832443237,0.7422748228670277,1739502683.419181,43.69995832443237,0.0,1739502683.4191825,43.69995832443237,-0.08361754819917644,1739502683.4191844,43.69995832443237,4.155298286254579,1739502683.419186,43.69995832443237,0.8258923710662042 +1739502683.439707,43.71995830535889,42.139797136358645,1739502683.4397097,43.71995830535889,1.889608830573974,1739502683.4397135,43.71995830535889,70.44484749950819,1739502683.4397168,43.71995830535889,39.221434354768334,1739502683.4397187,43.71995830535889,0.07543309835502113,1739502683.4397206,43.71995830535889,-2.585412007726218,1739502683.4397223,43.71995830535889,-1.517908068800869,1739502683.439724,43.71995830535889,-0.6108,1739502683.4397256,43.71995830535889,0.7422748228670277,1739502683.4397273,43.71995830535889,0.0,1739502683.4397292,43.71995830535889,-0.08361754819917644,1739502683.4397306,43.71995830535889,4.155298286254579,1739502683.4397326,43.71995830535889,0.8258923710662042 +1739502683.459155,43.7399582862854,42.091168825634995,1739502683.4591582,43.7399582862854,1.8134264939966158,1739502683.4591625,43.7399582862854,70.52558802189715,1739502683.459166,43.7399582862854,39.159918574582974,1739502683.4591677,43.7399582862854,0.06523099353144722,1739502683.4591699,43.7399582862854,-2.603824957618797,1739502683.4591718,43.7399582862854,-1.4885529892716358,1739502683.4591734,43.7399582862854,-0.6108,1739502683.459175,43.7399582862854,0.7599127464895922,1739502683.459177,43.7399582862854,0.0,1739502683.4591787,43.7399582862854,-0.04459293106541343,1739502683.4591806,43.7399582862854,4.130670602052144,1739502683.4591823,43.7399582862854,0.8167008784051033 +1739502683.4792218,43.759958267211914,42.091168825634995,1739502683.4792254,43.759958267211914,1.8134264939966158,1739502683.4792295,43.759958267211914,70.52558802189715,1739502683.4792328,43.759958267211914,39.159918574582974,1739502683.4792342,43.759958267211914,0.06523099353144722,1739502683.4792364,43.759958267211914,-2.603824957618797,1739502683.4792387,43.759958267211914,-1.4885529892716358,1739502683.4792404,43.759958267211914,-0.6108,1739502683.479242,43.759958267211914,0.7599127464895922,1739502683.479244,43.759958267211914,0.0,1739502683.4792457,43.759958267211914,-0.05678813191551113,1739502683.4792473,43.759958267211914,4.130670602052144,1739502683.479249,43.759958267211914,0.8167008784051033 +1739502683.499682,43.77995824813843,42.091168825634995,1739502683.499685,43.77995824813843,1.8134264939966158,1739502683.4996886,43.77995824813843,70.52558802189715,1739502683.499692,43.77995824813843,39.159918574582974,1739502683.4996936,43.77995824813843,0.06523099353144722,1739502683.4996955,43.77995824813843,-2.603824957618797,1739502683.4996974,43.77995824813843,-1.4885529892716358,1739502683.499699,43.77995824813843,-0.6108,1739502683.4997008,43.77995824813843,0.7599127464895922,1739502683.4997025,43.77995824813843,0.0,1739502683.4997041,43.77995824813843,-0.05678813191551113,1739502683.4997058,43.77995824813843,4.130670602052144,1739502683.4997077,43.77995824813843,0.8167008784051033 +1739502683.5191422,43.79995822906494,42.091168825634995,1739502683.5191453,43.79995822906494,1.8134264939966158,1739502683.5191488,43.79995822906494,70.52558802189715,1739502683.5191524,43.79995822906494,39.159918574582974,1739502683.519154,43.79995822906494,0.06523099353144722,1739502683.5191562,43.79995822906494,-2.603824957618797,1739502683.5191581,43.79995822906494,-1.4885529892716358,1739502683.5191598,43.79995822906494,-0.6108,1739502683.5191615,43.79995822906494,0.7599127464895922,1739502683.5191634,43.79995822906494,0.0,1739502683.5191653,43.79995822906494,-0.05678813191551113,1739502683.519167,43.79995822906494,4.130670602052144,1739502683.5191689,43.79995822906494,0.8167008784051033 +1739502683.5387838,43.819958209991455,42.091168825634995,1739502683.538786,43.819958209991455,1.8134264939966158,1739502683.5387888,43.819958209991455,70.52558802189715,1739502683.5387914,43.819958209991455,39.159918574582974,1739502683.5387926,43.819958209991455,0.06523099353144722,1739502683.5387943,43.819958209991455,-2.603824957618797,1739502683.5387955,43.819958209991455,-1.4885529892716358,1739502683.538797,43.819958209991455,-0.6108,1739502683.538798,43.819958209991455,0.7599127464895922,1739502683.5387993,43.819958209991455,0.0,1739502683.5388007,43.819958209991455,-0.05678813191551113,1739502683.538802,43.819958209991455,4.130670602052144,1739502683.538803,43.819958209991455,0.8167008784051033 +1739502683.5592532,43.83995819091797,42.091168825634995,1739502683.5592563,43.83995819091797,1.8134264939966158,1739502683.5592597,43.83995819091797,70.52558802189715,1739502683.5592628,43.83995819091797,39.159918574582974,1739502683.5592642,43.83995819091797,0.06523099353144722,1739502683.559266,43.83995819091797,-2.603824957618797,1739502683.5592678,43.83995819091797,-1.4885529892716358,1739502683.5592697,43.83995819091797,-0.6108,1739502683.5592709,43.83995819091797,0.7599127464895922,1739502683.5592728,43.83995819091797,0.0,1739502683.5592742,43.83995819091797,-0.05678813191551113,1739502683.559276,43.83995819091797,4.130670602052144,1739502683.5592775,43.83995819091797,0.8167008784051033 +1739502683.5803003,43.85995817184448,42.04108412913952,1739502683.5803044,43.85995817184448,1.7391971538715492,1739502683.580309,43.85995817184448,70.53599548387423,1739502683.5803137,43.85995817184448,39.16145918566727,1739502683.5803158,43.85995817184448,0.06547523675212849,1739502683.5803187,43.85995817184448,-2.615089614262872,1739502683.580321,43.85995817184448,-1.4070546491981544,1739502683.5803237,43.85995817184448,-0.6108,1739502683.5803256,43.85995817184448,0.8111088738243954,1739502683.5803282,43.85995817184448,0.0,1739502683.580331,43.85995817184448,0.026382488018039187,1739502683.5803332,43.85995817184448,4.104242031335271,1739502683.5803359,43.85995817184448,0.8107172215765106 +1739502683.600714,43.879958152770996,42.04108412913952,1739502683.6007178,43.879958152770996,1.7391971538715492,1739502683.600722,43.879958152770996,70.53599548387423,1739502683.6007266,43.879958152770996,39.16145918566727,1739502683.6007285,43.879958152770996,0.06547523675212849,1739502683.6007314,43.879958152770996,-2.615089614262872,1739502683.600734,43.879958152770996,-1.4070546491981544,1739502683.6007361,43.879958152770996,-0.6108,1739502683.6007385,43.879958152770996,0.8111088738243954,1739502683.6007411,43.879958152770996,0.0,1739502683.6007435,43.879958152770996,0.0003916522478848439,1739502683.600746,43.879958152770996,4.104242031335271,1739502683.600748,43.879958152770996,0.8107172215765106 +1739502683.6202703,43.89995813369751,42.04108412913952,1739502683.6202748,43.89995813369751,1.7391971538715492,1739502683.620279,43.89995813369751,70.53599548387423,1739502683.6202836,43.89995813369751,39.16145918566727,1739502683.6202862,43.89995813369751,0.06547523675212849,1739502683.620289,43.89995813369751,-2.615089614262872,1739502683.6202915,43.89995813369751,-1.4070546491981544,1739502683.620294,43.89995813369751,-0.6108,1739502683.6202965,43.89995813369751,0.8111088738243954,1739502683.620299,43.89995813369751,0.0,1739502683.6203017,43.89995813369751,0.0003916522478848439,1739502683.620304,43.89995813369751,4.104242031335271,1739502683.6203067,43.89995813369751,0.8107172215765106 +1739502683.640349,43.91995811462402,42.04108412913952,1739502683.640353,43.91995811462402,1.7391971538715492,1739502683.6403575,43.91995811462402,70.53599548387423,1739502683.640362,43.91995811462402,39.16145918566727,1739502683.6403642,43.91995811462402,0.06547523675212849,1739502683.6403673,43.91995811462402,-2.615089614262872,1739502683.6403697,43.91995811462402,-1.4070546491981544,1739502683.6403718,43.91995811462402,-0.6108,1739502683.640374,43.91995811462402,0.8111088738243954,1739502683.6403766,43.91995811462402,0.0,1739502683.6403792,43.91995811462402,0.0003916522478848439,1739502683.640382,43.91995811462402,4.104242031335271,1739502683.6403844,43.91995811462402,0.8107172215765106 +1739502683.6601365,43.93995809555054,42.04108412913952,1739502683.6601405,43.93995809555054,1.7391971538715492,1739502683.660145,43.93995809555054,70.53599548387423,1739502683.6601498,43.93995809555054,39.16145918566727,1739502683.660152,43.93995809555054,0.06547523675212849,1739502683.660155,43.93995809555054,-2.615089614262872,1739502683.6601577,43.93995809555054,-1.4070546491981544,1739502683.6601603,43.93995809555054,-0.6108,1739502683.6601632,43.93995809555054,0.8111088738243954,1739502683.6601658,43.93995809555054,0.0,1739502683.6601682,43.93995809555054,0.0003916522478848439,1739502683.6601713,43.93995809555054,4.104242031335271,1739502683.660174,43.93995809555054,0.8107172215765106 +1739502683.6788714,43.95995807647705,41.989226203077486,1739502683.6788735,43.95995807647705,1.6666624922343134,1739502683.6788769,43.95995807647705,70.70373542274764,1739502683.6788795,43.95995807647705,38.99575675937817,1739502683.678881,43.95995807647705,0.03952594631294354,1739502683.6788826,43.95995807647705,-2.6437055987572586,1739502683.6788838,43.95995807647705,-1.4424963819058618,1739502683.6788855,43.95995807647705,-0.6108,1739502683.6788864,43.95995807647705,0.7884341621539332,1739502683.678888,43.95995807647705,0.0,1739502683.6788895,43.95995807647705,-0.03258358062244392,1739502683.678891,43.95995807647705,4.076650089916402,1739502683.6788926,43.95995807647705,0.8107129757480677 +1739502683.7020788,43.979958057403564,41.989226203077486,1739502683.702083,43.979958057403564,1.6666624922343134,1739502683.702088,43.979958057403564,70.70373542274764,1739502683.702095,43.979958057403564,38.99575675937817,1739502683.702098,43.979958057403564,0.03952594631294354,1739502683.7021024,43.979958057403564,-2.6437055987572586,1739502683.7021058,43.979958057403564,-1.4424963819058618,1739502683.7021105,43.979958057403564,-0.6108,1739502683.7021143,43.979958057403564,0.7884341621539332,1739502683.7021182,43.979958057403564,0.0,1739502683.7021222,43.979958057403564,-0.022278813594134417,1739502683.702125,43.979958057403564,4.076650089916402,1739502683.7021298,43.979958057403564,0.8107129757480677 +1739502683.7188435,43.99995803833008,41.989226203077486,1739502683.7188454,43.99995803833008,1.6666624922343134,1739502683.7188485,43.99995803833008,70.70373542274764,1739502683.718851,43.99995803833008,38.99575675937817,1739502683.7188523,43.99995803833008,0.03952594631294354,1739502683.718854,43.99995803833008,-2.6437055987572586,1739502683.7188551,43.99995803833008,-1.4424963819058618,1739502683.7188563,43.99995803833008,-0.6108,1739502683.7188578,43.99995803833008,0.7884341621539332,1739502683.7188592,43.99995803833008,0.0,1739502683.7188609,43.99995803833008,-0.022278813594134417,1739502683.718862,43.99995803833008,4.076650089916402,1739502683.7188632,43.99995803833008,0.8107129757480677 +1739502683.7391036,44.01995801925659,41.989226203077486,1739502683.739106,44.01995801925659,1.6666624922343134,1739502683.7391086,44.01995801925659,70.70373542274764,1739502683.7391114,44.01995801925659,38.99575675937817,1739502683.7391126,44.01995801925659,0.03952594631294354,1739502683.7391143,44.01995801925659,-2.6437055987572586,1739502683.7391155,44.01995801925659,-1.4424963819058618,1739502683.7391171,44.01995801925659,-0.6108,1739502683.739118,44.01995801925659,0.7884341621539332,1739502683.7391195,44.01995801925659,0.0,1739502683.7391212,44.01995801925659,-0.022278813594134417,1739502683.7391224,44.01995801925659,4.076650089916402,1739502683.7391238,44.01995801925659,0.8107129757480677 +1739502683.769672,44.02995800971985,41.989226203077486,1739502683.7696798,44.02995800971985,1.6666624922343134,1739502683.76969,44.02995800971985,70.70373542274764,1739502683.7697,44.02995800971985,38.99575675937817,1739502683.769705,44.02995800971985,0.03952594631294354,1739502683.7697105,44.02995800971985,-2.6437055987572586,1739502683.7697155,44.02995800971985,-1.4424963819058618,1739502683.7697203,44.02995800971985,-0.6108,1739502683.7697248,44.02995800971985,0.7884341621539332,1739502683.7697308,44.02995800971985,0.0,1739502683.7697356,44.02995800971985,-0.022278813594134417,1739502683.7697408,44.02995800971985,4.076650089916402,1739502683.7697458,44.02995800971985,0.8107129757480677 +1739502683.7879155,44.04995799064636,41.989226203077486,1739502683.7879243,44.04995799064636,1.6666624922343134,1739502683.7879353,44.04995799064636,70.70373542274764,1739502683.787945,44.04995799064636,38.99575675937817,1739502683.78795,44.04995799064636,0.03952594631294354,1739502683.7879565,44.04995799064636,-2.6437055987572586,1739502683.7879612,44.04995799064636,-1.4424963819058618,1739502683.7879663,44.04995799064636,-0.6108,1739502683.787971,44.04995799064636,0.7884341621539332,1739502683.7879765,44.04995799064636,0.0,1739502683.7879813,44.04995799064636,-0.022278813594134417,1739502683.7879868,44.04995799064636,4.076650089916402,1739502683.7879915,44.04995799064636,0.8107129757480677 +1739502683.8134394,44.069957971572876,41.93546611141185,1739502683.8134458,44.069957971572876,1.5956915711390813,1739502683.813453,44.069957971572876,70.85273912737594,1739502683.81346,44.069957971572876,38.85337779574783,1739502683.813464,44.069957971572876,0.020163494280576524,1739502683.8134682,44.069957971572876,-2.6690343670772716,1739502683.813472,44.069957971572876,-1.4583462433771959,1739502683.8134754,44.069957971572876,-0.6108,1739502683.813479,44.069957971572876,0.7785000193694558,1739502683.813483,44.069957971572876,0.0,1739502683.8134866,44.069957971572876,-0.03287774859359821,1739502683.8134904,44.069957971572876,4.049042636466195,1739502683.813494,44.069957971572876,0.8080655986040941 +1739502683.832316,44.09995794296265,41.93546611141185,1739502683.832322,44.09995794296265,1.5956915711390813,1739502683.8323288,44.09995794296265,70.85273912737594,1739502683.832336,44.09995794296265,38.85337779574783,1739502683.8323393,44.09995794296265,0.020163494280576524,1739502683.8323433,44.09995794296265,-2.6690343670772716,1739502683.832347,44.09995794296265,-1.4583462433771959,1739502683.8323505,44.09995794296265,-0.6108,1739502683.8323536,44.09995794296265,0.7785000193694558,1739502683.8323574,44.09995794296265,0.0,1739502683.8323607,44.09995794296265,-0.029565579234638317,1739502683.8323646,44.09995794296265,4.049042636466195,1739502683.8323681,44.09995794296265,0.8080655986040941 +1739502683.852268,44.11995792388916,41.93546611141185,1739502683.852274,44.11995792388916,1.5956915711390813,1739502683.852281,44.11995792388916,70.85273912737594,1739502683.852288,44.11995792388916,38.85337779574783,1739502683.8522913,44.11995792388916,0.020163494280576524,1739502683.8522954,44.11995792388916,-2.6690343670772716,1739502683.852299,44.11995792388916,-1.4583462433771959,1739502683.8523023,44.11995792388916,-0.6108,1739502683.8523057,44.11995792388916,0.7785000193694558,1739502683.8523097,44.11995792388916,0.0,1739502683.852313,44.11995792388916,-0.029565579234638317,1739502683.8523169,44.11995792388916,4.049042636466195,1739502683.8523207,44.11995792388916,0.8080655986040941 +1739502683.8724408,44.139957904815674,41.93546611141185,1739502683.872447,44.139957904815674,1.5956915711390813,1739502683.8724544,44.139957904815674,70.85273912737594,1739502683.8724616,44.139957904815674,38.85337779574783,1739502683.872465,44.139957904815674,0.020163494280576524,1739502683.8724692,44.139957904815674,-2.6690343670772716,1739502683.8724725,44.139957904815674,-1.4583462433771959,1739502683.8724759,44.139957904815674,-0.6108,1739502683.8724792,44.139957904815674,0.7785000193694558,1739502683.872483,44.139957904815674,0.0,1739502683.8724864,44.139957904815674,-0.029565579234638317,1739502683.8724902,44.139957904815674,4.049042636466195,1739502683.872494,44.139957904815674,0.8080655986040941 +1739502683.893665,44.15995788574219,41.93546611141185,1739502683.8936713,44.15995788574219,1.5956915711390813,1739502683.8936784,44.15995788574219,70.85273912737594,1739502683.8936853,44.15995788574219,38.85337779574783,1739502683.893689,44.15995788574219,0.020163494280576524,1739502683.8936934,44.15995788574219,-2.6690343670772716,1739502683.893697,44.15995788574219,-1.4583462433771959,1739502683.8937006,44.15995788574219,-0.6108,1739502683.8937037,44.15995788574219,0.7785000193694558,1739502683.893708,44.15995788574219,0.0,1739502683.8937113,44.15995788574219,-0.029565579234638317,1739502683.893715,44.15995788574219,4.049042636466195,1739502683.8937182,44.15995788574219,0.8080655986040941 +1739502683.9138248,44.1799578666687,41.87996140548262,1739502683.9138334,44.1799578666687,1.5264733075513623,1739502683.913845,44.1799578666687,70.8616767395576,1739502683.913859,44.1799578666687,38.85092522716748,1739502683.9138665,44.1799578666687,0.0198609046505337,1739502683.9138763,44.1799578666687,-2.680035197713781,1739502683.9138849,44.1799578666687,-1.3741693482835464,1739502683.9138937,44.1799578666687,-0.6108,1739502683.9139023,44.1799578666687,0.8327308929000864,1739502683.9139113,44.1799578666687,0.0,1739502683.9139202,44.1799578666687,0.05401858743323856,1739502683.9139292,44.1799578666687,4.0214351830159885,1739502683.9139383,44.1799578666687,0.8048323746762113 +1739502683.9338596,44.199957847595215,41.87996140548262,1739502683.933869,44.199957847595215,1.5264733075513623,1739502683.9338806,44.199957847595215,70.8616767395576,1739502683.9338942,44.199957847595215,38.85092522716748,1739502683.9339015,44.199957847595215,0.0198609046505337,1739502683.9339113,44.199957847595215,-2.680035197713781,1739502683.9339201,44.199957847595215,-1.3741693482835464,1739502683.933929,44.199957847595215,-0.6108,1739502683.9339373,44.199957847595215,0.8327308929000864,1739502683.9339466,44.199957847595215,0.0,1739502683.9339554,44.199957847595215,0.027898518223875124,1739502683.9339645,44.199957847595215,4.0214351830159885,1739502683.9339733,44.199957847595215,0.8048323746762113 +1739502683.9529243,44.21995782852173,41.87996140548262,1739502683.952931,44.21995782852173,1.5264733075513623,1739502683.9529383,44.21995782852173,70.8616767395576,1739502683.9529452,44.21995782852173,38.85092522716748,1739502683.9529488,44.21995782852173,0.0198609046505337,1739502683.9529533,44.21995782852173,-2.680035197713781,1739502683.9529572,44.21995782852173,-1.3741693482835464,1739502683.9529607,44.21995782852173,-0.6108,1739502683.9529638,44.21995782852173,0.8327308929000864,1739502683.9529676,44.21995782852173,0.0,1739502683.9529712,44.21995782852173,0.027898518223875124,1739502683.9529748,44.21995782852173,4.0214351830159885,1739502683.9529781,44.21995782852173,0.8048323746762113 +1739502683.972217,44.23995780944824,41.87996140548262,1739502683.972223,44.23995780944824,1.5264733075513623,1739502683.9722297,44.23995780944824,70.8616767395576,1739502683.9722366,44.23995780944824,38.85092522716748,1739502683.9722402,44.23995780944824,0.0198609046505337,1739502683.972244,44.23995780944824,-2.680035197713781,1739502683.9722478,44.23995780944824,-1.3741693482835464,1739502683.9722512,44.23995780944824,-0.6108,1739502683.9722545,44.23995780944824,0.8327308929000864,1739502683.9722583,44.23995780944824,0.0,1739502683.9722617,44.23995780944824,0.027898518223875124,1739502683.9722652,44.23995780944824,4.0214351830159885,1739502683.9722686,44.23995780944824,0.8048323746762113 +1739502683.995456,44.259957790374756,41.87996140548262,1739502683.9954607,44.259957790374756,1.5264733075513623,1739502683.9954665,44.259957790374756,70.8616767395576,1739502683.9954724,44.259957790374756,38.85092522716748,1739502683.995475,44.259957790374756,0.0198609046505337,1739502683.9954782,44.259957790374756,-2.680035197713781,1739502683.995481,44.259957790374756,-1.3741693482835464,1739502683.9954836,44.259957790374756,-0.6108,1739502683.995486,44.259957790374756,0.8327308929000864,1739502683.9954891,44.259957790374756,0.0,1739502683.9954915,44.259957790374756,0.027898518223875124,1739502683.9954944,44.259957790374756,4.0214351830159885,1739502683.995497,44.259957790374756,0.8048323746762113 +1739502684.0115635,44.27995777130127,41.87996140548262,1739502684.0115693,44.27995777130127,1.5264733075513623,1739502684.0115747,44.27995777130127,70.8616767395576,1739502684.0115802,44.27995777130127,38.85092522716748,1739502684.0115826,44.27995777130127,0.0198609046505337,1739502684.0115862,44.27995777130127,-2.680035197713781,1739502684.0115893,44.27995777130127,-1.3741693482835464,1739502684.011592,44.27995777130127,-0.6108,1739502684.0115945,44.27995777130127,0.8327308929000864,1739502684.0115979,44.27995777130127,0.0,1739502684.0116005,44.27995777130127,0.027898518223875124,1739502684.0116034,44.27995777130127,4.0214351830159885,1739502684.0116062,44.27995777130127,0.8048323746762113 +1739502684.0313585,44.29995775222778,41.822561060291235,1739502684.031362,44.29995775222778,1.4588089851540094,1739502684.0313663,44.29995775222778,71.01631756685256,1739502684.031371,44.29995775222778,38.690166096562166,1739502684.031373,44.29995775222778,0.001637872058155401,1739502684.0313756,44.29995775222778,-2.706175542878591,1739502684.031378,44.29995775222778,-1.398662571434282,1739502684.03138,44.29995775222778,-0.6108,1739502684.031382,44.29995775222778,0.8165727054569462,1739502684.0313845,44.29995775222778,0.0,1739502684.0313866,44.29995775222778,-0.0008084402850497188,1739502684.031389,44.29995775222778,3.993827729565783,1739502684.031391,44.29995775222778,0.8084102153261565 +1739502684.0502279,44.3199577331543,41.822561060291235,1739502684.0502305,44.3199577331543,1.4588089851540094,1739502684.050234,44.3199577331543,71.01631756685256,1739502684.0502372,44.3199577331543,38.690166096562166,1739502684.0502386,44.3199577331543,0.001637872058155401,1739502684.0502408,44.3199577331543,-2.706175542878591,1739502684.0502422,44.3199577331543,-1.398662571434282,1739502684.0502439,44.3199577331543,-0.6108,1739502684.0502453,44.3199577331543,0.8165727054569462,1739502684.0502472,44.3199577331543,0.0,1739502684.0502486,44.3199577331543,0.008162490130789624,1739502684.0502505,44.3199577331543,3.993827729565783,1739502684.050252,44.3199577331543,0.8084102153261565 +1739502684.0699034,44.33995771408081,41.822561060291235,1739502684.069906,44.33995771408081,1.4588089851540094,1739502684.0699093,44.33995771408081,71.01631756685256,1739502684.069912,44.33995771408081,38.690166096562166,1739502684.0699136,44.33995771408081,0.001637872058155401,1739502684.0699155,44.33995771408081,-2.706175542878591,1739502684.0699172,44.33995771408081,-1.398662571434282,1739502684.0699189,44.33995771408081,-0.6108,1739502684.0699208,44.33995771408081,0.8165727054569462,1739502684.0699222,44.33995771408081,0.0,1739502684.069924,44.33995771408081,0.008162490130789624,1739502684.0699255,44.33995771408081,3.993827729565783,1739502684.0699275,44.33995771408081,0.8084102153261565 +1739502684.0901535,44.359957695007324,41.822561060291235,1739502684.0901563,44.359957695007324,1.4588089851540094,1739502684.0901597,44.359957695007324,71.01631756685256,1739502684.0901625,44.359957695007324,38.690166096562166,1739502684.090164,44.359957695007324,0.001637872058155401,1739502684.0901659,44.359957695007324,-2.706175542878591,1739502684.0901678,44.359957695007324,-1.398662571434282,1739502684.0901694,44.359957695007324,-0.6108,1739502684.0901706,44.359957695007324,0.8165727054569462,1739502684.0901728,44.359957695007324,0.0,1739502684.0901742,44.359957695007324,0.008162490130789624,1739502684.0901763,44.359957695007324,3.993827729565783,1739502684.0901778,44.359957695007324,0.8084102153261565 +1739502684.1100128,44.37995767593384,41.822561060291235,1739502684.110015,44.37995767593384,1.4588089851540094,1739502684.1100178,44.37995767593384,71.01631756685256,1739502684.1100209,44.37995767593384,38.690166096562166,1739502684.110022,44.37995767593384,0.001637872058155401,1739502684.110024,44.37995767593384,-2.706175542878591,1739502684.1100254,44.37995767593384,-1.398662571434282,1739502684.1100268,44.37995767593384,-0.6108,1739502684.110028,44.37995767593384,0.8165727054569462,1739502684.11003,44.37995767593384,0.0,1739502684.1100311,44.37995767593384,0.008162490130789624,1739502684.1100326,44.37995767593384,3.993827729565783,1739502684.110034,44.37995767593384,0.8084102153261565 +1739502684.130175,44.39995765686035,41.763155053355334,1739502684.1301777,44.39995765686035,1.3925758488359978,1739502684.1301808,44.39995765686035,71.02179311027818,1739502684.1301837,44.39995765686035,38.682908741525125,1739502684.130185,44.39995765686035,0.0008883940196151774,1739502684.1301868,44.39995765686035,-2.7172341809144474,1739502684.1301882,44.39995765686035,-1.3170898078048825,1739502684.1301897,44.39995765686035,-0.6108,1739502684.1301908,44.39995765686035,0.871637969066928,1739502684.130192,44.39995765686035,0.0,1739502684.1301937,44.39995765686035,0.08693350833313625,1739502684.130195,44.39995765686035,3.966220276115581,1739502684.130197,44.39995765686035,0.8093204200615057 +1739502684.1499927,44.419957637786865,41.763155053355334,1739502684.149996,44.419957637786865,1.3925758488359978,1739502684.149999,44.419957637786865,71.02179311027818,1739502684.1500018,44.419957637786865,38.682908741525125,1739502684.1500032,44.419957637786865,0.0008883940196151774,1739502684.1500053,44.419957637786865,-2.7172341809144474,1739502684.1500065,44.419957637786865,-1.3170898078048825,1739502684.1500082,44.419957637786865,-0.6108,1739502684.1500096,44.419957637786865,0.871637969066928,1739502684.1500113,44.419957637786865,0.0,1739502684.1500127,44.419957637786865,0.0623175490054223,1739502684.1500142,44.419957637786865,3.966220276115581,1739502684.1500158,44.419957637786865,0.8093204200615057 +1739502684.169849,44.43995761871338,41.763155053355334,1739502684.169852,44.43995761871338,1.3925758488359978,1739502684.169855,44.43995761871338,71.02179311027818,1739502684.1698582,44.43995761871338,38.682908741525125,1739502684.16986,44.43995761871338,0.0008883940196151774,1739502684.1698618,44.43995761871338,-2.7172341809144474,1739502684.1698632,44.43995761871338,-1.3170898078048825,1739502684.169865,44.43995761871338,-0.6108,1739502684.1698663,44.43995761871338,0.871637969066928,1739502684.1698678,44.43995761871338,0.0,1739502684.1698694,44.43995761871338,0.0623175490054223,1739502684.1698709,44.43995761871338,3.966220276115581,1739502684.1698723,44.43995761871338,0.8093204200615057 +1739502684.1899257,44.45995759963989,41.763155053355334,1739502684.1899288,44.45995759963989,1.3925758488359978,1739502684.1899319,44.45995759963989,71.02179311027818,1739502684.1899345,44.45995759963989,38.682908741525125,1739502684.1899362,44.45995759963989,0.0008883940196151774,1739502684.1899378,44.45995759963989,-2.7172341809144474,1739502684.1899395,44.45995759963989,-1.3170898078048825,1739502684.189941,44.45995759963989,-0.6108,1739502684.1899424,44.45995759963989,0.871637969066928,1739502684.189944,44.45995759963989,0.0,1739502684.1899457,44.45995759963989,0.0623175490054223,1739502684.1899471,44.45995759963989,3.966220276115581,1739502684.1899486,44.45995759963989,0.8093204200615057 +1739502684.2150238,44.479957580566406,41.763155053355334,1739502684.215032,44.479957580566406,1.3925758488359978,1739502684.2150426,44.479957580566406,71.02179311027818,1739502684.2150528,44.479957580566406,38.682908741525125,1739502684.2150576,44.479957580566406,0.0008883940196151774,1739502684.215064,44.479957580566406,-2.7172341809144474,1739502684.2150688,44.479957580566406,-1.3170898078048825,1739502684.2150738,44.479957580566406,-0.6108,1739502684.2150784,44.479957580566406,0.871637969066928,1739502684.2150843,44.479957580566406,0.0,1739502684.215089,44.479957580566406,0.0623175490054223,1739502684.2150946,44.479957580566406,3.966220276115581,1739502684.2150996,44.479957580566406,0.8093204200615057 +1739502684.2388115,44.49995756149292,41.763155053355334,1739502684.238819,44.49995756149292,1.3925758488359978,1739502684.2388282,44.49995756149292,71.02179311027818,1739502684.2388391,44.49995756149292,38.682908741525125,1739502684.2388446,44.49995756149292,0.0008883940196151774,1739502684.2388523,44.49995756149292,-2.7172341809144474,1739502684.2388592,44.49995756149292,-1.3170898078048825,1739502684.2388659,44.49995756149292,-0.6108,1739502684.2388725,44.49995756149292,0.871637969066928,1739502684.2388794,44.49995756149292,0.0,1739502684.2388864,44.49995756149292,0.0623175490054223,1739502684.2388933,44.49995756149292,3.966220276115581,1739502684.2389,44.49995756149292,0.8093204200615057 +1739502684.2561085,44.50995755195618,41.70163966210803,1739502684.256114,44.50995755195618,1.3276897348499883,1739502684.2561214,44.50995755195618,71.13753061428001,1739502684.2561297,44.50995755195618,38.55315431080618,1739502684.2561347,44.50995755195618,-0.011851297905062506,1739502684.2561405,44.50995755195618,-2.739336089174861,1739502684.2561462,44.50995755195618,-1.3159121757666585,1739502684.256152,44.50995755195618,-0.6108,1739502684.2561572,44.50995755195618,0.872459531043729,1739502684.256163,44.50995755195618,0.0,1739502684.2561684,44.50995755195618,0.052863084835189034,1739502684.256174,44.50995755195618,3.938612822665379,1739502684.2561796,44.50995755195618,0.8166419242182065 +1739502684.2734163,44.53995752334595,41.70163966210803,1739502684.2734194,44.53995752334595,1.3276897348499883,1739502684.2734232,44.53995752334595,71.13753061428001,1739502684.273427,44.53995752334595,38.55315431080618,1739502684.2734287,44.53995752334595,-0.011851297905062506,1739502684.273431,44.53995752334595,-2.739336089174861,1739502684.2734327,44.53995752334595,-1.3159121757666585,1739502684.2734349,44.53995752334595,-0.6108,1739502684.2734368,44.53995752334595,0.872459531043729,1739502684.2734387,44.53995752334595,0.0,1739502684.2734406,44.53995752334595,0.0558176068255225,1739502684.2734425,44.53995752334595,3.938612822665379,1739502684.2734447,44.53995752334595,0.8166419242182065 +1739502684.2944605,44.55995750427246,41.70163966210803,1739502684.294465,44.55995750427246,1.3276897348499883,1739502684.2944715,44.55995750427246,71.13753061428001,1739502684.2944784,44.55995750427246,38.55315431080618,1739502684.2944827,44.55995750427246,-0.011851297905062506,1739502684.2944877,44.55995750427246,-2.739336089174861,1739502684.2944925,44.55995750427246,-1.3159121757666585,1739502684.2944968,44.55995750427246,-0.6108,1739502684.2945013,44.55995750427246,0.872459531043729,1739502684.2945063,44.55995750427246,0.0,1739502684.2945108,44.55995750427246,0.0558176068255225,1739502684.2945154,44.55995750427246,3.938612822665379,1739502684.2945204,44.55995750427246,0.8166419242182065 +1739502684.3104815,44.579957485198975,41.70163966210803,1739502684.3104846,44.579957485198975,1.3276897348499883,1739502684.3104885,44.579957485198975,71.13753061428001,1739502684.3104918,44.579957485198975,38.55315431080618,1739502684.3104937,44.579957485198975,-0.011851297905062506,1739502684.310496,44.579957485198975,-2.739336089174861,1739502684.310498,44.579957485198975,-1.3159121757666585,1739502684.3105,44.579957485198975,-0.6108,1739502684.3105016,44.579957485198975,0.872459531043729,1739502684.3105037,44.579957485198975,0.0,1739502684.3105054,44.579957485198975,0.0558176068255225,1739502684.3105073,44.579957485198975,3.938612822665379,1739502684.310509,44.579957485198975,0.8166419242182065 +1739502684.3335025,44.59995746612549,41.70163966210803,1739502684.3335059,44.59995746612549,1.3276897348499883,1739502684.3335097,44.59995746612549,71.13753061428001,1739502684.3335135,44.59995746612549,38.55315431080618,1739502684.3335152,44.59995746612549,-0.011851297905062506,1739502684.3335176,44.59995746612549,-2.739336089174861,1739502684.3335195,44.59995746612549,-1.3159121757666585,1739502684.3335211,44.59995746612549,-0.6108,1739502684.333523,44.59995746612549,0.872459531043729,1739502684.333525,44.59995746612549,0.0,1739502684.3335268,44.59995746612549,0.0558176068255225,1739502684.3335285,44.59995746612549,3.938612822665379,1739502684.3335307,44.59995746612549,0.8166419242182065 +1739502684.3506272,44.619957447052,41.63785070163154,1739502684.3506298,44.619957447052,1.2640210525143996,1739502684.350634,44.619957447052,71.13861406438298,1739502684.3506377,44.619957447052,38.540060663385255,1739502684.3506393,44.619957447052,-0.013028254976606143,1739502684.3506417,44.619957447052,-2.750574778258286,1739502684.3506434,44.619957447052,-1.2378450919417423,1739502684.3506453,44.619957447052,-0.6108,1739502684.350647,44.619957447052,0.928685306708628,1739502684.350649,44.619957447052,0.0,1739502684.3506505,44.619957447052,0.12882749293643214,1739502684.3506527,44.619957447052,3.911005369215177,1739502684.3506544,44.619957447052,0.8226734181409311 +1739502684.3734381,44.639957427978516,41.63785070163154,1739502684.3734412,44.639957427978516,1.2640210525143996,1739502684.3734453,44.639957427978516,71.13861406438298,1739502684.3734493,44.639957427978516,38.540060663385255,1739502684.373451,44.639957427978516,-0.013028254976606143,1739502684.3734534,44.639957427978516,-2.750574778258286,1739502684.3734553,44.639957427978516,-1.2378450919417423,1739502684.373457,44.639957427978516,-0.6108,1739502684.3734586,44.639957427978516,0.928685306708628,1739502684.3734608,44.639957427978516,0.0,1739502684.3734624,44.639957427978516,0.10601188856769694,1739502684.3734643,44.639957427978516,3.911005369215177,1739502684.3734663,44.639957427978516,0.8226734181409311 +1739502684.3907394,44.65995740890503,41.63785070163154,1739502684.3907425,44.65995740890503,1.2640210525143996,1739502684.3907464,44.65995740890503,71.13861406438298,1739502684.3907502,44.65995740890503,38.540060663385255,1739502684.390752,44.65995740890503,-0.013028254976606143,1739502684.3907542,44.65995740890503,-2.750574778258286,1739502684.3907561,44.65995740890503,-1.2378450919417423,1739502684.3907578,44.65995740890503,-0.6108,1739502684.3907597,44.65995740890503,0.928685306708628,1739502684.3907616,44.65995740890503,0.0,1739502684.3907635,44.65995740890503,0.10601188856769694,1739502684.3907657,44.65995740890503,3.911005369215177,1739502684.3907673,44.65995740890503,0.8226734181409311 +1739502684.4106023,44.67995738983154,41.63785070163154,1739502684.410605,44.67995738983154,1.2640210525143996,1739502684.410609,44.67995738983154,71.13861406438298,1739502684.4106128,44.67995738983154,38.540060663385255,1739502684.4106147,44.67995738983154,-0.013028254976606143,1739502684.4106169,44.67995738983154,-2.750574778258286,1739502684.4106188,44.67995738983154,-1.2378450919417423,1739502684.4106205,44.67995738983154,-0.6108,1739502684.4106221,44.67995738983154,0.928685306708628,1739502684.4106243,44.67995738983154,0.0,1739502684.4106264,44.67995738983154,0.10601188856769694,1739502684.410628,44.67995738983154,3.911005369215177,1739502684.41063,44.67995738983154,0.8226734181409311 +1739502684.4315686,44.69995737075806,41.63785070163154,1739502684.4315724,44.69995737075806,1.2640210525143996,1739502684.4315763,44.69995737075806,71.13861406438298,1739502684.43158,44.69995737075806,38.540060663385255,1739502684.4315822,44.69995737075806,-0.013028254976606143,1739502684.4315846,44.69995737075806,-2.750574778258286,1739502684.4315865,44.69995737075806,-1.2378450919417423,1739502684.4315884,44.69995737075806,-0.6108,1739502684.43159,44.69995737075806,0.928685306708628,1739502684.4315922,44.69995737075806,0.0,1739502684.431594,44.69995737075806,0.10601188856769694,1739502684.431596,44.69995737075806,3.911005369215177,1739502684.4315982,44.69995737075806,0.8226734181409311 +1739502684.4509778,44.71995735168457,41.63785070163154,1739502684.4509816,44.71995735168457,1.2640210525143996,1739502684.450986,44.71995735168457,71.13861406438298,1739502684.4509895,44.71995735168457,38.540060663385255,1739502684.4509916,44.71995735168457,-0.013028254976606143,1739502684.450994,44.71995735168457,-2.750574778258286,1739502684.4509957,44.71995735168457,-1.2378450919417423,1739502684.4509978,44.71995735168457,-0.6108,1739502684.4509993,44.71995735168457,0.928685306708628,1739502684.451002,44.71995735168457,0.0,1739502684.4510036,44.71995735168457,0.10601188856769694,1739502684.4510057,44.71995735168457,3.911005369215177,1739502684.4510076,44.71995735168457,0.8226734181409311 +1739502684.4704907,44.739957332611084,41.57160770546459,1739502684.470494,44.739957332611084,1.20145866495381,1739502684.4704978,44.739957332611084,71.13971075044897,1739502684.470502,44.739957332611084,38.51491330711485,1739502684.4705036,44.739957332611084,-0.015288691495294169,1739502684.470506,44.739957332611084,-2.7627599256557644,1739502684.4705079,44.739957332611084,-1.1681165930839421,1739502684.4705095,44.739957332611084,-0.6108,1739502684.4705112,44.739957332611084,0.9819621230605471,1739502684.4705133,44.739957332611084,0.0,1739502684.4705153,44.739957332611084,0.16594032405235942,1739502684.4705172,44.739957332611084,3.883397915764975,1739502684.4705193,44.739957332611084,0.8347494473759478 +1739502684.4904912,44.7599573135376,41.57160770546459,1739502684.4904945,44.7599573135376,1.20145866495381,1739502684.4904983,44.7599573135376,71.13971075044897,1739502684.490502,44.7599573135376,38.51491330711485,1739502684.4905043,44.7599573135376,-0.015288691495294169,1739502684.4905064,44.7599573135376,-2.7627599256557644,1739502684.4905083,44.7599573135376,-1.1681165930839421,1739502684.49051,44.7599573135376,-0.6108,1739502684.4905117,44.7599573135376,0.9819621230605471,1739502684.4905136,44.7599573135376,0.0,1739502684.4905155,44.7599573135376,0.14721267568459928,1739502684.4905176,44.7599573135376,3.883397915764975,1739502684.4905193,44.7599573135376,0.8347494473759478 +1739502684.5111024,44.77995729446411,41.57160770546459,1739502684.511106,44.77995729446411,1.20145866495381,1739502684.5111098,44.77995729446411,71.13971075044897,1739502684.5111136,44.77995729446411,38.51491330711485,1739502684.5111156,44.77995729446411,-0.015288691495294169,1739502684.511118,44.77995729446411,-2.7627599256557644,1739502684.5111198,44.77995729446411,-1.1681165930839421,1739502684.5111217,44.77995729446411,-0.6108,1739502684.5111237,44.77995729446411,0.9819621230605471,1739502684.5111258,44.77995729446411,0.0,1739502684.5111275,44.77995729446411,0.14721267568459928,1739502684.5111296,44.77995729446411,3.883397915764975,1739502684.5111313,44.77995729446411,0.8347494473759478 +1739502684.5344627,44.78995728492737,41.57160770546459,1739502684.534468,44.78995728492737,1.20145866495381,1739502684.534474,44.78995728492737,71.13971075044897,1739502684.534481,44.78995728492737,38.51491330711485,1739502684.5344853,44.78995728492737,-0.015288691495294169,1739502684.5344903,44.78995728492737,-2.7627599256557644,1739502684.5344949,44.78995728492737,-1.1681165930839421,1739502684.5344996,44.78995728492737,-0.6108,1739502684.5345042,44.78995728492737,0.9819621230605471,1739502684.534509,44.78995728492737,0.0,1739502684.5345137,44.78995728492737,0.14721267568459928,1739502684.5345182,44.78995728492737,3.883397915764975,1739502684.5345232,44.78995728492737,0.8347494473759478 +1739502684.5534377,44.81995725631714,41.57160770546459,1739502684.5534408,44.81995725631714,1.20145866495381,1739502684.5534444,44.81995725631714,71.13971075044897,1739502684.5534482,44.81995725631714,38.51491330711485,1739502684.5534499,44.81995725631714,-0.015288691495294169,1739502684.5534523,44.81995725631714,-2.7627599256557644,1739502684.5534542,44.81995725631714,-1.1681165930839421,1739502684.5534558,44.81995725631714,-0.6108,1739502684.5534577,44.81995725631714,0.9819621230605471,1739502684.5534596,44.81995725631714,0.0,1739502684.5534613,44.81995725631714,0.14721267568459928,1739502684.5534632,44.81995725631714,3.883397915764975,1739502684.5534654,44.81995725631714,0.8347494473759478 +1739502684.5708935,44.83995723724365,41.50254291420188,1739502684.5708973,44.83995723724365,1.1397492913788705,1739502684.5709012,44.83995723724365,71.14082600855893,1739502684.570905,44.83995723724365,38.481766606844694,1739502684.5709069,44.83995723724365,-0.01852333931553053,1739502684.5709093,44.83995723724365,-2.775447133688037,1739502684.570911,44.83995723724365,-1.1034304251412541,1739502684.5709128,44.83995723724365,-0.6108,1739502684.5709143,44.83995723724365,1.0341154170489175,1739502684.5709167,44.83995723724365,0.0,1739502684.5709183,44.83995723724365,0.19966170083947493,1739502684.5709202,44.83995723724365,3.855790462314773,1739502684.5709221,44.83995723724365,0.8508440473166797 +1739502684.5904834,44.859957218170166,41.50254291420188,1739502684.5904865,44.859957218170166,1.1397492913788705,1739502684.5904903,44.859957218170166,71.14082600855893,1739502684.5904942,44.859957218170166,38.481766606844694,1739502684.590496,44.859957218170166,-0.01852333931553053,1739502684.5904982,44.859957218170166,-2.775447133688037,1739502684.5905,44.859957218170166,-1.1034304251412541,1739502684.5905018,44.859957218170166,-0.6108,1739502684.5905035,44.859957218170166,1.0341154170489175,1739502684.5905058,44.859957218170166,0.0,1739502684.5905073,44.859957218170166,0.1832713697322378,1739502684.5905094,44.859957218170166,3.855790462314773,1739502684.5905108,44.859957218170166,0.8508440473166797 +1739502684.6148913,44.86995720863342,41.50254291420188,1739502684.614896,44.86995720863342,1.1397492913788705,1739502684.6149025,44.86995720863342,71.14082600855893,1739502684.6149096,44.86995720863342,38.481766606844694,1739502684.6149135,44.86995720863342,-0.01852333931553053,1739502684.6149187,44.86995720863342,-2.775447133688037,1739502684.6149235,44.86995720863342,-1.1034304251412541,1739502684.6149282,44.86995720863342,-0.6108,1739502684.6149328,44.86995720863342,1.0341154170489175,1739502684.6149375,44.86995720863342,0.0,1739502684.6149423,44.86995720863342,0.1832713697322378,1739502684.6149468,44.86995720863342,3.855790462314773,1739502684.6149516,44.86995720863342,0.8508440473166797 +1739502684.6320379,44.89995718002319,41.50254291420188,1739502684.6320407,44.89995718002319,1.1397492913788705,1739502684.6320448,44.89995718002319,71.14082600855893,1739502684.6320484,44.89995718002319,38.481766606844694,1739502684.6320503,44.89995718002319,-0.01852333931553053,1739502684.6320524,44.89995718002319,-2.775447133688037,1739502684.6320543,44.89995718002319,-1.1034304251412541,1739502684.632056,44.89995718002319,-0.6108,1739502684.632058,44.89995718002319,1.0341154170489175,1739502684.6320598,44.89995718002319,0.0,1739502684.6320617,44.89995718002319,0.1832713697322378,1739502684.6320636,44.89995718002319,3.855790462314773,1739502684.6320655,44.89995718002319,0.8508440473166797 +1739502684.6535296,44.91995716094971,41.50254291420188,1739502684.6535327,44.91995716094971,1.1397492913788705,1739502684.6535366,44.91995716094971,71.14082600855893,1739502684.6535404,44.91995716094971,38.481766606844694,1739502684.653542,44.91995716094971,-0.01852333931553053,1739502684.6535444,44.91995716094971,-2.775447133688037,1739502684.6535463,44.91995716094971,-1.1034304251412541,1739502684.653548,44.91995716094971,-0.6108,1739502684.65355,44.91995716094971,1.0341154170489175,1739502684.6535518,44.91995716094971,0.0,1739502684.6535537,44.91995716094971,0.1832713697322378,1739502684.6535554,44.91995716094971,3.855790462314773,1739502684.6535575,44.91995716094971,0.8508440473166797 +1739502684.6734097,44.93995714187622,41.50254291420188,1739502684.6734133,44.93995714187622,1.1397492913788705,1739502684.6734176,44.93995714187622,71.14082600855893,1739502684.6734211,44.93995714187622,38.481766606844694,1739502684.673423,44.93995714187622,-0.01852333931553053,1739502684.6734252,44.93995714187622,-2.775447133688037,1739502684.673427,44.93995714187622,-1.1034304251412541,1739502684.673429,44.93995714187622,-0.6108,1739502684.6734307,44.93995714187622,1.0341154170489175,1739502684.673433,44.93995714187622,0.0,1739502684.673435,44.93995714187622,0.1832713697322378,1739502684.6734366,44.93995714187622,3.855790462314773,1739502684.6734388,44.93995714187622,0.8508440473166797 +1739502684.6908462,44.959957122802734,41.43026560860449,1739502684.6908493,44.959957122802734,1.0786736151624252,1739502684.690853,44.959957122802734,71.14196510971904,1739502684.6908567,44.959957122802734,38.43999977193919,1739502684.6908586,44.959957122802734,-0.02270002280608107,1739502684.6908607,44.959957122802734,-2.788691560842811,1739502684.6908627,44.959957122802734,-1.0437254431439529,1739502684.6908643,44.959957122802734,-0.6108,1739502684.690866,44.959957122802734,1.0847075129781594,1739502684.690868,44.959957122802734,0.0,1739502684.6908698,44.959957122802734,0.22716094167037904,1739502684.6908715,44.959957122802734,3.828183008864571,1739502684.6908734,44.959957122802734,0.8712620715310322 +1739502684.7104962,44.97995710372925,41.43026560860449,1739502684.7104993,44.97995710372925,1.0786736151624252,1739502684.7105033,44.97995710372925,71.14196510971904,1739502684.710507,44.97995710372925,38.43999977193919,1739502684.7105088,44.97995710372925,-0.02270002280608107,1739502684.7105112,44.97995710372925,-2.788691560842811,1739502684.7105129,44.97995710372925,-1.0437254431439529,1739502684.7105148,44.97995710372925,-0.6108,1739502684.7105165,44.97995710372925,1.0847075129781594,1739502684.7105186,44.97995710372925,0.0,1739502684.7105203,44.97995710372925,0.21344544144712718,1739502684.7105222,44.97995710372925,3.828183008864571,1739502684.7105238,44.97995710372925,0.8712620715310322 +1739502684.7305205,44.99995708465576,41.43026560860449,1739502684.730524,44.99995708465576,1.0786736151624252,1739502684.730528,44.99995708465576,71.14196510971904,1739502684.7305317,44.99995708465576,38.43999977193919,1739502684.7305334,44.99995708465576,-0.02270002280608107,1739502684.7305362,44.99995708465576,-2.788691560842811,1739502684.7305381,44.99995708465576,-1.0437254431439529,1739502684.73054,44.99995708465576,-0.6108,1739502684.7305417,44.99995708465576,1.0847075129781594,1739502684.7305439,44.99995708465576,0.0,1739502684.7305458,44.99995708465576,0.21344544144712718,1739502684.7305477,44.99995708465576,3.828183008864571,1739502684.7305498,44.99995708465576,0.8712620715310322 +1739502684.750702,45.019957065582275,41.43026560860449,1739502684.7507055,45.019957065582275,1.0786736151624252,1739502684.7507093,45.019957065582275,71.14196510971904,1739502684.7507129,45.019957065582275,38.43999977193919,1739502684.7507145,45.019957065582275,-0.02270002280608107,1739502684.7507172,45.019957065582275,-2.788691560842811,1739502684.750719,45.019957065582275,-1.0437254431439529,1739502684.750721,45.019957065582275,-0.6108,1739502684.7507226,45.019957065582275,1.0847075129781594,1739502684.750725,45.019957065582275,0.0,1739502684.7507272,45.019957065582275,0.21344544144712718,1739502684.7507288,45.019957065582275,3.828183008864571,1739502684.750731,45.019957065582275,0.8712620715310322 +1739502684.7705157,45.03995704650879,41.43026560860449,1739502684.7705193,45.03995704650879,1.0786736151624252,1739502684.7705233,45.03995704650879,71.14196510971904,1739502684.770527,45.03995704650879,38.43999977193919,1739502684.7705288,45.03995704650879,-0.02270002280608107,1739502684.7705312,45.03995704650879,-2.788691560842811,1739502684.7705328,45.03995704650879,-1.0437254431439529,1739502684.770535,45.03995704650879,-0.6108,1739502684.7705364,45.03995704650879,1.0847075129781594,1739502684.7705388,45.03995704650879,0.0,1739502684.7705405,45.03995704650879,0.21344544144712718,1739502684.7705424,45.03995704650879,3.828183008864571,1739502684.7705443,45.03995704650879,0.8712620715310322 +1739502684.7905004,45.0599570274353,41.35447594427345,1739502684.7905037,45.0599570274353,1.0181363318166774,1739502684.7905078,45.0599570274353,71.66300767393192,1739502684.7905116,45.0599570274353,37.87396681247373,1739502684.7905138,45.0599570274353,-0.06644839018524817,1739502684.7905161,45.0599570274353,-2.839512714609292,1739502684.790518,45.0599570274353,-1.2736717024129964,1739502684.79052,45.0599570274353,-0.6108,1739502684.7905216,45.0599570274353,0.9024458143704738,1739502684.7905235,45.0599570274353,0.0,1739502684.7905254,45.0599570274353,-0.0856396317998923,1739502684.7905273,45.0599570274353,3.800575555414369,1739502684.7905293,45.0599570274353,0.8946212995008026 +1739502684.8141656,45.079957008361816,41.35447594427345,1739502684.8141706,45.079957008361816,1.0181363318166774,1739502684.814177,45.079957008361816,71.66300767393192,1739502684.8141842,45.079957008361816,37.87396681247373,1739502684.814188,45.079957008361816,-0.06644839018524817,1739502684.8141932,45.079957008361816,-2.839512714609292,1739502684.8141978,45.079957008361816,-1.2736717024129964,1739502684.8142025,45.079957008361816,-0.6108,1739502684.8142073,45.079957008361816,0.9024458143704738,1739502684.814212,45.079957008361816,0.0,1739502684.8142166,45.079957008361816,0.007824514869671173,1739502684.8142214,45.079957008361816,3.800575555414369,1739502684.8142262,45.079957008361816,0.8946212995008026 +1739502684.8339376,45.09995698928833,41.35447594427345,1739502684.8339422,45.09995698928833,1.0181363318166774,1739502684.8339486,45.09995698928833,71.66300767393192,1739502684.8339558,45.09995698928833,37.87396681247373,1739502684.8339596,45.09995698928833,-0.06644839018524817,1739502684.833965,45.09995698928833,-2.839512714609292,1739502684.8339696,45.09995698928833,-1.2736717024129964,1739502684.8339741,45.09995698928833,-0.6108,1739502684.8339787,45.09995698928833,0.9024458143704738,1739502684.8339834,45.09995698928833,0.0,1739502684.8339884,45.09995698928833,0.007824514869671173,1739502684.833993,45.09995698928833,3.800575555414369,1739502684.8339975,45.09995698928833,0.8946212995008026 +1739502684.8524883,45.119956970214844,41.35447594427345,1739502684.8524919,45.119956970214844,1.0181363318166774,1739502684.8524966,45.119956970214844,71.66300767393192,1739502684.852502,45.119956970214844,37.87396681247373,1739502684.8525047,45.119956970214844,-0.06644839018524817,1739502684.852509,45.119956970214844,-2.839512714609292,1739502684.8525126,45.119956970214844,-1.2736717024129964,1739502684.8525162,45.119956970214844,-0.6108,1739502684.8525198,45.119956970214844,0.9024458143704738,1739502684.8525233,45.119956970214844,0.0,1739502684.852527,45.119956970214844,0.007824514869671173,1739502684.8525302,45.119956970214844,3.800575555414369,1739502684.8525338,45.119956970214844,0.8946212995008026 +1739502684.8702686,45.13995695114136,41.35447594427345,1739502684.8702714,45.13995695114136,1.0181363318166774,1739502684.870275,45.13995695114136,71.66300767393192,1739502684.870278,45.13995695114136,37.87396681247373,1739502684.8702788,45.13995695114136,-0.06644839018524817,1739502684.870281,45.13995695114136,-2.839512714609292,1739502684.8702822,45.13995695114136,-1.2736717024129964,1739502684.8702836,45.13995695114136,-0.6108,1739502684.8702848,45.13995695114136,0.9024458143704738,1739502684.8702862,45.13995695114136,0.0,1739502684.8702877,45.13995695114136,0.007824514869671173,1739502684.870289,45.13995695114136,3.800575555414369,1739502684.870291,45.13995695114136,0.8946212995008026 +1739502684.8901813,45.15995693206787,41.35447594427345,1739502684.8901842,45.15995693206787,1.0181363318166774,1739502684.8901873,45.15995693206787,71.66300767393192,1739502684.8901896,45.15995693206787,37.87396681247373,1739502684.890191,45.15995693206787,-0.06644839018524817,1739502684.8901927,45.15995693206787,-2.839512714609292,1739502684.890194,45.15995693206787,-1.2736717024129964,1739502684.8901951,45.15995693206787,-0.6108,1739502684.8901966,45.15995693206787,0.9024458143704738,1739502684.890198,45.15995693206787,0.0,1739502684.8901992,45.15995693206787,0.007824514869671173,1739502684.8902009,45.15995693206787,3.800575555414369,1739502684.890202,45.15995693206787,0.8946212995008026 +1739502684.9100995,45.179956912994385,41.27603238275469,1739502684.9101021,45.179956912994385,0.9589432434433913,1739502684.910105,45.179956912994385,71.73657152080781,1739502684.9101079,45.179956912994385,37.80253201970867,1739502684.9101093,45.179956912994385,-0.07076047407671233,1739502684.9101107,45.179956912994385,-2.8534000062349043,1739502684.9101121,45.179956912994385,-1.219059308234119,1739502684.9101138,45.179956912994385,-0.6108,1739502684.9101148,45.179956912994385,0.9427475753731753,1739502684.9101167,45.179956912994385,0.0,1739502684.910118,45.179956912994385,0.06789906851839622,1739502684.9101195,45.179956912994385,3.772968101964167,1739502684.910121,45.179956912994385,0.8936218171787471 +1739502684.9298944,45.1999568939209,41.27603238275469,1739502684.929897,45.1999568939209,0.9589432434433913,1739502684.9299002,45.1999568939209,71.73657152080781,1739502684.929903,45.1999568939209,37.80253201970867,1739502684.9299047,45.1999568939209,-0.07076047407671233,1739502684.9299064,45.1999568939209,-2.8534000062349043,1739502684.9299078,45.1999568939209,-1.219059308234119,1739502684.9299092,45.1999568939209,-0.6108,1739502684.9299104,45.1999568939209,0.9427475753731753,1739502684.9299123,45.1999568939209,0.0,1739502684.9299135,45.1999568939209,0.049125758194428215,1739502684.9299154,45.1999568939209,3.772968101964167,1739502684.929917,45.1999568939209,0.8936218171787471 +1739502684.949975,45.21995687484741,41.27603238275469,1739502684.9499779,45.21995687484741,0.9589432434433913,1739502684.949981,45.21995687484741,71.73657152080781,1739502684.9499836,45.21995687484741,37.80253201970867,1739502684.9499853,45.21995687484741,-0.07076047407671233,1739502684.9499872,45.21995687484741,-2.8534000062349043,1739502684.9499886,45.21995687484741,-1.219059308234119,1739502684.9499898,45.21995687484741,-0.6108,1739502684.9499912,45.21995687484741,0.9427475753731753,1739502684.949993,45.21995687484741,0.0,1739502684.9499943,45.21995687484741,0.049125758194428215,1739502684.9499958,45.21995687484741,3.772968101964167,1739502684.9499974,45.21995687484741,0.8936218171787471 +1739502684.9699433,45.239956855773926,41.27603238275469,1739502684.9699466,45.239956855773926,0.9589432434433913,1739502684.9699497,45.239956855773926,71.73657152080781,1739502684.9699528,45.239956855773926,37.80253201970867,1739502684.969954,45.239956855773926,-0.07076047407671233,1739502684.969956,45.239956855773926,-2.8534000062349043,1739502684.9699576,45.239956855773926,-1.219059308234119,1739502684.969959,45.239956855773926,-0.6108,1739502684.9699602,45.239956855773926,0.9427475753731753,1739502684.969962,45.239956855773926,0.0,1739502684.9699633,45.239956855773926,0.049125758194428215,1739502684.9699647,45.239956855773926,3.772968101964167,1739502684.9699667,45.239956855773926,0.8936218171787471 +1739502684.9900446,45.25995683670044,41.27603238275469,1739502684.9900475,45.25995683670044,0.9589432434433913,1739502684.9900508,45.25995683670044,71.73657152080781,1739502684.9900534,45.25995683670044,37.80253201970867,1739502684.9900548,45.25995683670044,-0.07076047407671233,1739502684.9900568,45.25995683670044,-2.8534000062349043,1739502684.9900582,45.25995683670044,-1.219059308234119,1739502684.9900596,45.25995683670044,-0.6108,1739502684.9900608,45.25995683670044,0.9427475753731753,1739502684.9900622,45.25995683670044,0.0,1739502684.9900637,45.25995683670044,0.049125758194428215,1739502684.990065,45.25995683670044,3.772968101964167,1739502684.990067,45.25995683670044,0.8936218171787471 +1739502685.0217886,45.269956827163696,41.27603238275469,1739502685.0217977,45.269956827163696,0.9589432434433913,1739502685.0218086,45.269956827163696,71.73657152080781,1739502685.021819,45.269956827163696,37.80253201970867,1739502685.0218244,45.269956827163696,-0.07076047407671233,1739502685.0218303,45.269956827163696,-2.8534000062349043,1739502685.0218353,45.269956827163696,-1.219059308234119,1739502685.02184,45.269956827163696,-0.6108,1739502685.0218446,45.269956827163696,0.9427475753731753,1739502685.0218503,45.269956827163696,0.0,1739502685.021855,45.269956827163696,0.049125758194428215,1739502685.0218604,45.269956827163696,3.772968101964167,1739502685.0218651,45.269956827163696,0.8936218171787471 +1739502685.0356405,45.28995680809021,41.1957521013195,1739502685.035649,45.28995680809021,0.9017742376943927,1739502685.0356596,45.28995680809021,71.8909113258176,1739502685.0356698,45.28995680809021,37.63772439291592,1739502685.0356748,45.28995680809021,-0.0794502721885475,1739502685.0356805,45.28995680809021,-2.872503614164953,1739502685.0356855,45.28995680809021,-1.2123180808361742,1739502685.0356903,45.28995680809021,-0.6108,1739502685.0356948,45.28995680809021,0.9478455302340844,1739502685.035701,45.28995680809021,0.0,1739502685.0357058,45.28995680809021,0.048760187172411006,1739502685.0357115,45.28995680809021,3.745360648513965,1739502685.0357163,45.28995680809021,0.8989711020423907 +1739502685.0583696,45.31995677947998,41.1957521013195,1739502685.0583777,45.31995677947998,0.9017742376943927,1739502685.058388,45.31995677947998,71.8909113258176,1739502685.0583973,45.31995677947998,37.63772439291592,1739502685.058402,45.31995677947998,-0.0794502721885475,1739502685.058408,45.31995677947998,-2.872503614164953,1739502685.058413,45.31995677947998,-1.2123180808361742,1739502685.058418,45.31995677947998,-0.6108,1739502685.0584226,45.31995677947998,0.9478455302340844,1739502685.058428,45.31995677947998,0.0,1739502685.058433,45.31995677947998,0.04887442819169363,1739502685.058438,45.31995677947998,3.745360648513965,1739502685.0584433,45.31995677947998,0.8989711020423907 +1739502685.076583,45.32995676994324,41.1957521013195,1739502685.0765874,45.32995676994324,0.9017742376943927,1739502685.0765934,45.32995676994324,71.8909113258176,1739502685.0765991,45.32995676994324,37.63772439291592,1739502685.0766017,45.32995676994324,-0.0794502721885475,1739502685.076605,45.32995676994324,-2.872503614164953,1739502685.076608,45.32995676994324,-1.2123180808361742,1739502685.0766106,45.32995676994324,-0.6108,1739502685.0766132,45.32995676994324,0.9478455302340844,1739502685.0766163,45.32995676994324,0.0,1739502685.0766187,45.32995676994324,0.04887442819169363,1739502685.0766215,45.32995676994324,3.745360648513965,1739502685.0766244,45.32995676994324,0.8989711020423907 +1739502685.0949433,45.35995674133301,41.1957521013195,1739502685.0949473,45.35995674133301,0.9017742376943927,1739502685.0949528,45.35995674133301,71.8909113258176,1739502685.094957,45.35995674133301,37.63772439291592,1739502685.0949593,45.35995674133301,-0.0794502721885475,1739502685.0949621,45.35995674133301,-2.872503614164953,1739502685.0949645,45.35995674133301,-1.2123180808361742,1739502685.0949664,45.35995674133301,-0.6108,1739502685.0949686,45.35995674133301,0.9478455302340844,1739502685.0949712,45.35995674133301,0.0,1739502685.094973,45.35995674133301,0.04887442819169363,1739502685.0949752,45.35995674133301,3.745360648513965,1739502685.0949779,45.35995674133301,0.8989711020423907 +1739502685.117623,45.37995672225952,41.1957521013195,1739502685.1176274,45.37995672225952,0.9017742376943927,1739502685.117633,45.37995672225952,71.8909113258176,1739502685.1176398,45.37995672225952,37.63772439291592,1739502685.117643,45.37995672225952,-0.0794502721885475,1739502685.1176474,45.37995672225952,-2.872503614164953,1739502685.1176515,45.37995672225952,-1.2123180808361742,1739502685.1176553,45.37995672225952,-0.6108,1739502685.1176593,45.37995672225952,0.9478455302340844,1739502685.1176634,45.37995672225952,0.0,1739502685.1176677,45.37995672225952,0.04887442819169363,1739502685.1176717,45.37995672225952,3.745360648513965,1739502685.1176758,45.37995672225952,0.8989711020423907 +1739502685.1356418,45.399956703186035,41.1134295898405,1739502685.1356452,45.399956703186035,0.8465108781155077,1739502685.1356494,45.399956703186035,71.98504633621285,1739502685.1356547,45.399956703186035,37.53300008999269,1739502685.1356575,45.399956703186035,-0.08439758710869782,1739502685.1356611,45.399956703186035,-2.887225433431552,1739502685.1356645,45.399956703186035,-1.170024702282587,1739502685.1356676,45.399956703186035,-0.6108,1739502685.135671,45.399956703186035,0.9804643137770747,1739502685.135674,45.399956703186035,0.0,1739502685.1356773,45.399956703186035,0.08853315003840992,1739502685.1356807,45.399956703186035,3.717753195063763,1739502685.135684,45.399956703186035,0.9043245224414828 +1739502685.1558871,45.41995668411255,41.1134295898405,1739502685.1558902,45.41995668411255,0.8465108781155077,1739502685.1558945,45.41995668411255,71.98504633621285,1739502685.155899,45.41995668411255,37.53300008999269,1739502685.1559017,45.41995668411255,-0.08439758710869782,1739502685.1559052,45.41995668411255,-2.887225433431552,1739502685.1559083,45.41995668411255,-1.170024702282587,1739502685.1559114,45.41995668411255,-0.6108,1739502685.1559145,45.41995668411255,0.9804643137770747,1739502685.1559176,45.41995668411255,0.0,1739502685.1559207,45.41995668411255,0.0761397913355919,1739502685.1559236,45.41995668411255,3.717753195063763,1739502685.155927,45.41995668411255,0.9043245224414828 +1739502685.1755223,45.43995666503906,41.1134295898405,1739502685.1755257,45.43995666503906,0.8465108781155077,1739502685.1755297,45.43995666503906,71.98504633621285,1739502685.1755345,45.43995666503906,37.53300008999269,1739502685.175537,45.43995666503906,-0.08439758710869782,1739502685.1755404,45.43995666503906,-2.887225433431552,1739502685.1755438,45.43995666503906,-1.170024702282587,1739502685.1755471,45.43995666503906,-0.6108,1739502685.17555,45.43995666503906,0.9804643137770747,1739502685.1755533,45.43995666503906,0.0,1739502685.1755564,45.43995666503906,0.0761397913355919,1739502685.1755595,45.43995666503906,3.717753195063763,1739502685.1755629,45.43995666503906,0.9043245224414828 +1739502685.1962085,45.459956645965576,41.1134295898405,1739502685.1962113,45.459956645965576,0.8465108781155077,1739502685.1962156,45.459956645965576,71.98504633621285,1739502685.1962204,45.459956645965576,37.53300008999269,1739502685.196223,45.459956645965576,-0.08439758710869782,1739502685.1962264,45.459956645965576,-2.887225433431552,1739502685.1962295,45.459956645965576,-1.170024702282587,1739502685.1962328,45.459956645965576,-0.6108,1739502685.1962354,45.459956645965576,0.9804643137770747,1739502685.1962385,45.459956645965576,0.0,1739502685.1962416,45.459956645965576,0.0761397913355919,1739502685.196245,45.459956645965576,3.717753195063763,1739502685.196248,45.459956645965576,0.9043245224414828 +1739502685.2210073,45.47995662689209,41.1134295898405,1739502685.221012,45.47995662689209,0.8465108781155077,1739502685.2210186,45.47995662689209,71.98504633621285,1739502685.2210264,45.47995662689209,37.53300008999269,1739502685.2210305,45.47995662689209,-0.08439758710869782,1739502685.221036,45.47995662689209,-2.887225433431552,1739502685.221041,45.47995662689209,-1.170024702282587,1739502685.2210455,45.47995662689209,-0.6108,1739502685.2210503,45.47995662689209,0.9804643137770747,1739502685.2210553,45.47995662689209,0.0,1739502685.22106,45.47995662689209,0.0761397913355919,1739502685.221065,45.47995662689209,3.717753195063763,1739502685.2210698,45.47995662689209,0.9043245224414828 +1739502685.2337987,45.4999566078186,41.02899345633571,1739502685.2338014,45.4999566078186,0.7931504064447878,1739502685.2338047,45.4999566078186,72.05698450387749,1739502685.2338078,45.4999566078186,37.44448431200913,1739502685.2338095,45.4999566078186,-0.08766062751963467,1739502685.2338114,45.4999566078186,-2.9006395697376774,1739502685.2338133,45.4999566078186,-1.117575238488683,1739502685.2338147,45.4999566078186,-0.6108,1739502685.2338161,45.4999566078186,1.022479480827616,1739502685.2338178,45.4999566078186,0.0,1739502685.2338192,45.4999566078186,0.12515253343716856,1739502685.2338207,45.4999566078186,3.690145741613561,1739502685.2338223,45.4999566078186,0.9126434393394649 +1739502685.2539308,45.51995658874512,41.02899345633571,1739502685.253933,45.51995658874512,0.7931504064447878,1739502685.2539363,45.51995658874512,72.05698450387749,1739502685.253939,45.51995658874512,37.44448431200913,1739502685.2539406,45.51995658874512,-0.08766062751963467,1739502685.253942,45.51995658874512,-2.9006395697376774,1739502685.2539432,45.51995658874512,-1.117575238488683,1739502685.2539449,45.51995658874512,-0.6108,1739502685.2539458,45.51995658874512,1.022479480827616,1739502685.2539475,45.51995658874512,0.0,1739502685.253949,45.51995658874512,0.10983604148815118,1739502685.25395,45.51995658874512,3.690145741613561,1739502685.253952,45.51995658874512,0.9126434393394649 +1739502685.273427,45.53995656967163,41.02899345633571,1739502685.2734294,45.53995656967163,0.7931504064447878,1739502685.2734325,45.53995656967163,72.05698450387749,1739502685.2734354,45.53995656967163,37.44448431200913,1739502685.2734368,45.53995656967163,-0.08766062751963467,1739502685.2734385,45.53995656967163,-2.9006395697376774,1739502685.2734396,45.53995656967163,-1.117575238488683,1739502685.273441,45.53995656967163,-0.6108,1739502685.273442,45.53995656967163,1.022479480827616,1739502685.2734437,45.53995656967163,0.0,1739502685.273445,45.53995656967163,0.10983604148815118,1739502685.2734463,45.53995656967163,3.690145741613561,1739502685.2734478,45.53995656967163,0.9126434393394649 +1739502685.2943382,45.559956550598145,41.02899345633571,1739502685.2943408,45.559956550598145,0.7931504064447878,1739502685.2943447,45.559956550598145,72.05698450387749,1739502685.2943478,45.559956550598145,37.44448431200913,1739502685.2943497,45.559956550598145,-0.08766062751963467,1739502685.2943516,45.559956550598145,-2.9006395697376774,1739502685.2943532,45.559956550598145,-1.117575238488683,1739502685.2943547,45.559956550598145,-0.6108,1739502685.294356,45.559956550598145,1.022479480827616,1739502685.2943583,45.559956550598145,0.0,1739502685.29436,45.559956550598145,0.10983604148815118,1739502685.2943616,45.559956550598145,3.690145741613561,1739502685.2943635,45.559956550598145,0.9126434393394649 +1739502685.3140929,45.57995653152466,41.02899345633571,1739502685.3140962,45.57995653152466,0.7931504064447878,1739502685.3141005,45.57995653152466,72.05698450387749,1739502685.314104,45.57995653152466,37.44448431200913,1739502685.3141057,45.57995653152466,-0.08766062751963467,1739502685.3141084,45.57995653152466,-2.9006395697376774,1739502685.3141105,45.57995653152466,-1.117575238488683,1739502685.314112,45.57995653152466,-0.6108,1739502685.3141136,45.57995653152466,1.022479480827616,1739502685.3141158,45.57995653152466,0.0,1739502685.3141177,45.57995653152466,0.10983604148815118,1739502685.3141196,45.57995653152466,3.690145741613561,1739502685.3141215,45.57995653152466,0.9126434393394649 +1739502685.3338299,45.59995651245117,41.02899345633571,1739502685.3338327,45.59995651245117,0.7931504064447878,1739502685.3338363,45.59995651245117,72.05698450387749,1739502685.3338394,45.59995651245117,37.44448431200913,1739502685.3338408,45.59995651245117,-0.08766062751963467,1739502685.333843,45.59995651245117,-2.9006395697376774,1739502685.3338444,45.59995651245117,-1.117575238488683,1739502685.3338463,45.59995651245117,-0.6108,1739502685.3338475,45.59995651245117,1.022479480827616,1739502685.3338497,45.59995651245117,0.0,1739502685.3338513,45.59995651245117,0.10983604148815118,1739502685.3338532,45.59995651245117,3.690145741613561,1739502685.333855,45.59995651245117,0.9126434393394649 +1739502685.3541703,45.619956493377686,40.94213976589536,1739502685.3541737,45.619956493377686,0.7415619299783982,1739502685.354177,45.619956493377686,72.12820452459776,1739502685.3541803,45.619956493377686,37.34865069372325,1739502685.3541822,45.619956493377686,-0.09149397225106999,1739502685.3541842,45.619956493377686,-2.913792891773733,1739502685.354186,45.619956493377686,-1.0659313659605256,1739502685.3541875,45.619956493377686,-0.5937457505197937,1739502685.3541892,45.619956493377686,1.0656081180932644,1739502685.3541908,45.619956493377686,0.0,1739502685.3541927,45.619956493377686,0.15461208444214625,1739502685.3541942,45.619956493377686,3.662538288163359,1739502685.3541963,45.619956493377686,0.9249885562484543 +1739502685.373993,45.6399564743042,40.94213976589536,1739502685.3739963,45.6399564743042,0.7415619299783982,1739502685.3739998,45.6399564743042,72.12820452459776,1739502685.3740032,45.6399564743042,37.34865069372325,1739502685.374005,45.6399564743042,-0.09149397225106999,1739502685.374007,45.6399564743042,-2.913792891773733,1739502685.3740091,45.6399564743042,-1.0659313659605256,1739502685.3740106,45.6399564743042,-0.5937457505197937,1739502685.3740122,45.6399564743042,1.0656081180932644,1739502685.3740141,45.6399564743042,0.0,1739502685.3740158,45.6399564743042,0.14061956184481006,1739502685.3740175,45.6399564743042,3.662538288163359,1739502685.3740191,45.6399564743042,0.9249885562484543 +1739502685.3953946,45.65995645523071,40.94213976589536,1739502685.395398,45.65995645523071,0.7415619299783982,1739502685.3954022,45.65995645523071,72.12820452459776,1739502685.3954062,45.65995645523071,37.34865069372325,1739502685.3954086,45.65995645523071,-0.09149397225106999,1739502685.3954113,45.65995645523071,-2.913792891773733,1739502685.3954132,45.65995645523071,-1.0659313659605256,1739502685.3954153,45.65995645523071,-0.5937457505197937,1739502685.3954175,45.65995645523071,1.0656081180932644,1739502685.3954196,45.65995645523071,0.0,1739502685.3954217,45.65995645523071,0.14061956184481006,1739502685.3954237,45.65995645523071,3.662538288163359,1739502685.3954258,45.65995645523071,0.9249885562484543 +1739502685.4161272,45.67995643615723,40.94213976589536,1739502685.4161305,45.67995643615723,0.7415619299783982,1739502685.416135,45.67995643615723,72.12820452459776,1739502685.4161398,45.67995643615723,37.34865069372325,1739502685.4161415,45.67995643615723,-0.09149397225106999,1739502685.4161444,45.67995643615723,-2.913792891773733,1739502685.4161468,45.67995643615723,-1.0659313659605256,1739502685.4161487,45.67995643615723,-0.5937457505197937,1739502685.4161506,45.67995643615723,1.0656081180932644,1739502685.4161534,45.67995643615723,0.0,1739502685.416155,45.67995643615723,0.14061956184481006,1739502685.4161575,45.67995643615723,3.662538288163359,1739502685.41616,45.67995643615723,0.9249885562484543 +1739502685.4374037,45.69995641708374,40.94213976589536,1739502685.4374077,45.69995641708374,0.7415619299783982,1739502685.4374123,45.69995641708374,72.12820452459776,1739502685.4374168,45.69995641708374,37.34865069372325,1739502685.4374187,45.69995641708374,-0.09149397225106999,1739502685.4374216,45.69995641708374,-2.913792891773733,1739502685.4374237,45.69995641708374,-1.0659313659605256,1739502685.4374254,45.69995641708374,-0.5937457505197937,1739502685.4374278,45.69995641708374,1.0656081180932644,1739502685.4374304,45.69995641708374,0.0,1739502685.4374323,45.69995641708374,0.14061956184481006,1739502685.4374344,45.69995641708374,3.662538288163359,1739502685.4374366,45.69995641708374,0.9249885562484543 +1739502685.455437,45.719956398010254,40.852593124490916,1739502685.4554412,45.719956398010254,0.6916660163772317,1739502685.4554458,45.719956398010254,72.24493224486308,1739502685.4554498,45.719956398010254,37.201261410232426,1739502685.455452,45.719956398010254,-0.09681335631417666,1739502685.4554548,45.719956398010254,-2.928915372382859,1739502685.455457,45.719956398010254,-1.0346975644750083,1739502685.4554594,45.719956398010254,-0.5627837492482726,1739502685.4554613,45.719956398010254,1.0925699575346424,1739502685.4554636,45.719956398010254,0.0,1739502685.4554658,45.719956398010254,0.15746687366030163,1739502685.455468,45.719956398010254,3.634930834713157,1739502685.4554706,45.719956398010254,0.9403678722685461 +1739502685.4765453,45.73995637893677,40.852593124490916,1739502685.476549,45.73995637893677,0.6916660163772317,1739502685.4765532,45.73995637893677,72.24493224486308,1739502685.4765573,45.73995637893677,37.201261410232426,1739502685.4765594,45.73995637893677,-0.09681335631417666,1739502685.476562,45.73995637893677,-2.928915372382859,1739502685.476564,45.73995637893677,-1.0346975644750083,1739502685.476566,45.73995637893677,-0.5627837492482726,1739502685.4765677,45.73995637893677,1.0925699575346424,1739502685.4765704,45.73995637893677,0.0,1739502685.4765725,45.73995637893677,0.15220208526609624,1739502685.4765747,45.73995637893677,3.634930834713157,1739502685.4765768,45.73995637893677,0.9403678722685461 +1739502685.4959102,45.75995635986328,40.852593124490916,1739502685.4959135,45.75995635986328,0.6916660163772317,1739502685.4959178,45.75995635986328,72.24493224486308,1739502685.495922,45.75995635986328,37.201261410232426,1739502685.4959242,45.75995635986328,-0.09681335631417666,1739502685.4959269,45.75995635986328,-2.928915372382859,1739502685.4959288,45.75995635986328,-1.0346975644750083,1739502685.495931,45.75995635986328,-0.5627837492482726,1739502685.4959328,45.75995635986328,1.0925699575346424,1739502685.495935,45.75995635986328,0.0,1739502685.495937,45.75995635986328,0.15220208526609624,1739502685.495939,45.75995635986328,3.634930834713157,1739502685.4959412,45.75995635986328,0.9403678722685461 +1739502685.516365,45.779956340789795,40.852593124490916,1739502685.5163684,45.779956340789795,0.6916660163772317,1739502685.5163727,45.779956340789795,72.24493224486308,1739502685.5163765,45.779956340789795,37.201261410232426,1739502685.5163789,45.779956340789795,-0.09681335631417666,1739502685.5163815,45.779956340789795,-2.928915372382859,1739502685.5163834,45.779956340789795,-1.0346975644750083,1739502685.5163856,45.779956340789795,-0.5627837492482726,1739502685.5163877,45.779956340789795,1.0925699575346424,1739502685.5163898,45.779956340789795,0.0,1739502685.5163922,45.779956340789795,0.15220208526609624,1739502685.5163941,45.779956340789795,3.634930834713157,1739502685.5163965,45.779956340789795,0.9403678722685461 +1739502685.534601,45.79995632171631,40.852593124490916,1739502685.5346038,45.79995632171631,0.6916660163772317,1739502685.5346074,45.79995632171631,72.24493224486308,1739502685.534611,45.79995632171631,37.201261410232426,1739502685.5346127,45.79995632171631,-0.09681335631417666,1739502685.5346148,45.79995632171631,-2.928915372382859,1739502685.534617,45.79995632171631,-1.0346975644750083,1739502685.5346184,45.79995632171631,-0.5627837492482726,1739502685.5346198,45.79995632171631,1.0925699575346424,1739502685.534622,45.79995632171631,0.0,1739502685.5346239,45.79995632171631,0.15220208526609624,1739502685.5346258,45.79995632171631,3.634930834713157,1739502685.5346277,45.79995632171631,0.9403678722685461 +1739502685.5538342,45.81995630264282,40.852593124490916,1739502685.553837,45.81995630264282,0.6916660163772317,1739502685.5538406,45.81995630264282,72.24493224486308,1739502685.5538437,45.81995630264282,37.201261410232426,1739502685.5538452,45.81995630264282,-0.09681335631417666,1739502685.553847,45.81995630264282,-2.928915372382859,1739502685.5538485,45.81995630264282,-1.0346975644750083,1739502685.5538504,45.81995630264282,-0.5627837492482726,1739502685.5538516,45.81995630264282,1.0925699575346424,1739502685.5538535,45.81995630264282,0.0,1739502685.553855,45.81995630264282,0.15220208526609624,1739502685.5538568,45.81995630264282,3.634930834713157,1739502685.5538585,45.81995630264282,0.9403678722685461 +1739502685.5791137,45.839956283569336,40.760131135677895,1739502685.5791218,45.839956283569336,0.6434412442258219,1739502685.5791323,45.839956283569336,72.41685591524478,1739502685.579142,45.839956283569336,36.99583263583284,1739502685.579147,45.839956283569336,-0.10200170779762406,1739502685.5791533,45.839956283569336,-2.9460923161890404,1739502685.5791585,45.839956283569336,-1.0244068967932327,1739502685.579163,45.839956283569336,-0.5287257108995822,1739502685.579168,45.839956283569336,1.1016017030829148,1739502685.5791736,45.839956283569336,0.0,1739502685.5791786,45.839956283569336,0.1409184131690075,1739502685.5791836,45.839956283569336,3.607323381262955,1739502685.579189,45.839956283569336,0.9571571400716431 +1739502685.5986512,45.85995626449585,40.760131135677895,1739502685.5986593,45.85995626449585,0.6434412442258219,1739502685.5986695,45.85995626449585,72.41685591524478,1739502685.5986795,45.85995626449585,36.99583263583284,1739502685.5986843,45.85995626449585,-0.10200170779762406,1739502685.5986907,45.85995626449585,-2.9460923161890404,1739502685.598696,45.85995626449585,-1.0244068967932327,1739502685.5987005,45.85995626449585,-0.5287257108995822,1739502685.598705,45.85995626449585,1.1016017030829148,1739502685.5987108,45.85995626449585,0.0,1739502685.598716,45.85995626449585,0.14444456301127173,1739502685.5987208,45.85995626449585,3.607323381262955,1739502685.5987258,45.85995626449585,0.9571571400716431 +1739502685.6198375,45.87995624542236,40.760131135677895,1739502685.6198459,45.87995624542236,0.6434412442258219,1739502685.6198559,45.87995624542236,72.41685591524478,1739502685.6198657,45.87995624542236,36.99583263583284,1739502685.6198704,45.87995624542236,-0.10200170779762406,1739502685.6198766,45.87995624542236,-2.9460923161890404,1739502685.6198816,45.87995624542236,-1.0244068967932327,1739502685.6198866,45.87995624542236,-0.5287257108995822,1739502685.619891,45.87995624542236,1.1016017030829148,1739502685.6198967,45.87995624542236,0.0,1739502685.6199012,45.87995624542236,0.14444456301127173,1739502685.6199062,45.87995624542236,3.607323381262955,1739502685.6199114,45.87995624542236,0.9571571400716431 +1739502685.6436946,45.89995622634888,40.760131135677895,1739502685.643703,45.89995622634888,0.6434412442258219,1739502685.6437135,45.89995622634888,72.41685591524478,1739502685.6437232,45.89995622634888,36.99583263583284,1739502685.6437285,45.89995622634888,-0.10200170779762406,1739502685.6437345,45.89995622634888,-2.9460923161890404,1739502685.6437395,45.89995622634888,-1.0244068967932327,1739502685.6437445,45.89995622634888,-0.5287257108995822,1739502685.6437492,45.89995622634888,1.1016017030829148,1739502685.6437547,45.89995622634888,0.0,1739502685.64376,45.89995622634888,0.14444456301127173,1739502685.643765,45.89995622634888,3.607323381262955,1739502685.6437702,45.89995622634888,0.9571571400716431 +1739502685.6650963,45.91995620727539,40.760131135677895,1739502685.6651044,45.91995620727539,0.6434412442258219,1739502685.665115,45.91995620727539,72.41685591524478,1739502685.6651251,45.91995620727539,36.99583263583284,1739502685.6651301,45.91995620727539,-0.10200170779762406,1739502685.665136,45.91995620727539,-2.9460923161890404,1739502685.6651413,45.91995620727539,-1.0244068967932327,1739502685.6651459,45.91995620727539,-0.5287257108995822,1739502685.6651506,45.91995620727539,1.1016017030829148,1739502685.6651564,45.91995620727539,0.0,1739502685.6651611,45.91995620727539,0.14444456301127173,1739502685.6651666,45.91995620727539,3.607323381262955,1739502685.6651714,45.91995620727539,0.9571571400716431 +1739502685.6844654,45.939956188201904,40.664761838447504,1739502685.6844742,45.939956188201904,0.5969965800014911,1739502685.684485,45.939956188201904,72.53534980959687,1739502685.6844947,45.939956188201904,36.84568768650836,1739502685.6844995,45.939956188201904,-0.10353379911726159,1739502685.684506,45.939956188201904,-2.9601799636324255,1739502685.6845107,45.939956188201904,-0.986331256223291,1739502685.6845152,45.939956188201904,-0.4978328924128429,1739502685.68452,45.939956188201904,1.1356733408684523,1739502685.6845255,45.939956188201904,0.0,1739502685.6845305,45.939956188201904,0.17097868292611243,1739502685.6845357,45.939956188201904,3.5798462131568063,1739502685.6845407,45.939956188201904,0.9729865758523326 +1739502685.7048218,45.95995616912842,40.664761838447504,1739502685.7048302,45.95995616912842,0.5969965800014911,1739502685.7048407,45.95995616912842,72.53534980959687,1739502685.7048514,45.95995616912842,36.84568768650836,1739502685.7048564,45.95995616912842,-0.10353379911726159,1739502685.7048628,45.95995616912842,-2.9601799636324255,1739502685.704868,45.95995616912842,-0.986331256223291,1739502685.7048728,45.95995616912842,-0.4978328924128429,1739502685.7048779,45.95995616912842,1.1356733408684523,1739502685.704883,45.95995616912842,0.0,1739502685.704888,45.95995616912842,0.16268676501611967,1739502685.7048934,45.95995616912842,3.5798462131568063,1739502685.7048988,45.95995616912842,0.9729865758523326 +1739502685.7363067,45.98995614051819,40.664761838447504,1739502685.7363157,45.98995614051819,0.5969965800014911,1739502685.7363267,45.98995614051819,72.53534980959687,1739502685.7363374,45.98995614051819,36.84568768650836,1739502685.7363422,45.98995614051819,-0.10353379911726159,1739502685.7363486,45.98995614051819,-2.9601799636324255,1739502685.7363536,45.98995614051819,-0.986331256223291,1739502685.7363586,45.98995614051819,-0.4978328924128429,1739502685.7363634,45.98995614051819,1.1356733408684523,1739502685.7363691,45.98995614051819,0.0,1739502685.736374,45.98995614051819,0.16268676501611967,1739502685.7363791,45.98995614051819,3.5798462131568063,1739502685.7363842,45.98995614051819,0.9729865758523326 +1739502685.7574406,46.0099561214447,40.664761838447504,1739502685.757448,46.0099561214447,0.5969965800014911,1739502685.7574568,46.0099561214447,72.53534980959687,1739502685.7574675,46.0099561214447,36.84568768650836,1739502685.7574732,46.0099561214447,-0.10353379911726159,1739502685.7574806,46.0099561214447,-2.9601799636324255,1739502685.7574875,46.0099561214447,-0.986331256223291,1739502685.7574942,46.0099561214447,-0.4978328924128429,1739502685.757501,46.0099561214447,1.1356733408684523,1739502685.757508,46.0099561214447,0.0,1739502685.7575147,46.0099561214447,0.16268676501611967,1739502685.7575216,46.0099561214447,3.5798462131568063,1739502685.7575285,46.0099561214447,0.9729865758523326 +1739502685.779313,46.029956102371216,40.664761838447504,1739502685.7793179,46.029956102371216,0.5969965800014911,1739502685.779324,46.029956102371216,72.53534980959687,1739502685.779331,46.029956102371216,36.84568768650836,1739502685.7793353,46.029956102371216,-0.10353379911726159,1739502685.7793403,46.029956102371216,-2.9601799636324255,1739502685.7793448,46.029956102371216,-0.986331256223291,1739502685.7793496,46.029956102371216,-0.4978328924128429,1739502685.7793543,46.029956102371216,1.1356733408684523,1739502685.7793589,46.029956102371216,0.0,1739502685.7793636,46.029956102371216,0.16268676501611967,1739502685.7793684,46.029956102371216,3.5798462131568063,1739502685.7793734,46.029956102371216,0.9729865758523326 +1739502685.7962472,46.059956073760986,40.5664719893891,1739502685.7962508,46.059956073760986,0.5524001289047122,1739502685.7962558,46.059956073760986,72.65491607552364,1739502685.7962599,46.059956073760986,36.69012746795165,1739502685.7962615,46.059956073760986,-0.104,1739502685.7962642,46.059956073760986,-2.973849056872343,1739502685.7962663,46.059956073760986,-0.9491475364714002,1739502685.7962682,46.059956073760986,-0.46777033921313693,1739502685.79627,46.059956073760986,1.169963676612076,1739502685.796272,46.059956073760986,0.0,1739502685.7962742,46.059956073760986,0.18638447414644438,1739502685.7962759,46.059956073760986,3.553164642202006,1739502685.7962778,46.059956073760986,0.9909847414243078 +1739502685.815663,46.0799560546875,40.5664719893891,1739502685.8156667,46.0799560546875,0.5524001289047122,1739502685.8156705,46.0799560546875,72.65491607552364,1739502685.8156745,46.0799560546875,36.69012746795165,1739502685.8156765,46.0799560546875,-0.104,1739502685.8156788,46.0799560546875,-2.973849056872343,1739502685.8156807,46.0799560546875,-0.9491475364714002,1739502685.815683,46.0799560546875,-0.46777033921313693,1739502685.8156846,46.0799560546875,1.169963676612076,1739502685.815687,46.0799560546875,0.0,1739502685.8156886,46.0799560546875,0.1789789351877682,1739502685.8156905,46.0799560546875,3.553164642202006,1739502685.8156927,46.0799560546875,0.9909847414243078 +1739502685.8370776,46.099956035614014,40.5664719893891,1739502685.8370814,46.099956035614014,0.5524001289047122,1739502685.8370857,46.099956035614014,72.65491607552364,1739502685.8370895,46.099956035614014,36.69012746795165,1739502685.8370917,46.099956035614014,-0.104,1739502685.8370938,46.099956035614014,-2.973849056872343,1739502685.837096,46.099956035614014,-0.9491475364714002,1739502685.8370976,46.099956035614014,-0.46777033921313693,1739502685.8370996,46.099956035614014,1.169963676612076,1739502685.8371015,46.099956035614014,0.0,1739502685.8371034,46.099956035614014,0.1789789351877682,1739502685.8371058,46.099956035614014,3.553164642202006,1739502685.8371077,46.099956035614014,0.9909847414243078 +1739502685.8564682,46.11995601654053,40.5664719893891,1739502685.8564742,46.11995601654053,0.5524001289047122,1739502685.8564808,46.11995601654053,72.65491607552364,1739502685.856488,46.11995601654053,36.69012746795165,1739502685.856492,46.11995601654053,-0.104,1739502685.8564975,46.11995601654053,-2.973849056872343,1739502685.856502,46.11995601654053,-0.9491475364714002,1739502685.8565066,46.11995601654053,-0.46777033921313693,1739502685.856511,46.11995601654053,1.169963676612076,1739502685.8565161,46.11995601654053,0.0,1739502685.8565211,46.11995601654053,0.1789789351877682,1739502685.8565261,46.11995601654053,3.553164642202006,1739502685.8565307,46.11995601654053,0.9909847414243078 +1739502685.8755019,46.13995599746704,40.5664719893891,1739502685.8755057,46.13995599746704,0.5524001289047122,1739502685.875511,46.13995599746704,72.65491607552364,1739502685.875515,46.13995599746704,36.69012746795165,1739502685.8755167,46.13995599746704,-0.104,1739502685.8755195,46.13995599746704,-2.973849056872343,1739502685.8755212,46.13995599746704,-0.9491475364714002,1739502685.8755233,46.13995599746704,-0.46777033921313693,1739502685.8755255,46.13995599746704,1.169963676612076,1739502685.8755274,46.13995599746704,0.0,1739502685.8755295,46.13995599746704,0.1789789351877682,1739502685.8755322,46.13995599746704,3.553164642202006,1739502685.875534,46.13995599746704,0.9909847414243078 +1739502685.8957372,46.159955978393555,40.465171754817135,1739502685.895741,46.159955978393555,0.5095692026831458,1739502685.8957458,46.159955978393555,72.7181664331077,1739502685.8957496,46.159955978393555,36.58769316034076,1739502685.8957517,46.159955978393555,-0.104,1739502685.8957543,46.159955978393555,-2.9846546870138075,1739502685.8957562,46.159955978393555,-0.8934043780786645,1739502685.8957584,46.159955978393555,-0.44198906967024787,1739502685.89576,46.159955978393555,1.2233184772792645,1739502685.8957622,46.159955978393555,0.0,1739502685.895764,46.159955978393555,0.22808851441088876,1739502685.8957663,46.159955978393555,3.528119265893799,1739502685.8957684,46.159955978393555,1.0105767164377166 +1739502685.9157147,46.17995595932007,40.465171754817135,1739502685.9157186,46.17995595932007,0.5095692026831458,1739502685.915723,46.17995595932007,72.7181664331077,1739502685.9157271,46.17995595932007,36.58769316034076,1739502685.9157288,46.17995595932007,-0.104,1739502685.9157312,46.17995595932007,-2.9846546870138075,1739502685.9157336,46.17995595932007,-0.8934043780786645,1739502685.9157352,46.17995595932007,-0.44198906967024787,1739502685.9157372,46.17995595932007,1.2233184772792645,1739502685.915739,46.17995595932007,0.0,1739502685.915741,46.17995595932007,0.21274176084154783,1739502685.9157429,46.17995595932007,3.528119265893799,1739502685.915745,46.17995595932007,1.0105767164377166 +1739502685.934761,46.19995594024658,40.465171754817135,1739502685.9347637,46.19995594024658,0.5095692026831458,1739502685.9347665,46.19995594024658,72.7181664331077,1739502685.9347694,46.19995594024658,36.58769316034076,1739502685.934771,46.19995594024658,-0.104,1739502685.934773,46.19995594024658,-2.9846546870138075,1739502685.9347746,46.19995594024658,-0.8934043780786645,1739502685.9347758,46.19995594024658,-0.44198906967024787,1739502685.9347773,46.19995594024658,1.2233184772792645,1739502685.934779,46.19995594024658,0.0,1739502685.9347804,46.19995594024658,0.21274176084154783,1739502685.9347818,46.19995594024658,3.528119265893799,1739502685.9347832,46.19995594024658,1.0105767164377166 +1739502685.9550524,46.219955921173096,40.465171754817135,1739502685.955055,46.219955921173096,0.5095692026831458,1739502685.9550583,46.219955921173096,72.7181664331077,1739502685.955061,46.219955921173096,36.58769316034076,1739502685.9550629,46.219955921173096,-0.104,1739502685.9550643,46.219955921173096,-2.9846546870138075,1739502685.9550662,46.219955921173096,-0.8934043780786645,1739502685.9550674,46.219955921173096,-0.44198906967024787,1739502685.9550688,46.219955921173096,1.2233184772792645,1739502685.9550707,46.219955921173096,0.0,1739502685.955072,46.219955921173096,0.21274176084154783,1739502685.9550736,46.219955921173096,3.528119265893799,1739502685.955075,46.219955921173096,1.0105767164377166 +1739502685.97483,46.23995590209961,40.465171754817135,1739502685.974833,46.23995590209961,0.5095692026831458,1739502685.9748359,46.23995590209961,72.7181664331077,1739502685.9748387,46.23995590209961,36.58769316034076,1739502685.9748406,46.23995590209961,-0.104,1739502685.9748425,46.23995590209961,-2.9846546870138075,1739502685.9748442,46.23995590209961,-0.8934043780786645,1739502685.9748454,46.23995590209961,-0.44198906967024787,1739502685.974847,46.23995590209961,1.2233184772792645,1739502685.9748487,46.23995590209961,0.0,1739502685.97485,46.23995590209961,0.21274176084154783,1739502685.9748516,46.23995590209961,3.528119265893799,1739502685.974853,46.23995590209961,1.0105767164377166 +1739502685.9948523,46.25995588302612,40.465171754817135,1739502685.9948547,46.25995588302612,0.5095692026831458,1739502685.9948575,46.25995588302612,72.7181664331077,1739502685.9948602,46.25995588302612,36.58769316034076,1739502685.9948618,46.25995588302612,-0.104,1739502685.9948635,46.25995588302612,-2.9846546870138075,1739502685.9948652,46.25995588302612,-0.8934043780786645,1739502685.9948664,46.25995588302612,-0.44198906967024787,1739502685.994868,46.25995588302612,1.2233184772792645,1739502685.9948695,46.25995588302612,0.0,1739502685.9948711,46.25995588302612,0.21274176084154783,1739502685.9948726,46.25995588302612,3.528119265893799,1739502685.994874,46.25995588302612,1.0105767164377166 +1739502686.0147362,46.27995586395264,40.36065005336615,1739502686.0147383,46.27995586395264,0.4683450314782247,1739502686.0147417,46.27995586395264,72.84000170974477,1739502686.0147443,46.27995586395264,36.418609229683454,1739502686.014746,46.27995586395264,-0.104,1739502686.0147476,46.27995586395264,-2.9974101185160857,1739502686.0147493,46.27995586395264,-0.8648032034598291,1739502686.0147505,46.27995586395264,-0.4158931114116524,1739502686.0147517,46.27995586395264,1.2516318364700962,1739502686.0147533,46.27995586395264,0.0,1739502686.0147545,46.27995586395264,0.21956217331887062,1739502686.0147562,46.27995586395264,3.5046211102439786,1739502686.0147576,46.27995586395264,1.0342010434478308 +1739502686.035714,46.29995584487915,40.36065005336615,1739502686.0357168,46.29995584487915,0.4683450314782247,1739502686.035721,46.29995584487915,72.84000170974477,1739502686.0357249,46.29995584487915,36.418609229683454,1739502686.0357265,46.29995584487915,-0.104,1739502686.0357292,46.29995584487915,-2.9974101185160857,1739502686.0357308,46.29995584487915,-0.8648032034598291,1739502686.0357327,46.29995584487915,-0.4158931114116524,1739502686.0357342,46.29995584487915,1.2516318364700962,1739502686.0357366,46.29995584487915,0.0,1739502686.0357385,46.29995584487915,0.21743079302226542,1739502686.0357404,46.29995584487915,3.5046211102439786,1739502686.0357423,46.29995584487915,1.0342010434478308 +1739502686.058405,46.319955825805664,40.36065005336615,1739502686.0584087,46.319955825805664,0.4683450314782247,1739502686.0584135,46.319955825805664,72.84000170974477,1739502686.058418,46.319955825805664,36.418609229683454,1739502686.0584202,46.319955825805664,-0.104,1739502686.058423,46.319955825805664,-2.9974101185160857,1739502686.0584252,46.319955825805664,-0.8648032034598291,1739502686.0584273,46.319955825805664,-0.4158931114116524,1739502686.0584292,46.319955825805664,1.2516318364700962,1739502686.058432,46.319955825805664,0.0,1739502686.0584342,46.319955825805664,0.21743079302226542,1739502686.0584366,46.319955825805664,3.5046211102439786,1739502686.058439,46.319955825805664,1.0342010434478308 +1739502686.0774333,46.33995580673218,40.36065005336615,1739502686.0774372,46.33995580673218,0.4683450314782247,1739502686.077442,46.33995580673218,72.84000170974477,1739502686.0774467,46.33995580673218,36.418609229683454,1739502686.0774486,46.33995580673218,-0.104,1739502686.0774515,46.33995580673218,-2.9974101185160857,1739502686.0774536,46.33995580673218,-0.8648032034598291,1739502686.0774555,46.33995580673218,-0.4158931114116524,1739502686.0774577,46.33995580673218,1.2516318364700962,1739502686.07746,46.33995580673218,0.0,1739502686.077462,46.33995580673218,0.21743079302226542,1739502686.0774648,46.33995580673218,3.5046211102439786,1739502686.0774672,46.33995580673218,1.0342010434478308 +1739502686.0955021,46.35995578765869,40.36065005336615,1739502686.0955052,46.35995578765869,0.4683450314782247,1739502686.095509,46.35995578765869,72.84000170974477,1739502686.0955126,46.35995578765869,36.418609229683454,1739502686.0955145,46.35995578765869,-0.104,1739502686.0955167,46.35995578765869,-2.9974101185160857,1739502686.0955188,46.35995578765869,-0.8648032034598291,1739502686.0955203,46.35995578765869,-0.4158931114116524,1739502686.0955222,46.35995578765869,1.2516318364700962,1739502686.095524,46.35995578765869,0.0,1739502686.095526,46.35995578765869,0.21743079302226542,1739502686.095528,46.35995578765869,3.5046211102439786,1739502686.0955298,46.35995578765869,1.0342010434478308 +1739502686.1153395,46.379955768585205,40.25278184086044,1739502686.1153426,46.379955768585205,0.4286204070358064,1739502686.1153464,46.379955768585205,72.90094231808335,1739502686.1153502,46.379955768585205,36.31004433387853,1739502686.1153522,46.379955768585205,-0.104,1739502686.1153543,46.379955768585205,-3.0073165346179853,1739502686.1153564,46.379955768585205,-0.8166357066455258,1739502686.115358,46.379955768585205,-0.3939431110345323,1739502686.11536,46.379955768585205,1.3008035209403852,1739502686.115362,46.379955768585205,0.0,1739502686.1153638,46.379955768585205,0.25431740872387165,1739502686.115366,46.379955768585205,3.482597729519573,1739502686.1153677,46.379955768585205,1.0580131871810048 +1739502686.1361458,46.39995574951172,40.25278184086044,1739502686.136149,46.39995574951172,0.4286204070358064,1739502686.1361535,46.39995574951172,72.90094231808335,1739502686.1361573,46.39995574951172,36.31004433387853,1739502686.136159,46.39995574951172,-0.104,1739502686.1361616,46.39995574951172,-3.0073165346179853,1739502686.1361632,46.39995574951172,-0.8166357066455258,1739502686.1361651,46.39995574951172,-0.3939431110345323,1739502686.1361668,46.39995574951172,1.3008035209403852,1739502686.136169,46.39995574951172,0.0,1739502686.1361709,46.39995574951172,0.24279033375938042,1739502686.1361728,46.39995574951172,3.482597729519573,1739502686.1361747,46.39995574951172,1.0580131871810048 +1739502686.1555927,46.41995573043823,40.25278184086044,1739502686.155596,46.41995573043823,0.4286204070358064,1739502686.1556,46.41995573043823,72.90094231808335,1739502686.1556036,46.41995573043823,36.31004433387853,1739502686.1556056,46.41995573043823,-0.104,1739502686.1556077,46.41995573043823,-3.0073165346179853,1739502686.1556096,46.41995573043823,-0.8166357066455258,1739502686.1556113,46.41995573043823,-0.3939431110345323,1739502686.155613,46.41995573043823,1.3008035209403852,1739502686.1556153,46.41995573043823,0.0,1739502686.1556168,46.41995573043823,0.24279033375938042,1739502686.155619,46.41995573043823,3.482597729519573,1739502686.1556206,46.41995573043823,1.0580131871810048 +1739502686.1753814,46.439955711364746,40.25278184086044,1739502686.1753843,46.439955711364746,0.4286204070358064,1739502686.1753883,46.439955711364746,72.90094231808335,1739502686.1753917,46.439955711364746,36.31004433387853,1739502686.1753938,46.439955711364746,-0.104,1739502686.1753957,46.439955711364746,-3.0073165346179853,1739502686.1753976,46.439955711364746,-0.8166357066455258,1739502686.1753995,46.439955711364746,-0.3939431110345323,1739502686.1754012,46.439955711364746,1.3008035209403852,1739502686.1754034,46.439955711364746,0.0,1739502686.175405,46.439955711364746,0.24279033375938042,1739502686.175407,46.439955711364746,3.482597729519573,1739502686.1754086,46.439955711364746,1.0580131871810048 +1739502686.1961584,46.45995569229126,40.25278184086044,1739502686.1961615,46.45995569229126,0.4286204070358064,1739502686.1961653,46.45995569229126,72.90094231808335,1739502686.1961691,46.45995569229126,36.31004433387853,1739502686.196171,46.45995569229126,-0.104,1739502686.196173,46.45995569229126,-3.0073165346179853,1739502686.1961749,46.45995569229126,-0.8166357066455258,1739502686.1961765,46.45995569229126,-0.3939431110345323,1739502686.1961782,46.45995569229126,1.3008035209403852,1739502686.1961806,46.45995569229126,0.0,1739502686.196182,46.45995569229126,0.24279033375938042,1739502686.196184,46.45995569229126,3.482597729519573,1739502686.1961858,46.45995569229126,1.0580131871810048 +1739502686.2156146,46.47995567321777,40.25278184086044,1739502686.2156174,46.47995567321777,0.4286204070358064,1739502686.215622,46.47995567321777,72.90094231808335,1739502686.2156258,46.47995567321777,36.31004433387853,1739502686.2156277,46.47995567321777,-0.104,1739502686.2156298,46.47995567321777,-3.0073165346179853,1739502686.215632,46.47995567321777,-0.8166357066455258,1739502686.2156336,46.47995567321777,-0.3939431110345323,1739502686.2156355,46.47995567321777,1.3008035209403852,1739502686.2156377,46.47995567321777,0.0,1739502686.2156396,46.47995567321777,0.24279033375938042,1739502686.2156413,46.47995567321777,3.482597729519573,1739502686.2156434,46.47995567321777,1.0580131871810048 +1739502686.2363677,46.49995565414429,40.14145726768009,1739502686.236371,46.49995565414429,0.3903050871907414,1739502686.236375,46.49995565414429,72.9024314742409,1739502686.2363787,46.49995565414429,36.254873434200825,1739502686.2363803,46.49995565414429,-0.104,1739502686.2363825,46.49995565414429,-3.01508940780851,1739502686.2363846,46.49995565414429,-0.7548729563828508,1739502686.2363863,46.49995565414429,-0.3757089048285064,1739502686.2363882,46.49995565414429,1.3666908319054611,1739502686.23639,46.49995565414429,0.0,1739502686.2363918,46.49995565414429,0.2995851713473865,1739502686.2363937,46.49995565414429,3.4619816491805318,1739502686.2363958,46.49995565414429,1.0848540589410833 +1739502686.2552469,46.5199556350708,40.14145726768009,1739502686.25525,46.5199556350708,0.3903050871907414,1739502686.2552538,46.5199556350708,72.9024314742409,1739502686.2552574,46.5199556350708,36.254873434200825,1739502686.255259,46.5199556350708,-0.104,1739502686.2552617,46.5199556350708,-3.01508940780851,1739502686.2552636,46.5199556350708,-0.7548729563828508,1739502686.2552652,46.5199556350708,-0.3757089048285064,1739502686.2552671,46.5199556350708,1.3666908319054611,1739502686.2552693,46.5199556350708,0.0,1739502686.2552712,46.5199556350708,0.2818367729643778,1739502686.255273,46.5199556350708,3.4619816491805318,1739502686.255275,46.5199556350708,1.0848540589410833 +1739502686.2753386,46.539955615997314,40.14145726768009,1739502686.275342,46.539955615997314,0.3903050871907414,1739502686.2753456,46.539955615997314,72.9024314742409,1739502686.2753496,46.539955615997314,36.254873434200825,1739502686.2753513,46.539955615997314,-0.104,1739502686.2753537,46.539955615997314,-3.01508940780851,1739502686.2753553,46.539955615997314,-0.7548729563828508,1739502686.2753572,46.539955615997314,-0.3757089048285064,1739502686.2753587,46.539955615997314,1.3666908319054611,1739502686.2753608,46.539955615997314,0.0,1739502686.2753625,46.539955615997314,0.2818367729643778,1739502686.2753644,46.539955615997314,3.4619816491805318,1739502686.2753663,46.539955615997314,1.0848540589410833 +1739502686.2962534,46.55995559692383,40.14145726768009,1739502686.2962568,46.55995559692383,0.3903050871907414,1739502686.2962608,46.55995559692383,72.9024314742409,1739502686.2962646,46.55995559692383,36.254873434200825,1739502686.2962666,46.55995559692383,-0.104,1739502686.2962687,46.55995559692383,-3.01508940780851,1739502686.2962708,46.55995559692383,-0.7548729563828508,1739502686.2962728,46.55995559692383,-0.3757089048285064,1739502686.2962742,46.55995559692383,1.3666908319054611,1739502686.2962763,46.55995559692383,0.0,1739502686.296278,46.55995559692383,0.2818367729643778,1739502686.29628,46.55995559692383,3.4619816491805318,1739502686.2962816,46.55995559692383,1.0848540589410833 +1739502686.3156621,46.57995557785034,40.14145726768009,1739502686.3156657,46.57995557785034,0.3903050871907414,1739502686.3156698,46.57995557785034,72.9024314742409,1739502686.3156734,46.57995557785034,36.254873434200825,1739502686.3156757,46.57995557785034,-0.104,1739502686.315678,46.57995557785034,-3.01508940780851,1739502686.3156798,46.57995557785034,-0.7548729563828508,1739502686.3156817,46.57995557785034,-0.3757089048285064,1739502686.3156836,46.57995557785034,1.3666908319054611,1739502686.3156857,46.57995557785034,0.0,1739502686.3156874,46.57995557785034,0.2818367729643778,1739502686.3156896,46.57995557785034,3.4619816491805318,1739502686.3156915,46.57995557785034,1.0848540589410833 +1739502686.3359754,46.599955558776855,40.026403470505485,1739502686.335979,46.599955558776855,0.35326837923400145,1739502686.3359833,46.599955558776855,73.2279836176653,1739502686.335987,46.599955558776855,35.86764788725258,1739502686.335989,46.599955558776855,-0.10389949405099594,1739502686.3359914,46.599955558776855,-3.0321032712165437,1739502686.3359933,46.599955558776855,-0.7963727393361062,1739502686.3359952,46.599955558776855,-0.34784180284972466,1739502686.3359969,46.599955558776855,1.322061869693683,1739502686.3359993,46.599955558776855,0.0,1739502686.336001,46.599955558776855,0.17206814692068206,1739502686.336003,46.599955558776855,3.44259700300547,1739502686.336005,46.599955558776855,1.1156910046437314 +1739502686.3556428,46.61995553970337,40.026403470505485,1739502686.3556466,46.61995553970337,0.35326837923400145,1739502686.355651,46.61995553970337,73.2279836176653,1739502686.3556547,46.61995553970337,35.86764788725258,1739502686.3556566,46.61995553970337,-0.10389949405099594,1739502686.355659,46.61995553970337,-3.0321032712165437,1739502686.3556612,46.61995553970337,-0.7963727393361062,1739502686.3556628,46.61995553970337,-0.34784180284972466,1739502686.3556647,46.61995553970337,1.322061869693683,1739502686.3556669,46.61995553970337,0.0,1739502686.3556688,46.61995553970337,0.2063708650499516,1739502686.3556707,46.61995553970337,3.44259700300547,1739502686.3556726,46.61995553970337,1.1156910046437314 +1739502686.375958,46.63995552062988,40.026403470505485,1739502686.3759615,46.63995552062988,0.35326837923400145,1739502686.3759656,46.63995552062988,73.2279836176653,1739502686.3759696,46.63995552062988,35.86764788725258,1739502686.3759716,46.63995552062988,-0.10389949405099594,1739502686.375974,46.63995552062988,-3.0321032712165437,1739502686.3759758,46.63995552062988,-0.7963727393361062,1739502686.3759778,46.63995552062988,-0.34784180284972466,1739502686.3759792,46.63995552062988,1.322061869693683,1739502686.3759818,46.63995552062988,0.0,1739502686.3759837,46.63995552062988,0.2063708650499516,1739502686.3759856,46.63995552062988,3.44259700300547,1739502686.3759878,46.63995552062988,1.1156910046437314 +1739502686.3962421,46.6599555015564,40.026403470505485,1739502686.3962457,46.6599555015564,0.35326837923400145,1739502686.3962495,46.6599555015564,73.2279836176653,1739502686.3962536,46.6599555015564,35.86764788725258,1739502686.3962557,46.6599555015564,-0.10389949405099594,1739502686.396258,46.6599555015564,-3.0321032712165437,1739502686.39626,46.6599555015564,-0.7963727393361062,1739502686.396262,46.6599555015564,-0.34784180284972466,1739502686.3962634,46.6599555015564,1.322061869693683,1739502686.3962657,46.6599555015564,0.0,1739502686.3962674,46.6599555015564,0.2063708650499516,1739502686.3962693,46.6599555015564,3.44259700300547,1739502686.396271,46.6599555015564,1.1156910046437314 +1739502686.4161959,46.67995548248291,40.026403470505485,1739502686.4161992,46.67995548248291,0.35326837923400145,1739502686.4162033,46.67995548248291,73.2279836176653,1739502686.4162073,46.67995548248291,35.86764788725258,1739502686.4162095,46.67995548248291,-0.10389949405099594,1739502686.4162116,46.67995548248291,-3.0321032712165437,1739502686.4162138,46.67995548248291,-0.7963727393361062,1739502686.4162157,46.67995548248291,-0.34784180284972466,1739502686.4162173,46.67995548248291,1.322061869693683,1739502686.4162197,46.67995548248291,0.0,1739502686.4162214,46.67995548248291,0.2063708650499516,1739502686.4162235,46.67995548248291,3.44259700300547,1739502686.4162254,46.67995548248291,1.1156910046437314 +1739502686.4366333,46.699955463409424,40.026403470505485,1739502686.4366372,46.699955463409424,0.35326837923400145,1739502686.4366412,46.699955463409424,73.2279836176653,1739502686.4366453,46.699955463409424,35.86764788725258,1739502686.4366472,46.699955463409424,-0.10389949405099594,1739502686.4366498,46.699955463409424,-3.0321032712165437,1739502686.4366515,46.699955463409424,-0.7963727393361062,1739502686.4366534,46.699955463409424,-0.34784180284972466,1739502686.436655,46.699955463409424,1.322061869693683,1739502686.4366572,46.699955463409424,0.0,1739502686.4366589,46.699955463409424,0.2063708650499516,1739502686.4366608,46.699955463409424,3.44259700300547,1739502686.4366627,46.699955463409424,1.1156910046437314 +1739502686.45578,46.71995544433594,39.907871013459676,1739502686.4557831,46.71995544433594,0.3175684113886854,1739502686.4557865,46.71995544433594,73.23644935925154,1739502686.4557898,46.71995544433594,35.81530983214945,1739502686.4557915,46.71995544433594,-0.10339135759368402,1739502686.4557934,46.71995544433594,-3.0390933868190233,1739502686.4557953,46.71995544433594,-0.7373073992566095,1739502686.4557967,46.71995544433594,-0.3331640532619114,1739502686.4557984,46.71995544433594,1.3860317559815925,1739502686.4558003,46.71995544433594,0.0,1739502686.455802,46.71995544433594,0.26750905958709287,1739502686.4558036,46.71995544433594,3.4242777437042498,1739502686.4558053,46.71995544433594,1.1376283947140282 +1739502686.474754,46.73995542526245,39.907871013459676,1739502686.4747574,46.73995542526245,0.3175684113886854,1739502686.474761,46.73995542526245,73.23644935925154,1739502686.4747639,46.73995542526245,35.81530983214945,1739502686.4747653,46.73995542526245,-0.10339135759368402,1739502686.4747672,46.73995542526245,-3.0390933868190233,1739502686.4747686,46.73995542526245,-0.7373073992566095,1739502686.47477,46.73995542526245,-0.3331640532619114,1739502686.4747715,46.73995542526245,1.3860317559815925,1739502686.4747732,46.73995542526245,0.0,1739502686.474775,46.73995542526245,0.24840336126756424,1739502686.4747763,46.73995542526245,3.4242777437042498,1739502686.474778,46.73995542526245,1.1376283947140282 +1739502686.495637,46.759955406188965,39.907871013459676,1739502686.49564,46.759955406188965,0.3175684113886854,1739502686.4956431,46.759955406188965,73.23644935925154,1739502686.4956462,46.759955406188965,35.81530983214945,1739502686.4956474,46.759955406188965,-0.10339135759368402,1739502686.4956493,46.759955406188965,-3.0390933868190233,1739502686.4956505,46.759955406188965,-0.7373073992566095,1739502686.4956517,46.759955406188965,-0.3331640532619114,1739502686.4956532,46.759955406188965,1.3860317559815925,1739502686.4956548,46.759955406188965,0.0,1739502686.4956563,46.759955406188965,0.24840336126756424,1739502686.4956574,46.759955406188965,3.4242777437042498,1739502686.4956586,46.759955406188965,1.1376283947140282 +1739502686.514776,46.77995538711548,39.907871013459676,1739502686.5147789,46.77995538711548,0.3175684113886854,1739502686.5147817,46.77995538711548,73.23644935925154,1739502686.5147846,46.77995538711548,35.81530983214945,1739502686.5147858,46.77995538711548,-0.10339135759368402,1739502686.5147877,46.77995538711548,-3.0390933868190233,1739502686.5147889,46.77995538711548,-0.7373073992566095,1739502686.51479,46.77995538711548,-0.3331640532619114,1739502686.5147917,46.77995538711548,1.3860317559815925,1739502686.5147932,46.77995538711548,0.0,1739502686.5147946,46.77995538711548,0.24840336126756424,1739502686.514796,46.77995538711548,3.4242777437042498,1739502686.5147974,46.77995538711548,1.1376283947140282 +1739502686.535437,46.79995536804199,39.907871013459676,1739502686.53544,46.79995536804199,0.3175684113886854,1739502686.5354433,46.79995536804199,73.23644935925154,1739502686.5354457,46.79995536804199,35.81530983214945,1739502686.5354474,46.79995536804199,-0.10339135759368402,1739502686.5354488,46.79995536804199,-3.0390933868190233,1739502686.5354502,46.79995536804199,-0.7373073992566095,1739502686.5354517,46.79995536804199,-0.3331640532619114,1739502686.5354528,46.79995536804199,1.3860317559815925,1739502686.5354548,46.79995536804199,0.0,1739502686.535456,46.79995536804199,0.24840336126756424,1739502686.5354574,46.79995536804199,3.4242777437042498,1739502686.5354588,46.79995536804199,1.1376283947140282 +1739502686.5552607,46.819955348968506,39.78612703487878,1739502686.5552633,46.819955348968506,0.2832455713954172,1739502686.5552664,46.819955348968506,73.43843787790074,1739502686.5552688,46.819955348968506,35.55898563607211,1739502686.5552704,46.819955348968506,-0.10172661885759071,1739502686.555272,46.819955348968506,-3.050771671558915,1739502686.555274,46.819955348968506,-0.7380863696233544,1739502686.5552752,46.819955348968506,-0.3134750688674399,1739502686.5552766,46.819955348968506,1.3851682829252843,1739502686.555278,46.819955348968506,0.0,1739502686.5552797,46.819955348968506,0.20762500253556593,1739502686.5552812,46.819955348968506,3.4071889501576296,1739502686.5552826,46.819955348968506,1.164800034930846 +1739502686.580635,46.83995532989502,39.78612703487878,1739502686.580644,46.83995532989502,0.2832455713954172,1739502686.5806549,46.83995532989502,73.43843787790074,1739502686.5806656,46.83995532989502,35.55898563607211,1739502686.5806923,46.83995532989502,-0.10172661885759071,1739502686.580712,46.83995532989502,-3.050771671558915,1739502686.5807195,46.83995532989502,-0.7380863696233544,1739502686.5807242,46.83995532989502,-0.3134750688674399,1739502686.580729,46.83995532989502,1.3851682829252843,1739502686.5807343,46.83995532989502,0.0,1739502686.580739,46.83995532989502,0.22036824799443822,1739502686.5807443,46.83995532989502,3.4071889501576296,1739502686.5807495,46.83995532989502,1.164800034930846 +1739502686.6009107,46.85995531082153,39.78612703487878,1739502686.6009195,46.85995531082153,0.2832455713954172,1739502686.60093,46.85995531082153,73.43843787790074,1739502686.60094,46.85995531082153,35.55898563607211,1739502686.6009452,46.85995531082153,-0.10172661885759071,1739502686.6009514,46.85995531082153,-3.050771671558915,1739502686.6009567,46.85995531082153,-0.7380863696233544,1739502686.6009614,46.85995531082153,-0.3134750688674399,1739502686.6009665,46.85995531082153,1.3851682829252843,1739502686.600972,46.85995531082153,0.0,1739502686.600977,46.85995531082153,0.22036824799443822,1739502686.6009822,46.85995531082153,3.4071889501576296,1739502686.6009877,46.85995531082153,1.164800034930846 +1739502686.646975,46.89995527267456,39.78612703487878,1739502686.646984,46.89995527267456,0.2832455713954172,1739502686.6469963,46.89995527267456,73.43843787790074,1739502686.6470098,46.89995527267456,35.55898563607211,1739502686.6470172,46.89995527267456,-0.10172661885759071,1739502686.647027,46.89995527267456,-3.050771671558915,1739502686.6470358,46.89995527267456,-0.7380863696233544,1739502686.6470447,46.89995527267456,-0.3134750688674399,1739502686.6470532,46.89995527267456,1.3851682829252843,1739502686.6470623,46.89995527267456,0.0,1739502686.647071,46.89995527267456,0.22036824799443822,1739502686.64708,46.89995527267456,3.4071889501576296,1739502686.647089,46.89995527267456,1.164800034930846 +1739502686.6746829,46.92995524406433,39.66109905293996,1739502686.674686,46.92995524406433,0.25023723084488836,1739502686.6746895,46.92995524406433,73.5139753415866,1739502686.6746929,46.92995524406433,35.4356532485243,1739502686.6746943,46.92995524406433,-0.101,1739502686.6746964,46.92995524406433,-3.0586590155647815,1739502686.6746984,46.92995524406433,-0.7025499435991941,1739502686.6746998,46.92995524406433,-0.2991301816967681,1739502686.6747012,46.92995524406433,1.4251125271084109,1739502686.6747031,46.92995524406433,0.0,1739502686.6747046,46.92995524406433,0.2437073880015093,1739502686.6747065,46.92995524406433,3.3909890077633515,1739502686.6747081,46.92995524406433,1.1886986251410934 +1739502686.6940918,46.9599552154541,39.66109905293996,1739502686.6940968,46.9599552154541,0.25023723084488836,1739502686.6941001,46.9599552154541,73.5139753415866,1739502686.694103,46.9599552154541,35.4356532485243,1739502686.6941047,46.9599552154541,-0.101,1739502686.6941068,46.9599552154541,-3.0586590155647815,1739502686.6941085,46.9599552154541,-0.7025499435991941,1739502686.6941102,46.9599552154541,-0.2991301816967681,1739502686.6941123,46.9599552154541,1.4251125271084109,1739502686.694114,46.9599552154541,0.0,1739502686.6941156,46.9599552154541,0.23641390196731749,1739502686.6941173,46.9599552154541,3.3909890077633515,1739502686.69412,46.9599552154541,1.1886986251410934 +1739502686.7159493,46.979955196380615,39.66109905293996,1739502686.7159548,46.979955196380615,0.25023723084488836,1739502686.7159617,46.979955196380615,73.5139753415866,1739502686.7159677,46.979955196380615,35.4356532485243,1739502686.7159703,46.979955196380615,-0.101,1739502686.7159734,46.979955196380615,-3.0586590155647815,1739502686.7159762,46.979955196380615,-0.7025499435991941,1739502686.715979,46.979955196380615,-0.2991301816967681,1739502686.7159815,46.979955196380615,1.4251125271084109,1739502686.7159843,46.979955196380615,0.0,1739502686.7159872,46.979955196380615,0.23641390196731749,1739502686.7159898,46.979955196380615,3.3909890077633515,1739502686.7159922,46.979955196380615,1.1886986251410934 +1739502686.7363565,46.99995517730713,39.66109905293996,1739502686.7363608,46.99995517730713,0.25023723084488836,1739502686.736365,46.99995517730713,73.5139753415866,1739502686.7363694,46.99995517730713,35.4356532485243,1739502686.736372,46.99995517730713,-0.101,1739502686.736375,46.99995517730713,-3.0586590155647815,1739502686.7363777,46.99995517730713,-0.7025499435991941,1739502686.7363799,46.99995517730713,-0.2991301816967681,1739502686.7363825,46.99995517730713,1.4251125271084109,1739502686.736385,46.99995517730713,0.0,1739502686.7363875,46.99995517730713,0.23641390196731749,1739502686.73639,46.99995517730713,3.3909890077633515,1739502686.7363927,46.99995517730713,1.1886986251410934 +1739502686.7559667,47.01995515823364,39.66109905293996,1739502686.7559705,47.01995515823364,0.25023723084488836,1739502686.755975,47.01995515823364,73.5139753415866,1739502686.7559793,47.01995515823364,35.4356532485243,1739502686.755982,47.01995515823364,-0.101,1739502686.7559848,47.01995515823364,-3.0586590155647815,1739502686.7559874,47.01995515823364,-0.7025499435991941,1739502686.7559912,47.01995515823364,-0.2991301816967681,1739502686.7559953,47.01995515823364,1.4251125271084109,1739502686.7559996,47.01995515823364,0.0,1739502686.7560036,47.01995515823364,0.23641390196731749,1739502686.7560077,47.01995515823364,3.3909890077633515,1739502686.7560117,47.01995515823364,1.1886986251410934 +1739502686.77567,47.039955139160156,39.53288483600638,1739502686.775674,47.039955139160156,0.21854679410644007,1739502686.7756784,47.039955139160156,73.73111337486895,1739502686.775683,47.039955139160156,35.16626562258922,1739502686.7756853,47.039955139160156,-0.1,1739502686.7756884,47.039955139160156,-3.0687712100848694,1739502686.7756908,47.039955139160156,-0.702771624713669,1739502686.7756934,47.039955139160156,-0.2807432648521371,1739502686.7756958,47.039955139160156,1.424859813091234,1739502686.775699,47.039955139160156,0.0,1739502686.7757015,47.039955139160156,0.1980434680216233,1739502686.7757044,47.039955139160156,3.3756267670446873,1739502686.7757072,47.039955139160156,1.2148255765998208 +1739502686.7959871,47.05995512008667,39.53288483600638,1739502686.7959921,47.05995512008667,0.21854679410644007,1739502686.7959979,47.05995512008667,73.73111337486895,1739502686.7960045,47.05995512008667,35.16626562258922,1739502686.7960083,47.05995512008667,-0.1,1739502686.7960134,47.05995512008667,-3.0687712100848694,1739502686.7960174,47.05995512008667,-0.702771624713669,1739502686.7960198,47.05995512008667,-0.2807432648521371,1739502686.7960215,47.05995512008667,1.424859813091234,1739502686.7960243,47.05995512008667,0.0,1739502686.796027,47.05995512008667,0.21003423649141317,1739502686.7960293,47.05995512008667,3.3756267670446873,1739502686.7960317,47.05995512008667,1.2148255765998208 +1739502686.8165905,47.079955101013184,39.53288483600638,1739502686.8165944,47.079955101013184,0.21854679410644007,1739502686.816599,47.079955101013184,73.73111337486895,1739502686.8166032,47.079955101013184,35.16626562258922,1739502686.8166053,47.079955101013184,-0.1,1739502686.8166084,47.079955101013184,-3.0687712100848694,1739502686.8166108,47.079955101013184,-0.702771624713669,1739502686.8166132,47.079955101013184,-0.2807432648521371,1739502686.8166156,47.079955101013184,1.424859813091234,1739502686.8166182,47.079955101013184,0.0,1739502686.8166223,47.079955101013184,0.21003423649141317,1739502686.816626,47.079955101013184,3.3756267670446873,1739502686.8166308,47.079955101013184,1.2148255765998208 +1739502686.8356416,47.0999550819397,39.53288483600638,1739502686.835645,47.0999550819397,0.21854679410644007,1739502686.8356488,47.0999550819397,73.73111337486895,1739502686.8356528,47.0999550819397,35.16626562258922,1739502686.8356552,47.0999550819397,-0.1,1739502686.835658,47.0999550819397,-3.0687712100848694,1739502686.8356602,47.0999550819397,-0.702771624713669,1739502686.8356626,47.0999550819397,-0.2807432648521371,1739502686.8356655,47.0999550819397,1.424859813091234,1739502686.8356686,47.0999550819397,0.0,1739502686.8356707,47.0999550819397,0.21003423649141317,1739502686.835673,47.0999550819397,3.3756267670446873,1739502686.8356757,47.0999550819397,1.2148255765998208 +1739502686.8560717,47.11995506286621,39.53288483600638,1739502686.8560753,47.11995506286621,0.21854679410644007,1739502686.8560793,47.11995506286621,73.73111337486895,1739502686.8560834,47.11995506286621,35.16626562258922,1739502686.856086,47.11995506286621,-0.1,1739502686.8560889,47.11995506286621,-3.0687712100848694,1739502686.8560915,47.11995506286621,-0.702771624713669,1739502686.8560936,47.11995506286621,-0.2807432648521371,1739502686.856096,47.11995506286621,1.424859813091234,1739502686.856099,47.11995506286621,0.0,1739502686.8561013,47.11995506286621,0.21003423649141317,1739502686.856104,47.11995506286621,3.3756267670446873,1739502686.8561063,47.11995506286621,1.2148255765998208 +1739502686.8759499,47.139955043792725,39.53288483600638,1739502686.8759546,47.139955043792725,0.21854679410644007,1739502686.8759606,47.139955043792725,73.73111337486895,1739502686.8759673,47.139955043792725,35.16626562258922,1739502686.8759708,47.139955043792725,-0.1,1739502686.8759751,47.139955043792725,-3.0687712100848694,1739502686.8759778,47.139955043792725,-0.702771624713669,1739502686.8759804,47.139955043792725,-0.2807432648521371,1739502686.8759825,47.139955043792725,1.424859813091234,1739502686.8759851,47.139955043792725,0.0,1739502686.8759875,47.139955043792725,0.21003423649141317,1739502686.87599,47.139955043792725,3.3756267670446873,1739502686.8759923,47.139955043792725,1.2148255765998208 +1739502686.8961759,47.15995502471924,39.401591398822156,1739502686.8961806,47.15995502471924,0.18817965227345912,1739502686.896187,47.15995502471924,73.74154718322245,1739502686.8961937,47.15995502471924,35.1102721358609,1739502686.8961968,47.15995502471924,-0.1,1739502686.8962002,47.15995502471924,-3.0745392361111556,1739502686.8962028,47.15995502471924,-0.652883690804454,1739502686.896205,47.15995502471924,-0.27032339136431327,1739502686.8962073,47.15995502471924,1.4828764950819822,1739502686.8962104,47.15995502471924,0.0,1739502686.896213,47.15995502471924,0.261287841298309,1739502686.8962152,47.15995502471924,3.3610338369876334,1739502686.896218,47.15995502471924,1.2376054157872356 +1739502686.9141424,47.17995500564575,39.401591398822156,1739502686.914161,47.17995500564575,0.18817965227345912,1739502686.9141726,47.17995500564575,73.74154718322245,1739502686.914178,47.17995500564575,35.1102721358609,1739502686.9141796,47.17995500564575,-0.1,1739502686.9141817,47.17995500564575,-3.0745392361111556,1739502686.914185,47.17995500564575,-0.652883690804454,1739502686.9141877,47.17995500564575,-0.27032339136431327,1739502686.9141905,47.17995500564575,1.4828764950819822,1739502686.9142027,47.17995500564575,0.0,1739502686.914213,47.17995500564575,0.24527107929474656,1739502686.9142165,47.17995500564575,3.3610338369876334,1739502686.91422,47.17995500564575,1.2376054157872356 +1739502686.933847,47.199954986572266,39.401591398822156,1739502686.9338493,47.199954986572266,0.18817965227345912,1739502686.9338524,47.199954986572266,73.74154718322245,1739502686.933855,47.199954986572266,35.1102721358609,1739502686.9338562,47.199954986572266,-0.1,1739502686.9338582,47.199954986572266,-3.0745392361111556,1739502686.9338593,47.199954986572266,-0.652883690804454,1739502686.9338608,47.199954986572266,-0.27032339136431327,1739502686.9338622,47.199954986572266,1.4828764950819822,1739502686.9338636,47.199954986572266,0.0,1739502686.9338646,47.199954986572266,0.24527107929474656,1739502686.9338663,47.199954986572266,3.3610338369876334,1739502686.9338677,47.199954986572266,1.2376054157872356 +1739502686.9542785,47.21995496749878,39.401591398822156,1739502686.9542809,47.21995496749878,0.18817965227345912,1739502686.9542835,47.21995496749878,73.74154718322245,1739502686.9542866,47.21995496749878,35.1102721358609,1739502686.9542878,47.21995496749878,-0.1,1739502686.9542897,47.21995496749878,-3.0745392361111556,1739502686.9542909,47.21995496749878,-0.652883690804454,1739502686.9542925,47.21995496749878,-0.27032339136431327,1739502686.9542937,47.21995496749878,1.4828764950819822,1739502686.9542954,47.21995496749878,0.0,1739502686.9542966,47.21995496749878,0.24527107929474656,1739502686.9542978,47.21995496749878,3.3610338369876334,1739502686.9542992,47.21995496749878,1.2376054157872356 +1739502686.9744837,47.23995494842529,39.401591398822156,1739502686.9744859,47.23995494842529,0.18817965227345912,1739502686.9744885,47.23995494842529,73.74154718322245,1739502686.9744914,47.23995494842529,35.1102721358609,1739502686.9744928,47.23995494842529,-0.1,1739502686.974494,47.23995494842529,-3.0745392361111556,1739502686.9744954,47.23995494842529,-0.652883690804454,1739502686.9744968,47.23995494842529,-0.27032339136431327,1739502686.974498,47.23995494842529,1.4828764950819822,1739502686.9744997,47.23995494842529,0.0,1739502686.9745011,47.23995494842529,0.24527107929474656,1739502686.9745023,47.23995494842529,3.3610338369876334,1739502686.9745038,47.23995494842529,1.2376054157872356 +1739502686.9996712,47.25995492935181,39.267227254878364,1739502686.9996798,47.25995492935181,0.15911467558427184,1739502686.9996898,47.25995492935181,73.97073769150855,1739502686.9997,47.25995492935181,34.82742162325282,1739502686.9997046,47.25995492935181,-0.09967881729275911,1739502686.999711,47.25995492935181,-3.0833691605561975,1739502686.999716,47.25995492935181,-0.6527079951227887,1739502686.9997213,47.25995492935181,-0.25284196192085046,1739502686.9997258,47.25995492935181,1.4830849377279316,1739502686.9997318,47.25995492935181,0.0,1739502686.9997363,47.25995492935181,0.20654780115015864,1739502686.9997416,47.25995492935181,3.3471118171883303,1739502686.9997466,47.25995492935181,1.2644361042235341 +1739502687.018727,47.27995491027832,39.267227254878364,1739502687.018736,47.27995491027832,0.15911467558427184,1739502687.0187469,47.27995491027832,73.97073769150855,1739502687.018757,47.27995491027832,34.82742162325282,1739502687.0187624,47.27995491027832,-0.09967881729275911,1739502687.0187683,47.27995491027832,-3.0833691605561975,1739502687.0187736,47.27995491027832,-0.6527079951227887,1739502687.0187786,47.27995491027832,-0.25284196192085046,1739502687.0187833,47.27995491027832,1.4830849377279316,1739502687.018789,47.27995491027832,0.0,1739502687.018794,47.27995491027832,0.21864883350439746,1739502687.0187993,47.27995491027832,3.3471118171883303,1739502687.0188043,47.27995491027832,1.2644361042235341 +1739502687.039882,47.299954891204834,39.267227254878364,1739502687.0398912,47.299954891204834,0.15911467558427184,1739502687.0399015,47.299954891204834,73.97073769150855,1739502687.0399108,47.299954891204834,34.82742162325282,1739502687.0399158,47.299954891204834,-0.09967881729275911,1739502687.0399218,47.299954891204834,-3.0833691605561975,1739502687.0399265,47.299954891204834,-0.6527079951227887,1739502687.0399313,47.299954891204834,-0.25284196192085046,1739502687.039936,47.299954891204834,1.4830849377279316,1739502687.0399415,47.299954891204834,0.0,1739502687.0399463,47.299954891204834,0.21864883350439746,1739502687.0399513,47.299954891204834,3.3471118171883303,1739502687.0399566,47.299954891204834,1.2644361042235341 +1739502687.0775151,47.31995487213135,39.267227254878364,1739502687.0775232,47.31995487213135,0.15911467558427184,1739502687.0775342,47.31995487213135,73.97073769150855,1739502687.0775447,47.31995487213135,34.82742162325282,1739502687.0775495,47.31995487213135,-0.09967881729275911,1739502687.0775557,47.31995487213135,-3.0833691605561975,1739502687.0775611,47.31995487213135,-0.6527079951227887,1739502687.077566,47.31995487213135,-0.25284196192085046,1739502687.0775707,47.31995487213135,1.4830849377279316,1739502687.0775762,47.31995487213135,0.0,1739502687.0775812,47.31995487213135,0.21864883350439746,1739502687.0775862,47.31995487213135,3.3471118171883303,1739502687.0775907,47.31995487213135,1.2644361042235341 +1739502687.1000447,47.34995484352112,39.267227254878364,1739502687.1000576,47.34995484352112,0.15911467558427184,1739502687.1000745,47.34995484352112,73.97073769150855,1739502687.1000938,47.34995484352112,34.82742162325282,1739502687.100105,47.34995484352112,-0.09967881729275911,1739502687.100119,47.34995484352112,-3.0833691605561975,1739502687.1001315,47.34995484352112,-0.6527079951227887,1739502687.1001441,47.34995484352112,-0.25284196192085046,1739502687.1001568,47.34995484352112,1.4830849377279316,1739502687.1001694,47.34995484352112,0.0,1739502687.1001823,47.34995484352112,0.21864883350439746,1739502687.1001952,47.34995484352112,3.3471118171883303,1739502687.100208,47.34995484352112,1.2644361042235341 +1739502687.1379764,47.389954805374146,39.129742418660214,1739502687.137982,47.389954805374146,0.13133200631206066,1739502687.1379893,47.389954805374146,74.13267647383114,1739502687.1379962,47.389954805374146,34.61804461436948,1739502687.1379995,47.389954805374146,-0.099,1739502687.138004,47.389954805374146,-3.0905847576828083,1739502687.1380076,47.389954805374146,-0.636009062420492,1739502687.138011,47.389954805374146,-0.23883348117874756,1739502687.1380143,47.389954805374146,1.5030306181757496,1739502687.1380181,47.389954805374146,0.0,1739502687.1380217,47.389954805374146,0.21315809256568283,1739502687.1380253,47.389954805374146,3.333855372020498,1739502687.1380289,47.389954805374146,1.2881566679417145 +1739502687.1590087,47.40995478630066,39.129742418660214,1739502687.1590142,47.40995478630066,0.13133200631206066,1739502687.159021,47.40995478630066,74.13267647383114,1739502687.1590261,47.40995478630066,34.61804461436948,1739502687.159029,47.40995478630066,-0.099,1739502687.1590326,47.40995478630066,-3.0905847576828083,1739502687.1590354,47.40995478630066,-0.636009062420492,1739502687.1590383,47.40995478630066,-0.23883348117874756,1739502687.1590407,47.40995478630066,1.5030306181757496,1739502687.1590443,47.40995478630066,0.0,1739502687.159047,47.40995478630066,0.2148739502340351,1739502687.15905,47.40995478630066,3.333855372020498,1739502687.159053,47.40995478630066,1.2881566679417145 +1739502687.179348,47.42995476722717,39.129742418660214,1739502687.179352,47.42995476722717,0.13133200631206066,1739502687.1793573,47.42995476722717,74.13267647383114,1739502687.1793618,47.42995476722717,34.61804461436948,1739502687.1793642,47.42995476722717,-0.099,1739502687.1793668,47.42995476722717,-3.0905847576828083,1739502687.1793692,47.42995476722717,-0.636009062420492,1739502687.1793718,47.42995476722717,-0.23883348117874756,1739502687.179374,47.42995476722717,1.5030306181757496,1739502687.1793766,47.42995476722717,0.0,1739502687.179379,47.42995476722717,0.2148739502340351,1739502687.1793811,47.42995476722717,3.333855372020498,1739502687.1793835,47.42995476722717,1.2881566679417145 +1739502687.1979082,47.45995473861694,39.129742418660214,1739502687.1979113,47.45995473861694,0.13133200631206066,1739502687.197915,47.45995473861694,74.13267647383114,1739502687.1979184,47.45995473861694,34.61804461436948,1739502687.19792,47.45995473861694,-0.099,1739502687.1979222,47.45995473861694,-3.0905847576828083,1739502687.1979241,47.45995473861694,-0.636009062420492,1739502687.1979256,47.45995473861694,-0.23883348117874756,1739502687.1979272,47.45995473861694,1.5030306181757496,1739502687.1979291,47.45995473861694,0.0,1739502687.1979306,47.45995473861694,0.2148739502340351,1739502687.1979322,47.45995473861694,3.333855372020498,1739502687.1979342,47.45995473861694,1.2881566679417145 +1739502687.2180886,47.47995471954346,38.989339256407206,1739502687.2180917,47.47995471954346,0.10485143839474809,1739502687.2180948,47.47995471954346,74.28290930318713,1739502687.2180974,47.47995471954346,34.420671922262194,1739502687.2180986,47.47995471954346,-0.09822603323951015,1739502687.2181005,47.47995471954346,-3.0971718481653183,1739502687.218102,47.47995471954346,-0.6162682931085965,1739502687.2181036,47.47995471954346,-0.2258775054545868,1739502687.2181048,47.47995471954346,1.526955826286195,1739502687.2181063,47.47995471954346,0.0,1739502687.2181077,47.47995471954346,0.21538833148427747,1739502687.218109,47.47995471954346,3.3211817857354102,1739502687.2181106,47.47995471954346,1.3117282390480105 +1739502687.2378364,47.49995470046997,38.989339256407206,1739502687.2378385,47.49995470046997,0.10485143839474809,1739502687.2378414,47.49995470046997,74.28290930318713,1739502687.2378442,47.49995470046997,34.420671922262194,1739502687.2378452,47.49995470046997,-0.09822603323951015,1739502687.237847,47.49995470046997,-3.0971718481653183,1739502687.2378483,47.49995470046997,-0.6162682931085965,1739502687.2378497,47.49995470046997,-0.2258775054545868,1739502687.237851,47.49995470046997,1.526955826286195,1739502687.2378523,47.49995470046997,0.0,1739502687.2378535,47.49995470046997,0.21522758723818458,1739502687.237855,47.49995470046997,3.3211817857354102,1739502687.2378561,47.49995470046997,1.3117282390480105 +1739502687.2576604,47.519954681396484,38.989339256407206,1739502687.2576632,47.519954681396484,0.10485143839474809,1739502687.257666,47.519954681396484,74.28290930318713,1739502687.257669,47.519954681396484,34.420671922262194,1739502687.2576702,47.519954681396484,-0.09822603323951015,1739502687.2576718,47.519954681396484,-3.0971718481653183,1739502687.2576733,47.519954681396484,-0.6162682931085965,1739502687.2576745,47.519954681396484,-0.2258775054545868,1739502687.2576761,47.519954681396484,1.526955826286195,1739502687.2576776,47.519954681396484,0.0,1739502687.257679,47.519954681396484,0.21522758723818458,1739502687.2576807,47.519954681396484,3.3211817857354102,1739502687.2576818,47.519954681396484,1.3117282390480105 +1739502687.277252,47.539954662323,38.989339256407206,1739502687.277254,47.539954662323,0.10485143839474809,1739502687.277257,47.539954662323,74.28290930318713,1739502687.2772596,47.539954662323,34.420671922262194,1739502687.277261,47.539954662323,-0.09822603323951015,1739502687.277263,47.539954662323,-3.0971718481653183,1739502687.277264,47.539954662323,-0.6162682931085965,1739502687.2772653,47.539954662323,-0.2258775054545868,1739502687.2772667,47.539954662323,1.526955826286195,1739502687.2772682,47.539954662323,0.0,1739502687.2772696,47.539954662323,0.21522758723818458,1739502687.277271,47.539954662323,3.3211817857354102,1739502687.2772725,47.539954662323,1.3117282390480105 +1739502687.2977085,47.55995464324951,38.989339256407206,1739502687.2977107,47.55995464324951,0.10485143839474809,1739502687.2977135,47.55995464324951,74.28290930318713,1739502687.297716,47.55995464324951,34.420671922262194,1739502687.2977176,47.55995464324951,-0.09822603323951015,1739502687.297719,47.55995464324951,-3.0971718481653183,1739502687.2977207,47.55995464324951,-0.6162682931085965,1739502687.2977219,47.55995464324951,-0.2258775054545868,1739502687.297723,47.55995464324951,1.526955826286195,1739502687.2977247,47.55995464324951,0.0,1739502687.2977257,47.55995464324951,0.21522758723818458,1739502687.2977273,47.55995464324951,3.3211817857354102,1739502687.2977285,47.55995464324951,1.3117282390480105 +1739502687.317852,47.579954624176025,38.989339256407206,1739502687.3178546,47.579954624176025,0.10485143839474809,1739502687.3178577,47.579954624176025,74.28290930318713,1739502687.3178604,47.579954624176025,34.420671922262194,1739502687.3178618,47.579954624176025,-0.09822603323951015,1739502687.3178637,47.579954624176025,-3.0971718481653183,1739502687.317865,47.579954624176025,-0.6162682931085965,1739502687.3178668,47.579954624176025,-0.2258775054545868,1739502687.317868,47.579954624176025,1.526955826286195,1739502687.3178697,47.579954624176025,0.0,1739502687.317871,47.579954624176025,0.21522758723818458,1739502687.3178723,47.579954624176025,3.3211817857354102,1739502687.317874,47.579954624176025,1.3117282390480105 +1739502687.3376038,47.59995460510254,38.84606866862808,1739502687.3376062,47.59995460510254,0.07964750689061706,1739502687.337609,47.59995460510254,74.40789819235826,1739502687.3376117,47.59995460510254,34.24850796613658,1739502687.337613,47.59995460510254,-0.098,1739502687.3376148,47.59995460510254,-3.102972353055895,1739502687.3376164,47.59995460510254,-0.5925026508903793,1739502687.3376176,47.59995460510254,-0.21458881322433912,1739502687.3376188,47.59995460510254,1.5562648310257425,1739502687.3376205,47.59995460510254,0.0,1739502687.3376217,47.59995460510254,0.2235490331900613,1739502687.3376231,47.59995460510254,3.3093487336402325,1739502687.3376245,47.59995460510254,1.335316251400633 +1739502687.3588197,47.61995458602905,38.84606866862808,1739502687.3588226,47.61995458602905,0.07964750689061706,1739502687.358826,47.61995458602905,74.40789819235826,1739502687.3588293,47.61995458602905,34.24850796613658,1739502687.358831,47.61995458602905,-0.098,1739502687.3588326,47.61995458602905,-3.102972353055895,1739502687.3588345,47.61995458602905,-0.5925026508903793,1739502687.358836,47.61995458602905,-0.21458881322433912,1739502687.3588376,47.61995458602905,1.5562648310257425,1739502687.3588395,47.61995458602905,0.0,1739502687.3588412,47.61995458602905,0.2209485796251096,1739502687.3588426,47.61995458602905,3.3093487336402325,1739502687.358844,47.61995458602905,1.335316251400633 +1739502687.39165,47.639954566955566,38.84606866862808,1739502687.391659,47.639954566955566,0.07964750689061706,1739502687.3916695,47.639954566955566,74.40789819235826,1739502687.3916795,47.639954566955566,34.24850796613658,1739502687.3916848,47.639954566955566,-0.098,1739502687.391691,47.639954566955566,-3.102972353055895,1739502687.3916965,47.639954566955566,-0.5925026508903793,1739502687.3917012,47.639954566955566,-0.21458881322433912,1739502687.3917058,47.639954566955566,1.5562648310257425,1739502687.3917112,47.639954566955566,0.0,1739502687.391716,47.639954566955566,0.2209485796251096,1739502687.391721,47.639954566955566,3.3093487336402325,1739502687.391726,47.639954566955566,1.335316251400633 +1739502687.406225,47.65995454788208,38.84606866862808,1739502687.406234,47.65995454788208,0.07964750689061706,1739502687.4062443,47.65995454788208,74.40789819235826,1739502687.4062543,47.65995454788208,34.24850796613658,1739502687.406259,47.65995454788208,-0.098,1739502687.4062648,47.65995454788208,-3.102972353055895,1739502687.4062698,47.65995454788208,-0.5925026508903793,1739502687.4062746,47.65995454788208,-0.21458881322433912,1739502687.4062793,47.65995454788208,1.5562648310257425,1739502687.406285,47.65995454788208,0.0,1739502687.4062898,47.65995454788208,0.2209485796251096,1739502687.4062953,47.65995454788208,3.3093487336402325,1739502687.4063008,47.65995454788208,1.335316251400633 +1739502687.42858,47.68995451927185,38.84606866862808,1739502687.428585,47.68995451927185,0.07964750689061706,1739502687.428591,47.68995451927185,74.40789819235826,1739502687.4285967,47.68995451927185,34.24850796613658,1739502687.4285996,47.68995451927185,-0.098,1739502687.428603,47.68995451927185,-3.102972353055895,1739502687.4286058,47.68995451927185,-0.5925026508903793,1739502687.4286084,47.68995451927185,-0.21458881322433912,1739502687.428611,47.68995451927185,1.5562648310257425,1739502687.4286141,47.68995451927185,0.0,1739502687.428617,47.68995451927185,0.2209485796251096,1739502687.4286199,47.68995451927185,3.3093487336402325,1739502687.4286222,47.68995451927185,1.335316251400633 +1739502687.447721,47.709954500198364,38.69992711597581,1739502687.447724,47.709954500198364,0.05568334517649198,1739502687.4477274,47.709954500198364,74.55764491202933,1739502687.44773,47.709954500198364,34.05038760730825,1739502687.4477317,47.709954500198364,-0.09709696809058138,1739502687.4477334,47.709954500198364,-3.1087452368836637,1739502687.447735,47.709954500198364,-0.5733820365728758,1739502687.4477367,47.709954500198364,-0.203166502993384,1739502687.4477382,47.709954500198364,1.580253224101372,1739502687.4477398,47.709954500198364,0.0,1739502687.4477415,47.709954500198364,0.22065801613876088,1739502687.447743,47.709954500198364,3.2980079453194655,1739502687.4477446,47.709954500198364,1.3595044068135933 +1739502687.467158,47.72995448112488,38.69992711597581,1739502687.4671614,47.72995448112488,0.05568334517649198,1739502687.4671655,47.72995448112488,74.55764491202933,1739502687.4671705,47.72995448112488,34.05038760730825,1739502687.4671733,47.72995448112488,-0.09709696809058138,1739502687.467177,47.72995448112488,-3.1087452368836637,1739502687.46718,47.72995448112488,-0.5733820365728758,1739502687.4671834,47.72995448112488,-0.203166502993384,1739502687.4671865,47.72995448112488,1.580253224101372,1739502687.4671898,47.72995448112488,0.0,1739502687.4671931,47.72995448112488,0.22074881728777873,1739502687.4671965,47.72995448112488,3.2980079453194655,1739502687.4671998,47.72995448112488,1.3595044068135933 +1739502687.486409,47.74995446205139,38.69992711597581,1739502687.4864113,47.74995446205139,0.05568334517649198,1739502687.4864142,47.74995446205139,74.55764491202933,1739502687.4864166,47.74995446205139,34.05038760730825,1739502687.486418,47.74995446205139,-0.09709696809058138,1739502687.4864197,47.74995446205139,-3.1087452368836637,1739502687.4864213,47.74995446205139,-0.5733820365728758,1739502687.4864225,47.74995446205139,-0.203166502993384,1739502687.4864237,47.74995446205139,1.580253224101372,1739502687.4864252,47.74995446205139,0.0,1739502687.4864264,47.74995446205139,0.22074881728777873,1739502687.486428,47.74995446205139,3.2980079453194655,1739502687.4864292,47.74995446205139,1.3595044068135933 +1739502687.5066402,47.769954442977905,38.69992711597581,1739502687.5066423,47.769954442977905,0.05568334517649198,1739502687.5066452,47.769954442977905,74.55764491202933,1739502687.5066478,47.769954442977905,34.05038760730825,1739502687.506649,47.769954442977905,-0.09709696809058138,1739502687.506651,47.769954442977905,-3.1087452368836637,1739502687.506652,47.769954442977905,-0.5733820365728758,1739502687.5066535,47.769954442977905,-0.203166502993384,1739502687.5066547,47.769954442977905,1.580253224101372,1739502687.5066564,47.769954442977905,0.0,1739502687.5066578,47.769954442977905,0.22074881728777873,1739502687.5066593,47.769954442977905,3.2980079453194655,1739502687.5066607,47.769954442977905,1.3595044068135933 +1739502687.526589,47.78995442390442,38.69992711597581,1739502687.5265913,47.78995442390442,0.05568334517649198,1739502687.5265942,47.78995442390442,74.55764491202933,1739502687.5265965,47.78995442390442,34.05038760730825,1739502687.526598,47.78995442390442,-0.09709696809058138,1739502687.5266,47.78995442390442,-3.1087452368836637,1739502687.5266013,47.78995442390442,-0.5733820365728758,1739502687.5266027,47.78995442390442,-0.203166502993384,1739502687.5266037,47.78995442390442,1.580253224101372,1739502687.5266054,47.78995442390442,0.0,1739502687.5266068,47.78995442390442,0.22074881728777873,1739502687.5266082,47.78995442390442,3.2980079453194655,1739502687.5266097,47.78995442390442,1.3595044068135933 +1739502687.5469692,47.80995440483093,38.55089770430696,1739502687.546971,47.80995440483093,0.0329439903745099,1739502687.546974,47.80995440483093,74.73148258210695,1739502687.5469766,47.80995440483093,33.82821232246097,1739502687.546978,47.80995440483093,-0.09629682231525385,1739502687.5469797,47.80995440483093,-3.114233523327534,1739502687.5469809,47.80995440483093,-0.5572575835853176,1739502687.546982,47.80995440483093,-0.19148014493250068,1739502687.5469837,47.80995440483093,1.6007698423622727,1739502687.5469851,47.80995440483093,0.0,1739502687.5469866,47.80995440483093,0.2154342360962343,1739502687.546988,47.80995440483093,3.2871787700477575,1739502687.5469892,47.80995440483093,1.3836747985547704 +1739502687.5666654,47.829954385757446,38.55089770430696,1739502687.566668,47.829954385757446,0.0329439903745099,1739502687.5666711,47.829954385757446,74.73148258210695,1739502687.566674,47.829954385757446,33.82821232246097,1739502687.5666754,47.829954385757446,-0.09629682231525385,1739502687.566677,47.829954385757446,-3.114233523327534,1739502687.5666785,47.829954385757446,-0.5572575835853176,1739502687.56668,47.829954385757446,-0.19148014493250068,1739502687.5666814,47.829954385757446,1.6007698423622727,1739502687.5666828,47.829954385757446,0.0,1739502687.5666845,47.829954385757446,0.21709504380750233,1739502687.5666857,47.829954385757446,3.2871787700477575,1739502687.5666873,47.829954385757446,1.3836747985547704 +1739502687.5865362,47.84995436668396,38.55089770430696,1739502687.5865386,47.84995436668396,0.0329439903745099,1739502687.5865414,47.84995436668396,74.73148258210695,1739502687.5865443,47.84995436668396,33.82821232246097,1739502687.5865457,47.84995436668396,-0.09629682231525385,1739502687.5865476,47.84995436668396,-3.114233523327534,1739502687.586549,47.84995436668396,-0.5572575835853176,1739502687.5865505,47.84995436668396,-0.19148014493250068,1739502687.586552,47.84995436668396,1.6007698423622727,1739502687.5865533,47.84995436668396,0.0,1739502687.5865548,47.84995436668396,0.21709504380750233,1739502687.5865564,47.84995436668396,3.2871787700477575,1739502687.5865576,47.84995436668396,1.3836747985547704 +1739502687.6069553,47.869954347610474,38.55089770430696,1739502687.6069577,47.869954347610474,0.0329439903745099,1739502687.6069605,47.869954347610474,74.73148258210695,1739502687.6069634,47.869954347610474,33.82821232246097,1739502687.606965,47.869954347610474,-0.09629682231525385,1739502687.6069667,47.869954347610474,-3.114233523327534,1739502687.6069682,47.869954347610474,-0.5572575835853176,1739502687.6069698,47.869954347610474,-0.19148014493250068,1739502687.606971,47.869954347610474,1.6007698423622727,1739502687.606973,47.869954347610474,0.0,1739502687.6069744,47.869954347610474,0.21709504380750233,1739502687.6069758,47.869954347610474,3.2871787700477575,1739502687.6069775,47.869954347610474,1.3836747985547704 +1739502687.6264892,47.88995432853699,38.55089770430696,1739502687.6264913,47.88995432853699,0.0329439903745099,1739502687.6264946,47.88995432853699,74.73148258210695,1739502687.6264977,47.88995432853699,33.82821232246097,1739502687.6264994,47.88995432853699,-0.09629682231525385,1739502687.6265013,47.88995432853699,-3.114233523327534,1739502687.6265028,47.88995432853699,-0.5572575835853176,1739502687.6265042,47.88995432853699,-0.19148014493250068,1739502687.6265054,47.88995432853699,1.6007698423622727,1739502687.6265073,47.88995432853699,0.0,1739502687.626509,47.88995432853699,0.21709504380750233,1739502687.6265106,47.88995432853699,3.2871787700477575,1739502687.626512,47.88995432853699,1.3836747985547704 +1739502687.6465113,47.9099543094635,38.55089770430696,1739502687.646514,47.9099543094635,0.0329439903745099,1739502687.646517,47.9099543094635,74.73148258210695,1739502687.64652,47.9099543094635,33.82821232246097,1739502687.6465213,47.9099543094635,-0.09629682231525385,1739502687.6465232,47.9099543094635,-3.114233523327534,1739502687.6465247,47.9099543094635,-0.5572575835853176,1739502687.646526,47.9099543094635,-0.19148014493250068,1739502687.6465278,47.9099543094635,1.6007698423622727,1739502687.6465294,47.9099543094635,0.0,1739502687.6465309,47.9099543094635,0.21709504380750233,1739502687.6465323,47.9099543094635,3.2871787700477575,1739502687.6465344,47.9099543094635,1.3836747985547704 +1739502687.6666281,47.929954290390015,38.39902545714323,1739502687.6666305,47.929954290390015,0.011407479089678318,1739502687.6666334,47.929954290390015,74.7451715041948,1739502687.6666365,47.929954290390015,33.76701506602912,1739502687.666638,47.929954290390015,-0.096,1739502687.6666396,47.929954290390015,-3.118408717096844,1739502687.6666412,47.929954290390015,-0.5185158807169912,1739502687.6666427,47.929954290390015,-0.18526705134343224,1739502687.6666439,47.929954290390015,1.651159927505958,1739502687.6666458,47.929954290390015,0.0,1739502687.666647,47.929954290390015,0.25583732406553944,1739502687.6666489,47.929954290390015,3.2769233003450022,1739502687.66665,47.929954290390015,1.4074295739590037 +1739502687.6865206,47.94995427131653,38.39902545714323,1739502687.686523,47.94995427131653,0.011407479089678318,1739502687.686526,47.94995427131653,74.7451715041948,1739502687.686529,47.94995427131653,33.76701506602912,1739502687.6865306,47.94995427131653,-0.096,1739502687.6865323,47.94995427131653,-3.118408717096844,1739502687.6865342,47.94995427131653,-0.5185158807169912,1739502687.6865356,47.94995427131653,-0.18526705134343224,1739502687.686537,47.94995427131653,1.651159927505958,1739502687.6865387,47.94995427131653,0.0,1739502687.6865401,47.94995427131653,0.24373035354695438,1739502687.6865416,47.94995427131653,3.2769233003450022,1739502687.686543,47.94995427131653,1.4074295739590037 +1739502687.7065923,47.96995425224304,38.39902545714323,1739502687.7065947,47.96995425224304,0.011407479089678318,1739502687.7065978,47.96995425224304,74.7451715041948,1739502687.706601,47.96995425224304,33.76701506602912,1739502687.7066026,47.96995425224304,-0.096,1739502687.7066045,47.96995425224304,-3.118408717096844,1739502687.7066061,47.96995425224304,-0.5185158807169912,1739502687.7066073,47.96995425224304,-0.18526705134343224,1739502687.706609,47.96995425224304,1.651159927505958,1739502687.7066107,47.96995425224304,0.0,1739502687.706612,47.96995425224304,0.24373035354695438,1739502687.7066135,47.96995425224304,3.2769233003450022,1739502687.7066152,47.96995425224304,1.4074295739590037 +1739502687.726568,47.989954233169556,38.39902545714323,1739502687.7265706,47.989954233169556,0.011407479089678318,1739502687.7265735,47.989954233169556,74.7451715041948,1739502687.7265766,47.989954233169556,33.76701506602912,1739502687.726578,47.989954233169556,-0.096,1739502687.7265797,47.989954233169556,-3.118408717096844,1739502687.7265813,47.989954233169556,-0.5185158807169912,1739502687.7265828,47.989954233169556,-0.18526705134343224,1739502687.7265844,47.989954233169556,1.651159927505958,1739502687.7265859,47.989954233169556,0.0,1739502687.726587,47.989954233169556,0.24373035354695438,1739502687.7265887,47.989954233169556,3.2769233003450022,1739502687.7265902,47.989954233169556,1.4074295739590037 +1739502687.7537289,48.00995421409607,38.39902545714323,1739502687.7537382,48.00995421409607,0.011407479089678318,1739502687.7537496,48.00995421409607,74.7451715041948,1739502687.75376,48.00995421409607,33.76701506602912,1739502687.753765,48.00995421409607,-0.096,1739502687.7537715,48.00995421409607,-3.118408717096844,1739502687.7537766,48.00995421409607,-0.5185158807169912,1739502687.7537816,48.00995421409607,-0.18526705134343224,1739502687.7537866,48.00995421409607,1.651159927505958,1739502687.7537925,48.00995421409607,0.0,1739502687.753797,48.00995421409607,0.24373035354695438,1739502687.7538025,48.00995421409607,3.2769233003450022,1739502687.753808,48.00995421409607,1.4074295739590037 +1739502687.7744117,48.019954204559326,38.39902545714323,1739502687.7744172,48.019954204559326,0.011407479089678318,1739502687.7744234,48.019954204559326,74.7451715041948,1739502687.774429,48.019954204559326,33.76701506602912,1739502687.774432,48.019954204559326,-0.096,1739502687.774436,48.019954204559326,-3.118408717096844,1739502687.7744389,48.019954204559326,-0.5185158807169912,1739502687.7744415,48.019954204559326,-0.18526705134343224,1739502687.7744443,48.019954204559326,1.651159927505958,1739502687.7744477,48.019954204559326,0.0,1739502687.774451,48.019954204559326,0.24373035354695438,1739502687.7744539,48.019954204559326,3.2769233003450022,1739502687.7744565,48.019954204559326,1.4074295739590037 +1739502687.792605,48.0499541759491,38.24421290988843,1739502687.7926104,48.0499541759491,-0.008956469879717766,1739502687.7926161,48.0499541759491,75.00639260371382,1739502687.7926219,48.0499541759491,33.4524739496682,1739502687.7926245,48.0499541759491,-0.09435562116818198,1739502687.7926278,48.0499541759491,-3.1237723774943364,1739502687.7926304,48.0499541759491,-0.5148503508349451,1739502687.7926333,48.0499541759491,-0.17196575655162394,1739502687.7926362,48.0499541759491,1.6560089345467268,1739502687.7926393,48.0499541759491,0.0,1739502687.7926419,48.0499541759491,0.21200018388531208,1739502687.7926445,48.0499541759491,3.2670489948217805,1739502687.7926474,48.0499541759491,1.4340930661409221 +1739502687.8117602,48.06995415687561,38.24421290988843,1739502687.8117652,48.06995415687561,-0.008956469879717766,1739502687.8117716,48.06995415687561,75.00639260371382,1739502687.811777,48.06995415687561,33.4524739496682,1739502687.8117802,48.06995415687561,-0.09435562116818198,1739502687.8117838,48.06995415687561,-3.1237723774943364,1739502687.8117864,48.06995415687561,-0.5148503508349451,1739502687.8117895,48.06995415687561,-0.17196575655162394,1739502687.8117924,48.06995415687561,1.6560089345467268,1739502687.8117955,48.06995415687561,0.0,1739502687.8117983,48.06995415687561,0.22191586840580468,1739502687.8118014,48.06995415687561,3.2670489948217805,1739502687.8118045,48.06995415687561,1.4340930661409221 +1739502687.8306434,48.089954137802124,38.24421290988843,1739502687.830654,48.089954137802124,-0.008956469879717766,1739502687.8306642,48.089954137802124,75.00639260371382,1739502687.8306744,48.089954137802124,33.4524739496682,1739502687.8306801,48.089954137802124,-0.09435562116818198,1739502687.8306878,48.089954137802124,-3.1237723774943364,1739502687.830694,48.089954137802124,-0.5148503508349451,1739502687.8306994,48.089954137802124,-0.17196575655162394,1739502687.8307056,48.089954137802124,1.6560089345467268,1739502687.8307114,48.089954137802124,0.0,1739502687.830717,48.089954137802124,0.22191586840580468,1739502687.8307233,48.089954137802124,3.2670489948217805,1739502687.8307292,48.089954137802124,1.4340930661409221 +1739502687.8498783,48.10995411872864,38.24421290988843,1739502687.8498852,48.10995411872864,-0.008956469879717766,1739502687.8498917,48.10995411872864,75.00639260371382,1739502687.849898,48.10995411872864,33.4524739496682,1739502687.849901,48.10995411872864,-0.09435562116818198,1739502687.8499055,48.10995411872864,-3.1237723774943364,1739502687.8499088,48.10995411872864,-0.5148503508349451,1739502687.8499122,48.10995411872864,-0.17196575655162394,1739502687.8499155,48.10995411872864,1.6560089345467268,1739502687.8499198,48.10995411872864,0.0,1739502687.8499246,48.10995411872864,0.22191586840580468,1739502687.8499303,48.10995411872864,3.2670489948217805,1739502687.8499346,48.10995411872864,1.4340930661409221 +1739502687.8703375,48.12995409965515,38.24421290988843,1739502687.8703432,48.12995409965515,-0.008956469879717766,1739502687.8703477,48.12995409965515,75.00639260371382,1739502687.8703542,48.12995409965515,33.4524739496682,1739502687.8703573,48.12995409965515,-0.09435562116818198,1739502687.8703635,48.12995409965515,-3.1237723774943364,1739502687.8703682,48.12995409965515,-0.5148503508349451,1739502687.8703713,48.12995409965515,-0.17196575655162394,1739502687.8703752,48.12995409965515,1.6560089345467268,1739502687.870378,48.12995409965515,0.0,1739502687.8703804,48.12995409965515,0.22191586840580468,1739502687.8703823,48.12995409965515,3.2670489948217805,1739502687.8703845,48.12995409965515,1.4340930661409221 +1739502687.8890188,48.149954080581665,38.08638693465914,1739502687.8890224,48.149954080581665,-0.028158611640270337,1739502687.8890274,48.149954080581665,75.02120483440247,1739502687.889034,48.149954080581665,33.38864604427432,1739502687.8890371,48.149954080581665,-0.0937805949934623,1739502687.889041,48.149954080581665,-3.1276247236538133,1739502687.889043,48.149954080581665,-0.47842143119627384,1739502687.889045,48.149954080581665,-0.1662891412707426,1739502687.8890471,48.149954080581665,1.7049803520029334,1739502687.889051,48.149954080581665,0.0,1739502687.889055,48.149954080581665,0.2574973845020969,1739502687.8890579,48.149954080581665,3.2575682094300253,1739502687.8890612,48.149954080581665,1.4586021985712638 +1739502687.9111385,48.16995406150818,38.08638693465914,1739502687.9111423,48.16995406150818,-0.028158611640270337,1739502687.911147,48.16995406150818,75.02120483440247,1739502687.911152,48.16995406150818,33.38864604427432,1739502687.9111543,48.16995406150818,-0.0937805949934623,1739502687.9111571,48.16995406150818,-3.1276247236538133,1739502687.9111598,48.16995406150818,-0.47842143119627384,1739502687.9111621,48.16995406150818,-0.1662891412707426,1739502687.9111645,48.16995406150818,1.7049803520029334,1739502687.9111671,48.16995406150818,0.0,1739502687.9111698,48.16995406150818,0.24637815343166958,1739502687.9111726,48.16995406150818,3.2575682094300253,1739502687.9111753,48.16995406150818,1.4586021985712638 +1739502687.9294443,48.18995404243469,38.08638693465914,1739502687.9294481,48.18995404243469,-0.028158611640270337,1739502687.929453,48.18995404243469,75.02120483440247,1739502687.9294581,48.18995404243469,33.38864604427432,1739502687.929461,48.18995404243469,-0.0937805949934623,1739502687.9294648,48.18995404243469,-3.1276247236538133,1739502687.9294684,48.18995404243469,-0.47842143119627384,1739502687.929472,48.18995404243469,-0.1662891412707426,1739502687.9294758,48.18995404243469,1.7049803520029334,1739502687.9294794,48.18995404243469,0.0,1739502687.9294827,48.18995404243469,0.24637815343166958,1739502687.9294863,48.18995404243469,3.2575682094300253,1739502687.9294903,48.18995404243469,1.4586021985712638 +1739502687.950458,48.209954023361206,38.08638693465914,1739502687.9504633,48.209954023361206,-0.028158611640270337,1739502687.9504695,48.209954023361206,75.02120483440247,1739502687.950474,48.209954023361206,33.38864604427432,1739502687.950477,48.209954023361206,-0.0937805949934623,1739502687.9504802,48.209954023361206,-3.1276247236538133,1739502687.9504828,48.209954023361206,-0.47842143119627384,1739502687.9504855,48.209954023361206,-0.1662891412707426,1739502687.9504879,48.209954023361206,1.7049803520029334,1739502687.9504912,48.209954023361206,0.0,1739502687.9504938,48.209954023361206,0.24637815343166958,1739502687.950497,48.209954023361206,3.2575682094300253,1739502687.9504993,48.209954023361206,1.4586021985712638 +1739502687.9681993,48.22995400428772,38.08638693465914,1739502687.9682016,48.22995400428772,-0.028158611640270337,1739502687.9682045,48.22995400428772,75.02120483440247,1739502687.9682074,48.22995400428772,33.38864604427432,1739502687.9682086,48.22995400428772,-0.0937805949934623,1739502687.9682105,48.22995400428772,-3.1276247236538133,1739502687.9682117,48.22995400428772,-0.47842143119627384,1739502687.968213,48.22995400428772,-0.1662891412707426,1739502687.9682143,48.22995400428772,1.7049803520029334,1739502687.9682157,48.22995400428772,0.0,1739502687.9682174,48.22995400428772,0.24637815343166958,1739502687.9682186,48.22995400428772,3.2575682094300253,1739502687.9682205,48.22995400428772,1.4586021985712638 +1739502687.991099,48.24995398521423,37.92560764998388,1739502687.991103,48.24995398521423,-0.04621573950310687,1739502687.9911082,48.24995398521423,75.28315614709759,1739502687.9911132,48.24995398521423,33.07281127194979,1739502687.991116,48.24995398521423,-0.09014363928991766,1739502687.9911196,48.24995398521423,-3.132540821078317,1739502687.991123,48.24995398521423,-0.474429810860093,1739502687.9911263,48.24995398521423,-0.15457132243136731,1739502687.9911296,48.24995398521423,1.7104335616226463,1739502687.9911332,48.24995398521423,0.0,1739502687.9911366,48.24995398521423,0.21510522148505262,1739502687.9911401,48.24995398521423,3.2485610824954145,1739502687.9911435,48.24995398521423,1.4855555424967304 +1739502688.0084913,48.26995396614075,37.92560764998388,1739502688.0084934,48.26995396614075,-0.04621573950310687,1739502688.0084958,48.26995396614075,75.28315614709759,1739502688.0084984,48.26995396614075,33.07281127194979,1739502688.0084996,48.26995396614075,-0.09014363928991766,1739502688.0085013,48.26995396614075,-3.132540821078317,1739502688.0085025,48.26995396614075,-0.474429810860093,1739502688.008504,48.26995396614075,-0.15457132243136731,1739502688.008505,48.26995396614075,1.7104335616226463,1739502688.0085065,48.26995396614075,0.0,1739502688.008508,48.26995396614075,0.22487801912591587,1739502688.0085092,48.26995396614075,3.2485610824954145,1739502688.0085104,48.26995396614075,1.4855555424967304 +1739502688.028291,48.28995394706726,37.92560764998388,1739502688.0282938,48.28995394706726,-0.04621573950310687,1739502688.0282967,48.28995394706726,75.28315614709759,1739502688.0282996,48.28995394706726,33.07281127194979,1739502688.0283008,48.28995394706726,-0.09014363928991766,1739502688.0283027,48.28995394706726,-3.132540821078317,1739502688.028304,48.28995394706726,-0.474429810860093,1739502688.0283053,48.28995394706726,-0.15457132243136731,1739502688.0283067,48.28995394706726,1.7104335616226463,1739502688.0283082,48.28995394706726,0.0,1739502688.0283096,48.28995394706726,0.22487801912591587,1739502688.028311,48.28995394706726,3.2485610824954145,1739502688.0283127,48.28995394706726,1.4855555424967304 +1739502688.0483584,48.309953927993774,37.92560764998388,1739502688.0483615,48.309953927993774,-0.04621573950310687,1739502688.048365,48.309953927993774,75.28315614709759,1739502688.048368,48.309953927993774,33.07281127194979,1739502688.0483694,48.309953927993774,-0.09014363928991766,1739502688.0483713,48.309953927993774,-3.132540821078317,1739502688.0483727,48.309953927993774,-0.474429810860093,1739502688.0483742,48.309953927993774,-0.15457132243136731,1739502688.0483756,48.309953927993774,1.7104335616226463,1739502688.048377,48.309953927993774,0.0,1739502688.0483785,48.309953927993774,0.22487801912591587,1739502688.04838,48.309953927993774,3.2485610824954145,1739502688.0483813,48.309953927993774,1.4855555424967304 +1739502688.069147,48.32995390892029,37.92560764998388,1739502688.0691507,48.32995390892029,-0.04621573950310687,1739502688.0691547,48.32995390892029,75.28315614709759,1739502688.0691605,48.32995390892029,33.07281127194979,1739502688.069164,48.32995390892029,-0.09014363928991766,1739502688.069169,48.32995390892029,-3.132540821078317,1739502688.0691738,48.32995390892029,-0.474429810860093,1739502688.0691776,48.32995390892029,-0.15457132243136731,1739502688.069181,48.32995390892029,1.7104335616226463,1739502688.0691833,48.32995390892029,0.0,1739502688.0691872,48.32995390892029,0.22487801912591587,1739502688.0691905,48.32995390892029,3.2485610824954145,1739502688.0691924,48.32995390892029,1.4855555424967304 +1739502688.089134,48.339953899383545,37.92560764998388,1739502688.0891373,48.339953899383545,-0.04621573950310687,1739502688.0891433,48.339953899383545,75.28315614709759,1739502688.0891502,48.339953899383545,33.07281127194979,1739502688.089154,48.339953899383545,-0.09014363928991766,1739502688.0891588,48.339953899383545,-3.132540821078317,1739502688.0891628,48.339953899383545,-0.474429810860093,1739502688.089166,48.339953899383545,-0.15457132243136731,1739502688.089168,48.339953899383545,1.7104335616226463,1739502688.0891721,48.339953899383545,0.0,1739502688.089175,48.339953899383545,0.22487801912591587,1739502688.0891771,48.339953899383545,3.2485610824954145,1739502688.089179,48.339953899383545,1.4855555424967304 +1739502688.1095555,48.369953870773315,37.76185436125822,1739502688.1095579,48.369953870773315,-0.0631442036564609,1739502688.1095607,48.369953870773315,75.28628438804753,1739502688.1095634,48.369953870773315,33.020796622544346,1739502688.1095648,48.369953870773315,-0.08972192376052311,1739502688.1095665,48.369953870773315,-3.135986849322853,1739502688.109568,48.369953870773315,-0.43933817377114304,1739502688.1095695,48.369953870773315,-0.1499802233831895,1739502688.1095705,48.369953870773315,1.7591314498834736,1739502688.1095724,48.369953870773315,0.0,1739502688.1095736,48.369953870773315,0.260156326739563,1739502688.1095753,48.369953870773315,3.2399968336696063,1739502688.1095765,48.369953870773315,1.5099996015013866 +1739502688.1288996,48.38995385169983,37.76185436125822,1739502688.128902,48.38995385169983,-0.0631442036564609,1739502688.1289048,48.38995385169983,75.28628438804753,1739502688.1289074,48.38995385169983,33.020796622544346,1739502688.1289089,48.38995385169983,-0.08972192376052311,1739502688.1289105,48.38995385169983,-3.135986849322853,1739502688.128912,48.38995385169983,-0.43933817377114304,1739502688.1289132,48.38995385169983,-0.1499802233831895,1739502688.1289144,48.38995385169983,1.7591314498834736,1739502688.128916,48.38995385169983,0.0,1739502688.1289175,48.38995385169983,0.24913184838208702,1739502688.1289213,48.38995385169983,3.2399968336696063,1739502688.1289263,48.38995385169983,1.5099996015013866 +1739502688.1481845,48.40995383262634,37.76185436125822,1739502688.1481872,48.40995383262634,-0.0631442036564609,1739502688.1481898,48.40995383262634,75.28628438804753,1739502688.1481922,48.40995383262634,33.020796622544346,1739502688.1481938,48.40995383262634,-0.08972192376052311,1739502688.1481953,48.40995383262634,-3.135986849322853,1739502688.1481967,48.40995383262634,-0.43933817377114304,1739502688.1481984,48.40995383262634,-0.1499802233831895,1739502688.1481998,48.40995383262634,1.7591314498834736,1739502688.1482015,48.40995383262634,0.0,1739502688.1482027,48.40995383262634,0.24913184838208702,1739502688.148204,48.40995383262634,3.2399968336696063,1739502688.1482053,48.40995383262634,1.5099996015013866 +1739502688.1680374,48.429953813552856,37.76185436125822,1739502688.1680398,48.429953813552856,-0.0631442036564609,1739502688.1680422,48.429953813552856,75.28628438804753,1739502688.168045,48.429953813552856,33.020796622544346,1739502688.1680462,48.429953813552856,-0.08972192376052311,1739502688.1680481,48.429953813552856,-3.135986849322853,1739502688.1680493,48.429953813552856,-0.43933817377114304,1739502688.168051,48.429953813552856,-0.1499802233831895,1739502688.1680522,48.429953813552856,1.7591314498834736,1739502688.168054,48.429953813552856,0.0,1739502688.1680553,48.429953813552856,0.24913184838208702,1739502688.1680567,48.429953813552856,3.2399968336696063,1739502688.1680582,48.429953813552856,1.5099996015013866 +1739502688.1955667,48.44995379447937,37.76185436125822,1739502688.1955879,48.44995379447937,-0.0631442036564609,1739502688.1956122,48.44995379447937,75.28628438804753,1739502688.1956394,48.44995379447937,33.020796622544346,1739502688.1956458,48.44995379447937,-0.08972192376052311,1739502688.1956627,48.44995379447937,-3.135986849322853,1739502688.195677,48.44995379447937,-0.43933817377114304,1739502688.1956897,48.44995379447937,-0.1499802233831895,1739502688.1957061,48.44995379447937,1.7591314498834736,1739502688.1957204,48.44995379447937,0.0,1739502688.1957326,48.44995379447937,0.24913184838208702,1739502688.195738,48.44995379447937,3.2399968336696063,1739502688.1957436,48.44995379447937,1.5099996015013866 +1739502688.2201283,48.45995378494263,37.76185436125822,1739502688.2201378,48.45995378494263,-0.0631442036564609,1739502688.2201495,48.45995378494263,75.28628438804753,1739502688.2201595,48.45995378494263,33.020796622544346,1739502688.2201643,48.45995378494263,-0.08972192376052311,1739502688.2201712,48.45995378494263,-3.135986849322853,1739502688.2201765,48.45995378494263,-0.43933817377114304,1739502688.2201812,48.45995378494263,-0.1499802233831895,1739502688.220186,48.45995378494263,1.7591314498834736,1739502688.2201917,48.45995378494263,0.0,1739502688.2201967,48.45995378494263,0.24913184838208702,1739502688.220202,48.45995378494263,3.2399968336696063,1739502688.2202077,48.45995378494263,1.5099996015013866 +1739502688.2377694,48.4899537563324,37.595144512883685,1739502688.2377763,48.4899537563324,-0.07896628616849277,1739502688.2377844,48.4899537563324,75.28946769724915,1739502688.2377918,48.4899537563324,32.96310793582403,1739502688.237795,48.4899537563324,-0.08925291004734978,1739502688.2377994,48.4899537563324,-3.139371901055266,1739502688.237803,48.4899537563324,-0.40676778820639936,1739502688.2378066,48.4899537563324,-0.14548594108789853,1739502688.23781,48.4899537563324,1.8055703067690922,1739502688.237814,48.4899537563324,0.0,1739502688.2378175,48.4899537563324,0.2770376237708286,1739502688.2378213,48.4899537563324,3.231742637218304,1739502688.237825,48.4899537563324,1.5372532435248905 +1739502688.2573013,48.50995373725891,37.595144512883685,1739502688.2573073,48.50995373725891,-0.07896628616849277,1739502688.257315,48.50995373725891,75.28946769724915,1739502688.2573233,48.50995373725891,32.96310793582403,1739502688.257328,48.50995373725891,-0.08925291004734978,1739502688.257334,48.50995373725891,-3.139371901055266,1739502688.2573397,48.50995373725891,-0.40676778820639936,1739502688.257345,48.50995373725891,-0.14548594108789853,1739502688.2573504,48.50995373725891,1.8055703067690922,1739502688.257356,48.50995373725891,0.0,1739502688.2573617,48.50995373725891,0.2683170632442018,1739502688.2573674,48.50995373725891,3.231742637218304,1739502688.2573726,48.50995373725891,1.5372532435248905 +1739502688.272453,48.529953718185425,37.595144512883685,1739502688.2724574,48.529953718185425,-0.07896628616849277,1739502688.2724624,48.529953718185425,75.28946769724915,1739502688.2724683,48.529953718185425,32.96310793582403,1739502688.272471,48.529953718185425,-0.08925291004734978,1739502688.2724755,48.529953718185425,-3.139371901055266,1739502688.272479,48.529953718185425,-0.40676778820639936,1739502688.2724824,48.529953718185425,-0.14548594108789853,1739502688.272486,48.529953718185425,1.8055703067690922,1739502688.2724898,48.529953718185425,0.0,1739502688.2724934,48.529953718185425,0.2683170632442018,1739502688.272497,48.529953718185425,3.231742637218304,1739502688.2725005,48.529953718185425,1.5372532435248905 +1739502688.2896996,48.54995369911194,37.595144512883685,1739502688.2897017,48.54995369911194,-0.07896628616849277,1739502688.2897046,48.54995369911194,75.28946769724915,1739502688.2897072,48.54995369911194,32.96310793582403,1739502688.2897089,48.54995369911194,-0.08925291004734978,1739502688.2897103,48.54995369911194,-3.139371901055266,1739502688.2897117,48.54995369911194,-0.40676778820639936,1739502688.289713,48.54995369911194,-0.14548594108789853,1739502688.2897143,48.54995369911194,1.8055703067690922,1739502688.289716,48.54995369911194,0.0,1739502688.2897172,48.54995369911194,0.2683170632442018,1739502688.2897189,48.54995369911194,3.231742637218304,1739502688.2897203,48.54995369911194,1.5372532435248905 +1739502688.3100135,48.56995368003845,37.595144512883685,1739502688.310016,48.56995368003845,-0.07896628616849277,1739502688.3100197,48.56995368003845,75.28946769724915,1739502688.3100226,48.56995368003845,32.96310793582403,1739502688.3100245,48.56995368003845,-0.08925291004734978,1739502688.3100262,48.56995368003845,-3.139371901055266,1739502688.3100276,48.56995368003845,-0.40676778820639936,1739502688.3100288,48.56995368003845,-0.14548594108789853,1739502688.3100302,48.56995368003845,1.8055703067690922,1739502688.310032,48.56995368003845,0.0,1739502688.310033,48.56995368003845,0.2683170632442018,1739502688.3100348,48.56995368003845,3.231742637218304,1739502688.310036,48.56995368003845,1.5372532435248905 +1739502688.3304222,48.589953660964966,37.42523911895955,1739502688.3304255,48.589953660964966,-0.09368959638497731,1739502688.3304288,48.589953660964966,75.5202192393713,1739502688.3304317,48.589953660964966,32.674077001653494,1739502688.3304334,48.589953660964966,-0.08685723202645589,1739502688.3304353,48.589953660964966,3.1401546139102057,1739502688.330437,48.589953660964966,-0.3962426548034719,1739502688.3304381,48.589953660964966,-0.13471928812584288,1739502688.3304393,48.589953660964966,1.8208375873107578,1739502688.330441,48.589953660964966,0.0,1739502688.3304424,48.589953660964966,0.24813157851073056,1739502688.3304439,48.589953660964966,3.223650612556335,1739502688.3304453,48.589953660964966,1.5663980406849913 +1739502688.3515265,48.60995364189148,37.42523911895955,1739502688.3515294,48.60995364189148,-0.09368959638497731,1739502688.3515334,48.60995364189148,75.5202192393713,1739502688.351536,48.60995364189148,32.674077001653494,1739502688.3515377,48.60995364189148,-0.08685723202645589,1739502688.3515394,48.60995364189148,3.1401546139102057,1739502688.351541,48.60995364189148,-0.3962426548034719,1739502688.3515425,48.60995364189148,-0.13471928812584288,1739502688.351544,48.60995364189148,1.8208375873107578,1739502688.3515456,48.60995364189148,0.0,1739502688.3515472,48.60995364189148,0.2544395466257665,1739502688.3515484,48.60995364189148,3.223650612556335,1739502688.35155,48.60995364189148,1.5663980406849913 +1739502688.370145,48.62995362281799,37.42523911895955,1739502688.3701506,48.62995362281799,-0.09368959638497731,1739502688.3701558,48.62995362281799,75.5202192393713,1739502688.3701613,48.62995362281799,32.674077001653494,1739502688.3701642,48.62995362281799,-0.08685723202645589,1739502688.3701682,48.62995362281799,3.1401546139102057,1739502688.3701715,48.62995362281799,-0.3962426548034719,1739502688.370175,48.62995362281799,-0.13471928812584288,1739502688.3701782,48.62995362281799,1.8208375873107578,1739502688.370182,48.62995362281799,0.0,1739502688.3701854,48.62995362281799,0.2544395466257665,1739502688.3701887,48.62995362281799,3.223650612556335,1739502688.3701923,48.62995362281799,1.5663980406849913 +1739502688.3894053,48.64995360374451,37.42523911895955,1739502688.3894074,48.64995360374451,-0.09368959638497731,1739502688.3894103,48.64995360374451,75.5202192393713,1739502688.3894129,48.64995360374451,32.674077001653494,1739502688.389414,48.64995360374451,-0.08685723202645589,1739502688.389416,48.64995360374451,3.1401546139102057,1739502688.3894172,48.64995360374451,-0.3962426548034719,1739502688.3894188,48.64995360374451,-0.13471928812584288,1739502688.3894198,48.64995360374451,1.8208375873107578,1739502688.3894215,48.64995360374451,0.0,1739502688.389423,48.64995360374451,0.2544395466257665,1739502688.389424,48.64995360374451,3.223650612556335,1739502688.3894258,48.64995360374451,1.5663980406849913 +1739502688.4100733,48.66995358467102,37.42523911895955,1739502688.410076,48.66995358467102,-0.09368959638497731,1739502688.4100788,48.66995358467102,75.5202192393713,1739502688.4100814,48.66995358467102,32.674077001653494,1739502688.4100828,48.66995358467102,-0.08685723202645589,1739502688.4100847,48.66995358467102,3.1401546139102057,1739502688.410086,48.66995358467102,-0.3962426548034719,1739502688.410087,48.66995358467102,-0.13471928812584288,1739502688.4100888,48.66995358467102,1.8208375873107578,1739502688.4100902,48.66995358467102,0.0,1739502688.4100916,48.66995358467102,0.2544395466257665,1739502688.4100935,48.66995358467102,3.223650612556335,1739502688.4100955,48.66995358467102,1.5663980406849913 +1739502688.4297516,48.689953565597534,37.252073608038394,1739502688.429754,48.689953565597534,-0.10730740886600376,1739502688.4297569,48.689953565597534,75.43746212717296,1739502688.4297597,48.689953565597534,32.70110537794488,1739502688.4297612,48.689953565597534,-0.08714601111245866,1739502688.4297628,48.689953565597534,3.137162548864968,1739502688.4297643,48.689953565597534,-0.3580932185669648,1739502688.4297657,48.689953565597534,-0.13269599898564635,1739502688.429767,48.689953565597534,1.8772654254692898,1739502688.4297688,48.689953565597534,0.0,1739502688.42977,48.689953565597534,0.2959876835358784,1739502688.4297712,48.689953565597534,3.2159282579726245,1739502688.4297729,48.689953565597534,1.5942615432306648 +1739502688.4498973,48.70995354652405,37.252073608038394,1739502688.4499002,48.70995354652405,-0.10730740886600376,1739502688.4499032,48.70995354652405,75.43746212717296,1739502688.449906,48.70995354652405,32.70110537794488,1739502688.4499078,48.70995354652405,-0.08714601111245866,1739502688.4499094,48.70995354652405,3.137162548864968,1739502688.449911,48.70995354652405,-0.3580932185669648,1739502688.4499123,48.70995354652405,-0.13269599898564635,1739502688.4499135,48.70995354652405,1.8772654254692898,1739502688.4499156,48.70995354652405,0.0,1739502688.449917,48.70995354652405,0.28300388223862494,1739502688.4499187,48.70995354652405,3.2159282579726245,1739502688.44992,48.70995354652405,1.5942615432306648 +1739502688.4702072,48.72995352745056,37.252073608038394,1739502688.4702098,48.72995352745056,-0.10730740886600376,1739502688.4702132,48.72995352745056,75.43746212717296,1739502688.470216,48.72995352745056,32.70110537794488,1739502688.4702172,48.72995352745056,-0.08714601111245866,1739502688.470219,48.72995352745056,3.137162548864968,1739502688.4702203,48.72995352745056,-0.3580932185669648,1739502688.4702218,48.72995352745056,-0.13269599898564635,1739502688.4702232,48.72995352745056,1.8772654254692898,1739502688.4702249,48.72995352745056,0.0,1739502688.4702263,48.72995352745056,0.28300388223862494,1739502688.4702277,48.72995352745056,3.2159282579726245,1739502688.470229,48.72995352745056,1.5942615432306648 +1739502688.4897664,48.749953508377075,37.252073608038394,1739502688.4897687,48.749953508377075,-0.10730740886600376,1739502688.489772,48.749953508377075,75.43746212717296,1739502688.4897747,48.749953508377075,32.70110537794488,1739502688.4897761,48.749953508377075,-0.08714601111245866,1739502688.4897778,48.749953508377075,3.137162548864968,1739502688.4897795,48.749953508377075,-0.3580932185669648,1739502688.4897807,48.749953508377075,-0.13269599898564635,1739502688.489782,48.749953508377075,1.8772654254692898,1739502688.4897835,48.749953508377075,0.0,1739502688.4897852,48.749953508377075,0.28300388223862494,1739502688.4897866,48.749953508377075,3.2159282579726245,1739502688.4897878,48.749953508377075,1.5942615432306648 +1739502688.5096438,48.76995348930359,37.252073608038394,1739502688.5096464,48.76995348930359,-0.10730740886600376,1739502688.5096495,48.76995348930359,75.43746212717296,1739502688.5096521,48.76995348930359,32.70110537794488,1739502688.5096536,48.76995348930359,-0.08714601111245866,1739502688.5096552,48.76995348930359,3.137162548864968,1739502688.509657,48.76995348930359,-0.3580932185669648,1739502688.509658,48.76995348930359,-0.13269599898564635,1739502688.5096598,48.76995348930359,1.8772654254692898,1739502688.5096614,48.76995348930359,0.0,1739502688.5096633,48.76995348930359,0.28300388223862494,1739502688.509665,48.76995348930359,3.2159282579726245,1739502688.5096672,48.76995348930359,1.5942615432306648 +1739502688.52963,48.7899534702301,37.252073608038394,1739502688.5296323,48.7899534702301,-0.10730740886600376,1739502688.5296357,48.7899534702301,75.43746212717296,1739502688.5296383,48.7899534702301,32.70110537794488,1739502688.5296402,48.7899534702301,-0.08714601111245866,1739502688.5296416,48.7899534702301,3.137162548864968,1739502688.5296433,48.7899534702301,-0.3580932185669648,1739502688.529645,48.7899534702301,-0.13269599898564635,1739502688.5296464,48.7899534702301,1.8772654254692898,1739502688.5296478,48.7899534702301,0.0,1739502688.5296493,48.7899534702301,0.28300388223862494,1739502688.5296504,48.7899534702301,3.2159282579726245,1739502688.5296519,48.7899534702301,1.5942615432306648 +1739502688.549726,48.809953451156616,37.07557307036615,1739502688.5497282,48.809953451156616,-0.11985022904082054,1739502688.5497317,48.809953451156616,75.46884069336288,1739502688.5497344,48.809953451156616,32.607215835323174,1739502688.549736,48.809953451156616,-0.08578745336517075,1739502688.5497377,48.809953451156616,3.133969691930602,1739502688.5497396,48.809953451156616,-0.33273987313837694,1739502688.5497408,48.809953451156616,-0.1279033166930895,1739502688.549742,48.809953451156616,1.915730157712702,1739502688.549744,48.809953451156616,0.0,1739502688.549745,48.809953451156616,0.29348257594900684,1739502688.5497468,48.809953451156616,3.208502332635277,1739502688.5497484,48.809953451156616,1.6255221756951805 +1739502688.5695984,48.82995343208313,37.07557307036615,1739502688.5696013,48.82995343208313,-0.11985022904082054,1739502688.5696042,48.82995343208313,75.46884069336288,1739502688.569607,48.82995343208313,32.607215835323174,1739502688.5696082,48.82995343208313,-0.08578745336517075,1739502688.5696099,48.82995343208313,3.133969691930602,1739502688.5696113,48.82995343208313,-0.33273987313837694,1739502688.5696127,48.82995343208313,-0.1279033166930895,1739502688.5696142,48.82995343208313,1.915730157712702,1739502688.5696156,48.82995343208313,0.0,1739502688.5696168,48.82995343208313,0.2902079820175214,1739502688.5696185,48.82995343208313,3.208502332635277,1739502688.56962,48.82995343208313,1.6255221756951805 +1739502688.603576,48.849953413009644,37.07557307036615,1739502688.603589,48.849953413009644,-0.11985022904082054,1739502688.6036062,48.849953413009644,75.46884069336288,1739502688.6036263,48.849953413009644,32.607215835323174,1739502688.6036372,48.849953413009644,-0.08578745336517075,1739502688.6036515,48.849953413009644,3.133969691930602,1739502688.6036644,48.849953413009644,-0.33273987313837694,1739502688.6036773,48.849953413009644,-0.1279033166930895,1739502688.6036897,48.849953413009644,1.915730157712702,1739502688.6037028,48.849953413009644,0.0,1739502688.6037157,48.849953413009644,0.2902079820175214,1739502688.6037283,48.849953413009644,3.208502332635277,1739502688.6037412,48.849953413009644,1.6255221756951805 +1739502688.620063,48.86995339393616,37.07557307036615,1739502688.6200686,48.86995339393616,-0.11985022904082054,1739502688.6200757,48.86995339393616,75.46884069336288,1739502688.6200845,48.86995339393616,32.607215835323174,1739502688.620089,48.86995339393616,-0.08578745336517075,1739502688.6200955,48.86995339393616,3.133969691930602,1739502688.620101,48.86995339393616,-0.33273987313837694,1739502688.6201062,48.86995339393616,-0.1279033166930895,1739502688.6201117,48.86995339393616,1.915730157712702,1739502688.6201172,48.86995339393616,0.0,1739502688.6201227,48.86995339393616,0.2902079820175214,1739502688.6201282,48.86995339393616,3.208502332635277,1739502688.6201339,48.86995339393616,1.6255221756951805 +1739502688.6378188,48.88995337486267,37.07557307036615,1739502688.6378243,48.88995337486267,-0.11985022904082054,1739502688.6378295,48.88995337486267,75.46884069336288,1739502688.6378324,48.88995337486267,32.607215835323174,1739502688.637834,48.88995337486267,-0.08578745336517075,1739502688.6378355,48.88995337486267,3.133969691930602,1739502688.6378372,48.88995337486267,-0.33273987313837694,1739502688.6378386,48.88995337486267,-0.1279033166930895,1739502688.6378398,48.88995337486267,1.915730157712702,1739502688.6378417,48.88995337486267,0.0,1739502688.637843,48.88995337486267,0.2902079820175214,1739502688.6378443,48.88995337486267,3.208502332635277,1739502688.6378639,48.88995337486267,1.6255221756951805 +1739502688.657289,48.909953355789185,36.895542428509614,1739502688.6572926,48.909953355789185,-0.13131067814431674,1739502688.657297,48.909953355789185,75.57394433159732,1739502688.6573017,48.909953355789185,32.43860374684463,1739502688.6573045,48.909953355789185,-0.084044829974757,1739502688.657308,48.909953355789185,3.130988048112826,1739502688.6573114,48.909953355789185,-0.31277865551394146,1739502688.6573145,48.909953355789185,-0.12084847375126767,1739502688.6573179,48.909953355789185,1.9465679717884043,1739502688.6573212,48.909953355789185,0.0,1739502688.6573243,48.909953355789185,0.28886766021045895,1739502688.6573277,48.909953355789185,3.2012197371807116,1739502688.657331,48.909953355789185,1.6572814607386184 +1739502688.6777816,48.9299533367157,36.895542428509614,1739502688.6777852,48.9299533367157,-0.13131067814431674,1739502688.6777894,48.9299533367157,75.57394433159732,1739502688.6777945,48.9299533367157,32.43860374684463,1739502688.677797,48.9299533367157,-0.084044829974757,1739502688.677801,48.9299533367157,3.130988048112826,1739502688.6778042,48.9299533367157,-0.31277865551394146,1739502688.6778073,48.9299533367157,-0.12084847375126767,1739502688.677811,48.9299533367157,1.9465679717884043,1739502688.6778142,48.9299533367157,0.0,1739502688.6778176,48.9299533367157,0.289286511049786,1739502688.677821,48.9299533367157,3.2012197371807116,1739502688.6778243,48.9299533367157,1.6572814607386184 +1739502688.6973157,48.94995331764221,36.895542428509614,1739502688.6973186,48.94995331764221,-0.13131067814431674,1739502688.697323,48.94995331764221,75.57394433159732,1739502688.6973279,48.94995331764221,32.43860374684463,1739502688.6973307,48.94995331764221,-0.084044829974757,1739502688.6973345,48.94995331764221,3.130988048112826,1739502688.6973376,48.94995331764221,-0.31277865551394146,1739502688.697341,48.94995331764221,-0.12084847375126767,1739502688.6973443,48.94995331764221,1.9465679717884043,1739502688.6973474,48.94995331764221,0.0,1739502688.6973507,48.94995331764221,0.289286511049786,1739502688.697354,48.94995331764221,3.2012197371807116,1739502688.6973574,48.94995331764221,1.6572814607386184 +1739502688.7176511,48.969953298568726,36.895542428509614,1739502688.7176542,48.969953298568726,-0.13131067814431674,1739502688.7176585,48.969953298568726,75.57394433159732,1739502688.7176633,48.969953298568726,32.43860374684463,1739502688.717666,48.969953298568726,-0.084044829974757,1739502688.7176695,48.969953298568726,3.130988048112826,1739502688.7176726,48.969953298568726,-0.31277865551394146,1739502688.7176757,48.969953298568726,-0.12084847375126767,1739502688.7176788,48.969953298568726,1.9465679717884043,1739502688.717682,48.969953298568726,0.0,1739502688.717685,48.969953298568726,0.289286511049786,1739502688.7176883,48.969953298568726,3.2012197371807116,1739502688.7176917,48.969953298568726,1.6572814607386184 +1739502688.7376254,48.98995327949524,36.895542428509614,1739502688.7376287,48.98995327949524,-0.13131067814431674,1739502688.7376332,48.98995327949524,75.57394433159732,1739502688.7376385,48.98995327949524,32.43860374684463,1739502688.7376413,48.98995327949524,-0.084044829974757,1739502688.737645,48.98995327949524,3.130988048112826,1739502688.7376478,48.98995327949524,-0.31277865551394146,1739502688.737651,48.98995327949524,-0.12084847375126767,1739502688.7376542,48.98995327949524,1.9465679717884043,1739502688.7376575,48.98995327949524,0.0,1739502688.737661,48.98995327949524,0.289286511049786,1739502688.7376642,48.98995327949524,3.2012197371807116,1739502688.7376676,48.98995327949524,1.6572814607386184 +1739502688.7569275,49.00995326042175,36.895542428509614,1739502688.7569306,49.00995326042175,-0.13131067814431674,1739502688.756935,49.00995326042175,75.57394433159732,1739502688.7569401,49.00995326042175,32.43860374684463,1739502688.7569427,49.00995326042175,-0.084044829974757,1739502688.7569463,49.00995326042175,3.130988048112826,1739502688.7569494,49.00995326042175,-0.31277865551394146,1739502688.7569528,49.00995326042175,-0.12084847375126767,1739502688.7569559,49.00995326042175,1.9465679717884043,1739502688.7569592,49.00995326042175,0.0,1739502688.7569625,49.00995326042175,0.289286511049786,1739502688.7569659,49.00995326042175,3.2012197371807116,1739502688.7569692,49.00995326042175,1.6572814607386184 +1739502688.7778876,49.02995324134827,36.71194809470455,1739502688.7778912,49.02995324134827,-0.1416796159667877,1739502688.7778952,49.02995324134827,75.77619074463786,1739502688.7779,49.02995324134827,32.17300386362528,1739502688.7779026,49.02995324134827,-0.08203968161784392,1739502688.7779062,49.02995324134827,3.1284538046844927,1739502688.7779095,49.02995324134827,-0.2984371829406371,1739502688.7779126,49.02995324134827,-0.1111810037861213,1739502688.7779157,49.02995324134827,1.9690299011945467,1739502688.7779188,49.02995324134827,0.0,1739502688.7779222,49.02995324134827,0.2758770603113592,1739502688.777925,49.02995324134827,3.194245936410567,1739502688.7779284,49.02995324134827,1.688962384779952 +1739502688.797406,49.04995322227478,36.71194809470455,1739502688.797409,49.04995322227478,-0.1416796159667877,1739502688.7974133,49.04995322227478,75.77619074463786,1739502688.7974184,49.04995322227478,32.17300386362528,1739502688.797421,49.04995322227478,-0.08203968161784392,1739502688.7974246,49.04995322227478,3.1284538046844927,1739502688.797428,49.04995322227478,-0.2984371829406371,1739502688.797431,49.04995322227478,-0.1111810037861213,1739502688.7974343,49.04995322227478,1.9690299011945467,1739502688.7974377,49.04995322227478,0.0,1739502688.7974408,49.04995322227478,0.2800675164145947,1739502688.797444,49.04995322227478,3.194245936410567,1739502688.7974474,49.04995322227478,1.688962384779952 +1739502688.8157682,49.069953203201294,36.71194809470455,1739502688.8157706,49.069953203201294,-0.1416796159667877,1739502688.8157735,49.069953203201294,75.77619074463786,1739502688.815776,49.069953203201294,32.17300386362528,1739502688.8157773,49.069953203201294,-0.08203968161784392,1739502688.8157787,49.069953203201294,3.1284538046844927,1739502688.8157806,49.069953203201294,-0.2984371829406371,1739502688.8157818,49.069953203201294,-0.1111810037861213,1739502688.8157833,49.069953203201294,1.9690299011945467,1739502688.815785,49.069953203201294,0.0,1739502688.8157861,49.069953203201294,0.2800675164145947,1739502688.8157876,49.069953203201294,3.194245936410567,1739502688.8157887,49.069953203201294,1.688962384779952 +1739502688.835405,49.08995318412781,36.71194809470455,1739502688.835407,49.08995318412781,-0.1416796159667877,1739502688.8354099,49.08995318412781,75.77619074463786,1739502688.8354125,49.08995318412781,32.17300386362528,1739502688.8354137,49.08995318412781,-0.08203968161784392,1739502688.8354156,49.08995318412781,3.1284538046844927,1739502688.8354168,49.08995318412781,-0.2984371829406371,1739502688.8354182,49.08995318412781,-0.1111810037861213,1739502688.8354194,49.08995318412781,1.9690299011945467,1739502688.8354208,49.08995318412781,0.0,1739502688.8354223,49.08995318412781,0.2800675164145947,1739502688.8354235,49.08995318412781,3.194245936410567,1739502688.8354251,49.08995318412781,1.688962384779952 +1739502688.8559,49.10995316505432,36.71194809470455,1739502688.8559022,49.10995316505432,-0.1416796159667877,1739502688.8559053,49.10995316505432,75.77619074463786,1739502688.8559082,49.10995316505432,32.17300386362528,1739502688.8559093,49.10995316505432,-0.08203968161784392,1739502688.8559113,49.10995316505432,3.1284538046844927,1739502688.8559124,49.10995316505432,-0.2984371829406371,1739502688.8559136,49.10995316505432,-0.1111810037861213,1739502688.8559148,49.10995316505432,1.9690299011945467,1739502688.8559163,49.10995316505432,0.0,1739502688.8559175,49.10995316505432,0.2800675164145947,1739502688.855919,49.10995316505432,3.194245936410567,1739502688.85592,49.10995316505432,1.688962384779952 +1739502688.8755832,49.129953145980835,36.52484704605236,1739502688.8755856,49.129953145980835,-0.15096114662610471,1739502688.8755884,49.129953145980835,75.98308141227254,1739502688.8755908,49.129953145980835,31.904588408136608,1739502688.8755925,49.129953145980835,-0.07976820206075849,1739502688.8755941,49.129953145980835,3.1261850073030146,1739502688.8755956,49.129953145980835,-0.28354633765050663,1739502688.8755968,49.129953145980835,-0.10194885625009995,1739502688.8755982,49.129953145980835,1.992626587688517,1739502688.8755999,49.129953145980835,0.0,1739502688.875601,49.129953145980835,0.2696376374475629,1739502688.8756025,49.129953145980835,3.1875865283045615,1739502688.875604,49.129953145980835,1.7197296109267672 +1739502688.8959389,49.14995312690735,36.52484704605236,1739502688.895941,49.14995312690735,-0.15096114662610471,1739502688.8959439,49.14995312690735,75.98308141227254,1739502688.8959467,49.14995312690735,31.904588408136608,1739502688.8959482,49.14995312690735,-0.07976820206075849,1739502688.8959498,49.14995312690735,3.1261850073030146,1739502688.8959513,49.14995312690735,-0.28354633765050663,1739502688.8959527,49.14995312690735,-0.10194885625009995,1739502688.895954,49.14995312690735,1.992626587688517,1739502688.8959558,49.14995312690735,0.0,1739502688.895957,49.14995312690735,0.27289697676174973,1739502688.8959584,49.14995312690735,3.1875865283045615,1739502688.89596,49.14995312690735,1.7197296109267672 +1739502688.9155815,49.16995310783386,36.52484704605236,1739502688.9155843,49.16995310783386,-0.15096114662610471,1739502688.9155872,49.16995310783386,75.98308141227254,1739502688.91559,49.16995310783386,31.904588408136608,1739502688.9155915,49.16995310783386,-0.07976820206075849,1739502688.9155934,49.16995310783386,3.1261850073030146,1739502688.915595,49.16995310783386,-0.28354633765050663,1739502688.9155962,49.16995310783386,-0.10194885625009995,1739502688.9155977,49.16995310783386,1.992626587688517,1739502688.915599,49.16995310783386,0.0,1739502688.915601,49.16995310783386,0.27289697676174973,1739502688.9156024,49.16995310783386,3.1875865283045615,1739502688.9156036,49.16995310783386,1.7197296109267672 +1739502688.9361656,49.189953088760376,36.52484704605236,1739502688.9361684,49.189953088760376,-0.15096114662610471,1739502688.9361718,49.189953088760376,75.98308141227254,1739502688.9361746,49.189953088760376,31.904588408136608,1739502688.9361758,49.189953088760376,-0.07976820206075849,1739502688.936178,49.189953088760376,3.1261850073030146,1739502688.9361794,49.189953088760376,-0.28354633765050663,1739502688.9361806,49.189953088760376,-0.10194885625009995,1739502688.9361818,49.189953088760376,1.992626587688517,1739502688.9361832,49.189953088760376,0.0,1739502688.936185,49.189953088760376,0.27289697676174973,1739502688.936186,49.189953088760376,3.1875865283045615,1739502688.9361877,49.189953088760376,1.7197296109267672 +1739502688.9618328,49.21995306015015,36.52484704605236,1739502688.9618351,49.21995306015015,-0.15096114662610471,1739502688.961838,49.21995306015015,75.98308141227254,1739502688.9618406,49.21995306015015,31.904588408136608,1739502688.9618418,49.21995306015015,-0.07976820206075849,1739502688.9618435,49.21995306015015,3.1261850073030146,1739502688.9618447,49.21995306015015,-0.28354633765050663,1739502688.9618464,49.21995306015015,-0.10194885625009995,1739502688.9618473,49.21995306015015,1.992626587688517,1739502688.9618487,49.21995306015015,0.0,1739502688.9618502,49.21995306015015,0.27289697676174973,1739502688.9618514,49.21995306015015,3.1875865283045615,1739502688.9618528,49.21995306015015,1.7197296109267672 +1739502688.9980795,49.24995303153992,36.33436350801378,1739502688.9980834,49.24995303153992,-0.1591835338972345,1739502688.9980884,49.24995303153992,76.32437257633187,1739502688.998094,49.24995303153992,31.5036548496893,1739502688.9980974,49.24995303153992,-0.07665869960385277,1739502688.9981012,49.24995303153992,3.1245109346397677,1739502688.9981053,49.24995303153992,-0.27464647875224113,1739502688.9981086,49.24995303153992,-0.0903348960799647,1739502688.9981122,49.24995303153992,2.0068644900446606,1739502688.998116,49.24995303153992,0.0,1739502688.9981196,49.24995303153992,0.25022138318716275,1739502688.9981234,49.24995303153992,3.1813875841466803,1739502688.9981272,49.24995303153992,1.7495569792194121 +1739502689.0160728,49.26995301246643,36.33436350801378,1739502689.0160756,49.26995301246643,-0.1591835338972345,1739502689.0160792,49.26995301246643,76.32437257633187,1739502689.0160818,49.26995301246643,31.5036548496893,1739502689.0160835,49.26995301246643,-0.07665869960385277,1739502689.0160851,49.26995301246643,3.1245109346397677,1739502689.0160868,49.26995301246643,-0.27464647875224113,1739502689.0160882,49.26995301246643,-0.0903348960799647,1739502689.0160897,49.26995301246643,2.0068644900446606,1739502689.0160916,49.26995301246643,0.0,1739502689.016093,49.26995301246643,0.2573075108252485,1739502689.0160947,49.26995301246643,3.1813875841466803,1739502689.0160966,49.26995301246643,1.7495569792194121 +1739502689.037368,49.289952993392944,36.33436350801378,1739502689.037371,49.289952993392944,-0.1591835338972345,1739502689.0373738,49.289952993392944,76.32437257633187,1739502689.0373764,49.289952993392944,31.5036548496893,1739502689.037378,49.289952993392944,-0.07665869960385277,1739502689.0373797,49.289952993392944,3.1245109346397677,1739502689.0373814,49.289952993392944,-0.27464647875224113,1739502689.0373826,49.289952993392944,-0.0903348960799647,1739502689.037384,49.289952993392944,2.0068644900446606,1739502689.0373855,49.289952993392944,0.0,1739502689.037387,49.289952993392944,0.2573075108252485,1739502689.0373883,49.289952993392944,3.1813875841466803,1739502689.0373898,49.289952993392944,1.7495569792194121 +1739502689.0562284,49.30995297431946,36.33436350801378,1739502689.0562305,49.30995297431946,-0.1591835338972345,1739502689.0562334,49.30995297431946,76.32437257633187,1739502689.0562363,49.30995297431946,31.5036548496893,1739502689.056238,49.30995297431946,-0.07665869960385277,1739502689.0562394,49.30995297431946,3.1245109346397677,1739502689.0562406,49.30995297431946,-0.27464647875224113,1739502689.0562425,49.30995297431946,-0.0903348960799647,1739502689.0562437,49.30995297431946,2.0068644900446606,1739502689.0562456,49.30995297431946,0.0,1739502689.0562468,49.30995297431946,0.2573075108252485,1739502689.0562484,49.30995297431946,3.1813875841466803,1739502689.0562496,49.30995297431946,1.7495569792194121 +1739502689.0763023,49.32995295524597,36.33436350801378,1739502689.0763052,49.32995295524597,-0.1591835338972345,1739502689.0763083,49.32995295524597,76.32437257633187,1739502689.0763118,49.32995295524597,31.5036548496893,1739502689.0763133,49.32995295524597,-0.07665869960385277,1739502689.0763152,49.32995295524597,3.1245109346397677,1739502689.0763168,49.32995295524597,-0.27464647875224113,1739502689.0763187,49.32995295524597,-0.0903348960799647,1739502689.0763202,49.32995295524597,2.0068644900446606,1739502689.076322,49.32995295524597,0.0,1739502689.0763237,49.32995295524597,0.2573075108252485,1739502689.0763254,49.32995295524597,3.1813875841466803,1739502689.076327,49.32995295524597,1.7495569792194121 +1739502689.0955877,49.349952936172485,36.140615005445106,1739502689.0955904,49.349952936172485,-0.16636770405833445,1739502689.0955932,49.349952936172485,76.32844847905596,1739502689.095596,49.349952936172485,31.442836075329016,1739502689.0955975,49.349952936172485,-0.07617981161676389,1739502689.0955992,49.349952936172485,3.122397025981592,1739502689.0956006,49.349952936172485,-0.2494915763173864,1739502689.095602,49.349952936172485,-0.08676624499494895,1739502689.0956037,49.349952936172485,2.0476595762370193,1739502689.0956051,49.349952936172485,0.0,1739502689.0956066,49.349952936172485,0.27537690922269786,1739502689.095608,49.349952936172485,3.175520636570718,1739502689.0956097,49.349952936172485,1.7779293577157833 +1739502689.1153963,49.369952917099,36.140615005445106,1739502689.115399,49.369952917099,-0.16636770405833445,1739502689.115402,49.369952917099,76.32844847905596,1739502689.1154048,49.369952917099,31.442836075329016,1739502689.1154063,49.369952917099,-0.07617981161676389,1739502689.115408,49.369952917099,3.122397025981592,1739502689.1154094,49.369952917099,-0.2494915763173864,1739502689.1154108,49.369952917099,-0.08676624499494895,1739502689.115412,49.369952917099,2.0476595762370193,1739502689.1154137,49.369952917099,0.0,1739502689.1154153,49.369952917099,0.269730218521236,1739502689.1154165,49.369952917099,3.175520636570718,1739502689.1154182,49.369952917099,1.7779293577157833 +1739502689.1357164,49.38995289802551,36.140615005445106,1739502689.1357186,49.38995289802551,-0.16636770405833445,1739502689.1357214,49.38995289802551,76.32844847905596,1739502689.135724,49.38995289802551,31.442836075329016,1739502689.1357255,49.38995289802551,-0.07617981161676389,1739502689.1357276,49.38995289802551,3.122397025981592,1739502689.135729,49.38995289802551,-0.2494915763173864,1739502689.1357305,49.38995289802551,-0.08676624499494895,1739502689.1357317,49.38995289802551,2.0476595762370193,1739502689.1357334,49.38995289802551,0.0,1739502689.1357346,49.38995289802551,0.269730218521236,1739502689.1357358,49.38995289802551,3.175520636570718,1739502689.1357374,49.38995289802551,1.7779293577157833 +1739502689.1557727,49.409952878952026,36.140615005445106,1739502689.155775,49.409952878952026,-0.16636770405833445,1739502689.1557777,49.409952878952026,76.32844847905596,1739502689.1557806,49.409952878952026,31.442836075329016,1739502689.1557817,49.409952878952026,-0.07617981161676389,1739502689.1557834,49.409952878952026,3.122397025981592,1739502689.1557846,49.409952878952026,-0.2494915763173864,1739502689.155786,49.409952878952026,-0.08676624499494895,1739502689.1557872,49.409952878952026,2.0476595762370193,1739502689.155789,49.409952878952026,0.0,1739502689.15579,49.409952878952026,0.269730218521236,1739502689.1557913,49.409952878952026,3.175520636570718,1739502689.1557927,49.409952878952026,1.7779293577157833 +1739502689.1757872,49.42995285987854,36.140615005445106,1739502689.1757896,49.42995285987854,-0.16636770405833445,1739502689.1757925,49.42995285987854,76.32844847905596,1739502689.1757956,49.42995285987854,31.442836075329016,1739502689.1757967,49.42995285987854,-0.07617981161676389,1739502689.1757984,49.42995285987854,3.122397025981592,1739502689.1758,49.42995285987854,-0.2494915763173864,1739502689.1758013,49.42995285987854,-0.08676624499494895,1739502689.1758025,49.42995285987854,2.0476595762370193,1739502689.1758041,49.42995285987854,0.0,1739502689.1758053,49.42995285987854,0.269730218521236,1739502689.1758068,49.42995285987854,3.175520636570718,1739502689.1758084,49.42995285987854,1.7779293577157833 +1739502689.1972868,49.449952840805054,36.140615005445106,1739502689.1972892,49.449952840805054,-0.16636770405833445,1739502689.197292,49.449952840805054,76.32844847905596,1739502689.197295,49.449952840805054,31.442836075329016,1739502689.1972961,49.449952840805054,-0.07617981161676389,1739502689.1972978,49.449952840805054,3.122397025981592,1739502689.1972992,49.449952840805054,-0.2494915763173864,1739502689.1973007,49.449952840805054,-0.08676624499494895,1739502689.197302,49.449952840805054,2.0476595762370193,1739502689.1973035,49.449952840805054,0.0,1739502689.1973047,49.449952840805054,0.269730218521236,1739502689.1973064,49.449952840805054,3.175520636570718,1739502689.1973076,49.449952840805054,1.7779293577157833 +1739502689.2159011,49.46995282173157,35.94364991917917,1739502689.2159035,49.46995282173157,-0.17255950935909414,1739502689.2159064,49.46995282173157,76.62206788529501,1739502689.2159088,49.46995282173157,31.089917761395167,1739502689.2159104,49.46995282173157,-0.0732807549650016,1739502689.2159119,49.46995282173157,3.1211413988559467,1739502689.2159135,49.46995282173157,-0.2373613162039887,1739502689.2159147,49.46995282173157,-0.07732887468496509,1739502689.215916,49.46995282173157,2.0676272192466123,1739502689.2159176,49.46995282173157,0.0,1739502689.2159188,49.46995282173157,0.2556388446026318,1739502689.2159204,49.46995282173157,3.170053518827438,1739502689.2159219,49.46995282173157,1.8075848174072195 +1739502689.235765,49.48995280265808,35.94364991917917,1739502689.2357674,49.48995280265808,-0.17255950935909414,1739502689.2357702,49.48995280265808,76.62206788529501,1739502689.235773,49.48995280265808,31.089917761395167,1739502689.2357745,49.48995280265808,-0.0732807549650016,1739502689.2357762,49.48995280265808,3.1211413988559467,1739502689.2357779,49.48995280265808,-0.2373613162039887,1739502689.235779,49.48995280265808,-0.07732887468496509,1739502689.23578,49.48995280265808,2.0676272192466123,1739502689.235782,49.48995280265808,0.0,1739502689.235783,49.48995280265808,0.26004240183939276,1739502689.2357845,49.48995280265808,3.170053518827438,1739502689.235786,49.48995280265808,1.8075848174072195 +1739502689.2573142,49.509952783584595,35.94364991917917,1739502689.2573178,49.509952783584595,-0.17255950935909414,1739502689.2573225,49.509952783584595,76.62206788529501,1739502689.2573278,49.509952783584595,31.089917761395167,1739502689.2573307,49.509952783584595,-0.0732807549650016,1739502689.2573345,49.509952783584595,3.1211413988559467,1739502689.257338,49.509952783584595,-0.2373613162039887,1739502689.2573414,49.509952783584595,-0.07732887468496509,1739502689.2573447,49.509952783584595,2.0676272192466123,1739502689.2573483,49.509952783584595,0.0,1739502689.2573519,49.509952783584595,0.26004240183939276,1739502689.2573555,49.509952783584595,3.170053518827438,1739502689.2573588,49.509952783584595,1.8075848174072195 +1739502689.277705,49.52995276451111,35.94364991917917,1739502689.2777085,49.52995276451111,-0.17255950935909414,1739502689.277713,49.52995276451111,76.62206788529501,1739502689.2777185,49.52995276451111,31.089917761395167,1739502689.2777214,49.52995276451111,-0.0732807549650016,1739502689.2777252,49.52995276451111,3.1211413988559467,1739502689.2777288,49.52995276451111,-0.2373613162039887,1739502689.2777321,49.52995276451111,-0.07732887468496509,1739502689.2777355,49.52995276451111,2.0676272192466123,1739502689.277739,49.52995276451111,0.0,1739502689.2777424,49.52995276451111,0.26004240183939276,1739502689.277746,49.52995276451111,3.170053518827438,1739502689.2777493,49.52995276451111,1.8075848174072195 +1739502689.2973886,49.54995274543762,35.94364991917917,1739502689.2973917,49.54995274543762,-0.17255950935909414,1739502689.2973955,49.54995274543762,76.62206788529501,1739502689.2974002,49.54995274543762,31.089917761395167,1739502689.2974029,49.54995274543762,-0.0732807549650016,1739502689.2974064,49.54995274543762,3.1211413988559467,1739502689.2974095,49.54995274543762,-0.2373613162039887,1739502689.2974126,49.54995274543762,-0.07732887468496509,1739502689.2974157,49.54995274543762,2.0676272192466123,1739502689.2974188,49.54995274543762,0.0,1739502689.297422,49.54995274543762,0.26004240183939276,1739502689.2974253,49.54995274543762,3.170053518827438,1739502689.2974281,49.54995274543762,1.8075848174072195 +1739502689.317452,49.569952726364136,35.74345759630508,1739502689.3174553,49.569952726364136,-0.1777768494546148,1739502689.3174598,49.569952726364136,76.74296823313404,1739502689.317465,49.569952726364136,30.91209267918774,1739502689.317468,49.569952726364136,-0.072152317568725,1739502689.3174715,49.569952726364136,3.119733880658133,1739502689.3174748,49.569952726364136,-0.2180757509724265,1739502689.3174782,49.569952726364136,-0.07170322335346987,1739502689.3174813,49.569952726364136,2.0997748634394267,1739502689.3174846,49.569952726364136,0.0,1739502689.317488,49.569952726364136,0.26539914642420404,1739502689.317491,49.569952726364136,3.164875931346321,1739502689.3174946,49.569952726364136,1.8360497007955254 +1739502689.3375142,49.58995270729065,35.74345759630508,1739502689.3375177,49.58995270729065,-0.1777768494546148,1739502689.3375432,49.58995270729065,76.74296823313404,1739502689.3375485,49.58995270729065,30.91209267918774,1739502689.3375514,49.58995270729065,-0.072152317568725,1739502689.3375552,49.58995270729065,3.119733880658133,1739502689.3375585,49.58995270729065,-0.2180757509724265,1739502689.3375618,49.58995270729065,-0.07170322335346987,1739502689.3375652,49.58995270729065,2.0997748634394267,1739502689.3375685,49.58995270729065,0.0,1739502689.3375719,49.58995270729065,0.2637251626439012,1739502689.3375752,49.58995270729065,3.164875931346321,1739502689.3375788,49.58995270729065,1.8360497007955254 +1739502689.3571053,49.60995268821716,35.74345759630508,1739502689.357108,49.60995268821716,-0.1777768494546148,1739502689.3571126,49.60995268821716,76.74296823313404,1739502689.3571177,49.60995268821716,30.91209267918774,1739502689.3571203,49.60995268821716,-0.072152317568725,1739502689.357124,49.60995268821716,3.119733880658133,1739502689.3571272,49.60995268821716,-0.2180757509724265,1739502689.3571305,49.60995268821716,-0.07170322335346987,1739502689.3571336,49.60995268821716,2.0997748634394267,1739502689.3571372,49.60995268821716,0.0,1739502689.3571403,49.60995268821716,0.2637251626439012,1739502689.3571436,49.60995268821716,3.164875931346321,1739502689.3571472,49.60995268821716,1.8360497007955254 +1739502689.386181,49.62995266914368,35.74345759630508,1739502689.3861876,49.62995266914368,-0.1777768494546148,1739502689.3862345,49.62995266914368,76.74296823313404,1739502689.3862438,49.62995266914368,30.91209267918774,1739502689.3862474,49.62995266914368,-0.072152317568725,1739502689.386252,49.62995266914368,3.119733880658133,1739502689.3862555,49.62995266914368,-0.2180757509724265,1739502689.3862588,49.62995266914368,-0.07170322335346987,1739502689.3862622,49.62995266914368,2.0997748634394267,1739502689.3862665,49.62995266914368,0.0,1739502689.38627,49.62995266914368,0.2637251626439012,1739502689.3862736,49.62995266914368,3.164875931346321,1739502689.3862774,49.62995266914368,1.8360497007955254 +1739502689.3997617,49.64995265007019,35.74345759630508,1739502689.3997662,49.64995265007019,-0.1777768494546148,1739502689.3997724,49.64995265007019,76.74296823313404,1739502689.3997793,49.64995265007019,30.91209267918774,1739502689.3997834,49.64995265007019,-0.072152317568725,1739502689.3997886,49.64995265007019,3.119733880658133,1739502689.3997931,49.64995265007019,-0.2180757509724265,1739502689.3997977,49.64995265007019,-0.07170322335346987,1739502689.3998022,49.64995265007019,2.0997748634394267,1739502689.399807,49.64995265007019,0.0,1739502689.3998115,49.64995265007019,0.2637251626439012,1739502689.3998163,49.64995265007019,3.164875931346321,1739502689.399821,49.64995265007019,1.8360497007955254 +1739502689.4184744,49.669952630996704,35.74345759630508,1739502689.4184785,49.669952630996704,-0.1777768494546148,1739502689.4184828,49.669952630996704,76.74296823313404,1739502689.4184875,49.669952630996704,30.91209267918774,1739502689.4184902,49.669952630996704,-0.072152317568725,1739502689.418494,49.669952630996704,3.119733880658133,1739502689.418497,49.669952630996704,-0.2180757509724265,1739502689.4185002,49.669952630996704,-0.07170322335346987,1739502689.4185033,49.669952630996704,2.0997748634394267,1739502689.4185069,49.669952630996704,0.0,1739502689.4185097,49.669952630996704,0.2637251626439012,1739502689.4185128,49.669952630996704,3.164875931346321,1739502689.4185162,49.669952630996704,1.8360497007955254 +1739502689.4373972,49.68995261192322,35.54008758103605,1739502689.4374008,49.68995261192322,-0.18206205804852793,1739502689.4374049,49.68995261192322,76.88230901196006,1739502689.4374096,49.68995261192322,30.714930219173013,1739502689.4374123,49.68995261192322,-0.06999890967457831,1739502689.4374156,49.68995261192322,3.118372062442411,1739502689.4374187,49.68995261192322,-0.20112324721994854,1739502689.437422,49.68995261192322,-0.06629726792247938,1739502689.4374251,49.68995261192322,2.1284459959832134,1739502689.4374285,49.68995261192322,0.0,1739502689.4374316,49.68995261192322,0.26336718076538573,1739502689.437435,49.68995261192322,3.1600551101479155,1739502689.437438,49.68995261192322,1.8649669458074443 +1739502689.457021,49.70995259284973,35.54008758103605,1739502689.457024,49.70995259284973,-0.18206205804852793,1739502689.4570284,49.70995259284973,76.88230901196006,1739502689.4570332,49.70995259284973,30.714930219173013,1739502689.4570358,49.70995259284973,-0.06999890967457831,1739502689.457039,49.70995259284973,3.118372062442411,1739502689.4570422,49.70995259284973,-0.20112324721994854,1739502689.4570453,49.70995259284973,-0.06629726792247938,1739502689.4570484,49.70995259284973,2.1284459959832134,1739502689.457052,49.70995259284973,0.0,1739502689.457055,49.70995259284973,0.2634790501757691,1739502689.457058,49.70995259284973,3.1600551101479155,1739502689.457061,49.70995259284973,1.8649669458074443 +1739502689.475904,49.729952573776245,35.54008758103605,1739502689.4759068,49.729952573776245,-0.18206205804852793,1739502689.4759097,49.729952573776245,76.88230901196006,1739502689.475912,49.729952573776245,30.714930219173013,1739502689.4759138,49.729952573776245,-0.06999890967457831,1739502689.4759152,49.729952573776245,3.118372062442411,1739502689.4759169,49.729952573776245,-0.20112324721994854,1739502689.4759183,49.729952573776245,-0.06629726792247938,1739502689.47592,49.729952573776245,2.1284459959832134,1739502689.4759214,49.729952573776245,0.0,1739502689.4759226,49.729952573776245,0.2634790501757691,1739502689.4759243,49.729952573776245,3.1600551101479155,1739502689.4759257,49.729952573776245,1.8649669458074443 +1739502689.4955359,49.74995255470276,35.54008758103605,1739502689.4955387,49.74995255470276,-0.18206205804852793,1739502689.495542,49.74995255470276,76.88230901196006,1739502689.4955447,49.74995255470276,30.714930219173013,1739502689.4955459,49.74995255470276,-0.06999890967457831,1739502689.4955475,49.74995255470276,3.118372062442411,1739502689.4955492,49.74995255470276,-0.20112324721994854,1739502689.4955506,49.74995255470276,-0.06629726792247938,1739502689.4955518,49.74995255470276,2.1284459959832134,1739502689.4955535,49.74995255470276,0.0,1739502689.495555,49.74995255470276,0.2634790501757691,1739502689.495556,49.74995255470276,3.1600551101479155,1739502689.4955575,49.74995255470276,1.8649669458074443 +1739502689.516264,49.76995253562927,35.54008758103605,1739502689.5162666,49.76995253562927,-0.18206205804852793,1739502689.5162692,49.76995253562927,76.88230901196006,1739502689.516272,49.76995253562927,30.714930219173013,1739502689.5162735,49.76995253562927,-0.06999890967457831,1739502689.5162756,49.76995253562927,3.118372062442411,1739502689.516277,49.76995253562927,-0.20112324721994854,1739502689.5162783,49.76995253562927,-0.06629726792247938,1739502689.5162797,49.76995253562927,2.1284459959832134,1739502689.5162816,49.76995253562927,0.0,1739502689.5162828,49.76995253562927,0.2634790501757691,1739502689.5162845,49.76995253562927,3.1600551101479155,1739502689.516286,49.76995253562927,1.8649669458074443 +1739502689.547015,49.789952516555786,35.33352609979971,1739502689.5470233,49.789952516555786,-0.1854384572941319,1739502689.5470338,49.789952516555786,77.18944457704652,1739502689.5470436,49.789952516555786,30.350153287477333,1739502689.5470488,49.789952516555786,-0.06632020600740052,1739502689.5470545,49.789952516555786,3.1176940658106784,1739502689.5470595,49.789952516555786,-0.18821431138968928,1739502689.5470643,49.789952516555786,-0.058165386040273354,1739502689.547069,49.789952516555786,2.150540665308852,1739502689.5470748,49.789952516555786,0.0,1739502689.5470796,49.789952516555786,0.25367997714832574,1739502689.5470848,49.789952516555786,3.155460716914593,1739502689.5470896,49.789952516555786,1.8937984758317072 +1739502689.5628347,49.8099524974823,35.33352609979971,1739502689.5628433,49.8099524974823,-0.1854384572941319,1739502689.5628538,49.8099524974823,77.18944457704652,1739502689.5628638,49.8099524974823,30.350153287477333,1739502689.562869,49.8099524974823,-0.06632020600740052,1739502689.5628755,49.8099524974823,3.1176940658106784,1739502689.5628808,49.8099524974823,-0.18821431138968928,1739502689.562886,49.8099524974823,-0.058165386040273354,1739502689.5628905,49.8099524974823,2.150540665308852,1739502689.5628965,49.8099524974823,0.0,1739502689.5629013,49.8099524974823,0.25674218947714467,1739502689.5629067,49.8099524974823,3.155460716914593,1739502689.5629117,49.8099524974823,1.8937984758317072 +1739502689.586507,49.83995246887207,35.33352609979971,1739502689.5865126,49.83995246887207,-0.1854384572941319,1739502689.58652,49.83995246887207,77.18944457704652,1739502689.5865273,49.83995246887207,30.350153287477333,1739502689.5865304,49.83995246887207,-0.06632020600740052,1739502689.5865352,49.83995246887207,3.1176940658106784,1739502689.5865388,49.83995246887207,-0.18821431138968928,1739502689.5865426,49.83995246887207,-0.058165386040273354,1739502689.586546,49.83995246887207,2.150540665308852,1739502689.5865498,49.83995246887207,0.0,1739502689.5865533,49.83995246887207,0.25674218947714467,1739502689.586557,49.83995246887207,3.155460716914593,1739502689.5865605,49.83995246887207,1.8937984758317072 +1739502689.6064224,49.859952449798584,35.33352609979971,1739502689.6064272,49.859952449798584,-0.1854384572941319,1739502689.6064327,49.859952449798584,77.18944457704652,1739502689.6064382,49.859952449798584,30.350153287477333,1739502689.6064408,49.859952449798584,-0.06632020600740052,1739502689.6064441,49.859952449798584,3.1176940658106784,1739502689.6064467,49.859952449798584,-0.18821431138968928,1739502689.6064494,49.859952449798584,-0.058165386040273354,1739502689.606452,49.859952449798584,2.150540665308852,1739502689.606455,49.859952449798584,0.0,1739502689.6064577,49.859952449798584,0.25674218947714467,1739502689.6064603,49.859952449798584,3.155460716914593,1739502689.6064632,49.859952449798584,1.8937984758317072 +1739502689.6256824,49.8799524307251,35.33352609979971,1739502689.6256866,49.8799524307251,-0.1854384572941319,1739502689.6256912,49.8799524307251,77.18944457704652,1739502689.6256952,49.8799524307251,30.350153287477333,1739502689.6256974,49.8799524307251,-0.06632020600740052,1739502689.6256998,49.8799524307251,3.1176940658106784,1739502689.6257021,49.8799524307251,-0.18821431138968928,1739502689.6257043,49.8799524307251,-0.058165386040273354,1739502689.6257062,49.8799524307251,2.150540665308852,1739502689.625709,49.8799524307251,0.0,1739502689.6257117,49.8799524307251,0.25674218947714467,1739502689.6257136,49.8799524307251,3.155460716914593,1739502689.625716,49.8799524307251,1.8937984758317072 +1739502689.6459785,49.89995241165161,35.123813401798905,1739502689.645982,49.89995241165161,-0.18792858712060845,1739502689.6459866,49.89995241165161,77.41360411192062,1739502689.6459908,49.89995241165161,30.069751925798414,1739502689.6459932,49.89995241165161,-0.06347869709921253,1739502689.6459959,49.89995241165161,3.116973889601074,1739502689.645998,49.89995241165161,-0.17279249514032632,1739502689.6460001,49.89995241165161,-0.05191566893712006,1739502689.6460023,49.89995241165161,2.1772372047120543,1739502689.6460044,49.89995241165161,0.0,1739502689.6460066,49.89995241165161,0.2546586192180036,1739502689.6460087,49.89995241165161,3.1511590265545477,1739502689.646011,49.89995241165161,1.921927469361164 +1739502689.66635,49.919952392578125,35.123813401798905,1739502689.6663535,49.919952392578125,-0.18792858712060845,1739502689.6663582,49.919952392578125,77.41360411192062,1739502689.6663623,49.919952392578125,30.069751925798414,1739502689.6663647,49.919952392578125,-0.06347869709921253,1739502689.6663673,49.919952392578125,3.116973889601074,1739502689.6663694,49.919952392578125,-0.17279249514032632,1739502689.6663716,49.919952392578125,-0.05191566893712006,1739502689.666374,49.919952392578125,2.1772372047120543,1739502689.6663764,49.919952392578125,0.0,1739502689.6663785,49.919952392578125,0.2553097353508902,1739502689.666381,49.919952392578125,3.1511590265545477,1739502689.6663828,49.919952392578125,1.921927469361164 +1739502689.6844091,49.93995237350464,35.123813401798905,1739502689.6844118,49.93995237350464,-0.18792858712060845,1739502689.6844149,49.93995237350464,77.41360411192062,1739502689.684418,49.93995237350464,30.069751925798414,1739502689.6844196,49.93995237350464,-0.06347869709921253,1739502689.6844215,49.93995237350464,3.116973889601074,1739502689.6844234,49.93995237350464,-0.17279249514032632,1739502689.6844249,49.93995237350464,-0.05191566893712006,1739502689.6844265,49.93995237350464,2.1772372047120543,1739502689.6844285,49.93995237350464,0.0,1739502689.68443,49.93995237350464,0.2553097353508902,1739502689.6844316,49.93995237350464,3.1511590265545477,1739502689.6844332,49.93995237350464,1.921927469361164 +1739502689.7042494,49.95995235443115,35.123813401798905,1739502689.7042518,49.95995235443115,-0.18792858712060845,1739502689.7042544,49.95995235443115,77.41360411192062,1739502689.704257,49.95995235443115,30.069751925798414,1739502689.7042582,49.95995235443115,-0.06347869709921253,1739502689.70426,49.95995235443115,3.116973889601074,1739502689.7042615,49.95995235443115,-0.17279249514032632,1739502689.704263,49.95995235443115,-0.05191566893712006,1739502689.7042642,49.95995235443115,2.1772372047120543,1739502689.7042658,49.95995235443115,0.0,1739502689.704267,49.95995235443115,0.2553097353508902,1739502689.7042682,49.95995235443115,3.1511590265545477,1739502689.7042696,49.95995235443115,1.921927469361164 +1739502689.727383,49.979952335357666,35.123813401798905,1739502689.727388,49.979952335357666,-0.18792858712060845,1739502689.727394,49.979952335357666,77.41360411192062,1739502689.7273996,49.979952335357666,30.069751925798414,1739502689.7274024,49.979952335357666,-0.06347869709921253,1739502689.727406,49.979952335357666,3.116973889601074,1739502689.7274091,49.979952335357666,-0.17279249514032632,1739502689.727412,49.979952335357666,-0.05191566893712006,1739502689.7274146,49.979952335357666,2.1772372047120543,1739502689.727418,49.979952335357666,0.0,1739502689.727421,49.979952335357666,0.2553097353508902,1739502689.727424,49.979952335357666,3.1511590265545477,1739502689.7274272,49.979952335357666,1.921927469361164 +1739502689.7449443,49.99995231628418,35.123813401798905,1739502689.7449474,49.99995231628418,-0.18792858712060845,1739502689.7449512,49.99995231628418,77.41360411192062,1739502689.7449546,49.99995231628418,30.069751925798414,1739502689.7449567,49.99995231628418,-0.06347869709921253,1739502689.7449586,49.99995231628418,3.116973889601074,1739502689.7449605,49.99995231628418,-0.17279249514032632,1739502689.744962,49.99995231628418,-0.05191566893712006,1739502689.7449636,49.99995231628418,2.1772372047120543,1739502689.744966,49.99995231628418,0.0,1739502689.7449677,49.99995231628418,0.2553097353508902,1739502689.7449694,49.99995231628418,3.1511590265545477,1739502689.7449713,49.99995231628418,1.921927469361164 +1739502689.7681718,50.01995229721069,34.91100862753623,1739502689.7681768,50.01995229721069,-0.1895731496161419,1739502689.7681832,50.01995229721069,77.44878282789055,1739502689.7681892,50.01995229721069,29.978681869792425,1739502689.7681918,50.01995229721069,-0.06276914858104271,1739502689.7681956,50.01995229721069,3.115889556104488,1739502689.7681985,50.01995229721069,-0.15427954692210352,1739502689.768201,50.01995229721069,-0.04866770269781849,1739502689.768204,50.01995229721069,2.209722836544501,1739502689.7682073,50.01995229721069,0.0,1739502689.7682102,50.01995229721069,0.2619113077850946,1739502689.768213,50.01995229721069,3.147163585334509,1739502689.768216,50.01995229721069,1.9498745214976987 +1739502689.7847745,50.03995227813721,34.91100862753623,1739502689.7847788,50.03995227813721,-0.1895731496161419,1739502689.7847831,50.03995227813721,77.44878282789055,1739502689.7847872,50.03995227813721,29.978681869792425,1739502689.784789,50.03995227813721,-0.06276914858104271,1739502689.7847912,50.03995227813721,3.115889556104488,1739502689.784793,50.03995227813721,-0.15427954692210352,1739502689.7847946,50.03995227813721,-0.04866770269781849,1739502689.7847962,50.03995227813721,2.209722836544501,1739502689.784798,50.03995227813721,0.0,1739502689.7848,50.03995227813721,0.2598483150468023,1739502689.784802,50.03995227813721,3.147163585334509,1739502689.7848039,50.03995227813721,1.9498745214976987 +1739502689.804338,50.05995225906372,34.91100862753623,1739502689.8043401,50.05995225906372,-0.1895731496161419,1739502689.804343,50.05995225906372,77.44878282789055,1739502689.8043456,50.05995225906372,29.978681869792425,1739502689.8043468,50.05995225906372,-0.06276914858104271,1739502689.8043487,50.05995225906372,3.115889556104488,1739502689.80435,50.05995225906372,-0.15427954692210352,1739502689.8043513,50.05995225906372,-0.04866770269781849,1739502689.8043525,50.05995225906372,2.209722836544501,1739502689.804354,50.05995225906372,0.0,1739502689.8043554,50.05995225906372,0.2598483150468023,1739502689.8043566,50.05995225906372,3.147163585334509,1739502689.804358,50.05995225906372,1.9498745214976987 +1739502689.8248937,50.079952239990234,34.91100862753623,1739502689.8248963,50.079952239990234,-0.1895731496161419,1739502689.8248994,50.079952239990234,77.44878282789055,1739502689.8249018,50.079952239990234,29.978681869792425,1739502689.8249032,50.079952239990234,-0.06276914858104271,1739502689.8249047,50.079952239990234,3.115889556104488,1739502689.8249059,50.079952239990234,-0.15427954692210352,1739502689.8249073,50.079952239990234,-0.04866770269781849,1739502689.8249085,50.079952239990234,2.209722836544501,1739502689.8249102,50.079952239990234,0.0,1739502689.824911,50.079952239990234,0.2598483150468023,1739502689.8249125,50.079952239990234,3.147163585334509,1739502689.824914,50.079952239990234,1.9498745214976987 +1739502689.8443222,50.09995222091675,34.91100862753623,1739502689.8443244,50.09995222091675,-0.1895731496161419,1739502689.8443272,50.09995222091675,77.44878282789055,1739502689.8443298,50.09995222091675,29.978681869792425,1739502689.844331,50.09995222091675,-0.06276914858104271,1739502689.8443327,50.09995222091675,3.115889556104488,1739502689.8443341,50.09995222091675,-0.15427954692210352,1739502689.8443353,50.09995222091675,-0.04866770269781849,1739502689.8443367,50.09995222091675,2.209722836544501,1739502689.8443384,50.09995222091675,0.0,1739502689.8443396,50.09995222091675,0.2598483150468023,1739502689.8443413,50.09995222091675,3.147163585334509,1739502689.8443425,50.09995222091675,1.9498745214976987 +1739502689.8647738,50.11995220184326,34.69510227372672,1739502689.8647761,50.11995220184326,-0.19039658738715914,1739502689.8647792,50.11995220184326,77.72242867794583,1739502689.8647826,50.11995220184326,29.648200639415304,1739502689.8647838,50.11995220184326,-0.05943637009510408,1739502689.8647854,50.11995220184326,3.1156498384877604,1739502689.8647866,50.11995220184326,-0.13977516036765456,1739502689.8647883,50.11995220184326,-0.04211343673079831,1739502689.8647895,50.11995220184326,2.2355127130745704,1739502689.8647912,50.11995220184326,0.0,1739502689.8647923,50.11995220184326,0.256011631831452,1739502689.8647935,50.11995220184326,3.143339298949896,1739502689.8647952,50.11995220184326,1.9783021169522192 +1739502689.8841782,50.139952182769775,34.69510227372672,1739502689.8841808,50.139952182769775,-0.19039658738715914,1739502689.8841836,50.139952182769775,77.72242867794583,1739502689.8841863,50.139952182769775,29.648200639415304,1739502689.8841877,50.139952182769775,-0.05943637009510408,1739502689.8841894,50.139952182769775,3.1156498384877604,1739502689.8841908,50.139952182769775,-0.13977516036765456,1739502689.884192,50.139952182769775,-0.04211343673079831,1739502689.8841932,50.139952182769775,2.2355127130745704,1739502689.884195,50.139952182769775,0.0,1739502689.8841963,50.139952182769775,0.2572105961223512,1739502689.8841977,50.139952182769775,3.143339298949896,1739502689.884199,50.139952182769775,1.9783021169522192 +1739502689.9043543,50.15995216369629,34.69510227372672,1739502689.9043572,50.15995216369629,-0.19039658738715914,1739502689.9043603,50.15995216369629,77.72242867794583,1739502689.9043636,50.15995216369629,29.648200639415304,1739502689.9043648,50.15995216369629,-0.05943637009510408,1739502689.9043663,50.15995216369629,3.1156498384877604,1739502689.904368,50.15995216369629,-0.13977516036765456,1739502689.904369,50.15995216369629,-0.04211343673079831,1739502689.9043705,50.15995216369629,2.2355127130745704,1739502689.904372,50.15995216369629,0.0,1739502689.9043732,50.15995216369629,0.2572105961223512,1739502689.904375,50.15995216369629,3.143339298949896,1739502689.9043763,50.15995216369629,1.9783021169522192 +1739502689.9243836,50.1799521446228,34.69510227372672,1739502689.924386,50.1799521446228,-0.19039658738715914,1739502689.924389,50.1799521446228,77.72242867794583,1739502689.9243917,50.1799521446228,29.648200639415304,1739502689.924393,50.1799521446228,-0.05943637009510408,1739502689.9243948,50.1799521446228,3.1156498384877604,1739502689.9243963,50.1799521446228,-0.13977516036765456,1739502689.9243975,50.1799521446228,-0.04211343673079831,1739502689.9243991,50.1799521446228,2.2355127130745704,1739502689.9244006,50.1799521446228,0.0,1739502689.924402,50.1799521446228,0.2572105961223512,1739502689.9244032,50.1799521446228,3.143339298949896,1739502689.9244046,50.1799521446228,1.9783021169522192 +1739502689.9444005,50.199952125549316,34.69510227372672,1739502689.9444027,50.199952125549316,-0.19039658738715914,1739502689.9444056,50.199952125549316,77.72242867794583,1739502689.9444084,50.199952125549316,29.648200639415304,1739502689.9444096,50.199952125549316,-0.05943637009510408,1739502689.944411,50.199952125549316,3.1156498384877604,1739502689.9444125,50.199952125549316,-0.13977516036765456,1739502689.9444137,50.199952125549316,-0.04211343673079831,1739502689.944415,50.199952125549316,2.2355127130745704,1739502689.9444165,50.199952125549316,0.0,1739502689.9444177,50.199952125549316,0.2572105961223512,1739502689.9444191,50.199952125549316,3.143339298949896,1739502689.9444203,50.199952125549316,1.9783021169522192 +1739502689.964969,50.21995210647583,34.69510227372672,1739502689.9649715,50.21995210647583,-0.19039658738715914,1739502689.9649744,50.21995210647583,77.72242867794583,1739502689.9649768,50.21995210647583,29.648200639415304,1739502689.9649782,50.21995210647583,-0.05943637009510408,1739502689.96498,50.21995210647583,3.1156498384877604,1739502689.9649816,50.21995210647583,-0.13977516036765456,1739502689.9649827,50.21995210647583,-0.04211343673079831,1739502689.9649837,50.21995210647583,2.2355127130745704,1739502689.9649856,50.21995210647583,0.0,1739502689.9649866,50.21995210647583,0.2572105961223512,1739502689.9649882,50.21995210647583,3.143339298949896,1739502689.9649894,50.21995210647583,1.9783021169522192 +1739502689.9841726,50.239952087402344,34.476080565423295,1739502689.9841754,50.239952087402344,-0.1904203695067439,1739502689.984179,50.239952087402344,77.99514065593482,1739502689.9841814,50.239952087402344,29.31921236352199,1739502689.984183,50.239952087402344,-0.05732670037586979,1739502689.9841845,50.239952087402344,3.115789370614402,1739502689.9841864,50.239952087402344,-0.12386870104941357,1739502689.9841878,50.239952087402344,-0.035747114805832765,1739502689.9841893,50.239952087402344,2.2641417550481533,1739502689.9841907,50.239952087402344,0.0,1739502689.9841924,50.239952087402344,0.25791789803507964,1739502689.9841936,50.239952087402344,3.139803823684501,1739502689.984195,50.239952087402344,2.006444889005721 +1739502690.004252,50.25995206832886,34.476080565423295,1739502690.004254,50.25995206832886,-0.1904203695067439,1739502690.0042574,50.25995206832886,77.99514065593482,1739502690.00426,50.25995206832886,29.31921236352199,1739502690.0042615,50.25995206832886,-0.05732670037586979,1739502690.0042632,50.25995206832886,3.115789370614402,1739502690.0042644,50.25995206832886,-0.12386870104941357,1739502690.004266,50.25995206832886,-0.035747114805832765,1739502690.0042672,50.25995206832886,2.2641417550481533,1739502690.004269,50.25995206832886,0.0,1739502690.00427,50.25995206832886,0.25769686604243214,1739502690.0042713,50.25995206832886,3.139803823684501,1739502690.004273,50.25995206832886,2.006444889005721 +1739502690.0241,50.27995204925537,34.476080565423295,1739502690.024103,50.27995204925537,-0.1904203695067439,1739502690.0241063,50.27995204925537,77.99514065593482,1739502690.024109,50.27995204925537,29.31921236352199,1739502690.02411,50.27995204925537,-0.05732670037586979,1739502690.0241115,50.27995204925537,3.115789370614402,1739502690.0241132,50.27995204925537,-0.12386870104941357,1739502690.0241144,50.27995204925537,-0.035747114805832765,1739502690.0241156,50.27995204925537,2.2641417550481533,1739502690.0241172,50.27995204925537,0.0,1739502690.0241184,50.27995204925537,0.25769686604243214,1739502690.02412,50.27995204925537,3.139803823684501,1739502690.0241215,50.27995204925537,2.006444889005721 +1739502690.0441673,50.299952030181885,34.476080565423295,1739502690.0441709,50.299952030181885,-0.1904203695067439,1739502690.0441735,50.299952030181885,77.99514065593482,1739502690.044176,50.299952030181885,29.31921236352199,1739502690.0441778,50.299952030181885,-0.05732670037586979,1739502690.0441794,50.299952030181885,3.115789370614402,1739502690.0441806,50.299952030181885,-0.12386870104941357,1739502690.0441825,50.299952030181885,-0.035747114805832765,1739502690.0441837,50.299952030181885,2.2641417550481533,1739502690.0441856,50.299952030181885,0.0,1739502690.0441868,50.299952030181885,0.25769686604243214,1739502690.0441885,50.299952030181885,3.139803823684501,1739502690.0441897,50.299952030181885,2.006444889005721 +1739502690.0640304,50.3199520111084,34.476080565423295,1739502690.064033,50.3199520111084,-0.1904203695067439,1739502690.064036,50.3199520111084,77.99514065593482,1739502690.0640385,50.3199520111084,29.31921236352199,1739502690.0640397,50.3199520111084,-0.05732670037586979,1739502690.0640414,50.3199520111084,3.115789370614402,1739502690.0640428,50.3199520111084,-0.12386870104941357,1739502690.064044,50.3199520111084,-0.035747114805832765,1739502690.0640454,50.3199520111084,2.2641417550481533,1739502690.0640469,50.3199520111084,0.0,1739502690.064048,50.3199520111084,0.25769686604243214,1739502690.0640495,50.3199520111084,3.139803823684501,1739502690.0640507,50.3199520111084,2.006444889005721 +1739502690.0842729,50.33995199203491,34.25396206853528,1739502690.0842755,50.33995199203491,-0.18968535461211466,1739502690.084278,50.33995199203491,78.22520451277626,1739502690.0842807,50.33995199203491,29.032770539544124,1739502690.0842822,50.33995199203491,-0.055065298651631296,1739502690.0842838,50.33995199203491,3.1158149673971596,1739502690.0842853,50.33995199203491,-0.10812851297017546,1739502690.0842865,50.33995199203491,-0.030440983487960108,1739502690.0842876,50.33995199203491,2.292832428231159,1739502690.0842893,50.33995199203491,0.0,1739502690.0842905,50.33995199203491,0.2584200072232452,1739502690.0842922,50.33995199203491,3.1365191135984665,1739502690.0842934,50.33995199203491,2.0346384027750832 +1739502690.1040852,50.359951972961426,34.25396206853528,1739502690.1040878,50.359951972961426,-0.18968535461211466,1739502690.1040905,50.359951972961426,78.22520451277626,1739502690.104093,50.359951972961426,29.032770539544124,1739502690.1040945,50.359951972961426,-0.055065298651631296,1739502690.1040962,50.359951972961426,3.1158149673971596,1739502690.1040976,50.359951972961426,-0.10812851297017546,1739502690.1040988,50.359951972961426,-0.030440983487960108,1739502690.1041,50.359951972961426,2.292832428231159,1739502690.104102,50.359951972961426,0.0,1739502690.104103,50.359951972961426,0.25819402545607595,1739502690.1041045,50.359951972961426,3.1365191135984665,1739502690.104106,50.359951972961426,2.0346384027750832 +1739502690.123994,50.37995195388794,34.25396206853528,1739502690.1239963,50.37995195388794,-0.18968535461211466,1739502690.1239989,50.37995195388794,78.22520451277626,1739502690.1240015,50.37995195388794,29.032770539544124,1739502690.124003,50.37995195388794,-0.055065298651631296,1739502690.1240046,50.37995195388794,3.1158149673971596,1739502690.1240058,50.37995195388794,-0.10812851297017546,1739502690.1240072,50.37995195388794,-0.030440983487960108,1739502690.1240084,50.37995195388794,2.292832428231159,1739502690.1240103,50.37995195388794,0.0,1739502690.1240115,50.37995195388794,0.25819402545607595,1739502690.1240127,50.37995195388794,3.1365191135984665,1739502690.1240141,50.37995195388794,2.0346384027750832 +1739502690.144044,50.39995193481445,34.25396206853528,1739502690.1440465,50.39995193481445,-0.18968535461211466,1739502690.1440494,50.39995193481445,78.22520451277626,1739502690.1440523,50.39995193481445,29.032770539544124,1739502690.1440535,50.39995193481445,-0.055065298651631296,1739502690.1440556,50.39995193481445,3.1158149673971596,1739502690.1440568,50.39995193481445,-0.10812851297017546,1739502690.1440585,50.39995193481445,-0.030440983487960108,1739502690.1440597,50.39995193481445,2.292832428231159,1739502690.144061,50.39995193481445,0.0,1739502690.1440625,50.39995193481445,0.25819402545607595,1739502690.144064,50.39995193481445,3.1365191135984665,1739502690.1440654,50.39995193481445,2.0346384027750832 +1739502690.1641955,50.41995191574097,34.25396206853528,1739502690.1641982,50.41995191574097,-0.18968535461211466,1739502690.1642013,50.41995191574097,78.22520451277626,1739502690.1642041,50.41995191574097,29.032770539544124,1739502690.1642053,50.41995191574097,-0.055065298651631296,1739502690.1642072,50.41995191574097,3.1158149673971596,1739502690.1642087,50.41995191574097,-0.10812851297017546,1739502690.1642098,50.41995191574097,-0.030440983487960108,1739502690.1642113,50.41995191574097,2.292832428231159,1739502690.1642127,50.41995191574097,0.0,1739502690.1642141,50.41995191574097,0.25819402545607595,1739502690.1642158,50.41995191574097,3.1365191135984665,1739502690.164217,50.41995191574097,2.0346384027750832 +1739502690.1841202,50.43995189666748,34.25396206853528,1739502690.1841226,50.43995189666748,-0.18968535461211466,1739502690.1841257,50.43995189666748,78.22520451277626,1739502690.1841285,50.43995189666748,29.032770539544124,1739502690.18413,50.43995189666748,-0.055065298651631296,1739502690.1841319,50.43995189666748,3.1158149673971596,1739502690.184133,50.43995189666748,-0.10812851297017546,1739502690.1841345,50.43995189666748,-0.030440983487960108,1739502690.184136,50.43995189666748,2.292832428231159,1739502690.1841376,50.43995189666748,0.0,1739502690.1841388,50.43995189666748,0.25819402545607595,1739502690.18414,50.43995189666748,3.1365191135984665,1739502690.1841416,50.43995189666748,2.0346384027750832 +1739502690.2041242,50.459951877593994,34.02874000583172,1739502690.2041264,50.459951877593994,-0.18822877890861456,1739502690.2041292,50.459951877593994,78.45649230998134,1739502690.204132,50.459951877593994,28.74493891538172,1739502690.2041333,50.459951877593994,-0.0526148625246301,1739502690.2041352,50.459951877593994,3.1159323102845815,1739502690.2041364,50.459951877593994,-0.09284349709081698,1739502690.204138,50.459951877593994,-0.02552250621606478,1739502690.204139,50.459951877593994,2.321041330204237,1739502690.2041411,50.459951877593994,0.0,1739502690.2041423,50.459951877593994,0.25809478625174936,1739502690.2041435,50.459951877593994,3.1334987750664545,1739502690.204145,50.459951877593994,2.0629155316808023 +1739502690.2241273,50.47995185852051,34.02874000583172,1739502690.2241294,50.47995185852051,-0.18822877890861456,1739502690.224132,50.47995185852051,78.45649230998134,1739502690.224135,50.47995185852051,28.74493891538172,1739502690.224136,50.47995185852051,-0.0526148625246301,1739502690.2241378,50.47995185852051,3.1159323102845815,1739502690.224139,50.47995185852051,-0.09284349709081698,1739502690.2241404,50.47995185852051,-0.02552250621606478,1739502690.2241416,50.47995185852051,2.321041330204237,1739502690.224143,50.47995185852051,0.0,1739502690.2241445,50.47995185852051,0.25812579852343465,1739502690.2241457,50.47995185852051,3.1334987750664545,1739502690.224147,50.47995185852051,2.0629155316808023 +1739502690.244173,50.49995183944702,34.02874000583172,1739502690.244176,50.49995183944702,-0.18822877890861456,1739502690.244179,50.49995183944702,78.45649230998134,1739502690.2441814,50.49995183944702,28.74493891538172,1739502690.244183,50.49995183944702,-0.0526148625246301,1739502690.2441847,50.49995183944702,3.1159323102845815,1739502690.2441862,50.49995183944702,-0.09284349709081698,1739502690.2441874,50.49995183944702,-0.02552250621606478,1739502690.2441888,50.49995183944702,2.321041330204237,1739502690.2441905,50.49995183944702,0.0,1739502690.2441916,50.49995183944702,0.25812579852343465,1739502690.244193,50.49995183944702,3.1334987750664545,1739502690.2441943,50.49995183944702,2.0629155316808023 +1739502690.2642882,50.519951820373535,34.02874000583172,1739502690.2642908,50.519951820373535,-0.18822877890861456,1739502690.2642941,50.519951820373535,78.45649230998134,1739502690.2642968,50.519951820373535,28.74493891538172,1739502690.264298,50.519951820373535,-0.0526148625246301,1739502690.2642999,50.519951820373535,3.1159323102845815,1739502690.264301,50.519951820373535,-0.09284349709081698,1739502690.2643025,50.519951820373535,-0.02552250621606478,1739502690.264304,50.519951820373535,2.321041330204237,1739502690.2643054,50.519951820373535,0.0,1739502690.2643068,50.519951820373535,0.25812579852343465,1739502690.2643082,50.519951820373535,3.1334987750664545,1739502690.2643094,50.519951820373535,2.0629155316808023 +1739502690.2841313,50.53995180130005,34.02874000583172,1739502690.2841341,50.53995180130005,-0.18822877890861456,1739502690.2841368,50.53995180130005,78.45649230998134,1739502690.2841396,50.53995180130005,28.74493891538172,1739502690.284141,50.53995180130005,-0.0526148625246301,1739502690.2841425,50.53995180130005,3.1159323102845815,1739502690.2841442,50.53995180130005,-0.09284349709081698,1739502690.2841454,50.53995180130005,-0.02552250621606478,1739502690.2841468,50.53995180130005,2.321041330204237,1739502690.2841482,50.53995180130005,0.0,1739502690.2841494,50.53995180130005,0.25812579852343465,1739502690.284151,50.53995180130005,3.1334987750664545,1739502690.2841525,50.53995180130005,2.0629155316808023 +1739502690.3039985,50.55995178222656,33.800416217154975,1739502690.3040006,50.55995178222656,-0.18608077825336888,1739502690.3040032,50.55995178222656,78.60082885108949,1739502690.304006,50.55995178222656,28.54412759119331,1739502690.3040075,50.55995178222656,-0.0518880660103766,1739502690.304009,50.55995178222656,3.1160682620307636,1739502690.3040104,50.55995178222656,-0.0766509208079497,1739502690.3040118,50.55995178222656,-0.021292660198404534,1739502690.304013,50.55995178222656,2.3513038291806896,1739502690.3040147,50.55995178222656,0.0,1739502690.304016,50.55995178222656,0.2610691453225667,1739502690.3040173,50.55995178222656,3.130646736140144,1739502690.304019,50.55995178222656,2.091154480335917 +1739502690.3239787,50.579951763153076,33.800416217154975,1739502690.3239808,50.579951763153076,-0.18608077825336888,1739502690.3239837,50.579951763153076,78.60082885108949,1739502690.3239865,50.579951763153076,28.54412759119331,1739502690.3239877,50.579951763153076,-0.0518880660103766,1739502690.3239894,50.579951763153076,3.1160682620307636,1739502690.3239913,50.579951763153076,-0.0766509208079497,1739502690.3239925,50.579951763153076,-0.021292660198404534,1739502690.323994,50.579951763153076,2.3513038291806896,1739502690.3239954,50.579951763153076,0.0,1739502690.3239968,50.579951763153076,0.26014934884477237,1739502690.323998,50.579951763153076,3.130646736140144,1739502690.3239994,50.579951763153076,2.091154480335917 +1739502690.3439384,50.59995174407959,33.800416217154975,1739502690.3439405,50.59995174407959,-0.18608077825336888,1739502690.3439434,50.59995174407959,78.60082885108949,1739502690.3439462,50.59995174407959,28.54412759119331,1739502690.3439472,50.59995174407959,-0.0518880660103766,1739502690.343949,50.59995174407959,3.1160682620307636,1739502690.3439505,50.59995174407959,-0.0766509208079497,1739502690.343952,50.59995174407959,-0.021292660198404534,1739502690.3439531,50.59995174407959,2.3513038291806896,1739502690.3439548,50.59995174407959,0.0,1739502690.343956,50.59995174407959,0.26014934884477237,1739502690.3439572,50.59995174407959,3.130646736140144,1739502690.3439586,50.59995174407959,2.091154480335917 +1739502690.3641143,50.6199517250061,33.800416217154975,1739502690.3641164,50.6199517250061,-0.18608077825336888,1739502690.3641193,50.6199517250061,78.60082885108949,1739502690.3641224,50.6199517250061,28.54412759119331,1739502690.3641236,50.6199517250061,-0.0518880660103766,1739502690.3641257,50.6199517250061,3.1160682620307636,1739502690.364127,50.6199517250061,-0.0766509208079497,1739502690.3641286,50.6199517250061,-0.021292660198404534,1739502690.3641298,50.6199517250061,2.3513038291806896,1739502690.3641317,50.6199517250061,0.0,1739502690.364133,50.6199517250061,0.26014934884477237,1739502690.3641343,50.6199517250061,3.130646736140144,1739502690.364136,50.6199517250061,2.091154480335917 +1739502690.3840892,50.63995170593262,33.800416217154975,1739502690.3840916,50.63995170593262,-0.18608077825336888,1739502690.3840947,50.63995170593262,78.60082885108949,1739502690.3840976,50.63995170593262,28.54412759119331,1739502690.3840988,50.63995170593262,-0.0518880660103766,1739502690.3841007,50.63995170593262,3.1160682620307636,1739502690.384102,50.63995170593262,-0.0766509208079497,1739502690.384104,50.63995170593262,-0.021292660198404534,1739502690.3841054,50.63995170593262,2.3513038291806896,1739502690.3841074,50.63995170593262,0.0,1739502690.3841085,50.63995170593262,0.26014934884477237,1739502690.38411,50.63995170593262,3.130646736140144,1739502690.384112,50.63995170593262,2.091154480335917 +1739502690.404062,50.65995168685913,33.800416217154975,1739502690.4040642,50.65995168685913,-0.18608077825336888,1739502690.4040673,50.65995168685913,78.60082885108949,1739502690.4040704,50.65995168685913,28.54412759119331,1739502690.404072,50.65995168685913,-0.0518880660103766,1739502690.4040737,50.65995168685913,3.1160682620307636,1739502690.4040751,50.65995168685913,-0.0766509208079497,1739502690.4040766,50.65995168685913,-0.021292660198404534,1739502690.404078,50.65995168685913,2.3513038291806896,1739502690.40408,50.65995168685913,0.0,1739502690.404081,50.65995168685913,0.26014934884477237,1739502690.4040828,50.65995168685913,3.130646736140144,1739502690.4040842,50.65995168685913,2.091154480335917 +1739502690.4241607,50.679951667785645,33.56897776872049,1739502690.4241633,50.679951667785645,-0.18326718634979677,1739502690.4241662,50.679951667785645,79.03121630681837,1739502690.424169,50.679951667785645,28.056750784508694,1739502690.4241707,50.679951667785645,-0.048,1739502690.4241724,50.679951667785645,3.1170580971325292,1739502690.4241738,50.679951667785645,-0.06048583571571539,1739502690.4241753,50.679951667785645,-0.015279020640665362,1739502690.4241767,50.679951667785645,2.3819085147785826,1739502690.4241784,50.679951667785645,0.0,1739502690.42418,50.679951667785645,0.2632057879486749,1739502690.4241815,50.679951667785645,3.128028045401894,1739502690.4241831,50.679951667785645,2.1196578646761144 +1739502690.4440928,50.69995164871216,33.56897776872049,1739502690.444095,50.69995164871216,-0.18326718634979677,1739502690.4440978,50.69995164871216,79.03121630681837,1739502690.4441009,50.69995164871216,28.056750784508694,1739502690.444102,50.69995164871216,-0.048,1739502690.4441042,50.69995164871216,3.1170580971325292,1739502690.4441056,50.69995164871216,-0.06048583571571539,1739502690.444107,50.69995164871216,-0.015279020640665362,1739502690.4441087,50.69995164871216,2.3819085147785826,1739502690.4441104,50.69995164871216,0.0,1739502690.4441116,50.69995164871216,0.2622506501024682,1739502690.4441133,50.69995164871216,3.128028045401894,1739502690.4441147,50.69995164871216,2.1196578646761144 +1739502690.4641225,50.71995162963867,33.56897776872049,1739502690.4641252,50.71995162963867,-0.18326718634979677,1739502690.464128,50.71995162963867,79.03121630681837,1739502690.4641309,50.71995162963867,28.056750784508694,1739502690.4641323,50.71995162963867,-0.048,1739502690.4641342,50.71995162963867,3.1170580971325292,1739502690.464136,50.71995162963867,-0.06048583571571539,1739502690.4641376,50.71995162963867,-0.015279020640665362,1739502690.4641387,50.71995162963867,2.3819085147785826,1739502690.4641407,50.71995162963867,0.0,1739502690.4641418,50.71995162963867,0.2622506501024682,1739502690.4641433,50.71995162963867,3.128028045401894,1739502690.4641447,50.71995162963867,2.1196578646761144 +1739502690.4841497,50.739951610565186,33.56897776872049,1739502690.4841523,50.739951610565186,-0.18326718634979677,1739502690.4841554,50.739951610565186,79.03121630681837,1739502690.4841585,50.739951610565186,28.056750784508694,1739502690.4841597,50.739951610565186,-0.048,1739502690.4841619,50.739951610565186,3.1170580971325292,1739502690.4841633,50.739951610565186,-0.06048583571571539,1739502690.4841647,50.739951610565186,-0.015279020640665362,1739502690.4841661,50.739951610565186,2.3819085147785826,1739502690.4841676,50.739951610565186,0.0,1739502690.4841692,50.739951610565186,0.2622506501024682,1739502690.4841704,50.739951610565186,3.128028045401894,1739502690.484172,50.739951610565186,2.1196578646761144 +1739502690.504153,50.7599515914917,33.56897776872049,1739502690.5041556,50.7599515914917,-0.18326718634979677,1739502690.5041585,50.7599515914917,79.03121630681837,1739502690.5041614,50.7599515914917,28.056750784508694,1739502690.5041628,50.7599515914917,-0.048,1739502690.5041647,50.7599515914917,3.1170580971325292,1739502690.504166,50.7599515914917,-0.06048583571571539,1739502690.5041673,50.7599515914917,-0.015279020640665362,1739502690.5041687,50.7599515914917,2.3819085147785826,1739502690.5041704,50.7599515914917,0.0,1739502690.5041718,50.7599515914917,0.2622506501024682,1739502690.5041733,50.7599515914917,3.128028045401894,1739502690.504175,50.7599515914917,2.1196578646761144 +1739502690.5241694,50.77995157241821,33.33440544908093,1739502690.5241718,50.77995157241821,-0.179823037409526,1739502690.524175,50.77995157241821,79.11976146896228,1739502690.524178,50.77995157241821,27.910835537204246,1739502690.5241792,50.77995157241821,-0.04732597820534733,1739502690.524181,50.77995157241821,3.1171676508867816,1739502690.5241826,50.77995157241821,-0.04589458995530117,1739502690.5241842,50.77995157241821,-0.01197542139030188,1739502690.5241857,50.77995157241821,2.409875436120946,1739502690.5241873,50.77995157241821,0.0,1739502690.524189,50.77995157241821,0.2612039408343468,1739502690.5241904,50.77995157241821,3.125627290703294,1739502690.5241919,50.77995157241821,2.14834439842585 +1739502690.5440845,50.79995155334473,33.33440544908093,1739502690.5440865,50.79995155334473,-0.179823037409526,1739502690.5440896,50.79995155334473,79.11976146896228,1739502690.5440927,50.79995155334473,27.910835537204246,1739502690.5440943,50.79995155334473,-0.04732597820534733,1739502690.5440958,50.79995155334473,3.1171676508867816,1739502690.5440972,50.79995155334473,-0.04589458995530117,1739502690.5440986,50.79995155334473,-0.01197542139030188,1739502690.5441,50.79995155334473,2.409875436120946,1739502690.5441017,50.79995155334473,0.0,1739502690.5441031,50.79995155334473,0.2615310376950961,1739502690.5441048,50.79995155334473,3.125627290703294,1739502690.544106,50.79995155334473,2.14834439842585 +1739502690.5641193,50.81995153427124,33.33440544908093,1739502690.564122,50.81995153427124,-0.179823037409526,1739502690.5641248,50.81995153427124,79.11976146896228,1739502690.5641277,50.81995153427124,27.910835537204246,1739502690.5641294,50.81995153427124,-0.04732597820534733,1739502690.564131,50.81995153427124,3.1171676508867816,1739502690.5641327,50.81995153427124,-0.04589458995530117,1739502690.5641341,50.81995153427124,-0.01197542139030188,1739502690.5641353,50.81995153427124,2.409875436120946,1739502690.5641372,50.81995153427124,0.0,1739502690.5641384,50.81995153427124,0.2615310376950961,1739502690.56414,50.81995153427124,3.125627290703294,1739502690.5641418,50.81995153427124,2.14834439842585 +1739502690.5841174,50.839951515197754,33.33440544908093,1739502690.5841203,50.839951515197754,-0.179823037409526,1739502690.5841231,50.839951515197754,79.11976146896228,1739502690.5841265,50.839951515197754,27.910835537204246,1739502690.584128,50.839951515197754,-0.04732597820534733,1739502690.5841298,50.839951515197754,3.1171676508867816,1739502690.584131,50.839951515197754,-0.04589458995530117,1739502690.5841327,50.839951515197754,-0.01197542139030188,1739502690.584134,50.839951515197754,2.409875436120946,1739502690.5841358,50.839951515197754,0.0,1739502690.584137,50.839951515197754,0.2615310376950961,1739502690.5841384,50.839951515197754,3.125627290703294,1739502690.58414,50.839951515197754,2.14834439842585 +1739502690.6040754,50.85995149612427,33.33440544908093,1739502690.6040778,50.85995149612427,-0.179823037409526,1739502690.604081,50.85995149612427,79.11976146896228,1739502690.6040838,50.85995149612427,27.910835537204246,1739502690.6040852,50.85995149612427,-0.04732597820534733,1739502690.604087,50.85995149612427,3.1171676508867816,1739502690.6040885,50.85995149612427,-0.04589458995530117,1739502690.6040897,50.85995149612427,-0.01197542139030188,1739502690.6040912,50.85995149612427,2.409875436120946,1739502690.6040928,50.85995149612427,0.0,1739502690.6040943,50.85995149612427,0.2615310376950961,1739502690.6040957,50.85995149612427,3.125627290703294,1739502690.6040974,50.85995149612427,2.14834439842585 +1739502690.624129,50.87995147705078,33.33440544908093,1739502690.624132,50.87995147705078,-0.179823037409526,1739502690.624135,50.87995147705078,79.11976146896228,1739502690.6241376,50.87995147705078,27.910835537204246,1739502690.624139,50.87995147705078,-0.04732597820534733,1739502690.6241407,50.87995147705078,3.1171676508867816,1739502690.6241426,50.87995147705078,-0.04589458995530117,1739502690.624144,50.87995147705078,-0.01197542139030188,1739502690.6241455,50.87995147705078,2.409875436120946,1739502690.6241472,50.87995147705078,0.0,1739502690.6241488,50.87995147705078,0.2615310376950961,1739502690.62415,50.87995147705078,3.125627290703294,1739502690.6241515,50.87995147705078,2.14834439842585 +1739502690.6441057,50.899951457977295,33.096688077958035,1739502690.644108,50.899951457977295,-0.1757871597310352,1739502690.6441112,50.899951457977295,79.40551905049514,1739502690.6441143,50.899951457977295,27.56783274694699,1739502690.6441154,50.899951457977295,-0.045,1739502690.6441174,50.899951457977295,3.1179416869913603,1739502690.644119,50.899951457977295,-0.03034933497396325,1739502690.6441202,50.899951457977295,-0.007620720950573954,1739502690.644122,50.899951457977295,2.440032268212659,1739502690.6441233,50.899951457977295,0.0,1739502690.644125,50.899951457977295,0.26375433510648855,1739502690.6441262,50.899951457977295,3.1234294412578274,1739502690.6441278,50.899951457977295,2.1769727140027646 +1739502690.6641107,50.91995143890381,33.096688077958035,1739502690.664113,50.91995143890381,-0.1757871597310352,1739502690.664116,50.91995143890381,79.40551905049514,1739502690.664119,50.91995143890381,27.56783274694699,1739502690.6641204,50.91995143890381,-0.045,1739502690.664122,50.91995143890381,3.1179416869913603,1739502690.6641235,50.91995143890381,-0.03034933497396325,1739502690.6641254,50.91995143890381,-0.007620720950573954,1739502690.6641266,50.91995143890381,2.440032268212659,1739502690.6641285,50.91995143890381,0.0,1739502690.6641297,50.91995143890381,0.2630595542098946,1739502690.6641316,50.91995143890381,3.1234294412578274,1739502690.664133,50.91995143890381,2.1769727140027646 +1739502690.6840827,50.93995141983032,33.096688077958035,1739502690.6840851,50.93995141983032,-0.1757871597310352,1739502690.684088,50.93995141983032,79.40551905049514,1739502690.6840909,50.93995141983032,27.56783274694699,1739502690.6840925,50.93995141983032,-0.045,1739502690.684094,50.93995141983032,3.1179416869913603,1739502690.6840954,50.93995141983032,-0.03034933497396325,1739502690.684097,50.93995141983032,-0.007620720950573954,1739502690.6840982,50.93995141983032,2.440032268212659,1739502690.6841002,50.93995141983032,0.0,1739502690.6841013,50.93995141983032,0.2630595542098946,1739502690.684103,50.93995141983032,3.1234294412578274,1739502690.6841047,50.93995141983032,2.1769727140027646 +1739502690.7040408,50.959951400756836,33.096688077958035,1739502690.7040436,50.959951400756836,-0.1757871597310352,1739502690.7040465,50.959951400756836,79.40551905049514,1739502690.7040493,50.959951400756836,27.56783274694699,1739502690.704051,50.959951400756836,-0.045,1739502690.7040527,50.959951400756836,3.1179416869913603,1739502690.704054,50.959951400756836,-0.03034933497396325,1739502690.7040555,50.959951400756836,-0.007620720950573954,1739502690.704057,50.959951400756836,2.440032268212659,1739502690.7040586,50.959951400756836,0.0,1739502690.70406,50.959951400756836,0.2630595542098946,1739502690.7040617,50.959951400756836,3.1234294412578274,1739502690.7040632,50.959951400756836,2.1769727140027646 +1739502690.7241626,50.97995138168335,33.096688077958035,1739502690.724166,50.97995138168335,-0.1757871597310352,1739502690.7241695,50.97995138168335,79.40551905049514,1739502690.7241728,50.97995138168335,27.56783274694699,1739502690.7241743,50.97995138168335,-0.045,1739502690.7241764,50.97995138168335,3.1179416869913603,1739502690.7241778,50.97995138168335,-0.03034933497396325,1739502690.7241795,50.97995138168335,-0.007620720950573954,1739502690.7241807,50.97995138168335,2.440032268212659,1739502690.7241828,50.97995138168335,0.0,1739502690.724184,50.97995138168335,0.2630595542098946,1739502690.7241857,50.97995138168335,3.1234294412578274,1739502690.7241874,50.97995138168335,2.1769727140027646 +1739502690.7442873,50.99995136260986,32.85582535440744,1739502690.7442899,50.99995136260986,-0.17118309209302485,1739502690.7442932,50.99995136260986,79.64832285025864,1739502690.7442966,50.99995136260986,27.267493374646957,1739502690.744298,50.99995136260986,-0.04275133756663229,1739502690.7443001,50.99995136260986,3.118614571661446,1739502690.7443016,50.99995136260986,-0.01543617397742306,1739502690.744303,50.99995136260986,-0.003794083924986035,1739502690.7443047,50.99995136260986,2.469317490182107,1739502690.7443063,50.99995136260986,0.0,1739502690.7443082,50.99995136260986,0.26380383977379473,1739502690.7443097,50.99995136260986,3.1213760609101637,1739502690.744312,50.99995136260986,2.2057462397995287 +1739502690.7654958,51.01995134353638,32.85582535440744,1739502690.7654994,51.01995134353638,-0.17118309209302485,1739502690.7655034,51.01995134353638,79.64832285025864,1739502690.7655077,51.01995134353638,27.267493374646957,1739502690.7655094,51.01995134353638,-0.04275133756663229,1739502690.7655118,51.01995134353638,3.118614571661446,1739502690.7655137,51.01995134353638,-0.01543617397742306,1739502690.7655158,51.01995134353638,-0.003794083924986035,1739502690.7655175,51.01995134353638,2.469317490182107,1739502690.7655199,51.01995134353638,0.0,1739502690.7655218,51.01995134353638,0.26357125038257845,1739502690.7655237,51.01995134353638,3.1213760609101637,1739502690.7655258,51.01995134353638,2.2057462397995287 +1739502690.7849607,51.03995132446289,32.85582535440744,1739502690.7849648,51.03995132446289,-0.17118309209302485,1739502690.7849693,51.03995132446289,79.64832285025864,1739502690.7849734,51.03995132446289,27.267493374646957,1739502690.784975,51.03995132446289,-0.04275133756663229,1739502690.7849777,51.03995132446289,3.118614571661446,1739502690.7849798,51.03995132446289,-0.01543617397742306,1739502690.784982,51.03995132446289,-0.003794083924986035,1739502690.7849839,51.03995132446289,2.469317490182107,1739502690.7849863,51.03995132446289,0.0,1739502690.7849884,51.03995132446289,0.26357125038257845,1739502690.7849905,51.03995132446289,3.1213760609101637,1739502690.7849925,51.03995132446289,2.2057462397995287 +1739502690.8049102,51.059951305389404,32.85582535440744,1739502690.804914,51.059951305389404,-0.17118309209302485,1739502690.804918,51.059951305389404,79.64832285025864,1739502690.804922,51.059951305389404,27.267493374646957,1739502690.8049242,51.059951305389404,-0.04275133756663229,1739502690.8049266,51.059951305389404,3.118614571661446,1739502690.8049288,51.059951305389404,-0.01543617397742306,1739502690.8049312,51.059951305389404,-0.003794083924986035,1739502690.8049328,51.059951305389404,2.469317490182107,1739502690.8049352,51.059951305389404,0.0,1739502690.804937,51.059951305389404,0.26357125038257845,1739502690.8049393,51.059951305389404,3.1213760609101637,1739502690.8049414,51.059951305389404,2.2057462397995287 +1739502690.82465,51.07995128631592,32.85582535440744,1739502690.8246531,51.07995128631592,-0.17118309209302485,1739502690.8246572,51.07995128631592,79.64832285025864,1739502690.8246613,51.07995128631592,27.267493374646957,1739502690.8246634,51.07995128631592,-0.04275133756663229,1739502690.8246655,51.07995128631592,3.118614571661446,1739502690.8246677,51.07995128631592,-0.01543617397742306,1739502690.8246694,51.07995128631592,-0.003794083924986035,1739502690.8246984,51.07995128631592,2.469317490182107,1739502690.824701,51.07995128631592,0.0,1739502690.824703,51.07995128631592,0.26357125038257845,1739502690.8247051,51.07995128631592,3.1213760609101637,1739502690.824707,51.07995128631592,2.2057462397995287 +1739502690.8449268,51.09995126724243,32.85582535440744,1739502690.8449306,51.09995126724243,-0.17118309209302485,1739502690.844935,51.09995126724243,79.64832285025864,1739502690.8449388,51.09995126724243,27.267493374646957,1739502690.844941,51.09995126724243,-0.04275133756663229,1739502690.8449433,51.09995126724243,3.118614571661446,1739502690.8449454,51.09995126724243,-0.01543617397742306,1739502690.8449473,51.09995126724243,-0.003794083924986035,1739502690.8449492,51.09995126724243,2.469317490182107,1739502690.8449516,51.09995126724243,0.0,1739502690.8449538,51.09995126724243,0.26357125038257845,1739502690.844956,51.09995126724243,3.1213760609101637,1739502690.8449583,51.09995126724243,2.2057462397995287 +1739502690.8648453,51.119951248168945,32.61180155334639,1739502690.8648486,51.119951248168945,-0.16603769365779986,1739502690.8648527,51.119951248168945,79.8015185458351,1739502690.8648565,51.119951248168945,27.056585622946418,1739502690.8648586,51.119951248168945,-0.040687142026785604,1739502690.8648615,51.119951248168945,3.119032003314072,1739502690.8648632,51.119951248168945,-0.0025761554388720625,1739502690.8648658,51.119951248168945,-0.0006407820253406622,1739502690.8648672,51.119951248168945,2.494852994738282,1739502690.8648696,51.119951248168945,0.0,1739502690.8648715,51.119951248168945,0.25873396957061007,1739502690.8648734,51.119951248168945,3.1194956216471166,1739502690.8648756,51.119951248168945,2.234607373922816 +1739502690.8849585,51.13995122909546,32.61180155334639,1739502690.8849626,51.13995122909546,-0.16603769365779986,1739502690.884967,51.13995122909546,79.8015185458351,1739502690.8849714,51.13995122909546,27.056585622946418,1739502690.884973,51.13995122909546,-0.040687142026785604,1739502690.884976,51.13995122909546,3.119032003314072,1739502690.8849778,51.13995122909546,-0.0025761554388720625,1739502690.8849797,51.13995122909546,-0.0006407820253406622,1739502690.8849819,51.13995122909546,2.494852994738282,1739502690.884984,51.13995122909546,0.0,1739502690.884986,51.13995122909546,0.260245620815466,1739502690.8849878,51.13995122909546,3.1194956216471166,1739502690.88499,51.13995122909546,2.234607373922816 +1739502690.904788,51.15995121002197,32.61180155334639,1739502690.9047918,51.15995121002197,-0.16603769365779986,1739502690.904796,51.15995121002197,79.8015185458351,1739502690.9048,51.15995121002197,27.056585622946418,1739502690.9048018,51.15995121002197,-0.040687142026785604,1739502690.9048047,51.15995121002197,3.119032003314072,1739502690.9048069,51.15995121002197,-0.0025761554388720625,1739502690.9048088,51.15995121002197,-0.0006407820253406622,1739502690.9048107,51.15995121002197,2.494852994738282,1739502690.904813,51.15995121002197,0.0,1739502690.9048152,51.15995121002197,0.260245620815466,1739502690.904817,51.15995121002197,3.1194956216471166,1739502690.9048193,51.15995121002197,2.234607373922816 +1739502690.9253092,51.179951190948486,32.61180155334639,1739502690.9253135,51.179951190948486,-0.16603769365779986,1739502690.9253187,51.179951190948486,79.8015185458351,1739502690.925323,51.179951190948486,27.056585622946418,1739502690.9253254,51.179951190948486,-0.040687142026785604,1739502690.925328,51.179951190948486,3.119032003314072,1739502690.9253302,51.179951190948486,-0.0025761554388720625,1739502690.9253325,51.179951190948486,-0.0006407820253406622,1739502690.9253342,51.179951190948486,2.494852994738282,1739502690.9253368,51.179951190948486,0.0,1739502690.925339,51.179951190948486,0.260245620815466,1739502690.9253411,51.179951190948486,3.1194956216471166,1739502690.9253435,51.179951190948486,2.234607373922816 +1739502690.944809,51.199951171875,32.61180155334639,1739502690.944813,51.199951171875,-0.16603769365779986,1739502690.9448173,51.199951171875,79.8015185458351,1739502690.9448214,51.199951171875,27.056585622946418,1739502690.9448233,51.199951171875,-0.040687142026785604,1739502690.9448256,51.199951171875,3.119032003314072,1739502690.9448276,51.199951171875,-0.0025761554388720625,1739502690.9448295,51.199951171875,-0.0006407820253406622,1739502690.9448314,51.199951171875,2.494852994738282,1739502690.9448338,51.199951171875,0.0,1739502690.944836,51.199951171875,0.260245620815466,1739502690.9448378,51.199951171875,3.1194956216471166,1739502690.94484,51.199951171875,2.234607373922816 +1739502690.9650528,51.219951152801514,32.36463428162872,1739502690.9650567,51.219951152801514,-0.1603760952745512,1739502690.9650612,51.219951152801514,80.46593248689672,1739502690.965065,51.219951152801514,26.335266562392864,1739502690.965067,51.219951152801514,-0.034214748339759855,1739502690.9650695,51.219951152801514,3.120671232789941,1739502690.9650717,51.219951152801514,0.017562625554074618,1739502690.9650733,51.219951152801514,0.003708658041234065,1739502690.9650753,51.219951152801514,2.465120353940889,1739502690.9650779,51.219951152801514,0.0,1739502690.9650798,51.219951152801514,0.17559074328281718,1739502690.965082,51.219951152801514,3.1177590191550646,1739502690.965084,51.219951152801514,2.263074944084088 +1739502690.9850488,51.23995113372803,32.36463428162872,1739502690.9850526,51.23995113372803,-0.1603760952745512,1739502690.9850569,51.23995113372803,80.46593248689672,1739502690.9850607,51.23995113372803,26.335266562392864,1739502690.9850626,51.23995113372803,-0.034214748339759855,1739502690.9850657,51.23995113372803,3.120671232789941,1739502690.9850676,51.23995113372803,0.017562625554074618,1739502690.9850695,51.23995113372803,0.003708658041234065,1739502690.9850714,51.23995113372803,2.465120353940889,1739502690.9850736,51.23995113372803,0.0,1739502690.9850757,51.23995113372803,0.20204540985680097,1739502690.9850779,51.23995113372803,3.1177590191550646,1739502690.9850795,51.23995113372803,2.263074944084088 +1739502691.0049021,51.25995111465454,32.36463428162872,1739502691.0049057,51.25995111465454,-0.1603760952745512,1739502691.0049095,51.25995111465454,80.46593248689672,1739502691.0049136,51.25995111465454,26.335266562392864,1739502691.0049157,51.25995111465454,-0.034214748339759855,1739502691.0049183,51.25995111465454,3.120671232789941,1739502691.0049202,51.25995111465454,0.017562625554074618,1739502691.0049224,51.25995111465454,0.003708658041234065,1739502691.0049243,51.25995111465454,2.465120353940889,1739502691.0049267,51.25995111465454,0.0,1739502691.0049286,51.25995111465454,0.20204540985680097,1739502691.0049305,51.25995111465454,3.1177590191550646,1739502691.0049326,51.25995111465454,2.263074944084088 +1739502691.0250437,51.279951095581055,32.36463428162872,1739502691.0250473,51.279951095581055,-0.1603760952745512,1739502691.025052,51.279951095581055,80.46593248689672,1739502691.025056,51.279951095581055,26.335266562392864,1739502691.025058,51.279951095581055,-0.034214748339759855,1739502691.0250607,51.279951095581055,3.120671232789941,1739502691.0250626,51.279951095581055,0.017562625554074618,1739502691.0250645,51.279951095581055,0.003708658041234065,1739502691.0250661,51.279951095581055,2.465120353940889,1739502691.0250688,51.279951095581055,0.0,1739502691.025071,51.279951095581055,0.20204540985680097,1739502691.0250728,51.279951095581055,3.1177590191550646,1739502691.025075,51.279951095581055,2.263074944084088 +1739502691.0447888,51.29995107650757,32.36463428162872,1739502691.044793,51.29995107650757,-0.1603760952745512,1739502691.0447972,51.29995107650757,80.46593248689672,1739502691.044801,51.29995107650757,26.335266562392864,1739502691.0448031,51.29995107650757,-0.034214748339759855,1739502691.0448055,51.29995107650757,3.120671232789941,1739502691.0448077,51.29995107650757,0.017562625554074618,1739502691.0448098,51.29995107650757,0.003708658041234065,1739502691.0448117,51.29995107650757,2.465120353940889,1739502691.0448143,51.29995107650757,0.0,1739502691.044816,51.29995107650757,0.20204540985680097,1739502691.0448182,51.29995107650757,3.1177590191550646,1739502691.0448208,51.29995107650757,2.263074944084088 +1739502691.0651822,51.31995105743408,32.36463428162872,1739502691.0651865,51.31995105743408,-0.1603760952745512,1739502691.065191,51.31995105743408,80.46593248689672,1739502691.065195,51.31995105743408,26.335266562392864,1739502691.065197,51.31995105743408,-0.034214748339759855,1739502691.0651996,51.31995105743408,3.120671232789941,1739502691.0652018,51.31995105743408,0.017562625554074618,1739502691.065204,51.31995105743408,0.003708658041234065,1739502691.0652058,51.31995105743408,2.465120353940889,1739502691.0652084,51.31995105743408,0.0,1739502691.06521,51.31995105743408,0.20204540985680097,1739502691.0652125,51.31995105743408,3.1177590191550646,1739502691.0652142,51.31995105743408,2.263074944084088 +1739502691.085066,51.339951038360596,32.11471340858202,1739502691.0850697,51.339951038360596,-0.15423809585907744,1739502691.085074,51.339951038360596,81.02492231221314,1739502691.085078,51.339951038360596,25.733103284168166,1739502691.08508,51.339951038360596,-0.030009429779215092,1739502691.0850823,51.339951038360596,3.122128447060251,1739502691.0850844,51.339951038360596,0.03787023694945271,1739502691.085086,51.339951038360596,0.00713893358183572,1739502691.0850883,51.339951038360596,2.4253953506922294,1739502691.0850906,51.339951038360596,0.0,1739502691.0850925,51.339951038360596,0.11285269688119451,1739502691.0850947,51.339951038360596,3.116195260150512,1739502691.0850966,51.339951038360596,2.2846699127313648 +1739502691.1047904,51.35995101928711,32.11471340858202,1739502691.104794,51.35995101928711,-0.15423809585907744,1739502691.1047988,51.35995101928711,81.02492231221314,1739502691.1048026,51.35995101928711,25.733103284168166,1739502691.1048045,51.35995101928711,-0.030009429779215092,1739502691.1048071,51.35995101928711,3.122128447060251,1739502691.104809,51.35995101928711,0.03787023694945271,1739502691.1048112,51.35995101928711,0.00713893358183572,1739502691.104813,51.35995101928711,2.4253953506922294,1739502691.1048152,51.35995101928711,0.0,1739502691.1048172,51.35995101928711,0.14072543796086467,1739502691.1048195,51.35995101928711,3.116195260150512,1739502691.1048214,51.35995101928711,2.2846699127313648 +1739502691.1251829,51.37995100021362,32.11471340858202,1739502691.1251876,51.37995100021362,-0.15423809585907744,1739502691.1251917,51.37995100021362,81.02492231221314,1739502691.1251962,51.37995100021362,25.733103284168166,1739502691.1251984,51.37995100021362,-0.030009429779215092,1739502691.1252007,51.37995100021362,3.122128447060251,1739502691.1252031,51.37995100021362,0.03787023694945271,1739502691.1252053,51.37995100021362,0.00713893358183572,1739502691.1252072,51.37995100021362,2.4253953506922294,1739502691.1252096,51.37995100021362,0.0,1739502691.125212,51.37995100021362,0.14072543796086467,1739502691.1252139,51.37995100021362,3.116195260150512,1739502691.1252162,51.37995100021362,2.2846699127313648 +1739502691.1448176,51.39995098114014,32.11471340858202,1739502691.1448212,51.39995098114014,-0.15423809585907744,1739502691.1448257,51.39995098114014,81.02492231221314,1739502691.14483,51.39995098114014,25.733103284168166,1739502691.144832,51.39995098114014,-0.030009429779215092,1739502691.1448345,51.39995098114014,3.122128447060251,1739502691.144837,51.39995098114014,0.03787023694945271,1739502691.1448393,51.39995098114014,0.00713893358183572,1739502691.144841,51.39995098114014,2.4253953506922294,1739502691.1448433,51.39995098114014,0.0,1739502691.1448452,51.39995098114014,0.14072543796086467,1739502691.1448474,51.39995098114014,3.116195260150512,1739502691.1448493,51.39995098114014,2.2846699127313648 +1739502691.1650324,51.41995096206665,32.11471340858202,1739502691.1650362,51.41995096206665,-0.15423809585907744,1739502691.1650407,51.41995096206665,81.02492231221314,1739502691.1650448,51.41995096206665,25.733103284168166,1739502691.1650467,51.41995096206665,-0.030009429779215092,1739502691.1650493,51.41995096206665,3.122128447060251,1739502691.165052,51.41995096206665,0.03787023694945271,1739502691.1650538,51.41995096206665,0.00713893358183572,1739502691.1650558,51.41995096206665,2.4253953506922294,1739502691.1650581,51.41995096206665,0.0,1739502691.1650603,51.41995096206665,0.14072543796086467,1739502691.1650627,51.41995096206665,3.116195260150512,1739502691.1650648,51.41995096206665,2.2846699127313648 +1739502691.1848614,51.439950942993164,31.86270175715927,1739502691.184865,51.439950942993164,-0.14766990451492035,1739502691.184869,51.439950942993164,81.0312226034987,1739502691.1848736,51.439950942993164,25.695924617795587,1739502691.1848752,51.439950942993164,-0.02969166339996228,1739502691.1848776,51.439950942993164,3.12246372318468,1739502691.1848795,51.439950942993164,0.047417868990137176,1739502691.1848817,51.439950942993164,0.009572521401700139,1739502691.1848834,51.439950942993164,2.4069404945953856,1739502691.1848857,51.439950942993164,0.0,1739502691.184888,51.439950942993164,0.09142400855378817,1739502691.1848898,51.439950942993164,3.114775807808298,1739502691.184892,51.439950942993164,2.300109779250462 +1739502691.2047882,51.45995092391968,31.86270175715927,1739502691.2047918,51.45995092391968,-0.14766990451492035,1739502691.204796,51.45995092391968,81.0312226034987,1739502691.2048006,51.45995092391968,25.695924617795587,1739502691.2048025,51.45995092391968,-0.02969166339996228,1739502691.2048051,51.45995092391968,3.12246372318468,1739502691.2048075,51.45995092391968,0.047417868990137176,1739502691.2048092,51.45995092391968,0.009572521401700139,1739502691.2048113,51.45995092391968,2.4069404945953856,1739502691.2048135,51.45995092391968,0.0,1739502691.2048154,51.45995092391968,0.10683071534492372,1739502691.2048173,51.45995092391968,3.114775807808298,1739502691.2048194,51.45995092391968,2.300109779250462 +1739502691.2256114,51.47995090484619,31.86270175715927,1739502691.2256148,51.47995090484619,-0.14766990451492035,1739502691.2256188,51.47995090484619,81.0312226034987,1739502691.2256231,51.47995090484619,25.695924617795587,1739502691.2256248,51.47995090484619,-0.02969166339996228,1739502691.2256274,51.47995090484619,3.12246372318468,1739502691.2256293,51.47995090484619,0.047417868990137176,1739502691.2256312,51.47995090484619,0.009572521401700139,1739502691.2256334,51.47995090484619,2.4069404945953856,1739502691.2256355,51.47995090484619,0.0,1739502691.2256374,51.47995090484619,0.10683071534492372,1739502691.2256393,51.47995090484619,3.114775807808298,1739502691.2256415,51.47995090484619,2.300109779250462 +1739502691.2439537,51.499950885772705,31.86270175715927,1739502691.2439556,51.499950885772705,-0.14766990451492035,1739502691.2439582,51.499950885772705,81.0312226034987,1739502691.2439609,51.499950885772705,25.695924617795587,1739502691.243962,51.499950885772705,-0.02969166339996228,1739502691.243964,51.499950885772705,3.12246372318468,1739502691.2439651,51.499950885772705,0.047417868990137176,1739502691.2439666,51.499950885772705,0.009572521401700139,1739502691.2439678,51.499950885772705,2.4069404945953856,1739502691.2439692,51.499950885772705,0.0,1739502691.2439706,51.499950885772705,0.10683071534492372,1739502691.2439718,51.499950885772705,3.114775807808298,1739502691.243973,51.499950885772705,2.300109779250462 +1739502691.2734618,51.529950857162476,31.86270175715927,1739502691.273466,51.529950857162476,-0.14766990451492035,1739502691.2734716,51.529950857162476,81.0312226034987,1739502691.2734768,51.529950857162476,25.695924617795587,1739502691.2734797,51.529950857162476,-0.02969166339996228,1739502691.2734835,51.529950857162476,3.12246372318468,1739502691.2734873,51.529950857162476,0.047417868990137176,1739502691.2734914,51.529950857162476,0.009572521401700139,1739502691.2734947,51.529950857162476,2.4069404945953856,1739502691.273498,51.529950857162476,0.0,1739502691.2735014,51.529950857162476,0.10683071534492372,1739502691.2735047,51.529950857162476,3.114775807808298,1739502691.2735083,51.529950857162476,2.300109779250462 +1739502691.3046396,51.559950828552246,31.6092282677087,1739502691.3046417,51.559950828552246,-0.14071877473286687,1739502691.3046448,51.559950828552246,81.03755944073498,1739502691.3046474,51.559950828552246,25.66680932906398,1739502691.3046486,51.559950828552246,-0.029442814778324628,1739502691.3046503,51.559950828552246,3.1228691409151796,1739502691.3046517,51.559950828552246,0.05589409905918539,1739502691.3046534,51.559950828552246,0.012151951099277483,1739502691.3046546,51.559950828552246,2.3906742822718496,1739502691.304656,51.559950828552246,0.0,1739502691.3046575,51.559950828552246,0.06660383820827664,1739502691.3046587,51.559950828552246,3.1134647003493026,1739502691.30466,51.559950828552246,2.3114995367162416 +1739502691.3245888,51.57995080947876,31.6092282677087,1739502691.3245912,51.57995080947876,-0.14071877473286687,1739502691.3245938,51.57995080947876,81.03755944073498,1739502691.3245962,51.57995080947876,25.66680932906398,1739502691.3245976,51.57995080947876,-0.029442814778324628,1739502691.324599,51.57995080947876,3.1228691409151796,1739502691.3246002,51.57995080947876,0.05589409905918539,1739502691.3246017,51.57995080947876,0.012151951099277483,1739502691.3246026,51.57995080947876,2.3906742822718496,1739502691.3246043,51.57995080947876,0.0,1739502691.3246055,51.57995080947876,0.079174745555608,1739502691.3246067,51.57995080947876,3.1134647003493026,1739502691.3246078,51.57995080947876,2.3114995367162416 +1739502691.3440626,51.59995079040527,31.6092282677087,1739502691.344065,51.59995079040527,-0.14071877473286687,1739502691.3440678,51.59995079040527,81.03755944073498,1739502691.3440707,51.59995079040527,25.66680932906398,1739502691.3440719,51.59995079040527,-0.029442814778324628,1739502691.3440738,51.59995079040527,3.1228691409151796,1739502691.344075,51.59995079040527,0.05589409905918539,1739502691.3440766,51.59995079040527,0.012151951099277483,1739502691.3440778,51.59995079040527,2.3906742822718496,1739502691.3440793,51.59995079040527,0.0,1739502691.3440807,51.59995079040527,0.079174745555608,1739502691.3440819,51.59995079040527,3.1134647003493026,1739502691.3440833,51.59995079040527,2.3114995367162416 +1739502691.3650887,51.61995077133179,31.6092282677087,1739502691.3650916,51.61995077133179,-0.14071877473286687,1739502691.3650942,51.61995077133179,81.03755944073498,1739502691.3650973,51.61995077133179,25.66680932906398,1739502691.3650982,51.61995077133179,-0.029442814778324628,1739502691.3651001,51.61995077133179,3.1228691409151796,1739502691.3651013,51.61995077133179,0.05589409905918539,1739502691.3651025,51.61995077133179,0.012151951099277483,1739502691.365104,51.61995077133179,2.3906742822718496,1739502691.3651054,51.61995077133179,0.0,1739502691.3651066,51.61995077133179,0.079174745555608,1739502691.365108,51.61995077133179,3.1134647003493026,1739502691.3651094,51.61995077133179,2.3114995367162416 +1739502691.3850145,51.6399507522583,31.6092282677087,1739502691.3850172,51.6399507522583,-0.14071877473286687,1739502691.38502,51.6399507522583,81.03755944073498,1739502691.3850226,51.6399507522583,25.66680932906398,1739502691.385024,51.6399507522583,-0.029442814778324628,1739502691.3850255,51.6399507522583,3.1228691409151796,1739502691.3850272,51.6399507522583,0.05589409905918539,1739502691.3850284,51.6399507522583,0.012151951099277483,1739502691.3850293,51.6399507522583,2.3906742822718496,1739502691.385031,51.6399507522583,0.0,1739502691.3850322,51.6399507522583,0.079174745555608,1739502691.3850338,51.6399507522583,3.1134647003493026,1739502691.3850353,51.6399507522583,2.3114995367162416 +1739502691.4049757,51.659950733184814,31.354628711324153,1739502691.4049776,51.659950733184814,-0.13341514039872937,1739502691.4049804,51.659950733184814,81.04392442964459,1739502691.4049833,51.659950733184814,25.6430829818233,1739502691.404985,51.659950733184814,-0.02924002548566927,1739502691.4049864,51.659950733184814,3.123355284935787,1739502691.4049878,51.659950733184814,0.06324439101844655,1739502691.4049892,51.659950733184814,0.014884282352059654,1739502691.4049904,51.659950733184814,2.3766578095626008,1739502691.4049926,51.659950733184814,0.0,1739502691.4049938,51.659950733184814,0.046160066367623716,1739502691.404995,51.659950733184814,3.112283822223347,1739502691.4049964,51.659950733184814,2.320180649184318 +1739502691.4239647,51.67995071411133,31.354628711324153,1739502691.423967,51.67995071411133,-0.13341514039872937,1739502691.4239697,51.67995071411133,81.04392442964459,1739502691.4239724,51.67995071411133,25.6430829818233,1739502691.4239738,51.67995071411133,-0.02924002548566927,1739502691.4239755,51.67995071411133,3.123355284935787,1739502691.423977,51.67995071411133,0.06324439101844655,1739502691.4239783,51.67995071411133,0.014884282352059654,1739502691.4239795,51.67995071411133,2.3766578095626008,1739502691.4239807,51.67995071411133,0.0,1739502691.4239821,51.67995071411133,0.056477160378282765,1739502691.4239833,51.67995071411133,3.112283822223347,1739502691.4239845,51.67995071411133,2.320180649184318 +1739502691.4439907,51.69995069503784,31.354628711324153,1739502691.4439929,51.69995069503784,-0.13341514039872937,1739502691.443996,51.69995069503784,81.04392442964459,1739502691.4439986,51.69995069503784,25.6430829818233,1739502691.4439998,51.69995069503784,-0.02924002548566927,1739502691.4440014,51.69995069503784,3.123355284935787,1739502691.444003,51.69995069503784,0.06324439101844655,1739502691.4440043,51.69995069503784,0.014884282352059654,1739502691.4440057,51.69995069503784,2.3766578095626008,1739502691.4440072,51.69995069503784,0.0,1739502691.4440084,51.69995069503784,0.056477160378282765,1739502691.44401,51.69995069503784,3.112283822223347,1739502691.4440114,51.69995069503784,2.320180649184318 +1739502691.4643595,51.719950675964355,31.354628711324153,1739502691.4643624,51.719950675964355,-0.13341514039872937,1739502691.4643662,51.719950675964355,81.04392442964459,1739502691.4643693,51.719950675964355,25.6430829818233,1739502691.464371,51.719950675964355,-0.02924002548566927,1739502691.4643736,51.719950675964355,3.123355284935787,1739502691.464375,51.719950675964355,0.06324439101844655,1739502691.464377,51.719950675964355,0.014884282352059654,1739502691.464378,51.719950675964355,2.3766578095626008,1739502691.4643803,51.719950675964355,0.0,1739502691.4643822,51.719950675964355,0.056477160378282765,1739502691.464384,51.719950675964355,3.112283822223347,1739502691.4643855,51.719950675964355,2.320180649184318 +1739502691.4842012,51.73995065689087,31.354628711324153,1739502691.4842038,51.73995065689087,-0.13341514039872937,1739502691.4842072,51.73995065689087,81.04392442964459,1739502691.4842103,51.73995065689087,25.6430829818233,1739502691.484212,51.73995065689087,-0.02924002548566927,1739502691.484214,51.73995065689087,3.123355284935787,1739502691.4842155,51.73995065689087,0.06324439101844655,1739502691.4842176,51.73995065689087,0.014884282352059654,1739502691.484219,51.73995065689087,2.3766578095626008,1739502691.484221,51.73995065689087,0.0,1739502691.4842224,51.73995065689087,0.056477160378282765,1739502691.484224,51.73995065689087,3.112283822223347,1739502691.4842255,51.73995065689087,2.320180649184318 +1739502691.5044441,51.75995063781738,31.354628711324153,1739502691.5044472,51.75995063781738,-0.13341514039872937,1739502691.504451,51.75995063781738,81.04392442964459,1739502691.5044549,51.75995063781738,25.6430829818233,1739502691.5044568,51.75995063781738,-0.02924002548566927,1739502691.5044587,51.75995063781738,3.123355284935787,1739502691.5044608,51.75995063781738,0.06324439101844655,1739502691.5044625,51.75995063781738,0.014884282352059654,1739502691.5044641,51.75995063781738,2.3766578095626008,1739502691.5044665,51.75995063781738,0.0,1739502691.504468,51.75995063781738,0.056477160378282765,1739502691.5044699,51.75995063781738,3.112283822223347,1739502691.5044715,51.75995063781738,2.320180649184318 +1739502691.52528,51.7799506187439,31.099232087745094,1739502691.5252843,51.7799506187439,-0.12580213426914444,1739502691.5252895,51.7799506187439,81.61070676567847,1739502691.5252936,51.7799506187439,25.064379767636336,1739502691.5252957,51.7799506187439,-0.024704850334833345,1739502691.525298,51.7799506187439,3.124841982167336,1739502691.5253005,51.7799506187439,0.08226646620638202,1739502691.5253024,51.7799506187439,0.01734299378248196,1739502691.5253046,51.7799506187439,2.340764437959501,1739502691.5253074,51.7799506187439,0.0,1739502691.525309,51.7799506187439,-0.0044269007330044186,1739502691.5253115,51.7799506187439,3.111211578671895,1739502691.5253134,51.7799506187439,2.3261588071165282 +1739502691.5447698,51.79995059967041,31.099232087745094,1739502691.5447733,51.79995059967041,-0.12580213426914444,1739502691.5447776,51.79995059967041,81.61070676567847,1739502691.544782,51.79995059967041,25.064379767636336,1739502691.5447838,51.79995059967041,-0.024704850334833345,1739502691.5447862,51.79995059967041,3.124841982167336,1739502691.5447888,51.79995059967041,0.08226646620638202,1739502691.5447907,51.79995059967041,0.01734299378248196,1739502691.5447927,51.79995059967041,2.340764437959501,1739502691.5447948,51.79995059967041,0.0,1739502691.544797,51.79995059967041,0.01460563084297295,1739502691.544799,51.79995059967041,3.111211578671895,1739502691.544801,51.79995059967041,2.3261588071165282 +1739502691.5652695,51.819950580596924,31.099232087745094,1739502691.5652733,51.819950580596924,-0.12580213426914444,1739502691.5652773,51.819950580596924,81.61070676567847,1739502691.5652819,51.819950580596924,25.064379767636336,1739502691.5652835,51.819950580596924,-0.024704850334833345,1739502691.5652862,51.819950580596924,3.124841982167336,1739502691.5652883,51.819950580596924,0.08226646620638202,1739502691.5652902,51.819950580596924,0.01734299378248196,1739502691.5652921,51.819950580596924,2.340764437959501,1739502691.5652945,51.819950580596924,0.0,1739502691.5652964,51.819950580596924,0.01460563084297295,1739502691.565299,51.819950580596924,3.111211578671895,1739502691.565301,51.819950580596924,2.3261588071165282 +1739502691.5848246,51.83995056152344,31.099232087745094,1739502691.5848284,51.83995056152344,-0.12580213426914444,1739502691.5848327,51.83995056152344,81.61070676567847,1739502691.5848367,51.83995056152344,25.064379767636336,1739502691.5848386,51.83995056152344,-0.024704850334833345,1739502691.5848415,51.83995056152344,3.124841982167336,1739502691.5848432,51.83995056152344,0.08226646620638202,1739502691.5848453,51.83995056152344,0.01734299378248196,1739502691.5848472,51.83995056152344,2.340764437959501,1739502691.5848494,51.83995056152344,0.0,1739502691.5848513,51.83995056152344,0.01460563084297295,1739502691.5848534,51.83995056152344,3.111211578671895,1739502691.5848553,51.83995056152344,2.3261588071165282 +1739502691.6049662,51.85995054244995,31.099232087745094,1739502691.60497,51.85995054244995,-0.12580213426914444,1739502691.604974,51.85995054244995,81.61070676567847,1739502691.604978,51.85995054244995,25.064379767636336,1739502691.6049802,51.85995054244995,-0.024704850334833345,1739502691.6049829,51.85995054244995,3.124841982167336,1739502691.6049845,51.85995054244995,0.08226646620638202,1739502691.6049867,51.85995054244995,0.01734299378248196,1739502691.6049886,51.85995054244995,2.340764437959501,1739502691.6049912,51.85995054244995,0.0,1739502691.604993,51.85995054244995,0.01460563084297295,1739502691.6049953,51.85995054244995,3.111211578671895,1739502691.6049972,51.85995054244995,2.3261588071165282 +1739502691.6253374,51.879950523376465,30.84338723321948,1739502691.6253407,51.879950523376465,-0.1179137300189046,1739502691.6253448,51.879950523376465,82.27725489546648,1739502691.6253486,51.879950523376465,24.394610221270323,1739502691.6253507,51.879950523376465,-0.01821463837518475,1739502691.6253529,51.879950523376465,3.126133730237513,1739502691.625355,51.879950523376465,0.10231012668022721,1739502691.625357,51.879950523376465,0.018889288166775917,1739502691.6253586,51.879950523376465,2.3035297732435067,1739502691.625361,51.879950523376465,0.0,1739502691.6253626,51.879950523376465,-0.04192528463453253,1739502691.6253648,51.879950523376465,3.1102699172022543,1739502691.6253667,51.879950523376465,2.3277891352086373 +1739502691.6447325,51.89995050430298,30.84338723321948,1739502691.6447358,51.89995050430298,-0.1179137300189046,1739502691.64474,51.89995050430298,82.27725489546648,1739502691.6447444,51.89995050430298,24.394610221270323,1739502691.6447463,51.89995050430298,-0.01821463837518475,1739502691.6447487,51.89995050430298,3.126133730237513,1739502691.6447508,51.89995050430298,0.10231012668022721,1739502691.644753,51.89995050430298,0.018889288166775917,1739502691.6447546,51.89995050430298,2.3035297732435067,1739502691.644757,51.89995050430298,0.0,1739502691.644759,51.89995050430298,-0.024259361965130566,1739502691.6447613,51.89995050430298,3.1102699172022543,1739502691.6447635,51.89995050430298,2.3277891352086373 +1739502691.66544,51.91995048522949,30.84338723321948,1739502691.6654444,51.91995048522949,-0.1179137300189046,1739502691.665449,51.91995048522949,82.27725489546648,1739502691.665453,51.91995048522949,24.394610221270323,1739502691.6654549,51.91995048522949,-0.01821463837518475,1739502691.6654572,51.91995048522949,3.126133730237513,1739502691.6654592,51.91995048522949,0.10231012668022721,1739502691.6654613,51.91995048522949,0.018889288166775917,1739502691.665463,51.91995048522949,2.3035297732435067,1739502691.6654654,51.91995048522949,0.0,1739502691.6654675,51.91995048522949,-0.024259361965130566,1739502691.6654758,51.91995048522949,3.1102699172022543,1739502691.6654782,51.91995048522949,2.3277891352086373 +1739502691.6848054,51.939950466156006,30.84338723321948,1739502691.6848094,51.939950466156006,-0.1179137300189046,1739502691.6848137,51.939950466156006,82.27725489546648,1739502691.684818,51.939950466156006,24.394610221270323,1739502691.68482,51.939950466156006,-0.01821463837518475,1739502691.6848223,51.939950466156006,3.126133730237513,1739502691.6848242,51.939950466156006,0.10231012668022721,1739502691.6848264,51.939950466156006,0.018889288166775917,1739502691.684828,51.939950466156006,2.3035297732435067,1739502691.6848304,51.939950466156006,0.0,1739502691.6848323,51.939950466156006,-0.024259361965130566,1739502691.6848342,51.939950466156006,3.1102699172022543,1739502691.6848364,51.939950466156006,2.3277891352086373 +1739502691.7047858,51.95995044708252,30.84338723321948,1739502691.7047899,51.95995044708252,-0.1179137300189046,1739502691.704794,51.95995044708252,82.27725489546648,1739502691.7047977,51.95995044708252,24.394610221270323,1739502691.7047994,51.95995044708252,-0.01821463837518475,1739502691.704802,51.95995044708252,3.126133730237513,1739502691.7048042,51.95995044708252,0.10231012668022721,1739502691.704806,51.95995044708252,0.018889288166775917,1739502691.704808,51.95995044708252,2.3035297732435067,1739502691.7048101,51.95995044708252,0.0,1739502691.704812,51.95995044708252,-0.024259361965130566,1739502691.7048147,51.95995044708252,3.1102699172022543,1739502691.7048166,51.95995044708252,2.3277891352086373 +1739502691.7255275,51.97995042800903,30.84338723321948,1739502691.7255316,51.97995042800903,-0.1179137300189046,1739502691.7255363,51.97995042800903,82.27725489546648,1739502691.7255406,51.97995042800903,24.394610221270323,1739502691.7255425,51.97995042800903,-0.01821463837518475,1739502691.7255452,51.97995042800903,3.126133730237513,1739502691.7255478,51.97995042800903,0.10231012668022721,1739502691.7255502,51.97995042800903,0.018889288166775917,1739502691.7255518,51.97995042800903,2.3035297732435067,1739502691.7255542,51.97995042800903,0.0,1739502691.7255561,51.97995042800903,-0.024259361965130566,1739502691.7255585,51.97995042800903,3.1102699172022543,1739502691.725561,51.97995042800903,2.3277891352086373 +1739502691.7449954,51.99995040893555,30.58762574269163,1739502691.7449994,51.99995040893555,-0.10979462257567363,1739502691.7450035,51.99995040893555,82.2902987314834,1739502691.7450082,51.99995040893555,24.387578232004714,1739502691.74501,51.99995040893555,-0.01815071120004286,1739502691.7450125,51.99995040893555,3.126812567165104,1739502691.7450147,51.99995040893555,0.10818498246559313,1739502691.7450166,51.99995040893555,0.0216090551346765,1739502691.7450185,51.99995040893555,2.29272885049853,1739502691.7450209,51.99995040893555,0.0,1739502691.745023,51.99995040893555,-0.03559775757020571,1739502691.7450247,51.99995040893555,3.109364530721727,1739502691.7450268,51.99995040893555,2.3247833571190135 +1739502691.7656314,52.01995038986206,30.58762574269163,1739502691.7656357,52.01995038986206,-0.10979462257567363,1739502691.7656403,52.01995038986206,82.2902987314834,1739502691.7656443,52.01995038986206,24.387578232004714,1739502691.7656462,52.01995038986206,-0.01815071120004286,1739502691.7656488,52.01995038986206,3.126812567165104,1739502691.7656507,52.01995038986206,0.10818498246559313,1739502691.7656527,52.01995038986206,0.0216090551346765,1739502691.7656546,52.01995038986206,2.29272885049853,1739502691.7656572,52.01995038986206,0.0,1739502691.7656589,52.01995038986206,-0.03205450662048337,1739502691.7656612,52.01995038986206,3.109364530721727,1739502691.7656631,52.01995038986206,2.3247833571190135 +1739502691.7850745,52.039950370788574,30.58762574269163,1739502691.7850785,52.039950370788574,-0.10979462257567363,1739502691.7850833,52.039950370788574,82.2902987314834,1739502691.7850876,52.039950370788574,24.387578232004714,1739502691.7850895,52.039950370788574,-0.01815071120004286,1739502691.7850926,52.039950370788574,3.126812567165104,1739502691.785095,52.039950370788574,0.10818498246559313,1739502691.785097,52.039950370788574,0.0216090551346765,1739502691.785099,52.039950370788574,2.29272885049853,1739502691.7851017,52.039950370788574,0.0,1739502691.7851033,52.039950370788574,-0.03205450662048337,1739502691.7851057,52.039950370788574,3.109364530721727,1739502691.7851074,52.039950370788574,2.3247833571190135 +1739502691.8050952,52.05995035171509,30.58762574269163,1739502691.805099,52.05995035171509,-0.10979462257567363,1739502691.8051026,52.05995035171509,82.2902987314834,1739502691.8051062,52.05995035171509,24.387578232004714,1739502691.805108,52.05995035171509,-0.01815071120004286,1739502691.8051102,52.05995035171509,3.126812567165104,1739502691.8051124,52.05995035171509,0.10818498246559313,1739502691.805114,52.05995035171509,0.0216090551346765,1739502691.805116,52.05995035171509,2.29272885049853,1739502691.8051178,52.05995035171509,0.0,1739502691.8051198,52.05995035171509,-0.03205450662048337,1739502691.8051212,52.05995035171509,3.109364530721727,1739502691.8051233,52.05995035171509,2.3247833571190135 +1739502691.8244767,52.0799503326416,30.58762574269163,1739502691.8244793,52.0799503326416,-0.10979462257567363,1739502691.8244822,52.0799503326416,82.2902987314834,1739502691.8244853,52.0799503326416,24.387578232004714,1739502691.824487,52.0799503326416,-0.01815071120004286,1739502691.8244886,52.0799503326416,3.126812567165104,1739502691.8244903,52.0799503326416,0.10818498246559313,1739502691.8244917,52.0799503326416,0.0216090551346765,1739502691.8244932,52.0799503326416,2.29272885049853,1739502691.8244948,52.0799503326416,0.0,1739502691.8244963,52.0799503326416,-0.03205450662048337,1739502691.824498,52.0799503326416,3.109364530721727,1739502691.8244994,52.0799503326416,2.3247833571190135 +1739502691.8443189,52.099950313568115,30.332209082228815,1739502691.8443217,52.099950313568115,-0.10146579018884516,1739502691.844325,52.099950313568115,82.30332498116701,1739502691.8443282,52.099950313568115,24.381550724379448,1739502691.8443294,52.099950313568115,-0.018095915676176792,1739502691.8443315,52.099950313568115,3.127583376737484,1739502691.8443334,52.099950313568115,0.11307043909493004,1739502691.844335,52.099950313568115,0.02451801790770877,1739502691.8443367,52.099950313568115,2.2837855169006973,1739502691.8443382,52.099950313568115,0.0,1739502691.8443396,52.099950313568115,-0.039973181127893866,1739502691.8443413,52.099950313568115,3.1085827653744764,1739502691.8443427,52.099950313568115,2.3212841106225595 +1739502691.8642163,52.11995029449463,30.332209082228815,1739502691.8642194,52.11995029449463,-0.10146579018884516,1739502691.8642225,52.11995029449463,82.30332498116701,1739502691.8642254,52.11995029449463,24.381550724379448,1739502691.8642268,52.11995029449463,-0.018095915676176792,1739502691.8642287,52.11995029449463,3.127583376737484,1739502691.8642302,52.11995029449463,0.11307043909493004,1739502691.8642316,52.11995029449463,0.02451801790770877,1739502691.864233,52.11995029449463,2.2837855169006973,1739502691.864235,52.11995029449463,0.0,1739502691.8642364,52.11995029449463,-0.03749859372186215,1739502691.8642378,52.11995029449463,3.1085827653744764,1739502691.8642395,52.11995029449463,2.3212841106225595 +1739502691.8843513,52.13995027542114,30.332209082228815,1739502691.8843544,52.13995027542114,-0.10146579018884516,1739502691.8843577,52.13995027542114,82.30332498116701,1739502691.8843608,52.13995027542114,24.381550724379448,1739502691.8843622,52.13995027542114,-0.018095915676176792,1739502691.8843641,52.13995027542114,3.127583376737484,1739502691.8843656,52.13995027542114,0.11307043909493004,1739502691.884367,52.13995027542114,0.02451801790770877,1739502691.8843687,52.13995027542114,2.2837855169006973,1739502691.8843708,52.13995027542114,0.0,1739502691.884372,52.13995027542114,-0.03749859372186215,1739502691.8843734,52.13995027542114,3.1085827653744764,1739502691.884375,52.13995027542114,2.3212841106225595 +1739502691.904298,52.159950256347656,30.332209082228815,1739502691.9043012,52.159950256347656,-0.10146579018884516,1739502691.9043043,52.159950256347656,82.30332498116701,1739502691.9043071,52.159950256347656,24.381550724379448,1739502691.904309,52.159950256347656,-0.018095915676176792,1739502691.9043107,52.159950256347656,3.127583376737484,1739502691.9043124,52.159950256347656,0.11307043909493004,1739502691.9043138,52.159950256347656,0.02451801790770877,1739502691.9043155,52.159950256347656,2.2837855169006973,1739502691.9043171,52.159950256347656,0.0,1739502691.9043188,52.159950256347656,-0.03749859372186215,1739502691.9043202,52.159950256347656,3.1085827653744764,1739502691.904322,52.159950256347656,2.3212841106225595 +1739502691.9253027,52.17995023727417,30.332209082228815,1739502691.9253063,52.17995023727417,-0.10146579018884516,1739502691.9253106,52.17995023727417,82.30332498116701,1739502691.9253156,52.17995023727417,24.381550724379448,1739502691.925318,52.17995023727417,-0.018095915676176792,1739502691.925321,52.17995023727417,3.127583376737484,1739502691.9253237,52.17995023727417,0.11307043909493004,1739502691.925326,52.17995023727417,0.02451801790770877,1739502691.9253287,52.17995023727417,2.2837855169006973,1739502691.9253325,52.17995023727417,0.0,1739502691.9253361,52.17995023727417,-0.03749859372186215,1739502691.9253404,52.17995023727417,3.1085827653744764,1739502691.9253445,52.17995023727417,2.3212841106225595 +1739502691.9455607,52.199950218200684,30.332209082228815,1739502691.945566,52.199950218200684,-0.10146579018884516,1739502691.9455717,52.199950218200684,82.30332498116701,1739502691.9455762,52.199950218200684,24.381550724379448,1739502691.9455786,52.199950218200684,-0.018095915676176792,1739502691.9455817,52.199950218200684,3.127583376737484,1739502691.9455838,52.199950218200684,0.11307043909493004,1739502691.9455864,52.199950218200684,0.02451801790770877,1739502691.9455888,52.199950218200684,2.2837855169006973,1739502691.945592,52.199950218200684,0.0,1739502691.9455945,52.199950218200684,-0.03749859372186215,1739502691.9455974,52.199950218200684,3.1085827653744764,1739502691.9456005,52.199950218200684,2.3212841106225595 +1739502691.9653194,52.2199501991272,30.07721976699525,1739502691.9653223,52.2199501991272,-0.09296670302014043,1739502691.9653254,52.2199501991272,82.31632943624392,1739502691.9653282,52.2199501991272,24.37685458632667,1739502691.9653294,52.2199501991272,-0.018053223512060627,1739502691.9653308,52.2199501991272,3.1284515363384315,1739502691.9653325,52.2199501991272,0.11709503883700534,1739502691.9653337,52.2199501991272,0.0276698651418782,1739502691.9653351,52.2199501991272,2.2764442833713137,1739502691.9653368,52.2199501991272,0.0,1739502691.9653382,52.2199501991272,-0.04213448171140318,1739502691.9653397,52.2199501991272,3.1079101922136614,1739502691.9653409,52.2199501991272,2.317130049136133 +1739502691.9851694,52.23995018005371,30.07721976699525,1739502691.9851735,52.23995018005371,-0.09296670302014043,1739502691.9851778,52.23995018005371,82.31632943624392,1739502691.9851825,52.23995018005371,24.37685458632667,1739502691.9851847,52.23995018005371,-0.018053223512060627,1739502691.9851878,52.23995018005371,3.1284515363384315,1739502691.985191,52.23995018005371,0.11709503883700534,1739502691.9851935,52.23995018005371,0.0276698651418782,1739502691.985196,52.23995018005371,2.2764442833713137,1739502691.9851992,52.23995018005371,0.0,1739502691.9852014,52.23995018005371,-0.040685765764819415,1739502691.9852037,52.23995018005371,3.1079101922136614,1739502691.9852066,52.23995018005371,2.317130049136133 +1739502692.0055094,52.259950160980225,30.07721976699525,1739502692.005513,52.259950160980225,-0.09296670302014043,1739502692.0055172,52.259950160980225,82.31632943624392,1739502692.0055213,52.259950160980225,24.37685458632667,1739502692.0055242,52.259950160980225,-0.018053223512060627,1739502692.005527,52.259950160980225,3.1284515363384315,1739502692.0055296,52.259950160980225,0.11709503883700534,1739502692.0055315,52.259950160980225,0.0276698651418782,1739502692.005534,52.259950160980225,2.2764442833713137,1739502692.0055366,52.259950160980225,0.0,1739502692.0055387,52.259950160980225,-0.040685765764819415,1739502692.005541,52.259950160980225,3.1079101922136614,1739502692.0055437,52.259950160980225,2.317130049136133 +1739502692.0252905,52.27995014190674,30.07721976699525,1739502692.0252926,52.27995014190674,-0.09296670302014043,1739502692.0252957,52.27995014190674,82.31632943624392,1739502692.025298,52.27995014190674,24.37685458632667,1739502692.0252995,52.27995014190674,-0.018053223512060627,1739502692.0253012,52.27995014190674,3.1284515363384315,1739502692.0253024,52.27995014190674,0.11709503883700534,1739502692.0253038,52.27995014190674,0.0276698651418782,1739502692.025305,52.27995014190674,2.2764442833713137,1739502692.0253067,52.27995014190674,0.0,1739502692.0253081,52.27995014190674,-0.040685765764819415,1739502692.0253093,52.27995014190674,3.1079101922136614,1739502692.0253115,52.27995014190674,2.317130049136133 +1739502692.0455182,52.29995012283325,30.07721976699525,1739502692.045523,52.29995012283325,-0.09296670302014043,1739502692.0455291,52.29995012283325,82.31632943624392,1739502692.0455363,52.29995012283325,24.37685458632667,1739502692.04554,52.29995012283325,-0.018053223512060627,1739502692.045545,52.29995012283325,3.1284515363384315,1739502692.0455496,52.29995012283325,0.11709503883700534,1739502692.0455542,52.29995012283325,0.0276698651418782,1739502692.0455585,52.29995012283325,2.2764442833713137,1739502692.0455632,52.29995012283325,0.0,1739502692.0455678,52.29995012283325,-0.040685765764819415,1739502692.0455723,52.29995012283325,3.1079101922136614,1739502692.045577,52.29995012283325,2.317130049136133 +1739502692.0670981,52.319950103759766,29.82270415460252,1739502692.0671031,52.319950103759766,-0.08432453083002311,1739502692.067109,52.319950103759766,82.69688832238847,1739502692.0671153,52.319950103759766,24.00520396243384,1739502692.0671184,52.319950103759766,-0.015,1739502692.0671222,52.319950103759766,3.129676667794785,1739502692.0671253,52.319950103759766,0.12977368744661533,1739502692.0671296,52.319950103759766,0.02944417836303114,1739502692.0671332,52.319950103759766,2.253471197678422,1739502692.067137,52.319950103759766,0.0,1739502692.0671399,52.319950103759766,-0.06763258872916834,1739502692.0671432,52.319950103759766,3.1073689354149177,1739502692.067147,52.319950103759766,2.312682898710067 +1739502692.0851903,52.33995008468628,29.82270415460252,1739502692.0851927,52.33995008468628,-0.08432453083002311,1739502692.0851958,52.33995008468628,82.69688832238847,1739502692.0851984,52.33995008468628,24.00520396243384,1739502692.0851996,52.33995008468628,-0.015,1739502692.0852015,52.33995008468628,3.129676667794785,1739502692.0852027,52.33995008468628,0.12977368744661533,1739502692.085204,52.33995008468628,0.02944417836303114,1739502692.0852053,52.33995008468628,2.253471197678422,1739502692.0852067,52.33995008468628,0.0,1739502692.0852082,52.33995008468628,-0.05921170103164508,1739502692.0852094,52.33995008468628,3.1073689354149177,1739502692.0852106,52.33995008468628,2.312682898710067 +1739502692.105233,52.35995006561279,29.82270415460252,1739502692.1052353,52.35995006561279,-0.08432453083002311,1739502692.1052384,52.35995006561279,82.69688832238847,1739502692.1052413,52.35995006561279,24.00520396243384,1739502692.1052427,52.35995006561279,-0.015,1739502692.1052442,52.35995006561279,3.129676667794785,1739502692.1052454,52.35995006561279,0.12977368744661533,1739502692.105247,52.35995006561279,0.02944417836303114,1739502692.1052482,52.35995006561279,2.253471197678422,1739502692.10525,52.35995006561279,0.0,1739502692.105251,52.35995006561279,-0.05921170103164508,1739502692.1052525,52.35995006561279,3.1073689354149177,1739502692.1052542,52.35995006561279,2.312682898710067 +1739502692.1246095,52.37995004653931,29.82270415460252,1739502692.124612,52.37995004653931,-0.08432453083002311,1739502692.124615,52.37995004653931,82.69688832238847,1739502692.1246178,52.37995004653931,24.00520396243384,1739502692.124619,52.37995004653931,-0.015,1739502692.124621,52.37995004653931,3.129676667794785,1739502692.1246223,52.37995004653931,0.12977368744661533,1739502692.1246238,52.37995004653931,0.02944417836303114,1739502692.1246252,52.37995004653931,2.253471197678422,1739502692.1246266,52.37995004653931,0.0,1739502692.124628,52.37995004653931,-0.05921170103164508,1739502692.1246293,52.37995004653931,3.1073689354149177,1739502692.1246307,52.37995004653931,2.312682898710067 +1739502692.144194,52.39995002746582,29.82270415460252,1739502692.1441965,52.39995002746582,-0.08432453083002311,1739502692.1441998,52.39995002746582,82.69688832238847,1739502692.1442027,52.39995002746582,24.00520396243384,1739502692.1442041,52.39995002746582,-0.015,1739502692.1442056,52.39995002746582,3.129676667794785,1739502692.144207,52.39995002746582,0.12977368744661533,1739502692.1442084,52.39995002746582,0.02944417836303114,1739502692.1442099,52.39995002746582,2.253471197678422,1739502692.1442115,52.39995002746582,0.0,1739502692.1442127,52.39995002746582,-0.05921170103164508,1739502692.1442146,52.39995002746582,3.1073689354149177,1739502692.1442158,52.39995002746582,2.312682898710067 +1739502692.1642075,52.419950008392334,29.82270415460252,1739502692.1642103,52.419950008392334,-0.08432453083002311,1739502692.1642134,52.419950008392334,82.69688832238847,1739502692.1642163,52.419950008392334,24.00520396243384,1739502692.164218,52.419950008392334,-0.015,1739502692.1642196,52.419950008392334,3.129676667794785,1739502692.1642213,52.419950008392334,0.12977368744661533,1739502692.1642225,52.419950008392334,0.02944417836303114,1739502692.1642237,52.419950008392334,2.253471197678422,1739502692.1642256,52.419950008392334,0.0,1739502692.164227,52.419950008392334,-0.05921170103164508,1739502692.1642284,52.419950008392334,3.1073689354149177,1739502692.16423,52.419950008392334,2.312682898710067 +1739502692.1842544,52.43994998931885,29.568800204722336,1739502692.184257,52.43994998931885,-0.07558089435422488,1739502692.18426,52.43994998931885,83.2634951486143,1739502692.1842628,52.43994998931885,23.451908574302525,1739502692.184264,52.43994998931885,-0.017436031719421034,1739502692.1842656,52.43994998931885,3.132087317386319,1739502692.184267,52.43994998931885,0.15383133978535107,1739502692.1842685,52.43994998931885,0.031571062442002,1739502692.1842697,52.43994998931885,2.210515309449282,1739502692.1842713,52.43994998931885,0.0,1739502692.1842725,52.43994998931885,-0.11202183843812863,1739502692.1842742,52.43994998931885,3.1069371893006466,1739502692.1842754,52.43994998931885,2.3060339691275575 +1739502692.2041883,52.45994997024536,29.568800204722336,1739502692.2041914,52.45994997024536,-0.07558089435422488,1739502692.2041945,52.45994997024536,83.2634951486143,1739502692.2041972,52.45994997024536,23.451908574302525,1739502692.2041986,52.45994997024536,-0.017436031719421034,1739502692.2042003,52.45994997024536,3.132087317386319,1739502692.2042017,52.45994997024536,0.15383133978535107,1739502692.204203,52.45994997024536,0.031571062442002,1739502692.2042043,52.45994997024536,2.210515309449282,1739502692.2042062,52.45994997024536,0.0,1739502692.2042077,52.45994997024536,-0.09551865967827533,1739502692.2042089,52.45994997024536,3.1069371893006466,1739502692.2042105,52.45994997024536,2.3060339691275575 +1739502692.2242937,52.479949951171875,29.568800204722336,1739502692.2242963,52.479949951171875,-0.07558089435422488,1739502692.2242992,52.479949951171875,83.2634951486143,1739502692.224302,52.479949951171875,23.451908574302525,1739502692.2243032,52.479949951171875,-0.017436031719421034,1739502692.2243056,52.479949951171875,3.132087317386319,1739502692.224307,52.479949951171875,0.15383133978535107,1739502692.2243085,52.479949951171875,0.031571062442002,1739502692.2243097,52.479949951171875,2.210515309449282,1739502692.2243118,52.479949951171875,0.0,1739502692.2243133,52.479949951171875,-0.09551865967827533,1739502692.2243147,52.479949951171875,3.1069371893006466,1739502692.2243161,52.479949951171875,2.3060339691275575 +1739502692.2441344,52.49994993209839,29.568800204722336,1739502692.2441375,52.49994993209839,-0.07558089435422488,1739502692.2441404,52.49994993209839,83.2634951486143,1739502692.2441432,52.49994993209839,23.451908574302525,1739502692.244145,52.49994993209839,-0.017436031719421034,1739502692.2441466,52.49994993209839,3.132087317386319,1739502692.2441483,52.49994993209839,0.15383133978535107,1739502692.2441497,52.49994993209839,0.031571062442002,1739502692.2441514,52.49994993209839,2.210515309449282,1739502692.2441528,52.49994993209839,0.0,1739502692.2441545,52.49994993209839,-0.09551865967827533,1739502692.244156,52.49994993209839,3.1069371893006466,1739502692.2441576,52.49994993209839,2.3060339691275575 +1739502692.2642949,52.5199499130249,29.568800204722336,1739502692.264298,52.5199499130249,-0.07558089435422488,1739502692.264301,52.5199499130249,83.2634951486143,1739502692.264304,52.5199499130249,23.451908574302525,1739502692.264305,52.5199499130249,-0.017436031719421034,1739502692.2643073,52.5199499130249,3.132087317386319,1739502692.2643087,52.5199499130249,0.15383133978535107,1739502692.2643101,52.5199499130249,0.031571062442002,1739502692.2643113,52.5199499130249,2.210515309449282,1739502692.2643135,52.5199499130249,0.0,1739502692.2643147,52.5199499130249,-0.09551865967827533,1739502692.2643158,52.5199499130249,3.1069371893006466,1739502692.2643175,52.5199499130249,2.3060339691275575 +1739502692.2842534,52.539949893951416,29.315804963273557,1739502692.284256,52.539949893951416,-0.06676694175262021,1739502692.284259,52.539949893951416,83.83512504315598,1739502692.284262,52.539949893951416,22.90113613145612,1739502692.2842634,52.539949893951416,-0.022,1739502692.2842653,52.539949893951416,3.1346139277711633,1739502692.2842665,52.539949893951416,0.17981846833599657,1739502692.2842681,52.539949893951416,0.033558903867037415,1739502692.2842693,52.539949893951416,2.1650337650640035,1739502692.2842708,52.539949893951416,0.0,1739502692.2842724,52.539949893951416,-0.14651992843000156,1739502692.2842739,52.539949893951416,3.106578552675704,1739502692.2842755,52.539949893951416,2.2956157865593845 +1739502692.3041754,52.55994987487793,29.315804963273557,1739502692.3041782,52.55994987487793,-0.06676694175262021,1739502692.304181,52.55994987487793,83.83512504315598,1739502692.3041835,52.55994987487793,22.90113613145612,1739502692.304185,52.55994987487793,-0.022,1739502692.3041868,52.55994987487793,3.1346139277711633,1739502692.3041883,52.55994987487793,0.17981846833599657,1739502692.3041897,52.55994987487793,0.033558903867037415,1739502692.3041909,52.55994987487793,2.1650337650640035,1739502692.3041928,52.55994987487793,0.0,1739502692.304194,52.55994987487793,-0.130582021495381,1739502692.3041956,52.55994987487793,3.106578552675704,1739502692.304197,52.55994987487793,2.2956157865593845 +1739502692.3241906,52.57994985580444,29.315804963273557,1739502692.3241932,52.57994985580444,-0.06676694175262021,1739502692.324196,52.57994985580444,83.83512504315598,1739502692.324199,52.57994985580444,22.90113613145612,1739502692.3242004,52.57994985580444,-0.022,1739502692.324202,52.57994985580444,3.1346139277711633,1739502692.3242033,52.57994985580444,0.17981846833599657,1739502692.3242047,52.57994985580444,0.033558903867037415,1739502692.324206,52.57994985580444,2.1650337650640035,1739502692.3242075,52.57994985580444,0.0,1739502692.3242092,52.57994985580444,-0.130582021495381,1739502692.3242104,52.57994985580444,3.106578552675704,1739502692.324212,52.57994985580444,2.2956157865593845 +1739502692.3442132,52.59994983673096,29.315804963273557,1739502692.3442163,52.59994983673096,-0.06676694175262021,1739502692.3442194,52.59994983673096,83.83512504315598,1739502692.3442223,52.59994983673096,22.90113613145612,1739502692.3442235,52.59994983673096,-0.022,1739502692.3442252,52.59994983673096,3.1346139277711633,1739502692.3442268,52.59994983673096,0.17981846833599657,1739502692.344228,52.59994983673096,0.033558903867037415,1739502692.3442297,52.59994983673096,2.1650337650640035,1739502692.3442311,52.59994983673096,0.0,1739502692.3442326,52.59994983673096,-0.130582021495381,1739502692.344234,52.59994983673096,3.106578552675704,1739502692.3442354,52.59994983673096,2.2956157865593845 +1739502692.3641553,52.61994981765747,29.315804963273557,1739502692.3641586,52.61994981765747,-0.06676694175262021,1739502692.364162,52.61994981765747,83.83512504315598,1739502692.3641648,52.61994981765747,22.90113613145612,1739502692.3641663,52.61994981765747,-0.022,1739502692.3641677,52.61994981765747,3.1346139277711633,1739502692.3641691,52.61994981765747,0.17981846833599657,1739502692.3641706,52.61994981765747,0.033558903867037415,1739502692.3641717,52.61994981765747,2.1650337650640035,1739502692.3641737,52.61994981765747,0.0,1739502692.3641753,52.61994981765747,-0.130582021495381,1739502692.364177,52.61994981765747,3.106578552675704,1739502692.3641784,52.61994981765747,2.2956157865593845 +1739502692.3842728,52.639949798583984,29.315804963273557,1739502692.3842754,52.639949798583984,-0.06676694175262021,1739502692.3842785,52.639949798583984,83.83512504315598,1739502692.3842814,52.639949798583984,22.90113613145612,1739502692.3842826,52.639949798583984,-0.022,1739502692.3842845,52.639949798583984,3.1346139277711633,1739502692.3842857,52.639949798583984,0.17981846833599657,1739502692.384287,52.639949798583984,0.033558903867037415,1739502692.3842885,52.639949798583984,2.1650337650640035,1739502692.38429,52.639949798583984,0.0,1739502692.3842914,52.639949798583984,-0.130582021495381,1739502692.384293,52.639949798583984,3.106578552675704,1739502692.3842945,52.639949798583984,2.2956157865593845 +1739502692.404256,52.6599497795105,29.064188959637875,1739502692.4042587,52.6599497795105,-0.05792141736458767,1739502692.4042618,52.6599497795105,83.85349301142139,1739502692.4042647,52.6599497795105,22.911990705370705,1739502692.4042664,52.6599497795105,-0.022,1739502692.404268,52.6599497795105,3.135753926084083,1739502692.4042695,52.6599497795105,0.18113568111842318,1739502692.404271,52.6599497795105,0.03675090626822165,1739502692.404272,52.6599497795105,2.162753518583151,1739502692.4042737,52.6599497795105,0.0,1739502692.4042752,52.6599497795105,-0.11264598035489612,1739502692.4042764,52.6599497795105,3.106307740383685,1739502692.404278,52.6599497795105,2.281004515469384 +1739502692.4246511,52.67994976043701,29.064188959637875,1739502692.424654,52.67994976043701,-0.05792141736458767,1739502692.424657,52.67994976043701,83.85349301142139,1739502692.42466,52.67994976043701,22.911990705370705,1739502692.4246614,52.67994976043701,-0.022,1739502692.4246633,52.67994976043701,3.135753926084083,1739502692.4246647,52.67994976043701,0.18113568111842318,1739502692.4246662,52.67994976043701,0.03675090626822165,1739502692.4246674,52.67994976043701,2.162753518583151,1739502692.424669,52.67994976043701,0.0,1739502692.4246848,52.67994976043701,-0.11825099688623286,1739502692.4246905,52.67994976043701,3.106307740383685,1739502692.4246948,52.67994976043701,2.281004515469384 +1739502692.4442568,52.699949741363525,29.064188959637875,1739502692.4442596,52.699949741363525,-0.05792141736458767,1739502692.4442627,52.699949741363525,83.85349301142139,1739502692.4442654,52.699949741363525,22.911990705370705,1739502692.444267,52.699949741363525,-0.022,1739502692.4442687,52.699949741363525,3.135753926084083,1739502692.4442704,52.699949741363525,0.18113568111842318,1739502692.4442718,52.699949741363525,0.03675090626822165,1739502692.4442737,52.699949741363525,2.162753518583151,1739502692.444277,52.699949741363525,0.0,1739502692.4442782,52.699949741363525,-0.11825099688623286,1739502692.44428,52.699949741363525,3.106307740383685,1739502692.4442813,52.699949741363525,2.281004515469384 +1739502692.4641562,52.71994972229004,29.064188959637875,1739502692.4641588,52.71994972229004,-0.05792141736458767,1739502692.4641619,52.71994972229004,83.85349301142139,1739502692.4641645,52.71994972229004,22.911990705370705,1739502692.4641662,52.71994972229004,-0.022,1739502692.4641676,52.71994972229004,3.135753926084083,1739502692.4641695,52.71994972229004,0.18113568111842318,1739502692.4641707,52.71994972229004,0.03675090626822165,1739502692.4641721,52.71994972229004,2.162753518583151,1739502692.4641738,52.71994972229004,0.0,1739502692.464175,52.71994972229004,-0.11825099688623286,1739502692.4641767,52.71994972229004,3.106307740383685,1739502692.4641778,52.71994972229004,2.281004515469384 +1739502692.4842541,52.73994970321655,29.064188959637875,1739502692.484257,52.73994970321655,-0.05792141736458767,1739502692.48426,52.73994970321655,83.85349301142139,1739502692.4842632,52.73994970321655,22.911990705370705,1739502692.4842644,52.73994970321655,-0.022,1739502692.4842665,52.73994970321655,3.135753926084083,1739502692.484268,52.73994970321655,0.18113568111842318,1739502692.4842699,52.73994970321655,0.03675090626822165,1739502692.484271,52.73994970321655,2.162753518583151,1739502692.4842727,52.73994970321655,0.0,1739502692.4842741,52.73994970321655,-0.11825099688623286,1739502692.4842753,52.73994970321655,3.106307740383685,1739502692.484277,52.73994970321655,2.281004515469384 +1739502692.5043707,52.759949684143066,28.814084828268065,1739502692.5043733,52.759949684143066,-0.04907355844973704,1739502692.5043764,52.759949684143066,83.79945576160853,1739502692.504379,52.759949684143066,22.991911973424646,1739502692.5043805,52.759949684143066,-0.021686000246068083,1739502692.5043821,52.759949684143066,3.136888678479264,1739502692.5043836,52.759949684143066,0.17882960882942614,1739502692.5043848,52.759949684143066,0.04051300383618153,1739502692.5043862,52.759949684143066,2.1667471740794673,1739502692.5043879,52.759949684143066,0.0,1739502692.504389,52.759949684143066,-0.0936162383407872,1739502692.5043907,52.759949684143066,3.106168917216454,1739502692.5043921,52.759949684143066,2.268061779513149 +1739502692.5242133,52.77994966506958,28.814084828268065,1739502692.5242171,52.77994966506958,-0.04907355844973704,1739502692.5242221,52.77994966506958,83.79945576160853,1739502692.5242274,52.77994966506958,22.991911973424646,1739502692.5242305,52.77994966506958,-0.021686000246068083,1739502692.5242343,52.77994966506958,3.136888678479264,1739502692.5242379,52.77994966506958,0.17882960882942614,1739502692.5242414,52.77994966506958,0.04051300383618153,1739502692.5242448,52.77994966506958,2.1667471740794673,1739502692.5242484,52.77994966506958,0.0,1739502692.5242517,52.77994966506958,-0.10131460543368176,1739502692.5242553,52.77994966506958,3.106168917216454,1739502692.5242589,52.77994966506958,2.268061779513149 +1739502692.5442126,52.799949645996094,28.814084828268065,1739502692.5442152,52.799949645996094,-0.04907355844973704,1739502692.5442183,52.799949645996094,83.79945576160853,1739502692.544221,52.799949645996094,22.991911973424646,1739502692.5442224,52.799949645996094,-0.021686000246068083,1739502692.544224,52.799949645996094,3.136888678479264,1739502692.5442255,52.799949645996094,0.17882960882942614,1739502692.544227,52.799949645996094,0.04051300383618153,1739502692.5442283,52.799949645996094,2.1667471740794673,1739502692.54423,52.799949645996094,0.0,1739502692.5442314,52.799949645996094,-0.10131460543368176,1739502692.5442328,52.799949645996094,3.106168917216454,1739502692.5442345,52.799949645996094,2.268061779513149 +1739502692.5642092,52.81994962692261,28.814084828268065,1739502692.5642128,52.81994962692261,-0.04907355844973704,1739502692.5642176,52.81994962692261,83.79945576160853,1739502692.5642228,52.81994962692261,22.991911973424646,1739502692.5642257,52.81994962692261,-0.021686000246068083,1739502692.5642297,52.81994962692261,3.136888678479264,1739502692.564233,52.81994962692261,0.17882960882942614,1739502692.5642364,52.81994962692261,0.04051300383618153,1739502692.56424,52.81994962692261,2.1667471740794673,1739502692.5642433,52.81994962692261,0.0,1739502692.564247,52.81994962692261,-0.10131460543368176,1739502692.5642505,52.81994962692261,3.106168917216454,1739502692.5642538,52.81994962692261,2.268061779513149 +1739502692.584234,52.83994960784912,28.814084828268065,1739502692.5842369,52.83994960784912,-0.04907355844973704,1739502692.5842402,52.83994960784912,83.79945576160853,1739502692.5842433,52.83994960784912,22.991911973424646,1739502692.5842447,52.83994960784912,-0.021686000246068083,1739502692.5842469,52.83994960784912,3.136888678479264,1739502692.5842483,52.83994960784912,0.17882960882942614,1739502692.58425,52.83994960784912,0.04051300383618153,1739502692.5842512,52.83994960784912,2.1667471740794673,1739502692.5842526,52.83994960784912,0.0,1739502692.584254,52.83994960784912,-0.10131460543368176,1739502692.5842555,52.83994960784912,3.106168917216454,1739502692.5842571,52.83994960784912,2.268061779513149 +1739502692.604043,52.859949588775635,28.814084828268065,1739502692.6040454,52.859949588775635,-0.04907355844973704,1739502692.604048,52.859949588775635,83.79945576160853,1739502692.6040506,52.859949588775635,22.991911973424646,1739502692.604052,52.859949588775635,-0.021686000246068083,1739502692.6040537,52.859949588775635,3.136888678479264,1739502692.6040554,52.859949588775635,0.17882960882942614,1739502692.6040566,52.859949588775635,0.04051300383618153,1739502692.6040578,52.859949588775635,2.1667471740794673,1739502692.6040595,52.859949588775635,0.0,1739502692.6040606,52.859949588775635,-0.10131460543368176,1739502692.6040623,52.859949588775635,3.106168917216454,1739502692.6040637,52.859949588775635,2.268061779513149 +1739502692.6242244,52.87994956970215,28.56529521473258,1739502692.6242273,52.87994956970215,-0.04025872219436444,1739502692.6242304,52.87994956970215,84.35605233338389,1739502692.6242332,52.87994956970215,22.45720568172001,1739502692.6242347,52.87994956970215,-0.02,1739502692.6242366,52.87994956970215,3.138275962208658,1739502692.6242378,52.87994956970215,0.1958512523162258,1739502692.6242394,52.87994956970215,0.04031306931008312,1739502692.6242406,52.87994956970215,2.1374418783014675,1739502692.624242,52.87994956970215,0.0,1739502692.6242435,52.87994956970215,-0.1280291097755638,1739502692.624245,52.87994956970215,3.1062064012380866,1739502692.6242466,52.87994956970215,2.257122699996629 +1739502692.6439893,52.89994955062866,28.56529521473258,1739502692.6439915,52.89994955062866,-0.04025872219436444,1739502692.6439946,52.89994955062866,84.35605233338389,1739502692.6439974,52.89994955062866,22.45720568172001,1739502692.6439986,52.89994955062866,-0.02,1739502692.6440003,52.89994955062866,3.138275962208658,1739502692.6440017,52.89994955062866,0.1958512523162258,1739502692.6440032,52.89994955062866,0.04031306931008312,1739502692.6440043,52.89994955062866,2.1374418783014675,1739502692.6440058,52.89994955062866,0.0,1739502692.6440072,52.89994955062866,-0.11968082169516148,1739502692.6440086,52.89994955062866,3.1062064012380866,1739502692.6440103,52.89994955062866,2.257122699996629 +1739502692.6641407,52.919949531555176,28.56529521473258,1739502692.6641436,52.919949531555176,-0.04025872219436444,1739502692.6641467,52.919949531555176,84.35605233338389,1739502692.6641493,52.919949531555176,22.45720568172001,1739502692.6641505,52.919949531555176,-0.02,1739502692.6641524,52.919949531555176,3.138275962208658,1739502692.6641538,52.919949531555176,0.1958512523162258,1739502692.6641552,52.919949531555176,0.04031306931008312,1739502692.6641564,52.919949531555176,2.1374418783014675,1739502692.6641579,52.919949531555176,0.0,1739502692.6641593,52.919949531555176,-0.11968082169516148,1739502692.6641607,52.919949531555176,3.1062064012380866,1739502692.6641622,52.919949531555176,2.257122699996629 +1739502692.683962,52.93994951248169,28.56529521473258,1739502692.6839643,52.93994951248169,-0.04025872219436444,1739502692.6839669,52.93994951248169,84.35605233338389,1739502692.6839695,52.93994951248169,22.45720568172001,1739502692.6839712,52.93994951248169,-0.02,1739502692.6839728,52.93994951248169,3.138275962208658,1739502692.683974,52.93994951248169,0.1958512523162258,1739502692.6839757,52.93994951248169,0.04031306931008312,1739502692.6839767,52.93994951248169,2.1374418783014675,1739502692.6839783,52.93994951248169,0.0,1739502692.6839797,52.93994951248169,-0.11968082169516148,1739502692.683981,52.93994951248169,3.1062064012380866,1739502692.6839826,52.93994951248169,2.257122699996629 +1739502692.704017,52.9599494934082,28.56529521473258,1739502692.7040193,52.9599494934082,-0.04025872219436444,1739502692.704022,52.9599494934082,84.35605233338389,1739502692.7040248,52.9599494934082,22.45720568172001,1739502692.7040265,52.9599494934082,-0.02,1739502692.7040281,52.9599494934082,3.138275962208658,1739502692.7040293,52.9599494934082,0.1958512523162258,1739502692.7040308,52.9599494934082,0.04031306931008312,1739502692.704032,52.9599494934082,2.1374418783014675,1739502692.7040336,52.9599494934082,0.0,1739502692.7040348,52.9599494934082,-0.11968082169516148,1739502692.7040362,52.9599494934082,3.1062064012380866,1739502692.7040377,52.9599494934082,2.257122699996629 +1739502692.724365,52.97994947433472,28.31781769232265,1739502692.7243676,52.97994947433472,-0.03150446107716576,1739502692.724371,52.97994947433472,84.38501595776695,1739502692.7243743,52.97994947433472,22.454393803718755,1739502692.7243757,52.97994947433472,-0.02,1739502692.7243776,52.97994947433472,3.1396305838959155,1739502692.724379,52.97994947433472,0.1955951696792149,1739502692.7243807,52.97994947433472,0.04369023536468364,1739502692.724382,52.97994947433472,2.1378798125610023,1739502692.724384,52.97994947433472,0.0,1739502692.7243853,52.97994947433472,-0.1000243686364298,1739502692.7243872,52.97994947433472,3.106265933656267,1739502692.7243886,52.97994947433472,2.244046826805718 +1739502692.7441013,52.99994945526123,28.31781769232265,1739502692.7441041,52.99994945526123,-0.03150446107716576,1739502692.7441072,52.99994945526123,84.38501595776695,1739502692.7441103,52.99994945526123,22.454393803718755,1739502692.7441118,52.99994945526123,-0.02,1739502692.7441137,52.99994945526123,3.1396305838959155,1739502692.744115,52.99994945526123,0.1955951696792149,1739502692.7441168,52.99994945526123,0.04369023536468364,1739502692.7441182,52.99994945526123,2.1378798125610023,1739502692.74412,52.99994945526123,0.0,1739502692.7441213,52.99994945526123,-0.10616701424471575,1739502692.744123,52.99994945526123,3.106265933656267,1739502692.7441244,52.99994945526123,2.244046826805718 +1739502692.764389,53.019949436187744,28.31781769232265,1739502692.764392,53.019949436187744,-0.03150446107716576,1739502692.7643952,53.019949436187744,84.38501595776695,1739502692.7643983,53.019949436187744,22.454393803718755,1739502692.7643995,53.019949436187744,-0.02,1739502692.7644017,53.019949436187744,3.1396305838959155,1739502692.764403,53.019949436187744,0.1955951696792149,1739502692.7644048,53.019949436187744,0.04369023536468364,1739502692.764406,53.019949436187744,2.1378798125610023,1739502692.7644083,53.019949436187744,0.0,1739502692.7644095,53.019949436187744,-0.10616701424471575,1739502692.7644114,53.019949436187744,3.106265933656267,1739502692.764413,53.019949436187744,2.244046826805718 +1739502692.784107,53.03994941711426,28.31781769232265,1739502692.7841094,53.03994941711426,-0.03150446107716576,1739502692.7841127,53.03994941711426,84.38501595776695,1739502692.7841158,53.03994941711426,22.454393803718755,1739502692.7841172,53.03994941711426,-0.02,1739502692.7841191,53.03994941711426,3.1396305838959155,1739502692.7841206,53.03994941711426,0.1955951696792149,1739502692.7841222,53.03994941711426,0.04369023536468364,1739502692.7841237,53.03994941711426,2.1378798125610023,1739502692.7841253,53.03994941711426,0.0,1739502692.7841268,53.03994941711426,-0.10616701424471575,1739502692.7841282,53.03994941711426,3.106265933656267,1739502692.7841303,53.03994941711426,2.244046826805718 +1739502692.8041131,53.05994939804077,28.31781769232265,1739502692.8041155,53.05994939804077,-0.03150446107716576,1739502692.8041186,53.05994939804077,84.38501595776695,1739502692.8041215,53.05994939804077,22.454393803718755,1739502692.8041232,53.05994939804077,-0.02,1739502692.8041246,53.05994939804077,3.1396305838959155,1739502692.8041263,53.05994939804077,0.1955951696792149,1739502692.8041277,53.05994939804077,0.04369023536468364,1739502692.8041296,53.05994939804077,2.1378798125610023,1739502692.8041313,53.05994939804077,0.0,1739502692.804133,53.05994939804077,-0.10616701424471575,1739502692.8041344,53.05994939804077,3.106265933656267,1739502692.8041363,53.05994939804077,2.244046826805718 +1739502692.824305,53.079949378967285,28.31781769232265,1739502692.824308,53.079949378967285,-0.03150446107716576,1739502692.824311,53.079949378967285,84.38501595776695,1739502692.824314,53.079949378967285,22.454393803718755,1739502692.8243158,53.079949378967285,-0.02,1739502692.8243177,53.079949378967285,3.1396305838959155,1739502692.8243196,53.079949378967285,0.1955951696792149,1739502692.824321,53.079949378967285,0.04369023536468364,1739502692.8243222,53.079949378967285,2.1378798125610023,1739502692.8243241,53.079949378967285,0.0,1739502692.8243253,53.079949378967285,-0.10616701424471575,1739502692.824327,53.079949378967285,3.106265933656267,1739502692.8243284,53.079949378967285,2.244046826805718 +1739502692.8441527,53.0999493598938,28.07169612949886,1739502692.8441548,53.0999493598938,-0.022826182776424453,1739502692.8441582,53.0999493598938,84.41382085889565,1739502692.8441613,53.0999493598938,22.448591738265076,1739502692.8441625,53.0999493598938,-0.02,1739502692.8441646,53.0999493598938,3.1410900517631477,1739502692.844166,53.0999493598938,0.19465933962906945,1739502692.8441677,53.0999493598938,0.047276804051635285,1739502692.844169,53.0999493598938,2.139480965586817,1739502692.8441708,53.0999493598938,0.0,1739502692.844172,53.0999493598938,-0.0871087236727949,1739502692.844174,53.0999493598938,3.1064653672295077,1739502692.8441753,53.0999493598938,2.2325454089682113 +1739502692.8642972,53.11994934082031,28.07169612949886,1739502692.8643,53.11994934082031,-0.022826182776424453,1739502692.8643034,53.11994934082031,84.41382085889565,1739502692.8643064,53.11994934082031,22.448591738265076,1739502692.8643079,53.11994934082031,-0.02,1739502692.8643098,53.11994934082031,3.1410900517631477,1739502692.8643115,53.11994934082031,0.19465933962906945,1739502692.8643131,53.11994934082031,0.047276804051635285,1739502692.8643146,53.11994934082031,2.139480965586817,1739502692.8643167,53.11994934082031,0.0,1739502692.8643181,53.11994934082031,-0.0930644433813943,1739502692.8643198,53.11994934082031,3.1064653672295077,1739502692.8643212,53.11994934082031,2.2325454089682113 +1739502692.8841848,53.139949321746826,28.07169612949886,1739502692.8841875,53.139949321746826,-0.022826182776424453,1739502692.8841906,53.139949321746826,84.41382085889565,1739502692.8841934,53.139949321746826,22.448591738265076,1739502692.884195,53.139949321746826,-0.02,1739502692.8841968,53.139949321746826,3.1410900517631477,1739502692.8841984,53.139949321746826,0.19465933962906945,1739502692.8841999,53.139949321746826,0.047276804051635285,1739502692.8842015,53.139949321746826,2.139480965586817,1739502692.8842032,53.139949321746826,0.0,1739502692.8842049,53.139949321746826,-0.0930644433813943,1739502692.8842063,53.139949321746826,3.1064653672295077,1739502692.884208,53.139949321746826,2.2325454089682113 +1739502692.9040585,53.15994930267334,28.07169612949886,1739502692.9040604,53.15994930267334,-0.022826182776424453,1739502692.9040635,53.15994930267334,84.41382085889565,1739502692.9040668,53.15994930267334,22.448591738265076,1739502692.9040685,53.15994930267334,-0.02,1739502692.9040701,53.15994930267334,3.1410900517631477,1739502692.9040716,53.15994930267334,0.19465933962906945,1739502692.9040732,53.15994930267334,0.047276804051635285,1739502692.9040747,53.15994930267334,2.139480965586817,1739502692.9040766,53.15994930267334,0.0,1739502692.9040778,53.15994930267334,-0.0930644433813943,1739502692.9040797,53.15994930267334,3.1064653672295077,1739502692.904081,53.15994930267334,2.2325454089682113 +1739502692.9242923,53.17994928359985,28.07169612949886,1739502692.9242952,53.17994928359985,-0.022826182776424453,1739502692.9242988,53.17994928359985,84.41382085889565,1739502692.9243019,53.17994928359985,22.448591738265076,1739502692.924303,53.17994928359985,-0.02,1739502692.924305,53.17994928359985,3.1410900517631477,1739502692.9243064,53.17994928359985,0.19465933962906945,1739502692.924308,53.17994928359985,0.047276804051635285,1739502692.9243095,53.17994928359985,2.139480965586817,1739502692.924311,53.17994928359985,0.0,1739502692.9243126,53.17994928359985,-0.0930644433813943,1739502692.9243143,53.17994928359985,3.1064653672295077,1739502692.924316,53.17994928359985,2.2325454089682113 +1739502692.9441729,53.19994926452637,27.826778362855208,1739502692.9441752,53.19994926452637,-0.014254532761818872,1739502692.9441783,53.19994926452637,85.04492056436618,1739502692.9441812,53.19994926452637,21.837889103231497,1739502692.944183,53.19994926452637,-0.016,1739502692.9441848,53.19994926452637,-3.1413012026857787,1739502692.9441864,53.19994926452637,0.20999790446738956,1739502692.9441879,53.19994926452637,0.04496256299177024,1739502692.944189,53.19994926452637,2.1133881296476726,1739502692.944191,53.19994926452637,0.0,1739502692.9441924,53.19994926452637,-0.11619636243460056,1739502692.9441943,53.19994926452637,3.1068123335510975,1739502692.9441957,53.19994926452637,2.222355762638622 +1739502692.9642997,53.21994924545288,27.826778362855208,1739502692.9643073,53.21994924545288,-0.014254532761818872,1739502692.9643202,53.21994924545288,85.04492056436618,1739502692.9643235,53.21994924545288,21.837889103231497,1739502692.9643373,53.21994924545288,-0.016,1739502692.96434,53.21994924545288,-3.1413012026857787,1739502692.964344,53.21994924545288,0.20999790446738956,1739502692.9643474,53.21994924545288,0.04496256299177024,1739502692.9643507,53.21994924545288,2.1133881296476726,1739502692.9643548,53.21994924545288,0.0,1739502692.9643674,53.21994924545288,-0.10896763299094925,1739502692.964369,53.21994924545288,3.1068123335510975,1739502692.9643712,53.21994924545288,2.222355762638622 +1739502692.9841425,53.239949226379395,27.826778362855208,1739502692.984145,53.239949226379395,-0.014254532761818872,1739502692.984148,53.239949226379395,85.04492056436618,1739502692.984151,53.239949226379395,21.837889103231497,1739502692.9841523,53.239949226379395,-0.016,1739502692.9841542,53.239949226379395,-3.1413012026857787,1739502692.9841557,53.239949226379395,0.20999790446738956,1739502692.984157,53.239949226379395,0.04496256299177024,1739502692.9841585,53.239949226379395,2.1133881296476726,1739502692.9841602,53.239949226379395,0.0,1739502692.9841616,53.239949226379395,-0.10896763299094925,1739502692.984163,53.239949226379395,3.1068123335510975,1739502692.9841647,53.239949226379395,2.222355762638622 +1739502693.0042088,53.25994920730591,27.826778362855208,1739502693.0042114,53.25994920730591,-0.014254532761818872,1739502693.0042145,53.25994920730591,85.04492056436618,1739502693.0042176,53.25994920730591,21.837889103231497,1739502693.004219,53.25994920730591,-0.016,1739502693.004221,53.25994920730591,-3.1413012026857787,1739502693.0042224,53.25994920730591,0.20999790446738956,1739502693.004224,53.25994920730591,0.04496256299177024,1739502693.0042255,53.25994920730591,2.1133881296476726,1739502693.0042274,53.25994920730591,0.0,1739502693.0042286,53.25994920730591,-0.10896763299094925,1739502693.0042303,53.25994920730591,3.1068123335510975,1739502693.0042315,53.25994920730591,2.222355762638622 +1739502693.0243578,53.27994918823242,27.826778362855208,1739502693.024363,53.27994918823242,-0.014254532761818872,1739502693.0243695,53.27994918823242,85.04492056436618,1739502693.0243769,53.27994918823242,21.837889103231497,1739502693.0243807,53.27994918823242,-0.016,1739502693.0243857,53.27994918823242,-3.1413012026857787,1739502693.0243907,53.27994918823242,0.20999790446738956,1739502693.0243948,53.27994918823242,0.04496256299177024,1739502693.0243983,53.27994918823242,2.1133881296476726,1739502693.0244024,53.27994918823242,0.0,1739502693.024406,53.27994918823242,-0.10896763299094925,1739502693.0244098,53.27994918823242,3.1068123335510975,1739502693.0244136,53.27994918823242,2.222355762638622 +1739502693.0440335,53.299949169158936,27.826778362855208,1739502693.0440361,53.299949169158936,-0.014254532761818872,1739502693.0440392,53.299949169158936,85.04492056436618,1739502693.0440423,53.299949169158936,21.837889103231497,1739502693.0440435,53.299949169158936,-0.016,1739502693.0440457,53.299949169158936,-3.1413012026857787,1739502693.044047,53.299949169158936,0.20999790446738956,1739502693.0440483,53.299949169158936,0.04496256299177024,1739502693.04405,53.299949169158936,2.1133881296476726,1739502693.0440514,53.299949169158936,0.0,1739502693.044053,53.299949169158936,-0.10896763299094925,1739502693.0440547,53.299949169158936,3.1068123335510975,1739502693.0440567,53.299949169158936,2.222355762638622 +1739502693.0644453,53.31994915008545,27.58307653651783,1739502693.0644493,53.31994915008545,-0.0058176167547916435,1739502693.0644546,53.31994915008545,85.06710586747889,1739502693.0644605,53.31994915008545,21.839850450379863,1739502693.0644636,53.31994915008545,-0.016,1739502693.064468,53.31994915008545,-3.1398197175389186,1739502693.0644715,53.31994915008545,0.2076840474058266,1739502693.064475,53.31994915008545,0.04835190178068724,1739502693.0644789,53.31994915008545,2.117303815102238,1739502693.064483,53.31994915008545,0.0,1739502693.0644867,53.31994915008545,-0.08571088339065015,1739502693.0644906,53.31994915008545,3.10719619501144,1739502693.0644941,53.31994915008545,2.2102824375080825 +1739502693.0841088,53.33994913101196,27.58307653651783,1739502693.0841115,53.33994913101196,-0.0058176167547916435,1739502693.0841143,53.33994913101196,85.06710586747889,1739502693.0841172,53.33994913101196,21.839850450379863,1739502693.0841188,53.33994913101196,-0.016,1739502693.0841205,53.33994913101196,-3.1398197175389186,1739502693.0841222,53.33994913101196,0.2076840474058266,1739502693.0841238,53.33994913101196,0.04835190178068724,1739502693.0841253,53.33994913101196,2.117303815102238,1739502693.084127,53.33994913101196,0.0,1739502693.0841281,53.33994913101196,-0.09297862240584465,1739502693.0841298,53.33994913101196,3.10719619501144,1739502693.0841312,53.33994913101196,2.2102824375080825 +1739502693.1041632,53.35994911193848,27.58307653651783,1739502693.1041653,53.35994911193848,-0.0058176167547916435,1739502693.1041687,53.35994911193848,85.06710586747889,1739502693.1041718,53.35994911193848,21.839850450379863,1739502693.1041734,53.35994911193848,-0.016,1739502693.104175,53.35994911193848,-3.1398197175389186,1739502693.1041765,53.35994911193848,0.2076840474058266,1739502693.1041782,53.35994911193848,0.04835190178068724,1739502693.1041796,53.35994911193848,2.117303815102238,1739502693.1041813,53.35994911193848,0.0,1739502693.1041827,53.35994911193848,-0.09297862240584465,1739502693.1041846,53.35994911193848,3.10719619501144,1739502693.1041858,53.35994911193848,2.2102824375080825 +1739502693.1250803,53.37994909286499,27.58307653651783,1739502693.1250844,53.37994909286499,-0.0058176167547916435,1739502693.1250885,53.37994909286499,85.06710586747889,1739502693.1250925,53.37994909286499,21.839850450379863,1739502693.1250944,53.37994909286499,-0.016,1739502693.125097,53.37994909286499,-3.1398197175389186,1739502693.1250987,53.37994909286499,0.2076840474058266,1739502693.1251009,53.37994909286499,0.04835190178068724,1739502693.1251023,53.37994909286499,2.117303815102238,1739502693.125105,53.37994909286499,0.0,1739502693.1251066,53.37994909286499,-0.09297862240584465,1739502693.1251087,53.37994909286499,3.10719619501144,1739502693.1251109,53.37994909286499,2.2102824375080825 +1739502693.1447904,53.399949073791504,27.58307653651783,1739502693.1447942,53.399949073791504,-0.0058176167547916435,1739502693.1447983,53.399949073791504,85.06710586747889,1739502693.1448023,53.399949073791504,21.839850450379863,1739502693.144804,53.399949073791504,-0.016,1739502693.1448066,53.399949073791504,-3.1398197175389186,1739502693.1448085,53.399949073791504,0.2076840474058266,1739502693.1448104,53.399949073791504,0.04835190178068724,1739502693.1448123,53.399949073791504,2.117303815102238,1739502693.1448143,53.399949073791504,0.0,1739502693.1448162,53.399949073791504,-0.09297862240584465,1739502693.144818,53.399949073791504,3.10719619501144,1739502693.1448202,53.399949073791504,2.2102824375080825 +1739502693.164574,53.41994905471802,27.340599944413864,1739502693.164577,53.41994905471802,0.0024836875830622773,1739502693.1645808,53.41994905471802,85.08917953866468,1739502693.1645846,53.41994905471802,21.838141891356408,1739502693.1645865,53.41994905471802,-0.016,1739502693.1645885,53.41994905471802,-3.138233497030691,1739502693.1645906,53.41994905471802,0.20558980328129692,1739502693.1645923,53.41994905471802,0.05214355924277005,1739502693.1645942,53.41994905471802,2.1208541092045032,1739502693.1645968,53.41994905471802,0.0,1739502693.1645985,53.41994905471802,-0.07300356164054181,1739502693.1646004,53.41994905471802,3.1075800564717824,1739502693.1646023,53.41994905471802,2.2000998814269144 +1739502693.184808,53.43994903564453,27.340599944413864,1739502693.1848116,53.43994903564453,0.0024836875830622773,1739502693.1848154,53.43994903564453,85.08917953866468,1739502693.184819,53.43994903564453,21.838141891356408,1739502693.1848207,53.43994903564453,-0.016,1739502693.184823,53.43994903564453,-3.138233497030691,1739502693.1848252,53.43994903564453,0.20558980328129692,1739502693.1848269,53.43994903564453,0.05214355924277005,1739502693.1848285,53.43994903564453,2.1208541092045032,1739502693.1848307,53.43994903564453,0.0,1739502693.1848326,53.43994903564453,-0.07924577222241114,1739502693.1848345,53.43994903564453,3.1075800564717824,1739502693.1848364,53.43994903564453,2.2000998814269144 +1739502693.2047808,53.459949016571045,27.340599944413864,1739502693.2047842,53.459949016571045,0.0024836875830622773,1739502693.2047884,53.459949016571045,85.08917953866468,1739502693.2047925,53.459949016571045,21.838141891356408,1739502693.2047944,53.459949016571045,-0.016,1739502693.204797,53.459949016571045,-3.138233497030691,1739502693.204799,53.459949016571045,0.20558980328129692,1739502693.2048008,53.459949016571045,0.05214355924277005,1739502693.2048025,53.459949016571045,2.1208541092045032,1739502693.2048047,53.459949016571045,0.0,1739502693.2048063,53.459949016571045,-0.07924577222241114,1739502693.2048085,53.459949016571045,3.1075800564717824,1739502693.2048104,53.459949016571045,2.2000998814269144 +1739502693.2246327,53.47994899749756,27.340599944413864,1739502693.2246358,53.47994899749756,0.0024836875830622773,1739502693.2246397,53.47994899749756,85.08917953866468,1739502693.2246432,53.47994899749756,21.838141891356408,1739502693.2246451,53.47994899749756,-0.016,1739502693.2246473,53.47994899749756,-3.138233497030691,1739502693.224649,53.47994899749756,0.20558980328129692,1739502693.2246509,53.47994899749756,0.05214355924277005,1739502693.2246525,53.47994899749756,2.1208541092045032,1739502693.2246547,53.47994899749756,0.0,1739502693.2246563,53.47994899749756,-0.07924577222241114,1739502693.2246583,53.47994899749756,3.1075800564717824,1739502693.22466,53.47994899749756,2.2000998814269144 +1739502693.2445765,53.49994897842407,27.340599944413864,1739502693.2445798,53.49994897842407,0.0024836875830622773,1739502693.2445838,53.49994897842407,85.08917953866468,1739502693.2445877,53.49994897842407,21.838141891356408,1739502693.2445896,53.49994897842407,-0.016,1739502693.244592,53.49994897842407,-3.138233497030691,1739502693.2445936,53.49994897842407,0.20558980328129692,1739502693.2445958,53.49994897842407,0.05214355924277005,1739502693.2445972,53.49994897842407,2.1208541092045032,1739502693.2445996,53.49994897842407,0.0,1739502693.244601,53.49994897842407,-0.07924577222241114,1739502693.2446032,53.49994897842407,3.1075800564717824,1739502693.2446053,53.49994897842407,2.2000998814269144 +1739502693.2651188,53.519948959350586,27.340599944413864,1739502693.2651227,53.519948959350586,0.0024836875830622773,1739502693.265127,53.519948959350586,85.08917953866468,1739502693.2651308,53.519948959350586,21.838141891356408,1739502693.265133,53.519948959350586,-0.016,1739502693.2651353,53.519948959350586,-3.138233497030691,1739502693.2651377,53.519948959350586,0.20558980328129692,1739502693.2651393,53.519948959350586,0.05214355924277005,1739502693.2651412,53.519948959350586,2.1208541092045032,1739502693.2651436,53.519948959350586,0.0,1739502693.2651453,53.519948959350586,-0.07924577222241114,1739502693.2651474,53.519948959350586,3.1075800564717824,1739502693.2651494,53.519948959350586,2.2000998814269144 +1739502693.2847912,53.5399489402771,27.099149627479964,1739502693.2847948,53.5399489402771,0.010643899496992404,1739502693.2847986,53.5399489402771,85.62591484748987,1739502693.2848027,53.5399489402771,21.31851151946758,1739502693.2848046,53.5399489402771,-0.016,1739502693.284807,53.5399489402771,-3.136983523884064,1739502693.2848089,53.5399489402771,0.22017550363661234,1739502693.2848108,53.5399489402771,0.050597405416012285,1739502693.2848125,53.5399489402771,2.0962506179946807,1739502693.2848146,53.5399489402771,0.0,1739502693.2848163,53.5399489402771,-0.10259272135001363,1739502693.2848184,53.5399489402771,3.1081045300602463,1739502693.2848203,53.5399489402771,2.1915474129587365 +1739502693.304666,53.55994892120361,27.099149627479964,1739502693.3046696,53.55994892120361,0.010643899496992404,1739502693.304695,53.55994892120361,85.62591484748987,1739502693.3047054,53.55994892120361,21.31851151946758,1739502693.3047082,53.55994892120361,-0.016,1739502693.304711,53.55994892120361,-3.136983523884064,1739502693.3047132,53.55994892120361,0.22017550363661234,1739502693.3047152,53.55994892120361,0.050597405416012285,1739502693.304717,53.55994892120361,2.0962506179946807,1739502693.3047192,53.55994892120361,0.0,1739502693.3047209,53.55994892120361,-0.09529679496405574,1739502693.3047228,53.55994892120361,3.1081045300602463,1739502693.3047247,53.55994892120361,2.1915474129587365 +1739502693.3251333,53.57994890213013,27.099149627479964,1739502693.3251374,53.57994890213013,0.010643899496992404,1739502693.3251429,53.57994890213013,85.62591484748987,1739502693.325147,53.57994890213013,21.31851151946758,1739502693.3251488,53.57994890213013,-0.016,1739502693.3251512,53.57994890213013,-3.136983523884064,1739502693.3251534,53.57994890213013,0.22017550363661234,1739502693.325155,53.57994890213013,0.050597405416012285,1739502693.3251572,53.57994890213013,2.0962506179946807,1739502693.325159,53.57994890213013,0.0,1739502693.3251612,53.57994890213013,-0.09529679496405574,1739502693.3251634,53.57994890213013,3.1081045300602463,1739502693.3251653,53.57994890213013,2.1915474129587365 +1739502693.344808,53.59994888305664,27.099149627479964,1739502693.3448114,53.59994888305664,0.010643899496992404,1739502693.3448153,53.59994888305664,85.62591484748987,1739502693.3448193,53.59994888305664,21.31851151946758,1739502693.344821,53.59994888305664,-0.016,1739502693.3448234,53.59994888305664,-3.136983523884064,1739502693.344825,53.59994888305664,0.22017550363661234,1739502693.3448267,53.59994888305664,0.050597405416012285,1739502693.3448284,53.59994888305664,2.0962506179946807,1739502693.3448305,53.59994888305664,0.0,1739502693.3448322,53.59994888305664,-0.09529679496405574,1739502693.344834,53.59994888305664,3.1081045300602463,1739502693.3448362,53.59994888305664,2.1915474129587365 +1739502693.3650017,53.619948863983154,27.099149627479964,1739502693.365005,53.619948863983154,0.010643899496992404,1739502693.365009,53.619948863983154,85.62591484748987,1739502693.3650126,53.619948863983154,21.31851151946758,1739502693.3650146,53.619948863983154,-0.016,1739502693.3650172,53.619948863983154,-3.136983523884064,1739502693.3650188,53.619948863983154,0.22017550363661234,1739502693.365021,53.619948863983154,0.050597405416012285,1739502693.3650224,53.619948863983154,2.0962506179946807,1739502693.3650248,53.619948863983154,0.0,1739502693.3650265,53.619948863983154,-0.09529679496405574,1739502693.3650286,53.619948863983154,3.1081045300602463,1739502693.3650308,53.619948863983154,2.1915474129587365 +1739502693.3847902,53.63994884490967,26.85873053082815,1739502693.3847938,53.63994884490967,0.018638339146165528,1739502693.3847978,53.63994884490967,85.64756056062818,1739502693.3848016,53.63994884490967,21.31768866912046,1739502693.3848033,53.63994884490967,-0.016,1739502693.384806,53.63994884490967,-3.1353415028453417,1739502693.3848076,53.63994884490967,0.21711647872860387,1739502693.3848095,53.63994884490967,0.05430086426042247,1739502693.3848112,53.63994884490967,2.1013868865037244,1739502693.3848133,53.63994884490967,0.0,1739502693.3848152,53.63994884490967,-0.07268195199936457,1739502693.3848171,53.63994884490967,3.1086512057394478,1739502693.384819,53.63994884490967,2.181135981563135 +1739502693.4047172,53.65994882583618,26.85873053082815,1739502693.4047208,53.65994882583618,0.018638339146165528,1739502693.4047248,53.65994882583618,85.64756056062818,1739502693.4047284,53.65994882583618,21.31768866912046,1739502693.40473,53.65994882583618,-0.016,1739502693.4047325,53.65994882583618,-3.1353415028453417,1739502693.4047344,53.65994882583618,0.21711647872860387,1739502693.4047363,53.65994882583618,0.05430086426042247,1739502693.404738,53.65994882583618,2.1013868865037244,1739502693.40474,53.65994882583618,0.0,1739502693.4047415,53.65994882583618,-0.07974909505941064,1739502693.4047437,53.65994882583618,3.1086512057394478,1739502693.4047456,53.65994882583618,2.181135981563135 +1739502693.4252315,53.679948806762695,26.85873053082815,1739502693.4252348,53.679948806762695,0.018638339146165528,1739502693.4252393,53.679948806762695,85.64756056062818,1739502693.4252431,53.679948806762695,21.31768866912046,1739502693.4252446,53.679948806762695,-0.016,1739502693.4252472,53.679948806762695,-3.1353415028453417,1739502693.425249,53.679948806762695,0.21711647872860387,1739502693.4252508,53.679948806762695,0.05430086426042247,1739502693.4252527,53.679948806762695,2.1013868865037244,1739502693.4252548,53.679948806762695,0.0,1739502693.4252567,53.679948806762695,-0.07974909505941064,1739502693.4252586,53.679948806762695,3.1086512057394478,1739502693.4252605,53.679948806762695,2.181135981563135 +1739502693.444713,53.69994878768921,26.85873053082815,1739502693.4447165,53.69994878768921,0.018638339146165528,1739502693.444721,53.69994878768921,85.64756056062818,1739502693.4447248,53.69994878768921,21.31768866912046,1739502693.4447267,53.69994878768921,-0.016,1739502693.444729,53.69994878768921,-3.1353415028453417,1739502693.4447312,53.69994878768921,0.21711647872860387,1739502693.444733,53.69994878768921,0.05430086426042247,1739502693.4447348,53.69994878768921,2.1013868865037244,1739502693.4447367,53.69994878768921,0.0,1739502693.4447386,53.69994878768921,-0.07974909505941064,1739502693.4447403,53.69994878768921,3.1086512057394478,1739502693.4447424,53.69994878768921,2.181135981563135 +1739502693.4652364,53.71994876861572,26.85873053082815,1739502693.4652402,53.71994876861572,0.018638339146165528,1739502693.4652448,53.71994876861572,85.64756056062818,1739502693.4652486,53.71994876861572,21.31768866912046,1739502693.4652503,53.71994876861572,-0.016,1739502693.4652526,53.71994876861572,-3.1353415028453417,1739502693.4652543,53.71994876861572,0.21711647872860387,1739502693.4652562,53.71994876861572,0.05430086426042247,1739502693.465258,53.71994876861572,2.1013868865037244,1739502693.46526,53.71994876861572,0.0,1739502693.465262,53.71994876861572,-0.07974909505941064,1739502693.465264,53.71994876861572,3.1086512057394478,1739502693.4652662,53.71994876861572,2.181135981563135 +1739502693.4851527,53.739948749542236,26.85873053082815,1739502693.4851563,53.739948749542236,0.018638339146165528,1739502693.4851604,53.739948749542236,85.64756056062818,1739502693.485164,53.739948749542236,21.31768866912046,1739502693.4851658,53.739948749542236,-0.016,1739502693.4851682,53.739948749542236,-3.1353415028453417,1739502693.4851701,53.739948749542236,0.21711647872860387,1739502693.485172,53.739948749542236,0.05430086426042247,1739502693.4851735,53.739948749542236,2.1013868865037244,1739502693.4851756,53.739948749542236,0.0,1739502693.4851773,53.739948749542236,-0.07974909505941064,1739502693.4851797,53.739948749542236,3.1086512057394478,1739502693.4851813,53.739948749542236,2.181135981563135 +1739502693.5049045,53.75994873046875,26.619357339301683,1739502693.504908,53.75994873046875,0.0264597308979706,1739502693.504912,53.75994873046875,86.08372232054519,1739502693.5049157,53.75994873046875,20.898714220806816,1739502693.5049176,53.75994873046875,-0.017,1739502693.5049198,53.75994873046875,-3.133995798840719,1739502693.5049217,53.75994873046875,0.22829984249812163,1739502693.5049233,53.75994873046875,0.05356805739193359,1739502693.504925,53.75994873046875,2.0826702780270905,1739502693.504927,53.75994873046875,0.0,1739502693.5049286,53.75994873046875,-0.09447669996534196,1739502693.5049307,53.75994873046875,3.1092719870687766,1739502693.5049326,53.75994873046875,2.1725445984417737 +1739502693.5249982,53.779948711395264,26.619357339301683,1739502693.525002,53.779948711395264,0.0264597308979706,1739502693.525006,53.779948711395264,86.08372232054519,1739502693.5250099,53.779948711395264,20.898714220806816,1739502693.5250118,53.779948711395264,-0.017,1739502693.5250142,53.779948711395264,-3.133995798840719,1739502693.525016,53.779948711395264,0.22829984249812163,1739502693.5250185,53.779948711395264,0.05356805739193359,1739502693.5250201,53.779948711395264,2.0826702780270905,1739502693.5250223,53.779948711395264,0.0,1739502693.525024,53.779948711395264,-0.08987432041468324,1739502693.525026,53.779948711395264,3.1092719870687766,1739502693.5250285,53.779948711395264,2.1725445984417737 +1739502693.5447743,53.79994869232178,26.619357339301683,1739502693.5447779,53.79994869232178,0.0264597308979706,1739502693.544782,53.79994869232178,86.08372232054519,1739502693.5447857,53.79994869232178,20.898714220806816,1739502693.5447874,53.79994869232178,-0.017,1739502693.5447898,53.79994869232178,-3.133995798840719,1739502693.5447917,53.79994869232178,0.22829984249812163,1739502693.5447934,53.79994869232178,0.05356805739193359,1739502693.544795,53.79994869232178,2.0826702780270905,1739502693.5447974,53.79994869232178,0.0,1739502693.5447993,53.79994869232178,-0.08987432041468324,1739502693.544801,53.79994869232178,3.1092719870687766,1739502693.5448031,53.79994869232178,2.1725445984417737 +1739502693.5647416,53.81994867324829,26.619357339301683,1739502693.5647447,53.81994867324829,0.0264597308979706,1739502693.5647485,53.81994867324829,86.08372232054519,1739502693.564752,53.81994867324829,20.898714220806816,1739502693.564754,53.81994867324829,-0.017,1739502693.564756,53.81994867324829,-3.133995798840719,1739502693.5647578,53.81994867324829,0.22829984249812163,1739502693.5647595,53.81994867324829,0.05356805739193359,1739502693.5647614,53.81994867324829,2.0826702780270905,1739502693.5647633,53.81994867324829,0.0,1739502693.564765,53.81994867324829,-0.08987432041468324,1739502693.564767,53.81994867324829,3.1092719870687766,1739502693.5647688,53.81994867324829,2.1725445984417737 +1739502693.584669,53.839948654174805,26.619357339301683,1739502693.5846913,53.839948654174805,0.0264597308979706,1739502693.5846956,53.839948654174805,86.08372232054519,1739502693.5846996,53.839948654174805,20.898714220806816,1739502693.5847015,53.839948654174805,-0.017,1739502693.5847037,53.839948654174805,-3.133995798840719,1739502693.5847058,53.839948654174805,0.22829984249812163,1739502693.5847075,53.839948654174805,0.05356805739193359,1739502693.5847094,53.839948654174805,2.0826702780270905,1739502693.5847113,53.839948654174805,0.0,1739502693.5847132,53.839948654174805,-0.08987432041468324,1739502693.5847154,53.839948654174805,3.1092719870687766,1739502693.584717,53.839948654174805,2.1725445984417737 +1739502693.6047533,53.85994863510132,26.38098964360499,1739502693.604756,53.85994863510132,0.034098539524910265,1739502693.6047602,53.85994863510132,86.12592868030077,1739502693.604764,53.85994863510132,20.876154239478986,1739502693.604766,53.85994863510132,-0.017,1739502693.6047685,53.85994863510132,-3.1323104374610375,1739502693.6047704,53.85994863510132,0.22550553220012773,1739502693.604772,53.85994863510132,0.057139943164241425,1739502693.604774,53.85994863510132,2.087331187301008,1739502693.604776,53.85994863510132,0.0,1739502693.6047778,53.85994863510132,-0.06880653451738815,1739502693.6047795,53.85994863510132,3.109900178963118,1739502693.6047816,53.85994863510132,2.1627214092279026 +1739502693.6251264,53.87994861602783,26.38098964360499,1739502693.62513,53.87994861602783,0.034098539524910265,1739502693.625134,53.87994861602783,86.12592868030077,1739502693.6251378,53.87994861602783,20.876154239478986,1739502693.6251397,53.87994861602783,-0.017,1739502693.6251423,53.87994861602783,-3.1323104374610375,1739502693.625144,53.87994861602783,0.22550553220012773,1739502693.6251462,53.87994861602783,0.057139943164241425,1739502693.6251476,53.87994861602783,2.087331187301008,1739502693.6251502,53.87994861602783,0.0,1739502693.625152,53.87994861602783,-0.07539022192689471,1739502693.625154,53.87994861602783,3.109900178963118,1739502693.6251562,53.87994861602783,2.1627214092279026 +1739502693.6447017,53.899948596954346,26.38098964360499,1739502693.644705,53.899948596954346,0.034098539524910265,1739502693.644709,53.899948596954346,86.12592868030077,1739502693.6447127,53.899948596954346,20.876154239478986,1739502693.6447148,53.899948596954346,-0.017,1739502693.6447172,53.899948596954346,-3.1323104374610375,1739502693.6447194,53.899948596954346,0.22550553220012773,1739502693.6447215,53.899948596954346,0.057139943164241425,1739502693.6447232,53.899948596954346,2.087331187301008,1739502693.6447256,53.899948596954346,0.0,1739502693.6447272,53.899948596954346,-0.07539022192689471,1739502693.6447291,53.899948596954346,3.109900178963118,1739502693.6447308,53.899948596954346,2.1627214092279026 +1739502693.6650648,53.91994857788086,26.38098964360499,1739502693.6650689,53.91994857788086,0.034098539524910265,1739502693.6650736,53.91994857788086,86.12592868030077,1739502693.6650772,53.91994857788086,20.876154239478986,1739502693.6650794,53.91994857788086,-0.017,1739502693.6650817,53.91994857788086,-3.1323104374610375,1739502693.665084,53.91994857788086,0.22550553220012773,1739502693.6650858,53.91994857788086,0.057139943164241425,1739502693.6650877,53.91994857788086,2.087331187301008,1739502693.6650898,53.91994857788086,0.0,1739502693.6650915,53.91994857788086,-0.07539022192689471,1739502693.6650941,53.91994857788086,3.109900178963118,1739502693.6650963,53.91994857788086,2.1627214092279026 +1739502693.6847746,53.93994855880737,26.38098964360499,1739502693.6847782,53.93994855880737,0.034098539524910265,1739502693.6847823,53.93994855880737,86.12592868030077,1739502693.6847858,53.93994855880737,20.876154239478986,1739502693.6847878,53.93994855880737,-0.017,1739502693.6847901,53.93994855880737,-3.1323104374610375,1739502693.6847918,53.93994855880737,0.22550553220012773,1739502693.6847937,53.93994855880737,0.057139943164241425,1739502693.6847951,53.93994855880737,2.087331187301008,1739502693.6847975,53.93994855880737,0.0,1739502693.684799,53.93994855880737,-0.07539022192689471,1739502693.684801,53.93994855880737,3.109900178963118,1739502693.684803,53.93994855880737,2.1627214092279026 +1739502693.7047346,53.95994853973389,26.38098964360499,1739502693.7047386,53.95994853973389,0.034098539524910265,1739502693.7047424,53.95994853973389,86.12592868030077,1739502693.7047462,53.95994853973389,20.876154239478986,1739502693.704748,53.95994853973389,-0.017,1739502693.7047503,53.95994853973389,-3.1323104374610375,1739502693.7047522,53.95994853973389,0.22550553220012773,1739502693.704754,53.95994853973389,0.057139943164241425,1739502693.7047558,53.95994853973389,2.087331187301008,1739502693.704758,53.95994853973389,0.0,1739502693.7047596,53.95994853973389,-0.07539022192689471,1739502693.7047615,53.95994853973389,3.109900178963118,1739502693.7047634,53.95994853973389,2.1627214092279026 +1739502693.7252703,53.9799485206604,26.143608042403464,1739502693.7252736,53.9799485206604,0.04154348841554878,1739502693.7252784,53.9799485206604,86.62107041480232,1739502693.7252827,53.9799485206604,20.39726753471378,1739502693.7252846,53.9799485206604,-0.016956582887282388,1739502693.7252872,53.9799485206604,-3.131412600675192,1739502693.7252889,53.9799485206604,0.23613921663892992,1739502693.725291,53.9799485206604,0.05491021112652436,1739502693.7252927,53.9799485206604,2.0696496848075023,1739502693.7252948,53.9799485206604,0.0,1739502693.7252967,53.9799485206604,-0.08929223175939983,1739502693.7252984,53.9799485206604,3.110669419601192,1739502693.7253006,53.9799485206604,2.154597535645846 +1739502693.7447214,53.999948501586914,26.143608042403464,1739502693.7447252,53.999948501586914,0.04154348841554878,1739502693.7447293,53.999948501586914,86.62107041480232,1739502693.7447329,53.999948501586914,20.39726753471378,1739502693.7447348,53.999948501586914,-0.016956582887282388,1739502693.7447374,53.999948501586914,-3.131412600675192,1739502693.744739,53.999948501586914,0.23613921663892992,1739502693.7447412,53.999948501586914,0.05491021112652436,1739502693.7447429,53.999948501586914,2.0696496848075023,1739502693.7447453,53.999948501586914,0.0,1739502693.744747,53.999948501586914,-0.08494785083834389,1739502693.7447488,53.999948501586914,3.110669419601192,1739502693.7447505,53.999948501586914,2.154597535645846 +1739502693.7652664,54.01994848251343,26.143608042403464,1739502693.76527,54.01994848251343,0.04154348841554878,1739502693.765274,54.01994848251343,86.62107041480232,1739502693.7652776,54.01994848251343,20.39726753471378,1739502693.7652795,54.01994848251343,-0.016956582887282388,1739502693.7652822,54.01994848251343,-3.131412600675192,1739502693.7652838,54.01994848251343,0.23613921663892992,1739502693.7652857,54.01994848251343,0.05491021112652436,1739502693.7652874,54.01994848251343,2.0696496848075023,1739502693.7652895,54.01994848251343,0.0,1739502693.7652912,54.01994848251343,-0.08494785083834389,1739502693.7652936,54.01994848251343,3.110669419601192,1739502693.765296,54.01994848251343,2.154597535645846 +1739502693.7851772,54.03994846343994,26.143608042403464,1739502693.7851803,54.03994846343994,0.04154348841554878,1739502693.7851841,54.03994846343994,86.62107041480232,1739502693.7851877,54.03994846343994,20.39726753471378,1739502693.7851896,54.03994846343994,-0.016956582887282388,1739502693.785192,54.03994846343994,-3.131412600675192,1739502693.7851937,54.03994846343994,0.23613921663892992,1739502693.7851956,54.03994846343994,0.05491021112652436,1739502693.785197,54.03994846343994,2.0696496848075023,1739502693.7851992,54.03994846343994,0.0,1739502693.7852008,54.03994846343994,-0.08494785083834389,1739502693.785203,54.03994846343994,3.110669419601192,1739502693.7852046,54.03994846343994,2.154597535645846 +1739502693.8046992,54.059948444366455,26.143608042403464,1739502693.8047037,54.059948444366455,0.04154348841554878,1739502693.8047087,54.059948444366455,86.62107041480232,1739502693.8047125,54.059948444366455,20.39726753471378,1739502693.8047147,54.059948444366455,-0.016956582887282388,1739502693.804717,54.059948444366455,-3.131412600675192,1739502693.8047187,54.059948444366455,0.23613921663892992,1739502693.8047209,54.059948444366455,0.05491021112652436,1739502693.8047228,54.059948444366455,2.0696496848075023,1739502693.8047247,54.059948444366455,0.0,1739502693.8047266,54.059948444366455,-0.08494785083834389,1739502693.8047285,54.059948444366455,3.110669419601192,1739502693.8047304,54.059948444366455,2.154597535645846 +1739502693.8251474,54.07994842529297,25.90717579281735,1739502693.825151,54.07994842529297,0.04877199322228343,1739502693.825155,54.07994842529297,86.66860775397875,1739502693.8251588,54.07994842529297,20.368301277621928,1739502693.825161,54.07994842529297,-0.01669083740937547,1739502693.8251634,54.07994842529297,-3.1297744073609044,1739502693.8251653,54.07994842529297,0.23230369014075158,1739502693.8251672,54.07994842529297,0.05813788711527428,1739502693.8251688,54.07994842529297,2.0760099948386843,1739502693.825171,54.07994842529297,0.0,1739502693.8251727,54.07994842529297,-0.06219112903330641,1739502693.825175,54.07994842529297,3.1114609313633363,1739502693.8251772,54.07994842529297,2.1453126040987147 +1739502693.844627,54.09994840621948,25.90717579281735,1739502693.8446302,54.09994840621948,0.04877199322228343,1739502693.844634,54.09994840621948,86.66860775397875,1739502693.8446379,54.09994840621948,20.368301277621928,1739502693.8446398,54.09994840621948,-0.01669083740937547,1739502693.8446426,54.09994840621948,-3.1297744073609044,1739502693.8446443,54.09994840621948,0.23230369014075158,1739502693.8446465,54.09994840621948,0.05813788711527428,1739502693.8446481,54.09994840621948,2.0760099948386843,1739502693.8446503,54.09994840621948,0.0,1739502693.8446517,54.09994840621948,-0.0693026092600304,1739502693.8446538,54.09994840621948,3.1114609313633363,1739502693.8446562,54.09994840621948,2.1453126040987147 +1739502693.864914,54.119948387145996,25.90717579281735,1739502693.8649178,54.119948387145996,0.04877199322228343,1739502693.8649223,54.119948387145996,86.66860775397875,1739502693.864926,54.119948387145996,20.368301277621928,1739502693.8649282,54.119948387145996,-0.01669083740937547,1739502693.8649304,54.119948387145996,-3.1297744073609044,1739502693.8649323,54.119948387145996,0.23230369014075158,1739502693.8649342,54.119948387145996,0.05813788711527428,1739502693.8649359,54.119948387145996,2.0760099948386843,1739502693.8649383,54.119948387145996,0.0,1739502693.86494,54.119948387145996,-0.0693026092600304,1739502693.8649418,54.119948387145996,3.1114609313633363,1739502693.864944,54.119948387145996,2.1453126040987147 +1739502693.8847191,54.13994836807251,25.90717579281735,1739502693.8847225,54.13994836807251,0.04877199322228343,1739502693.8847265,54.13994836807251,86.66860775397875,1739502693.88473,54.13994836807251,20.368301277621928,1739502693.8847322,54.13994836807251,-0.01669083740937547,1739502693.8847344,54.13994836807251,-3.1297744073609044,1739502693.8847363,54.13994836807251,0.23230369014075158,1739502693.8847382,54.13994836807251,0.05813788711527428,1739502693.88474,54.13994836807251,2.0760099948386843,1739502693.8847423,54.13994836807251,0.0,1739502693.8847442,54.13994836807251,-0.0693026092600304,1739502693.884746,54.13994836807251,3.1114609313633363,1739502693.8847477,54.13994836807251,2.1453126040987147 +1739502693.9047596,54.15994834899902,25.90717579281735,1739502693.9047632,54.15994834899902,0.04877199322228343,1739502693.9047673,54.15994834899902,86.66860775397875,1739502693.904771,54.15994834899902,20.368301277621928,1739502693.9047728,54.15994834899902,-0.01669083740937547,1739502693.9047751,54.15994834899902,-3.1297744073609044,1739502693.9047773,54.15994834899902,0.23230369014075158,1739502693.904779,54.15994834899902,0.05813788711527428,1739502693.904781,54.15994834899902,2.0760099948386843,1739502693.904783,54.15994834899902,0.0,1739502693.904785,54.15994834899902,-0.0693026092600304,1739502693.9047868,54.15994834899902,3.1114609313633363,1739502693.904789,54.15994834899902,2.1453126040987147 +1739502693.9249556,54.17994832992554,25.90717579281735,1739502693.924959,54.17994832992554,0.04877199322228343,1739502693.9249632,54.17994832992554,86.66860775397875,1739502693.924967,54.17994832992554,20.368301277621928,1739502693.924969,54.17994832992554,-0.01669083740937547,1739502693.9249713,54.17994832992554,-3.1297744073609044,1739502693.9249732,54.17994832992554,0.23230369014075158,1739502693.9249752,54.17994832992554,0.05813788711527428,1739502693.9249768,54.17994832992554,2.0760099948386843,1739502693.9249794,54.17994832992554,0.0,1739502693.9249814,54.17994832992554,-0.0693026092600304,1739502693.9249833,54.17994832992554,3.1114609313633363,1739502693.9249854,54.17994832992554,2.1453126040987147 +1739502693.9447098,54.19994831085205,25.671662474334322,1739502693.9447138,54.19994831085205,0.0557858089115193,1739502693.9447176,54.19994831085205,86.78869174550886,1739502693.9447212,54.19994831085205,20.26311571195668,1739502693.9447231,54.19994831085205,-0.015728324654151634,1739502693.9447255,54.19994831085205,-3.128370993599477,1739502693.9447277,54.19994831085205,0.23014848797804927,1739502693.9447293,54.19994831085205,0.06040509196261467,1739502693.9447312,54.19994831085205,2.079592459309813,1739502693.9447334,54.19994831085205,0.0,1739502693.944735,54.19994831085205,-0.053259731000741495,1739502693.944737,54.19994831085205,3.1122524431254805,1739502693.9447389,54.19994831085205,2.1378655930536254 +1739502693.9646516,54.219948291778564,25.671662474334322,1739502693.9646552,54.219948291778564,0.0557858089115193,1739502693.9646592,54.219948291778564,86.78869174550886,1739502693.964663,54.219948291778564,20.26311571195668,1739502693.964665,54.219948291778564,-0.015728324654151634,1739502693.9646673,54.219948291778564,-3.128370993599477,1739502693.9646692,54.219948291778564,0.23014848797804927,1739502693.9646947,54.219948291778564,0.06040509196261467,1739502693.9646966,54.219948291778564,2.079592459309813,1739502693.9646988,54.219948291778564,0.0,1739502693.9647007,54.219948291778564,-0.058273133743812267,1739502693.9647026,54.219948291778564,3.1122524431254805,1739502693.9647045,54.219948291778564,2.1378655930536254 +1739502693.9847777,54.23994827270508,25.671662474334322,1739502693.9847815,54.23994827270508,0.0557858089115193,1739502693.984786,54.23994827270508,86.78869174550886,1739502693.9847898,54.23994827270508,20.26311571195668,1739502693.9847915,54.23994827270508,-0.015728324654151634,1739502693.984794,54.23994827270508,-3.128370993599477,1739502693.9847958,54.23994827270508,0.23014848797804927,1739502693.984798,54.23994827270508,0.06040509196261467,1739502693.9847994,54.23994827270508,2.079592459309813,1739502693.9848018,54.23994827270508,0.0,1739502693.9848037,54.23994827270508,-0.058273133743812267,1739502693.9848053,54.23994827270508,3.1122524431254805,1739502693.9848073,54.23994827270508,2.1378655930536254 +1739502694.0049493,54.25994825363159,25.671662474334322,1739502694.004953,54.25994825363159,0.0557858089115193,1739502694.0049567,54.25994825363159,86.78869174550886,1739502694.0049605,54.25994825363159,20.26311571195668,1739502694.0049624,54.25994825363159,-0.015728324654151634,1739502694.0049648,54.25994825363159,-3.128370993599477,1739502694.0049667,54.25994825363159,0.23014848797804927,1739502694.0049686,54.25994825363159,0.06040509196261467,1739502694.0049706,54.25994825363159,2.079592459309813,1739502694.0049725,54.25994825363159,0.0,1739502694.0049744,54.25994825363159,-0.058273133743812267,1739502694.0049763,54.25994825363159,3.1122524431254805,1739502694.0049782,54.25994825363159,2.1378655930536254 +1739502694.0249598,54.279948234558105,25.671662474334322,1739502694.0249634,54.279948234558105,0.0557858089115193,1739502694.0249677,54.279948234558105,86.78869174550886,1739502694.0249712,54.279948234558105,20.26311571195668,1739502694.0249734,54.279948234558105,-0.015728324654151634,1739502694.0249755,54.279948234558105,-3.128370993599477,1739502694.0249774,54.279948234558105,0.23014848797804927,1739502694.0249794,54.279948234558105,0.06040509196261467,1739502694.0249813,54.279948234558105,2.079592459309813,1739502694.0249836,54.279948234558105,0.0,1739502694.0249853,54.279948234558105,-0.058273133743812267,1739502694.0249872,54.279948234558105,3.1122524431254805,1739502694.0249894,54.279948234558105,2.1378655930536254 +1739502694.0448008,54.29994821548462,25.436917000673038,1739502694.044804,54.29994821548462,0.06258062407893306,1739502694.044808,54.29994821548462,87.01498342250895,1739502694.0448117,54.29994821548462,20.04959506935105,1739502694.0448136,54.29994821548462,-0.014778136994100438,1739502694.044816,54.29994821548462,-3.1272342310226686,1739502694.044818,54.29994821548462,0.23042663665673538,1739502694.0448196,54.29994821548462,0.060953512588496905,1739502694.0448215,54.29994821548462,2.079129762075362,1739502694.0448236,54.29994821548462,0.0,1739502694.0448253,54.29994821548462,-0.04966126137365473,1739502694.0448275,54.29994821548462,3.113170417768091,1739502694.0448291,54.29994821548462,2.131482235329187 +1739502694.0651464,54.31994819641113,25.436917000673038,1739502694.0651503,54.31994819641113,0.06258062407893306,1739502694.0651543,54.31994819641113,87.01498342250895,1739502694.0651581,54.31994819641113,20.04959506935105,1739502694.0651608,54.31994819641113,-0.014778136994100438,1739502694.065163,54.31994819641113,-3.1272342310226686,1739502694.0651648,54.31994819641113,0.23042663665673538,1739502694.065167,54.31994819641113,0.060953512588496905,1739502694.0651689,54.31994819641113,2.079129762075362,1739502694.065171,54.31994819641113,0.0,1739502694.0651727,54.31994819641113,-0.05235247325382497,1739502694.0651748,54.31994819641113,3.113170417768091,1739502694.0651767,54.31994819641113,2.131482235329187 +1739502694.0847456,54.33994817733765,25.436917000673038,1739502694.084749,54.33994817733765,0.06258062407893306,1739502694.084753,54.33994817733765,87.01498342250895,1739502694.0847569,54.33994817733765,20.04959506935105,1739502694.0847583,54.33994817733765,-0.014778136994100438,1739502694.084761,54.33994817733765,-3.1272342310226686,1739502694.0847628,54.33994817733765,0.23042663665673538,1739502694.0847645,54.33994817733765,0.060953512588496905,1739502694.0847661,54.33994817733765,2.079129762075362,1739502694.0847683,54.33994817733765,0.0,1739502694.08477,54.33994817733765,-0.05235247325382497,1739502694.084772,54.33994817733765,3.113170417768091,1739502694.0847738,54.33994817733765,2.131482235329187 +1739502694.1047132,54.35994815826416,25.436917000673038,1739502694.1047168,54.35994815826416,0.06258062407893306,1739502694.1047208,54.35994815826416,87.01498342250895,1739502694.1047246,54.35994815826416,20.04959506935105,1739502694.1047266,54.35994815826416,-0.014778136994100438,1739502694.1047292,54.35994815826416,-3.1272342310226686,1739502694.104731,54.35994815826416,0.23042663665673538,1739502694.1047328,54.35994815826416,0.060953512588496905,1739502694.1047344,54.35994815826416,2.079129762075362,1739502694.1047366,54.35994815826416,0.0,1739502694.1047382,54.35994815826416,-0.05235247325382497,1739502694.1047404,54.35994815826416,3.113170417768091,1739502694.104742,54.35994815826416,2.131482235329187 +1739502694.1251009,54.379948139190674,25.436917000673038,1739502694.1251044,54.379948139190674,0.06258062407893306,1739502694.1251082,54.379948139190674,87.01498342250895,1739502694.125112,54.379948139190674,20.04959506935105,1739502694.1251142,54.379948139190674,-0.014778136994100438,1739502694.1251166,54.379948139190674,-3.1272342310226686,1739502694.1251187,54.379948139190674,0.23042663665673538,1739502694.1251204,54.379948139190674,0.060953512588496905,1739502694.1251223,54.379948139190674,2.079129762075362,1739502694.1251252,54.379948139190674,0.0,1739502694.125127,54.379948139190674,-0.05235247325382497,1739502694.1251292,54.379948139190674,3.113170417768091,1739502694.1251314,54.379948139190674,2.131482235329187 +1739502694.1447062,54.39994812011719,25.436917000673038,1739502694.1447098,54.39994812011719,0.06258062407893306,1739502694.1447139,54.39994812011719,87.01498342250895,1739502694.1447182,54.39994812011719,20.04959506935105,1739502694.14472,54.39994812011719,-0.014778136994100438,1739502694.1447225,54.39994812011719,-3.1272342310226686,1739502694.1447244,54.39994812011719,0.23042663665673538,1739502694.1447263,54.39994812011719,0.060953512588496905,1739502694.144728,54.39994812011719,2.079129762075362,1739502694.1447303,54.39994812011719,0.0,1739502694.1447322,54.39994812011719,-0.05235247325382497,1739502694.144734,54.39994812011719,3.113170417768091,1739502694.1447358,54.39994812011719,2.131482235329187 +1739502694.1648474,54.4199481010437,25.202827726728685,1739502694.164851,54.4199481010437,0.06913409126463055,1739502694.1648552,54.4199481010437,87.45086999624127,1739502694.1648593,54.4199481010437,19.625078746487414,1739502694.1648614,54.4199481010437,-0.012,1739502694.1648638,54.4199481010437,-3.1270476516590597,1739502694.164866,54.4199481010437,0.23428862310104875,1739502694.1648684,54.4199481010437,0.057816105722524,1739502694.1648703,54.4199481010437,2.0727160183281406,1739502694.1648724,54.4199481010437,0.0,1739502694.1648743,54.4199481010437,-0.05342143598169343,1739502694.1648762,54.4199481010437,3.1141255877480174,1739502694.1648781,54.4199481010437,2.125803403238354 +1739502694.184735,54.439948081970215,25.202827726728685,1739502694.1847386,54.439948081970215,0.06913409126463055,1739502694.1847422,54.439948081970215,87.45086999624127,1739502694.184746,54.439948081970215,19.625078746487414,1739502694.1847477,54.439948081970215,-0.012,1739502694.1847503,54.439948081970215,-3.1270476516590597,1739502694.1847522,54.439948081970215,0.23428862310104875,1739502694.184754,54.439948081970215,0.057816105722524,1739502694.1847558,54.439948081970215,2.0727160183281406,1739502694.1847577,54.439948081970215,0.0,1739502694.1847596,54.439948081970215,-0.053087384910213586,1739502694.1847615,54.439948081970215,3.1141255877480174,1739502694.1847634,54.439948081970215,2.125803403238354 +1739502694.204777,54.45994806289673,25.202827726728685,1739502694.2047806,54.45994806289673,0.06913409126463055,1739502694.2047844,54.45994806289673,87.45086999624127,1739502694.204788,54.45994806289673,19.625078746487414,1739502694.20479,54.45994806289673,-0.012,1739502694.2047923,54.45994806289673,-3.1270476516590597,1739502694.2047942,54.45994806289673,0.23428862310104875,1739502694.204796,54.45994806289673,0.057816105722524,1739502694.2047977,54.45994806289673,2.0727160183281406,1739502694.2048,54.45994806289673,0.0,1739502694.2048016,54.45994806289673,-0.053087384910213586,1739502694.2048032,54.45994806289673,3.1141255877480174,1739502694.2048054,54.45994806289673,2.125803403238354 +1739502694.2252848,54.47994804382324,25.202827726728685,1739502694.2252884,54.47994804382324,0.06913409126463055,1739502694.2252934,54.47994804382324,87.45086999624127,1739502694.2252972,54.47994804382324,19.625078746487414,1739502694.225299,54.47994804382324,-0.012,1739502694.2253015,54.47994804382324,-3.1270476516590597,1739502694.2253036,54.47994804382324,0.23428862310104875,1739502694.2253053,54.47994804382324,0.057816105722524,1739502694.2253072,54.47994804382324,2.0727160183281406,1739502694.2253091,54.47994804382324,0.0,1739502694.225311,54.47994804382324,-0.053087384910213586,1739502694.225313,54.47994804382324,3.1141255877480174,1739502694.2253149,54.47994804382324,2.125803403238354 +1739502694.2446132,54.499948024749756,25.202827726728685,1739502694.2446167,54.499948024749756,0.06913409126463055,1739502694.244621,54.499948024749756,87.45086999624127,1739502694.244625,54.499948024749756,19.625078746487414,1739502694.244627,54.499948024749756,-0.012,1739502694.2446296,54.499948024749756,-3.1270476516590597,1739502694.2446313,54.499948024749756,0.23428862310104875,1739502694.2446334,54.499948024749756,0.057816105722524,1739502694.2446349,54.499948024749756,2.0727160183281406,1739502694.2446373,54.499948024749756,0.0,1739502694.244639,54.499948024749756,-0.053087384910213586,1739502694.244641,54.499948024749756,3.1141255877480174,1739502694.2446427,54.499948024749756,2.125803403238354 +1739502694.265357,54.51994800567627,24.96936517560978,1739502694.2653608,54.51994800567627,0.07544684884385067,1739502694.265366,54.51994800567627,88.18377127531915,1739502694.2653701,54.51994800567627,18.9037943197776,1739502694.2653725,54.51994800567627,-0.011,1739502694.265375,54.51994800567627,-3.127341563535313,1739502694.265377,54.51994800567627,0.2472074149036965,1739502694.2653794,54.51994800567627,0.0515879579104653,1739502694.265381,54.51994800567627,2.0514047450168214,1739502694.2653832,54.51994800567627,0.0,1739502694.2653852,54.51994800567627,-0.07563931843109953,1739502694.2653873,54.51994800567627,3.115080757727944,1739502694.2653892,54.51994800567627,2.1199965796019535 +1739502694.284762,54.53994798660278,24.96936517560978,1739502694.2847655,54.53994798660278,0.07544684884385067,1739502694.2847695,54.53994798660278,88.18377127531915,1739502694.2847733,54.53994798660278,18.9037943197776,1739502694.2847755,54.53994798660278,-0.011,1739502694.2847776,54.53994798660278,-3.127341563535313,1739502694.2847795,54.53994798660278,0.2472074149036965,1739502694.2847812,54.53994798660278,0.0515879579104653,1739502694.2847831,54.53994798660278,2.0514047450168214,1739502694.2847853,54.53994798660278,0.0,1739502694.284787,54.53994798660278,-0.06859183458513218,1739502694.284789,54.53994798660278,3.115080757727944,1739502694.2847908,54.53994798660278,2.1199965796019535 +1739502694.3047419,54.5599479675293,24.96936517560978,1739502694.3047452,54.5599479675293,0.07544684884385067,1739502694.3047493,54.5599479675293,88.18377127531915,1739502694.3047528,54.5599479675293,18.9037943197776,1739502694.3047547,54.5599479675293,-0.011,1739502694.3047569,54.5599479675293,-3.127341563535313,1739502694.3047588,54.5599479675293,0.2472074149036965,1739502694.3047607,54.5599479675293,0.0515879579104653,1739502694.3047624,54.5599479675293,2.0514047450168214,1739502694.3047645,54.5599479675293,0.0,1739502694.3047662,54.5599479675293,-0.06859183458513218,1739502694.3047683,54.5599479675293,3.115080757727944,1739502694.30477,54.5599479675293,2.1199965796019535 +1739502694.324842,54.57994794845581,24.96936517560978,1739502694.3248456,54.57994794845581,0.07544684884385067,1739502694.3248498,54.57994794845581,88.18377127531915,1739502694.3248537,54.57994794845581,18.9037943197776,1739502694.3248556,54.57994794845581,-0.011,1739502694.3248582,54.57994794845581,-3.127341563535313,1739502694.3248599,54.57994794845581,0.2472074149036965,1739502694.3248618,54.57994794845581,0.0515879579104653,1739502694.3248634,54.57994794845581,2.0514047450168214,1739502694.3248656,54.57994794845581,0.0,1739502694.3248675,54.57994794845581,-0.06859183458513218,1739502694.3248696,54.57994794845581,3.115080757727944,1739502694.3248715,54.57994794845581,2.1199965796019535 +1739502694.3449206,54.599947929382324,24.96936517560978,1739502694.3449237,54.599947929382324,0.07544684884385067,1739502694.3449275,54.599947929382324,88.18377127531915,1739502694.3449311,54.599947929382324,18.9037943197776,1739502694.3449328,54.599947929382324,-0.011,1739502694.3449352,54.599947929382324,-3.127341563535313,1739502694.3449368,54.599947929382324,0.2472074149036965,1739502694.344939,54.599947929382324,0.0515879579104653,1739502694.344941,54.599947929382324,2.0514047450168214,1739502694.3449428,54.599947929382324,0.0,1739502694.3449447,54.599947929382324,-0.06859183458513218,1739502694.3449464,54.599947929382324,3.115080757727944,1739502694.3449483,54.599947929382324,2.1199965796019535 +1739502694.3650022,54.61994791030884,24.96936517560978,1739502694.365006,54.61994791030884,0.07544684884385067,1739502694.3650105,54.61994791030884,88.18377127531915,1739502694.3650143,54.61994791030884,18.9037943197776,1739502694.365016,54.61994791030884,-0.011,1739502694.3650188,54.61994791030884,-3.127341563535313,1739502694.365021,54.61994791030884,0.2472074149036965,1739502694.365023,54.61994791030884,0.0515879579104653,1739502694.3650248,54.61994791030884,2.0514047450168214,1739502694.3650274,54.61994791030884,0.0,1739502694.365029,54.61994791030884,-0.06859183458513218,1739502694.365031,54.61994791030884,3.115080757727944,1739502694.365033,54.61994791030884,2.1199965796019535 +1739502694.3848026,54.63994789123535,24.73663426814703,1739502694.384806,54.63994789123535,0.08151738431890809,1739502694.3848097,54.63994789123535,88.18936288763372,1739502694.3848135,54.63994789123535,18.913502859897488,1739502694.3848155,54.63994789123535,-0.011,1739502694.3848176,54.63994789123535,-3.125706080812263,1739502694.3848195,54.63994789123535,0.2412911457540131,1739502694.3848212,54.63994789123535,0.05463007571700557,1739502694.384823,54.63994789123535,2.0611370885994265,1739502694.384825,54.63994789123535,0.0,1739502694.384827,54.63994789123535,-0.04330830734119301,1739502694.3848286,54.63994789123535,3.11603592770787,1739502694.3848307,54.63994789123535,2.11234650338472 +1739502694.4047391,54.659947872161865,24.73663426814703,1739502694.4047425,54.659947872161865,0.08151738431890809,1739502694.4047465,54.659947872161865,88.18936288763372,1739502694.40475,54.659947872161865,18.913502859897488,1739502694.4047518,54.659947872161865,-0.011,1739502694.4047544,54.659947872161865,-3.125706080812263,1739502694.4047563,54.659947872161865,0.2412911457540131,1739502694.404758,54.659947872161865,0.05463007571700557,1739502694.40476,54.659947872161865,2.0611370885994265,1739502694.4047618,54.659947872161865,0.0,1739502694.4047637,54.659947872161865,-0.05120941478529373,1739502694.4047656,54.659947872161865,3.11603592770787,1739502694.4047675,54.659947872161865,2.11234650338472 +1739502694.4249933,54.67994785308838,24.73663426814703,1739502694.4249969,54.67994785308838,0.08151738431890809,1739502694.425001,54.67994785308838,88.18936288763372,1739502694.4250047,54.67994785308838,18.913502859897488,1739502694.4250066,54.67994785308838,-0.011,1739502694.425009,54.67994785308838,-3.125706080812263,1739502694.425011,54.67994785308838,0.2412911457540131,1739502694.4250128,54.67994785308838,0.05463007571700557,1739502694.4250145,54.67994785308838,2.0611370885994265,1739502694.4250166,54.67994785308838,0.0,1739502694.4250183,54.67994785308838,-0.05120941478529373,1739502694.4250205,54.67994785308838,3.11603592770787,1739502694.4250224,54.67994785308838,2.11234650338472 +1739502694.444861,54.69994783401489,24.73663426814703,1739502694.444865,54.69994783401489,0.08151738431890809,1739502694.444869,54.69994783401489,88.18936288763372,1739502694.4448733,54.69994783401489,18.913502859897488,1739502694.4448752,54.69994783401489,-0.011,1739502694.4448776,54.69994783401489,-3.125706080812263,1739502694.4448795,54.69994783401489,0.2412911457540131,1739502694.4448814,54.69994783401489,0.05463007571700557,1739502694.444883,54.69994783401489,2.0611370885994265,1739502694.4448855,54.69994783401489,0.0,1739502694.4448874,54.69994783401489,-0.05120941478529373,1739502694.4448893,54.69994783401489,3.11603592770787,1739502694.4448912,54.69994783401489,2.11234650338472 +1739502694.4649832,54.719947814941406,24.73663426814703,1739502694.4649868,54.719947814941406,0.08151738431890809,1739502694.464991,54.719947814941406,88.18936288763372,1739502694.464995,54.719947814941406,18.913502859897488,1739502694.4649966,54.719947814941406,-0.011,1739502694.4649987,54.719947814941406,-3.125706080812263,1739502694.4650006,54.719947814941406,0.2412911457540131,1739502694.4650028,54.719947814941406,0.05463007571700557,1739502694.4650042,54.719947814941406,2.0611370885994265,1739502694.4650064,54.719947814941406,0.0,1739502694.465008,54.719947814941406,-0.05120941478529373,1739502694.46501,54.719947814941406,3.11603592770787,1739502694.465012,54.719947814941406,2.11234650338472 +1739502694.4849055,54.73994779586792,24.504633490556156,1739502694.484909,54.73994779586792,0.08734711175468224,1739502694.484913,54.73994779586792,88.19493673602334,1739502694.4849167,54.73994779586792,18.91916016754497,1739502694.4849188,54.73994779586792,-0.011,1739502694.484921,54.73994779586792,-3.1239868135023956,1739502694.484923,54.73994779586792,0.23571482517652528,1739502694.484925,54.73994779586792,0.05800152516710299,1739502694.4849265,54.73994779586792,2.0703524774295476,1739502694.4849286,54.73994779586792,0.0,1739502694.4849303,54.73994779586792,-0.029637092939993337,1739502694.4849324,54.73994779586792,3.1169910976877966,1739502694.484934,54.73994779586792,2.106730925366174 +1739502694.504879,54.759947776794434,24.504633490556156,1739502694.5048826,54.759947776794434,0.08734711175468224,1739502694.5048866,54.759947776794434,88.19493673602334,1739502694.5048902,54.759947776794434,18.91916016754497,1739502694.5048919,54.759947776794434,-0.011,1739502694.5048943,54.759947776794434,-3.1239868135023956,1739502694.504896,54.759947776794434,0.23571482517652528,1739502694.504898,54.759947776794434,0.05800152516710299,1739502694.5048997,54.759947776794434,2.0703524774295476,1739502694.504902,54.759947776794434,0.0,1739502694.5049038,54.759947776794434,-0.03637844793662648,1739502694.5049057,54.759947776794434,3.1169910976877966,1739502694.5049078,54.759947776794434,2.106730925366174 +1739502694.5249329,54.77994775772095,24.504633490556156,1739502694.5249362,54.77994775772095,0.08734711175468224,1739502694.5249405,54.77994775772095,88.19493673602334,1739502694.5249445,54.77994775772095,18.91916016754497,1739502694.5249467,54.77994775772095,-0.011,1739502694.5249488,54.77994775772095,-3.1239868135023956,1739502694.5249505,54.77994775772095,0.23571482517652528,1739502694.5249524,54.77994775772095,0.05800152516710299,1739502694.524954,54.77994775772095,2.0703524774295476,1739502694.5249567,54.77994775772095,0.0,1739502694.5249581,54.77994775772095,-0.03637844793662648,1739502694.5249603,54.77994775772095,3.1169910976877966,1739502694.5249622,54.77994775772095,2.106730925366174 +1739502694.5447605,54.79994773864746,24.504633490556156,1739502694.544764,54.79994773864746,0.08734711175468224,1739502694.544768,54.79994773864746,88.19493673602334,1739502694.5447717,54.79994773864746,18.91916016754497,1739502694.5447736,54.79994773864746,-0.011,1739502694.544776,54.79994773864746,-3.1239868135023956,1739502694.5447779,54.79994773864746,0.23571482517652528,1739502694.5447798,54.79994773864746,0.05800152516710299,1739502694.5447817,54.79994773864746,2.0703524774295476,1739502694.5447836,54.79994773864746,0.0,1739502694.5447855,54.79994773864746,-0.03637844793662648,1739502694.5447874,54.79994773864746,3.1169910976877966,1739502694.5447893,54.79994773864746,2.106730925366174 +1739502694.5650675,54.819947719573975,24.504633490556156,1739502694.5650706,54.819947719573975,0.08734711175468224,1739502694.5650747,54.819947719573975,88.19493673602334,1739502694.5650783,54.819947719573975,18.91916016754497,1739502694.5650802,54.819947719573975,-0.011,1739502694.5650823,54.819947719573975,-3.1239868135023956,1739502694.565084,54.819947719573975,0.23571482517652528,1739502694.5650856,54.819947719573975,0.05800152516710299,1739502694.5650876,54.819947719573975,2.0703524774295476,1739502694.5650895,54.819947719573975,0.0,1739502694.5650914,54.819947719573975,-0.03637844793662648,1739502694.565093,54.819947719573975,3.1169910976877966,1739502694.5650952,54.819947719573975,2.106730925366174 +1739502694.584775,54.83994770050049,24.504633490556156,1739502694.5847785,54.83994770050049,0.08734711175468224,1739502694.5847824,54.83994770050049,88.19493673602334,1739502694.584786,54.83994770050049,18.91916016754497,1739502694.584788,54.83994770050049,-0.011,1739502694.5847902,54.83994770050049,-3.1239868135023956,1739502694.5847921,54.83994770050049,0.23571482517652528,1739502694.5847938,54.83994770050049,0.05800152516710299,1739502694.5847957,54.83994770050049,2.0703524774295476,1739502694.5847976,54.83994770050049,0.0,1739502694.5847995,54.83994770050049,-0.03637844793662648,1739502694.5848014,54.83994770050049,3.1169910976877966,1739502694.5848033,54.83994770050049,2.106730925366174 +1739502694.6048625,54.859947681427,24.27314748709074,1739502694.604866,54.859947681427,0.09294264697621557,1739502694.6048703,54.859947681427,88.20049799564173,1739502694.6048741,54.859947681427,18.92129810519192,1739502694.6048763,54.859947681427,-0.011,1739502694.6048787,54.859947681427,-3.122173276619706,1739502694.6048803,54.859947681427,0.23045369107901867,1739502694.6048825,54.859947681427,0.061760666643187356,1739502694.604884,54.859947681427,2.079084762838683,1739502694.604886,54.859947681427,0.0,1739502694.6048877,54.859947681427,-0.018077520239888158,1739502694.60489,54.859947681427,3.117946267667723,1739502694.604892,54.859947681427,2.102881326733499 +1739502694.625187,54.879947662353516,24.27314748709074,1739502694.6251907,54.879947662353516,0.09294264697621557,1739502694.6251955,54.879947662353516,88.20049799564173,1739502694.6251993,54.879947662353516,18.92129810519192,1739502694.6252012,54.879947662353516,-0.011,1739502694.6252036,54.879947662353516,-3.122173276619706,1739502694.6252058,54.879947662353516,0.23045369107901867,1739502694.625208,54.879947662353516,0.061760666643187356,1739502694.6252098,54.879947662353516,2.079084762838683,1739502694.6252122,54.879947662353516,0.0,1739502694.6252139,54.879947662353516,-0.023796563894816103,1739502694.625216,54.879947662353516,3.117946267667723,1739502694.6252182,54.879947662353516,2.102881326733499 +1739502694.6448336,54.89994764328003,24.27314748709074,1739502694.6448371,54.89994764328003,0.09294264697621557,1739502694.6448412,54.89994764328003,88.20049799564173,1739502694.644845,54.89994764328003,18.92129810519192,1739502694.6448476,54.89994764328003,-0.011,1739502694.64485,54.89994764328003,-3.122173276619706,1739502694.644852,54.89994764328003,0.23045369107901867,1739502694.6448538,54.89994764328003,0.061760666643187356,1739502694.6448553,54.89994764328003,2.079084762838683,1739502694.6448576,54.89994764328003,0.0,1739502694.6448593,54.89994764328003,-0.023796563894816103,1739502694.6448615,54.89994764328003,3.117946267667723,1739502694.6448636,54.89994764328003,2.102881326733499 +1739502694.6649148,54.91994762420654,24.27314748709074,1739502694.664918,54.91994762420654,0.09294264697621557,1739502694.6649215,54.91994762420654,88.20049799564173,1739502694.664925,54.91994762420654,18.92129810519192,1739502694.6649275,54.91994762420654,-0.011,1739502694.6649299,54.91994762420654,-3.122173276619706,1739502694.6649315,54.91994762420654,0.23045369107901867,1739502694.6649334,54.91994762420654,0.061760666643187356,1739502694.6649349,54.91994762420654,2.079084762838683,1739502694.6649373,54.91994762420654,0.0,1739502694.6649387,54.91994762420654,-0.023796563894816103,1739502694.6649406,54.91994762420654,3.117946267667723,1739502694.6649423,54.91994762420654,2.102881326733499 +1739502694.684829,54.93994760513306,24.27314748709074,1739502694.6848326,54.93994760513306,0.09294264697621557,1739502694.6848366,54.93994760513306,88.20049799564173,1739502694.6848402,54.93994760513306,18.92129810519192,1739502694.6848419,54.93994760513306,-0.011,1739502694.6848443,54.93994760513306,-3.122173276619706,1739502694.6848464,54.93994760513306,0.23045369107901867,1739502694.684848,54.93994760513306,0.061760666643187356,1739502694.68485,54.93994760513306,2.079084762838683,1739502694.684852,54.93994760513306,0.0,1739502694.6848538,54.93994760513306,-0.023796563894816103,1739502694.6848557,54.93994760513306,3.117946267667723,1739502694.6848576,54.93994760513306,2.102881326733499 +1739502694.7050946,54.95994758605957,24.042025837779523,1739502694.7050982,54.95994758605957,0.0983084789010622,1739502694.705102,54.95994758605957,88.60112018654114,1739502694.7051058,54.95994758605957,18.525906883831848,1739502694.7051075,54.95994758605957,-0.01,1739502694.7051098,54.95994758605957,-3.1219602699668694,1739502694.7051117,54.95994758605957,0.2334373019037135,1739502694.7051136,54.95994758605957,0.05888993020888941,1739502694.7051153,54.95994758605957,2.074128136806082,1739502694.7051175,54.95994758605957,0.0,1739502694.7051191,54.95994758605957,-0.027205079251001112,1739502694.7051213,54.95994758605957,3.1189014376476494,1739502694.7051232,54.95994758605957,2.100268054309901 +1739502694.7256873,54.979947566986084,24.042025837779523,1739502694.7256906,54.979947566986084,0.0983084789010622,1739502694.725695,54.979947566986084,88.60112018654114,1739502694.7256987,54.979947566986084,18.525906883831848,1739502694.7257009,54.979947566986084,-0.01,1739502694.725703,54.979947566986084,-3.1219602699668694,1739502694.725705,54.979947566986084,0.2334373019037135,1739502694.7257068,54.979947566986084,0.05888993020888941,1739502694.7257082,54.979947566986084,2.074128136806082,1739502694.7257106,54.979947566986084,0.0,1739502694.725712,54.979947566986084,-0.026139917503818833,1739502694.7257142,54.979947566986084,3.1189014376476494,1739502694.7257166,54.979947566986084,2.100268054309901 +1739502694.7450821,54.9999475479126,24.042025837779523,1739502694.7450857,54.9999475479126,0.0983084789010622,1739502694.7450895,54.9999475479126,88.60112018654114,1739502694.745093,54.9999475479126,18.525906883831848,1739502694.745095,54.9999475479126,-0.01,1739502694.7450972,54.9999475479126,-3.1219602699668694,1739502694.7450993,54.9999475479126,0.2334373019037135,1739502694.745101,54.9999475479126,0.05888993020888941,1739502694.7451026,54.9999475479126,2.074128136806082,1739502694.7451046,54.9999475479126,0.0,1739502694.7451067,54.9999475479126,-0.026139917503818833,1739502694.7451084,54.9999475479126,3.1189014376476494,1739502694.7451105,54.9999475479126,2.100268054309901 +1739502694.765668,55.01994752883911,24.042025837779523,1739502694.7656715,55.01994752883911,0.0983084789010622,1739502694.7656758,55.01994752883911,88.60112018654114,1739502694.7656796,55.01994752883911,18.525906883831848,1739502694.7656815,55.01994752883911,-0.01,1739502694.7656837,55.01994752883911,-3.1219602699668694,1739502694.7656856,55.01994752883911,0.2334373019037135,1739502694.7656872,55.01994752883911,0.05888993020888941,1739502694.7656891,55.01994752883911,2.074128136806082,1739502694.7656913,55.01994752883911,0.0,1739502694.7656932,55.01994752883911,-0.026139917503818833,1739502694.7656953,55.01994752883911,3.1189014376476494,1739502694.765697,55.01994752883911,2.100268054309901 +1739502694.7851155,55.039947509765625,24.042025837779523,1739502694.7851188,55.039947509765625,0.0983084789010622,1739502694.7851226,55.039947509765625,88.60112018654114,1739502694.7851264,55.039947509765625,18.525906883831848,1739502694.785128,55.039947509765625,-0.01,1739502694.7851307,55.039947509765625,-3.1219602699668694,1739502694.7851326,55.039947509765625,0.2334373019037135,1739502694.7851346,55.039947509765625,0.05888993020888941,1739502694.7851365,55.039947509765625,2.074128136806082,1739502694.7851386,55.039947509765625,0.0,1739502694.7851405,55.039947509765625,-0.026139917503818833,1739502694.7851422,55.039947509765625,3.1189014376476494,1739502694.7851443,55.039947509765625,2.100268054309901 +1739502694.8050678,55.05994749069214,24.042025837779523,1739502694.8050714,55.05994749069214,0.0983084789010622,1739502694.8050752,55.05994749069214,88.60112018654114,1739502694.805079,55.05994749069214,18.525906883831848,1739502694.805081,55.05994749069214,-0.01,1739502694.805083,55.05994749069214,-3.1219602699668694,1739502694.8050852,55.05994749069214,0.2334373019037135,1739502694.8050873,55.05994749069214,0.05888993020888941,1739502694.8050888,55.05994749069214,2.074128136806082,1739502694.805091,55.05994749069214,0.0,1739502694.8050926,55.05994749069214,-0.026139917503818833,1739502694.8050947,55.05994749069214,3.1189014376476494,1739502694.8050964,55.05994749069214,2.100268054309901 +1739502694.8256469,55.07994747161865,23.811198935337504,1739502694.8256502,55.07994747161865,0.10344687779812478,1739502694.8256543,55.07994747161865,88.81953833526894,1739502694.8256583,55.07994747161865,18.31326389099936,1739502694.8256602,55.07994747161865,-0.008279840504944149,1739502694.8256626,55.07994747161865,-3.1212738718266952,1739502694.8256645,55.07994747161865,0.23119428541552067,1739502694.8256667,55.07994747161865,0.05870895474832752,1739502694.8256683,55.07994747161865,2.0778533209538868,1739502694.8256705,55.07994747161865,0.0,1739502694.8256721,55.07994747161865,-0.016527544632892032,1739502694.8256743,55.07994747161865,3.1198566076275758,1739502694.8256762,55.07994747161865,2.097384734078433 +1739502694.8450818,55.099947452545166,23.811198935337504,1739502694.8450856,55.099947452545166,0.10344687779812478,1739502694.8450894,55.099947452545166,88.81953833526894,1739502694.8450935,55.099947452545166,18.31326389099936,1739502694.8450952,55.099947452545166,-0.008279840504944149,1739502694.8450978,55.099947452545166,-3.1212738718266952,1739502694.8450994,55.099947452545166,0.23119428541552067,1739502694.8451014,55.099947452545166,0.05870895474832752,1739502694.845103,55.099947452545166,2.0778533209538868,1739502694.8451052,55.099947452545166,0.0,1739502694.8451068,55.099947452545166,-0.019531413124546315,1739502694.845109,55.099947452545166,3.1198566076275758,1739502694.845111,55.099947452545166,2.097384734078433 +1739502694.8656428,55.11994743347168,23.811198935337504,1739502694.8656464,55.11994743347168,0.10344687779812478,1739502694.8656502,55.11994743347168,88.81953833526894,1739502694.865654,55.11994743347168,18.31326389099936,1739502694.8656561,55.11994743347168,-0.008279840504944149,1739502694.8656583,55.11994743347168,-3.1212738718266952,1739502694.8656602,55.11994743347168,0.23119428541552067,1739502694.865662,55.11994743347168,0.05870895474832752,1739502694.865664,55.11994743347168,2.0778533209538868,1739502694.8656662,55.11994743347168,0.0,1739502694.8656678,55.11994743347168,-0.019531413124546315,1739502694.8656702,55.11994743347168,3.1198566076275758,1739502694.865672,55.11994743347168,2.097384734078433 +1739502694.8849404,55.13994741439819,23.811198935337504,1739502694.8849442,55.13994741439819,0.10344687779812478,1739502694.8849487,55.13994741439819,88.81953833526894,1739502694.8849525,55.13994741439819,18.31326389099936,1739502694.8849547,55.13994741439819,-0.008279840504944149,1739502694.8849576,55.13994741439819,-3.1212738718266952,1739502694.8849595,55.13994741439819,0.23119428541552067,1739502694.8849616,55.13994741439819,0.05870895474832752,1739502694.8849633,55.13994741439819,2.0778533209538868,1739502694.8849654,55.13994741439819,0.0,1739502694.884967,55.13994741439819,-0.019531413124546315,1739502694.8849692,55.13994741439819,3.1198566076275758,1739502694.8849716,55.13994741439819,2.097384734078433 +1739502694.9050467,55.15994739532471,23.811198935337504,1739502694.9050503,55.15994739532471,0.10344687779812478,1739502694.905054,55.15994739532471,88.81953833526894,1739502694.905058,55.15994739532471,18.31326389099936,1739502694.9050596,55.15994739532471,-0.008279840504944149,1739502694.905062,55.15994739532471,-3.1212738718266952,1739502694.9050636,55.15994739532471,0.23119428541552067,1739502694.905066,55.15994739532471,0.05870895474832752,1739502694.9050674,55.15994739532471,2.0778533209538868,1739502694.9050696,55.15994739532471,0.0,1739502694.9050713,55.15994739532471,-0.019531413124546315,1739502694.9050734,55.15994739532471,3.1198566076275758,1739502694.9050753,55.15994739532471,2.097384734078433 +1739502694.9255452,55.17994737625122,23.580647297491975,1739502694.9255488,55.17994737625122,0.10835882190529755,1739502694.9255528,55.17994737625122,89.0427191661582,1739502694.9255567,55.17994737625122,18.094377195133983,1739502694.9255588,55.17994737625122,-0.0063708577237109165,1739502694.9255612,55.17994737625122,-3.120683555526692,1739502694.925563,55.17994737625122,0.22870620085698581,1739502694.9255652,55.17994737625122,0.05832304459435707,1739502694.9255667,55.17994737625122,2.081993339683886,1739502694.925569,55.17994737625122,0.0,1739502694.9255707,55.17994737625122,-0.010394147377643178,1739502694.925573,55.17994737625122,3.120811777607502,1739502694.9255753,55.17994737625122,2.095242884479581 +1739502694.9450066,55.199947357177734,23.580647297491975,1739502694.94501,55.199947357177734,0.10835882190529755,1739502694.945014,55.199947357177734,89.0427191661582,1739502694.9450176,55.199947357177734,18.094377195133983,1739502694.9450197,55.199947357177734,-0.0063708577237109165,1739502694.9450219,55.199947357177734,-3.120683555526692,1739502694.945024,55.199947357177734,0.22870620085698581,1739502694.9450257,55.199947357177734,0.05832304459435707,1739502694.9450276,55.199947357177734,2.081993339683886,1739502694.9450297,55.199947357177734,0.0,1739502694.9450316,55.199947357177734,-0.013249544795694845,1739502694.9450336,55.199947357177734,3.120811777607502,1739502694.9450355,55.199947357177734,2.095242884479581 +1739502694.9653575,55.21994733810425,23.580647297491975,1739502694.965361,55.21994733810425,0.10835882190529755,1739502694.9653652,55.21994733810425,89.0427191661582,1739502694.965369,55.21994733810425,18.094377195133983,1739502694.965371,55.21994733810425,-0.0063708577237109165,1739502694.9653733,55.21994733810425,-3.120683555526692,1739502694.965375,55.21994733810425,0.22870620085698581,1739502694.965377,55.21994733810425,0.05832304459435707,1739502694.9653788,55.21994733810425,2.081993339683886,1739502694.965381,55.21994733810425,0.0,1739502694.9653826,55.21994733810425,-0.013249544795694845,1739502694.9653845,55.21994733810425,3.120811777607502,1739502694.9653864,55.21994733810425,2.095242884479581 +1739502694.9849586,55.23994731903076,23.580647297491975,1739502694.9849622,55.23994731903076,0.10835882190529755,1739502694.984966,55.23994731903076,89.0427191661582,1739502694.98497,55.23994731903076,18.094377195133983,1739502694.9849718,55.23994731903076,-0.0063708577237109165,1739502694.9849741,55.23994731903076,-3.120683555526692,1739502694.984976,55.23994731903076,0.22870620085698581,1739502694.984978,55.23994731903076,0.05832304459435707,1739502694.9849796,55.23994731903076,2.081993339683886,1739502694.9849818,55.23994731903076,0.0,1739502694.9849834,55.23994731903076,-0.013249544795694845,1739502694.9849856,55.23994731903076,3.120811777607502,1739502694.9849877,55.23994731903076,2.095242884479581 +1739502695.0051625,55.259947299957275,23.580647297491975,1739502695.0051658,55.259947299957275,0.10835882190529755,1739502695.0051696,55.259947299957275,89.0427191661582,1739502695.0051737,55.259947299957275,18.094377195133983,1739502695.0051758,55.259947299957275,-0.0063708577237109165,1739502695.005178,55.259947299957275,-3.120683555526692,1739502695.00518,55.259947299957275,0.22870620085698581,1739502695.0051818,55.259947299957275,0.05832304459435707,1739502695.0051835,55.259947299957275,2.081993339683886,1739502695.0051856,55.259947299957275,0.0,1739502695.0051873,55.259947299957275,-0.013249544795694845,1739502695.0051892,55.259947299957275,3.120811777607502,1739502695.0051908,55.259947299957275,2.095242884479581 +1739502695.025293,55.27994728088379,23.580647297491975,1739502695.0252967,55.27994728088379,0.10835882190529755,1739502695.0253007,55.27994728088379,89.0427191661582,1739502695.0253043,55.27994728088379,18.094377195133983,1739502695.0253065,55.27994728088379,-0.0063708577237109165,1739502695.0253084,55.27994728088379,-3.120683555526692,1739502695.0253105,55.27994728088379,0.22870620085698581,1739502695.0253122,55.27994728088379,0.05832304459435707,1739502695.0253139,55.27994728088379,2.081993339683886,1739502695.025316,55.27994728088379,0.0,1739502695.025318,55.27994728088379,-0.013249544795694845,1739502695.02532,55.27994728088379,3.120811777607502,1739502695.025322,55.27994728088379,2.095242884479581 +1739502695.0450785,55.2999472618103,23.350285548830747,1739502695.045082,55.2999472618103,0.11304658426857017,1739502695.0450861,55.2999472618103,89.26296941694471,1739502695.0450897,55.2999472618103,17.87692010849777,1739502695.0450919,55.2999472618103,-0.00537097441148469,1739502695.0450943,55.2999472618103,-3.1199607913062026,1739502695.0450962,55.2999472618103,0.22690051244104054,1739502695.045098,55.2999472618103,0.05813399942045523,1739502695.0450995,55.2999472618103,2.0850030580103556,1739502695.0451016,55.2999472618103,0.0,1739502695.0451033,55.2999472618103,-0.006843901212797248,1739502695.0451055,55.2999472618103,3.1217669475874286,1739502695.0451074,55.2999472618103,2.0938487241552677 +1739502695.064815,55.319947242736816,23.350285548830747,1739502695.0648181,55.319947242736816,0.11304658426857017,1739502695.064822,55.319947242736816,89.26296941694471,1739502695.0648255,55.319947242736816,17.87692010849777,1739502695.0648274,55.319947242736816,-0.00537097441148469,1739502695.06483,55.319947242736816,-3.1199607913062026,1739502695.0648317,55.319947242736816,0.22690051244104054,1739502695.0648339,55.319947242736816,0.05813399942045523,1739502695.0648353,55.319947242736816,2.0850030580103556,1739502695.0648375,55.319947242736816,0.0,1739502695.0648391,55.319947242736816,-0.008845666144912112,1739502695.064841,55.319947242736816,3.1217669475874286,1739502695.064843,55.319947242736816,2.0938487241552677 +1739502695.0850775,55.33994722366333,23.350285548830747,1739502695.085081,55.33994722366333,0.11304658426857017,1739502695.0850852,55.33994722366333,89.26296941694471,1739502695.085089,55.33994722366333,17.87692010849777,1739502695.0850909,55.33994722366333,-0.00537097441148469,1739502695.0850933,55.33994722366333,-3.1199607913062026,1739502695.0850952,55.33994722366333,0.22690051244104054,1739502695.085097,55.33994722366333,0.05813399942045523,1739502695.0850985,55.33994722366333,2.0850030580103556,1739502695.085101,55.33994722366333,0.0,1739502695.0851026,55.33994722366333,-0.008845666144912112,1739502695.0851045,55.33994722366333,3.1217669475874286,1739502695.0851064,55.33994722366333,2.0938487241552677 +1739502695.105005,55.359947204589844,23.350285548830747,1739502695.1050084,55.359947204589844,0.11304658426857017,1739502695.1050127,55.359947204589844,89.26296941694471,1739502695.1050165,55.359947204589844,17.87692010849777,1739502695.1050184,55.359947204589844,-0.00537097441148469,1739502695.1050208,55.359947204589844,-3.1199607913062026,1739502695.1050224,55.359947204589844,0.22690051244104054,1739502695.1050243,55.359947204589844,0.05813399942045523,1739502695.105026,55.359947204589844,2.0850030580103556,1739502695.1050282,55.359947204589844,0.0,1739502695.1050298,55.359947204589844,-0.008845666144912112,1739502695.1050317,55.359947204589844,3.1217669475874286,1739502695.1050334,55.359947204589844,2.0938487241552677 +1739502695.125318,55.37994718551636,23.350285548830747,1739502695.1253216,55.37994718551636,0.11304658426857017,1739502695.1253262,55.37994718551636,89.26296941694471,1739502695.12533,55.37994718551636,17.87692010849777,1739502695.1253316,55.37994718551636,-0.00537097441148469,1739502695.125334,55.37994718551636,-3.1199607913062026,1739502695.1253362,55.37994718551636,0.22690051244104054,1739502695.1253378,55.37994718551636,0.05813399942045523,1739502695.1253397,55.37994718551636,2.0850030580103556,1739502695.1253417,55.37994718551636,0.0,1739502695.1253436,55.37994718551636,-0.008845666144912112,1739502695.1253455,55.37994718551636,3.1217669475874286,1739502695.1253476,55.37994718551636,2.0938487241552677 +1739502695.1454663,55.39994716644287,23.12005487601691,1739502695.1454694,55.39994716644287,0.11751167899115789,1739502695.145473,55.39994716644287,89.30476287497007,1739502695.1454766,55.39994716644287,17.837070628221152,1739502695.1454785,55.39994716644287,-0.005018324143549998,1739502695.1454806,55.39994716644287,-3.1184034798960405,1739502695.1454825,55.39994716644287,0.22219501543352957,1739502695.1454842,55.39994716644287,0.061100292328902975,1739502695.145486,55.39994716644287,2.0928666300503145,1739502695.1454885,55.39994716644287,0.0,1739502695.1454902,55.39994716644287,0.004004927837437433,1739502695.145492,55.39994716644287,3.122722117567355,1739502695.1454937,55.39994716644287,2.0928775154653336 +1739502695.1652656,55.419947147369385,23.12005487601691,1739502695.1652687,55.419947147369385,0.11751167899115789,1739502695.1652725,55.419947147369385,89.30476287497007,1739502695.165276,55.419947147369385,17.837070628221152,1739502695.165278,55.419947147369385,-0.005018324143549998,1739502695.1652803,55.419947147369385,-3.1184034798960405,1739502695.165282,55.419947147369385,0.22219501543352957,1739502695.165284,55.419947147369385,0.061100292328902975,1739502695.1652853,55.419947147369385,2.0928666300503145,1739502695.1652875,55.419947147369385,0.0,1739502695.1652892,55.419947147369385,-1.0885415019146194e-05,1739502695.165291,55.419947147369385,3.122722117567355,1739502695.1652927,55.419947147369385,2.0928775154653336 +1739502695.1850846,55.4399471282959,23.12005487601691,1739502695.1850882,55.4399471282959,0.11751167899115789,1739502695.1850927,55.4399471282959,89.30476287497007,1739502695.1850965,55.4399471282959,17.837070628221152,1739502695.1850982,55.4399471282959,-0.005018324143549998,1739502695.1851006,55.4399471282959,-3.1184034798960405,1739502695.1851027,55.4399471282959,0.22219501543352957,1739502695.1851044,55.4399471282959,0.061100292328902975,1739502695.1851063,55.4399471282959,2.0928666300503145,1739502695.1851082,55.4399471282959,0.0,1739502695.18511,55.4399471282959,-1.0885415019146194e-05,1739502695.185112,55.4399471282959,3.122722117567355,1739502695.1851141,55.4399471282959,2.0928775154653336 +1739502695.2050414,55.45994710922241,23.12005487601691,1739502695.2050447,55.45994710922241,0.11751167899115789,1739502695.2050488,55.45994710922241,89.30476287497007,1739502695.2050524,55.45994710922241,17.837070628221152,1739502695.2050545,55.45994710922241,-0.005018324143549998,1739502695.2050567,55.45994710922241,-3.1184034798960405,1739502695.2050588,55.45994710922241,0.22219501543352957,1739502695.2050607,55.45994710922241,0.061100292328902975,1739502695.2050622,55.45994710922241,2.0928666300503145,1739502695.2050648,55.45994710922241,0.0,1739502695.2050664,55.45994710922241,-1.0885415019146194e-05,1739502695.2050686,55.45994710922241,3.122722117567355,1739502695.2050703,55.45994710922241,2.0928775154653336 +1739502695.2250814,55.479947090148926,23.12005487601691,1739502695.2250843,55.479947090148926,0.11751167899115789,1739502695.2250886,55.479947090148926,89.30476287497007,1739502695.2250922,55.479947090148926,17.837070628221152,1739502695.2250938,55.479947090148926,-0.005018324143549998,1739502695.2250962,55.479947090148926,-3.1184034798960405,1739502695.225098,55.479947090148926,0.22219501543352957,1739502695.2250998,55.479947090148926,0.061100292328902975,1739502695.2251012,55.479947090148926,2.0928666300503145,1739502695.2251034,55.479947090148926,0.0,1739502695.225105,55.479947090148926,-1.0885415019146194e-05,1739502695.225107,55.479947090148926,3.122722117567355,1739502695.225109,55.479947090148926,2.0928775154653336 +1739502695.245043,55.49994707107544,23.12005487601691,1739502695.2450469,55.49994707107544,0.11751167899115789,1739502695.2450507,55.49994707107544,89.30476287497007,1739502695.2450545,55.49994707107544,17.837070628221152,1739502695.2450566,55.49994707107544,-0.005018324143549998,1739502695.2450588,55.49994707107544,-3.1184034798960405,1739502695.2450607,55.49994707107544,0.22219501543352957,1739502695.2450626,55.49994707107544,0.061100292328902975,1739502695.2450643,55.49994707107544,2.0928666300503145,1739502695.2450662,55.49994707107544,0.0,1739502695.245068,55.49994707107544,-1.0885415019146194e-05,1739502695.2450702,55.49994707107544,3.122722117567355,1739502695.2450724,55.49994707107544,2.0928775154653336 +1739502695.2655146,55.51994705200195,22.889869942888467,1739502695.2655184,55.51994705200195,0.1217559335047893,1739502695.265523,55.51994705200195,89.54360380475535,1739502695.265527,55.51994705200195,17.598082336471528,1739502695.2655292,55.51994705200195,-0.0028910146865002966,1739502695.265532,55.51994705200195,-3.1180422179740686,1739502695.265534,55.51994705200195,0.21942618602837527,1739502695.2655358,55.51994705200195,0.06013755895229046,1739502695.2655377,55.51994705200195,2.097507600708225,1739502695.2655404,55.51994705200195,0.0,1739502695.2655425,55.51994705200195,0.006625544852091455,1739502695.2655444,55.51994705200195,3.1236772875472814,1739502695.2655466,55.51994705200195,2.0929559416743513 +1739502695.285037,55.53994703292847,22.889869942888467,1739502695.285041,55.53994703292847,0.1217559335047893,1739502695.285045,55.53994703292847,89.54360380475535,1739502695.2850485,55.53994703292847,17.598082336471528,1739502695.2850504,55.53994703292847,-0.0028910146865002966,1739502695.2850528,55.53994703292847,-3.1180422179740686,1739502695.2850547,55.53994703292847,0.21942618602837527,1739502695.2850566,55.53994703292847,0.06013755895229046,1739502695.285058,55.53994703292847,2.097507600708225,1739502695.2850604,55.53994703292847,0.0,1739502695.285062,55.53994703292847,0.004551659033873889,1739502695.285064,55.53994703292847,3.1236772875472814,1739502695.285066,55.53994703292847,2.0929559416743513 +1739502695.3050976,55.55994701385498,22.889869942888467,1739502695.3051012,55.55994701385498,0.1217559335047893,1739502695.3051052,55.55994701385498,89.54360380475535,1739502695.305109,55.55994701385498,17.598082336471528,1739502695.3051107,55.55994701385498,-0.0028910146865002966,1739502695.3051133,55.55994701385498,-3.1180422179740686,1739502695.3051152,55.55994701385498,0.21942618602837527,1739502695.305117,55.55994701385498,0.06013755895229046,1739502695.3051188,55.55994701385498,2.097507600708225,1739502695.3051207,55.55994701385498,0.0,1739502695.3051226,55.55994701385498,0.004551659033873889,1739502695.3051245,55.55994701385498,3.1236772875472814,1739502695.305127,55.55994701385498,2.0929559416743513 +1739502695.3253994,55.579946994781494,22.889869942888467,1739502695.3254027,55.579946994781494,0.1217559335047893,1739502695.3254066,55.579946994781494,89.54360380475535,1739502695.3254104,55.579946994781494,17.598082336471528,1739502695.3254123,55.579946994781494,-0.0028910146865002966,1739502695.3254144,55.579946994781494,-3.1180422179740686,1739502695.3254166,55.579946994781494,0.21942618602837527,1739502695.325418,55.579946994781494,0.06013755895229046,1739502695.3254197,55.579946994781494,2.097507600708225,1739502695.3254218,55.579946994781494,0.0,1739502695.3254237,55.579946994781494,0.004551659033873889,1739502695.3254254,55.579946994781494,3.1236772875472814,1739502695.3254275,55.579946994781494,2.0929559416743513 +1739502695.3450108,55.59994697570801,22.889869942888467,1739502695.3450143,55.59994697570801,0.1217559335047893,1739502695.3450184,55.59994697570801,89.54360380475535,1739502695.345022,55.59994697570801,17.598082336471528,1739502695.3450236,55.59994697570801,-0.0028910146865002966,1739502695.3450263,55.59994697570801,-3.1180422179740686,1739502695.3450282,55.59994697570801,0.21942618602837527,1739502695.34503,55.59994697570801,0.06013755895229046,1739502695.3450317,55.59994697570801,2.097507600708225,1739502695.345034,55.59994697570801,0.0,1739502695.3450358,55.59994697570801,0.004551659033873889,1739502695.345038,55.59994697570801,3.1236772875472814,1739502695.3450396,55.59994697570801,2.0929559416743513 +1739502695.3655663,55.61994695663452,22.65965605038508,1739502695.3655698,55.61994695663452,0.12578075359450214,1739502695.3655744,55.61994695663452,89.82283913305785,1739502695.3655782,55.61994695663452,17.31786877727733,1739502695.36558,55.61994695663452,-0.0006315823891529422,1739502695.365583,55.61994695663452,-3.1179322681202293,1739502695.3655849,55.61994695663452,0.21698757143365321,1739502695.3655868,55.61994695663452,0.05836130082252747,1739502695.3655887,55.61994695663452,2.1016036049575155,1739502695.3655908,55.61994695663452,0.0,1739502695.3655925,55.61994695663452,0.009790554540681208,1739502695.3655946,55.61994695663452,3.1246324575272078,1739502695.3655972,55.61994695663452,2.0934502063361147 +1739502695.3851686,55.639946937561035,22.65965605038508,1739502695.3851721,55.639946937561035,0.12578075359450214,1739502695.3851764,55.639946937561035,89.82283913305785,1739502695.38518,55.639946937561035,17.31786877727733,1739502695.3851817,55.639946937561035,-0.0006315823891529422,1739502695.3851843,55.639946937561035,-3.1179322681202293,1739502695.385186,55.639946937561035,0.21698757143365321,1739502695.3851879,55.639946937561035,0.05836130082252747,1739502695.3851895,55.639946937561035,2.1016036049575155,1739502695.385192,55.639946937561035,0.0,1739502695.3851938,55.639946937561035,0.008153398621400854,1739502695.3851957,55.639946937561035,3.1246324575272078,1739502695.3851979,55.639946937561035,2.0934502063361147 +1739502695.4049757,55.65994691848755,22.65965605038508,1739502695.4049792,55.65994691848755,0.12578075359450214,1739502695.404983,55.65994691848755,89.82283913305785,1739502695.4049866,55.65994691848755,17.31786877727733,1739502695.4049885,55.65994691848755,-0.0006315823891529422,1739502695.4049907,55.65994691848755,-3.1179322681202293,1739502695.404993,55.65994691848755,0.21698757143365321,1739502695.4049947,55.65994691848755,0.05836130082252747,1739502695.4049966,55.65994691848755,2.1016036049575155,1739502695.4049985,55.65994691848755,0.0,1739502695.4050004,55.65994691848755,0.008153398621400854,1739502695.4050028,55.65994691848755,3.1246324575272078,1739502695.4050045,55.65994691848755,2.0934502063361147 +1739502695.4253068,55.67994689941406,22.65965605038508,1739502695.4253104,55.67994689941406,0.12578075359450214,1739502695.425315,55.67994689941406,89.82283913305785,1739502695.4253185,55.67994689941406,17.31786877727733,1739502695.4253204,55.67994689941406,-0.0006315823891529422,1739502695.4253232,55.67994689941406,-3.1179322681202293,1739502695.4253254,55.67994689941406,0.21698757143365321,1739502695.4253273,55.67994689941406,0.05836130082252747,1739502695.425329,55.67994689941406,2.1016036049575155,1739502695.425331,55.67994689941406,0.0,1739502695.4253333,55.67994689941406,0.008153398621400854,1739502695.4253354,55.67994689941406,3.1246324575272078,1739502695.4253373,55.67994689941406,2.0934502063361147 +1739502695.445039,55.699946880340576,22.65965605038508,1739502695.4450428,55.699946880340576,0.12578075359450214,1739502695.4450471,55.699946880340576,89.82283913305785,1739502695.4450507,55.699946880340576,17.31786877727733,1739502695.4450526,55.699946880340576,-0.0006315823891529422,1739502695.445055,55.699946880340576,-3.1179322681202293,1739502695.4450576,55.699946880340576,0.21698757143365321,1739502695.4450593,55.699946880340576,0.05836130082252747,1739502695.4450612,55.699946880340576,2.1016036049575155,1739502695.445063,55.699946880340576,0.0,1739502695.4450653,55.699946880340576,0.008153398621400854,1739502695.445067,55.699946880340576,3.1246324575272078,1739502695.445069,55.699946880340576,2.0934502063361147 +1739502695.4656408,55.71994686126709,22.65965605038508,1739502695.4656448,55.71994686126709,0.12578075359450214,1739502695.4656487,55.71994686126709,89.82283913305785,1739502695.4656527,55.71994686126709,17.31786877727733,1739502695.4656549,55.71994686126709,-0.0006315823891529422,1739502695.4656572,55.71994686126709,-3.1179322681202293,1739502695.4656591,55.71994686126709,0.21698757143365321,1739502695.4656608,55.71994686126709,0.05836130082252747,1739502695.4656627,55.71994686126709,2.1016036049575155,1739502695.4656649,55.71994686126709,0.0,1739502695.4656665,55.71994686126709,0.008153398621400854,1739502695.4656687,55.71994686126709,3.1246324575272078,1739502695.4656706,55.71994686126709,2.0934502063361147 +1739502695.485111,55.7399468421936,22.42936016906471,1739502695.4851143,55.7399468421936,0.1295869683105053,1739502695.4851184,55.7399468421936,90.61032320337185,1739502695.485122,55.7399468421936,16.528559976098457,1739502695.4851239,55.7399468421936,0.00532576291441987,1739502695.4851263,55.7399468421936,-3.12053740037919,1739502695.4851282,55.7399468421936,0.2186837192788358,1739502695.48513,55.7399468421936,0.04820875554129231,1739502695.4851317,55.7399468421936,2.098753834506794,1739502695.485134,55.7399468421936,0.0,1739502695.4851353,55.7399468421936,0.00266249651776475,1739502695.4851375,55.7399468421936,3.125587627507134,1739502695.4851391,55.7399468421936,2.094375429956606 +1739502695.5051212,55.75994682312012,22.42936016906471,1739502695.5051246,55.75994682312012,0.1295869683105053,1739502695.5051286,55.75994682312012,90.61032320337185,1739502695.5051324,55.75994682312012,16.528559976098457,1739502695.5051346,55.75994682312012,0.00532576291441987,1739502695.505137,55.75994682312012,-3.12053740037919,1739502695.5051386,55.75994682312012,0.2186837192788358,1739502695.5051405,55.75994682312012,0.04820875554129231,1739502695.5051425,55.75994682312012,2.098753834506794,1739502695.5051446,55.75994682312012,0.0,1739502695.5051463,55.75994682312012,0.004378404550188009,1739502695.5051482,55.75994682312012,3.125587627507134,1739502695.5051508,55.75994682312012,2.094375429956606 +1739502695.5256321,55.77994680404663,22.42936016906471,1739502695.5256364,55.77994680404663,0.1295869683105053,1739502695.5256407,55.77994680404663,90.61032320337185,1739502695.5256445,55.77994680404663,16.528559976098457,1739502695.5256464,55.77994680404663,0.00532576291441987,1739502695.5256486,55.77994680404663,-3.12053740037919,1739502695.5256507,55.77994680404663,0.2186837192788358,1739502695.5256524,55.77994680404663,0.04820875554129231,1739502695.525654,55.77994680404663,2.098753834506794,1739502695.5256562,55.77994680404663,0.0,1739502695.5256581,55.77994680404663,0.004378404550188009,1739502695.5256603,55.77994680404663,3.125587627507134,1739502695.525662,55.77994680404663,2.094375429956606 +1739502695.5453825,55.799946784973145,22.42936016906471,1739502695.5453868,55.799946784973145,0.1295869683105053,1739502695.5453916,55.799946784973145,90.61032320337185,1739502695.5453954,55.799946784973145,16.528559976098457,1739502695.5453975,55.799946784973145,0.00532576291441987,1739502695.5454001,55.799946784973145,-3.12053740037919,1739502695.5454018,55.799946784973145,0.2186837192788358,1739502695.545404,55.799946784973145,0.04820875554129231,1739502695.5454056,55.799946784973145,2.098753834506794,1739502695.5454078,55.799946784973145,0.0,1739502695.5454094,55.799946784973145,0.004378404550188009,1739502695.5454125,55.799946784973145,3.125587627507134,1739502695.5454144,55.799946784973145,2.094375429956606 +1739502695.565681,55.81994676589966,22.42936016906471,1739502695.5656848,55.81994676589966,0.1295869683105053,1739502695.565689,55.81994676589966,90.61032320337185,1739502695.565693,55.81994676589966,16.528559976098457,1739502695.565695,55.81994676589966,0.00532576291441987,1739502695.5656972,55.81994676589966,-3.12053740037919,1739502695.5656993,55.81994676589966,0.2186837192788358,1739502695.565701,55.81994676589966,0.04820875554129231,1739502695.565703,55.81994676589966,2.098753834506794,1739502695.565705,55.81994676589966,0.0,1739502695.5657067,55.81994676589966,0.004378404550188009,1739502695.5657086,55.81994676589966,3.125587627507134,1739502695.5657105,55.81994676589966,2.094375429956606 +1739502695.5853274,55.83994674682617,22.198982028236397,1739502695.5853307,55.83994674682617,0.13317443952927377,1739502695.5853348,55.83994674682617,90.62576212627856,1739502695.5853386,55.83994674682617,16.51215778437048,1739502695.5853407,55.83994674682617,0.005464764539233233,1739502695.5853426,55.83994674682617,-3.119139311078765,1739502695.5853448,55.83994674682617,0.21327786800647877,1739502695.5853465,55.83994674682617,0.05061826014128602,1739502695.5853484,55.83994674682617,2.107849930055061,1739502695.5853505,55.83994674682617,0.0,1739502695.5853524,55.83994674682617,0.016908105226804013,1739502695.5853543,55.83994674682617,3.1265427974870605,1739502695.585356,55.83994674682617,2.0948573588569235 +1739502695.605039,55.859946727752686,22.198982028236397,1739502695.6050425,55.859946727752686,0.13317443952927377,1739502695.6050465,55.859946727752686,90.62576212627856,1739502695.6050503,55.859946727752686,16.51215778437048,1739502695.6050522,55.859946727752686,0.005464764539233233,1739502695.6050544,55.859946727752686,-3.119139311078765,1739502695.6050565,55.859946727752686,0.21327786800647877,1739502695.6050587,55.859946727752686,0.05061826014128602,1739502695.6050603,55.859946727752686,2.107849930055061,1739502695.6050625,55.859946727752686,0.0,1739502695.6050642,55.859946727752686,0.012992571198137348,1739502695.6050665,55.859946727752686,3.1265427974870605,1739502695.6050684,55.859946727752686,2.0948573588569235 +1739502695.625439,55.8799467086792,22.198982028236397,1739502695.6254423,55.8799467086792,0.13317443952927377,1739502695.6254466,55.8799467086792,90.62576212627856,1739502695.6254501,55.8799467086792,16.51215778437048,1739502695.625452,55.8799467086792,0.005464764539233233,1739502695.6254544,55.8799467086792,-3.119139311078765,1739502695.625456,55.8799467086792,0.21327786800647877,1739502695.6254582,55.8799467086792,0.05061826014128602,1739502695.62546,55.8799467086792,2.107849930055061,1739502695.625462,55.8799467086792,0.0,1739502695.6254637,55.8799467086792,0.012992571198137348,1739502695.6254659,55.8799467086792,3.1265427974870605,1739502695.625468,55.8799467086792,2.0948573588569235 +1739502695.645077,55.89994668960571,22.198982028236397,1739502695.6450808,55.89994668960571,0.13317443952927377,1739502695.6450846,55.89994668960571,90.62576212627856,1739502695.6450884,55.89994668960571,16.51215778437048,1739502695.6450906,55.89994668960571,0.005464764539233233,1739502695.645093,55.89994668960571,-3.119139311078765,1739502695.6450946,55.89994668960571,0.21327786800647877,1739502695.6450965,55.89994668960571,0.05061826014128602,1739502695.6450982,55.89994668960571,2.107849930055061,1739502695.6451004,55.89994668960571,0.0,1739502695.645102,55.89994668960571,0.012992571198137348,1739502695.6451042,55.89994668960571,3.1265427974870605,1739502695.6451058,55.89994668960571,2.0948573588569235 +1739502695.665899,55.91994667053223,22.198982028236397,1739502695.665903,55.91994667053223,0.13317443952927377,1739502695.6659076,55.91994667053223,90.62576212627856,1739502695.6659112,55.91994667053223,16.51215778437048,1739502695.6659133,55.91994667053223,0.005464764539233233,1739502695.6659157,55.91994667053223,-3.119139311078765,1739502695.6659179,55.91994667053223,0.21327786800647877,1739502695.66592,55.91994667053223,0.05061826014128602,1739502695.6659214,55.91994667053223,2.107849930055061,1739502695.6659238,55.91994667053223,0.0,1739502695.6659257,55.91994667053223,0.012992571198137348,1739502695.6659276,55.91994667053223,3.1265427974870605,1739502695.6659298,55.91994667053223,2.0948573588569235 +1739502695.6850832,55.93994665145874,22.198982028236397,1739502695.6850865,55.93994665145874,0.13317443952927377,1739502695.6850908,55.93994665145874,90.62576212627856,1739502695.6850946,55.93994665145874,16.51215778437048,1739502695.6850965,55.93994665145874,0.005464764539233233,1739502695.6850986,55.93994665145874,-3.119139311078765,1739502695.6851008,55.93994665145874,0.21327786800647877,1739502695.6851027,55.93994665145874,0.05061826014128602,1739502695.6851041,55.93994665145874,2.107849930055061,1739502695.6851063,55.93994665145874,0.0,1739502695.685108,55.93994665145874,0.012992571198137348,1739502695.68511,55.93994665145874,3.1265427974870605,1739502695.685112,55.93994665145874,2.0948573588569235 +1739502695.7053409,55.959946632385254,21.968493674810173,1739502695.7053447,55.959946632385254,0.13654341244023893,1739502695.7053492,55.959946632385254,90.64120821493103,1739502695.7053533,55.959946632385254,16.49371183221706,1739502695.7053552,55.959946632385254,0.005621086167652045,1739502695.7053576,55.959946632385254,-3.117683503974718,1739502695.7053595,55.959946632385254,0.20807209870278515,1739502695.7053614,55.959946632385254,0.053277947192523156,1739502695.7053638,55.959946632385254,2.1166466191246123,1739502695.7053657,55.959946632385254,0.0,1739502695.7053678,55.959946632385254,0.02360555783034631,1739502695.7053697,55.959946632385254,3.127497967466987,1739502695.7053716,55.959946632385254,2.0963576217913378 +1739502695.7255857,55.97994661331177,21.968493674810173,1739502695.7255893,55.97994661331177,0.13654341244023893,1739502695.7255933,55.97994661331177,90.64120821493103,1739502695.7255974,55.97994661331177,16.49371183221706,1739502695.7255995,55.97994661331177,0.005621086167652045,1739502695.7256021,55.97994661331177,-3.117683503974718,1739502695.7256038,55.97994661331177,0.20807209870278515,1739502695.7256057,55.97994661331177,0.053277947192523156,1739502695.7256074,55.97994661331177,2.1166466191246123,1739502695.7256095,55.97994661331177,0.0,1739502695.7256114,55.97994661331177,0.020288997333274494,1739502695.7256138,55.97994661331177,3.127497967466987,1739502695.7256155,55.97994661331177,2.0963576217913378 +1739502695.74495,55.99994659423828,21.968493674810173,1739502695.7449539,55.99994659423828,0.13654341244023893,1739502695.7449584,55.99994659423828,90.64120821493103,1739502695.7449622,55.99994659423828,16.49371183221706,1739502695.7449644,55.99994659423828,0.005621086167652045,1739502695.744967,55.99994659423828,-3.117683503974718,1739502695.744969,55.99994659423828,0.20807209870278515,1739502695.744971,55.99994659423828,0.053277947192523156,1739502695.7449727,55.99994659423828,2.1166466191246123,1739502695.7449749,55.99994659423828,0.0,1739502695.744977,55.99994659423828,0.020288997333274494,1739502695.7449787,55.99994659423828,3.127497967466987,1739502695.744981,55.99994659423828,2.0963576217913378 +1739502695.7657213,56.019946575164795,21.968493674810173,1739502695.7657254,56.019946575164795,0.13654341244023893,1739502695.7657301,56.019946575164795,90.64120821493103,1739502695.7657342,56.019946575164795,16.49371183221706,1739502695.765736,56.019946575164795,0.005621086167652045,1739502695.7657385,56.019946575164795,-3.117683503974718,1739502695.7657406,56.019946575164795,0.20807209870278515,1739502695.7657423,56.019946575164795,0.053277947192523156,1739502695.7657442,56.019946575164795,2.1166466191246123,1739502695.765746,56.019946575164795,0.0,1739502695.765748,56.019946575164795,0.020288997333274494,1739502695.76575,56.019946575164795,3.127497967466987,1739502695.7657523,56.019946575164795,2.0963576217913378 +1739502695.7850647,56.03994655609131,21.968493674810173,1739502695.785068,56.03994655609131,0.13654341244023893,1739502695.7850718,56.03994655609131,90.64120821493103,1739502695.7850757,56.03994655609131,16.49371183221706,1739502695.7850776,56.03994655609131,0.005621086167652045,1739502695.7850797,56.03994655609131,-3.117683503974718,1739502695.7850816,56.03994655609131,0.20807209870278515,1739502695.7850833,56.03994655609131,0.053277947192523156,1739502695.7850852,56.03994655609131,2.1166466191246123,1739502695.7850873,56.03994655609131,0.0,1739502695.785089,56.03994655609131,0.020288997333274494,1739502695.7850912,56.03994655609131,3.127497967466987,1739502695.7850928,56.03994655609131,2.0963576217913378 +1739502695.805106,56.05994653701782,21.737806373453065,1739502695.8051095,56.05994653701782,0.13969489691279957,1739502695.8051138,56.05994653701782,90.99916479616732,1739502695.8051174,56.05994653701782,16.131344346234762,1739502695.8051193,56.05994653701782,0.008,1739502695.805122,56.05994653701782,-3.118107132344626,1739502695.8051236,56.05994653701782,0.2053476073423042,1739502695.8051255,56.05994653701782,0.050141011297182986,1739502695.8051274,56.05994653701782,2.121265078819243,1739502695.8051295,56.05994653701782,0.0,1739502695.8051312,56.05994653701782,0.023786815528130407,1739502695.805133,56.05994653701782,3.1284531374469133,1739502695.805135,56.05994653701782,2.0985713321936768 +1739502695.8255835,56.079946517944336,21.737806373453065,1739502695.8255873,56.079946517944336,0.13969489691279957,1739502695.8255913,56.079946517944336,90.99916479616732,1739502695.825595,56.079946517944336,16.131344346234762,1739502695.8255968,56.079946517944336,0.008,1739502695.8255994,56.079946517944336,-3.118107132344626,1739502695.8256013,56.079946517944336,0.2053476073423042,1739502695.825603,56.079946517944336,0.050141011297182986,1739502695.825605,56.079946517944336,2.121265078819243,1739502695.8256068,56.079946517944336,0.0,1739502695.8256087,56.079946517944336,0.022693746625566114,1739502695.8256106,56.079946517944336,3.1284531374469133,1739502695.8256125,56.079946517944336,2.0985713321936768 +1739502695.8450723,56.09994649887085,21.737806373453065,1739502695.845076,56.09994649887085,0.13969489691279957,1739502695.84508,56.09994649887085,90.99916479616732,1739502695.8450835,56.09994649887085,16.131344346234762,1739502695.8450854,56.09994649887085,0.008,1739502695.8450878,56.09994649887085,-3.118107132344626,1739502695.8450897,56.09994649887085,0.2053476073423042,1739502695.8450916,56.09994649887085,0.050141011297182986,1739502695.8450935,56.09994649887085,2.121265078819243,1739502695.8450954,56.09994649887085,0.0,1739502695.8450973,56.09994649887085,0.022693746625566114,1739502695.845099,56.09994649887085,3.1284531374469133,1739502695.845101,56.09994649887085,2.0985713321936768 +1739502695.865141,56.11994647979736,21.737806373453065,1739502695.865144,56.11994647979736,0.13969489691279957,1739502695.8651476,56.11994647979736,90.99916479616732,1739502695.8651514,56.11994647979736,16.131344346234762,1739502695.8651533,56.11994647979736,0.008,1739502695.865156,56.11994647979736,-3.118107132344626,1739502695.8651578,56.11994647979736,0.2053476073423042,1739502695.8651597,56.11994647979736,0.050141011297182986,1739502695.8651614,56.11994647979736,2.121265078819243,1739502695.8651638,56.11994647979736,0.0,1739502695.8651655,56.11994647979736,0.022693746625566114,1739502695.8651674,56.11994647979736,3.1284531374469133,1739502695.865169,56.11994647979736,2.0985713321936768 +1739502695.8851466,56.13994646072388,21.737806373453065,1739502695.8851502,56.13994646072388,0.13969489691279957,1739502695.8851542,56.13994646072388,90.99916479616732,1739502695.885158,56.13994646072388,16.131344346234762,1739502695.8851602,56.13994646072388,0.008,1739502695.8851626,56.13994646072388,-3.118107132344626,1739502695.8851645,56.13994646072388,0.2053476073423042,1739502695.8851664,56.13994646072388,0.050141011297182986,1739502695.885168,56.13994646072388,2.121265078819243,1739502695.8851705,56.13994646072388,0.0,1739502695.8851721,56.13994646072388,0.022693746625566114,1739502695.885174,56.13994646072388,3.1284531374469133,1739502695.8851762,56.13994646072388,2.0985713321936768 +1739502695.905053,56.15994644165039,21.737806373453065,1739502695.9050567,56.15994644165039,0.13969489691279957,1739502695.9050608,56.15994644165039,90.99916479616732,1739502695.9050643,56.15994644165039,16.131344346234762,1739502695.9050663,56.15994644165039,0.008,1739502695.9050686,56.15994644165039,-3.118107132344626,1739502695.9050705,56.15994644165039,0.2053476073423042,1739502695.9050725,56.15994644165039,0.050141011297182986,1739502695.9050741,56.15994644165039,2.121265078819243,1739502695.9050763,56.15994644165039,0.0,1739502695.905078,56.15994644165039,0.022693746625566114,1739502695.9050798,56.15994644165039,3.1284531374469133,1739502695.9050817,56.15994644165039,2.0985713321936768 +1739502695.9254613,56.179946422576904,21.506855636790856,1739502695.9254646,56.179946422576904,0.14262934256766613,1739502695.9254684,56.179946422576904,91.02503421311914,1739502695.9254723,56.179946422576904,16.10046186254194,1739502695.9254742,56.179946422576904,0.008,1739502695.9254763,56.179946422576904,-3.1166959238101417,1739502695.9254785,56.179946422576904,0.20049109261292253,1739502695.9254801,56.179946422576904,0.052641366382421007,1739502695.925482,56.179946422576904,2.1295226737647277,1739502695.925484,56.179946422576904,0.0,1739502695.9254858,56.179946422576904,0.03105892959129225,1739502695.9254878,56.179946422576904,3.1294083074268397,1739502695.92549,56.179946422576904,2.1010778655641764 +1739502695.9451036,56.19994640350342,21.506855636790856,1739502695.9451072,56.19994640350342,0.14262934256766613,1739502695.9451115,56.19994640350342,91.02503421311914,1739502695.945115,56.19994640350342,16.10046186254194,1739502695.945117,56.19994640350342,0.008,1739502695.9451194,56.19994640350342,-3.1166959238101417,1739502695.9451213,56.19994640350342,0.20049109261292253,1739502695.9451234,56.19994640350342,0.052641366382421007,1739502695.945125,56.19994640350342,2.1295226737647277,1739502695.9451275,56.19994640350342,0.0,1739502695.9451292,56.19994640350342,0.028444808200551286,1739502695.9451313,56.19994640350342,3.1294083074268397,1739502695.945133,56.19994640350342,2.1010778655641764 +1739502695.9655242,56.21994638442993,21.506855636790856,1739502695.9655278,56.21994638442993,0.14262934256766613,1739502695.965532,56.21994638442993,91.02503421311914,1739502695.965536,56.21994638442993,16.10046186254194,1739502695.9655378,56.21994638442993,0.008,1739502695.9655402,56.21994638442993,-3.1166959238101417,1739502695.965542,56.21994638442993,0.20049109261292253,1739502695.965544,56.21994638442993,0.052641366382421007,1739502695.9655457,56.21994638442993,2.1295226737647277,1739502695.965548,56.21994638442993,0.0,1739502695.9655497,56.21994638442993,0.028444808200551286,1739502695.9655519,56.21994638442993,3.1294083074268397,1739502695.9655538,56.21994638442993,2.1010778655641764 +1739502695.988137,56.239946365356445,21.506855636790856,1739502695.9881425,56.239946365356445,0.14262934256766613,1739502695.9881496,56.239946365356445,91.02503421311914,1739502695.988158,56.239946365356445,16.10046186254194,1739502695.9881628,56.239946365356445,0.008,1739502695.9881685,56.239946365356445,-3.1166959238101417,1739502695.9881737,56.239946365356445,0.20049109261292253,1739502695.9881792,56.239946365356445,0.052641366382421007,1739502695.9881842,56.239946365356445,2.1295226737647277,1739502695.9881897,56.239946365356445,0.0,1739502695.9881954,56.239946365356445,0.028444808200551286,1739502695.9882007,56.239946365356445,3.1294083074268397,1739502695.9882061,56.239946365356445,2.1010778655641764 +1739502696.005594,56.25994634628296,21.506855636790856,1739502696.0055983,56.25994634628296,0.14262934256766613,1739502696.0056026,56.25994634628296,91.02503421311914,1739502696.0056067,56.25994634628296,16.10046186254194,1739502696.0056093,56.25994634628296,0.008,1739502696.0056121,56.25994634628296,-3.1166959238101417,1739502696.005614,56.25994634628296,0.20049109261292253,1739502696.0056162,56.25994634628296,0.052641366382421007,1739502696.005618,56.25994634628296,2.1295226737647277,1739502696.0056205,56.25994634628296,0.0,1739502696.0056229,56.25994634628296,0.028444808200551286,1739502696.0056248,56.25994634628296,3.1294083074268397,1739502696.0056272,56.25994634628296,2.1010778655641764 +1739502696.0254178,56.27994632720947,21.2755985583672,1739502696.0254211,56.27994632720947,0.145346752186839,1739502696.0254252,56.27994632720947,91.35020061220109,1739502696.0254292,56.27994632720947,15.769085385701782,1739502696.0254314,56.27994632720947,0.009,1739502696.025434,56.27994632720947,-3.116836715828113,1739502696.0254362,56.27994632720947,0.1981704630960128,1739502696.0254383,56.27994632720947,0.05015798974896722,1739502696.0254402,56.27994632720947,2.13347981238818,1739502696.0254426,56.27994632720947,0.0,1739502696.0254445,56.27994632720947,0.02968111843260792,1739502696.025447,56.27994632720947,3.130363477406766,1739502696.0254493,56.27994632720947,2.104185041156399 +1739502696.045584,56.299946308135986,21.2755985583672,1739502696.0455873,56.299946308135986,0.145346752186839,1739502696.045592,56.299946308135986,91.35020061220109,1739502696.0455961,56.299946308135986,15.769085385701782,1739502696.0455983,56.299946308135986,0.009,1739502696.0456007,56.299946308135986,-3.116836715828113,1739502696.045603,56.299946308135986,0.1981704630960128,1739502696.0456054,56.299946308135986,0.05015798974896722,1739502696.0456073,56.299946308135986,2.13347981238818,1739502696.0456097,56.299946308135986,0.0,1739502696.0456119,56.299946308135986,0.029294771231781258,1739502696.0456138,56.299946308135986,3.130363477406766,1739502696.0456161,56.299946308135986,2.104185041156399 +1739502696.066074,56.3199462890625,21.2755985583672,1739502696.0660777,56.3199462890625,0.145346752186839,1739502696.066082,56.3199462890625,91.35020061220109,1739502696.066086,56.3199462890625,15.769085385701782,1739502696.0660882,56.3199462890625,0.009,1739502696.0660908,56.3199462890625,-3.116836715828113,1739502696.066093,56.3199462890625,0.1981704630960128,1739502696.066095,56.3199462890625,0.05015798974896722,1739502696.0660968,56.3199462890625,2.13347981238818,1739502696.0660994,56.3199462890625,0.0,1739502696.0661016,56.3199462890625,0.029294771231781258,1739502696.0661037,56.3199462890625,3.130363477406766,1739502696.066106,56.3199462890625,2.104185041156399 +1739502696.08477,56.339946269989014,21.2755985583672,1739502696.0847723,56.339946269989014,0.145346752186839,1739502696.0847752,56.339946269989014,91.35020061220109,1739502696.084778,56.339946269989014,15.769085385701782,1739502696.0847793,56.339946269989014,0.009,1739502696.0847807,56.339946269989014,-3.116836715828113,1739502696.0847824,56.339946269989014,0.1981704630960128,1739502696.0847836,56.339946269989014,0.05015798974896722,1739502696.0847852,56.339946269989014,2.13347981238818,1739502696.0847867,56.339946269989014,0.0,1739502696.084788,56.339946269989014,0.029294771231781258,1739502696.0847895,56.339946269989014,3.130363477406766,1739502696.084791,56.339946269989014,2.104185041156399 +1739502696.1042087,56.35994625091553,21.2755985583672,1739502696.1042109,56.35994625091553,0.145346752186839,1739502696.1042135,56.35994625091553,91.35020061220109,1739502696.104216,56.35994625091553,15.769085385701782,1739502696.1042175,56.35994625091553,0.009,1739502696.1042192,56.35994625091553,-3.116836715828113,1739502696.1042204,56.35994625091553,0.1981704630960128,1739502696.1042216,56.35994625091553,0.05015798974896722,1739502696.104223,56.35994625091553,2.13347981238818,1739502696.1042242,56.35994625091553,0.0,1739502696.1042256,56.35994625091553,0.029294771231781258,1739502696.104227,56.35994625091553,3.130363477406766,1739502696.1042283,56.35994625091553,2.104185041156399 +1739502696.1243553,56.37994623184204,21.2755985583672,1739502696.1243582,56.37994623184204,0.145346752186839,1739502696.124361,56.37994623184204,91.35020061220109,1739502696.1243653,56.37994623184204,15.769085385701782,1739502696.124369,56.37994623184204,0.009,1739502696.1243734,56.37994623184204,-3.116836715828113,1739502696.1243753,56.37994623184204,0.1981704630960128,1739502696.124377,56.37994623184204,0.05015798974896722,1739502696.124379,56.37994623184204,2.13347981238818,1739502696.1243806,56.37994623184204,0.0,1739502696.1243827,56.37994623184204,0.029294771231781258,1739502696.1243849,56.37994623184204,3.130363477406766,1739502696.124389,56.37994623184204,2.104185041156399 +1739502696.1442392,56.399946212768555,21.043990299761077,1739502696.1442416,56.399946212768555,0.14784703440297164,1739502696.144245,56.399946212768555,91.47651271134418,1739502696.1442478,56.399946212768555,15.636342715720906,1739502696.1442492,56.399946212768555,0.009,1739502696.1442509,56.399946212768555,-3.1159222428927906,1739502696.1442523,56.399946212768555,0.19439693387211185,1739502696.1442537,56.399946212768555,0.05101592722616963,1739502696.144255,56.399946212768555,2.13993014242962,1739502696.1442568,56.399946212768555,0.0,1739502696.144258,56.399946212768555,0.034000292085118136,1739502696.1442597,56.399946212768555,3.1313186473866925,1739502696.144261,56.399946212768555,2.107400326575289 +1739502696.1643429,56.41994619369507,21.043990299761077,1739502696.164345,56.41994619369507,0.14784703440297164,1739502696.164348,56.41994619369507,91.47651271134418,1739502696.1643505,56.41994619369507,15.636342715720906,1739502696.164352,56.41994619369507,0.009,1739502696.1643534,56.41994619369507,-3.1159222428927906,1739502696.1643548,56.41994619369507,0.19439693387211185,1739502696.1643565,56.41994619369507,0.05101592722616963,1739502696.1643577,56.41994619369507,2.13993014242962,1739502696.164359,56.41994619369507,0.0,1739502696.1643605,56.41994619369507,0.03252981585433101,1739502696.1643617,56.41994619369507,3.1313186473866925,1739502696.1643631,56.41994619369507,2.107400326575289 +1739502696.1841242,56.43994617462158,21.043990299761077,1739502696.1841261,56.43994617462158,0.14784703440297164,1739502696.1841292,56.43994617462158,91.47651271134418,1739502696.1841319,56.43994617462158,15.636342715720906,1739502696.1841333,56.43994617462158,0.009,1739502696.1841352,56.43994617462158,-3.1159222428927906,1739502696.1841364,56.43994617462158,0.19439693387211185,1739502696.1841378,56.43994617462158,0.05101592722616963,1739502696.184139,56.43994617462158,2.13993014242962,1739502696.1841404,56.43994617462158,0.0,1739502696.1841419,56.43994617462158,0.03252981585433101,1739502696.184143,56.43994617462158,3.1313186473866925,1739502696.1841447,56.43994617462158,2.107400326575289 +1739502696.2040515,56.459946155548096,21.043990299761077,1739502696.2040534,56.459946155548096,0.14784703440297164,1739502696.204056,56.459946155548096,91.47651271134418,1739502696.2040591,56.459946155548096,15.636342715720906,1739502696.2040603,56.459946155548096,0.009,1739502696.204062,56.459946155548096,-3.1159222428927906,1739502696.2040632,56.459946155548096,0.19439693387211185,1739502696.2040646,56.459946155548096,0.05101592722616963,1739502696.2040658,56.459946155548096,2.13993014242962,1739502696.2040672,56.459946155548096,0.0,1739502696.204069,56.459946155548096,0.03252981585433101,1739502696.20407,56.459946155548096,3.1313186473866925,1739502696.2040715,56.459946155548096,2.107400326575289 +1739502696.224513,56.47994613647461,21.043990299761077,1739502696.224516,56.47994613647461,0.14784703440297164,1739502696.2245193,56.47994613647461,91.47651271134418,1739502696.2245219,56.47994613647461,15.636342715720906,1739502696.2245235,56.47994613647461,0.009,1739502696.224526,56.47994613647461,-3.1159222428927906,1739502696.2245271,56.47994613647461,0.19439693387211185,1739502696.2245286,56.47994613647461,0.05101592722616963,1739502696.22453,56.47994613647461,2.13993014242962,1739502696.2245314,56.47994613647461,0.0,1739502696.2245333,56.47994613647461,0.03252981585433101,1739502696.2245347,56.47994613647461,3.1313186473866925,1739502696.2245362,56.47994613647461,2.107400326575289 +1739502696.2443027,56.49994611740112,20.81201010841919,1739502696.2443051,56.49994611740112,0.15012972452527773,1739502696.244308,56.49994611740112,91.80068006073196,1739502696.2443109,56.49994611740112,15.305063313457232,1739502696.2443123,56.49994611740112,0.009,1739502696.244314,56.49994611740112,-3.11597068097556,1739502696.2443154,56.49994611740112,0.19244118918876196,1739502696.2443168,56.49994611740112,0.04869834512986396,1739502696.2443185,56.49994611740112,2.143280888626741,1739502696.24432,56.49994611740112,0.0,1739502696.2443213,56.49994611740112,0.03223122632413852,1739502696.2443228,56.49994611740112,3.132273817366619,1739502696.2443242,56.49994611740112,2.110956353013239 +1739502696.2670739,56.51994609832764,20.81201010841919,1739502696.2670777,56.51994609832764,0.15012972452527773,1739502696.2670825,56.51994609832764,91.80068006073196,1739502696.267088,56.51994609832764,15.305063313457232,1739502696.267091,56.51994609832764,0.009,1739502696.2670949,56.51994609832764,-3.11597068097556,1739502696.2670984,56.51994609832764,0.19244118918876196,1739502696.267102,56.51994609832764,0.04869834512986396,1739502696.2671053,56.51994609832764,2.143280888626741,1739502696.2671092,56.51994609832764,0.0,1739502696.2671127,56.51994609832764,0.032324535613502015,1739502696.2671165,56.51994609832764,3.132273817366619,1739502696.26712,56.51994609832764,2.110956353013239 +1739502696.2862265,56.53994607925415,20.81201010841919,1739502696.2862303,56.53994607925415,0.15012972452527773,1739502696.2862353,56.53994607925415,91.80068006073196,1739502696.2862406,56.53994607925415,15.305063313457232,1739502696.2862437,56.53994607925415,0.009,1739502696.2862475,56.53994607925415,-3.11597068097556,1739502696.2862508,56.53994607925415,0.19244118918876196,1739502696.2862544,56.53994607925415,0.04869834512986396,1739502696.2862577,56.53994607925415,2.143280888626741,1739502696.2862613,56.53994607925415,0.0,1739502696.2862647,56.53994607925415,0.032324535613502015,1739502696.2862682,56.53994607925415,3.132273817366619,1739502696.2862716,56.53994607925415,2.110956353013239 +1739502696.3055134,56.559946060180664,20.81201010841919,1739502696.3055186,56.559946060180664,0.15012972452527773,1739502696.3055239,56.559946060180664,91.80068006073196,1739502696.3055296,56.559946060180664,15.305063313457232,1739502696.3055334,56.559946060180664,0.009,1739502696.3055367,56.559946060180664,-3.11597068097556,1739502696.3055415,56.559946060180664,0.19244118918876196,1739502696.3055456,56.559946060180664,0.04869834512986396,1739502696.305549,56.559946060180664,2.143280888626741,1739502696.3055525,56.559946060180664,0.0,1739502696.3055558,56.559946060180664,0.032324535613502015,1739502696.3055594,56.559946060180664,3.132273817366619,1739502696.3055627,56.559946060180664,2.110956353013239 +1739502696.3268843,56.57994604110718,20.81201010841919,1739502696.326888,56.57994604110718,0.15012972452527773,1739502696.3268929,56.57994604110718,91.80068006073196,1739502696.326898,56.57994604110718,15.305063313457232,1739502696.326901,56.57994604110718,0.009,1739502696.3269048,56.57994604110718,-3.11597068097556,1739502696.3269083,56.57994604110718,0.19244118918876196,1739502696.3269117,56.57994604110718,0.04869834512986396,1739502696.326915,56.57994604110718,2.143280888626741,1739502696.3269186,56.57994604110718,0.0,1739502696.3269224,56.57994604110718,0.032324535613502015,1739502696.3269258,56.57994604110718,3.132273817366619,1739502696.3269293,56.57994604110718,2.110956353013239 +1739502696.3456395,56.59994602203369,20.81201010841919,1739502696.3456423,56.59994602203369,0.15012972452527773,1739502696.345645,56.59994602203369,91.80068006073196,1739502696.345648,56.59994602203369,15.305063313457232,1739502696.3456495,56.59994602203369,0.009,1739502696.3456516,56.59994602203369,-3.11597068097556,1739502696.345653,56.59994602203369,0.19244118918876196,1739502696.3456545,56.59994602203369,0.04869834512986396,1739502696.345656,56.59994602203369,2.143280888626741,1739502696.3456573,56.59994602203369,0.0,1739502696.3456585,56.59994602203369,0.032324535613502015,1739502696.34566,56.59994602203369,3.132273817366619,1739502696.3456612,56.59994602203369,2.110956353013239 +1739502696.3653789,56.619946002960205,20.57963697251532,1739502696.3653815,56.619946002960205,0.15219430628934116,1739502696.365384,56.619946002960205,91.86416252911172,1739502696.365387,56.619946002960205,15.234505854804958,1739502696.3653884,56.619946002960205,0.009,1739502696.36539,56.619946002960205,-3.1148093882827905,1739502696.3653917,56.619946002960205,0.18789366953770886,1739502696.365393,56.619946002960205,0.050466605893591254,1739502696.3653946,56.619946002960205,2.15109237874014,1739502696.3653963,56.619946002960205,0.0,1739502696.3653975,56.619946002960205,0.038541257432983325,1739502696.365399,56.619946002960205,3.1332289873465453,1739502696.3654003,56.619946002960205,2.1144938481494955 +1739502696.3867254,56.63994598388672,20.57963697251532,1739502696.3867302,56.63994598388672,0.15219430628934116,1739502696.3867364,56.63994598388672,91.86416252911172,1739502696.3867414,56.63994598388672,15.234505854804958,1739502696.3867443,56.63994598388672,0.009,1739502696.3867493,56.63994598388672,-3.1148093882827905,1739502696.3867526,56.63994598388672,0.18789366953770886,1739502696.3867555,56.63994598388672,0.050466605893591254,1739502696.3867586,56.63994598388672,2.15109237874014,1739502696.3867621,56.63994598388672,0.0,1739502696.386765,56.63994598388672,0.03659853059064444,1739502696.38677,56.63994598388672,3.1332289873465453,1739502696.3867726,56.63994598388672,2.1144938481494955 +1739502696.4054198,56.65994596481323,20.57963697251532,1739502696.4054224,56.65994596481323,0.15219430628934116,1739502696.405425,56.65994596481323,91.86416252911172,1739502696.4054275,56.65994596481323,15.234505854804958,1739502696.4054286,56.65994596481323,0.009,1739502696.4054303,56.65994596481323,-3.1148093882827905,1739502696.4054315,56.65994596481323,0.18789366953770886,1739502696.405433,56.65994596481323,0.050466605893591254,1739502696.405434,56.65994596481323,2.15109237874014,1739502696.4054353,56.65994596481323,0.0,1739502696.4054365,56.65994596481323,0.03659853059064444,1739502696.4054377,56.65994596481323,3.1332289873465453,1739502696.405439,56.65994596481323,2.1144938481494955 +1739502696.4243252,56.679945945739746,20.57963697251532,1739502696.4243274,56.679945945739746,0.15219430628934116,1739502696.4243305,56.679945945739746,91.86416252911172,1739502696.4243333,56.679945945739746,15.234505854804958,1739502696.4243345,56.679945945739746,0.009,1739502696.4243362,56.679945945739746,-3.1148093882827905,1739502696.4243376,56.679945945739746,0.18789366953770886,1739502696.4243393,56.679945945739746,0.050466605893591254,1739502696.4243402,56.679945945739746,2.15109237874014,1739502696.424342,56.679945945739746,0.0,1739502696.4243433,56.679945945739746,0.03659853059064444,1739502696.4243448,56.679945945739746,3.1332289873465453,1739502696.4243462,56.679945945739746,2.1144938481494955 +1739502696.444224,56.69994592666626,20.57963697251532,1739502696.444226,56.69994592666626,0.15219430628934116,1739502696.4442291,56.69994592666626,91.86416252911172,1739502696.444232,56.69994592666626,15.234505854804958,1739502696.4442332,56.69994592666626,0.009,1739502696.444235,56.69994592666626,-3.1148093882827905,1739502696.4442363,56.69994592666626,0.18789366953770886,1739502696.4442375,56.69994592666626,0.050466605893591254,1739502696.444239,56.69994592666626,2.15109237874014,1739502696.4442403,56.69994592666626,0.0,1739502696.4442415,56.69994592666626,0.03659853059064444,1739502696.444243,56.69994592666626,3.1332289873465453,1739502696.4442441,56.69994592666626,2.1144938481494955 +1739502696.4644048,56.71994590759277,20.346850530940756,1739502696.4644084,56.71994590759277,0.1540401896477741,1739502696.4644117,56.71994590759277,92.1493227839405,1739502696.4644148,56.71994590759277,14.941345044836725,1739502696.4644163,56.71994590759277,0.009,1739502696.464418,56.71994590759277,-3.1147671517602937,1739502696.4644194,56.71994590759277,0.185082510205166,1739502696.4644208,56.71994590759277,0.048607514111852074,1739502696.4644222,56.71994590759277,2.1559354733156386,1739502696.464424,56.71994590759277,0.0,1739502696.4644253,56.71994590759277,0.03782444660076693,1739502696.4644265,56.71994590759277,3.1341841573264717,1739502696.4644277,56.71994590759277,2.1184941257192142 +1739502696.4841373,56.73994588851929,20.346850530940756,1739502696.4841392,56.73994588851929,0.1540401896477741,1739502696.484142,56.73994588851929,92.1493227839405,1739502696.4841447,56.73994588851929,14.941345044836725,1739502696.484146,56.73994588851929,0.009,1739502696.4841478,56.73994588851929,-3.1147671517602937,1739502696.484149,56.73994588851929,0.185082510205166,1739502696.4841502,56.73994588851929,0.048607514111852074,1739502696.4841516,56.73994588851929,2.1559354733156386,1739502696.484153,56.73994588851929,0.0,1739502696.4841545,56.73994588851929,0.03744134759642437,1739502696.4841557,56.73994588851929,3.1341841573264717,1739502696.4841568,56.73994588851929,2.1184941257192142 +1739502696.5042121,56.7599458694458,20.346850530940756,1739502696.5042143,56.7599458694458,0.1540401896477741,1739502696.5042171,56.7599458694458,92.1493227839405,1739502696.5042195,56.7599458694458,14.941345044836725,1739502696.5042212,56.7599458694458,0.009,1739502696.5042226,56.7599458694458,-3.1147671517602937,1739502696.5042243,56.7599458694458,0.185082510205166,1739502696.5042255,56.7599458694458,0.048607514111852074,1739502696.5042264,56.7599458694458,2.1559354733156386,1739502696.504228,56.7599458694458,0.0,1739502696.5042293,56.7599458694458,0.03744134759642437,1739502696.5042307,56.7599458694458,3.1341841573264717,1739502696.504232,56.7599458694458,2.1184941257192142 +1739502696.5243313,56.779945850372314,20.346850530940756,1739502696.5243337,56.779945850372314,0.1540401896477741,1739502696.5243368,56.779945850372314,92.1493227839405,1739502696.5243394,56.779945850372314,14.941345044836725,1739502696.5243406,56.779945850372314,0.009,1739502696.5243425,56.779945850372314,-3.1147671517602937,1739502696.5243437,56.779945850372314,0.185082510205166,1739502696.5243454,56.779945850372314,0.048607514111852074,1739502696.5243464,56.779945850372314,2.1559354733156386,1739502696.524348,56.779945850372314,0.0,1739502696.5243492,56.779945850372314,0.03744134759642437,1739502696.5243506,56.779945850372314,3.1341841573264717,1739502696.524352,56.779945850372314,2.1184941257192142 +1739502696.5443463,56.79994583129883,20.346850530940756,1739502696.5443494,56.79994583129883,0.1540401896477741,1739502696.5443525,56.79994583129883,92.1493227839405,1739502696.5443556,56.79994583129883,14.941345044836725,1739502696.5443568,56.79994583129883,0.009,1739502696.5443587,56.79994583129883,-3.1147671517602937,1739502696.54436,56.79994583129883,0.185082510205166,1739502696.5443614,56.79994583129883,0.048607514111852074,1739502696.5443628,56.79994583129883,2.1559354733156386,1739502696.5443645,56.79994583129883,0.0,1739502696.544366,56.79994583129883,0.03744134759642437,1739502696.544367,56.79994583129883,3.1341841573264717,1739502696.5443687,56.79994583129883,2.1184941257192142 +1739502696.5643919,56.81994581222534,20.346850530940756,1739502696.5643947,56.81994581222534,0.1540401896477741,1739502696.5643978,56.81994581222534,92.1493227839405,1739502696.5644004,56.81994581222534,14.941345044836725,1739502696.5644019,56.81994581222534,0.009,1739502696.5644038,56.81994581222534,-3.1147671517602937,1739502696.564405,56.81994581222534,0.185082510205166,1739502696.5644062,56.81994581222534,0.048607514111852074,1739502696.5644076,56.81994581222534,2.1559354733156386,1739502696.5644093,56.81994581222534,0.0,1739502696.5644107,56.81994581222534,0.03744134759642437,1739502696.564412,56.81994581222534,3.1341841573264717,1739502696.5644135,56.81994581222534,2.1184941257192142 +1739502696.5842814,56.839945793151855,20.113615775453987,1739502696.5842838,56.839945793151855,0.15566683606806375,1739502696.5842867,56.839945793151855,92.9571393689625,1739502696.5842893,56.839945793151855,14.125314121847195,1739502696.5842907,56.839945793151855,0.009,1739502696.5842927,56.839945793151855,-3.1171053234363684,1739502696.5842938,56.839945793151855,0.1853079783048427,1739502696.5842955,56.839945793151855,0.039660871694944505,1739502696.5842965,56.839945793151855,2.1555466326458044,1739502696.5842981,56.839945793151855,0.0,1739502696.5842996,56.839945793151855,0.030901695242229143,1739502696.5843008,56.839945793151855,3.135139327306398,1739502696.5843022,56.839945793151855,2.1226012947029727 +1739502696.6042402,56.85994577407837,20.113615775453987,1739502696.6042423,56.85994577407837,0.15566683606806375,1739502696.6042454,56.85994577407837,92.9571393689625,1739502696.604248,56.85994577407837,14.125314121847195,1739502696.6042492,56.85994577407837,0.009,1739502696.6042511,56.85994577407837,-3.1171053234363684,1739502696.6042523,56.85994577407837,0.1853079783048427,1739502696.604254,56.85994577407837,0.039660871694944505,1739502696.6042552,56.85994577407837,2.1555466326458044,1739502696.6042569,56.85994577407837,0.0,1739502696.604258,56.85994577407837,0.03294533794283172,1739502696.6042593,56.85994577407837,3.135139327306398,1739502696.604261,56.85994577407837,2.1226012947029727 +1739502696.624243,56.87994575500488,20.113615775453987,1739502696.6242454,56.87994575500488,0.15566683606806375,1739502696.6242487,56.87994575500488,92.9571393689625,1739502696.6242514,56.87994575500488,14.125314121847195,1739502696.6242526,56.87994575500488,0.009,1739502696.6242545,56.87994575500488,-3.1171053234363684,1739502696.6242557,56.87994575500488,0.1853079783048427,1739502696.624257,56.87994575500488,0.039660871694944505,1739502696.624258,56.87994575500488,2.1555466326458044,1739502696.6242595,56.87994575500488,0.0,1739502696.624261,56.87994575500488,0.03294533794283172,1739502696.6242628,56.87994575500488,3.135139327306398,1739502696.6242642,56.87994575500488,2.1226012947029727 +1739502696.646124,56.8999457359314,20.113615775453987,1739502696.6461265,56.8999457359314,0.15566683606806375,1739502696.6461291,56.8999457359314,92.9571393689625,1739502696.646132,56.8999457359314,14.125314121847195,1739502696.6461334,56.8999457359314,0.009,1739502696.6461356,56.8999457359314,-3.1171053234363684,1739502696.6461368,56.8999457359314,0.1853079783048427,1739502696.6461382,56.8999457359314,0.039660871694944505,1739502696.6461394,56.8999457359314,2.1555466326458044,1739502696.6461408,56.8999457359314,0.0,1739502696.6461422,56.8999457359314,0.03294533794283172,1739502696.6461437,56.8999457359314,3.135139327306398,1739502696.6461453,56.8999457359314,2.1226012947029727 +1739502696.66429,56.91994571685791,20.113615775453987,1739502696.6642926,56.91994571685791,0.15566683606806375,1739502696.664296,56.91994571685791,92.9571393689625,1739502696.6642985,56.91994571685791,14.125314121847195,1739502696.6642997,56.91994571685791,0.009,1739502696.6643016,56.91994571685791,-3.1171053234363684,1739502696.6643033,56.91994571685791,0.1853079783048427,1739502696.6643047,56.91994571685791,0.039660871694944505,1739502696.6643057,56.91994571685791,2.1555466326458044,1739502696.664307,56.91994571685791,0.0,1739502696.6643085,56.91994571685791,0.03294533794283172,1739502696.66431,56.91994571685791,3.135139327306398,1739502696.6643114,56.91994571685791,2.1226012947029727 +1739502696.6842704,56.939945697784424,19.87995253967947,1739502696.6842732,56.939945697784424,0.15707327787066294,1739502696.6842763,56.939945697784424,92.98261006810372,1739502696.6842787,56.939945697784424,14.092628416036966,1739502696.6842802,56.939945697784424,0.00899685098336412,1739502696.6842818,56.939945697784424,-3.116011897589119,1739502696.684283,56.939945697784424,0.17989364103278757,1739502696.6842842,56.939945697784424,0.04122017831510667,1739502696.6842854,56.939945697784424,2.164903567837543,1739502696.684287,56.939945697784424,0.0,1739502696.6842883,56.939945697784424,0.04130814070526446,1739502696.6842892,56.939945697784424,3.1360944972863245,1739502696.6842906,56.939945697784424,2.1262088047090026 +1739502696.7049255,56.95994567871094,19.87995253967947,1739502696.704928,56.95994567871094,0.15707327787066294,1739502696.7049305,56.95994567871094,92.98261006810372,1739502696.704933,56.95994567871094,14.092628416036966,1739502696.7049341,56.95994567871094,0.00899685098336412,1739502696.7049358,56.95994567871094,-3.116011897589119,1739502696.704937,56.95994567871094,0.17989364103278757,1739502696.7049382,56.95994567871094,0.04122017831510667,1739502696.7049394,56.95994567871094,2.164903567837543,1739502696.7049408,56.95994567871094,0.0,1739502696.7049417,56.95994567871094,0.038694763128540366,1739502696.7049432,56.95994567871094,3.1360944972863245,1739502696.7049444,56.95994567871094,2.1262088047090026 +1739502696.7241893,56.97994565963745,19.87995253967947,1739502696.7241914,56.97994565963745,0.15707327787066294,1739502696.7241948,56.97994565963745,92.98261006810372,1739502696.7241974,56.97994565963745,14.092628416036966,1739502696.7241986,56.97994565963745,0.00899685098336412,1739502696.7242005,56.97994565963745,-3.116011897589119,1739502696.7242017,56.97994565963745,0.17989364103278757,1739502696.724203,56.97994565963745,0.04122017831510667,1739502696.7242043,56.97994565963745,2.164903567837543,1739502696.7242057,56.97994565963745,0.0,1739502696.7242072,56.97994565963745,0.038694763128540366,1739502696.7242088,56.97994565963745,3.1360944972863245,1739502696.7242103,56.97994565963745,2.1262088047090026 +1739502696.744386,56.999945640563965,19.87995253967947,1739502696.7443886,56.999945640563965,0.15707327787066294,1739502696.7443917,56.999945640563965,92.98261006810372,1739502696.7443948,56.999945640563965,14.092628416036966,1739502696.744396,56.999945640563965,0.00899685098336412,1739502696.7443976,56.999945640563965,-3.116011897589119,1739502696.7443988,56.999945640563965,0.17989364103278757,1739502696.7444,56.999945640563965,0.04122017831510667,1739502696.7444015,56.999945640563965,2.164903567837543,1739502696.744403,56.999945640563965,0.0,1739502696.7444043,56.999945640563965,0.038694763128540366,1739502696.7444055,56.999945640563965,3.1360944972863245,1739502696.744407,56.999945640563965,2.1262088047090026 +1739502696.7644088,57.01994562149048,19.87995253967947,1739502696.7644122,57.01994562149048,0.15707327787066294,1739502696.7644153,57.01994562149048,92.98261006810372,1739502696.764418,57.01994562149048,14.092628416036966,1739502696.7644193,57.01994562149048,0.00899685098336412,1739502696.7644212,57.01994562149048,-3.116011897589119,1739502696.7644227,57.01994562149048,0.17989364103278757,1739502696.7644238,57.01994562149048,0.04122017831510667,1739502696.7644253,57.01994562149048,2.164903567837543,1739502696.7644267,57.01994562149048,0.0,1739502696.7644281,57.01994562149048,0.038694763128540366,1739502696.7644293,57.01994562149048,3.1360944972863245,1739502696.7644305,57.01994562149048,2.1262088047090026 +1739502696.7842705,57.03994560241699,19.87995253967947,1739502696.784273,57.03994560241699,0.15707327787066294,1739502696.7842755,57.03994560241699,92.98261006810372,1739502696.7842782,57.03994560241699,14.092628416036966,1739502696.7842796,57.03994560241699,0.00899685098336412,1739502696.784281,57.03994560241699,-3.116011897589119,1739502696.7842827,57.03994560241699,0.17989364103278757,1739502696.7842839,57.03994560241699,0.04122017831510667,1739502696.7842848,57.03994560241699,2.164903567837543,1739502696.7842867,57.03994560241699,0.0,1739502696.784288,57.03994560241699,0.038694763128540366,1739502696.7842894,57.03994560241699,3.1360944972863245,1739502696.7842906,57.03994560241699,2.1262088047090026 +1739502696.8042376,57.059945583343506,19.645855404118304,1739502696.80424,57.059945583343506,0.1582587159995823,1739502696.8042426,57.059945583343506,93.00812784131803,1739502696.8042452,57.059945583343506,14.058534684289473,1739502696.8042464,57.059945583343506,0.008707921053300616,1739502696.804248,57.059945583343506,-3.1148329410457762,1739502696.8042493,57.059945583343506,0.1749322859830654,1739502696.8042507,57.059945583343506,0.04300146155955674,1739502696.804252,57.059945583343506,2.173513327162557,1739502696.8042533,57.059945583343506,0.0,1739502696.8042545,57.059945583343506,0.04498010017223328,1739502696.8042557,57.059945583343506,3.137049667266251,1739502696.804257,57.059945583343506,2.1304973961042872 +1739502696.8243546,57.07994556427002,19.645855404118304,1739502696.824357,57.07994556427002,0.1582587159995823,1739502696.82436,57.07994556427002,93.00812784131803,1739502696.8243625,57.07994556427002,14.058534684289473,1739502696.8243637,57.07994556427002,0.008707921053300616,1739502696.8243656,57.07994556427002,-3.1148329410457762,1739502696.824367,57.07994556427002,0.1749322859830654,1739502696.8243685,57.07994556427002,0.04300146155955674,1739502696.8243694,57.07994556427002,2.173513327162557,1739502696.8243709,57.07994556427002,0.0,1739502696.8243723,57.07994556427002,0.04301593105826962,1739502696.8243737,57.07994556427002,3.137049667266251,1739502696.8243752,57.07994556427002,2.1304973961042872 +1739502696.8444397,57.09994554519653,19.645855404118304,1739502696.8444424,57.09994554519653,0.1582587159995823,1739502696.8444455,57.09994554519653,93.00812784131803,1739502696.8444483,57.09994554519653,14.058534684289473,1739502696.8444498,57.09994554519653,0.008707921053300616,1739502696.8444514,57.09994554519653,-3.1148329410457762,1739502696.8444526,57.09994554519653,0.1749322859830654,1739502696.844454,57.09994554519653,0.04300146155955674,1739502696.8444555,57.09994554519653,2.173513327162557,1739502696.844457,57.09994554519653,0.0,1739502696.8444583,57.09994554519653,0.04301593105826962,1739502696.8444598,57.09994554519653,3.137049667266251,1739502696.844461,57.09994554519653,2.1304973961042872 +1739502696.8643975,57.11994552612305,19.645855404118304,1739502696.8644006,57.11994552612305,0.1582587159995823,1739502696.8644037,57.11994552612305,93.00812784131803,1739502696.8644066,57.11994552612305,14.058534684289473,1739502696.8644078,57.11994552612305,0.008707921053300616,1739502696.8644097,57.11994552612305,-3.1148329410457762,1739502696.8644109,57.11994552612305,0.1749322859830654,1739502696.864412,57.11994552612305,0.04300146155955674,1739502696.8644135,57.11994552612305,2.173513327162557,1739502696.8644152,57.11994552612305,0.0,1739502696.8644166,57.11994552612305,0.04301593105826962,1739502696.864418,57.11994552612305,3.137049667266251,1739502696.8644197,57.11994552612305,2.1304973961042872 +1739502696.8841755,57.13994550704956,19.645855404118304,1739502696.8841777,57.13994550704956,0.1582587159995823,1739502696.8841805,57.13994550704956,93.00812784131803,1739502696.8841834,57.13994550704956,14.058534684289473,1739502696.8841846,57.13994550704956,0.008707921053300616,1739502696.884186,57.13994550704956,-3.1148329410457762,1739502696.8841877,57.13994550704956,0.1749322859830654,1739502696.884189,57.13994550704956,0.04300146155955674,1739502696.8841903,57.13994550704956,2.173513327162557,1739502696.884192,57.13994550704956,0.0,1739502696.8841932,57.13994550704956,0.04301593105826962,1739502696.8841949,57.13994550704956,3.137049667266251,1739502696.884196,57.13994550704956,2.1304973961042872 +1739502696.9042127,57.159945487976074,19.411268119123843,1739502696.904215,57.159945487976074,0.15922255684691056,1739502696.904218,57.159945487976074,93.03369881922326,1739502696.9042203,57.159945487976074,14.023560712964322,1739502696.9042218,57.159945487976074,0.008411531465799347,1739502696.9042232,57.159945487976074,-3.113608272856083,1739502696.9042249,57.159945487976074,0.1701401179458365,1739502696.904226,57.159945487976074,0.04497666542928524,1739502696.9042275,57.159945487976074,2.181861993097123,1739502696.9042292,57.159945487976074,0.0,1739502696.9042304,57.159945487976074,0.048319992699861175,1739502696.9042318,57.159945487976074,3.1380048372461773,1739502696.9042332,57.159945487976074,2.135199520747014 +1739502696.9243674,57.17994546890259,19.411268119123843,1739502696.9243698,57.17994546890259,0.15922255684691056,1739502696.9243731,57.17994546890259,93.03369881922326,1739502696.924376,57.17994546890259,14.023560712964322,1739502696.9243774,57.17994546890259,0.008411531465799347,1739502696.9243789,57.17994546890259,-3.113608272856083,1739502696.9243803,57.17994546890259,0.1701401179458365,1739502696.9243822,57.17994546890259,0.04497666542928524,1739502696.9243832,57.17994546890259,2.181861993097123,1739502696.924385,57.17994546890259,0.0,1739502696.924386,57.17994546890259,0.046662472350108786,1739502696.9243877,57.17994546890259,3.1380048372461773,1739502696.924389,57.17994546890259,2.135199520747014 +1739502696.9442637,57.1999454498291,19.411268119123843,1739502696.944266,57.1999454498291,0.15922255684691056,1739502696.9442687,57.1999454498291,93.03369881922326,1739502696.9442713,57.1999454498291,14.023560712964322,1739502696.9442728,57.1999454498291,0.008411531465799347,1739502696.9442744,57.1999454498291,-3.113608272856083,1739502696.9442756,57.1999454498291,0.1701401179458365,1739502696.944277,57.1999454498291,0.04497666542928524,1739502696.9442782,57.1999454498291,2.181861993097123,1739502696.94428,57.1999454498291,0.0,1739502696.944281,57.1999454498291,0.046662472350108786,1739502696.9442825,57.1999454498291,3.1380048372461773,1739502696.944284,57.1999454498291,2.135199520747014 +1739502696.9643657,57.219945430755615,19.411268119123843,1739502696.9643686,57.219945430755615,0.15922255684691056,1739502696.9643722,57.219945430755615,93.03369881922326,1739502696.9643753,57.219945430755615,14.023560712964322,1739502696.9643767,57.219945430755615,0.008411531465799347,1739502696.9643784,57.219945430755615,-3.113608272856083,1739502696.9643798,57.219945430755615,0.1701401179458365,1739502696.9643815,57.219945430755615,0.04497666542928524,1739502696.9643826,57.219945430755615,2.181861993097123,1739502696.9643846,57.219945430755615,0.0,1739502696.964386,57.219945430755615,0.046662472350108786,1739502696.9643874,57.219945430755615,3.1380048372461773,1739502696.9643888,57.219945430755615,2.135199520747014 +1739502696.9841883,57.23994541168213,19.411268119123843,1739502696.9841905,57.23994541168213,0.15922255684691056,1739502696.9841933,57.23994541168213,93.03369881922326,1739502696.9841962,57.23994541168213,14.023560712964322,1739502696.9841974,57.23994541168213,0.008411531465799347,1739502696.9841993,57.23994541168213,-3.113608272856083,1739502696.9842005,57.23994541168213,0.1701401179458365,1739502696.9842017,57.23994541168213,0.04497666542928524,1739502696.984203,57.23994541168213,2.181861993097123,1739502696.9842045,57.23994541168213,0.0,1739502696.9842057,57.23994541168213,0.046662472350108786,1739502696.9842074,57.23994541168213,3.1380048372461773,1739502696.9842086,57.23994541168213,2.135199520747014 +1739502697.0042627,57.25994539260864,19.411268119123843,1739502697.0042653,57.25994539260864,0.15922255684691056,1739502697.004268,57.25994539260864,93.03369881922326,1739502697.0042708,57.25994539260864,14.023560712964322,1739502697.0042722,57.25994539260864,0.008411531465799347,1739502697.004274,57.25994539260864,-3.113608272856083,1739502697.004275,57.25994539260864,0.1701401179458365,1739502697.0042765,57.25994539260864,0.04497666542928524,1739502697.0042777,57.25994539260864,2.181861993097123,1739502697.0042794,57.25994539260864,0.0,1739502697.0042806,57.25994539260864,0.046662472350108786,1739502697.004282,57.25994539260864,3.1380048372461773,1739502697.0042837,57.25994539260864,2.135199520747014 +1739502697.0244598,57.279945373535156,19.176138281961148,1739502697.0244627,57.279945373535156,0.15996403150200322,1739502697.0244656,57.279945373535156,93.35248170708678,1739502697.0244684,57.279945373535156,13.694495574359227,1739502697.0244699,57.279945373535156,0.008,1739502697.0244715,57.279945373535156,-3.1138773996107547,1739502697.0244732,57.279945373535156,0.16639471495526992,1739502697.0244744,57.279945373535156,0.04249292369993626,1739502697.0244756,57.279945373535156,2.188409359155557,1739502697.0244772,57.279945373535156,0.0,1739502697.0244784,57.279945373535156,0.04870664578055196,1739502697.02448,57.279945373535156,3.1389600072261037,1739502697.0244813,57.279945373535156,2.1403415179908514 +1739502697.0443654,57.29994535446167,19.176138281961148,1739502697.044368,57.29994535446167,0.15996403150200322,1739502697.0443711,57.29994535446167,93.35248170708678,1739502697.044374,57.29994535446167,13.694495574359227,1739502697.044376,57.29994535446167,0.008,1739502697.0443776,57.29994535446167,-3.1138773996107547,1739502697.0443792,57.29994535446167,0.16639471495526992,1739502697.0443807,57.29994535446167,0.04249292369993626,1739502697.0443816,57.29994535446167,2.188409359155557,1739502697.0443838,57.29994535446167,0.0,1739502697.0443852,57.29994535446167,0.04806784116470553,1739502697.0443866,57.29994535446167,3.1389600072261037,1739502697.044388,57.29994535446167,2.1403415179908514 +1739502697.0643742,57.319945335388184,19.176138281961148,1739502697.0643768,57.319945335388184,0.15996403150200322,1739502697.0643802,57.319945335388184,93.35248170708678,1739502697.064383,57.319945335388184,13.694495574359227,1739502697.0643842,57.319945335388184,0.008,1739502697.064386,57.319945335388184,-3.1138773996107547,1739502697.064387,57.319945335388184,0.16639471495526992,1739502697.0643885,57.319945335388184,0.04249292369993626,1739502697.06439,57.319945335388184,2.188409359155557,1739502697.0643914,57.319945335388184,0.0,1739502697.0643926,57.319945335388184,0.04806784116470553,1739502697.0643942,57.319945335388184,3.1389600072261037,1739502697.0643954,57.319945335388184,2.1403415179908514 +1739502697.0843306,57.3399453163147,19.176138281961148,1739502697.084333,57.3399453163147,0.15996403150200322,1739502697.0843358,57.3399453163147,93.35248170708678,1739502697.0843382,57.3399453163147,13.694495574359227,1739502697.0843394,57.3399453163147,0.008,1739502697.084341,57.3399453163147,-3.1138773996107547,1739502697.0843422,57.3399453163147,0.16639471495526992,1739502697.0843434,57.3399453163147,0.04249292369993626,1739502697.0843446,57.3399453163147,2.188409359155557,1739502697.084346,57.3399453163147,0.0,1739502697.0843475,57.3399453163147,0.04806784116470553,1739502697.0843487,57.3399453163147,3.1389600072261037,1739502697.0843499,57.3399453163147,2.1403415179908514 +1739502697.1041803,57.35994529724121,19.176138281961148,1739502697.1041822,57.35994529724121,0.15996403150200322,1739502697.104185,57.35994529724121,93.35248170708678,1739502697.1041877,57.35994529724121,13.694495574359227,1739502697.104189,57.35994529724121,0.008,1739502697.1041903,57.35994529724121,-3.1138773996107547,1739502697.104192,57.35994529724121,0.16639471495526992,1739502697.1041932,57.35994529724121,0.04249292369993626,1739502697.1041946,57.35994529724121,2.188409359155557,1739502697.1041958,57.35994529724121,0.0,1739502697.104197,57.35994529724121,0.04806784116470553,1739502697.1041987,57.35994529724121,3.1389600072261037,1739502697.1042,57.35994529724121,2.1403415179908514 +1739502697.1244743,57.379945278167725,18.94043844743375,1739502697.1244776,57.379945278167725,0.16048216752555966,1739502697.1244805,57.379945278167725,93.67389625679455,1739502697.1244833,57.379945278167725,13.362571272581635,1739502697.1244848,57.379945278167725,0.007,1739502697.1244864,57.379945278167725,-3.1140833128009717,1739502697.1244879,57.379945278167725,0.1628386876511877,1739502697.1244893,57.379945278167725,0.0401631557998839,1739502697.1244905,57.379945278167725,2.194643857716679,1739502697.1244926,57.379945278167725,0.0,1739502697.124494,57.379945278167725,0.04948963913476089,1739502697.1244953,57.379945278167725,3.13991517720603,1739502697.1244967,57.379945278167725,2.1455985307388743 +1739502697.144362,57.39994525909424,18.94043844743375,1739502697.1443646,57.39994525909424,0.16048216752555966,1739502697.1443675,57.39994525909424,93.67389625679455,1739502697.1443698,57.39994525909424,13.362571272581635,1739502697.1443715,57.39994525909424,0.007,1739502697.144373,57.39994525909424,-3.1140833128009717,1739502697.1443744,57.39994525909424,0.1628386876511877,1739502697.1443758,57.39994525909424,0.0401631557998839,1739502697.1443768,57.39994525909424,2.194643857716679,1739502697.1443787,57.39994525909424,0.0,1739502697.1443799,57.39994525909424,0.04904532697780484,1739502697.1443813,57.39994525909424,3.13991517720603,1739502697.1443825,57.39994525909424,2.1455985307388743 +1739502697.1642957,57.41994524002075,18.94043844743375,1739502697.1642983,57.41994524002075,0.16048216752555966,1739502697.1643014,57.41994524002075,93.67389625679455,1739502697.164304,57.41994524002075,13.362571272581635,1739502697.1643054,57.41994524002075,0.007,1739502697.1643069,57.41994524002075,-3.1140833128009717,1739502697.1643083,57.41994524002075,0.1628386876511877,1739502697.1643097,57.41994524002075,0.0401631557998839,1739502697.164311,57.41994524002075,2.194643857716679,1739502697.1643138,57.41994524002075,0.0,1739502697.1643155,57.41994524002075,0.04904532697780484,1739502697.164317,57.41994524002075,3.13991517720603,1739502697.1643186,57.41994524002075,2.1455985307388743 +1739502697.1842248,57.439945220947266,18.94043844743375,1739502697.184227,57.439945220947266,0.16048216752555966,1739502697.18423,57.439945220947266,93.67389625679455,1739502697.1842327,57.439945220947266,13.362571272581635,1739502697.184234,57.439945220947266,0.007,1739502697.1842358,57.439945220947266,-3.1140833128009717,1739502697.184237,57.439945220947266,0.1628386876511877,1739502697.1842384,57.439945220947266,0.0401631557998839,1739502697.1842396,57.439945220947266,2.194643857716679,1739502697.184241,57.439945220947266,0.0,1739502697.1842425,57.439945220947266,0.04904532697780484,1739502697.1842437,57.439945220947266,3.13991517720603,1739502697.184245,57.439945220947266,2.1455985307388743 +1739502697.2041137,57.45994520187378,18.94043844743375,1739502697.2041159,57.45994520187378,0.16048216752555966,1739502697.2041185,57.45994520187378,93.67389625679455,1739502697.204121,57.45994520187378,13.362571272581635,1739502697.2041223,57.45994520187378,0.007,1739502697.204124,57.45994520187378,-3.1140833128009717,1739502697.2041252,57.45994520187378,0.1628386876511877,1739502697.2041268,57.45994520187378,0.0401631557998839,1739502697.204128,57.45994520187378,2.194643857716679,1739502697.2041292,57.45994520187378,0.0,1739502697.2041306,57.45994520187378,0.04904532697780484,1739502697.2041318,57.45994520187378,3.13991517720603,1739502697.204133,57.45994520187378,2.1455985307388743 +1739502697.2243366,57.47994518280029,18.94043844743375,1739502697.2243397,57.47994518280029,0.16048216752555966,1739502697.2243433,57.47994518280029,93.67389625679455,1739502697.224346,57.47994518280029,13.362571272581635,1739502697.2243474,57.47994518280029,0.007,1739502697.2243493,57.47994518280029,-3.1140833128009717,1739502697.2243505,57.47994518280029,0.1628386876511877,1739502697.224352,57.47994518280029,0.0401631557998839,1739502697.2243533,57.47994518280029,2.194643857716679,1739502697.2243547,57.47994518280029,0.0,1739502697.2243562,57.47994518280029,0.04904532697780484,1739502697.2243574,57.47994518280029,3.13991517720603,1739502697.2243588,57.47994518280029,2.1455985307388743 +1739502697.2442377,57.49994516372681,18.70415296106543,1739502697.2442398,57.49994516372681,0.1607758966578281,1739502697.2442431,57.49994516372681,94.08523246317583,1739502697.2442458,57.49994516372681,12.940481756336604,1739502697.244248,57.49994516372681,0.006,1739502697.2442493,57.49994516372681,-3.1147454058564668,1739502697.2442508,57.49994516372681,0.15893899254126195,1739502697.2442522,57.49994516372681,0.03671626782049933,1739502697.2442534,57.49994516372681,2.2015013024682695,1739502697.2442548,57.49994516372681,0.0,1739502697.244256,57.49994516372681,0.05119609577384467,1739502697.2442575,57.49994516372681,3.1408703471859565,1739502697.2442589,57.49994516372681,2.1509773223838606 +1739502697.264423,57.51994514465332,18.70415296106543,1739502697.2644258,57.51994514465332,0.1607758966578281,1739502697.2644293,57.51994514465332,94.08523246317583,1739502697.264432,57.51994514465332,12.940481756336604,1739502697.2644331,57.51994514465332,0.006,1739502697.2644346,57.51994514465332,-3.1147454058564668,1739502697.2644362,57.51994514465332,0.15893899254126195,1739502697.2644374,57.51994514465332,0.03671626782049933,1739502697.2644389,57.51994514465332,2.2015013024682695,1739502697.2644403,57.51994514465332,0.0,1739502697.2644415,57.51994514465332,0.05052398008440884,1739502697.2644432,57.51994514465332,3.1408703471859565,1739502697.2644444,57.51994514465332,2.1509773223838606 +1739502697.28437,57.539945125579834,18.70415296106543,1739502697.2843726,57.539945125579834,0.1607758966578281,1739502697.2843752,57.539945125579834,94.08523246317583,1739502697.2843778,57.539945125579834,12.940481756336604,1739502697.2843792,57.539945125579834,0.006,1739502697.2843812,57.539945125579834,-3.1147454058564668,1739502697.2843826,57.539945125579834,0.15893899254126195,1739502697.2843838,57.539945125579834,0.03671626782049933,1739502697.284385,57.539945125579834,2.2015013024682695,1739502697.2843866,57.539945125579834,0.0,1739502697.2843878,57.539945125579834,0.05052398008440884,1739502697.284389,57.539945125579834,3.1408703471859565,1739502697.2843907,57.539945125579834,2.1509773223838606 +1739502697.304103,57.55994510650635,18.70415296106543,1739502697.3041053,57.55994510650635,0.1607758966578281,1739502697.3041077,57.55994510650635,94.08523246317583,1739502697.3041103,57.55994510650635,12.940481756336604,1739502697.304112,57.55994510650635,0.006,1739502697.3041134,57.55994510650635,-3.1147454058564668,1739502697.3041146,57.55994510650635,0.15893899254126195,1739502697.304116,57.55994510650635,0.03671626782049933,1739502697.3041172,57.55994510650635,2.2015013024682695,1739502697.3041189,57.55994510650635,0.0,1739502697.3041198,57.55994510650635,0.05052398008440884,1739502697.3041213,57.55994510650635,3.1408703471859565,1739502697.3041227,57.55994510650635,2.1509773223838606 +1739502697.3242683,57.57994508743286,18.70415296106543,1739502697.324271,57.57994508743286,0.1607758966578281,1739502697.3242736,57.57994508743286,94.08523246317583,1739502697.3242762,57.57994508743286,12.940481756336604,1739502697.3242774,57.57994508743286,0.006,1739502697.3242793,57.57994508743286,-3.1147454058564668,1739502697.3242805,57.57994508743286,0.15893899254126195,1739502697.324282,57.57994508743286,0.03671626782049933,1739502697.324283,57.57994508743286,2.2015013024682695,1739502697.3242843,57.57994508743286,0.0,1739502697.324286,57.57994508743286,0.05052398008440884,1739502697.3242872,57.57994508743286,3.1408703471859565,1739502697.3242886,57.57994508743286,2.1509773223838606 +1739502697.3441374,57.599945068359375,18.467269198514625,1739502697.3441398,57.599945068359375,0.16084410383332415,1739502697.3441424,57.599945068359375,94.12218639834093,1739502697.3441448,57.599945068359375,12.892476652418473,1739502697.3441463,57.599945068359375,0.006,1739502697.3441477,57.599945068359375,-3.113824032497421,1739502697.3441489,57.599945068359375,0.1535459335185706,1739502697.3441503,57.599945068359375,0.037912643836378934,1739502697.3441515,57.599945068359375,2.211020083011009,1739502697.3441532,57.599945068359375,0.0,1739502697.3441544,57.599945068359375,0.05633226714810977,1739502697.3441556,57.599945068359375,3.141825517165883,1739502697.344157,57.599945068359375,2.1565029067603723 +1739502697.3643231,57.61994504928589,18.467269198514625,1739502697.3643253,57.61994504928589,0.16084410383332415,1739502697.3643281,57.61994504928589,94.12218639834093,1739502697.364331,57.61994504928589,12.892476652418473,1739502697.3643322,57.61994504928589,0.006,1739502697.3643339,57.61994504928589,-3.113824032497421,1739502697.3643353,57.61994504928589,0.1535459335185706,1739502697.3643367,57.61994504928589,0.037912643836378934,1739502697.364338,57.61994504928589,2.211020083011009,1739502697.3643394,57.61994504928589,0.0,1739502697.3643408,57.61994504928589,0.0545171762506369,1739502697.3643422,57.61994504928589,3.141825517165883,1739502697.3643436,57.61994504928589,2.1565029067603723 +1739502697.3844004,57.6399450302124,18.467269198514625,1739502697.384403,57.6399450302124,0.16084410383332415,1739502697.3844068,57.6399450302124,94.12218639834093,1739502697.3844097,57.6399450302124,12.892476652418473,1739502697.3844109,57.6399450302124,0.006,1739502697.3844128,57.6399450302124,-3.113824032497421,1739502697.3844144,57.6399450302124,0.1535459335185706,1739502697.3844156,57.6399450302124,0.037912643836378934,1739502697.3844173,57.6399450302124,2.211020083011009,1739502697.3844187,57.6399450302124,0.0,1739502697.3844202,57.6399450302124,0.0545171762506369,1739502697.3844216,57.6399450302124,3.141825517165883,1739502697.3844235,57.6399450302124,2.1565029067603723 +1739502697.404163,57.659945011138916,18.467269198514625,1739502697.4041653,57.659945011138916,0.16084410383332415,1739502697.4041681,57.659945011138916,94.12218639834093,1739502697.404171,57.659945011138916,12.892476652418473,1739502697.4041727,57.659945011138916,0.006,1739502697.404174,57.659945011138916,-3.113824032497421,1739502697.4041753,57.659945011138916,0.1535459335185706,1739502697.4041767,57.659945011138916,0.037912643836378934,1739502697.404178,57.659945011138916,2.211020083011009,1739502697.4041796,57.659945011138916,0.0,1739502697.4041808,57.659945011138916,0.0545171762506369,1739502697.404182,57.659945011138916,3.141825517165883,1739502697.4041834,57.659945011138916,2.1565029067603723 +1739502697.4243622,57.67994499206543,18.467269198514625,1739502697.424365,57.67994499206543,0.16084410383332415,1739502697.4243689,57.67994499206543,94.12218639834093,1739502697.4243717,57.67994499206543,12.892476652418473,1739502697.424373,57.67994499206543,0.006,1739502697.4243748,57.67994499206543,-3.113824032497421,1739502697.4243762,57.67994499206543,0.1535459335185706,1739502697.4243777,57.67994499206543,0.037912643836378934,1739502697.4243789,57.67994499206543,2.211020083011009,1739502697.4243803,57.67994499206543,0.0,1739502697.424382,57.67994499206543,0.0545171762506369,1739502697.4243832,57.67994499206543,3.141825517165883,1739502697.4243848,57.67994499206543,2.1565029067603723 +1739502697.4442022,57.69994497299194,18.467269198514625,1739502697.4442046,57.69994497299194,0.16084410383332415,1739502697.4442074,57.69994497299194,94.12218639834093,1739502697.4442103,57.69994497299194,12.892476652418473,1739502697.4442115,57.69994497299194,0.006,1739502697.4442132,57.69994497299194,-3.113824032497421,1739502697.4442146,57.69994497299194,0.1535459335185706,1739502697.444216,57.69994497299194,0.037912643836378934,1739502697.4442174,57.69994497299194,2.211020083011009,1739502697.4442189,57.69994497299194,0.0,1739502697.4442198,57.69994497299194,0.0545171762506369,1739502697.4442215,57.69994497299194,3.141825517165883,1739502697.4442227,57.69994497299194,2.1565029067603723 +1739502697.46445,57.71994495391846,18.22975149754553,1739502697.4644532,57.71994495391846,0.16068561988930607,1739502697.4644566,57.71994495391846,94.5487055206979,1739502697.464459,57.71994495391846,12.453951741111077,1739502697.4644606,57.71994495391846,0.005,1739502697.4644625,57.71994495391846,-3.114644362826468,1739502697.464464,57.71994495391846,0.1488236677108165,1739502697.4644651,57.71994495391846,0.03423534326848249,1739502697.4644666,57.71994495391846,2.219388700222603,1739502697.4644682,57.71994495391846,0.0,1739502697.4644694,57.71994495391846,0.057955146919382125,1739502697.464471,57.71994495391846,3.1427806871458093,1739502697.4644725,57.71994495391846,2.1625079198416133 +1739502697.484371,57.73994493484497,18.22975149754553,1739502697.4843736,57.73994493484497,0.16068561988930607,1739502697.4843764,57.73994493484497,94.5487055206979,1739502697.4843788,57.73994493484497,12.453951741111077,1739502697.4843802,57.73994493484497,0.005,1739502697.484382,57.73994493484497,-3.114644362826468,1739502697.4843836,57.73994493484497,0.1488236677108165,1739502697.4843848,57.73994493484497,0.03423534326848249,1739502697.484386,57.73994493484497,2.219388700222603,1739502697.4843876,57.73994493484497,0.0,1739502697.4843888,57.73994493484497,0.05688078038098965,1739502697.4843903,57.73994493484497,3.1427806871458093,1739502697.4843917,57.73994493484497,2.1625079198416133 +1739502697.5043032,57.759944915771484,18.22975149754553,1739502697.5043054,57.759944915771484,0.16068561988930607,1739502697.5043082,57.759944915771484,94.5487055206979,1739502697.504311,57.759944915771484,12.453951741111077,1739502697.5043123,57.759944915771484,0.005,1739502697.5043142,57.759944915771484,-3.114644362826468,1739502697.5043154,57.759944915771484,0.1488236677108165,1739502697.504317,57.759944915771484,0.03423534326848249,1739502697.504318,57.759944915771484,2.219388700222603,1739502697.5043194,57.759944915771484,0.0,1739502697.5043209,57.759944915771484,0.05688078038098965,1739502697.504322,57.759944915771484,3.1427806871458093,1739502697.5043235,57.759944915771484,2.1625079198416133 +1739502697.5243983,57.779944896698,18.22975149754553,1739502697.5244012,57.779944896698,0.16068561988930607,1739502697.5244043,57.779944896698,94.5487055206979,1739502697.5244071,57.779944896698,12.453951741111077,1739502697.5244086,57.779944896698,0.005,1739502697.5244105,57.779944896698,-3.114644362826468,1739502697.5244117,57.779944896698,0.1488236677108165,1739502697.524413,57.779944896698,0.03423534326848249,1739502697.5244143,57.779944896698,2.219388700222603,1739502697.524416,57.779944896698,0.0,1739502697.5244172,57.779944896698,0.05688078038098965,1739502697.5244188,57.779944896698,3.1427806871458093,1739502697.5244203,57.779944896698,2.1625079198416133 +1739502697.5442863,57.79994487762451,18.22975149754553,1739502697.5442889,57.79994487762451,0.16068561988930607,1739502697.5442915,57.79994487762451,94.5487055206979,1739502697.5442946,57.79994487762451,12.453951741111077,1739502697.544296,57.79994487762451,0.005,1739502697.5442977,57.79994487762451,-3.114644362826468,1739502697.5442991,57.79994487762451,0.1488236677108165,1739502697.5443006,57.79994487762451,0.03423534326848249,1739502697.5443017,57.79994487762451,2.219388700222603,1739502697.5443034,57.79994487762451,0.0,1739502697.5443044,57.79994487762451,0.05688078038098965,1739502697.5443058,57.79994487762451,3.1427806871458093,1739502697.5443072,57.79994487762451,2.1625079198416133 +1739502697.564456,57.819944858551025,17.99156506930546,1739502697.564459,57.819944858551025,0.16029917894149115,1739502697.5644622,57.819944858551025,94.57562020064807,1739502697.564465,57.819944858551025,12.414596782833021,1739502697.564467,57.819944858551025,0.005,1739502697.5644686,57.819944858551025,-3.113753324320556,1739502697.56447,57.819944858551025,0.14334625327103384,1739502697.5644715,57.819944858551025,0.035366693811517524,1739502697.564473,57.819944858551025,2.229135248351711,1739502697.5644748,57.819944858551025,0.0,1739502697.5644763,57.819944858551025,0.06201010404080795,1739502697.5644777,57.819944858551025,3.1437358571257357,1739502697.5644794,57.819944858551025,2.168728059005549 +1739502697.5843399,57.83994483947754,17.99156506930546,1739502697.5843425,57.83994483947754,0.16029917894149115,1739502697.5843456,57.83994483947754,94.57562020064807,1739502697.5843482,57.83994483947754,12.414596782833021,1739502697.5843494,57.83994483947754,0.005,1739502697.5843513,57.83994483947754,-3.113753324320556,1739502697.5843527,57.83994483947754,0.14334625327103384,1739502697.5843542,57.83994483947754,0.035366693811517524,1739502697.584355,57.83994483947754,2.229135248351711,1739502697.5843568,57.83994483947754,0.0,1739502697.5843582,57.83994483947754,0.06040718934616196,1739502697.5843594,57.83994483947754,3.1437358571257357,1739502697.5843613,57.83994483947754,2.168728059005549 +1739502697.6042192,57.85994482040405,17.99156506930546,1739502697.6042213,57.85994482040405,0.16029917894149115,1739502697.6042244,57.85994482040405,94.57562020064807,1739502697.604227,57.85994482040405,12.414596782833021,1739502697.6042283,57.85994482040405,0.005,1739502697.60423,57.85994482040405,-3.113753324320556,1739502697.604231,57.85994482040405,0.14334625327103384,1739502697.6042328,57.85994482040405,0.035366693811517524,1739502697.6042337,57.85994482040405,2.229135248351711,1739502697.6042352,57.85994482040405,0.0,1739502697.6042366,57.85994482040405,0.06040718934616196,1739502697.604238,57.85994482040405,3.1437358571257357,1739502697.6042395,57.85994482040405,2.168728059005549 +1739502697.624346,57.879944801330566,17.99156506930546,1739502697.6243489,57.879944801330566,0.16029917894149115,1739502697.624352,57.879944801330566,94.57562020064807,1739502697.6243553,57.879944801330566,12.414596782833021,1739502697.6243567,57.879944801330566,0.005,1739502697.6243584,57.879944801330566,-3.113753324320556,1739502697.6243598,57.879944801330566,0.14334625327103384,1739502697.6243618,57.879944801330566,0.035366693811517524,1739502697.6243632,57.879944801330566,2.229135248351711,1739502697.6243653,57.879944801330566,0.0,1739502697.6243665,57.879944801330566,0.06040718934616196,1739502697.6243682,57.879944801330566,3.1437358571257357,1739502697.6243696,57.879944801330566,2.168728059005549 +1739502697.6442904,57.89994478225708,17.99156506930546,1739502697.644293,57.89994478225708,0.16029917894149115,1739502697.644296,57.89994478225708,94.57562020064807,1739502697.6442988,57.89994478225708,12.414596782833021,1739502697.6443,57.89994478225708,0.005,1739502697.644302,57.89994478225708,-3.113753324320556,1739502697.644303,57.89994478225708,0.14334625327103384,1739502697.6443043,57.89994478225708,0.035366693811517524,1739502697.6443057,57.89994478225708,2.229135248351711,1739502697.6443071,57.89994478225708,0.0,1739502697.6443088,57.89994478225708,0.06040718934616196,1739502697.6443102,57.89994478225708,3.1437358571257357,1739502697.6443117,57.89994478225708,2.168728059005549 +1739502697.6643488,57.919944763183594,17.99156506930546,1739502697.6643517,57.919944763183594,0.16029917894149115,1739502697.6643546,57.919944763183594,94.57562020064807,1739502697.6643574,57.919944763183594,12.414596782833021,1739502697.6643586,57.919944763183594,0.005,1739502697.6643605,57.919944763183594,-3.113753324320556,1739502697.6643617,57.919944763183594,0.14334625327103384,1739502697.6643631,57.919944763183594,0.035366693811517524,1739502697.6643648,57.919944763183594,2.229135248351711,1739502697.6643665,57.919944763183594,0.0,1739502697.664368,57.919944763183594,0.06040718934616196,1739502697.6643696,57.919944763183594,3.1437358571257357,1739502697.664371,57.919944763183594,2.168728059005549 +1739502697.684302,57.93994474411011,17.752671441705576,1739502697.6843045,57.93994474411011,0.15968340225137645,1739502697.6843069,57.93994474411011,95.17480758703775,1739502697.6843097,57.93994474411011,11.802129355359632,1739502697.6843114,57.93994474411011,0.002597725675291024,1739502697.6843128,57.93994474411011,-3.1152002343085816,1739502697.684314,57.93994474411011,0.1386479500653867,1739502697.6843154,57.93994474411011,0.03005000428070026,1739502697.6843166,57.93994474411011,2.2375295366604515,1739502697.6843183,57.93994474411011,0.0,1739502697.6843195,57.93994474411011,0.06295071382140714,1739502697.684321,57.93994474411011,3.144691027105662,1739502697.6843224,57.93994474411011,2.175373674758704 +1739502697.7042527,57.95994472503662,17.752671441705576,1739502697.7042549,57.95994472503662,0.15968340225137645,1739502697.704258,57.95994472503662,95.17480758703775,1739502697.7042606,57.95994472503662,11.802129355359632,1739502697.7042623,57.95994472503662,0.002597725675291024,1739502697.7042637,57.95994472503662,-3.1152002343085816,1739502697.704265,57.95994472503662,0.1386479500653867,1739502697.7042665,57.95994472503662,0.03005000428070026,1739502697.7042677,57.95994472503662,2.2375295366604515,1739502697.7042694,57.95994472503662,0.0,1739502697.7042706,57.95994472503662,0.06215586190174749,1739502697.704272,57.95994472503662,3.144691027105662,1739502697.7042737,57.95994472503662,2.175373674758704 +1739502697.7244148,57.979944705963135,17.752671441705576,1739502697.7244177,57.979944705963135,0.15968340225137645,1739502697.7244208,57.979944705963135,95.17480758703775,1739502697.7244236,57.979944705963135,11.802129355359632,1739502697.724425,57.979944705963135,0.002597725675291024,1739502697.7244267,57.979944705963135,-3.1152002343085816,1739502697.724428,57.979944705963135,0.1386479500653867,1739502697.7244296,57.979944705963135,0.03005000428070026,1739502697.7244308,57.979944705963135,2.2375295366604515,1739502697.7244327,57.979944705963135,0.0,1739502697.724434,57.979944705963135,0.06215586190174749,1739502697.7244356,57.979944705963135,3.144691027105662,1739502697.7244372,57.979944705963135,2.175373674758704 +1739502697.746394,57.99994468688965,17.752671441705576,1739502697.7463977,57.99994468688965,0.15968340225137645,1739502697.7464027,57.99994468688965,95.17480758703775,1739502697.746408,57.99994468688965,11.802129355359632,1739502697.7464108,57.99994468688965,0.002597725675291024,1739502697.7464147,57.99994468688965,-3.1152002343085816,1739502697.746418,57.99994468688965,0.1386479500653867,1739502697.7464213,57.99994468688965,0.03005000428070026,1739502697.7464247,57.99994468688965,2.2375295366604515,1739502697.7464283,57.99994468688965,0.0,1739502697.7464316,57.99994468688965,0.06215586190174749,1739502697.746435,57.99994468688965,3.144691027105662,1739502697.7464385,57.99994468688965,2.175373674758704 +1739502697.7643502,58.01994466781616,17.752671441705576,1739502697.7643528,58.01994466781616,0.15968340225137645,1739502697.764356,58.01994466781616,95.17480758703775,1739502697.7643583,58.01994466781616,11.802129355359632,1739502697.7643597,58.01994466781616,0.002597725675291024,1739502697.7643611,58.01994466781616,-3.1152002343085816,1739502697.7643626,58.01994466781616,0.1386479500653867,1739502697.7643638,58.01994466781616,0.03005000428070026,1739502697.764365,58.01994466781616,2.2375295366604515,1739502697.7643666,58.01994466781616,0.0,1739502697.7643678,58.01994466781616,0.06215586190174749,1739502697.7643695,58.01994466781616,3.144691027105662,1739502697.7643707,58.01994466781616,2.175373674758704 +1739502697.7842195,58.039944648742676,17.513041955351085,1739502697.7842216,58.039944648742676,0.15883683841653884,1739502697.7842243,58.039944648742676,95.21793920145387,1739502697.784227,58.039944648742676,11.74540464628213,1739502697.7842283,58.039944648742676,0.0021210474477489963,1739502697.78423,58.039944648742676,-3.1144277622868874,1739502697.7842312,58.039944648742676,0.13333519878003774,1739502697.7842324,58.039944648742676,0.030759155672440756,1739502697.7842338,58.039944648742676,2.2470597252603923,1739502697.7842352,58.039944648742676,0.0,1739502697.7842362,58.039944648742676,0.06613061197662486,1739502697.7842379,58.039944648742676,3.1456461970855885,1739502697.784239,58.039944648742676,2.1821712234965576 +1739502697.8041868,58.05994462966919,17.513041955351085,1739502697.8041892,58.05994462966919,0.15883683841653884,1739502697.8041918,58.05994462966919,95.21793920145387,1739502697.8041942,58.05994462966919,11.74540464628213,1739502697.804196,58.05994462966919,0.0021210474477489963,1739502697.8041973,58.05994462966919,-3.1144277622868874,1739502697.8041987,58.05994462966919,0.13333519878003774,1739502697.8042,58.05994462966919,0.030759155672440756,1739502697.8042011,58.05994462966919,2.2470597252603923,1739502697.8042026,58.05994462966919,0.0,1739502697.8042037,58.05994462966919,0.06488850176383476,1739502697.804205,58.05994462966919,3.1456461970855885,1739502697.8042064,58.05994462966919,2.1821712234965576 +1739502697.8245196,58.0799446105957,17.513041955351085,1739502697.8245227,58.0799446105957,0.15883683841653884,1739502697.824526,58.0799446105957,95.21793920145387,1739502697.824529,58.0799446105957,11.74540464628213,1739502697.8245304,58.0799446105957,0.0021210474477489963,1739502697.8245323,58.0799446105957,-3.1144277622868874,1739502697.8245335,58.0799446105957,0.13333519878003774,1739502697.8245351,58.0799446105957,0.030759155672440756,1739502697.8245363,58.0799446105957,2.2470597252603923,1739502697.8245382,58.0799446105957,0.0,1739502697.8245394,58.0799446105957,0.06488850176383476,1739502697.8245409,58.0799446105957,3.1456461970855885,1739502697.8245425,58.0799446105957,2.1821712234965576 +1739502697.8446891,58.09994459152222,17.513041955351085,1739502697.8446925,58.09994459152222,0.15883683841653884,1739502697.844696,58.09994459152222,95.21793920145387,1739502697.8446991,58.09994459152222,11.74540464628213,1739502697.8447006,58.09994459152222,0.0021210474477489963,1739502697.8447025,58.09994459152222,-3.1144277622868874,1739502697.8447042,58.09994459152222,0.13333519878003774,1739502697.8447058,58.09994459152222,0.030759155672440756,1739502697.8447073,58.09994459152222,2.2470597252603923,1739502697.8447092,58.09994459152222,0.0,1739502697.8447104,58.09994459152222,0.06488850176383476,1739502697.8447123,58.09994459152222,3.1456461970855885,1739502697.8447137,58.09994459152222,2.1821712234965576 +1739502697.8671107,58.11994457244873,17.513041955351085,1739502697.8671155,58.11994457244873,0.15883683841653884,1739502697.867121,58.11994457244873,95.21793920145387,1739502697.8671267,58.11994457244873,11.74540464628213,1739502697.86713,58.11994457244873,0.0021210474477489963,1739502697.867134,58.11994457244873,-3.1144277622868874,1739502697.8671386,58.11994457244873,0.13333519878003774,1739502697.8671424,58.11994457244873,0.030759155672440756,1739502697.8671465,58.11994457244873,2.2470597252603923,1739502697.8671505,58.11994457244873,0.0,1739502697.8671544,58.11994457244873,0.06488850176383476,1739502697.8671584,58.11994457244873,3.1456461970855885,1739502697.8671625,58.11994457244873,2.1821712234965576 +1739502697.884602,58.139944553375244,17.513041955351085,1739502697.8846052,58.139944553375244,0.15883683841653884,1739502697.8846085,58.139944553375244,95.21793920145387,1739502697.8846116,58.139944553375244,11.74540464628213,1739502697.884613,58.139944553375244,0.0021210474477489963,1739502697.8846152,58.139944553375244,-3.1144277622868874,1739502697.8846166,58.139944553375244,0.13333519878003774,1739502697.8846185,58.139944553375244,0.030759155672440756,1739502697.8846197,58.139944553375244,2.2470597252603923,1739502697.8846219,58.139944553375244,0.0,1739502697.8846233,58.139944553375244,0.06488850176383476,1739502697.884625,58.139944553375244,3.1456461970855885,1739502697.8846264,58.139944553375244,2.1821712234965576 +1739502697.9045985,58.15994453430176,17.27264731455648,1739502697.9046016,58.15994453430176,0.1577579474711639,1739502697.9046047,58.15994453430176,95.261208079015,1739502697.9046078,58.15994453430176,11.68787977050024,1739502697.9046092,58.15994453430176,0.001637645130254119,1739502697.9046113,58.15994453430176,-3.113645267643962,1739502697.9046128,58.15994453430176,0.12814596053538105,1739502697.9046144,58.15994453430176,0.0315283103231483,1739502697.9046159,58.15994453430176,2.256407537657062,1739502697.9046178,58.15994453430176,0.0,1739502697.904619,58.15994453430176,0.06811584491202732,1739502697.904621,58.15994453430176,3.146601367065515,1739502697.9046226,58.15994453430176,2.1893002381400986 +1739502697.9268508,58.17994451522827,17.27264731455648,1739502697.9268546,58.17994451522827,0.1577579474711639,1739502697.9268596,58.17994451522827,95.261208079015,1739502697.9268649,58.17994451522827,11.68787977050024,1739502697.926868,58.17994451522827,0.001637645130254119,1739502697.9268718,58.17994451522827,-3.113645267643962,1739502697.9268754,58.17994451522827,0.12814596053538105,1739502697.9268787,58.17994451522827,0.0315283103231483,1739502697.9268823,58.17994451522827,2.256407537657062,1739502697.9268858,58.17994451522827,0.0,1739502697.9268894,58.17994451522827,0.06710729951696326,1739502697.926893,58.17994451522827,3.146601367065515,1739502697.9268963,58.17994451522827,2.1893002381400986 +1739502697.9443815,58.199944496154785,17.27264731455648,1739502697.944384,58.199944496154785,0.1577579474711639,1739502697.944388,58.199944496154785,95.261208079015,1739502697.944391,58.199944496154785,11.68787977050024,1739502697.9443922,58.199944496154785,0.001637645130254119,1739502697.9443939,58.199944496154785,-3.113645267643962,1739502697.9443955,58.199944496154785,0.12814596053538105,1739502697.9443967,58.199944496154785,0.0315283103231483,1739502697.9443982,58.199944496154785,2.256407537657062,1739502697.9443996,58.199944496154785,0.0,1739502697.9444013,58.199944496154785,0.06710729951696326,1739502697.9444025,58.199944496154785,3.146601367065515,1739502697.9444036,58.199944496154785,2.1893002381400986 +1739502697.964226,58.2199444770813,17.27264731455648,1739502697.9642284,58.2199444770813,0.1577579474711639,1739502697.9642315,58.2199444770813,95.261208079015,1739502697.9642339,58.2199444770813,11.68787977050024,1739502697.964235,58.2199444770813,0.001637645130254119,1739502697.9642367,58.2199444770813,-3.113645267643962,1739502697.9642382,58.2199444770813,0.12814596053538105,1739502697.9642394,58.2199444770813,0.0315283103231483,1739502697.9642403,58.2199444770813,2.256407537657062,1739502697.9642422,58.2199444770813,0.0,1739502697.9642432,58.2199444770813,0.06710729951696326,1739502697.9642444,58.2199444770813,3.146601367065515,1739502697.9642458,58.2199444770813,2.1893002381400986 +1739502697.984219,58.23994445800781,17.27264731455648,1739502697.9842217,58.23994445800781,0.1577579474711639,1739502697.9842246,58.23994445800781,95.261208079015,1739502697.9842272,58.23994445800781,11.68787977050024,1739502697.9842284,58.23994445800781,0.001637645130254119,1739502697.9842305,58.23994445800781,-3.113645267643962,1739502697.9842317,58.23994445800781,0.12814596053538105,1739502697.9842331,58.23994445800781,0.0315283103231483,1739502697.9842343,58.23994445800781,2.256407537657062,1739502697.9842358,58.23994445800781,0.0,1739502697.984237,58.23994445800781,0.06710729951696326,1739502697.9842386,58.23994445800781,3.146601367065515,1739502697.9842398,58.23994445800781,2.1893002381400986 +1739502698.0043323,58.259944438934326,17.03146098340464,1739502698.0043347,58.259944438934326,0.15644512196260596,1739502698.004337,58.259944438934326,95.77222192140539,1739502698.00434,58.259944438934326,11.162200595001085,1739502698.0043414,58.259944438934326,-0.001,1739502698.0043428,58.259944438934326,-3.1147737084480664,1739502698.004344,58.259944438934326,0.1224389445473073,1739502698.0043457,58.259944438934326,0.027276564432544823,1739502698.0043466,58.259944438934326,2.266732973807172,1739502698.0043483,58.259944438934326,0.0,1739502698.0043495,58.259944438934326,0.07145167496965411,1739502698.0043507,58.259944438934326,3.1475565370454412,1739502698.0043523,58.259944438934326,2.1966389170566076 +1739502698.024312,58.27994441986084,17.03146098340464,1739502698.0243146,58.27994441986084,0.15644512196260596,1739502698.0243187,58.27994441986084,95.77222192140539,1739502698.0243218,58.27994441986084,11.162200595001085,1739502698.0243232,58.27994441986084,-0.001,1739502698.024325,58.27994441986084,-3.1147737084480664,1739502698.0243263,58.27994441986084,0.1224389445473073,1739502698.024328,58.27994441986084,0.027276564432544823,1739502698.024329,58.27994441986084,2.266732973807172,1739502698.0243304,58.27994441986084,0.0,1739502698.0243318,58.27994441986084,0.07009405675056435,1739502698.024333,58.27994441986084,3.1475565370454412,1739502698.0243344,58.27994441986084,2.1966389170566076 +1739502698.0443416,58.29994440078735,17.03146098340464,1739502698.044344,58.29994440078735,0.15644512196260596,1739502698.044347,58.29994440078735,95.77222192140539,1739502698.04435,58.29994440078735,11.162200595001085,1739502698.0443516,58.29994440078735,-0.001,1739502698.0443532,58.29994440078735,-3.1147737084480664,1739502698.044355,58.29994440078735,0.1224389445473073,1739502698.0443563,58.29994440078735,0.027276564432544823,1739502698.0443575,58.29994440078735,2.266732973807172,1739502698.0443594,58.29994440078735,0.0,1739502698.0443606,58.29994440078735,0.07009405675056435,1739502698.0443623,58.29994440078735,3.1475565370454412,1739502698.0443635,58.29994440078735,2.1966389170566076 +1739502698.0642385,58.31994438171387,17.03146098340464,1739502698.064241,58.31994438171387,0.15644512196260596,1739502698.064244,58.31994438171387,95.77222192140539,1739502698.0642464,58.31994438171387,11.162200595001085,1739502698.0642478,58.31994438171387,-0.001,1739502698.0642493,58.31994438171387,-3.1147737084480664,1739502698.0642505,58.31994438171387,0.1224389445473073,1739502698.064252,58.31994438171387,0.027276564432544823,1739502698.0642529,58.31994438171387,2.266732973807172,1739502698.0642545,58.31994438171387,0.0,1739502698.0642557,58.31994438171387,0.07009405675056435,1739502698.0642567,58.31994438171387,3.1475565370454412,1739502698.064258,58.31994438171387,2.1966389170566076 +1739502698.0841846,58.33994436264038,17.03146098340464,1739502698.084187,58.33994436264038,0.15644512196260596,1739502698.08419,58.33994436264038,95.77222192140539,1739502698.0841925,58.33994436264038,11.162200595001085,1739502698.0841937,58.33994436264038,-0.001,1739502698.0841954,58.33994436264038,-3.1147737084480664,1739502698.0841968,58.33994436264038,0.1224389445473073,1739502698.0841982,58.33994436264038,0.027276564432544823,1739502698.0841992,58.33994436264038,2.266732973807172,1739502698.0842009,58.33994436264038,0.0,1739502698.084202,58.33994436264038,0.07009405675056435,1739502698.0842032,58.33994436264038,3.1475565370454412,1739502698.0842044,58.33994436264038,2.1966389170566076 +1739502698.10419,58.359944343566895,17.03146098340464,1739502698.1041925,58.359944343566895,0.15644512196260596,1739502698.1041949,58.359944343566895,95.77222192140539,1739502698.1041973,58.359944343566895,11.162200595001085,1739502698.1041987,58.359944343566895,-0.001,1739502698.1042001,58.359944343566895,-3.1147737084480664,1739502698.1042016,58.359944343566895,0.1224389445473073,1739502698.1042027,58.359944343566895,0.027276564432544823,1739502698.1042037,58.359944343566895,2.266732973807172,1739502698.1042056,58.359944343566895,0.0,1739502698.1042068,58.359944343566895,0.07009405675056435,1739502698.1042082,58.359944343566895,3.1475565370454412,1739502698.1042094,58.359944343566895,2.1966389170566076 +1739502698.124312,58.37994432449341,16.78944866383005,1739502698.1243143,58.37994432449341,0.1548966266854368,1739502698.1243176,58.37994432449341,95.7942434939914,1739502698.1243203,58.37994432449341,11.124777628712337,1739502698.1243217,58.37994432449341,-0.0012463102887249181,1739502698.1243236,58.37994432449341,-3.1140352881953084,1739502698.1243248,58.37994432449341,0.11694535058817138,1739502698.1243265,58.37994432449341,0.02796741725333051,1739502698.1243274,58.37994432449341,2.276716905260982,1739502698.1243289,58.37994432449341,0.0,1739502698.12433,58.37994432449341,0.07341449991512795,1739502698.1243312,58.37994432449341,3.1485117070253676,1739502698.1243324,58.37994432449341,2.2043400445151096 +1739502698.1443813,58.39994430541992,16.78944866383005,1739502698.1443837,58.39994430541992,0.1548966266854368,1739502698.1443868,58.39994430541992,95.7942434939914,1739502698.1443894,58.39994430541992,11.124777628712337,1739502698.1443908,58.39994430541992,-0.0012463102887249181,1739502698.1443925,58.39994430541992,-3.1140352881953084,1739502698.144394,58.39994430541992,0.11694535058817138,1739502698.1443956,58.39994430541992,0.02796741725333051,1739502698.1443968,58.39994430541992,2.276716905260982,1739502698.1443985,58.39994430541992,0.0,1739502698.1443996,58.39994430541992,0.07237686074587257,1739502698.144401,58.39994430541992,3.1485117070253676,1739502698.1444027,58.39994430541992,2.2043400445151096 +1739502698.1643026,58.419944286346436,16.78944866383005,1739502698.1643054,58.419944286346436,0.1548966266854368,1739502698.1643085,58.419944286346436,95.7942434939914,1739502698.1643114,58.419944286346436,11.124777628712337,1739502698.1643124,58.419944286346436,-0.0012463102887249181,1739502698.1643143,58.419944286346436,-3.1140352881953084,1739502698.164316,58.419944286346436,0.11694535058817138,1739502698.1643171,58.419944286346436,0.02796741725333051,1739502698.1643186,58.419944286346436,2.276716905260982,1739502698.16432,58.419944286346436,0.0,1739502698.1643212,58.419944286346436,0.07237686074587257,1739502698.1643229,58.419944286346436,3.1485117070253676,1739502698.164324,58.419944286346436,2.2043400445151096 +1739502698.1843185,58.43994426727295,16.78944866383005,1739502698.184321,58.43994426727295,0.1548966266854368,1739502698.184324,58.43994426727295,95.7942434939914,1739502698.184327,58.43994426727295,11.124777628712337,1739502698.184328,58.43994426727295,-0.0012463102887249181,1739502698.1843297,58.43994426727295,-3.1140352881953084,1739502698.1843312,58.43994426727295,0.11694535058817138,1739502698.1843326,58.43994426727295,0.02796741725333051,1739502698.1843338,58.43994426727295,2.276716905260982,1739502698.1843355,58.43994426727295,0.0,1739502698.1843367,58.43994426727295,0.07237686074587257,1739502698.184338,58.43994426727295,3.1485117070253676,1739502698.1843395,58.43994426727295,2.2043400445151096 +1739502698.204331,58.45994424819946,16.78944866383005,1739502698.2043335,58.45994424819946,0.1548966266854368,1739502698.2043364,58.45994424819946,95.7942434939914,1739502698.204339,58.45994424819946,11.124777628712337,1739502698.2043405,58.45994424819946,-0.0012463102887249181,1739502698.2043421,58.45994424819946,-3.1140352881953084,1739502698.2043433,58.45994424819946,0.11694535058817138,1739502698.2043447,58.45994424819946,0.02796741725333051,1739502698.2043462,58.45994424819946,2.276716905260982,1739502698.2043476,58.45994424819946,0.0,1739502698.2043486,58.45994424819946,0.07237686074587257,1739502698.2043502,58.45994424819946,3.1485117070253676,1739502698.2043514,58.45994424819946,2.2043400445151096 +1739502698.2243848,58.47994422912598,16.546582120143828,1739502698.2243876,58.47994422912598,0.15311067407925005,1739502698.2243912,58.47994422912598,96.13946426573212,1739502698.2243938,58.47994422912598,10.763738587669343,1739502698.2243953,58.47994422912598,-0.00411984380109797,1739502698.2243967,58.47994422912598,-3.114410214708233,1739502698.2243984,58.47994422912598,0.1116907120978291,1739502698.2243998,58.47994422912598,0.02563090236230953,1739502698.224401,58.47994422912598,2.286307709045867,1739502698.2244024,58.47994422912598,0.0,1739502698.2244039,58.47994422912598,0.07481455695140087,1739502698.2244055,58.47994422912598,3.149466877005294,1739502698.2244067,58.47994422912598,2.212254932658156 +1739502698.2443147,58.49994421005249,16.546582120143828,1739502698.2443173,58.49994421005249,0.15311067407925005,1739502698.24432,58.49994421005249,96.13946426573212,1739502698.2443228,58.49994421005249,10.763738587669343,1739502698.2443244,58.49994421005249,-0.00411984380109797,1739502698.2443259,58.49994421005249,-3.114410214708233,1739502698.2443273,58.49994421005249,0.1116907120978291,1739502698.244329,58.49994421005249,0.02563090236230953,1739502698.24433,58.49994421005249,2.286307709045867,1739502698.2443318,58.49994421005249,0.0,1739502698.244333,58.49994421005249,0.07405277638771102,1739502698.2443347,58.49994421005249,3.149466877005294,1739502698.244336,58.49994421005249,2.212254932658156 +1739502698.2662177,58.519944190979004,16.546582120143828,1739502698.266221,58.519944190979004,0.15311067407925005,1739502698.2662256,58.519944190979004,96.13946426573212,1739502698.2662308,58.519944190979004,10.763738587669343,1739502698.2662334,58.519944190979004,-0.00411984380109797,1739502698.266237,58.519944190979004,-3.114410214708233,1739502698.2662404,58.519944190979004,0.1116907120978291,1739502698.2662432,58.519944190979004,0.02563090236230953,1739502698.2662466,58.519944190979004,2.286307709045867,1739502698.26625,58.519944190979004,0.0,1739502698.266253,58.519944190979004,0.07405277638771102,1739502698.2662563,58.519944190979004,3.149466877005294,1739502698.2662597,58.519944190979004,2.212254932658156 +1739502698.2842047,58.53994417190552,16.546582120143828,1739502698.2842073,58.53994417190552,0.15311067407925005,1739502698.28421,58.53994417190552,96.13946426573212,1739502698.2842126,58.53994417190552,10.763738587669343,1739502698.2842135,58.53994417190552,-0.00411984380109797,1739502698.2842155,58.53994417190552,-3.114410214708233,1739502698.284217,58.53994417190552,0.1116907120978291,1739502698.284218,58.53994417190552,0.02563090236230953,1739502698.2842195,58.53994417190552,2.286307709045867,1739502698.284221,58.53994417190552,0.0,1739502698.2842221,58.53994417190552,0.07405277638771102,1739502698.2842233,58.53994417190552,3.149466877005294,1739502698.2842247,58.53994417190552,2.212254932658156 +1739502698.3041973,58.55994415283203,16.546582120143828,1739502698.3041997,58.55994415283203,0.15311067407925005,1739502698.3042023,58.55994415283203,96.13946426573212,1739502698.3042054,58.55994415283203,10.763738587669343,1739502698.3042066,58.55994415283203,-0.00411984380109797,1739502698.304208,58.55994415283203,-3.114410214708233,1739502698.3042097,58.55994415283203,0.1116907120978291,1739502698.304211,58.55994415283203,0.02563090236230953,1739502698.3042119,58.55994415283203,2.286307709045867,1739502698.3042135,58.55994415283203,0.0,1739502698.304215,58.55994415283203,0.07405277638771102,1739502698.3042164,58.55994415283203,3.149466877005294,1739502698.3042176,58.55994415283203,2.212254932658156 +1739502698.324376,58.579944133758545,16.546582120143828,1739502698.3243787,58.579944133758545,0.15311067407925005,1739502698.3243816,58.579944133758545,96.13946426573212,1739502698.3243845,58.579944133758545,10.763738587669343,1739502698.324386,58.579944133758545,-0.00411984380109797,1739502698.3243876,58.579944133758545,-3.114410214708233,1739502698.3243897,58.579944133758545,0.1116907120978291,1739502698.324391,58.579944133758545,0.02563090236230953,1739502698.324392,58.579944133758545,2.286307709045867,1739502698.3243937,58.579944133758545,0.0,1739502698.324395,58.579944133758545,0.07405277638771102,1739502698.324397,58.579944133758545,3.149466877005294,1739502698.3243983,58.579944133758545,2.212254932658156 +1739502698.344467,58.59994411468506,16.30283491841427,1739502698.3444695,58.59994411468506,0.1510854097519152,1739502698.3444724,58.59994411468506,96.68887458366592,1739502698.344475,58.59994411468506,10.198100285184454,1739502698.3444765,58.59994411468506,-0.008379810867678618,1739502698.3444781,58.59994411468506,-3.1154770277007335,1739502698.3444796,58.59994411468506,0.10555860153468892,1739502698.344481,58.59994411468506,0.02173789229950718,1739502698.3444824,58.59994411468506,2.2975511782985167,1739502698.3444836,58.59994411468506,0.0,1739502698.3444848,58.59994411468506,0.07859221329639225,1739502698.3444865,58.59994411468506,3.1504220469852204,1739502698.3444877,58.59994411468506,2.2203775399661776 +1739502698.3644028,58.61994409561157,16.30283491841427,1739502698.3644052,58.61994409561157,0.1510854097519152,1739502698.364408,58.61994409561157,96.68887458366592,1739502698.3644109,58.61994409561157,10.198100285184454,1739502698.364412,58.61994409561157,-0.008379810867678618,1739502698.364414,58.61994409561157,-3.1154770277007335,1739502698.3644154,58.61994409561157,0.10555860153468892,1739502698.3644168,58.61994409561157,0.02173789229950718,1739502698.364418,58.61994409561157,2.2975511782985167,1739502698.3644197,58.61994409561157,0.0,1739502698.364421,58.61994409561157,0.07717363833233915,1739502698.364422,58.61994409561157,3.1504220469852204,1739502698.3644238,58.61994409561157,2.2203775399661776 +1739502698.3842106,58.639944076538086,16.30283491841427,1739502698.3842127,58.639944076538086,0.1510854097519152,1739502698.3842156,58.639944076538086,96.68887458366592,1739502698.3842185,58.639944076538086,10.198100285184454,1739502698.3842196,58.639944076538086,-0.008379810867678618,1739502698.384221,58.639944076538086,-3.1154770277007335,1739502698.3842227,58.639944076538086,0.10555860153468892,1739502698.384224,58.639944076538086,0.02173789229950718,1739502698.3842254,58.639944076538086,2.2975511782985167,1739502698.3842268,58.639944076538086,0.0,1739502698.384228,58.639944076538086,0.07717363833233915,1739502698.3842294,58.639944076538086,3.1504220469852204,1739502698.3842306,58.639944076538086,2.2203775399661776 +1739502698.404196,58.6599440574646,16.30283491841427,1739502698.4041984,58.6599440574646,0.1510854097519152,1739502698.4042013,58.6599440574646,96.68887458366592,1739502698.4042041,58.6599440574646,10.198100285184454,1739502698.4042053,58.6599440574646,-0.008379810867678618,1739502698.4042068,58.6599440574646,-3.1154770277007335,1739502698.4042084,58.6599440574646,0.10555860153468892,1739502698.4042099,58.6599440574646,0.02173789229950718,1739502698.4042113,58.6599440574646,2.2975511782985167,1739502698.4042125,58.6599440574646,0.0,1739502698.4042137,58.6599440574646,0.07717363833233915,1739502698.4042153,58.6599440574646,3.1504220469852204,1739502698.4042165,58.6599440574646,2.2203775399661776 +1739502698.4244032,58.67994403839111,16.30283491841427,1739502698.424406,58.67994403839111,0.1510854097519152,1739502698.4244096,58.67994403839111,96.68887458366592,1739502698.4244125,58.67994403839111,10.198100285184454,1739502698.424414,58.67994403839111,-0.008379810867678618,1739502698.4244163,58.67994403839111,-3.1154770277007335,1739502698.4244177,58.67994403839111,0.10555860153468892,1739502698.4244192,58.67994403839111,0.02173789229950718,1739502698.4244204,58.67994403839111,2.2975511782985167,1739502698.424422,58.67994403839111,0.0,1739502698.4244237,58.67994403839111,0.07717363833233915,1739502698.4244251,58.67994403839111,3.1504220469852204,1739502698.4244268,58.67994403839111,2.2203775399661776 +1739502698.4442549,58.69994401931763,16.05818210946566,1739502698.4442575,58.69994401931763,0.1488189150674799,1739502698.4442604,58.69994401931763,97.12015342946545,1739502698.4442635,58.69994401931763,9.749948252229741,1739502698.4442647,58.69994401931763,-0.009678404642120835,1739502698.4442666,58.69994401931763,-3.1164724720332737,1739502698.4442677,58.69994401931763,0.09676740359434742,1739502698.444269,58.69994401931763,0.018663584471521583,1739502698.4442704,58.69994401931763,2.313766714805801,1739502698.4442718,58.69994401931763,0.0,1739502698.4442732,58.69994401931763,0.088485318416231,1739502698.4442744,58.69994401931763,3.151377216965147,1739502698.4442759,58.69994401931763,2.2288162987334488 +1739502698.4643955,58.71994400024414,16.05818210946566,1739502698.4643981,58.71994400024414,0.1488189150674799,1739502698.4644012,58.71994400024414,97.12015342946545,1739502698.4644036,58.71994400024414,9.749948252229741,1739502698.4644053,58.71994400024414,-0.009678404642120835,1739502698.464407,58.71994400024414,-3.1164724720332737,1739502698.4644084,58.71994400024414,0.09676740359434742,1739502698.4644098,58.71994400024414,0.018663584471521583,1739502698.4644108,58.71994400024414,2.313766714805801,1739502698.4644125,58.71994400024414,0.0,1739502698.4644136,58.71994400024414,0.08495041607235221,1739502698.4644153,58.71994400024414,3.151377216965147,1739502698.4644167,58.71994400024414,2.2288162987334488 +1739502698.484395,58.739943981170654,16.05818210946566,1739502698.484398,58.739943981170654,0.1488189150674799,1739502698.484401,58.739943981170654,97.12015342946545,1739502698.484404,58.739943981170654,9.749948252229741,1739502698.4844055,58.739943981170654,-0.009678404642120835,1739502698.4844072,58.739943981170654,-3.1164724720332737,1739502698.4844086,58.739943981170654,0.09676740359434742,1739502698.48441,58.739943981170654,0.018663584471521583,1739502698.4844115,58.739943981170654,2.313766714805801,1739502698.4844131,58.739943981170654,0.0,1739502698.4844146,58.739943981170654,0.08495041607235221,1739502698.484416,58.739943981170654,3.151377216965147,1739502698.4844177,58.739943981170654,2.2288162987334488 +1739502698.5043302,58.75994396209717,16.05818210946566,1739502698.5043325,58.75994396209717,0.1488189150674799,1739502698.5043354,58.75994396209717,97.12015342946545,1739502698.5043383,58.75994396209717,9.749948252229741,1739502698.5043395,58.75994396209717,-0.009678404642120835,1739502698.504341,58.75994396209717,-3.1164724720332737,1739502698.5043426,58.75994396209717,0.09676740359434742,1739502698.5043437,58.75994396209717,0.018663584471521583,1739502698.5043452,58.75994396209717,2.313766714805801,1739502698.5043466,58.75994396209717,0.0,1739502698.5043478,58.75994396209717,0.08495041607235221,1739502698.5043492,58.75994396209717,3.151377216965147,1739502698.5043507,58.75994396209717,2.2288162987334488 +1739502698.5261211,58.77994394302368,16.05818210946566,1739502698.5261245,58.77994394302368,0.1488189150674799,1739502698.5261292,58.77994394302368,97.12015342946545,1739502698.526134,58.77994394302368,9.749948252229741,1739502698.526137,58.77994394302368,-0.009678404642120835,1739502698.5261407,58.77994394302368,-3.1164724720332737,1739502698.526144,58.77994394302368,0.09676740359434742,1739502698.5261474,58.77994394302368,0.018663584471521583,1739502698.5261507,58.77994394302368,2.313766714805801,1739502698.526154,58.77994394302368,0.0,1739502698.5261574,58.77994394302368,0.08495041607235221,1739502698.5261607,58.77994394302368,3.151377216965147,1739502698.526164,58.77994394302368,2.2288162987334488 +1739502698.5442064,58.799943923950195,16.05818210946566,1739502698.5442085,58.799943923950195,0.1488189150674799,1739502698.5442114,58.799943923950195,97.12015342946545,1739502698.5442142,58.799943923950195,9.749948252229741,1739502698.5442154,58.799943923950195,-0.009678404642120835,1739502698.544217,58.799943923950195,-3.1164724720332737,1739502698.5442185,58.799943923950195,0.09676740359434742,1739502698.54422,58.799943923950195,0.018663584471521583,1739502698.5442212,58.799943923950195,2.313766714805801,1739502698.5442228,58.799943923950195,0.0,1739502698.544224,58.799943923950195,0.08495041607235221,1739502698.5442252,58.799943923950195,3.151377216965147,1739502698.5442266,58.799943923950195,2.2288162987334488 +1739502698.5684733,58.81994390487671,15.81255255905506,1739502698.5684795,58.81994390487671,0.14630872403483242,1739502698.5684867,58.81994390487671,97.13169550814371,1739502698.5684938,58.81994390487671,9.719666222008174,1739502698.5684974,58.81994390487671,-0.009935032016879874,1739502698.5685015,58.81994390487671,-3.115954636976303,1739502698.5685048,58.81994390487671,0.09080002870143285,1739502698.5685081,58.81994390487671,0.018771971592297477,1739502698.5685115,58.81994390487671,2.324838813043948,1739502698.568515,58.81994390487671,0.0,1739502698.5685184,58.81994390487671,0.08742544048151213,1739502698.568522,58.81994390487671,3.1523323869450732,1739502698.5685256,58.81994390487671,2.2381868181974087 +1739502698.589031,58.83994388580322,15.81255255905506,1739502698.5890338,58.83994388580322,0.14630872403483242,1739502698.5890374,58.83994388580322,97.13169550814371,1739502698.589041,58.83994388580322,9.719666222008174,1739502698.589043,58.83994388580322,-0.009935032016879874,1739502698.589045,58.83994388580322,-3.115954636976303,1739502698.5890467,58.83994388580322,0.09080002870143285,1739502698.5890486,58.83994388580322,0.018771971592297477,1739502698.58905,58.83994388580322,2.324838813043948,1739502698.5890522,58.83994388580322,0.0,1739502698.5890539,58.83994388580322,0.08665199484653918,1739502698.5890558,58.83994388580322,3.1523323869450732,1739502698.5890577,58.83994388580322,2.2381868181974087 +1739502698.604338,58.859943866729736,15.81255255905506,1739502698.6043406,58.859943866729736,0.14630872403483242,1739502698.6043434,58.859943866729736,97.13169550814371,1739502698.6043458,58.859943866729736,9.719666222008174,1739502698.6043472,58.859943866729736,-0.009935032016879874,1739502698.6043487,58.859943866729736,-3.115954636976303,1739502698.6043499,58.859943866729736,0.09080002870143285,1739502698.6043513,58.859943866729736,0.018771971592297477,1739502698.6043525,58.859943866729736,2.324838813043948,1739502698.6043541,58.859943866729736,0.0,1739502698.6043553,58.859943866729736,0.08665199484653918,1739502698.6043565,58.859943866729736,3.1523323869450732,1739502698.604358,58.859943866729736,2.2381868181974087 +1739502698.625616,58.87994384765625,15.81255255905506,1739502698.6256185,58.87994384765625,0.14630872403483242,1739502698.6256213,58.87994384765625,97.13169550814371,1739502698.6256237,58.87994384765625,9.719666222008174,1739502698.6256251,58.87994384765625,-0.009935032016879874,1739502698.6256268,58.87994384765625,-3.115954636976303,1739502698.6256282,58.87994384765625,0.09080002870143285,1739502698.6256294,58.87994384765625,0.018771971592297477,1739502698.6256304,58.87994384765625,2.324838813043948,1739502698.6256323,58.87994384765625,0.0,1739502698.6256332,58.87994384765625,0.08665199484653918,1739502698.625635,58.87994384765625,3.1523323869450732,1739502698.625636,58.87994384765625,2.2381868181974087 +1739502698.6442542,58.899943828582764,15.81255255905506,1739502698.644257,58.899943828582764,0.14630872403483242,1739502698.64426,58.899943828582764,97.13169550814371,1739502698.6442626,58.899943828582764,9.719666222008174,1739502698.644264,58.899943828582764,-0.009935032016879874,1739502698.6442657,58.899943828582764,-3.115954636976303,1739502698.644267,58.899943828582764,0.09080002870143285,1739502698.6442683,58.899943828582764,0.018771971592297477,1739502698.6442695,58.899943828582764,2.324838813043948,1739502698.6442711,58.899943828582764,0.0,1739502698.6442726,58.899943828582764,0.08665199484653918,1739502698.644274,58.899943828582764,3.1523323869450732,1739502698.6442754,58.899943828582764,2.2381868181974087 +1739502698.6644115,58.91994380950928,15.56589345298601,1739502698.6644142,58.91994380950928,0.1435523823098519,1739502698.6644175,58.91994380950928,97.14328572978724,1739502698.6644204,58.91994380950928,9.689123559403365,1739502698.6644218,58.91994380950928,-0.01,1739502698.6644235,58.91994380950928,-3.1154698930388767,1739502698.664425,58.91994380950928,0.08481519252113719,1739502698.6644266,58.91994380950928,0.018847571103134994,1739502698.6644278,58.91994380950928,2.3359965261165776,1739502698.6644294,58.91994380950928,0.0,1739502698.6644306,58.91994380950928,0.0890976027760208,1739502698.6644318,58.91994380950928,3.1532875569249996,1739502698.664434,58.91994380950928,2.247663176319603 +1739502698.684191,58.93994379043579,15.56589345298601,1739502698.6841931,58.93994379043579,0.1435523823098519,1739502698.6841958,58.93994379043579,97.14328572978724,1739502698.6841984,58.93994379043579,9.689123559403365,1739502698.6842,58.93994379043579,-0.01,1739502698.6842015,58.93994379043579,-3.1154698930388767,1739502698.6842027,58.93994379043579,0.08481519252113719,1739502698.684204,58.93994379043579,0.018847571103134994,1739502698.6842053,58.93994379043579,2.3359965261165776,1739502698.684207,58.93994379043579,0.0,1739502698.6842082,58.93994379043579,0.08833334979697449,1739502698.6842093,58.93994379043579,3.1532875569249996,1739502698.684211,58.93994379043579,2.247663176319603 +1739502698.7041903,58.959943771362305,15.56589345298601,1739502698.7041924,58.959943771362305,0.1435523823098519,1739502698.7041953,58.959943771362305,97.14328572978724,1739502698.7041981,58.959943771362305,9.689123559403365,1739502698.7041993,58.959943771362305,-0.01,1739502698.7042012,58.959943771362305,-3.1154698930388767,1739502698.7042024,58.959943771362305,0.08481519252113719,1739502698.704204,58.959943771362305,0.018847571103134994,1739502698.704205,58.959943771362305,2.3359965261165776,1739502698.7042067,58.959943771362305,0.0,1739502698.704208,58.959943771362305,0.08833334979697449,1739502698.704209,58.959943771362305,3.1532875569249996,1739502698.7042108,58.959943771362305,2.247663176319603 +1739502698.7243228,58.97994375228882,15.56589345298601,1739502698.724326,58.97994375228882,0.1435523823098519,1739502698.7243295,58.97994375228882,97.14328572978724,1739502698.7243326,58.97994375228882,9.689123559403365,1739502698.7243338,58.97994375228882,-0.01,1739502698.7243357,58.97994375228882,-3.1154698930388767,1739502698.7243369,58.97994375228882,0.08481519252113719,1739502698.7243385,58.97994375228882,0.018847571103134994,1739502698.7243397,58.97994375228882,2.3359965261165776,1739502698.7243412,58.97994375228882,0.0,1739502698.7243426,58.97994375228882,0.08833334979697449,1739502698.724344,58.97994375228882,3.1532875569249996,1739502698.7243454,58.97994375228882,2.247663176319603 +1739502698.746029,58.99994373321533,15.56589345298601,1739502698.7460322,58.99994373321533,0.1435523823098519,1739502698.7460365,58.99994373321533,97.14328572978724,1739502698.7460415,58.99994373321533,9.689123559403365,1739502698.7460442,58.99994373321533,-0.01,1739502698.7460477,58.99994373321533,-3.1154698930388767,1739502698.746051,58.99994373321533,0.08481519252113719,1739502698.7460544,58.99994373321533,0.018847571103134994,1739502698.7460575,58.99994373321533,2.3359965261165776,1739502698.7460608,58.99994373321533,0.0,1739502698.7460642,58.99994373321533,0.08833334979697449,1739502698.7460675,58.99994373321533,3.1532875569249996,1739502698.746071,58.99994373321533,2.247663176319603 +1739502698.7643933,59.019943714141846,15.56589345298601,1739502698.7643957,59.019943714141846,0.1435523823098519,1739502698.7643988,59.019943714141846,97.14328572978724,1739502698.7644017,59.019943714141846,9.689123559403365,1739502698.7644029,59.019943714141846,-0.01,1739502698.7644048,59.019943714141846,-3.1154698930388767,1739502698.764406,59.019943714141846,0.08481519252113719,1739502698.7644076,59.019943714141846,0.018847571103134994,1739502698.7644086,59.019943714141846,2.3359965261165776,1739502698.76441,59.019943714141846,0.0,1739502698.7644117,59.019943714141846,0.08833334979697449,1739502698.7644129,59.019943714141846,3.1532875569249996,1739502698.7644145,59.019943714141846,2.247663176319603 +1739502698.784257,59.03994369506836,15.318182838286564,1739502698.7842593,59.03994369506836,0.14054765109588896,1739502698.7842622,59.03994369506836,97.1549251239469,1739502698.7842648,59.03994369506836,9.658112593293462,1739502698.784266,59.03994369506836,-0.01,1739502698.7842674,59.03994369506836,-3.115000728525754,1739502698.7842693,59.03994369506836,0.07893721165996737,1739502698.7842705,59.03994369506836,0.01890977966858178,1739502698.7842717,59.03994369506836,2.3470071482154964,1739502698.7842731,59.03994369506836,0.0,1739502698.784274,59.03994369506836,0.09026038473315898,1739502698.7842758,59.03994369506836,3.154242726904926,1739502698.784277,59.03994369506836,2.2573489622947274 +1739502698.8041742,59.05994367599487,15.318182838286564,1739502698.804176,59.05994367599487,0.14054765109588896,1739502698.8041787,59.05994367599487,97.1549251239469,1739502698.8041816,59.05994367599487,9.658112593293462,1739502698.8041828,59.05994367599487,-0.01,1739502698.8041844,59.05994367599487,-3.115000728525754,1739502698.8041856,59.05994367599487,0.07893721165996737,1739502698.8041873,59.05994367599487,0.01890977966858178,1739502698.8041885,59.05994367599487,2.3470071482154964,1739502698.80419,59.05994367599487,0.0,1739502698.8041909,59.05994367599487,0.08965818592076902,1739502698.8041925,59.05994367599487,3.154242726904926,1739502698.8041937,59.05994367599487,2.2573489622947274 +1739502698.824353,59.07994365692139,15.318182838286564,1739502698.8243563,59.07994365692139,0.14054765109588896,1739502698.8243597,59.07994365692139,97.1549251239469,1739502698.8243625,59.07994365692139,9.658112593293462,1739502698.8243642,59.07994365692139,-0.01,1739502698.8243663,59.07994365692139,-3.115000728525754,1739502698.8243678,59.07994365692139,0.07893721165996737,1739502698.8243692,59.07994365692139,0.01890977966858178,1739502698.8243709,59.07994365692139,2.3470071482154964,1739502698.8243728,59.07994365692139,0.0,1739502698.824374,59.07994365692139,0.08965818592076902,1739502698.8243756,59.07994365692139,3.154242726904926,1739502698.8243768,59.07994365692139,2.2573489622947274 +1739502698.844192,59.0999436378479,15.318182838286564,1739502698.8441944,59.0999436378479,0.14054765109588896,1739502698.8441968,59.0999436378479,97.1549251239469,1739502698.8441997,59.0999436378479,9.658112593293462,1739502698.8442008,59.0999436378479,-0.01,1739502698.8442025,59.0999436378479,-3.115000728525754,1739502698.8442037,59.0999436378479,0.07893721165996737,1739502698.8442051,59.0999436378479,0.01890977966858178,1739502698.8442063,59.0999436378479,2.3470071482154964,1739502698.8442078,59.0999436378479,0.0,1739502698.8442092,59.0999436378479,0.08965818592076902,1739502698.8442104,59.0999436378479,3.154242726904926,1739502698.8442118,59.0999436378479,2.2573489622947274 +1739502698.8667307,59.119943618774414,15.318182838286564,1739502698.8667347,59.119943618774414,0.14054765109588896,1739502698.8667395,59.119943618774414,97.1549251239469,1739502698.8667448,59.119943618774414,9.658112593293462,1739502698.8667476,59.119943618774414,-0.01,1739502698.8667512,59.119943618774414,-3.115000728525754,1739502698.8667545,59.119943618774414,0.07893721165996737,1739502698.8667583,59.119943618774414,0.01890977966858178,1739502698.8667614,59.119943618774414,2.3470071482154964,1739502698.866765,59.119943618774414,0.0,1739502698.8667684,59.119943618774414,0.08965818592076902,1739502698.8667717,59.119943618774414,3.154242726904926,1739502698.8667753,59.119943618774414,2.2573489622947274 +1739502698.884278,59.13994359970093,15.069405260810598,1739502698.8842802,59.13994359970093,0.13729231413636267,1739502698.884283,59.13994359970093,97.45432068358875,1739502698.8842857,59.13994359970093,9.33910645443878,1739502698.884287,59.13994359970093,-0.01,1739502698.8842888,59.13994359970093,-3.1158941877349986,1739502698.88429,59.13994359970093,0.06931897797727038,1739502698.8842914,59.13994359970093,0.016201967863562348,1739502698.8842926,59.13994359970093,2.3651360565655293,1739502698.884294,59.13994359970093,0.0,1739502698.8842955,59.13994359970093,0.10176527133786159,1739502698.884297,59.13994359970093,3.1551978968848524,1739502698.8842983,59.13994359970093,2.267154251901143 +1739502698.9042394,59.15994358062744,15.069405260810598,1739502698.904242,59.15994358062744,0.13729231413636267,1739502698.9042447,59.15994358062744,97.45432068358875,1739502698.9042475,59.15994358062744,9.33910645443878,1739502698.9042487,59.15994358062744,-0.01,1739502698.9042506,59.15994358062744,-3.1158941877349986,1739502698.9042518,59.15994358062744,0.06931897797727038,1739502698.9042532,59.15994358062744,0.016201967863562348,1739502698.9042544,59.15994358062744,2.3651360565655293,1739502698.904256,59.15994358062744,0.0,1739502698.904257,59.15994358062744,0.09798180466438611,1739502698.9042585,59.15994358062744,3.1551978968848524,1739502698.90426,59.15994358062744,2.267154251901143 +1739502698.924322,59.179943561553955,15.069405260810598,1739502698.9243248,59.179943561553955,0.13729231413636267,1739502698.9243279,59.179943561553955,97.45432068358875,1739502698.924331,59.179943561553955,9.33910645443878,1739502698.9243324,59.179943561553955,-0.01,1739502698.924334,59.179943561553955,-3.1158941877349986,1739502698.9243352,59.179943561553955,0.06931897797727038,1739502698.924337,59.179943561553955,0.016201967863562348,1739502698.924338,59.179943561553955,2.3651360565655293,1739502698.92434,59.179943561553955,0.0,1739502698.924342,59.179943561553955,0.09798180466438611,1739502698.9243464,59.179943561553955,3.1551978968848524,1739502698.9243507,59.179943561553955,2.267154251901143 +1739502698.9489799,59.19994354248047,15.069405260810598,1739502698.9489894,59.19994354248047,0.13729231413636267,1739502698.9490001,59.19994354248047,97.45432068358875,1739502698.9490104,59.19994354248047,9.33910645443878,1739502698.9490151,59.19994354248047,-0.01,1739502698.9490209,59.19994354248047,-3.1158941877349986,1739502698.9490263,59.19994354248047,0.06931897797727038,1739502698.949031,59.19994354248047,0.016201967863562348,1739502698.949036,59.19994354248047,2.3651360565655293,1739502698.9490414,59.19994354248047,0.0,1739502698.9490464,59.19994354248047,0.09798180466438611,1739502698.9490516,59.19994354248047,3.1551978968848524,1739502698.9490569,59.19994354248047,2.267154251901143 +1739502698.968194,59.21994352340698,15.069405260810598,1739502698.9681985,59.21994352340698,0.13729231413636267,1739502698.9682047,59.21994352340698,97.45432068358875,1739502698.968212,59.21994352340698,9.33910645443878,1739502698.9682162,59.21994352340698,-0.01,1739502698.9682212,59.21994352340698,-3.1158941877349986,1739502698.9682257,59.21994352340698,0.06931897797727038,1739502698.9682305,59.21994352340698,0.016201967863562348,1739502698.968235,59.21994352340698,2.3651360565655293,1739502698.9682395,59.21994352340698,0.0,1739502698.9682446,59.21994352340698,0.09798180466438611,1739502698.968249,59.21994352340698,3.1551978968848524,1739502698.9682536,59.21994352340698,2.267154251901143 +1739502698.986134,59.239943504333496,15.069405260810598,1739502698.9861374,59.239943504333496,0.13729231413636267,1739502698.9861417,59.239943504333496,97.45432068358875,1739502698.9861465,59.239943504333496,9.33910645443878,1739502698.986149,59.239943504333496,-0.01,1739502698.9861526,59.239943504333496,-3.1158941877349986,1739502698.9861557,59.239943504333496,0.06931897797727038,1739502698.9861588,59.239943504333496,0.016201967863562348,1739502698.986162,59.239943504333496,2.3651360565655293,1739502698.9861653,59.239943504333496,0.0,1739502698.9861684,59.239943504333496,0.09798180466438611,1739502698.9861717,59.239943504333496,3.1551978968848524,1739502698.9861748,59.239943504333496,2.267154251901143 +1739502699.0061574,59.25994348526001,14.819498414738941,1739502699.006161,59.25994348526001,0.13378344490892502,1739502699.006165,59.25994348526001,97.64744119118393,1739502699.00617,59.25994348526001,9.124386792079884,1739502699.0061727,59.25994348526001,-0.011,1739502699.0061765,59.25994348526001,-3.116175721408548,1739502699.0061796,59.25994348526001,0.061847848853042064,1739502699.006183,59.25994348526001,0.014635154086961755,1739502699.006186,59.25994348526001,2.379314575675644,1739502699.0061893,59.25994348526001,0.0,1739502699.0061927,59.25994348526001,0.10289352251384241,1739502699.006196,59.25994348526001,3.156153066864779,1739502699.0061994,59.25994348526001,2.277955965996124 +1739502699.0258696,59.27994346618652,14.819498414738941,1739502699.0258727,59.27994346618652,0.13378344490892502,1739502699.0258768,59.27994346618652,97.64744119118393,1739502699.0258813,59.27994346618652,9.124386792079884,1739502699.025884,59.27994346618652,-0.011,1739502699.0258873,59.27994346618652,-3.116175721408548,1739502699.0258904,59.27994346618652,0.061847848853042064,1739502699.0258934,59.27994346618652,0.014635154086961755,1739502699.0258965,59.27994346618652,2.379314575675644,1739502699.0259,59.27994346618652,0.0,1739502699.0259027,59.27994346618652,0.10135860967952004,1739502699.0259058,59.27994346618652,3.156153066864779,1739502699.025909,59.27994346618652,2.277955965996124 +1739502699.0463095,59.29994344711304,14.819498414738941,1739502699.0463128,59.29994344711304,0.13378344490892502,1739502699.046317,59.29994344711304,97.64744119118393,1739502699.0463216,59.29994344711304,9.124386792079884,1739502699.0463243,59.29994344711304,-0.011,1739502699.0463278,59.29994344711304,-3.116175721408548,1739502699.046331,59.29994344711304,0.061847848853042064,1739502699.046334,59.29994344711304,0.014635154086961755,1739502699.0463371,59.29994344711304,2.379314575675644,1739502699.0463405,59.29994344711304,0.0,1739502699.0463433,59.29994344711304,0.10135860967952004,1739502699.0463464,59.29994344711304,3.156153066864779,1739502699.0463495,59.29994344711304,2.277955965996124 +1739502699.0655549,59.31994342803955,14.819498414738941,1739502699.0655575,59.31994342803955,0.13378344490892502,1739502699.06556,59.31994342803955,97.64744119118393,1739502699.0655627,59.31994342803955,9.124386792079884,1739502699.0655642,59.31994342803955,-0.011,1739502699.0655656,59.31994342803955,-3.116175721408548,1739502699.065567,59.31994342803955,0.061847848853042064,1739502699.0655682,59.31994342803955,0.014635154086961755,1739502699.0655696,59.31994342803955,2.379314575675644,1739502699.0655708,59.31994342803955,0.0,1739502699.065572,59.31994342803955,0.10135860967952004,1739502699.0655735,59.31994342803955,3.156153066864779,1739502699.0655746,59.31994342803955,2.277955965996124 +1739502699.084195,59.339943408966064,14.819498414738941,1739502699.084197,59.339943408966064,0.13378344490892502,1739502699.0841997,59.339943408966064,97.64744119118393,1739502699.0842025,59.339943408966064,9.124386792079884,1739502699.0842037,59.339943408966064,-0.011,1739502699.0842054,59.339943408966064,-3.116175721408548,1739502699.0842068,59.339943408966064,0.061847848853042064,1739502699.084208,59.339943408966064,0.014635154086961755,1739502699.0842094,59.339943408966064,2.379314575675644,1739502699.0842109,59.339943408966064,0.0,1739502699.0842123,59.339943408966064,0.10135860967952004,1739502699.0842135,59.339943408966064,3.156153066864779,1739502699.0842147,59.339943408966064,2.277955965996124 +1739502699.1042552,59.35994338989258,14.56839741302652,1739502699.1042576,59.35994338989258,0.1300179117791842,1739502699.1042604,59.35994338989258,97.92876518547853,1739502699.1042628,59.35994338989258,8.820899439925661,1739502699.1042643,59.35994338989258,-0.0103556473037014,1739502699.104266,59.35994338989258,-3.117174087698996,1739502699.1042674,59.35994338989258,0.05118445770341723,1739502699.1042688,59.35994338989258,0.011892698716967036,1739502699.1042697,59.35994338989258,2.399698646979144,1739502699.1042714,59.35994338989258,0.0,1739502699.1042726,59.35994338989258,0.11488732881457336,1739502699.1042743,59.35994338989258,3.157108236844705,1739502699.1042755,59.35994338989258,2.289039045666189 +1739502699.1243234,59.37994337081909,14.56839741302652,1739502699.124326,59.37994337081909,0.1300179117791842,1739502699.1243293,59.37994337081909,97.92876518547853,1739502699.1243317,59.37994337081909,8.820899439925661,1739502699.1243331,59.37994337081909,-0.0103556473037014,1739502699.1243348,59.37994337081909,-3.117174087698996,1739502699.1243365,59.37994337081909,0.05118445770341723,1739502699.1243377,59.37994337081909,0.011892698716967036,1739502699.1243389,59.37994337081909,2.399698646979144,1739502699.1243405,59.37994337081909,0.0,1739502699.124342,59.37994337081909,0.11065960131295505,1739502699.1243436,59.37994337081909,3.157108236844705,1739502699.1243448,59.37994337081909,2.289039045666189 +1739502699.1443834,59.399943351745605,14.56839741302652,1739502699.1443865,59.399943351745605,0.1300179117791842,1739502699.1443894,59.399943351745605,97.92876518547853,1739502699.1443923,59.399943351745605,8.820899439925661,1739502699.1443934,59.399943351745605,-0.0103556473037014,1739502699.1443954,59.399943351745605,-3.117174087698996,1739502699.1443965,59.399943351745605,0.05118445770341723,1739502699.144398,59.399943351745605,0.011892698716967036,1739502699.1443994,59.399943351745605,2.399698646979144,1739502699.1444008,59.399943351745605,0.0,1739502699.1444025,59.399943351745605,0.11065960131295505,1739502699.1444037,59.399943351745605,3.157108236844705,1739502699.144405,59.399943351745605,2.289039045666189 +1739502699.1643283,59.41994333267212,14.56839741302652,1739502699.164331,59.41994333267212,0.1300179117791842,1739502699.1643345,59.41994333267212,97.92876518547853,1739502699.1643376,59.41994333267212,8.820899439925661,1739502699.1643388,59.41994333267212,-0.0103556473037014,1739502699.1643407,59.41994333267212,-3.117174087698996,1739502699.1643422,59.41994333267212,0.05118445770341723,1739502699.1643438,59.41994333267212,0.011892698716967036,1739502699.1643453,59.41994333267212,2.399698646979144,1739502699.1643472,59.41994333267212,0.0,1739502699.1643486,59.41994333267212,0.11065960131295505,1739502699.1643503,59.41994333267212,3.157108236844705,1739502699.1643517,59.41994333267212,2.289039045666189 +1739502699.1842542,59.43994331359863,14.56839741302652,1739502699.1842568,59.43994331359863,0.1300179117791842,1739502699.18426,59.43994331359863,97.92876518547853,1739502699.1842625,59.43994331359863,8.820899439925661,1739502699.1842637,59.43994331359863,-0.0103556473037014,1739502699.1842654,59.43994331359863,-3.117174087698996,1739502699.184267,59.43994331359863,0.05118445770341723,1739502699.1842685,59.43994331359863,0.011892698716967036,1739502699.1842697,59.43994331359863,2.399698646979144,1739502699.184271,59.43994331359863,0.0,1739502699.1842723,59.43994331359863,0.11065960131295505,1739502699.1842737,59.43994331359863,3.157108236844705,1739502699.184275,59.43994331359863,2.289039045666189 +1739502699.2046688,59.45994329452515,14.56839741302652,1739502699.2046885,59.45994329452515,0.1300179117791842,1739502699.2046962,59.45994329452515,97.92876518547853,1739502699.2047045,59.45994329452515,8.820899439925661,1739502699.204707,59.45994329452515,-0.0103556473037014,1739502699.204709,59.45994329452515,-3.117174087698996,1739502699.204711,59.45994329452515,0.05118445770341723,1739502699.2047124,59.45994329452515,0.011892698716967036,1739502699.204714,59.45994329452515,2.399698646979144,1739502699.2047157,59.45994329452515,0.0,1739502699.2047174,59.45994329452515,0.11065960131295505,1739502699.204719,59.45994329452515,3.157108236844705,1739502699.2047207,59.45994329452515,2.289039045666189 +1739502699.2252533,59.47994327545166,14.316020353051027,1739502699.2252579,59.47994327545166,0.1259921132650499,1739502699.2252622,59.47994327545166,98.16581567855565,1739502699.2252655,59.47994327545166,8.559454155042316,1739502699.225267,59.47994327545166,-0.01,1739502699.2252693,59.47994327545166,-3.1179732216811415,1739502699.2252707,59.47994327545166,0.04116297292947738,1739502699.225273,59.47994327545166,0.009534483666961822,1739502699.2252743,59.47994327545166,2.4190148089279195,1739502699.2252765,59.47994327545166,0.0,1739502699.225278,59.47994327545166,0.12101304863701981,1739502699.2252803,59.47994327545166,3.1580634068246316,1739502699.225282,59.47994327545166,2.301237214700999 +1739502699.2475398,59.499943256378174,14.316020353051027,1739502699.247544,59.499943256378174,0.1259921132650499,1739502699.2475498,59.499943256378174,98.16581567855565,1739502699.2475555,59.499943256378174,8.559454155042316,1739502699.247559,59.499943256378174,-0.01,1739502699.2475638,59.499943256378174,-3.1179732216811415,1739502699.2475677,59.499943256378174,0.04116297292947738,1739502699.2475717,59.499943256378174,0.009534483666961822,1739502699.2475755,59.499943256378174,2.4190148089279195,1739502699.2475796,59.499943256378174,0.0,1739502699.2475836,59.499943256378174,0.11777759422692036,1739502699.247588,59.499943256378174,3.1580634068246316,1739502699.2475917,59.499943256378174,2.301237214700999 +1739502699.2647915,59.51994323730469,14.316020353051027,1739502699.264794,59.51994323730469,0.1259921132650499,1739502699.2647977,59.51994323730469,98.16581567855565,1739502699.264801,59.51994323730469,8.559454155042316,1739502699.2648025,59.51994323730469,-0.01,1739502699.2648046,59.51994323730469,-3.1179732216811415,1739502699.264806,59.51994323730469,0.04116297292947738,1739502699.2648077,59.51994323730469,0.009534483666961822,1739502699.2648091,59.51994323730469,2.4190148089279195,1739502699.264811,59.51994323730469,0.0,1739502699.2648125,59.51994323730469,0.11777759422692036,1739502699.2648141,59.51994323730469,3.1580634068246316,1739502699.2648158,59.51994323730469,2.301237214700999 +1739502699.284714,59.5399432182312,14.316020353051027,1739502699.2847173,59.5399432182312,0.1259921132650499,1739502699.2847211,59.5399432182312,98.16581567855565,1739502699.2847247,59.5399432182312,8.559454155042316,1739502699.2847264,59.5399432182312,-0.01,1739502699.2847283,59.5399432182312,-3.1179732216811415,1739502699.2847302,59.5399432182312,0.04116297292947738,1739502699.2847316,59.5399432182312,0.009534483666961822,1739502699.2847338,59.5399432182312,2.4190148089279195,1739502699.2847354,59.5399432182312,0.0,1739502699.284737,59.5399432182312,0.11777759422692036,1739502699.2847385,59.5399432182312,3.1580634068246316,1739502699.2847404,59.5399432182312,2.301237214700999 +1739502699.3046992,59.559943199157715,14.316020353051027,1739502699.304702,59.559943199157715,0.1259921132650499,1739502699.3047056,59.559943199157715,98.16581567855565,1739502699.304709,59.559943199157715,8.559454155042316,1739502699.3047104,59.559943199157715,-0.01,1739502699.3047128,59.559943199157715,-3.1179732216811415,1739502699.3047147,59.559943199157715,0.04116297292947738,1739502699.304717,59.559943199157715,0.009534483666961822,1739502699.3047185,59.559943199157715,2.4190148089279195,1739502699.3047204,59.559943199157715,0.0,1739502699.3047216,59.559943199157715,0.11777759422692036,1739502699.3047235,59.559943199157715,3.1580634068246316,1739502699.304725,59.559943199157715,2.301237214700999 +1739502699.324518,59.57994318008423,14.062277390625983,1739502699.3245203,59.57994318008423,0.12170208750692257,1739502699.3245237,59.57994318008423,98.33553876546561,1739502699.3245268,59.57994318008423,8.36398191974298,1739502699.3245285,59.57994318008423,-0.0108049662451562,1739502699.3245304,59.57994318008423,-3.1183430382892214,1739502699.324532,59.57994318008423,0.03319390164387667,1739502699.3245335,59.57994318008423,0.007846822455825575,1739502699.3245351,59.57994318008423,2.434485913825182,1739502699.3245368,59.57994318008423,0.0,1739502699.3245382,59.57994318008423,0.12155293941353978,1739502699.32454,59.57994318008423,3.159018576804558,1739502699.3245413,59.57994318008423,2.3141127705559956 +1739502699.3446925,59.59994316101074,14.062277390625983,1739502699.3446999,59.59994316101074,0.12170208750692257,1739502699.3447075,59.59994316101074,98.33553876546561,1739502699.344712,59.59994316101074,8.36398191974298,1739502699.344714,59.59994316101074,-0.0108049662451562,1739502699.3447163,59.59994316101074,-3.1183430382892214,1739502699.344719,59.59994316101074,0.03319390164387667,1739502699.3447208,59.59994316101074,0.007846822455825575,1739502699.344723,59.59994316101074,2.434485913825182,1739502699.3447251,59.59994316101074,0.0,1739502699.344727,59.59994316101074,0.12037314326918658,1739502699.3447292,59.59994316101074,3.159018576804558,1739502699.344731,59.59994316101074,2.3141127705559956 +1739502699.3645382,59.619943141937256,14.062277390625983,1739502699.3645406,59.619943141937256,0.12170208750692257,1739502699.364544,59.619943141937256,98.33553876546561,1739502699.3645473,59.619943141937256,8.36398191974298,1739502699.364549,59.619943141937256,-0.0108049662451562,1739502699.3645508,59.619943141937256,-3.1183430382892214,1739502699.3645525,59.619943141937256,0.03319390164387667,1739502699.3645544,59.619943141937256,0.007846822455825575,1739502699.3645558,59.619943141937256,2.434485913825182,1739502699.3645577,59.619943141937256,0.0,1739502699.3645594,59.619943141937256,0.12037314326918658,1739502699.3645608,59.619943141937256,3.159018576804558,1739502699.3645625,59.619943141937256,2.3141127705559956 +1739502699.3847358,59.63994312286377,14.062277390625983,1739502699.3847408,59.63994312286377,0.12170208750692257,1739502699.384745,59.63994312286377,98.33553876546561,1739502699.3847482,59.63994312286377,8.36398191974298,1739502699.38475,59.63994312286377,-0.0108049662451562,1739502699.3847518,59.63994312286377,-3.1183430382892214,1739502699.3847535,59.63994312286377,0.03319390164387667,1739502699.384755,59.63994312286377,0.007846822455825575,1739502699.3847566,59.63994312286377,2.434485913825182,1739502699.3847585,59.63994312286377,0.0,1739502699.3847601,59.63994312286377,0.12037314326918658,1739502699.3847618,59.63994312286377,3.159018576804558,1739502699.3847635,59.63994312286377,2.3141127705559956 +1739502699.404712,59.65994310379028,14.062277390625983,1739502699.4047153,59.65994310379028,0.12170208750692257,1739502699.4047189,59.65994310379028,98.33553876546561,1739502699.4047222,59.65994310379028,8.36398191974298,1739502699.4047236,59.65994310379028,-0.0108049662451562,1739502699.4047258,59.65994310379028,-3.1183430382892214,1739502699.4047275,59.65994310379028,0.03319390164387667,1739502699.4047291,59.65994310379028,0.007846822455825575,1739502699.4047306,59.65994310379028,2.434485913825182,1739502699.4047325,59.65994310379028,0.0,1739502699.404734,59.65994310379028,0.12037314326918658,1739502699.4047358,59.65994310379028,3.159018576804558,1739502699.4047372,59.65994310379028,2.3141127705559956 +1739502699.424588,59.6799430847168,14.062277390625983,1739502699.4245906,59.6799430847168,0.12170208750692257,1739502699.4245937,59.6799430847168,98.33553876546561,1739502699.4245968,59.6799430847168,8.36398191974298,1739502699.4245982,59.6799430847168,-0.0108049662451562,1739502699.4246001,59.6799430847168,-3.1183430382892214,1739502699.4246018,59.6799430847168,0.03319390164387667,1739502699.4246035,59.6799430847168,0.007846822455825575,1739502699.4246047,59.6799430847168,2.434485913825182,1739502699.4246068,59.6799430847168,0.0,1739502699.424608,59.6799430847168,0.12037314326918658,1739502699.42461,59.6799430847168,3.159018576804558,1739502699.4246113,59.6799430847168,2.3141127705559956 +1739502699.444832,59.69994306564331,13.807103326135024,1739502699.4448357,59.69994306564331,0.11714405611348067,1739502699.4448395,59.69994306564331,98.64305388773174,1739502699.444843,59.69994306564331,8.03006565114845,1739502699.4448447,59.69994306564331,-0.011,1739502699.4448469,59.69994306564331,-3.1194146701904097,1739502699.4448483,59.69994306564331,0.021940120602032563,1739502699.4448502,59.69994306564331,0.005046331662182824,1739502699.4448516,59.69994306564331,2.456502610685976,1739502699.4448538,59.69994306564331,0.0,1739502699.4448552,59.69994306564331,0.13319625378453903,1739502699.444857,59.69994306564331,3.1599737467844844,1739502699.4448586,59.69994306564331,2.327313581564826 +1739502699.465069,59.719943046569824,13.807103326135024,1739502699.4650722,59.719943046569824,0.11714405611348067,1739502699.4650767,59.719943046569824,98.64305388773174,1739502699.4650798,59.719943046569824,8.03006565114845,1739502699.4650817,59.719943046569824,-0.011,1739502699.4650836,59.719943046569824,-3.1194146701904097,1739502699.4650853,59.719943046569824,0.021940120602032563,1739502699.4650867,59.719943046569824,0.005046331662182824,1739502699.4650884,59.719943046569824,2.456502610685976,1739502699.46509,59.719943046569824,0.0,1739502699.4650915,59.719943046569824,0.12918902912115016,1739502699.4650934,59.719943046569824,3.1599737467844844,1739502699.4650953,59.719943046569824,2.327313581564826 +1739502699.4847653,59.73994302749634,13.807103326135024,1739502699.4847686,59.73994302749634,0.11714405611348067,1739502699.4847724,59.73994302749634,98.64305388773174,1739502699.4847753,59.73994302749634,8.03006565114845,1739502699.484777,59.73994302749634,-0.011,1739502699.4847796,59.73994302749634,-3.1194146701904097,1739502699.484781,59.73994302749634,0.021940120602032563,1739502699.4847827,59.73994302749634,0.005046331662182824,1739502699.4847841,59.73994302749634,2.456502610685976,1739502699.484786,59.73994302749634,0.0,1739502699.4847875,59.73994302749634,0.12918902912115016,1739502699.484789,59.73994302749634,3.1599737467844844,1739502699.4847908,59.73994302749634,2.327313581564826 +1739502699.5047593,59.75994300842285,13.807103326135024,1739502699.5047624,59.75994300842285,0.11714405611348067,1739502699.504766,59.75994300842285,98.64305388773174,1739502699.5047693,59.75994300842285,8.03006565114845,1739502699.5047708,59.75994300842285,-0.011,1739502699.504773,59.75994300842285,-3.1194146701904097,1739502699.5047746,59.75994300842285,0.021940120602032563,1739502699.5047762,59.75994300842285,0.005046331662182824,1739502699.5047777,59.75994300842285,2.456502610685976,1739502699.5047793,59.75994300842285,0.0,1739502699.5047808,59.75994300842285,0.12918902912115016,1739502699.5047827,59.75994300842285,3.1599737467844844,1739502699.5047843,59.75994300842285,2.327313581564826 +1739502699.5245013,59.779942989349365,13.807103326135024,1739502699.5245037,59.779942989349365,0.11714405611348067,1739502699.524507,59.779942989349365,98.64305388773174,1739502699.5245101,59.779942989349365,8.03006565114845,1739502699.5245118,59.779942989349365,-0.011,1739502699.5245135,59.779942989349365,-3.1194146701904097,1739502699.5245152,59.779942989349365,0.021940120602032563,1739502699.5245168,59.779942989349365,0.005046331662182824,1739502699.5245183,59.779942989349365,2.456502610685976,1739502699.52452,59.779942989349365,0.0,1739502699.5245216,59.779942989349365,0.12918902912115016,1739502699.5245233,59.779942989349365,3.1599737467844844,1739502699.5245247,59.779942989349365,2.327313581564826 +1739502699.544794,59.79994297027588,13.55043905530778,1739502699.5447974,59.79994297027588,0.11231415764510011,1739502699.5448008,59.79994297027588,98.98556827168933,1739502699.544804,59.79994297027588,7.659315832647607,1739502699.5448055,59.79994297027588,-0.012891010330552151,1739502699.5448077,59.79994297027588,-3.1203426615755876,1739502699.5448096,59.79994297027588,0.01127655146335862,1739502699.5448112,59.79994297027588,0.0024942793248694368,1739502699.544813,59.79994297027588,2.4775483203465285,1739502699.5448148,59.79994297027588,0.0,1739502699.5448167,59.79994297027588,0.139260026769323,1739502699.5448182,59.79994297027588,3.160928916764411,1739502699.54482,59.79994297027588,2.3414354824057173 +1739502699.565021,59.81994295120239,13.55043905530778,1739502699.5650246,59.81994295120239,0.11231415764510011,1739502699.5650282,59.81994295120239,98.98556827168933,1739502699.5650315,59.81994295120239,7.659315832647607,1739502699.565033,59.81994295120239,-0.012891010330552151,1739502699.565035,59.81994295120239,-3.1203426615755876,1739502699.5650368,59.81994295120239,0.01127655146335862,1739502699.5650384,59.81994295120239,0.0024942793248694368,1739502699.5650399,59.81994295120239,2.4775483203465285,1739502699.5650418,59.81994295120239,0.0,1739502699.5650432,59.81994295120239,0.1361128379408112,1739502699.5650449,59.81994295120239,3.160928916764411,1739502699.5650468,59.81994295120239,2.3414354824057173 +1739502699.5846882,59.839942932128906,13.55043905530778,1739502699.5846915,59.839942932128906,0.11231415764510011,1739502699.584695,59.839942932128906,98.98556827168933,1739502699.5846984,59.839942932128906,7.659315832647607,1739502699.5846999,59.839942932128906,-0.012891010330552151,1739502699.5847025,59.839942932128906,-3.1203426615755876,1739502699.584704,59.839942932128906,0.01127655146335862,1739502699.5847058,59.839942932128906,0.0024942793248694368,1739502699.5847073,59.839942932128906,2.4775483203465285,1739502699.5847092,59.839942932128906,0.0,1739502699.5847106,59.839942932128906,0.1361128379408112,1739502699.5847123,59.839942932128906,3.160928916764411,1739502699.584714,59.839942932128906,2.3414354824057173 +1739502699.6047,59.85994291305542,13.55043905530778,1739502699.6047032,59.85994291305542,0.11231415764510011,1739502699.6047065,59.85994291305542,98.98556827168933,1739502699.6047099,59.85994291305542,7.659315832647607,1739502699.6047118,59.85994291305542,-0.012891010330552151,1739502699.6047137,59.85994291305542,-3.1203426615755876,1739502699.6047158,59.85994291305542,0.01127655146335862,1739502699.6047173,59.85994291305542,0.0024942793248694368,1739502699.6047187,59.85994291305542,2.4775483203465285,1739502699.6047206,59.85994291305542,0.0,1739502699.6047223,59.85994291305542,0.1361128379408112,1739502699.6047237,59.85994291305542,3.160928916764411,1739502699.6047254,59.85994291305542,2.3414354824057173 +1739502699.6248825,59.879942893981934,13.55043905530778,1739502699.6248856,59.879942893981934,0.11231415764510011,1739502699.6248891,59.879942893981934,98.98556827168933,1739502699.6248922,59.879942893981934,7.659315832647607,1739502699.6248937,59.879942893981934,-0.012891010330552151,1739502699.6248958,59.879942893981934,-3.1203426615755876,1739502699.6248972,59.879942893981934,0.01127655146335862,1739502699.6248991,59.879942893981934,0.0024942793248694368,1739502699.6249006,59.879942893981934,2.4775483203465285,1739502699.6249027,59.879942893981934,0.0,1739502699.6249042,59.879942893981934,0.1361128379408112,1739502699.624906,59.879942893981934,3.160928916764411,1739502699.6249075,59.879942893981934,2.3414354824057173 +1739502699.645195,59.89994287490845,13.55043905530778,1739502699.6451979,59.89994287490845,0.11231415764510011,1739502699.645201,59.89994287490845,98.98556827168933,1739502699.6452038,59.89994287490845,7.659315832647607,1739502699.645205,59.89994287490845,-0.012891010330552151,1739502699.645207,59.89994287490845,-3.1203426615755876,1739502699.6452084,59.89994287490845,0.01127655146335862,1739502699.6452098,59.89994287490845,0.0024942793248694368,1739502699.6452112,59.89994287490845,2.4775483203465285,1739502699.6452127,59.89994287490845,0.0,1739502699.6452143,59.89994287490845,0.1361128379408112,1739502699.6452155,59.89994287490845,3.160928916764411,1739502699.645217,59.89994287490845,2.3414354824057173 +1739502699.6654525,59.91994285583496,13.292179242106776,1739502699.6654587,59.91994285583496,0.10720745453783032,1739502699.6654623,59.91994285583496,99.22507692964703,1739502699.6654654,59.91994285583496,7.389889887108681,1739502699.665483,59.91994285583496,-0.014411269499188953,1739502699.6654875,59.91994285583496,-3.1209902214147833,1739502699.6654897,59.91994285583496,0.0018359958181210852,1739502699.6655028,59.91994285583496,0.00040458293261129105,1739502699.6655042,59.91994285583496,2.496330703748454,1739502699.6655064,59.91994285583496,0.0,1739502699.6655097,59.91994285583496,0.14166913561598063,1739502699.6655111,59.91994285583496,3.161884086744337,1739502699.6655142,59.91994285583496,2.3563979122944 +1739502699.6861448,59.939942836761475,13.292179242106776,1739502699.6861486,59.939942836761475,0.10720745453783032,1739502699.6861532,59.939942836761475,99.22507692964703,1739502699.6861584,59.939942836761475,7.389889887108681,1739502699.686161,59.939942836761475,-0.014411269499188953,1739502699.6861653,59.939942836761475,-3.1209902214147833,1739502699.686169,59.939942836761475,0.0018359958181210852,1739502699.6861725,59.939942836761475,0.00040458293261129105,1739502699.686176,59.939942836761475,2.496330703748454,1739502699.6861796,59.939942836761475,0.0,1739502699.686183,59.939942836761475,0.13993279145405424,1739502699.6861866,59.939942836761475,3.161884086744337,1739502699.68619,59.939942836761475,2.3563979122944 +1739502699.704311,59.95994281768799,13.292179242106776,1739502699.7043138,59.95994281768799,0.10720745453783032,1739502699.704317,59.95994281768799,99.22507692964703,1739502699.7043202,59.95994281768799,7.389889887108681,1739502699.7043219,59.95994281768799,-0.014411269499188953,1739502699.7043238,59.95994281768799,-3.1209902214147833,1739502699.704326,59.95994281768799,0.0018359958181210852,1739502699.7043276,59.95994281768799,0.00040458293261129105,1739502699.704329,59.95994281768799,2.496330703748454,1739502699.704331,59.95994281768799,0.0,1739502699.704332,59.95994281768799,0.13993279145405424,1739502699.7043335,59.95994281768799,3.161884086744337,1739502699.7043352,59.95994281768799,2.3563979122944 +1739502699.7251303,59.9799427986145,13.292179242106776,1739502699.7251334,59.9799427986145,0.10720745453783032,1739502699.7251377,59.9799427986145,99.22507692964703,1739502699.7251427,59.9799427986145,7.389889887108681,1739502699.7251453,59.9799427986145,-0.014411269499188953,1739502699.7251482,59.9799427986145,-3.1209902214147833,1739502699.7251508,59.9799427986145,0.0018359958181210852,1739502699.725153,59.9799427986145,0.00040458293261129105,1739502699.725155,59.9799427986145,2.496330703748454,1739502699.725158,59.9799427986145,0.0,1739502699.7251606,59.9799427986145,0.13993279145405424,1739502699.7251632,59.9799427986145,3.161884086744337,1739502699.725166,59.9799427986145,2.3563979122944 +1739502699.745576,59.999942779541016,13.292179242106776,1739502699.7455797,59.999942779541016,0.10720745453783032,1739502699.745584,59.999942779541016,99.22507692964703,1739502699.7455885,59.999942779541016,7.389889887108681,1739502699.7455907,59.999942779541016,-0.014411269499188953,1739502699.7455938,59.999942779541016,-3.1209902214147833,1739502699.7455962,59.999942779541016,0.0018359958181210852,1739502699.7455986,59.999942779541016,0.00040458293261129105,1739502699.7456005,59.999942779541016,2.496330703748454,1739502699.7456028,59.999942779541016,0.0,1739502699.7456048,59.999942779541016,0.13993279145405424,1739502699.7456079,59.999942779541016,3.161884086744337,1739502699.7456105,59.999942779541016,2.3563979122944 +1739502699.7656267,60.01994276046753,13.032266233659133,1739502699.7656305,60.01994276046753,0.1018196965091338,1739502699.7656345,60.01994276046753,99.46390290185593,1739502699.7656388,60.01994276046753,7.120468821450745,1739502699.7656415,60.01994276046753,-0.015707488095038337,1739502699.7656446,60.01994276046753,-3.1217151616702887,1739502699.7656472,60.01994276046753,-0.008095504882811322,1739502699.7656493,60.01994276046753,-0.001778256540267089,1739502699.765652,60.01994276046753,2.483861306991412,1739502699.7656546,60.01994276046753,0.0,1739502699.7656572,60.01994276046753,0.09954058268403863,1739502699.7656596,60.01994276046753,3.1628392567242636,1739502699.7656622,60.01994276046753,2.3716981507907393 +1739502699.784108,60.03994274139404,13.032266233659133,1739502699.7841108,60.03994274139404,0.1018196965091338,1739502699.7841136,60.03994274139404,99.46390290185593,1739502699.7841165,60.03994274139404,7.120468821450745,1739502699.7841177,60.03994274139404,-0.015707488095038337,1739502699.7841196,60.03994274139404,-3.1217151616702887,1739502699.7841208,60.03994274139404,-0.008095504882811322,1739502699.7841225,60.03994274139404,-0.001778256540267089,1739502699.7841237,60.03994274139404,2.483861306991412,1739502699.7841253,60.03994274139404,0.0,1739502699.7841268,60.03994274139404,0.11216315620067263,1739502699.7841282,60.03994274139404,3.1628392567242636,1739502699.7841296,60.03994274139404,2.3716981507907393 +1739502699.8040504,60.05994272232056,13.032266233659133,1739502699.8040526,60.05994272232056,0.1018196965091338,1739502699.804055,60.05994272232056,99.46390290185593,1739502699.8040576,60.05994272232056,7.120468821450745,1739502699.8040586,60.05994272232056,-0.015707488095038337,1739502699.8040605,60.05994272232056,-3.1217151616702887,1739502699.8040617,60.05994272232056,-0.008095504882811322,1739502699.8040626,60.05994272232056,-0.001778256540267089,1739502699.804064,60.05994272232056,2.483861306991412,1739502699.8040652,60.05994272232056,0.0,1739502699.8040667,60.05994272232056,0.11216315620067263,1739502699.8040679,60.05994272232056,3.1628392567242636,1739502699.804069,60.05994272232056,2.3716981507907393 +1739502699.8241465,60.07994270324707,13.032266233659133,1739502699.824149,60.07994270324707,0.1018196965091338,1739502699.8241518,60.07994270324707,99.46390290185593,1739502699.8241546,60.07994270324707,7.120468821450745,1739502699.8241558,60.07994270324707,-0.015707488095038337,1739502699.8241575,60.07994270324707,-3.1217151616702887,1739502699.8241587,60.07994270324707,-0.008095504882811322,1739502699.82416,60.07994270324707,-0.001778256540267089,1739502699.8241613,60.07994270324707,2.483861306991412,1739502699.8241627,60.07994270324707,0.0,1739502699.8241642,60.07994270324707,0.11216315620067263,1739502699.8241653,60.07994270324707,3.1628392567242636,1739502699.8241668,60.07994270324707,2.3716981507907393 +1739502699.8443623,60.099942684173584,13.032266233659133,1739502699.8443654,60.099942684173584,0.1018196965091338,1739502699.8443685,60.099942684173584,99.46390290185593,1739502699.8443713,60.099942684173584,7.120468821450745,1739502699.8443725,60.099942684173584,-0.015707488095038337,1739502699.844374,60.099942684173584,-3.1217151616702887,1739502699.8443756,60.099942684173584,-0.008095504882811322,1739502699.8443768,60.099942684173584,-0.001778256540267089,1739502699.844378,60.099942684173584,2.483861306991412,1739502699.84438,60.099942684173584,0.0,1739502699.844381,60.099942684173584,0.11216315620067263,1739502699.8443828,60.099942684173584,3.1628392567242636,1739502699.844384,60.099942684173584,2.3716981507907393 +1739502699.8642347,60.1199426651001,13.032266233659133,1739502699.8642373,60.1199426651001,0.1018196965091338,1739502699.864241,60.1199426651001,99.46390290185593,1739502699.864244,60.1199426651001,7.120468821450745,1739502699.8642452,60.1199426651001,-0.015707488095038337,1739502699.8642473,60.1199426651001,-3.1217151616702887,1739502699.8642485,60.1199426651001,-0.008095504882811322,1739502699.8642507,60.1199426651001,-0.001778256540267089,1739502699.864252,60.1199426651001,2.483861306991412,1739502699.8642538,60.1199426651001,0.0,1739502699.864255,60.1199426651001,0.11216315620067263,1739502699.864257,60.1199426651001,3.1628392567242636,1739502699.8642583,60.1199426651001,2.3716981507907393 +1739502699.8841434,60.13994264602661,12.770849688226065,1739502699.8841455,60.13994264602661,0.09615099078000888,1739502699.8841486,60.13994264602661,99.89258072016068,1739502699.8841512,60.13994264602661,6.667745718750699,1739502699.8841527,60.13994264602661,-0.018,1739502699.8841543,60.13994264602661,-3.122891074365007,1739502699.8841558,60.13994264602661,-0.021365739817502914,1739502699.8841572,60.13994264602661,-0.004403777859854703,1739502699.8841584,60.13994264602661,2.4576316443815935,1739502699.88416,60.13994264602661,0.0,1739502699.8841612,60.13994264602661,0.05651585384870689,1739502699.884163,60.13994264602661,3.16379442670419,1739502699.884164,60.13994264602661,2.3837259971462603 +1739502699.9040778,60.159942626953125,12.770849688226065,1739502699.9040804,60.159942626953125,0.09615099078000888,1739502699.9040833,60.159942626953125,99.89258072016068,1739502699.9040859,60.159942626953125,6.667745718750699,1739502699.9040873,60.159942626953125,-0.018,1739502699.9040887,60.159942626953125,-3.122891074365007,1739502699.9040902,60.159942626953125,-0.021365739817502914,1739502699.9040914,60.159942626953125,-0.004403777859854703,1739502699.9040928,60.159942626953125,2.4576316443815935,1739502699.9040942,60.159942626953125,0.0,1739502699.9040954,60.159942626953125,0.07390564723533322,1739502699.904097,60.159942626953125,3.16379442670419,1739502699.9040983,60.159942626953125,2.3837259971462603 +1739502699.9241967,60.17994260787964,12.770849688226065,1739502699.9241993,60.17994260787964,0.09615099078000888,1739502699.9242022,60.17994260787964,99.89258072016068,1739502699.924205,60.17994260787964,6.667745718750699,1739502699.9242063,60.17994260787964,-0.018,1739502699.9242082,60.17994260787964,-3.122891074365007,1739502699.9242094,60.17994260787964,-0.021365739817502914,1739502699.9242108,60.17994260787964,-0.004403777859854703,1739502699.9242125,60.17994260787964,2.4576316443815935,1739502699.9242141,60.17994260787964,0.0,1739502699.9242153,60.17994260787964,0.07390564723533322,1739502699.9242167,60.17994260787964,3.16379442670419,1739502699.9242182,60.17994260787964,2.3837259971462603 +1739502699.9441595,60.19994258880615,12.770849688226065,1739502699.9441621,60.19994258880615,0.09615099078000888,1739502699.9441648,60.19994258880615,99.89258072016068,1739502699.9441679,60.19994258880615,6.667745718750699,1739502699.9441695,60.19994258880615,-0.018,1739502699.944171,60.19994258880615,-3.122891074365007,1739502699.9441726,60.19994258880615,-0.021365739817502914,1739502699.9441738,60.19994258880615,-0.004403777859854703,1739502699.944175,60.19994258880615,2.4576316443815935,1739502699.9441767,60.19994258880615,0.0,1739502699.944178,60.19994258880615,0.07390564723533322,1739502699.9441795,60.19994258880615,3.16379442670419,1739502699.9441807,60.19994258880615,2.3837259971462603 +1739502699.9641778,60.219942569732666,12.770849688226065,1739502699.9641807,60.219942569732666,0.09615099078000888,1739502699.9641836,60.219942569732666,99.89258072016068,1739502699.964187,60.219942569732666,6.667745718750699,1739502699.964188,60.219942569732666,-0.018,1739502699.9641902,60.219942569732666,-3.122891074365007,1739502699.9641914,60.219942569732666,-0.021365739817502914,1739502699.964193,60.219942569732666,-0.004403777859854703,1739502699.9641943,60.219942569732666,2.4576316443815935,1739502699.9641962,60.219942569732666,0.0,1739502699.9641974,60.219942569732666,0.07390564723533322,1739502699.9641986,60.219942569732666,3.16379442670419,1739502699.9642003,60.219942569732666,2.3837259971462603 +1739502699.9841256,60.23994255065918,12.508294359948373,1739502699.9841285,60.23994255065918,0.09020671977515615,1739502699.9841313,60.23994255065918,99.9172609210188,1739502699.9841342,60.23994255065918,6.626846321444638,1739502699.9841352,60.23994255065918,-0.018480765421712786,1739502699.984137,60.23994255065918,-3.1231150414837954,1739502699.9841383,60.23994255065918,-0.027525840460198767,1739502699.9841397,60.23994255065918,-0.006109200701590046,1739502699.984141,60.23994255065918,2.445550031794864,1739502699.9841425,60.23994255065918,0.0,1739502699.9841442,60.23994255065918,0.04453263182001264,1739502699.9841454,60.23994255065918,3.1647495966841164,1739502699.9841468,60.23994255065918,2.391838326639294 +1739502700.0041714,60.25994253158569,12.508294359948373,1739502700.0041735,60.25994253158569,0.09020671977515615,1739502700.0041764,60.25994253158569,99.9172609210188,1739502700.004179,60.25994253158569,6.626846321444638,1739502700.0041804,60.25994253158569,-0.018480765421712786,1739502700.004182,60.25994253158569,-3.1231150414837954,1739502700.0041833,60.25994253158569,-0.027525840460198767,1739502700.0041845,60.25994253158569,-0.006109200701590046,1739502700.0041864,60.25994253158569,2.445550031794864,1739502700.0041878,60.25994253158569,0.0,1739502700.0041893,60.25994253158569,0.05371170515556978,1739502700.0041904,60.25994253158569,3.1647495966841164,1739502700.0041916,60.25994253158569,2.391838326639294 +1739502700.0241888,60.27994251251221,12.508294359948373,1739502700.0241914,60.27994251251221,0.09020671977515615,1739502700.0241947,60.27994251251221,99.9172609210188,1739502700.0241978,60.27994251251221,6.626846321444638,1739502700.0241995,60.27994251251221,-0.018480765421712786,1739502700.0242014,60.27994251251221,-3.1231150414837954,1739502700.0242028,60.27994251251221,-0.027525840460198767,1739502700.0242043,60.27994251251221,-0.006109200701590046,1739502700.024206,60.27994251251221,2.445550031794864,1739502700.0242078,60.27994251251221,0.0,1739502700.0242095,60.27994251251221,0.05371170515556978,1739502700.024211,60.27994251251221,3.1647495966841164,1739502700.0242128,60.27994251251221,2.391838326639294 +1739502700.044161,60.29994249343872,12.508294359948373,1739502700.0441635,60.29994249343872,0.09020671977515615,1739502700.0441666,60.29994249343872,99.9172609210188,1739502700.0441697,60.29994249343872,6.626846321444638,1739502700.0441713,60.29994249343872,-0.018480765421712786,1739502700.044173,60.29994249343872,-3.1231150414837954,1739502700.0441747,60.29994249343872,-0.027525840460198767,1739502700.044176,60.29994249343872,-0.006109200701590046,1739502700.0441773,60.29994249343872,2.445550031794864,1739502700.0441792,60.29994249343872,0.0,1739502700.0441806,60.29994249343872,0.05371170515556978,1739502700.0441825,60.29994249343872,3.1647495966841164,1739502700.044184,60.29994249343872,2.391838326639294 +1739502700.0666747,60.319942474365234,12.508294359948373,1739502700.0666783,60.319942474365234,0.09020671977515615,1739502700.066683,60.319942474365234,99.9172609210188,1739502700.0666888,60.319942474365234,6.626846321444638,1739502700.0666916,60.319942474365234,-0.018480765421712786,1739502700.0666957,60.319942474365234,-3.1231150414837954,1739502700.0666993,60.319942474365234,-0.027525840460198767,1739502700.0667028,60.319942474365234,-0.006109200701590046,1739502700.0667064,60.319942474365234,2.445550031794864,1739502700.06671,60.319942474365234,0.0,1739502700.0667136,60.319942474365234,0.05371170515556978,1739502700.0667174,60.319942474365234,3.1647495966841164,1739502700.066721,60.319942474365234,2.391838326639294 +1739502700.0842612,60.33994245529175,12.508294359948373,1739502700.084264,60.33994245529175,0.09020671977515615,1739502700.084267,60.33994245529175,99.9172609210188,1739502700.0842698,60.33994245529175,6.626846321444638,1739502700.0842714,60.33994245529175,-0.018480765421712786,1739502700.0842733,60.33994245529175,-3.1231150414837954,1739502700.084275,60.33994245529175,-0.027525840460198767,1739502700.0842762,60.33994245529175,-0.006109200701590046,1739502700.0842779,60.33994245529175,2.445550031794864,1739502700.0842793,60.33994245529175,0.0,1739502700.0842807,60.33994245529175,0.05371170515556978,1739502700.0842824,60.33994245529175,3.1647495966841164,1739502700.0842838,60.33994245529175,2.391838326639294 +1739502700.1043282,60.35994243621826,12.244988261261025,1739502700.1043313,60.35994243621826,0.08399383370388325,1739502700.1043346,60.35994243621826,100.28357824945135,1739502700.104338,60.35994243621826,6.249147432840361,1739502700.1043391,60.35994243621826,-0.020668372175776512,1739502700.104341,60.35994243621826,-3.1241386249636616,1739502700.1043425,60.35994243621826,-0.03992660115256156,1739502700.1043441,60.35994243621826,-0.008526874876184148,1739502700.1043453,60.35994243621826,2.4214086339059766,1739502700.1043472,60.35994243621826,0.0,1739502700.1043484,60.35994243621826,0.010309546057800364,1739502700.10435,60.35994243621826,3.1657047666640428,1739502700.1043518,60.35994243621826,2.397535904237407 +1739502700.1247442,60.379942417144775,12.244988261261025,1739502700.1247468,60.379942417144775,0.08399383370388325,1739502700.1247504,60.379942417144775,100.28357824945135,1739502700.1247535,60.379942417144775,6.249147432840361,1739502700.1247551,60.379942417144775,-0.020668372175776512,1739502700.124757,60.379942417144775,-3.1241386249636616,1739502700.1247585,60.379942417144775,-0.03992660115256156,1739502700.1247602,60.379942417144775,-0.008526874876184148,1739502700.1247616,60.379942417144775,2.4214086339059766,1739502700.1247635,60.379942417144775,0.0,1739502700.124765,60.379942417144775,0.02387272966856946,1739502700.1247663,60.379942417144775,3.1657047666640428,1739502700.124768,60.379942417144775,2.397535904237407 +1739502700.1447368,60.39994239807129,12.244988261261025,1739502700.1447399,60.39994239807129,0.08399383370388325,1739502700.144744,60.39994239807129,100.28357824945135,1739502700.1447473,60.39994239807129,6.249147432840361,1739502700.1447487,60.39994239807129,-0.020668372175776512,1739502700.144751,60.39994239807129,-3.1241386249636616,1739502700.1447527,60.39994239807129,-0.03992660115256156,1739502700.1447544,60.39994239807129,-0.008526874876184148,1739502700.1447556,60.39994239807129,2.4214086339059766,1739502700.1447575,60.39994239807129,0.0,1739502700.1447597,60.39994239807129,0.02387272966856946,1739502700.1447613,60.39994239807129,3.1657047666640428,1739502700.144763,60.39994239807129,2.397535904237407 +1739502700.1649227,60.4199423789978,12.244988261261025,1739502700.1649265,60.4199423789978,0.08399383370388325,1739502700.16493,60.4199423789978,100.28357824945135,1739502700.1649334,60.4199423789978,6.249147432840361,1739502700.1649349,60.4199423789978,-0.020668372175776512,1739502700.164937,60.4199423789978,-3.1241386249636616,1739502700.1649387,60.4199423789978,-0.03992660115256156,1739502700.1649404,60.4199423789978,-0.008526874876184148,1739502700.164942,60.4199423789978,2.4214086339059766,1739502700.1649442,60.4199423789978,0.0,1739502700.1649456,60.4199423789978,0.02387272966856946,1739502700.1649475,60.4199423789978,3.1657047666640428,1739502700.1649492,60.4199423789978,2.397535904237407 +1739502700.1844833,60.439942359924316,12.244988261261025,1739502700.1844866,60.439942359924316,0.08399383370388325,1739502700.1844897,60.439942359924316,100.28357824945135,1739502700.184493,60.439942359924316,6.249147432840361,1739502700.1844945,60.439942359924316,-0.020668372175776512,1739502700.1844966,60.439942359924316,-3.1241386249636616,1739502700.184498,60.439942359924316,-0.03992660115256156,1739502700.1844997,60.439942359924316,-0.008526874876184148,1739502700.1845012,60.439942359924316,2.4214086339059766,1739502700.184503,60.439942359924316,0.0,1739502700.1845047,60.439942359924316,0.02387272966856946,1739502700.1845064,60.439942359924316,3.1657047666640428,1739502700.1845078,60.439942359924316,2.397535904237407 +1739502700.2045648,60.45994234085083,11.98120171574094,1739502700.204568,60.45994234085083,0.07751753271893502,1739502700.2045715,60.45994234085083,100.5228570618227,1739502700.2045743,60.45994234085083,6.004606209213242,1739502700.2045763,60.45994234085083,-0.021929572136914426,1739502700.2045784,60.45994234085083,-3.124954765299653,1739502700.2045798,60.45994234085083,-0.05038545993354473,1739502700.2045813,60.45994234085083,-0.010830203224755112,1739502700.204583,60.45994234085083,2.401233020405122,1739502700.2045846,60.45994234085083,0.0,1739502700.2045863,60.45994234085083,-0.009305071445733925,1739502700.204588,60.45994234085083,3.166659936643969,1739502700.2045896,60.45994234085083,2.4001700222048 +1739502700.224465,60.479942321777344,11.98120171574094,1739502700.2244675,60.479942321777344,0.07751753271893502,1739502700.2244709,60.479942321777344,100.5228570618227,1739502700.2244742,60.479942321777344,6.004606209213242,1739502700.2244756,60.479942321777344,-0.021929572136914426,1739502700.2244778,60.479942321777344,-3.124954765299653,1739502700.2244792,60.479942321777344,-0.05038545993354473,1739502700.2244809,60.479942321777344,-0.010830203224755112,1739502700.2244823,60.479942321777344,2.401233020405122,1739502700.2244842,60.479942321777344,0.0,1739502700.2244856,60.479942321777344,0.001062998200322074,1739502700.224487,60.479942321777344,3.166659936643969,1739502700.224489,60.479942321777344,2.4001700222048 +1739502700.2443173,60.49994230270386,11.98120171574094,1739502700.24432,60.49994230270386,0.07751753271893502,1739502700.244323,60.49994230270386,100.5228570618227,1739502700.2443264,60.49994230270386,6.004606209213242,1739502700.244328,60.49994230270386,-0.021929572136914426,1739502700.24433,60.49994230270386,-3.124954765299653,1739502700.2443316,60.49994230270386,-0.05038545993354473,1739502700.244333,60.49994230270386,-0.010830203224755112,1739502700.2443347,60.49994230270386,2.401233020405122,1739502700.2443364,60.49994230270386,0.0,1739502700.244338,60.49994230270386,0.001062998200322074,1739502700.2443397,60.49994230270386,3.166659936643969,1739502700.2443411,60.49994230270386,2.4001700222048 +1739502700.2651584,60.51994228363037,11.98120171574094,1739502700.2651618,60.51994228363037,0.07751753271893502,1739502700.2651658,60.51994228363037,100.5228570618227,1739502700.2651694,60.51994228363037,6.004606209213242,1739502700.2651715,60.51994228363037,-0.021929572136914426,1739502700.2651737,60.51994228363037,-3.124954765299653,1739502700.2651756,60.51994228363037,-0.05038545993354473,1739502700.2651772,60.51994228363037,-0.010830203224755112,1739502700.265179,60.51994228363037,2.401233020405122,1739502700.2651813,60.51994228363037,0.0,1739502700.2651827,60.51994228363037,0.001062998200322074,1739502700.2651842,60.51994228363037,3.166659936643969,1739502700.265186,60.51994228363037,2.4001700222048 +1739502700.2845328,60.539942264556885,11.98120171574094,1739502700.284536,60.539942264556885,0.07751753271893502,1739502700.2845395,60.539942264556885,100.5228570618227,1739502700.2845428,60.539942264556885,6.004606209213242,1739502700.2845442,60.539942264556885,-0.021929572136914426,1739502700.2845464,60.539942264556885,-3.124954765299653,1739502700.2845478,60.539942264556885,-0.05038545993354473,1739502700.2845495,60.539942264556885,-0.010830203224755112,1739502700.284551,60.539942264556885,2.401233020405122,1739502700.284553,60.539942264556885,0.0,1739502700.2845545,60.539942264556885,0.001062998200322074,1739502700.2845562,60.539942264556885,3.166659936643969,1739502700.2845576,60.539942264556885,2.4001700222048 +1739502700.3045008,60.5599422454834,11.98120171574094,1739502700.3045034,60.5599422454834,0.07751753271893502,1739502700.3045068,60.5599422454834,100.5228570618227,1739502700.30451,60.5599422454834,6.004606209213242,1739502700.3045118,60.5599422454834,-0.021929572136914426,1739502700.3045137,60.5599422454834,-3.124954765299653,1739502700.304516,60.5599422454834,-0.05038545993354473,1739502700.3045177,60.5599422454834,-0.010830203224755112,1739502700.3045192,60.5599422454834,2.401233020405122,1739502700.3045208,60.5599422454834,0.0,1739502700.3045225,60.5599422454834,0.001062998200322074,1739502700.304524,60.5599422454834,3.166659936643969,1739502700.3045256,60.5599422454834,2.4001700222048 +1739502700.324791,60.57994222640991,11.717282650855442,1739502700.3247936,60.57994222640991,0.07078575444751056,1739502700.3247972,60.57994222640991,100.67079260052253,1739502700.3248,60.57994222640991,5.85684915726137,1739502700.3248017,60.57994222640991,-0.022,1739502700.3248036,60.57994222640991,-3.1257614010326567,1739502700.324805,60.57994222640991,-0.0597313038065891,1739502700.3248067,60.57994222640991,-0.013353404712924885,1739502700.3248081,60.57994222640991,2.383346729589716,1739502700.32481,60.57994222640991,0.0,1739502700.3248115,60.57994222640991,-0.024823861100592426,1739502700.3248134,60.57994222640991,3.1676151066238956,1739502700.3248148,60.57994222640991,2.4000809418547857 +1739502700.344627,60.599942207336426,11.717282650855442,1739502700.3446295,60.599942207336426,0.07078575444751056,1739502700.3446333,60.599942207336426,100.67079260052253,1739502700.3446364,60.599942207336426,5.85684915726137,1739502700.344638,60.599942207336426,-0.022,1739502700.3446403,60.599942207336426,-3.1257614010326567,1739502700.3446417,60.599942207336426,-0.0597313038065891,1739502700.3446434,60.599942207336426,-0.013353404712924885,1739502700.3446448,60.599942207336426,2.383346729589716,1739502700.3446467,60.599942207336426,0.0,1739502700.3446481,60.599942207336426,-0.016734212265069548,1739502700.34465,60.599942207336426,3.1676151066238956,1739502700.3446515,60.599942207336426,2.4000809418547857 +1739502700.3649287,60.61994218826294,11.717282650855442,1739502700.3649318,60.61994218826294,0.07078575444751056,1739502700.3649354,60.61994218826294,100.67079260052253,1739502700.3649387,60.61994218826294,5.85684915726137,1739502700.3649404,60.61994218826294,-0.022,1739502700.3649426,60.61994218826294,-3.1257614010326567,1739502700.3649445,60.61994218826294,-0.0597313038065891,1739502700.364946,60.61994218826294,-0.013353404712924885,1739502700.3649476,60.61994218826294,2.383346729589716,1739502700.3649492,60.61994218826294,0.0,1739502700.3649511,60.61994218826294,-0.016734212265069548,1739502700.3649528,60.61994218826294,3.1676151066238956,1739502700.3649547,60.61994218826294,2.4000809418547857 +1739502700.3889248,60.63994216918945,11.717282650855442,1739502700.3889332,60.63994216918945,0.07078575444751056,1739502700.3889434,60.63994216918945,100.67079260052253,1739502700.3889534,60.63994216918945,5.85684915726137,1739502700.388958,60.63994216918945,-0.022,1739502700.3889644,60.63994216918945,-3.1257614010326567,1739502700.3889692,60.63994216918945,-0.0597313038065891,1739502700.3889744,60.63994216918945,-0.013353404712924885,1739502700.388979,60.63994216918945,2.383346729589716,1739502700.3889847,60.63994216918945,0.0,1739502700.3889894,60.63994216918945,-0.016734212265069548,1739502700.3889945,60.63994216918945,3.1676151066238956,1739502700.3889997,60.63994216918945,2.4000809418547857 +1739502700.4089696,60.65994215011597,11.717282650855442,1739502700.4089777,60.65994215011597,0.07078575444751056,1739502700.408987,60.65994215011597,100.67079260052253,1739502700.4089968,60.65994215011597,5.85684915726137,1739502700.4090016,60.65994215011597,-0.022,1739502700.4090073,60.65994215011597,-3.1257614010326567,1739502700.4090126,60.65994215011597,-0.0597313038065891,1739502700.4090173,60.65994215011597,-0.013353404712924885,1739502700.4090219,60.65994215011597,2.383346729589716,1739502700.4090276,60.65994215011597,0.0,1739502700.4090323,60.65994215011597,-0.016734212265069548,1739502700.4090378,60.65994215011597,3.1676151066238956,1739502700.4090426,60.65994215011597,2.4000809418547857 +1739502700.4319165,60.67994213104248,11.45345385982394,1739502700.4319248,60.67994213104248,0.06380412366758303,1739502700.4319353,60.67994213104248,101.00232154603299,1739502700.4319453,60.67994213104248,5.528956726767972,1739502700.43195,60.67994213104248,-0.023,1739502700.431956,60.67994213104248,-3.1269419733694623,1739502700.4319613,60.67994213104248,-0.07303692597481282,1739502700.4319663,60.67994213104248,-0.015977300053280543,1739502700.4319708,60.67994213104248,2.3581117458605183,1739502700.431976,60.67994213104248,0.0,1739502700.4319813,60.67994213104248,-0.05079834555700273,1739502700.4319863,60.67994213104248,3.168570276603822,1739502700.4319918,60.67994213104248,2.398265042784354 +1739502700.454317,60.699942111968994,11.45345385982394,1739502700.4543257,60.699942111968994,0.06380412366758303,1739502700.4543357,60.699942111968994,101.00232154603299,1739502700.454346,60.699942111968994,5.528956726767972,1739502700.4543512,60.699942111968994,-0.023,1739502700.4543571,60.699942111968994,-3.1269419733694623,1739502700.4543624,60.699942111968994,-0.07303692597481282,1739502700.4543672,60.699942111968994,-0.015977300053280543,1739502700.454372,60.699942111968994,2.3581117458605183,1739502700.4543774,60.699942111968994,0.0,1739502700.4543824,60.699942111968994,-0.040153296923835846,1739502700.4543874,60.699942111968994,3.168570276603822,1739502700.4543927,60.699942111968994,2.398265042784354 +1739502700.4817638,60.71994209289551,11.45345385982394,1739502700.4817712,60.71994209289551,0.06380412366758303,1739502700.4817805,60.71994209289551,101.00232154603299,1739502700.4817896,60.71994209289551,5.528956726767972,1739502700.4817944,60.71994209289551,-0.023,1739502700.4817996,60.71994209289551,-3.1269419733694623,1739502700.4818044,60.71994209289551,-0.07303692597481282,1739502700.4818084,60.71994209289551,-0.015977300053280543,1739502700.4818127,60.71994209289551,2.3581117458605183,1739502700.481818,60.71994209289551,0.0,1739502700.481822,60.71994209289551,-0.040153296923835846,1739502700.4818265,60.71994209289551,3.168570276603822,1739502700.4818308,60.71994209289551,2.398265042784354 +1739502700.4995384,60.74994206428528,11.45345385982394,1739502700.499542,60.74994206428528,0.06380412366758303,1739502700.4995465,60.74994206428528,101.00232154603299,1739502700.499551,60.74994206428528,5.528956726767972,1739502700.4995532,60.74994206428528,-0.023,1739502700.4995558,60.74994206428528,-3.1269419733694623,1739502700.499558,60.74994206428528,-0.07303692597481282,1739502700.49956,60.74994206428528,-0.015977300053280543,1739502700.4995623,60.74994206428528,2.3581117458605183,1739502700.499565,60.74994206428528,0.0,1739502700.4995668,60.74994206428528,-0.040153296923835846,1739502700.499569,60.74994206428528,3.168570276603822,1739502700.499571,60.74994206428528,2.398265042784354 +1739502700.5168912,60.76994204521179,11.45345385982394,1739502700.5168934,60.76994204521179,0.06380412366758303,1739502700.516897,60.76994204521179,101.00232154603299,1739502700.5168998,60.76994204521179,5.528956726767972,1739502700.5169015,60.76994204521179,-0.023,1739502700.5169032,60.76994204521179,-3.1269419733694623,1739502700.5169046,60.76994204521179,-0.07303692597481282,1739502700.516906,60.76994204521179,-0.015977300053280543,1739502700.5169075,60.76994204521179,2.3581117458605183,1739502700.5169091,60.76994204521179,0.0,1739502700.5169106,60.76994204521179,-0.040153296923835846,1739502700.516912,60.76994204521179,3.168570276603822,1739502700.5169134,60.76994204521179,2.398265042784354 +1739502700.53802,60.789942026138306,11.189984068248583,1739502700.538022,60.789942026138306,0.05658017475817889,1739502700.538025,60.789942026138306,101.4513854975948,1739502700.5380275,60.789942026138306,5.089111251272517,1739502700.5380287,60.789942026138306,-0.024,1739502700.5380304,60.789942026138306,-3.1283854467011167,1739502700.5380316,60.789942026138306,-0.08984351679937971,1739502700.538033,60.789942026138306,-0.018534579540481606,1739502700.5380342,60.789942026138306,2.326618482663202,1739502700.5380356,60.789942026138306,0.0,1739502700.5380368,60.789942026138306,-0.07926172618346299,1739502700.538038,60.789942026138306,3.1695254465837484,1739502700.5380394,60.789942026138306,2.3936588166900625 +1739502700.5567398,60.80994200706482,11.189984068248583,1739502700.5567422,60.80994200706482,0.05658017475817889,1739502700.556745,60.80994200706482,101.4513854975948,1739502700.5567477,60.80994200706482,5.089111251272517,1739502700.556749,60.80994200706482,-0.024,1739502700.5567508,60.80994200706482,-3.1283854467011167,1739502700.5567522,60.80994200706482,-0.08984351679937971,1739502700.5567536,60.80994200706482,-0.018534579540481606,1739502700.5567546,60.80994200706482,2.326618482663202,1739502700.5567563,60.80994200706482,0.0,1739502700.5567575,60.80994200706482,-0.06704033402686038,1739502700.556759,60.80994200706482,3.1695254465837484,1739502700.5567603,60.80994200706482,2.3936588166900625 +1739502700.5770512,60.82994198799133,11.189984068248583,1739502700.5770535,60.82994198799133,0.05658017475817889,1739502700.5770564,60.82994198799133,101.4513854975948,1739502700.577059,60.82994198799133,5.089111251272517,1739502700.5770605,60.82994198799133,-0.024,1739502700.5770624,60.82994198799133,-3.1283854467011167,1739502700.5770638,60.82994198799133,-0.08984351679937971,1739502700.577065,60.82994198799133,-0.018534579540481606,1739502700.5770662,60.82994198799133,2.326618482663202,1739502700.5770679,60.82994198799133,0.0,1739502700.577069,60.82994198799133,-0.06704033402686038,1739502700.5770702,60.82994198799133,3.1695254465837484,1739502700.5770717,60.82994198799133,2.3936588166900625 +1739502700.5965626,60.84994196891785,11.189984068248583,1739502700.5965648,60.84994196891785,0.05658017475817889,1739502700.5965676,60.84994196891785,101.4513854975948,1739502700.59657,60.84994196891785,5.089111251272517,1739502700.5965717,60.84994196891785,-0.024,1739502700.596573,60.84994196891785,-3.1283854467011167,1739502700.5965748,60.84994196891785,-0.08984351679937971,1739502700.596576,60.84994196891785,-0.018534579540481606,1739502700.5965772,60.84994196891785,2.326618482663202,1739502700.596579,60.84994196891785,0.0,1739502700.5965803,60.84994196891785,-0.06704033402686038,1739502700.596582,60.84994196891785,3.1695254465837484,1739502700.5965831,60.84994196891785,2.3936588166900625 +1739502700.6168778,60.86994194984436,11.189984068248583,1739502700.61688,60.86994194984436,0.05658017475817889,1739502700.6168828,60.86994194984436,101.4513854975948,1739502700.6168852,60.86994194984436,5.089111251272517,1739502700.6168866,60.86994194984436,-0.024,1739502700.6168883,60.86994194984436,-3.1283854467011167,1739502700.6168897,60.86994194984436,-0.08984351679937971,1739502700.6168911,60.86994194984436,-0.018534579540481606,1739502700.6168926,60.86994194984436,2.326618482663202,1739502700.6168942,60.86994194984436,0.0,1739502700.6168954,60.86994194984436,-0.06704033402686038,1739502700.616897,60.86994194984436,3.1695254465837484,1739502700.6168983,60.86994194984436,2.3936588166900625 +1739502700.6372528,60.889941930770874,11.189984068248583,1739502700.6372554,60.889941930770874,0.05658017475817889,1739502700.637259,60.889941930770874,101.4513854975948,1739502700.6372616,60.889941930770874,5.089111251272517,1739502700.637263,60.889941930770874,-0.024,1739502700.637265,60.889941930770874,-3.1283854467011167,1739502700.6372666,60.889941930770874,-0.08984351679937971,1739502700.637268,60.889941930770874,-0.018534579540481606,1739502700.6372695,60.889941930770874,2.326618482663202,1739502700.637271,60.889941930770874,0.0,1739502700.6372724,60.889941930770874,-0.06704033402686038,1739502700.6372738,60.889941930770874,3.1695254465837484,1739502700.637275,60.889941930770874,2.3936588166900625 +1739502700.657186,60.90994191169739,10.927177923122116,1739502700.6571894,60.90994191169739,0.049131025558600605,1739502700.6571925,60.90994191169739,101.79718483207785,1739502700.6571953,60.90994191169739,4.758478047276896,1739502700.6571968,60.90994191169739,-0.025,1739502700.6571987,60.90994191169739,-3.1295759468586892,1739502700.6571999,60.90994191169739,-0.10362898554056067,1739502700.657201,60.90994191169739,-0.020911512044356383,1739502700.6572025,60.90994191169739,2.3011006304262756,1739502700.657204,60.90994191169739,0.0,1739502700.6572056,60.90994191169739,-0.09313083506859844,1739502700.6572068,60.90994191169739,3.1704080990216457,1739502700.6572082,60.90994191169739,2.3860781785736194 +1739502700.6772764,60.9299418926239,10.927177923122116,1739502700.6772795,60.9299418926239,0.049131025558600605,1739502700.6772826,60.9299418926239,101.79718483207785,1739502700.6772854,60.9299418926239,4.758478047276896,1739502700.677287,60.9299418926239,-0.025,1739502700.6772888,60.9299418926239,-3.1295759468586892,1739502700.6772907,60.9299418926239,-0.10362898554056067,1739502700.677292,60.9299418926239,-0.020911512044356383,1739502700.6772933,60.9299418926239,2.3011006304262756,1739502700.6772952,60.9299418926239,0.0,1739502700.6772964,60.9299418926239,-0.08497754814734382,1739502700.6772978,60.9299418926239,3.1704080990216457,1739502700.6772995,60.9299418926239,2.3860781785736194 +1739502700.696938,60.949941873550415,10.927177923122116,1739502700.6969402,60.949941873550415,0.049131025558600605,1739502700.696943,60.949941873550415,101.79718483207785,1739502700.6969457,60.949941873550415,4.758478047276896,1739502700.696947,60.949941873550415,-0.025,1739502700.6969488,60.949941873550415,-3.1295759468586892,1739502700.6969502,60.949941873550415,-0.10362898554056067,1739502700.696952,60.949941873550415,-0.020911512044356383,1739502700.6969533,60.949941873550415,2.3011006304262756,1739502700.696955,60.949941873550415,0.0,1739502700.6969562,60.949941873550415,-0.08497754814734382,1739502700.6969573,60.949941873550415,3.1704080990216457,1739502700.696959,60.949941873550415,2.3860781785736194 +1739502700.717334,60.96994185447693,10.927177923122116,1739502700.7173362,60.96994185447693,0.049131025558600605,1739502700.7173388,60.96994185447693,101.79718483207785,1739502700.7173417,60.96994185447693,4.758478047276896,1739502700.717343,60.96994185447693,-0.025,1739502700.7173448,60.96994185447693,-3.1295759468586892,1739502700.7173457,60.96994185447693,-0.10362898554056067,1739502700.7173474,60.96994185447693,-0.020911512044356383,1739502700.7173486,60.96994185447693,2.3011006304262756,1739502700.7173502,60.96994185447693,0.0,1739502700.7173514,60.96994185447693,-0.08497754814734382,1739502700.7173526,60.96994185447693,3.1704080990216457,1739502700.717354,60.96994185447693,2.3860781785736194 +1739502700.741153,60.98994183540344,10.927177923122116,1739502700.7411618,60.98994183540344,0.049131025558600605,1739502700.7411726,60.98994183540344,101.79718483207785,1739502700.7411828,60.98994183540344,4.758478047276896,1739502700.7411876,60.98994183540344,-0.025,1739502700.7411938,60.98994183540344,-3.1295759468586892,1739502700.7411985,60.98994183540344,-0.10362898554056067,1739502700.7412035,60.98994183540344,-0.020911512044356383,1739502700.741208,60.98994183540344,2.3011006304262756,1739502700.7412133,60.98994183540344,0.0,1739502700.7412186,60.98994183540344,-0.08497754814734382,1739502700.7412236,60.98994183540344,3.1704080990216457,1739502700.7412288,60.98994183540344,2.3860781785736194 +1739502700.7619507,61.009941816329956,10.665282162575256,1739502700.7619588,61.009941816329956,0.041484292270824064,1739502700.761969,61.009941816329956,101.82835042758292,1739502700.7619793,61.009941816329956,4.745869984131076,1739502700.7619843,61.009941816329956,-0.025,1739502700.7619905,61.009941816329956,-3.130361555829668,1739502700.761996,61.009941816329956,-0.10888475082861918,1739502700.7620008,61.009941816329956,-0.023862018466605878,1739502700.7620056,61.009941816329956,2.291445706401838,1739502700.7620108,61.009941816329956,0.0,1739502700.7620158,61.009941816329956,-0.0855246869937631,1739502700.7620208,61.009941816329956,3.1712181493928826,1739502700.762026,61.009941816329956,2.376799412393991 +1739502700.7924173,61.02994179725647,10.665282162575256,1739502700.7924256,61.02994179725647,0.041484292270824064,1739502700.7924364,61.02994179725647,101.82835042758292,1739502700.7924466,61.02994179725647,4.745869984131076,1739502700.7924516,61.02994179725647,-0.025,1739502700.7924578,61.02994179725647,-3.130361555829668,1739502700.7924626,61.02994179725647,-0.10888475082861918,1739502700.7924674,61.02994179725647,-0.023862018466605878,1739502700.7924721,61.02994179725647,2.291445706401838,1739502700.7924776,61.02994179725647,0.0,1739502700.7924826,61.02994179725647,-0.0853537059921532,1739502700.7924879,61.02994179725647,3.1712181493928826,1739502700.7924929,61.02994179725647,2.376799412393991 +1739502700.8133056,61.05994176864624,10.665282162575256,1739502700.813314,61.05994176864624,0.041484292270824064,1739502700.8133247,61.05994176864624,101.82835042758292,1739502700.8133352,61.05994176864624,4.745869984131076,1739502700.8133402,61.05994176864624,-0.025,1739502700.8133469,61.05994176864624,-3.130361555829668,1739502700.813352,61.05994176864624,-0.10888475082861918,1739502700.813357,61.05994176864624,-0.023862018466605878,1739502700.8133616,61.05994176864624,2.291445706401838,1739502700.8133674,61.05994176864624,0.0,1739502700.813372,61.05994176864624,-0.0853537059921532,1739502700.8133776,61.05994176864624,3.1712181493928826,1739502700.8133826,61.05994176864624,2.376799412393991 +1739502700.8623586,61.09994173049927,10.665282162575256,1739502700.8623638,61.09994173049927,0.041484292270824064,1739502700.8623698,61.09994173049927,101.82835042758292,1739502700.8623753,61.09994173049927,4.745869984131076,1739502700.862378,61.09994173049927,-0.025,1739502700.8623812,61.09994173049927,-3.130361555829668,1739502700.862384,61.09994173049927,-0.10888475082861918,1739502700.8623867,61.09994173049927,-0.023862018466605878,1739502700.8623893,61.09994173049927,2.291445706401838,1739502700.8623927,61.09994173049927,0.0,1739502700.862395,61.09994173049927,-0.0853537059921532,1739502700.862398,61.09994173049927,3.1712181493928826,1739502700.8624008,61.09994173049927,2.376799412393991 +1739502700.8821187,61.11994171142578,10.404419540983893,1739502700.8821237,61.11994171142578,0.033673471421997725,1739502700.8821301,61.11994171142578,102.15350549412622,1739502700.8821359,61.11994171142578,4.439412591434963,1739502700.8821387,61.11994171142578,-0.025910356272047966,1739502700.882142,61.11994171142578,-3.1316040908609,1739502700.8821447,61.11994171142578,-0.1210532374258982,1739502700.8821473,61.11994171142578,-0.026125307513570874,1739502700.88215,61.11994171142578,2.2692471895556685,1739502700.8821533,61.11994171142578,0.0,1739502700.8821557,61.11994171142578,-0.10404730776454085,1739502700.8821585,61.11994171142578,3.17187549411445,1739502700.8821616,61.11994171142578,2.3674527429361856 +1739502700.9020333,61.14994168281555,10.404419540983893,1739502700.9020383,61.14994168281555,0.033673471421997725,1739502700.902044,61.14994168281555,102.15350549412622,1739502700.9020493,61.14994168281555,4.439412591434963,1739502700.9020522,61.14994168281555,-0.025910356272047966,1739502700.9020555,61.14994168281555,-3.1316040908609,1739502700.9020581,61.14994168281555,-0.1210532374258982,1739502700.9020607,61.14994168281555,-0.026125307513570874,1739502700.9020634,61.14994168281555,2.2692471895556685,1739502700.9020665,61.14994168281555,0.0,1739502700.902069,61.14994168281555,-0.09820555338051706,1739502700.9020717,61.14994168281555,3.17187549411445,1739502700.9020748,61.14994168281555,2.3674527429361856 +1739502700.9242573,61.169941663742065,10.404419540983893,1739502700.9242623,61.169941663742065,0.033673471421997725,1739502700.9242685,61.169941663742065,102.15350549412622,1739502700.924274,61.169941663742065,4.439412591434963,1739502700.924276,61.169941663742065,-0.025910356272047966,1739502700.9242797,61.169941663742065,-3.1316040908609,1739502700.9242823,61.169941663742065,-0.1210532374258982,1739502700.9242852,61.169941663742065,-0.026125307513570874,1739502700.9242878,61.169941663742065,2.2692471895556685,1739502700.9242911,61.169941663742065,0.0,1739502700.9242935,61.169941663742065,-0.09820555338051706,1739502700.9242964,61.169941663742065,3.17187549411445,1739502700.9242995,61.169941663742065,2.3674527429361856 +1739502700.9414723,61.18994164466858,10.404419540983893,1739502700.9414775,61.18994164466858,0.033673471421997725,1739502700.9414833,61.18994164466858,102.15350549412622,1739502700.941489,61.18994164466858,4.439412591434963,1739502700.9414914,61.18994164466858,-0.025910356272047966,1739502700.9414947,61.18994164466858,-3.1316040908609,1739502700.9414976,61.18994164466858,-0.1210532374258982,1739502700.9415007,61.18994164466858,-0.026125307513570874,1739502700.9415033,61.18994164466858,2.2692471895556685,1739502700.9415069,61.18994164466858,0.0,1739502700.9415095,61.18994164466858,-0.09820555338051706,1739502700.9415128,61.18994164466858,3.17187549411445,1739502700.9415164,61.18994164466858,2.3674527429361856 +1739502700.9606621,61.20994162559509,10.404419540983893,1739502700.9606657,61.20994162559509,0.033673471421997725,1739502700.9606698,61.20994162559509,102.15350549412622,1739502700.9606833,61.20994162559509,4.439412591434963,1739502700.960685,61.20994162559509,-0.025910356272047966,1739502700.9606879,61.20994162559509,-3.1316040908609,1739502700.96069,61.20994162559509,-0.1210532374258982,1739502700.9606917,61.20994162559509,-0.026125307513570874,1739502700.960694,61.20994162559509,2.2692471895556685,1739502700.9606962,61.20994162559509,0.0,1739502700.9606981,61.20994162559509,-0.09820555338051706,1739502700.9607003,61.20994162559509,3.17187549411445,1739502700.960702,61.20994162559509,2.3674527429361856 +1739502700.9802406,61.229941606521606,10.14467520191236,1739502700.980243,61.229941606521606,0.0257379665017492,1739502700.980246,61.229941606521606,103.02852885236695,1739502700.980249,61.229941606521606,3.5862671148040484,1739502700.9802504,61.229941606521606,-0.02648630087082637,1739502700.9802518,61.229941606521606,-3.1336298731560035,1739502700.9802532,61.229941606521606,-0.15006620290899422,1739502700.9802547,61.229941606521606,-0.026792186483575606,1739502700.980256,61.229941606521606,2.2171836614766987,1739502700.9802577,61.229941606521606,0.0,1739502700.9802592,61.229941606521606,-0.15804496509107224,1739502700.9802604,61.229941606521606,3.172438203758676,1739502700.9802618,61.229941606521606,2.3565287981476595 +1739502701.000042,61.24994158744812,10.14467520191236,1739502701.0000443,61.24994158744812,0.0257379665017492,1739502701.0000467,61.24994158744812,103.02852885236695,1739502701.000049,61.24994158744812,3.5862671148040484,1739502701.0000505,61.24994158744812,-0.02648630087082637,1739502701.000052,61.24994158744812,-3.1336298731560035,1739502701.0000532,61.24994158744812,-0.15006620290899422,1739502701.0000546,61.24994158744812,-0.026792186483575606,1739502701.0000556,61.24994158744812,2.2171836614766987,1739502701.000057,61.24994158744812,0.0,1739502701.0000582,61.24994158744812,-0.13934513667096082,1739502701.0000594,61.24994158744812,3.172438203758676,1739502701.0000606,61.24994158744812,2.3565287981476595 +1739502701.02053,61.269941568374634,10.14467520191236,1739502701.0205321,61.269941568374634,0.0257379665017492,1739502701.0205352,61.269941568374634,103.02852885236695,1739502701.0205376,61.269941568374634,3.5862671148040484,1739502701.0205388,61.269941568374634,-0.02648630087082637,1739502701.0205405,61.269941568374634,-3.1336298731560035,1739502701.0205417,61.269941568374634,-0.15006620290899422,1739502701.0205433,61.269941568374634,-0.026792186483575606,1739502701.0205443,61.269941568374634,2.2171836614766987,1739502701.0205457,61.269941568374634,0.0,1739502701.0205472,61.269941568374634,-0.13934513667096082,1739502701.0205483,61.269941568374634,3.172438203758676,1739502701.0205495,61.269941568374634,2.3565287981476595 +1739502701.0411117,61.28994154930115,10.14467520191236,1739502701.0411158,61.28994154930115,0.0257379665017492,1739502701.0411186,61.28994154930115,103.02852885236695,1739502701.0411217,61.28994154930115,3.5862671148040484,1739502701.0411232,61.28994154930115,-0.02648630087082637,1739502701.041125,61.28994154930115,-3.1336298731560035,1739502701.0411265,61.28994154930115,-0.15006620290899422,1739502701.0411282,61.28994154930115,-0.026792186483575606,1739502701.04113,61.28994154930115,2.2171836614766987,1739502701.0411315,61.28994154930115,0.0,1739502701.0411332,61.28994154930115,-0.13934513667096082,1739502701.0411346,61.28994154930115,3.172438203758676,1739502701.041136,61.28994154930115,2.3565287981476595 +1739502701.0806382,61.329941511154175,10.14467520191236,1739502701.0806417,61.329941511154175,0.0257379665017492,1739502701.0806448,61.329941511154175,103.02852885236695,1739502701.0806482,61.329941511154175,3.5862671148040484,1739502701.0806494,61.329941511154175,-0.02648630087082637,1739502701.0806515,61.329941511154175,-3.1336298731560035,1739502701.080653,61.329941511154175,-0.15006620290899422,1739502701.0806546,61.329941511154175,-0.026792186483575606,1739502701.080656,61.329941511154175,2.2171836614766987,1739502701.0806582,61.329941511154175,0.0,1739502701.0806594,61.329941511154175,-0.13934513667096082,1739502701.0806613,61.329941511154175,3.172438203758676,1739502701.080663,61.329941511154175,2.3565287981476595 +1739502701.1000218,61.34994149208069,9.886381535540163,1739502701.1000242,61.34994149208069,0.01770303361464798,1739502701.1000273,61.34994149208069,103.03472790035987,1739502701.10003,61.34994149208069,3.6113009637772526,1739502701.1000314,61.34994149208069,-0.02715826178424517,1739502701.1000333,61.34994149208069,-3.1344436567563823,1739502701.1000347,61.34994149208069,-0.15217210767934816,1739502701.1000361,61.34994149208069,-0.029677089052725106,1739502701.1000376,61.34994149208069,2.2134514641007943,1739502701.1000392,61.34994149208069,0.0,1739502701.1000404,61.34994149208069,-0.12204741063736417,1739502701.1000423,61.34994149208069,3.1729936317115612,1739502701.1000438,61.34994149208069,2.3409044176678075 +1739502701.1212947,61.3699414730072,9.886381535540163,1739502701.1212978,61.3699414730072,0.01770303361464798,1739502701.121301,61.3699414730072,103.03472790035987,1739502701.121304,61.3699414730072,3.6113009637772526,1739502701.1213057,61.3699414730072,-0.02715826178424517,1739502701.1213074,61.3699414730072,-3.1344436567563823,1739502701.1213093,61.3699414730072,-0.15217210767934816,1739502701.1213105,61.3699414730072,-0.029677089052725106,1739502701.1213117,61.3699414730072,2.2134514641007943,1739502701.1213136,61.3699414730072,0.0,1739502701.1213145,61.3699414730072,-0.12745295356701325,1739502701.1213162,61.3699414730072,3.1729936317115612,1739502701.1213176,61.3699414730072,2.3409044176678075 +1739502701.1416483,61.389941453933716,9.886381535540163,1739502701.141651,61.389941453933716,0.01770303361464798,1739502701.1416543,61.389941453933716,103.03472790035987,1739502701.1416569,61.389941453933716,3.6113009637772526,1739502701.1416583,61.389941453933716,-0.02715826178424517,1739502701.14166,61.389941453933716,-3.1344436567563823,1739502701.1416616,61.389941453933716,-0.15217210767934816,1739502701.1416633,61.389941453933716,-0.029677089052725106,1739502701.1416645,61.389941453933716,2.2134514641007943,1739502701.1416664,61.389941453933716,0.0,1739502701.1416676,61.389941453933716,-0.12745295356701325,1739502701.1416688,61.389941453933716,3.1729936317115612,1739502701.1416705,61.389941453933716,2.3409044176678075 +1739502701.1603968,61.40994143486023,9.886381535540163,1739502701.1603997,61.40994143486023,0.01770303361464798,1739502701.1604028,61.40994143486023,103.03472790035987,1739502701.1604054,61.40994143486023,3.6113009637772526,1739502701.160407,61.40994143486023,-0.02715826178424517,1739502701.1604087,61.40994143486023,-3.1344436567563823,1739502701.1604104,61.40994143486023,-0.15217210767934816,1739502701.1604118,61.40994143486023,-0.029677089052725106,1739502701.1604133,61.40994143486023,2.2134514641007943,1739502701.1604147,61.40994143486023,0.0,1739502701.1604164,61.40994143486023,-0.12745295356701325,1739502701.1604178,61.40994143486023,3.1729936317115612,1739502701.1604192,61.40994143486023,2.3409044176678075 +1739502701.1802843,61.42994141578674,9.886381535540163,1739502701.180287,61.42994141578674,0.01770303361464798,1739502701.18029,61.42994141578674,103.03472790035987,1739502701.1802926,61.42994141578674,3.6113009637772526,1739502701.180294,61.42994141578674,-0.02715826178424517,1739502701.180296,61.42994141578674,-3.1344436567563823,1739502701.1802971,61.42994141578674,-0.15217210767934816,1739502701.1802988,61.42994141578674,-0.029677089052725106,1739502701.1803,61.42994141578674,2.2134514641007943,1739502701.1803017,61.42994141578674,0.0,1739502701.1803029,61.42994141578674,-0.12745295356701325,1739502701.180304,61.42994141578674,3.1729936317115612,1739502701.1803057,61.42994141578674,2.3409044176678075 +1739502701.2001793,61.44994139671326,9.629710479534776,1739502701.200182,61.44994139671326,0.009586756207608182,1739502701.2001848,61.44994139671326,103.040888005704,1739502701.2001877,61.44994139671326,3.6330353550819114,1739502701.200189,61.44994139671326,-0.027369275292057394,1739502701.200191,61.44994139671326,-3.135429977959421,1739502701.2001927,61.44994139671326,-0.15391884093791575,1739502701.2001944,61.44994139671326,-0.032869877751817406,1739502701.2001956,61.44994139671326,2.21036057675519,1739502701.2001972,61.44994139671326,0.0,1739502701.2001987,61.44994139671326,-0.11166113339096377,1739502701.2002,61.44994139671326,3.1734250244478277,1739502701.2002017,61.44994139671326,2.3269566571867726 +1739502701.2199357,61.46994137763977,9.629710479534776,1739502701.2199383,61.46994137763977,0.009586756207608182,1739502701.2199416,61.46994137763977,103.040888005704,1739502701.2199442,61.46994137763977,3.6330353550819114,1739502701.2199454,61.46994137763977,-0.027369275292057394,1739502701.2199476,61.46994137763977,-3.135429977959421,1739502701.2199488,61.46994137763977,-0.15391884093791575,1739502701.2199504,61.46994137763977,-0.032869877751817406,1739502701.2199516,61.46994137763977,2.21036057675519,1739502701.2199533,61.46994137763977,0.0,1739502701.2199547,61.46994137763977,-0.11659608043158265,1739502701.2199562,61.46994137763977,3.1734250244478277,1739502701.2199578,61.46994137763977,2.3269566571867726 +1739502701.2414048,61.489941358566284,9.629710479534776,1739502701.2414074,61.489941358566284,0.009586756207608182,1739502701.2414105,61.489941358566284,103.040888005704,1739502701.2414136,61.489941358566284,3.6330353550819114,1739502701.2414153,61.489941358566284,-0.027369275292057394,1739502701.241417,61.489941358566284,-3.135429977959421,1739502701.2414186,61.489941358566284,-0.15391884093791575,1739502701.24142,61.489941358566284,-0.032869877751817406,1739502701.2414212,61.489941358566284,2.21036057675519,1739502701.2414234,61.489941358566284,0.0,1739502701.2414248,61.489941358566284,-0.11659608043158265,1739502701.2414265,61.489941358566284,3.1734250244478277,1739502701.241428,61.489941358566284,2.3269566571867726 +1739502701.262578,61.5099413394928,9.629710479534776,1739502701.262583,61.5099413394928,0.009586756207608182,1739502701.2625878,61.5099413394928,103.040888005704,1739502701.2625937,61.5099413394928,3.6330353550819114,1739502701.2625976,61.5099413394928,-0.027369275292057394,1739502701.262602,61.5099413394928,-3.135429977959421,1739502701.2626054,61.5099413394928,-0.15391884093791575,1739502701.262609,61.5099413394928,-0.032869877751817406,1739502701.2626128,61.5099413394928,2.21036057675519,1739502701.2626164,61.5099413394928,0.0,1739502701.26262,61.5099413394928,-0.11659608043158265,1739502701.262624,61.5099413394928,3.1734250244478277,1739502701.2626278,61.5099413394928,2.3269566571867726 +1739502701.2822456,61.52994132041931,9.629710479534776,1739502701.2822504,61.52994132041931,0.009586756207608182,1739502701.282256,61.52994132041931,103.040888005704,1739502701.282261,61.52994132041931,3.6330353550819114,1739502701.2822645,61.52994132041931,-0.027369275292057394,1739502701.2822685,61.52994132041931,-3.135429977959421,1739502701.2822714,61.52994132041931,-0.15391884093791575,1739502701.2822745,61.52994132041931,-0.032869877751817406,1739502701.282279,61.52994132041931,2.21036057675519,1739502701.2822824,61.52994132041931,0.0,1739502701.282286,61.52994132041931,-0.11659608043158265,1739502701.2822895,61.52994132041931,3.1734250244478277,1739502701.2822933,61.52994132041931,2.3269566571867726 +1739502701.2999656,61.549941301345825,9.629710479534776,1739502701.2999685,61.549941301345825,0.009586756207608182,1739502701.2999713,61.549941301345825,103.040888005704,1739502701.2999742,61.549941301345825,3.6330353550819114,1739502701.2999754,61.549941301345825,-0.027369275292057394,1739502701.2999773,61.549941301345825,-3.135429977959421,1739502701.2999787,61.549941301345825,-0.15391884093791575,1739502701.29998,61.549941301345825,-0.032869877751817406,1739502701.2999814,61.549941301345825,2.21036057675519,1739502701.299983,61.549941301345825,0.0,1739502701.2999845,61.549941301345825,-0.11659608043158265,1739502701.299986,61.549941301345825,3.1734250244478277,1739502701.2999873,61.549941301345825,2.3269566571867726 +1739502701.3205235,61.56994128227234,9.374505712917289,1739502701.3205264,61.56994128227234,0.0014281594606737613,1739502701.3205295,61.56994128227234,103.04701292010283,1739502701.320532,61.56994128227234,3.652241720556503,1739502701.3205335,61.56994128227234,-0.027555744859771872,1739502701.320535,61.56994128227234,-3.13652758555049,1739502701.3205366,61.56994128227234,-0.15461784762539457,1739502701.3205378,61.56994128227234,-0.03626208490863744,1739502701.3205392,61.56994128227234,2.209124876832482,1739502701.3205407,61.56994128227234,0.0,1739502701.3205419,61.56994128227234,-0.09997004987754195,1739502701.3205435,61.56994128227234,3.173681061413053,1739502701.320545,61.56994128227234,2.314290564664687 +1739502701.3401496,61.58994126319885,9.374505712917289,1739502701.3401525,61.58994126319885,0.0014281594606737613,1739502701.3401554,61.58994126319885,103.04701292010283,1739502701.3401585,61.58994126319885,3.652241720556503,1739502701.3401597,61.58994126319885,-0.027555744859771872,1739502701.3401618,61.58994126319885,-3.13652758555049,1739502701.3401632,61.58994126319885,-0.15461784762539457,1739502701.3401647,61.58994126319885,-0.03626208490863744,1739502701.3401659,61.58994126319885,2.209124876832482,1739502701.3401678,61.58994126319885,0.0,1739502701.340169,61.58994126319885,-0.10516568783220537,1739502701.3401701,61.58994126319885,3.173681061413053,1739502701.3401718,61.58994126319885,2.314290564664687 +1739502701.3613017,61.609941244125366,9.374505712917289,1739502701.3613043,61.609941244125366,0.0014281594606737613,1739502701.3613071,61.609941244125366,103.04701292010283,1739502701.36131,61.609941244125366,3.652241720556503,1739502701.3613112,61.609941244125366,-0.027555744859771872,1739502701.361313,61.609941244125366,-3.13652758555049,1739502701.3613145,61.609941244125366,-0.15461784762539457,1739502701.3613157,61.609941244125366,-0.03626208490863744,1739502701.3613172,61.609941244125366,2.209124876832482,1739502701.361319,61.609941244125366,0.0,1739502701.3613205,61.609941244125366,-0.10516568783220537,1739502701.361322,61.609941244125366,3.173681061413053,1739502701.3613234,61.609941244125366,2.314290564664687 +1739502701.3800433,61.62994122505188,9.374505712917289,1739502701.3800461,61.62994122505188,0.0014281594606737613,1739502701.380049,61.62994122505188,103.04701292010283,1739502701.3800523,61.62994122505188,3.652241720556503,1739502701.3800535,61.62994122505188,-0.027555744859771872,1739502701.3800552,61.62994122505188,-3.13652758555049,1739502701.3800569,61.62994122505188,-0.15461784762539457,1739502701.3800583,61.62994122505188,-0.03626208490863744,1739502701.3800597,61.62994122505188,2.209124876832482,1739502701.3800611,61.62994122505188,0.0,1739502701.3800626,61.62994122505188,-0.10516568783220537,1739502701.3800642,61.62994122505188,3.173681061413053,1739502701.3800654,61.62994122505188,2.314290564664687 +1739502701.4004653,61.649941205978394,9.374505712917289,1739502701.4004674,61.649941205978394,0.0014281594606737613,1739502701.4004703,61.649941205978394,103.04701292010283,1739502701.400473,61.649941205978394,3.652241720556503,1739502701.4004748,61.649941205978394,-0.027555744859771872,1739502701.4004765,61.649941205978394,-3.13652758555049,1739502701.400478,61.649941205978394,-0.15461784762539457,1739502701.4004793,61.649941205978394,-0.03626208490863744,1739502701.4004805,61.649941205978394,2.209124876832482,1739502701.400482,61.649941205978394,0.0,1739502701.4004838,61.649941205978394,-0.10516568783220537,1739502701.4004853,61.649941205978394,3.173681061413053,1739502701.400487,61.649941205978394,2.314290564664687 +1739502701.420704,61.66994118690491,9.120643285517101,1739502701.4207067,61.66994118690491,-0.0067416131660067435,1739502701.42071,61.66994118690491,103.32885173134603,1739502701.4207127,61.66994118690491,3.3937226989825455,1739502701.420714,61.66994118690491,-0.016133465636399294,1739502701.420716,61.66994118690491,-3.1399527069712017,1739502701.4207175,61.66994118690491,-0.175312025366504,1739502701.4207187,61.66994118690491,-0.04104897646177483,1739502701.4207199,61.66994118690491,2.1728531325597893,1739502701.4207218,61.66994118690491,0.0,1739502701.420723,61.66994118690491,-0.14118164113590503,1739502701.4207244,61.66994118690491,3.1738492604057638,1739502701.420726,61.66994118690491,2.30277978090894 +1739502701.4422975,61.68994116783142,9.120643285517101,1739502701.4423,61.68994116783142,-0.0067416131660067435,1739502701.442303,61.68994116783142,103.32885173134603,1739502701.4423058,61.68994116783142,3.3937226989825455,1739502701.4423072,61.68994116783142,-0.016133465636399294,1739502701.4423094,61.68994116783142,-3.1399527069712017,1739502701.4423106,61.68994116783142,-0.175312025366504,1739502701.4423122,61.68994116783142,-0.04104897646177483,1739502701.4423134,61.68994116783142,2.1728531325597893,1739502701.4423153,61.68994116783142,0.0,1739502701.4423165,61.68994116783142,-0.12992664834915058,1739502701.442318,61.68994116783142,3.1738492604057638,1739502701.4423196,61.68994116783142,2.30277978090894 +1739502701.4617782,61.709941148757935,9.120643285517101,1739502701.4617822,61.709941148757935,-0.0067416131660067435,1739502701.4617875,61.709941148757935,103.32885173134603,1739502701.4617927,61.709941148757935,3.3937226989825455,1739502701.4617956,61.709941148757935,-0.016133465636399294,1739502701.4617994,61.709941148757935,-3.1399527069712017,1739502701.461803,61.709941148757935,-0.175312025366504,1739502701.4618063,61.709941148757935,-0.04104897646177483,1739502701.4618104,61.709941148757935,2.1728531325597893,1739502701.461814,61.709941148757935,0.0,1739502701.4618175,61.709941148757935,-0.12992664834915058,1739502701.4618208,61.709941148757935,3.1738492604057638,1739502701.4618244,61.709941148757935,2.30277978090894 +1739502701.4826205,61.72994112968445,9.120643285517101,1739502701.4826248,61.72994112968445,-0.0067416131660067435,1739502701.4826295,61.72994112968445,103.32885173134603,1739502701.4826355,61.72994112968445,3.3937226989825455,1739502701.4826386,61.72994112968445,-0.016133465636399294,1739502701.4826424,61.72994112968445,-3.1399527069712017,1739502701.482646,61.72994112968445,-0.175312025366504,1739502701.4826496,61.72994112968445,-0.04104897646177483,1739502701.482653,61.72994112968445,2.1728531325597893,1739502701.4826565,61.72994112968445,0.0,1739502701.48266,61.72994112968445,-0.12992664834915058,1739502701.4826636,61.72994112968445,3.1738492604057638,1739502701.4826674,61.72994112968445,2.30277978090894 +1739502701.501946,61.74994111061096,9.120643285517101,1739502701.5019488,61.74994111061096,-0.0067416131660067435,1739502701.501952,61.74994111061096,103.32885173134603,1739502701.5019546,61.74994111061096,3.3937226989825455,1739502701.501956,61.74994111061096,-0.016133465636399294,1739502701.501958,61.74994111061096,-3.1399527069712017,1739502701.5019593,61.74994111061096,-0.175312025366504,1739502701.5019608,61.74994111061096,-0.04104897646177483,1739502701.5019622,61.74994111061096,2.1728531325597893,1739502701.501964,61.74994111061096,0.0,1739502701.5019655,61.74994111061096,-0.12992664834915058,1739502701.5019674,61.74994111061096,3.1738492604057638,1739502701.5019686,61.74994111061096,2.30277978090894 +1739502701.5202477,61.769941091537476,9.120643285517101,1739502701.52025,61.769941091537476,-0.0067416131660067435,1739502701.520253,61.769941091537476,103.32885173134603,1739502701.5202558,61.769941091537476,3.3937226989825455,1739502701.5202572,61.769941091537476,-0.016133465636399294,1739502701.520259,61.769941091537476,-3.1399527069712017,1739502701.52026,61.769941091537476,-0.175312025366504,1739502701.5202613,61.769941091537476,-0.04104897646177483,1739502701.5202627,61.769941091537476,2.1728531325597893,1739502701.5202641,61.769941091537476,0.0,1739502701.5202656,61.769941091537476,-0.12992664834915058,1739502701.5202668,61.769941091537476,3.1738492604057638,1739502701.520268,61.769941091537476,2.30277978090894 +1739502701.5405056,61.78994107246399,8.868202713299336,1739502701.5405083,61.78994107246399,-0.014886570745307637,1739502701.540511,61.78994107246399,104.12859181094454,1739502701.5405138,61.78994107246399,2.623895685164623,1739502701.5405152,61.78994107246399,0.022616502646341925,1739502701.5405169,61.78994107246399,3.1355867633764083,1739502701.540518,61.78994107246399,-0.23858969725259252,1739502701.5405197,61.78994107246399,-0.046988677976556426,1739502701.540521,61.78994107246399,2.065596350009202,1739502701.5405226,61.78994107246399,0.0,1739502701.5405238,61.78994107246399,-0.2649233038989893,1739502701.5405252,61.78994107246399,3.1738045323924147,1739502701.5405269,61.78994107246399,2.288333171389253 +1739502701.560215,61.8099410533905,8.868202713299336,1739502701.5602174,61.8099410533905,-0.014886570745307637,1739502701.5602202,61.8099410533905,104.12859181094454,1739502701.5602226,61.8099410533905,2.623895685164623,1739502701.560224,61.8099410533905,0.022616502646341925,1739502701.5602257,61.8099410533905,3.1355867633764083,1739502701.5602272,61.8099410533905,-0.23858969725259252,1739502701.5602283,61.8099410533905,-0.046988677976556426,1739502701.5602295,61.8099410533905,2.065596350009202,1739502701.5602312,61.8099410533905,0.0,1739502701.5602324,61.8099410533905,-0.22273682138005135,1739502701.560234,61.8099410533905,3.1738045323924147,1739502701.5602355,61.8099410533905,2.288333171389253 +1739502701.5814455,61.82994103431702,8.868202713299336,1739502701.5814486,61.82994103431702,-0.014886570745307637,1739502701.581452,61.82994103431702,104.12859181094454,1739502701.5814543,61.82994103431702,2.623895685164623,1739502701.5814557,61.82994103431702,0.022616502646341925,1739502701.5814574,61.82994103431702,3.1355867633764083,1739502701.5814593,61.82994103431702,-0.23858969725259252,1739502701.581461,61.82994103431702,-0.046988677976556426,1739502701.5814626,61.82994103431702,2.065596350009202,1739502701.5814643,61.82994103431702,0.0,1739502701.5814655,61.82994103431702,-0.22273682138005135,1739502701.5814672,61.82994103431702,3.1738045323924147,1739502701.5814693,61.82994103431702,2.288333171389253 +1739502701.60046,61.84994101524353,8.868202713299336,1739502701.600465,61.84994101524353,-0.014886570745307637,1739502701.6004715,61.84994101524353,104.12859181094454,1739502701.6004772,61.84994101524353,2.623895685164623,1739502701.6004803,61.84994101524353,0.022616502646341925,1739502701.6004848,61.84994101524353,3.1355867633764083,1739502701.6004913,61.84994101524353,-0.23858969725259252,1739502701.6004963,61.84994101524353,-0.046988677976556426,1739502701.6004994,61.84994101524353,2.065596350009202,1739502701.6005025,61.84994101524353,0.0,1739502701.600505,61.84994101524353,-0.22273682138005135,1739502701.6005085,61.84994101524353,3.1738045323924147,1739502701.6005123,61.84994101524353,2.288333171389253 +1739502701.620772,61.869940996170044,8.868202713299336,1739502701.620775,61.869940996170044,-0.014886570745307637,1739502701.620778,61.869940996170044,104.12859181094454,1739502701.620781,61.869940996170044,2.623895685164623,1739502701.6207829,61.869940996170044,0.022616502646341925,1739502701.6207845,61.869940996170044,3.1355867633764083,1739502701.6207867,61.869940996170044,-0.23858969725259252,1739502701.6207883,61.869940996170044,-0.046988677976556426,1739502701.6207895,61.869940996170044,2.065596350009202,1739502701.620791,61.869940996170044,0.0,1739502701.6207926,61.869940996170044,-0.22273682138005135,1739502701.6207943,61.869940996170044,3.1738045323924147,1739502701.620796,61.869940996170044,2.288333171389253 +1739502701.6417458,61.88994097709656,8.617814452929174,1739502701.6417496,61.88994097709656,-0.022930510227708645,1739502701.6417522,61.88994097709656,104.15789528134735,1739502701.641755,61.88994097709656,2.6431525100232665,1739502701.6417568,61.88994097709656,0.02183050979496872,1739502701.6417587,61.88994097709656,3.1341009857696056,1739502701.6417603,61.88994097709656,-0.2355735983270846,1739502701.6417615,61.88994097709656,-0.05067520074821536,1739502701.6417627,61.88994097709656,2.0705864021299734,1739502701.6417644,61.88994097709656,0.0,1739502701.641766,61.88994097709656,-0.18015031159870168,1739502701.6417675,61.88994097709656,3.173538876254534,1739502701.641769,61.88994097709656,2.2640450067609437 +1739502701.660251,61.90994095802307,8.617814452929174,1739502701.6602535,61.90994095802307,-0.022930510227708645,1739502701.6602566,61.90994095802307,104.15789528134735,1739502701.6602592,61.90994095802307,2.6431525100232665,1739502701.660261,61.90994095802307,0.02183050979496872,1739502701.6602628,61.90994095802307,3.1341009857696056,1739502701.6602643,61.90994095802307,-0.2355735983270846,1739502701.6602654,61.90994095802307,-0.05067520074821536,1739502701.6602666,61.90994095802307,2.0705864021299734,1739502701.6602683,61.90994095802307,0.0,1739502701.6602697,61.90994095802307,-0.1934586046309703,1739502701.6602712,61.90994095802307,3.173538876254534,1739502701.6602726,61.90994095802307,2.2640450067609437 +1739502701.6805248,61.929940938949585,8.617814452929174,1739502701.6805277,61.929940938949585,-0.022930510227708645,1739502701.6805308,61.929940938949585,104.15789528134735,1739502701.6805336,61.929940938949585,2.6431525100232665,1739502701.680535,61.929940938949585,0.02183050979496872,1739502701.6805367,61.929940938949585,3.1341009857696056,1739502701.6805382,61.929940938949585,-0.2355735983270846,1739502701.6805394,61.929940938949585,-0.05067520074821536,1739502701.680541,61.929940938949585,2.0705864021299734,1739502701.6805425,61.929940938949585,0.0,1739502701.6805437,61.929940938949585,-0.1934586046309703,1739502701.6805456,61.929940938949585,3.173538876254534,1739502701.680547,61.929940938949585,2.2640450067609437 +1739502701.7025757,61.9499409198761,8.617814452929174,1739502701.7025797,61.9499409198761,-0.022930510227708645,1739502701.7025845,61.9499409198761,104.15789528134735,1739502701.7025902,61.9499409198761,2.6431525100232665,1739502701.702593,61.9499409198761,0.02183050979496872,1739502701.7025971,61.9499409198761,3.1341009857696056,1739502701.7026005,61.9499409198761,-0.2355735983270846,1739502701.702604,61.9499409198761,-0.05067520074821536,1739502701.7026076,61.9499409198761,2.0705864021299734,1739502701.7026114,61.9499409198761,0.0,1739502701.7026148,61.9499409198761,-0.1934586046309703,1739502701.7026184,61.9499409198761,3.173538876254534,1739502701.702622,61.9499409198761,2.2640450067609437 +1739502701.7206032,61.96994090080261,8.617814452929174,1739502701.7206056,61.96994090080261,-0.022930510227708645,1739502701.7206087,61.96994090080261,104.15789528134735,1739502701.7206113,61.96994090080261,2.6431525100232665,1739502701.7206128,61.96994090080261,0.02183050979496872,1739502701.7206147,61.96994090080261,3.1341009857696056,1739502701.7206163,61.96994090080261,-0.2355735983270846,1739502701.7206178,61.96994090080261,-0.05067520074821536,1739502701.720619,61.96994090080261,2.0705864021299734,1739502701.7206206,61.96994090080261,0.0,1739502701.7206218,61.96994090080261,-0.1934586046309703,1739502701.7206233,61.96994090080261,3.173538876254534,1739502701.720625,61.96994090080261,2.2640450067609437 +1739502701.7402809,61.989940881729126,8.617814452929174,1739502701.7402835,61.989940881729126,-0.022930510227708645,1739502701.7402868,61.989940881729126,104.15789528134735,1739502701.7402894,61.989940881729126,2.6431525100232665,1739502701.7402909,61.989940881729126,0.02183050979496872,1739502701.7402925,61.989940881729126,3.1341009857696056,1739502701.7402942,61.989940881729126,-0.2355735983270846,1739502701.7402954,61.989940881729126,-0.05067520074821536,1739502701.7402966,61.989940881729126,2.0705864021299734,1739502701.7402985,61.989940881729126,0.0,1739502701.7402997,61.989940881729126,-0.1934586046309703,1739502701.7403014,61.989940881729126,3.173538876254534,1739502701.740303,61.989940881729126,2.2640450067609437 +1739502701.7623854,62.00994086265564,8.369930236266711,1739502701.7623904,62.00994086265564,-0.030801322357739913,1739502701.7623951,62.00994086265564,104.18690560550898,1739502701.7624006,62.00994086265564,2.6559629708534813,1739502701.7624032,62.00994086265564,0.02130763384271505,1739502701.7624075,62.00994086265564,3.132473330836227,1739502701.7624106,62.00994086265564,-0.23189435084697807,1739502701.7624142,62.00994086265564,-0.05453708615722465,1739502701.7624176,62.00994086265564,2.0766899401360623,1739502701.7624216,62.00994086265564,0.0,1739502701.7624252,62.00994086265564,-0.1541578456448642,1739502701.7624288,62.00994086265564,3.1730665638141184,1739502701.7624323,62.00994086265564,2.2431292810164605 +1739502701.781255,62.02994084358215,8.369930236266711,1739502701.7812576,62.02994084358215,-0.030801322357739913,1739502701.7812612,62.02994084358215,104.18690560550898,1739502701.781264,62.02994084358215,2.6559629708534813,1739502701.7812655,62.02994084358215,0.02130763384271505,1739502701.7812674,62.02994084358215,3.132473330836227,1739502701.7812693,62.02994084358215,-0.23189435084697807,1739502701.7812705,62.02994084358215,-0.05453708615722465,1739502701.7812722,62.02994084358215,2.0766899401360623,1739502701.7812736,62.02994084358215,0.0,1739502701.7812748,62.02994084358215,-0.16643934088039813,1739502701.7812767,62.02994084358215,3.1730665638141184,1739502701.7812784,62.02994084358215,2.2431292810164605 +1739502701.800722,62.04994082450867,8.369930236266711,1739502701.8007245,62.04994082450867,-0.030801322357739913,1739502701.8007278,62.04994082450867,104.18690560550898,1739502701.8007305,62.04994082450867,2.6559629708534813,1739502701.8007317,62.04994082450867,0.02130763384271505,1739502701.8007333,62.04994082450867,3.132473330836227,1739502701.800735,62.04994082450867,-0.23189435084697807,1739502701.8007362,62.04994082450867,-0.05453708615722465,1739502701.8007379,62.04994082450867,2.0766899401360623,1739502701.8007393,62.04994082450867,0.0,1739502701.800741,62.04994082450867,-0.16643934088039813,1739502701.8007424,62.04994082450867,3.1730665638141184,1739502701.8007438,62.04994082450867,2.2431292810164605 +1739502701.822531,62.06994080543518,8.369930236266711,1739502701.8225348,62.06994080543518,-0.030801322357739913,1739502701.8225396,62.06994080543518,104.18690560550898,1739502701.8225446,62.06994080543518,2.6559629708534813,1739502701.8225477,62.06994080543518,0.02130763384271505,1739502701.8225513,62.06994080543518,3.132473330836227,1739502701.8225548,62.06994080543518,-0.23189435084697807,1739502701.8225582,62.06994080543518,-0.05453708615722465,1739502701.8225615,62.06994080543518,2.0766899401360623,1739502701.822565,62.06994080543518,0.0,1739502701.8225684,62.06994080543518,-0.16643934088039813,1739502701.822572,62.06994080543518,3.1730665638141184,1739502701.8225753,62.06994080543518,2.2431292810164605 +1739502701.8417106,62.089940786361694,8.369930236266711,1739502701.8417132,62.089940786361694,-0.030801322357739913,1739502701.8417163,62.089940786361694,104.18690560550898,1739502701.8417192,62.089940786361694,2.6559629708534813,1739502701.8417206,62.089940786361694,0.02130763384271505,1739502701.841722,62.089940786361694,3.132473330836227,1739502701.8417237,62.089940786361694,-0.23189435084697807,1739502701.8417249,62.089940786361694,-0.05453708615722465,1739502701.8417263,62.089940786361694,2.0766899401360623,1739502701.8417277,62.089940786361694,0.0,1739502701.8417299,62.089940786361694,-0.16643934088039813,1739502701.841731,62.089940786361694,3.1730665638141184,1739502701.8417323,62.089940786361694,2.2431292810164605 +1739502701.8620374,62.10994076728821,8.124222647036099,1739502701.862041,62.10994076728821,-0.03847148568167569,1739502701.862044,62.10994076728821,104.88175209184325,1739502701.8620467,62.10994076728821,1.9977105984038859,1739502701.862048,62.10994076728821,0.03377930458172987,1739502701.8620503,62.10994076728821,3.129800064189902,1739502701.8620515,62.10994076728821,-0.2612112719813868,1739502701.862053,62.10994076728821,-0.053434312234036344,1739502701.862054,62.10994076728821,2.028550937541699,1739502701.8620558,62.10994076728821,0.0,1739502701.8620572,62.10994076728821,-0.2099489891247374,1739502701.8620584,62.10994076728821,3.1724462380719687,1739502701.8620598,62.10994076728821,2.2249031526753407 +1739502701.8798704,62.12994074821472,8.124222647036099,1739502701.8798728,62.12994074821472,-0.03847148568167569,1739502701.8798761,62.12994074821472,104.88175209184325,1739502701.8798792,62.12994074821472,1.9977105984038859,1739502701.8798807,62.12994074821472,0.03377930458172987,1739502701.8798826,62.12994074821472,3.129800064189902,1739502701.8798838,62.12994074821472,-0.2612112719813868,1739502701.8798852,62.12994074821472,-0.053434312234036344,1739502701.8798866,62.12994074821472,2.028550937541699,1739502701.879888,62.12994074821472,0.0,1739502701.8798897,62.12994074821472,-0.19635221513364165,1739502701.8798912,62.12994074821472,3.1724462380719687,1739502701.8798926,62.12994074821472,2.2249031526753407 +1739502701.9008117,62.149940729141235,8.124222647036099,1739502701.9008143,62.149940729141235,-0.03847148568167569,1739502701.9008174,62.149940729141235,104.88175209184325,1739502701.9008203,62.149940729141235,1.9977105984038859,1739502701.9008214,62.149940729141235,0.03377930458172987,1739502701.9008234,62.149940729141235,3.129800064189902,1739502701.9008245,62.149940729141235,-0.2612112719813868,1739502701.9008257,62.149940729141235,-0.053434312234036344,1739502701.9008272,62.149940729141235,2.028550937541699,1739502701.9008286,62.149940729141235,0.0,1739502701.90083,62.149940729141235,-0.19635221513364165,1739502701.9008315,62.149940729141235,3.1724462380719687,1739502701.9008331,62.149940729141235,2.2249031526753407 +1739502701.9198618,62.16994071006775,8.124222647036099,1739502701.9198642,62.16994071006775,-0.03847148568167569,1739502701.919867,62.16994071006775,104.88175209184325,1739502701.91987,62.16994071006775,1.9977105984038859,1739502701.9198713,62.16994071006775,0.03377930458172987,1739502701.919873,62.16994071006775,3.129800064189902,1739502701.9198747,62.16994071006775,-0.2612112719813868,1739502701.9198759,62.16994071006775,-0.053434312234036344,1739502701.919877,62.16994071006775,2.028550937541699,1739502701.919879,62.16994071006775,0.0,1739502701.91988,62.16994071006775,-0.19635221513364165,1739502701.9198818,62.16994071006775,3.1724462380719687,1739502701.919883,62.16994071006775,2.2249031526753407 +1739502701.9470763,62.18994069099426,8.124222647036099,1739502701.9470842,62.18994069099426,-0.03847148568167569,1739502701.9470944,62.18994069099426,104.88175209184325,1739502701.9471045,62.18994069099426,1.9977105984038859,1739502701.9471097,62.18994069099426,0.03377930458172987,1739502701.9471161,62.18994069099426,3.129800064189902,1739502701.947121,62.18994069099426,-0.2612112719813868,1739502701.947126,62.18994069099426,-0.053434312234036344,1739502701.9471307,62.18994069099426,2.028550937541699,1739502701.9471362,62.18994069099426,0.0,1739502701.9471412,62.18994069099426,-0.19635221513364165,1739502701.9471464,62.18994069099426,3.1724462380719687,1739502701.9471517,62.18994069099426,2.2249031526753407 +1739502701.9662058,62.209940671920776,8.124222647036099,1739502701.9662142,62.209940671920776,-0.03847148568167569,1739502701.9662247,62.209940671920776,104.88175209184325,1739502701.9662352,62.209940671920776,1.9977105984038859,1739502701.96624,62.209940671920776,0.03377930458172987,1739502701.966246,62.209940671920776,3.129800064189902,1739502701.9662514,62.209940671920776,-0.2612112719813868,1739502701.9662561,62.209940671920776,-0.053434312234036344,1739502701.9662607,62.209940671920776,2.028550937541699,1739502701.9662664,62.209940671920776,0.0,1739502701.9662714,62.209940671920776,-0.19635221513364165,1739502701.9662766,62.209940671920776,3.1724462380719687,1739502701.9662817,62.209940671920776,2.2249031526753407 +1739502701.9938786,62.22994065284729,7.88069964354294,1739502701.9938872,62.22994065284729,-0.04591472666055818,1739502701.9938977,62.22994065284729,104.93168175080034,1739502701.9939077,62.22994065284729,1.9913158657676577,1739502701.9939125,62.22994065284729,0.03392463941437142,1739502701.9939187,62.22994065284729,3.1280369950167093,1739502701.993924,62.22994065284729,-0.25761320371896773,1739502701.9939287,62.22994065284729,-0.05702397820558603,1739502701.9939332,62.22994065284729,2.0343984411888116,1739502701.993939,62.22994065284729,0.0,1739502701.9939435,62.22994065284729,-0.1561861796751485,1739502701.9939487,62.22994065284729,3.1717888957377065,1739502701.9939537,62.22994065284729,2.2031365151744025 +1739502702.0123026,62.249940633773804,7.88069964354294,1739502702.0123107,62.249940633773804,-0.04591472666055818,1739502702.012321,62.249940633773804,104.93168175080034,1739502702.0123312,62.249940633773804,1.9913158657676577,1739502702.0123367,62.249940633773804,0.03392463941437142,1739502702.0123427,62.249940633773804,3.1280369950167093,1739502702.012348,62.249940633773804,-0.25761320371896773,1739502702.012353,62.249940633773804,-0.05702397820558603,1739502702.012358,62.249940633773804,2.0343984411888116,1739502702.0123637,62.249940633773804,0.0,1739502702.012369,62.249940633773804,-0.16873807398559082,1739502702.0123742,62.249940633773804,3.1717888957377065,1739502702.0123796,62.249940633773804,2.2031365151744025 +1739502702.0420244,62.279940605163574,7.88069964354294,1739502702.0420387,62.279940605163574,-0.04591472666055818,1739502702.0420582,62.279940605163574,104.93168175080034,1739502702.0420809,62.279940605163574,1.9913158657676577,1739502702.042089,62.279940605163574,0.03392463941437142,1739502702.0420995,62.279940605163574,3.1280369950167093,1739502702.0421152,62.279940605163574,-0.25761320371896773,1739502702.0421238,62.279940605163574,-0.05702397820558603,1739502702.042131,62.279940605163574,2.0343984411888116,1739502702.042139,62.279940605163574,0.0,1739502702.042155,62.279940605163574,-0.16873807398559082,1739502702.042165,62.279940605163574,3.1717888957377065,1739502702.0421789,62.279940605163574,2.2031365151744025 +1739502702.0607698,62.29994058609009,7.88069964354294,1739502702.0607738,62.29994058609009,-0.04591472666055818,1739502702.0607789,62.29994058609009,104.93168175080034,1739502702.0607834,62.29994058609009,1.9913158657676577,1739502702.0607858,62.29994058609009,0.03392463941437142,1739502702.0607884,62.29994058609009,3.1280369950167093,1739502702.0607908,62.29994058609009,-0.25761320371896773,1739502702.0607932,62.29994058609009,-0.05702397820558603,1739502702.060795,62.29994058609009,2.0343984411888116,1739502702.0607977,62.29994058609009,0.0,1739502702.0608,62.29994058609009,-0.16873807398559082,1739502702.0608022,62.29994058609009,3.1717888957377065,1739502702.0608046,62.29994058609009,2.2031365151744025 +1739502702.079037,62.3199405670166,7.88069964354294,1739502702.0790403,62.3199405670166,-0.04591472666055818,1739502702.0790448,62.3199405670166,104.93168175080034,1739502702.0790486,62.3199405670166,1.9913158657676577,1739502702.0790508,62.3199405670166,0.03392463941437142,1739502702.0790532,62.3199405670166,3.1280369950167093,1739502702.0790548,62.3199405670166,-0.25761320371896773,1739502702.079057,62.3199405670166,-0.05702397820558603,1739502702.0790586,62.3199405670166,2.0343984411888116,1739502702.0790608,62.3199405670166,0.0,1739502702.0790625,62.3199405670166,-0.16873807398559082,1739502702.0790646,62.3199405670166,3.1717888957377065,1739502702.0790663,62.3199405670166,2.2031365151744025 +1739502702.0986505,62.339940547943115,7.639391987222988,1739502702.0986543,62.339940547943115,-0.053125621285348146,1739502702.0986583,62.339940547943115,104.98115703124053,1739502702.098662,62.339940547943115,1.9788006866893846,1739502702.0986636,62.339940547943115,0.034209075302513985,1739502702.098666,62.339940547943115,3.1261653310323982,1739502702.0986679,62.339940547943115,-0.25410251173669934,1739502702.0986698,62.339940547943115,-0.060881253616648354,1739502702.0986717,62.339940547943115,2.0401201893829097,1739502702.0986736,62.339940547943115,0.0,1739502702.0986755,62.339940547943115,-0.13353779735589125,1739502702.0986772,62.339940547943115,3.171064820715189,1739502702.098679,62.339940547943115,2.1846580803978055 +1739502702.1186018,62.35994052886963,7.639391987222988,1739502702.1186051,62.35994052886963,-0.053125621285348146,1739502702.1186094,62.35994052886963,104.98115703124053,1739502702.1186135,62.35994052886963,1.9788006866893846,1739502702.1186154,62.35994052886963,0.034209075302513985,1739502702.1186178,62.35994052886963,3.1261653310323982,1739502702.1186197,62.35994052886963,-0.25410251173669934,1739502702.118622,62.35994052886963,-0.060881253616648354,1739502702.1186237,62.35994052886963,2.0401201893829097,1739502702.1186264,62.35994052886963,0.0,1739502702.118628,62.35994052886963,-0.14453789101489578,1739502702.11863,62.35994052886963,3.171064820715189,1739502702.1186318,62.35994052886963,2.1846580803978055 +1739502702.1390553,62.37994050979614,7.639391987222988,1739502702.1390595,62.37994050979614,-0.053125621285348146,1739502702.139064,62.37994050979614,104.98115703124053,1739502702.139068,62.37994050979614,1.9788006866893846,1739502702.1390698,62.37994050979614,0.034209075302513985,1739502702.1390724,62.37994050979614,3.1261653310323982,1739502702.1390743,62.37994050979614,-0.25410251173669934,1739502702.1390762,62.37994050979614,-0.060881253616648354,1739502702.1390781,62.37994050979614,2.0401201893829097,1739502702.139081,62.37994050979614,0.0,1739502702.139083,62.37994050979614,-0.14453789101489578,1739502702.1390848,62.37994050979614,3.171064820715189,1739502702.139087,62.37994050979614,2.1846580803978055 +1739502702.1584942,62.399940490722656,7.639391987222988,1739502702.158497,62.399940490722656,-0.053125621285348146,1739502702.1585002,62.399940490722656,104.98115703124053,1739502702.1585028,62.399940490722656,1.9788006866893846,1739502702.1585045,62.399940490722656,0.034209075302513985,1739502702.1585062,62.399940490722656,3.1261653310323982,1739502702.1585078,62.399940490722656,-0.25410251173669934,1739502702.1585093,62.399940490722656,-0.060881253616648354,1739502702.1585107,62.399940490722656,2.0401201893829097,1739502702.158512,62.399940490722656,0.0,1739502702.1585133,62.399940490722656,-0.14453789101489578,1739502702.158515,62.399940490722656,3.171064820715189,1739502702.1585164,62.399940490722656,2.1846580803978055 +1739502702.1778953,62.41994047164917,7.639391987222988,1739502702.1778977,62.41994047164917,-0.053125621285348146,1739502702.1779006,62.41994047164917,104.98115703124053,1739502702.1779032,62.41994047164917,1.9788006866893846,1739502702.1779044,62.41994047164917,0.034209075302513985,1739502702.177906,62.41994047164917,3.1261653310323982,1739502702.1779075,62.41994047164917,-0.25410251173669934,1739502702.177909,62.41994047164917,-0.060881253616648354,1739502702.1779103,62.41994047164917,2.0401201893829097,1739502702.1779118,62.41994047164917,0.0,1739502702.1779132,62.41994047164917,-0.14453789101489578,1739502702.1779146,62.41994047164917,3.171064820715189,1739502702.1779158,62.41994047164917,2.1846580803978055 +1739502702.1984634,62.439940452575684,7.399969757476075,1739502702.1984668,62.439940452575684,-0.06009323565458935,1739502702.1984713,62.439940452575684,105.60848263734283,1739502702.1984766,62.439940452575684,1.382987817387169,1739502702.1984794,62.439940452575684,0.042896262111854946,1739502702.198483,62.439940452575684,3.1244778537075066,1739502702.1984863,62.439940452575684,-0.27505115890360066,1739502702.1984897,62.439940452575684,-0.05832239463120391,1739502702.198493,62.439940452575684,2.006214884622831,1739502702.1984963,62.439940452575684,0.0,1739502702.1984997,62.439940452575684,-0.1709892594311843,1739502702.1985033,62.439940452575684,3.1701995659764735,1739502702.1985066,62.439940452575684,2.168938086004275 +1739502702.2184827,62.4599404335022,7.399969757476075,1739502702.2184868,62.4599404335022,-0.06009323565458935,1739502702.2184918,62.4599404335022,105.60848263734283,1739502702.2184975,62.4599404335022,1.382987817387169,1739502702.2185004,62.4599404335022,0.042896262111854946,1739502702.2185044,62.4599404335022,3.1244778537075066,1739502702.218508,62.4599404335022,-0.27505115890360066,1739502702.2185118,62.4599404335022,-0.05832239463120391,1739502702.2185154,62.4599404335022,2.006214884622831,1739502702.218519,62.4599404335022,0.0,1739502702.2185225,62.4599404335022,-0.16272320138144414,1739502702.2185264,62.4599404335022,3.1701995659764735,1739502702.21853,62.4599404335022,2.168938086004275 +1739502702.2402046,62.47994041442871,7.399969757476075,1739502702.2402086,62.47994041442871,-0.06009323565458935,1739502702.2402143,62.47994041442871,105.60848263734283,1739502702.2402203,62.47994041442871,1.382987817387169,1739502702.240224,62.47994041442871,0.042896262111854946,1739502702.2402284,62.47994041442871,3.1244778537075066,1739502702.2402325,62.47994041442871,-0.27505115890360066,1739502702.2402365,62.47994041442871,-0.05832239463120391,1739502702.2402403,62.47994041442871,2.006214884622831,1739502702.2402446,62.47994041442871,0.0,1739502702.240249,62.47994041442871,-0.16272320138144414,1739502702.240253,62.47994041442871,3.1701995659764735,1739502702.240257,62.47994041442871,2.168938086004275 +1739502702.2600567,62.499940395355225,7.399969757476075,1739502702.260061,62.499940395355225,-0.06009323565458935,1739502702.2600667,62.499940395355225,105.60848263734283,1739502702.260073,62.499940395355225,1.382987817387169,1739502702.2600763,62.499940395355225,0.042896262111854946,1739502702.2600808,62.499940395355225,3.1244778537075066,1739502702.2600846,62.499940395355225,-0.27505115890360066,1739502702.260089,62.499940395355225,-0.05832239463120391,1739502702.2600927,62.499940395355225,2.006214884622831,1739502702.260097,62.499940395355225,0.0,1739502702.2601008,62.499940395355225,-0.16272320138144414,1739502702.2601054,62.499940395355225,3.1701995659764735,1739502702.2601097,62.499940395355225,2.168938086004275 +1739502702.280319,62.51994037628174,7.399969757476075,1739502702.280323,62.51994037628174,-0.06009323565458935,1739502702.2803288,62.51994037628174,105.60848263734283,1739502702.280335,62.51994037628174,1.382987817387169,1739502702.2803385,62.51994037628174,0.042896262111854946,1739502702.2803428,62.51994037628174,3.1244778537075066,1739502702.2803469,62.51994037628174,-0.27505115890360066,1739502702.2803507,62.51994037628174,-0.05832239463120391,1739502702.2803547,62.51994037628174,2.006214884622831,1739502702.280359,62.51994037628174,0.0,1739502702.280363,62.51994037628174,-0.16272320138144414,1739502702.2803671,62.51994037628174,3.1701995659764735,1739502702.2803712,62.51994037628174,2.168938086004275 +1739502702.2996683,62.53994035720825,7.399969757476075,1739502702.2996724,62.53994035720825,-0.06009323565458935,1739502702.2996778,62.53994035720825,105.60848263734283,1739502702.299684,62.53994035720825,1.382987817387169,1739502702.2996874,62.53994035720825,0.042896262111854946,1739502702.2996917,62.53994035720825,3.1244778537075066,1739502702.299696,62.53994035720825,-0.27505115890360066,1739502702.2997,62.53994035720825,-0.05832239463120391,1739502702.2997038,62.53994035720825,2.006214884622831,1739502702.299708,62.53994035720825,0.0,1739502702.2997117,62.53994035720825,-0.16272320138144414,1739502702.2997158,62.53994035720825,3.1701995659764735,1739502702.2997203,62.53994035720825,2.168938086004275 +1739502702.3200004,62.559940338134766,7.162389176817541,1739502702.3200047,62.559940338134766,-0.06679415259418686,1739502702.32001,62.559940338134766,105.63533594387417,1739502702.3200161,62.559940338134766,1.3920940996861644,1739502702.3200197,62.559940338134766,0.042777998705374486,1739502702.320024,62.559940338134766,3.12260593232862,1739502702.3200278,62.559940338134766,-0.2693727679260539,1739502702.320032,62.559940338134766,-0.06210123751056454,1739502702.320036,62.559940338134766,2.0153492743689663,1739502702.32004,62.559940338134766,0.0,1739502702.320044,62.559940338134766,-0.12328381782073357,1739502702.320048,62.559940338134766,3.1692971490560304,1739502702.3200521,62.559940338134766,2.1509579076332006 +1739502702.346449,62.57994031906128,7.162389176817541,1739502702.346457,62.57994031906128,-0.06679415259418686,1739502702.3464675,62.57994031906128,105.63533594387417,1739502702.346478,62.57994031906128,1.3920940996861644,1739502702.3464835,62.57994031906128,0.042777998705374486,1739502702.3464897,62.57994031906128,3.12260593232862,1739502702.3464952,62.57994031906128,-0.2693727679260539,1739502702.3465002,62.57994031906128,-0.06210123751056454,1739502702.346505,62.57994031906128,2.0153492743689663,1739502702.3465106,62.57994031906128,0.0,1739502702.3465157,62.57994031906128,-0.13560863326423434,1739502702.3465211,62.57994031906128,3.1692971490560304,1739502702.3465266,62.57994031906128,2.1509579076332006 +1739502702.3658764,62.59994029998779,7.162389176817541,1739502702.3658843,62.59994029998779,-0.06679415259418686,1739502702.3658946,62.59994029998779,105.63533594387417,1739502702.3659048,62.59994029998779,1.3920940996861644,1739502702.36591,62.59994029998779,0.042777998705374486,1739502702.365916,62.59994029998779,3.12260593232862,1739502702.365921,62.59994029998779,-0.2693727679260539,1739502702.365926,62.59994029998779,-0.06210123751056454,1739502702.3659306,62.59994029998779,2.0153492743689663,1739502702.3659368,62.59994029998779,0.0,1739502702.3659415,62.59994029998779,-0.13560863326423434,1739502702.3659468,62.59994029998779,3.1692971490560304,1739502702.365952,62.59994029998779,2.1509579076332006 +1739502702.394523,62.62994027137756,7.162389176817541,1739502702.3945274,62.62994027137756,-0.06679415259418686,1739502702.394533,62.62994027137756,105.63533594387417,1739502702.3945382,62.62994027137756,1.3920940996861644,1739502702.394541,62.62994027137756,0.042777998705374486,1739502702.3945444,62.62994027137756,3.12260593232862,1739502702.394547,62.62994027137756,-0.2693727679260539,1739502702.3945498,62.62994027137756,-0.06210123751056454,1739502702.3945522,62.62994027137756,2.0153492743689663,1739502702.3945553,62.62994027137756,0.0,1739502702.3945644,62.62994027137756,-0.13560863326423434,1739502702.3945675,62.62994027137756,3.1692971490560304,1739502702.3945699,62.62994027137756,2.1509579076332006 +1739502702.4139044,62.64994025230408,7.162389176817541,1739502702.413909,62.64994025230408,-0.06679415259418686,1739502702.4139147,62.64994025230408,105.63533594387417,1739502702.41392,62.64994025230408,1.3920940996861644,1739502702.4139228,62.64994025230408,0.042777998705374486,1739502702.4139261,62.64994025230408,3.12260593232862,1739502702.4139287,62.64994025230408,-0.2693727679260539,1739502702.4139316,62.64994025230408,-0.06210123751056454,1739502702.4139338,62.64994025230408,2.0153492743689663,1739502702.4139369,62.64994025230408,0.0,1739502702.4139395,62.64994025230408,-0.13560863326423434,1739502702.4139423,62.64994025230408,3.1692971490560304,1739502702.4139447,62.64994025230408,2.1509579076332006 +1739502702.4335752,62.67994022369385,6.92661973719601,1739502702.4335804,62.67994022369385,-0.07322530072694189,1739502702.433586,62.67994022369385,105.84757000034718,1739502702.4335914,62.67994022369385,1.2095789597532118,1739502702.4335942,62.67994022369385,0.044,1739502702.4335973,62.67994022369385,3.1210909848340447,1739502702.4336002,62.67994022369385,-0.27001103604155907,1739502702.433603,62.67994022369385,-0.06340929440008587,1739502702.4336057,62.67994022369385,2.014320470505652,1739502702.4336085,62.67994022369385,0.0,1739502702.4336116,62.67994022369385,-0.11549734122435515,1739502702.4336143,62.67994022369385,3.168327784703925,1739502702.4336176,62.67994022369385,2.136102594613094 +1739502702.4564655,62.69994020462036,6.92661973719601,1739502702.4564707,62.69994020462036,-0.07322530072694189,1739502702.4564779,62.69994020462036,105.84757000034718,1739502702.456485,62.69994020462036,1.2095789597532118,1739502702.4564893,62.69994020462036,0.044,1739502702.456494,62.69994020462036,3.1210909848340447,1739502702.4564984,62.69994020462036,-0.27001103604155907,1739502702.4565027,62.69994020462036,-0.06340929440008587,1739502702.4565072,62.69994020462036,2.014320470505652,1739502702.4565115,62.69994020462036,0.0,1739502702.4565158,62.69994020462036,-0.12178212410744216,1739502702.4565208,62.69994020462036,3.168327784703925,1739502702.4565248,62.69994020462036,2.136102594613094 +1739502702.4923506,62.719940185546875,6.92661973719601,1739502702.4923546,62.719940185546875,-0.07322530072694189,1739502702.4923596,62.719940185546875,105.84757000034718,1739502702.4923656,62.719940185546875,1.2095789597532118,1739502702.4923687,62.719940185546875,0.044,1739502702.4923725,62.719940185546875,3.1210909848340447,1739502702.4923759,62.719940185546875,-0.27001103604155907,1739502702.4923792,62.719940185546875,-0.06340929440008587,1739502702.4923823,62.719940185546875,2.014320470505652,1739502702.4923859,62.719940185546875,0.0,1739502702.4923892,62.719940185546875,-0.12178212410744216,1739502702.4923925,62.719940185546875,3.168327784703925,1739502702.492396,62.719940185546875,2.136102594613094 +1739502702.4954998,62.73994016647339,6.92661973719601,1739502702.4955022,62.73994016647339,-0.07322530072694189,1739502702.4955053,62.73994016647339,105.84757000034718,1739502702.495508,62.73994016647339,1.2095789597532118,1739502702.4955091,62.73994016647339,0.044,1739502702.495511,62.73994016647339,3.1210909848340447,1739502702.4955125,62.73994016647339,-0.27001103604155907,1739502702.4955142,62.73994016647339,-0.06340929440008587,1739502702.4955153,62.73994016647339,2.014320470505652,1739502702.4955173,62.73994016647339,0.0,1739502702.4955184,62.73994016647339,-0.12178212410744216,1739502702.49552,62.73994016647339,3.168327784703925,1739502702.4955215,62.73994016647339,2.136102594613094 +1739502702.5158255,62.7599401473999,6.92661973719601,1739502702.5158281,62.7599401473999,-0.07322530072694189,1739502702.5158308,62.7599401473999,105.84757000034718,1739502702.5158334,62.7599401473999,1.2095789597532118,1739502702.5158346,62.7599401473999,0.044,1739502702.5158362,62.7599401473999,3.1210909848340447,1739502702.5158372,62.7599401473999,-0.27001103604155907,1739502702.5158384,62.7599401473999,-0.06340929440008587,1739502702.5158398,62.7599401473999,2.014320470505652,1739502702.5158412,62.7599401473999,0.0,1739502702.5158427,62.7599401473999,-0.12178212410744216,1739502702.5158439,62.7599401473999,3.168327784703925,1739502702.5158453,62.7599401473999,2.136102594613094 +1739502702.5357773,62.779940128326416,6.692411397076601,1739502702.5357802,62.779940128326416,-0.07937921482429289,1739502702.5357828,62.779940128326416,105.86865490487203,1739502702.5357854,62.779940128326416,1.2154062322127388,1739502702.535787,62.779940128326416,0.044,1739502702.535789,62.779940128326416,3.119069696671695,1739502702.5357904,62.779940128326416,-0.2640345648112698,1739502702.5357916,62.779940128326416,-0.06755258366940706,1739502702.5357928,62.779940128326416,2.023974353248729,1739502702.5357945,62.779940128326416,0.0,1739502702.5357957,62.779940128326416,-0.08816761047459648,1739502702.5357974,62.779940128326416,3.167283983101646,1739502702.5357985,62.779940128326416,2.1226465061209043 +1739502702.5565364,62.79994010925293,6.692411397076601,1739502702.556539,62.79994010925293,-0.07937921482429289,1739502702.5565422,62.79994010925293,105.86865490487203,1739502702.556545,62.79994010925293,1.2154062322127388,1739502702.5565462,62.79994010925293,0.044,1739502702.556548,62.79994010925293,3.119069696671695,1739502702.5565493,62.79994010925293,-0.2640345648112698,1739502702.556551,62.79994010925293,-0.06755258366940706,1739502702.556552,62.79994010925293,2.023974353248729,1739502702.5565538,62.79994010925293,0.0,1739502702.556555,62.79994010925293,-0.09867215287217546,1739502702.5565565,62.79994010925293,3.167283983101646,1739502702.5565581,62.79994010925293,2.1226465061209043 +1739502702.57519,62.81994009017944,6.692411397076601,1739502702.575193,62.81994009017944,-0.07937921482429289,1739502702.5751963,62.81994009017944,105.86865490487203,1739502702.5751984,62.81994009017944,1.2154062322127388,1739502702.5751998,62.81994009017944,0.044,1739502702.5752015,62.81994009017944,3.119069696671695,1739502702.5752032,62.81994009017944,-0.2640345648112698,1739502702.5752046,62.81994009017944,-0.06755258366940706,1739502702.5752058,62.81994009017944,2.023974353248729,1739502702.5752075,62.81994009017944,0.0,1739502702.5752087,62.81994009017944,-0.09867215287217546,1739502702.5752103,62.81994009017944,3.167283983101646,1739502702.5752118,62.81994009017944,2.1226465061209043 +1739502702.5956662,62.83994007110596,6.692411397076601,1739502702.5956688,62.83994007110596,-0.07937921482429289,1739502702.5956721,62.83994007110596,105.86865490487203,1739502702.5956745,62.83994007110596,1.2154062322127388,1739502702.595676,62.83994007110596,0.044,1739502702.5956776,62.83994007110596,3.119069696671695,1739502702.5956793,62.83994007110596,-0.2640345648112698,1739502702.5956807,62.83994007110596,-0.06755258366940706,1739502702.5956821,62.83994007110596,2.023974353248729,1739502702.5956836,62.83994007110596,0.0,1739502702.5956848,62.83994007110596,-0.09867215287217546,1739502702.5956864,62.83994007110596,3.167283983101646,1739502702.5956879,62.83994007110596,2.1226465061209043 +1739502702.615163,62.85994005203247,6.692411397076601,1739502702.615166,62.85994005203247,-0.07937921482429289,1739502702.6151693,62.85994005203247,105.86865490487203,1739502702.6151724,62.85994005203247,1.2154062322127388,1739502702.615174,62.85994005203247,0.044,1739502702.6151762,62.85994005203247,3.119069696671695,1739502702.6151776,62.85994005203247,-0.2640345648112698,1739502702.6151793,62.85994005203247,-0.06755258366940706,1739502702.6151807,62.85994005203247,2.023974353248729,1739502702.6151826,62.85994005203247,0.0,1739502702.615184,62.85994005203247,-0.09867215287217546,1739502702.6151857,62.85994005203247,3.167283983101646,1739502702.6151872,62.85994005203247,2.1226465061209043 +1739502702.6387904,62.879940032958984,6.459539216885268,1739502702.6387956,62.879940032958984,-0.08524039965441776,1739502702.6388013,62.879940032958984,106.6881379480606,1739502702.6388083,62.879940032958984,0.4182084410417777,1739502702.638812,62.879940032958984,0.065,1739502702.638817,62.879940032958984,3.1167290193347026,1739502702.6388214,62.879940032958984,-0.2981828405590059,1739502702.6388257,62.879940032958984,-0.06269701924051282,1739502702.6388304,62.879940032958984,1.9694305881614935,1739502702.638835,62.879940032958984,0.0,1739502702.6388392,62.879940032958984,-0.16228183505351718,1739502702.638844,62.879940032958984,3.16609095250424,1739502702.6388483,62.879940032958984,2.1118343845002836 +1739502702.6574032,62.8999400138855,6.459539216885268,1739502702.657408,62.8999400138855,-0.08524039965441776,1739502702.6574144,62.8999400138855,106.6881379480606,1739502702.657421,62.8999400138855,0.4182084410417777,1739502702.657425,62.8999400138855,0.065,1739502702.6574297,62.8999400138855,3.1167290193347026,1739502702.6574342,62.8999400138855,-0.2981828405590059,1739502702.6574388,62.8999400138855,-0.06269701924051282,1739502702.657443,62.8999400138855,1.9694305881614935,1739502702.6574476,62.8999400138855,0.0,1739502702.6574523,62.8999400138855,-0.14240379633879008,1739502702.6574566,62.8999400138855,3.16609095250424,1739502702.6574612,62.8999400138855,2.1118343845002836 +1739502702.683098,62.91993999481201,6.459539216885268,1739502702.6831071,62.91993999481201,-0.08524039965441776,1739502702.6831179,62.91993999481201,106.6881379480606,1739502702.6831279,62.91993999481201,0.4182084410417777,1739502702.6831326,62.91993999481201,0.065,1739502702.683139,62.91993999481201,3.1167290193347026,1739502702.683144,62.91993999481201,-0.2981828405590059,1739502702.683149,62.91993999481201,-0.06269701924051282,1739502702.6831539,62.91993999481201,1.9694305881614935,1739502702.6831596,62.91993999481201,0.0,1739502702.6831644,62.91993999481201,-0.14240379633879008,1739502702.6831696,62.91993999481201,3.16609095250424,1739502702.6831748,62.91993999481201,2.1118343845002836 +1739502702.7029936,62.939939975738525,6.459539216885268,1739502702.703003,62.939939975738525,-0.08524039965441776,1739502702.703013,62.939939975738525,106.6881379480606,1739502702.7030232,62.939939975738525,0.4182084410417777,1739502702.703028,62.939939975738525,0.065,1739502702.7030344,62.939939975738525,3.1167290193347026,1739502702.7030396,62.939939975738525,-0.2981828405590059,1739502702.703045,62.939939975738525,-0.06269701924051282,1739502702.7030494,62.939939975738525,1.9694305881614935,1739502702.7030554,62.939939975738525,0.0,1739502702.70306,62.939939975738525,-0.14240379633879008,1739502702.7030654,62.939939975738525,3.16609095250424,1739502702.7030702,62.939939975738525,2.1118343845002836 +1739502702.7203732,62.95993995666504,6.459539216885268,1739502702.7203822,62.95993995666504,-0.08524039965441776,1739502702.7203932,62.95993995666504,106.6881379480606,1739502702.7204037,62.95993995666504,0.4182084410417777,1739502702.7204087,62.95993995666504,0.065,1739502702.7204146,62.95993995666504,3.1167290193347026,1739502702.72042,62.95993995666504,-0.2981828405590059,1739502702.7204247,62.95993995666504,-0.06269701924051282,1739502702.7204294,62.95993995666504,1.9694305881614935,1739502702.7204351,62.95993995666504,0.0,1739502702.72044,62.95993995666504,-0.14240379633879008,1739502702.720445,62.95993995666504,3.16609095250424,1739502702.7204497,62.95993995666504,2.1118343845002836 +1739502702.746284,62.97993993759155,6.459539216885268,1739502702.74629,62.97993993759155,-0.08524039965441776,1739502702.7462974,62.97993993759155,106.6881379480606,1739502702.7463043,62.97993993759155,0.4182084410417777,1739502702.7463078,62.97993993759155,0.065,1739502702.746312,62.97993993759155,3.1167290193347026,1739502702.7463155,62.97993993759155,-0.2981828405590059,1739502702.746319,62.97993993759155,-0.06269701924051282,1739502702.7463222,62.97993993759155,1.9694305881614935,1739502702.746326,62.97993993759155,0.0,1739502702.7463293,62.97993993759155,-0.14240379633879008,1739502702.746333,62.97993993759155,3.16609095250424,1739502702.7463365,62.97993993759155,2.1118343845002836 +1739502702.7646575,62.999939918518066,6.228122458662758,1739502702.7646632,62.999939918518066,-0.09078153256094268,1739502702.764691,62.999939918518066,106.69832582655529,1739502702.7647002,62.999939918518066,0.4399936624039431,1739502702.7647038,62.999939918518066,0.065,1739502702.7647083,62.999939918518066,3.1146851779070968,1739502702.7647116,62.999939918518066,-0.29040508122020314,1739502702.7647152,62.999939918518066,-0.06651252251924519,1739502702.7647185,62.999939918518066,1.9817229971812247,1739502702.7647223,62.999939918518066,0.0,1739502702.7647257,62.999939918518066,-0.10127075288285939,1739502702.7647295,62.999939918518066,3.1648605996554053,1739502702.7647336,62.999939918518066,2.095847834571857 +1739502702.7863529,63.01993989944458,6.228122458662758,1739502702.7863588,63.01993989944458,-0.09078153256094268,1739502702.7863662,63.01993989944458,106.69832582655529,1739502702.7863734,63.01993989944458,0.4399936624039431,1739502702.7863767,63.01993989944458,0.065,1739502702.7863808,63.01993989944458,3.1146851779070968,1739502702.7863846,63.01993989944458,-0.29040508122020314,1739502702.786388,63.01993989944458,-0.06651252251924519,1739502702.7863913,63.01993989944458,1.9817229971812247,1739502702.786395,63.01993989944458,0.0,1739502702.7863984,63.01993989944458,-0.11412483739063228,1739502702.7864022,63.01993989944458,3.1648605996554053,1739502702.7864056,63.01993989944458,2.095847834571857 +1739502702.8115706,63.04993987083435,6.228122458662758,1739502702.8115804,63.04993987083435,-0.09078153256094268,1739502702.8115923,63.04993987083435,106.69832582655529,1739502702.811606,63.04993987083435,0.4399936624039431,1739502702.8116143,63.04993987083435,0.065,1739502702.8116248,63.04993987083435,3.1146851779070968,1739502702.811634,63.04993987083435,-0.29040508122020314,1739502702.8116434,63.04993987083435,-0.06651252251924519,1739502702.8116524,63.04993987083435,1.9817229971812247,1739502702.8116622,63.04993987083435,0.0,1739502702.811671,63.04993987083435,-0.11412483739063228,1739502702.8116803,63.04993987083435,3.1648605996554053,1739502702.811686,63.04993987083435,2.095847834571857 +1739502702.8244977,63.069939851760864,6.228122458662758,1739502702.8245003,63.069939851760864,-0.09078153256094268,1739502702.824504,63.069939851760864,106.69832582655529,1739502702.824507,63.069939851760864,0.4399936624039431,1739502702.8245084,63.069939851760864,0.065,1739502702.82451,63.069939851760864,3.1146851779070968,1739502702.824512,63.069939851760864,-0.29040508122020314,1739502702.8245134,63.069939851760864,-0.06651252251924519,1739502702.824515,63.069939851760864,1.9817229971812247,1739502702.824517,63.069939851760864,0.0,1739502702.824519,63.069939851760864,-0.11412483739063228,1739502702.8245206,63.069939851760864,3.1648605996554053,1739502702.8245225,63.069939851760864,2.095847834571857 +1739502702.8440626,63.08993983268738,6.228122458662758,1739502702.844066,63.08993983268738,-0.09078153256094268,1739502702.8440695,63.08993983268738,106.69832582655529,1739502702.8440728,63.08993983268738,0.4399936624039431,1739502702.8440745,63.08993983268738,0.065,1739502702.8440764,63.08993983268738,3.1146851779070968,1739502702.844078,63.08993983268738,-0.29040508122020314,1739502702.8440797,63.08993983268738,-0.06651252251924519,1739502702.844081,63.08993983268738,1.9817229971812247,1739502702.8440828,63.08993983268738,0.0,1739502702.8440845,63.08993983268738,-0.11412483739063228,1739502702.844086,63.08993983268738,3.1648605996554053,1739502702.8440876,63.08993983268738,2.095847834571857 +1739502702.869175,63.10993981361389,5.998269372888142,1739502702.8691883,63.10993981361389,-0.09600223189198953,1739502702.869203,63.10993981361389,106.70844458302871,1739502702.8692186,63.10993981361389,0.45488846919810344,1739502702.8692262,63.10993981361389,0.065,1739502702.8692362,63.10993981361389,3.1125567662717675,1739502702.8692443,63.10993981361389,-0.28311602313383283,1739502702.8692522,63.10993981361389,-0.07068538877926611,1739502702.8692596,63.10993981361389,1.9933126706919257,1739502702.869269,63.10993981361389,0.0,1739502702.869278,63.10993981361389,-0.07907543764401656,1739502702.8692873,63.10993981361389,3.1636302468065707,1739502702.8692963,63.10993981361389,2.08334105293807 +1739502702.9127693,63.13993978500366,5.998269372888142,1739502702.9127781,63.13993978500366,-0.09600223189198953,1739502702.9127903,63.13993978500366,106.70844458302871,1739502702.912804,63.13993978500366,0.45488846919810344,1739502702.9128115,63.13993978500366,0.065,1739502702.9128213,63.13993978500366,3.1125567662717675,1739502702.9128299,63.13993978500366,-0.28311602313383283,1739502702.9128387,63.13993978500366,-0.07068538877926611,1739502702.9128473,63.13993978500366,1.9933126706919257,1739502702.912857,63.13993978500366,0.0,1739502702.9128659,63.13993978500366,-0.09002838224614407,1739502702.912875,63.13993978500366,3.1636302468065707,1739502702.912884,63.13993978500366,2.08334105293807 +1739502702.9284434,63.159939765930176,5.998269372888142,1739502702.9284494,63.159939765930176,-0.09600223189198953,1739502702.9284573,63.159939765930176,106.70844458302871,1739502702.9284647,63.159939765930176,0.45488846919810344,1739502702.9284685,63.159939765930176,0.065,1739502702.9284732,63.159939765930176,3.1125567662717675,1739502702.9284768,63.159939765930176,-0.28311602313383283,1739502702.9284801,63.159939765930176,-0.07068538877926611,1739502702.9284837,63.159939765930176,1.9933126706919257,1739502702.9284878,63.159939765930176,0.0,1739502702.9284916,63.159939765930176,-0.09002838224614407,1739502702.9284952,63.159939765930176,3.1636302468065707,1739502702.928499,63.159939765930176,2.08334105293807 +1739502702.950476,63.17993974685669,5.998269372888142,1739502702.9504821,63.17993974685669,-0.09600223189198953,1739502702.9504905,63.17993974685669,106.70844458302871,1739502702.9504993,63.17993974685669,0.45488846919810344,1739502702.9505033,63.17993974685669,0.065,1739502702.9505086,63.17993974685669,3.1125567662717675,1739502702.9505134,63.17993974685669,-0.28311602313383283,1739502702.9505184,63.17993974685669,-0.07068538877926611,1739502702.950523,63.17993974685669,1.9933126706919257,1739502702.9505274,63.17993974685669,0.0,1739502702.9505324,63.17993974685669,-0.09002838224614407,1739502702.950537,63.17993974685669,3.1636302468065707,1739502702.9505415,63.17993974685669,2.08334105293807 +1739502702.9678845,63.20993971824646,5.769638302642161,1739502702.967887,63.20993971824646,-0.10090376610591356,1739502702.96789,63.20993971824646,106.71850925165374,1739502702.9678926,63.20993971824646,0.46412412268247083,1739502702.967894,63.20993971824646,0.065,1739502702.9678957,63.20993971824646,3.1103327760958868,1739502702.9678972,63.20993971824646,-0.27557894270873573,1739502702.9678984,63.20993971824646,-0.07509951043169992,1739502702.9678996,63.20993971824646,2.0053679852467434,1739502702.9679015,63.20993971824646,0.0,1739502702.9679027,63.20993971824646,-0.05845677195048919,1739502702.9679043,63.20993971824646,3.162272736161935,1739502702.9679055,63.20993971824646,2.0736908918833667 +1739502702.9878888,63.229939699172974,5.769638302642161,1739502702.9878912,63.229939699172974,-0.10090376610591356,1739502702.987894,63.229939699172974,106.71850925165374,1739502702.9878967,63.229939699172974,0.46412412268247083,1739502702.9878979,63.229939699172974,0.065,1739502702.9878995,63.229939699172974,3.1103327760958868,1739502702.987901,63.229939699172974,-0.27557894270873573,1739502702.9879026,63.229939699172974,-0.07509951043169992,1739502702.9879038,63.229939699172974,2.0053679852467434,1739502702.9879053,63.229939699172974,0.0,1739502702.9879065,63.229939699172974,-0.06832290663662333,1739502702.987908,63.229939699172974,3.162272736161935,1739502702.987909,63.229939699172974,2.0736908918833667 +1739502703.0077758,63.24993968009949,5.769638302642161,1739502703.00778,63.24993968009949,-0.10090376610591356,1739502703.0077853,63.24993968009949,106.71850925165374,1739502703.00779,63.24993968009949,0.46412412268247083,1739502703.0077932,63.24993968009949,0.065,1739502703.0077972,63.24993968009949,3.1103327760958868,1739502703.0078,63.24993968009949,-0.27557894270873573,1739502703.0078032,63.24993968009949,-0.07509951043169992,1739502703.0078056,63.24993968009949,2.0053679852467434,1739502703.0078087,63.24993968009949,0.0,1739502703.0078115,63.24993968009949,-0.06832290663662333,1739502703.0078144,63.24993968009949,3.162272736161935,1739502703.007817,63.24993968009949,2.0736908918833667 +1739502703.0281653,63.269939661026,5.769638302642161,1739502703.0281684,63.269939661026,-0.10090376610591356,1739502703.0281718,63.269939661026,106.71850925165374,1739502703.0281749,63.269939661026,0.46412412268247083,1739502703.0281763,63.269939661026,0.065,1739502703.028178,63.269939661026,3.1103327760958868,1739502703.0281794,63.269939661026,-0.27557894270873573,1739502703.028181,63.269939661026,-0.07509951043169992,1739502703.0281823,63.269939661026,2.0053679852467434,1739502703.0281842,63.269939661026,0.0,1739502703.0281854,63.269939661026,-0.06832290663662333,1739502703.0281868,63.269939661026,3.162272736161935,1739502703.0281885,63.269939661026,2.0736908918833667 +1739502703.0472162,63.289939641952515,5.769638302642161,1739502703.0472188,63.289939641952515,-0.10090376610591356,1739502703.047222,63.289939641952515,106.71850925165374,1739502703.0472248,63.289939641952515,0.46412412268247083,1739502703.0472264,63.289939641952515,0.065,1739502703.0472288,63.289939641952515,3.1103327760958868,1739502703.0472302,63.289939641952515,-0.27557894270873573,1739502703.0472314,63.289939641952515,-0.07509951043169992,1739502703.0472329,63.289939641952515,2.0053679852467434,1739502703.0472345,63.289939641952515,0.0,1739502703.0472357,63.289939641952515,-0.06832290663662333,1739502703.0472372,63.289939641952515,3.162272736161935,1739502703.0472383,63.289939641952515,2.0736908918833667 +1739502703.0673828,63.30993962287903,5.769638302642161,1739502703.0673866,63.30993962287903,-0.10090376610591356,1739502703.0673912,63.30993962287903,106.71850925165374,1739502703.067395,63.30993962287903,0.46412412268247083,1739502703.067397,63.30993962287903,0.065,1739502703.0674,63.30993962287903,3.1103327760958868,1739502703.0674021,63.30993962287903,-0.27557894270873573,1739502703.0674043,63.30993962287903,-0.07509951043169992,1739502703.0674064,63.30993962287903,2.0053679852467434,1739502703.067409,63.30993962287903,0.0,1739502703.0674112,63.30993962287903,-0.06832290663662333,1739502703.0674143,63.30993962287903,3.162272736161935,1739502703.067417,63.30993962287903,2.0736908918833667 +1739502703.0892262,63.32993960380554,5.541933909912263,1739502703.089229,63.32993960380554,-0.10545646771698358,1739502703.0892322,63.32993960380554,106.99378738957041,1739502703.0892348,63.32993960380554,0.20341726876539967,1739502703.0892363,63.32993960380554,0.065,1739502703.0892382,63.32993960380554,3.10967394133611,1739502703.0892398,63.32993960380554,-0.27261232832108884,1739502703.089241,63.32993960380554,-0.07337301529986268,1739502703.0892425,63.32993960380554,2.0101329601614815,1739502703.089244,63.32993960380554,0.0,1739502703.089245,63.32993960380554,-0.05079473135530159,1739502703.0892465,63.32993960380554,3.160735299162871,1739502703.089248,63.32993960380554,2.0664052498835632 +1739502703.1079617,63.349939584732056,5.541933909912263,1739502703.1079638,63.349939584732056,-0.10545646771698358,1739502703.1079667,63.349939584732056,106.99378738957041,1739502703.1079695,63.349939584732056,0.20341726876539967,1739502703.1079707,63.349939584732056,0.065,1739502703.1079726,63.349939584732056,3.10967394133611,1739502703.1079738,63.349939584732056,-0.27261232832108884,1739502703.1079755,63.349939584732056,-0.07337301529986268,1739502703.1079767,63.349939584732056,2.0101329601614815,1739502703.1079786,63.349939584732056,0.0,1739502703.1079798,63.349939584732056,-0.05627228972208176,1739502703.1079812,63.349939584732056,3.160735299162871,1739502703.1079829,63.349939584732056,2.0664052498835632 +1739502703.1291611,63.36993956565857,5.541933909912263,1739502703.1291635,63.36993956565857,-0.10545646771698358,1739502703.1291664,63.36993956565857,106.99378738957041,1739502703.129169,63.36993956565857,0.20341726876539967,1739502703.1291702,63.36993956565857,0.065,1739502703.129172,63.36993956565857,3.10967394133611,1739502703.1291735,63.36993956565857,-0.27261232832108884,1739502703.1291747,63.36993956565857,-0.07337301529986268,1739502703.1291761,63.36993956565857,2.0101329601614815,1739502703.1291778,63.36993956565857,0.0,1739502703.1291792,63.36993956565857,-0.05627228972208176,1739502703.1291807,63.36993956565857,3.160735299162871,1739502703.129182,63.36993956565857,2.0664052498835632 +1739502703.147612,63.38993954658508,5.541933909912263,1739502703.147615,63.38993954658508,-0.10545646771698358,1739502703.147618,63.38993954658508,106.99378738957041,1739502703.147621,63.38993954658508,0.20341726876539967,1739502703.1476223,63.38993954658508,0.065,1739502703.1476245,63.38993954658508,3.10967394133611,1739502703.1476257,63.38993954658508,-0.27261232832108884,1739502703.1476274,63.38993954658508,-0.07337301529986268,1739502703.1476285,63.38993954658508,2.0101329601614815,1739502703.1476305,63.38993954658508,0.0,1739502703.1476316,63.38993954658508,-0.05627228972208176,1739502703.1476328,63.38993954658508,3.160735299162871,1739502703.1476345,63.38993954658508,2.0664052498835632 +1739502703.1673312,63.4099395275116,5.541933909912263,1739502703.167334,63.4099395275116,-0.10545646771698358,1739502703.167337,63.4099395275116,106.99378738957041,1739502703.1673396,63.4099395275116,0.20341726876539967,1739502703.1673408,63.4099395275116,0.065,1739502703.1673427,63.4099395275116,3.10967394133611,1739502703.167344,63.4099395275116,-0.27261232832108884,1739502703.1673455,63.4099395275116,-0.07337301529986268,1739502703.1673467,63.4099395275116,2.0101329601614815,1739502703.1673484,63.4099395275116,0.0,1739502703.1673498,63.4099395275116,-0.05627228972208176,1739502703.1673512,63.4099395275116,3.160735299162871,1739502703.1673527,63.4099395275116,2.0664052498835632 +1739502703.187617,63.42993950843811,5.3149786312174,1739502703.1876197,63.42993950843811,-0.10964062679466924,1739502703.1876223,63.42993950843811,107.30820996041838,1739502703.1876254,63.42993950843811,-0.0986735353301138,1739502703.187627,63.42993950843811,0.065,1739502703.1876287,63.42993950843811,3.1093445374240027,1739502703.1876302,63.42993950843811,-0.2697953705135101,1739502703.1876318,63.42993950843811,-0.07061274341930904,1739502703.187633,63.42993950843811,2.0146680360783,1739502703.187635,63.42993950843811,0.0,1739502703.1876361,63.42993950843811,-0.04070725338436906,1739502703.1876378,63.42993950843811,3.1591753574167,1739502703.1876395,63.42993950843811,2.0602393665073415 +1739502703.2073588,63.449939489364624,5.3149786312174,1739502703.2073615,63.449939489364624,-0.10964062679466924,1739502703.2073648,63.449939489364624,107.30820996041838,1739502703.2073677,63.449939489364624,-0.0986735353301138,1739502703.2073689,63.449939489364624,0.065,1739502703.2073708,63.449939489364624,3.1093445374240027,1739502703.2073722,63.449939489364624,-0.2697953705135101,1739502703.2073739,63.449939489364624,-0.07061274341930904,1739502703.2073748,63.449939489364624,2.0146680360783,1739502703.2073767,63.449939489364624,0.0,1739502703.2073781,63.449939489364624,-0.04557133042904171,1739502703.2073798,63.449939489364624,3.1591753574167,1739502703.2073812,63.449939489364624,2.0602393665073415 +1739502703.227399,63.46993947029114,5.3149786312174,1739502703.227402,63.46993947029114,-0.10964062679466924,1739502703.2274055,63.46993947029114,107.30820996041838,1739502703.2274084,63.46993947029114,-0.0986735353301138,1739502703.2274098,63.46993947029114,0.065,1739502703.2274117,63.46993947029114,3.1093445374240027,1739502703.2274132,63.46993947029114,-0.2697953705135101,1739502703.227415,63.46993947029114,-0.07061274341930904,1739502703.2274163,63.46993947029114,2.0146680360783,1739502703.2274182,63.46993947029114,0.0,1739502703.2274194,63.46993947029114,-0.04557133042904171,1739502703.227421,63.46993947029114,3.1591753574167,1739502703.2274225,63.46993947029114,2.0602393665073415 +1739502703.2473464,63.48993945121765,5.3149786312174,1739502703.2473493,63.48993945121765,-0.10964062679466924,1739502703.2473521,63.48993945121765,107.30820996041838,1739502703.2473552,63.48993945121765,-0.0986735353301138,1739502703.2473567,63.48993945121765,0.065,1739502703.2473583,63.48993945121765,3.1093445374240027,1739502703.2473595,63.48993945121765,-0.2697953705135101,1739502703.247361,63.48993945121765,-0.07061274341930904,1739502703.2473624,63.48993945121765,2.0146680360783,1739502703.247364,63.48993945121765,0.0,1739502703.2473657,63.48993945121765,-0.04557133042904171,1739502703.247367,63.48993945121765,3.1591753574167,1739502703.247368,63.48993945121765,2.0602393665073415 +1739502703.2674668,63.509939432144165,5.3149786312174,1739502703.26747,63.509939432144165,-0.10964062679466924,1739502703.2674727,63.509939432144165,107.30820996041838,1739502703.2674754,63.509939432144165,-0.0986735353301138,1739502703.2674768,63.509939432144165,0.065,1739502703.2674785,63.509939432144165,3.1093445374240027,1739502703.2674801,63.509939432144165,-0.2697953705135101,1739502703.2674813,63.509939432144165,-0.07061274341930904,1739502703.2674825,63.509939432144165,2.0146680360783,1739502703.2674844,63.509939432144165,0.0,1739502703.2674856,63.509939432144165,-0.04557133042904171,1739502703.2674873,63.509939432144165,3.1591753574167,1739502703.2674885,63.509939432144165,2.0602393665073415 +1739502703.2874165,63.52993941307068,5.3149786312174,1739502703.287419,63.52993941307068,-0.10964062679466924,1739502703.2874224,63.52993941307068,107.30820996041838,1739502703.2874253,63.52993941307068,-0.0986735353301138,1739502703.2874265,63.52993941307068,0.065,1739502703.2874284,63.52993941307068,3.1093445374240027,1739502703.2874298,63.52993941307068,-0.2697953705135101,1739502703.2874312,63.52993941307068,-0.07061274341930904,1739502703.2874324,63.52993941307068,2.0146680360783,1739502703.287434,63.52993941307068,0.0,1739502703.2874353,63.52993941307068,-0.04557133042904171,1739502703.2874367,63.52993941307068,3.1591753574167,1739502703.2874382,63.52993941307068,2.0602393665073415 +1739502703.3075874,63.54993939399719,5.088625304328671,1739502703.3075895,63.54993939399719,-0.11346046359113338,1739502703.3075926,63.54993939399719,107.61939281969823,1739502703.3075955,63.54993939399719,-0.4000691655238664,1739502703.3075972,63.54993939399719,0.065,1739502703.3075986,63.54993939399719,3.109089912438834,1739502703.3076,63.54993939399719,-0.26637783881106597,1739502703.3076017,63.54993939399719,-0.06782476752001479,1739502703.307603,63.54993939399719,2.0201837261673883,1739502703.3076048,63.54993939399719,0.0,1739502703.307606,63.54993939399719,-0.030430519179067732,1739502703.3076077,63.54993939399719,3.157615415670529,1739502703.3076088,63.54993939399719,2.0553457519642904 +1739502703.3273492,63.569939374923706,5.088625304328671,1739502703.327352,63.569939374923706,-0.11346046359113338,1739502703.3273551,63.569939374923706,107.61939281969823,1739502703.327358,63.569939374923706,-0.4000691655238664,1739502703.3273594,63.569939374923706,0.065,1739502703.3273613,63.569939374923706,3.109089912438834,1739502703.3273625,63.569939374923706,-0.26637783881106597,1739502703.3273642,63.569939374923706,-0.06782476752001479,1739502703.3273656,63.569939374923706,2.0201837261673883,1739502703.327367,63.569939374923706,0.0,1739502703.3273687,63.569939374923706,-0.035162025796902086,1739502703.32737,63.569939374923706,3.157615415670529,1739502703.3273718,63.569939374923706,2.0553457519642904 +1739502703.3494434,63.58993935585022,5.088625304328671,1739502703.3494477,63.58993935585022,-0.11346046359113338,1739502703.3494527,63.58993935585022,107.61939281969823,1739502703.3494587,63.58993935585022,-0.4000691655238664,1739502703.349462,63.58993935585022,0.065,1739502703.349466,63.58993935585022,3.109089912438834,1739502703.3494694,63.58993935585022,-0.26637783881106597,1739502703.3494728,63.58993935585022,-0.06782476752001479,1739502703.3494759,63.58993935585022,2.0201837261673883,1739502703.3494792,63.58993935585022,0.0,1739502703.3494825,63.58993935585022,-0.035162025796902086,1739502703.349486,63.58993935585022,3.157615415670529,1739502703.3494892,63.58993935585022,2.0553457519642904 +1739502703.3692374,63.60993933677673,5.088625304328671,1739502703.3692412,63.60993933677673,-0.11346046359113338,1739502703.3692462,63.60993933677673,107.61939281969823,1739502703.3692513,63.60993933677673,-0.4000691655238664,1739502703.3692544,63.60993933677673,0.065,1739502703.369258,63.60993933677673,3.109089912438834,1739502703.369261,63.60993933677673,-0.26637783881106597,1739502703.3692641,63.60993933677673,-0.06782476752001479,1739502703.3692672,63.60993933677673,2.0201837261673883,1739502703.3692703,63.60993933677673,0.0,1739502703.3692734,63.60993933677673,-0.035162025796902086,1739502703.3692765,63.60993933677673,3.157615415670529,1739502703.3692794,63.60993933677673,2.0553457519642904 +1739502703.3898907,63.62993931770325,5.088625304328671,1739502703.3898942,63.62993931770325,-0.11346046359113338,1739502703.3898985,63.62993931770325,107.61939281969823,1739502703.3899038,63.62993931770325,-0.4000691655238664,1739502703.3899064,63.62993931770325,0.065,1739502703.38991,63.62993931770325,3.109089912438834,1739502703.389913,63.62993931770325,-0.26637783881106597,1739502703.389916,63.62993931770325,-0.06782476752001479,1739502703.389919,63.62993931770325,2.0201837261673883,1739502703.3899221,63.62993931770325,0.0,1739502703.3899248,63.62993931770325,-0.035162025796902086,1739502703.3899279,63.62993931770325,3.157615415670529,1739502703.389931,63.62993931770325,2.0553457519642904 +1739502703.4072094,63.64993929862976,4.862758551748229,1739502703.4072118,63.64993929862976,-0.11691964308037406,1739502703.4072146,63.64993929862976,107.64333815465125,1739502703.4072175,63.64993929862976,-0.41630433087978913,1739502703.4072187,63.64993929862976,0.065,1739502703.4072201,63.64993929862976,3.107145690831883,1739502703.4072218,63.64993929862976,-0.25824809335835014,1739502703.407223,63.64993929862976,-0.071070273206053,1739502703.4072244,63.64993929862976,2.0333654087615045,1739502703.4072258,63.64993929862976,0.0,1739502703.407227,63.64993929862976,-0.010381265840513257,1739502703.4072285,63.64993929862976,3.156055473924358,1739502703.40723,63.64993929862976,2.0514906671657465 +1739502703.4279003,63.669939279556274,4.862758551748229,1739502703.4279027,63.669939279556274,-0.11691964308037406,1739502703.4279056,63.669939279556274,107.64333815465125,1739502703.4279082,63.669939279556274,-0.41630433087978913,1739502703.4279094,63.669939279556274,0.065,1739502703.4279108,63.669939279556274,3.107145690831883,1739502703.4279122,63.669939279556274,-0.25824809335835014,1739502703.4279134,63.669939279556274,-0.071070273206053,1739502703.4279144,63.669939279556274,2.0333654087615045,1739502703.427916,63.669939279556274,0.0,1739502703.4279172,63.669939279556274,-0.01812525840424195,1739502703.4279187,63.669939279556274,3.156055473924358,1739502703.4279199,63.669939279556274,2.0514906671657465 +1739502703.4473004,63.68993926048279,4.862758551748229,1739502703.447303,63.68993926048279,-0.11691964308037406,1739502703.4473062,63.68993926048279,107.64333815465125,1739502703.4473093,63.68993926048279,-0.41630433087978913,1739502703.447311,63.68993926048279,0.065,1739502703.4473124,63.68993926048279,3.107145690831883,1739502703.447314,63.68993926048279,-0.25824809335835014,1739502703.4473152,63.68993926048279,-0.071070273206053,1739502703.4473164,63.68993926048279,2.0333654087615045,1739502703.4473186,63.68993926048279,0.0,1739502703.4473197,63.68993926048279,-0.01812525840424195,1739502703.4473214,63.68993926048279,3.156055473924358,1739502703.4473228,63.68993926048279,2.0514906671657465 +1739502703.4675,63.7099392414093,4.862758551748229,1739502703.4675047,63.7099392414093,-0.11691964308037406,1739502703.4675097,63.7099392414093,107.64333815465125,1739502703.4675145,63.7099392414093,-0.41630433087978913,1739502703.4675188,63.7099392414093,0.065,1739502703.4675221,63.7099392414093,3.107145690831883,1739502703.4675236,63.7099392414093,-0.25824809335835014,1739502703.4675248,63.7099392414093,-0.071070273206053,1739502703.4675262,63.7099392414093,2.0333654087615045,1739502703.4675276,63.7099392414093,0.0,1739502703.467529,63.7099392414093,-0.01812525840424195,1739502703.4675305,63.7099392414093,3.156055473924358,1739502703.4675317,63.7099392414093,2.0514906671657465 +1739502703.4874225,63.729939222335815,4.862758551748229,1739502703.487425,63.729939222335815,-0.11691964308037406,1739502703.4874282,63.729939222335815,107.64333815465125,1739502703.4874308,63.729939222335815,-0.41630433087978913,1739502703.4874325,63.729939222335815,0.065,1739502703.4874341,63.729939222335815,3.107145690831883,1739502703.4874356,63.729939222335815,-0.25824809335835014,1739502703.487437,63.729939222335815,-0.071070273206053,1739502703.4874384,63.729939222335815,2.0333654087615045,1739502703.48744,63.729939222335815,0.0,1739502703.4874418,63.729939222335815,-0.01812525840424195,1739502703.4874432,63.729939222335815,3.156055473924358,1739502703.4874444,63.729939222335815,2.0514906671657465 +1739502703.5074859,63.74993920326233,4.862758551748229,1739502703.5074885,63.74993920326233,-0.11691964308037406,1739502703.5074916,63.74993920326233,107.64333815465125,1739502703.5074947,63.74993920326233,-0.41630433087978913,1739502703.5074959,63.74993920326233,0.065,1739502703.5074978,63.74993920326233,3.107145690831883,1739502703.5074997,63.74993920326233,-0.25824809335835014,1739502703.5075011,63.74993920326233,-0.071070273206053,1739502703.5075023,63.74993920326233,2.0333654087615045,1739502703.507504,63.74993920326233,0.0,1739502703.5075054,63.74993920326233,-0.01812525840424195,1739502703.5075068,63.74993920326233,3.156055473924358,1739502703.5075083,63.74993920326233,2.0514906671657465 +1739502703.527605,63.76993918418884,4.63720069758525,1739502703.527607,63.76993918418884,-0.1200221330218536,1739502703.5276098,63.76993918418884,108.02514672260311,1739502703.5276127,63.76993918418884,-0.7944505312137902,1739502703.5276139,63.76993918418884,0.065,1739502703.5276158,63.76993918418884,3.1075421204419786,1739502703.5276172,63.76993918418884,-0.2550887233079274,1739502703.5276186,63.76993918418884,-0.06631539305799157,1739502703.5276198,63.76993918418884,2.038511232065328,1739502703.5276217,63.76993918418884,0.0,1739502703.527623,63.76993918418884,-0.007976881397600367,1739502703.5276244,63.76993918418884,3.1544955321781867,1739502703.5276258,63.76993918418884,2.049659483356816 +1739502703.547573,63.789939165115356,4.63720069758525,1739502703.5475755,63.789939165115356,-0.1200221330218536,1739502703.5475783,63.789939165115356,108.02514672260311,1739502703.547581,63.789939165115356,-0.7944505312137902,1739502703.5475824,63.789939165115356,0.065,1739502703.547584,63.789939165115356,3.1075421204419786,1739502703.5475855,63.789939165115356,-0.2550887233079274,1739502703.547587,63.789939165115356,-0.06631539305799157,1739502703.547588,63.789939165115356,2.038511232065328,1739502703.5475895,63.789939165115356,0.0,1739502703.547591,63.789939165115356,-0.011148251291487998,1739502703.5475924,63.789939165115356,3.1544955321781867,1739502703.5475938,63.789939165115356,2.049659483356816 +1739502703.567315,63.80993914604187,4.63720069758525,1739502703.5673177,63.80993914604187,-0.1200221330218536,1739502703.5673208,63.80993914604187,108.02514672260311,1739502703.5673234,63.80993914604187,-0.7944505312137902,1739502703.5673249,63.80993914604187,0.065,1739502703.5673265,63.80993914604187,3.1075421204419786,1739502703.5673277,63.80993914604187,-0.2550887233079274,1739502703.567329,63.80993914604187,-0.06631539305799157,1739502703.5673304,63.80993914604187,2.038511232065328,1739502703.5673318,63.80993914604187,0.0,1739502703.5673332,63.80993914604187,-0.011148251291487998,1739502703.5673347,63.80993914604187,3.1544955321781867,1739502703.5673358,63.80993914604187,2.049659483356816 +1739502703.5873675,63.829939126968384,4.63720069758525,1739502703.58737,63.829939126968384,-0.1200221330218536,1739502703.587373,63.829939126968384,108.02514672260311,1739502703.5873759,63.829939126968384,-0.7944505312137902,1739502703.587377,63.829939126968384,0.065,1739502703.587379,63.829939126968384,3.1075421204419786,1739502703.5873802,63.829939126968384,-0.2550887233079274,1739502703.5873818,63.829939126968384,-0.06631539305799157,1739502703.5873828,63.829939126968384,2.038511232065328,1739502703.5873845,63.829939126968384,0.0,1739502703.587386,63.829939126968384,-0.011148251291487998,1739502703.587387,63.829939126968384,3.1544955321781867,1739502703.5873885,63.829939126968384,2.049659483356816 +1739502703.6072817,63.8499391078949,4.63720069758525,1739502703.6072843,63.8499391078949,-0.1200221330218536,1739502703.6072874,63.8499391078949,108.02514672260311,1739502703.60729,63.8499391078949,-0.7944505312137902,1739502703.6072915,63.8499391078949,0.065,1739502703.6072931,63.8499391078949,3.1075421204419786,1739502703.6072948,63.8499391078949,-0.2550887233079274,1739502703.6072965,63.8499391078949,-0.06631539305799157,1739502703.6072974,63.8499391078949,2.038511232065328,1739502703.6072993,63.8499391078949,0.0,1739502703.6073005,63.8499391078949,-0.011148251291487998,1739502703.607302,63.8499391078949,3.1544955321781867,1739502703.6073034,63.8499391078949,2.049659483356816 +1739502703.6274621,63.86993908882141,4.411817492289305,1739502703.6274643,63.86993908882141,-0.12277056702030009,1739502703.627467,63.86993908882141,108.04385627707669,1739502703.6274695,63.86993908882141,-0.8107095019584629,1739502703.6274712,63.86993908882141,0.065,1739502703.6274726,63.86993908882141,3.105654166273178,1739502703.6274738,63.86993908882141,-0.2469960112228094,1739502703.6274755,63.86993908882141,-0.06944662482701788,1739502703.6274765,63.86993908882141,2.0517517139674686,1739502703.6274781,63.86993908882141,0.0,1739502703.6274796,63.86993908882141,0.009892880457944654,1739502703.627481,63.86993908882141,3.1529355904320155,1739502703.6274824,63.86993908882141,2.0484341914923623 +1739502703.6473136,63.889939069747925,4.411817492289305,1739502703.6473165,63.889939069747925,-0.12277056702030009,1739502703.6473198,63.889939069747925,108.04385627707669,1739502703.6473224,63.889939069747925,-0.8107095019584629,1739502703.6473238,63.889939069747925,0.065,1739502703.6473258,63.889939069747925,3.105654166273178,1739502703.6473272,63.889939069747925,-0.2469960112228094,1739502703.6473286,63.889939069747925,-0.06944662482701788,1739502703.6473298,63.889939069747925,2.0517517139674686,1739502703.6473312,63.889939069747925,0.0,1739502703.6473327,63.889939069747925,0.003317522475106305,1739502703.647334,63.889939069747925,3.1529355904320155,1739502703.6473355,63.889939069747925,2.0484341914923623 +1739502703.667504,63.90993905067444,4.411817492289305,1739502703.667507,63.90993905067444,-0.12277056702030009,1739502703.6675103,63.90993905067444,108.04385627707669,1739502703.6675134,63.90993905067444,-0.8107095019584629,1739502703.6675146,63.90993905067444,0.065,1739502703.6675167,63.90993905067444,3.105654166273178,1739502703.667518,63.90993905067444,-0.2469960112228094,1739502703.6675196,63.90993905067444,-0.06944662482701788,1739502703.6675205,63.90993905067444,2.0517517139674686,1739502703.6675222,63.90993905067444,0.0,1739502703.6675236,63.90993905067444,0.003317522475106305,1739502703.667525,63.90993905067444,3.1529355904320155,1739502703.6675267,63.90993905067444,2.0484341914923623 +1739502703.687386,63.92993903160095,4.411817492289305,1739502703.6873891,63.92993903160095,-0.12277056702030009,1739502703.6873922,63.92993903160095,108.04385627707669,1739502703.687395,63.92993903160095,-0.8107095019584629,1739502703.6873965,63.92993903160095,0.065,1739502703.6873984,63.92993903160095,3.105654166273178,1739502703.6873996,63.92993903160095,-0.2469960112228094,1739502703.6874013,63.92993903160095,-0.06944662482701788,1739502703.6874025,63.92993903160095,2.0517517139674686,1739502703.6874044,63.92993903160095,0.0,1739502703.6874056,63.92993903160095,0.003317522475106305,1739502703.687407,63.92993903160095,3.1529355904320155,1739502703.6874084,63.92993903160095,2.0484341914923623 +1739502703.7077768,63.949939012527466,4.411817492289305,1739502703.7077806,63.949939012527466,-0.12277056702030009,1739502703.707784,63.949939012527466,108.04385627707669,1739502703.7077875,63.949939012527466,-0.8107095019584629,1739502703.707789,63.949939012527466,0.065,1739502703.7077913,63.949939012527466,3.105654166273178,1739502703.7077932,63.949939012527466,-0.2469960112228094,1739502703.7077951,63.949939012527466,-0.06944662482701788,1739502703.7077968,63.949939012527466,2.0517517139674686,1739502703.7077987,63.949939012527466,0.0,1739502703.7078004,63.949939012527466,0.003317522475106305,1739502703.707802,63.949939012527466,3.1529355904320155,1739502703.707804,63.949939012527466,2.0484341914923623 +1739502703.728531,63.96993899345398,4.411817492289305,1739502703.7285337,63.96993899345398,-0.12277056702030009,1739502703.728537,63.96993899345398,108.04385627707669,1739502703.7285402,63.96993899345398,-0.8107095019584629,1739502703.7285416,63.96993899345398,0.065,1739502703.728544,63.96993899345398,3.105654166273178,1739502703.728546,63.96993899345398,-0.2469960112228094,1739502703.7285473,63.96993899345398,-0.06944662482701788,1739502703.7285488,63.96993899345398,2.0517517139674686,1739502703.7285507,63.96993899345398,0.0,1739502703.7285523,63.96993899345398,0.003317522475106305,1739502703.728554,63.96993899345398,3.1529355904320155,1739502703.7285557,63.96993899345398,2.0484341914923623 +1739502703.7479532,63.98993897438049,4.186471853868161,1739502703.7479565,63.98993897438049,-0.12516694767297132,1739502703.7479613,63.98993897438049,108.4565589482467,1739502703.7479646,63.98993897438049,-1.2243994673469625,1739502703.7479663,63.98993897438049,0.065,1739502703.7479684,63.98993897438049,3.106461766790521,1739502703.7479703,63.98993897438049,-0.24309153082962062,1739502703.747972,63.98993897438049,-0.06367886263747273,1739502703.7479737,63.98993897438049,2.058170553112274,1739502703.7479753,63.98993897438049,0.0,1739502703.747977,63.98993897438049,0.011935986186242201,1739502703.7479787,63.98993897438049,3.1513756486858444,1739502703.7479808,63.98993897438049,2.048927838601608 +1739502703.7676573,64.009938955307,4.186471853868161,1739502703.7676601,64.009938955307,-0.12516694767297132,1739502703.767663,64.009938955307,108.4565589482467,1739502703.7676659,64.009938955307,-1.2243994673469625,1739502703.7676675,64.009938955307,0.065,1739502703.7676692,64.009938955307,3.106461766790521,1739502703.7676709,64.009938955307,-0.24309153082962062,1739502703.7676723,64.009938955307,-0.06367886263747273,1739502703.7676735,64.009938955307,2.058170553112274,1739502703.7676752,64.009938955307,0.0,1739502703.7676764,64.009938955307,0.009242714510665717,1739502703.767678,64.009938955307,3.1513756486858444,1739502703.7676795,64.009938955307,2.048927838601608 +1739502703.7874637,64.02993893623352,4.186471853868161,1739502703.7874665,64.02993893623352,-0.12516694767297132,1739502703.7874706,64.02993893623352,108.4565589482467,1739502703.7874737,64.02993893623352,-1.2243994673469625,1739502703.787475,64.02993893623352,0.065,1739502703.787477,64.02993893623352,3.106461766790521,1739502703.7874784,64.02993893623352,-0.24309153082962062,1739502703.7874804,64.02993893623352,-0.06367886263747273,1739502703.7874815,64.02993893623352,2.058170553112274,1739502703.7874835,64.02993893623352,0.0,1739502703.787485,64.02993893623352,0.009242714510665717,1739502703.7874866,64.02993893623352,3.1513756486858444,1739502703.787488,64.02993893623352,2.048927838601608 +1739502703.8074574,64.04993891716003,4.186471853868161,1739502703.8074605,64.04993891716003,-0.12516694767297132,1739502703.807464,64.04993891716003,108.4565589482467,1739502703.8074667,64.04993891716003,-1.2243994673469625,1739502703.8074682,64.04993891716003,0.065,1739502703.80747,64.04993891716003,3.106461766790521,1739502703.8074715,64.04993891716003,-0.24309153082962062,1739502703.8074732,64.04993891716003,-0.06367886263747273,1739502703.8074746,64.04993891716003,2.058170553112274,1739502703.8074763,64.04993891716003,0.0,1739502703.8074777,64.04993891716003,0.009242714510665717,1739502703.8074794,64.04993891716003,3.1513756486858444,1739502703.8074806,64.04993891716003,2.048927838601608 +1739502703.8275766,64.06993889808655,4.186471853868161,1739502703.82758,64.06993889808655,-0.12516694767297132,1739502703.8275833,64.06993889808655,108.4565589482467,1739502703.8275864,64.06993889808655,-1.2243994673469625,1739502703.8275878,64.06993889808655,0.065,1739502703.8275898,64.06993889808655,3.106461766790521,1739502703.8275912,64.06993889808655,-0.24309153082962062,1739502703.8275926,64.06993889808655,-0.06367886263747273,1739502703.8275943,64.06993889808655,2.058170553112274,1739502703.8275957,64.06993889808655,0.0,1739502703.8275974,64.06993889808655,0.009242714510665717,1739502703.8275988,64.06993889808655,3.1513756486858444,1739502703.8276005,64.06993889808655,2.048927838601608 +1739502703.8474813,64.08993887901306,3.9610497810537746,1739502703.8474844,64.08993887901306,-0.127212453332338,1739502703.8474874,64.08993887901306,108.47977946725223,1739502703.84749,64.08993887901306,-1.2496327387905874,1739502703.8474915,64.08993887901306,0.065,1739502703.8474934,64.08993887901306,3.104721218752833,1739502703.8474948,64.08993887901306,-0.2350531922675907,1739502703.8474965,64.08993887901306,-0.06638602928407587,1739502703.847498,64.08993887901306,2.071448618166799,1739502703.8474998,64.08993887901306,0.0,1739502703.8475013,64.08993887901306,0.027092449045553958,1739502703.847503,64.08993887901306,3.1498157069396733,1739502703.8475041,64.08993887901306,2.049934214820649 +1739502703.872414,64.10993885993958,3.9610497810537746,1739502703.8724236,64.10993885993958,-0.127212453332338,1739502703.872434,64.10993885993958,108.47977946725223,1739502703.872444,64.10993885993958,-1.2496327387905874,1739502703.8724487,64.10993885993958,0.065,1739502703.872455,64.10993885993958,3.104721218752833,1739502703.8724606,64.10993885993958,-0.2350531922675907,1739502703.8724654,64.10993885993958,-0.06638602928407587,1739502703.87247,64.10993885993958,2.071448618166799,1739502703.8724754,64.10993885993958,0.0,1739502703.8724802,64.10993885993958,0.021514403346149624,1739502703.8724854,64.10993885993958,3.1498157069396733,1739502703.8724902,64.10993885993958,2.049934214820649 +1739502703.8906693,64.11993885040283,3.9610497810537746,1739502703.8906739,64.11993885040283,-0.127212453332338,1739502703.8906798,64.11993885040283,108.47977946725223,1739502703.890685,64.11993885040283,-1.2496327387905874,1739502703.890688,64.11993885040283,0.065,1739502703.8906913,64.11993885040283,3.104721218752833,1739502703.8906941,64.11993885040283,-0.2350531922675907,1739502703.8906968,64.11993885040283,-0.06638602928407587,1739502703.8906991,64.11993885040283,2.071448618166799,1739502703.890702,64.11993885040283,0.0,1739502703.8907049,64.11993885040283,0.021514403346149624,1739502703.8907077,64.11993885040283,3.1498157069396733,1739502703.8907106,64.11993885040283,2.049934214820649 +1739502703.9089267,64.1499388217926,3.9610497810537746,1739502703.9089303,64.1499388217926,-0.127212453332338,1739502703.9089346,64.1499388217926,108.47977946725223,1739502703.9089386,64.1499388217926,-1.2496327387905874,1739502703.9089408,64.1499388217926,0.065,1739502703.9089437,64.1499388217926,3.104721218752833,1739502703.9089456,64.1499388217926,-0.2350531922675907,1739502703.908948,64.1499388217926,-0.06638602928407587,1739502703.9089499,64.1499388217926,2.071448618166799,1739502703.9089522,64.1499388217926,0.0,1739502703.9089544,64.1499388217926,0.021514403346149624,1739502703.9089568,64.1499388217926,3.1498157069396733,1739502703.908959,64.1499388217926,2.049934214820649 +1739502703.9291074,64.16993880271912,3.9610497810537746,1739502703.9291108,64.16993880271912,-0.127212453332338,1739502703.9291146,64.16993880271912,108.47977946725223,1739502703.9291182,64.16993880271912,-1.2496327387905874,1739502703.92912,64.16993880271912,0.065,1739502703.9291222,64.16993880271912,3.104721218752833,1739502703.9291244,64.16993880271912,-0.2350531922675907,1739502703.9291263,64.16993880271912,-0.06638602928407587,1739502703.9291277,64.16993880271912,2.071448618166799,1739502703.9291298,64.16993880271912,0.0,1739502703.9291315,64.16993880271912,0.021514403346149624,1739502703.9291337,64.16993880271912,3.1498157069396733,1739502703.9291356,64.16993880271912,2.049934214820649 +1739502703.949089,64.18993878364563,3.9610497810537746,1739502703.9490924,64.18993878364563,-0.127212453332338,1739502703.949096,64.18993878364563,108.47977946725223,1739502703.9490998,64.18993878364563,-1.2496327387905874,1739502703.9491017,64.18993878364563,0.065,1739502703.9491038,64.18993878364563,3.104721218752833,1739502703.9491057,64.18993878364563,-0.2350531922675907,1739502703.9491074,64.18993878364563,-0.06638602928407587,1739502703.9491093,64.18993878364563,2.071448618166799,1739502703.9491112,64.18993878364563,0.0,1739502703.9491131,64.18993878364563,0.021514403346149624,1739502703.9491148,64.18993878364563,3.1498157069396733,1739502703.949117,64.18993878364563,2.049934214820649 +1739502703.9700682,64.20993876457214,3.7354348451228407,1739502703.9700723,64.20993876457214,-0.12890771884868357,1739502703.9700773,64.20993876457214,108.87687748548294,1739502703.9700818,64.20993876457214,-1.6516636451934015,1739502703.9700842,64.20993876457214,0.065,1739502703.9700866,64.20993876457214,3.105613352275686,1739502703.970089,64.20993876457214,-0.22979798725620312,1739502703.9700913,64.20993876457214,-0.06072618069245609,1739502703.9700937,64.20993876457214,2.080175659997404,1739502703.9700963,64.20993876457214,0.0,1739502703.9700987,64.20993876457214,0.030620730052122284,1739502703.9701009,64.20993876457214,3.148255765193502,1739502703.9701033,64.20993876457214,2.0524006589067034 +1739502703.9895706,64.22993874549866,3.7354348451228407,1739502703.9895747,64.22993874549866,-0.12890771884868357,1739502703.9895794,64.22993874549866,108.87687748548294,1739502703.9895842,64.22993874549866,-1.6516636451934015,1739502703.9895864,64.22993874549866,0.065,1739502703.9895895,64.22993874549866,3.105613352275686,1739502703.989592,64.22993874549866,-0.22979798725620312,1739502703.9895947,64.22993874549866,-0.06072618069245609,1739502703.989597,64.22993874549866,2.080175659997404,1739502703.9896002,64.22993874549866,0.0,1739502703.9896028,64.22993874549866,0.027775001090700524,1739502703.9896054,64.22993874549866,3.148255765193502,1739502703.9896076,64.22993874549866,2.0524006589067034 +1739502704.0092943,64.24993872642517,3.7354348451228407,1739502704.009299,64.24993872642517,-0.12890771884868357,1739502704.0093036,64.24993872642517,108.87687748548294,1739502704.0093079,64.24993872642517,-1.6516636451934015,1739502704.0093102,64.24993872642517,0.065,1739502704.009313,64.24993872642517,3.105613352275686,1739502704.0093157,64.24993872642517,-0.22979798725620312,1739502704.009318,64.24993872642517,-0.06072618069245609,1739502704.0093212,64.24993872642517,2.080175659997404,1739502704.009324,64.24993872642517,0.0,1739502704.0093262,64.24993872642517,0.027775001090700524,1739502704.0093296,64.24993872642517,3.148255765193502,1739502704.0093322,64.24993872642517,2.0524006589067034 +1739502704.0307176,64.26993870735168,3.7354348451228407,1739502704.0307245,64.26993870735168,-0.12890771884868357,1739502704.0307314,64.26993870735168,108.87687748548294,1739502704.030737,64.26993870735168,-1.6516636451934015,1739502704.0307395,64.26993870735168,0.065,1739502704.0307434,64.26993870735168,3.105613352275686,1739502704.0307465,64.26993870735168,-0.22979798725620312,1739502704.03075,64.26993870735168,-0.06072618069245609,1739502704.0307522,64.26993870735168,2.080175659997404,1739502704.0307562,64.26993870735168,0.0,1739502704.03076,64.26993870735168,0.027775001090700524,1739502704.0307639,64.26993870735168,3.148255765193502,1739502704.030767,64.26993870735168,2.0524006589067034 +1739502704.0505517,64.2899386882782,3.7354348451228407,1739502704.0505557,64.2899386882782,-0.12890771884868357,1739502704.0505605,64.2899386882782,108.87687748548294,1739502704.0505657,64.2899386882782,-1.6516636451934015,1739502704.0505683,64.2899386882782,0.065,1739502704.0505724,64.2899386882782,3.105613352275686,1739502704.050576,64.2899386882782,-0.22979798725620312,1739502704.0505793,64.2899386882782,-0.06072618069245609,1739502704.0505824,64.2899386882782,2.080175659997404,1739502704.0505862,64.2899386882782,0.0,1739502704.0505898,64.2899386882782,0.027775001090700524,1739502704.0505934,64.2899386882782,3.148255765193502,1739502704.050597,64.2899386882782,2.0524006589067034 +1739502704.0700045,64.30993866920471,3.5095240909689966,1739502704.0700083,64.30993866920471,-0.13025277449007877,1739502704.070013,64.30993866920471,109.1818177456125,1739502704.0700173,64.30993866920471,-1.962671083416914,1739502704.0700195,64.30993866920471,0.065,1739502704.0700226,64.30993866920471,3.105926897696744,1739502704.070025,64.30993866920471,-0.2231756523366671,1739502704.0700276,64.30993866920471,-0.057158360105618825,1739502704.07003,64.30993866920471,2.091225400114128,1739502704.0700328,64.30993866920471,0.0,1739502704.070035,64.30993866920471,0.0394348606670638,1739502704.0700376,64.30993866920471,3.146695823447331,1739502704.0700397,64.30993866920471,2.0554342479536793 +1739502704.0903203,64.32993865013123,3.5095240909689966,1739502704.0903249,64.32993865013123,-0.13025277449007877,1739502704.09033,64.32993865013123,109.1818177456125,1739502704.0903347,64.32993865013123,-1.962671083416914,1739502704.0903373,64.32993865013123,0.065,1739502704.0903404,64.32993865013123,3.105926897696744,1739502704.090343,64.32993865013123,-0.2231756523366671,1739502704.0903454,64.32993865013123,-0.057158360105618825,1739502704.0903478,64.32993865013123,2.091225400114128,1739502704.0903509,64.32993865013123,0.0,1739502704.0903533,64.32993865013123,0.035791152160448814,1739502704.0903559,64.32993865013123,3.146695823447331,1739502704.0903583,64.32993865013123,2.0554342479536793 +1739502704.1099308,64.34993863105774,3.5095240909689966,1739502704.109935,64.34993863105774,-0.13025277449007877,1739502704.10994,64.34993863105774,109.1818177456125,1739502704.1099446,64.34993863105774,-1.962671083416914,1739502704.1099472,64.34993863105774,0.065,1739502704.1099503,64.34993863105774,3.105926897696744,1739502704.109953,64.34993863105774,-0.2231756523366671,1739502704.1099555,64.34993863105774,-0.057158360105618825,1739502704.1099582,64.34993863105774,2.091225400114128,1739502704.109961,64.34993863105774,0.0,1739502704.109964,64.34993863105774,0.035791152160448814,1739502704.1099665,64.34993863105774,3.146695823447331,1739502704.1099691,64.34993863105774,2.0554342479536793 +1739502704.1294546,64.36993861198425,3.5095240909689966,1739502704.1294577,64.36993861198425,-0.13025277449007877,1739502704.1294618,64.36993861198425,109.1818177456125,1739502704.1294663,64.36993861198425,-1.962671083416914,1739502704.1294692,64.36993861198425,0.065,1739502704.1294725,64.36993861198425,3.105926897696744,1739502704.1294756,64.36993861198425,-0.2231756523366671,1739502704.1294787,64.36993861198425,-0.057158360105618825,1739502704.1294818,64.36993861198425,2.091225400114128,1739502704.1294851,64.36993861198425,0.0,1739502704.1294882,64.36993861198425,0.035791152160448814,1739502704.129491,64.36993861198425,3.146695823447331,1739502704.1294947,64.36993861198425,2.0554342479536793 +1739502704.1497414,64.38993859291077,3.5095240909689966,1739502704.149745,64.38993859291077,-0.13025277449007877,1739502704.149749,64.38993859291077,109.1818177456125,1739502704.1497536,64.38993859291077,-1.962671083416914,1739502704.1497564,64.38993859291077,0.065,1739502704.1497598,64.38993859291077,3.105926897696744,1739502704.149763,64.38993859291077,-0.2231756523366671,1739502704.1497662,64.38993859291077,-0.057158360105618825,1739502704.1497693,64.38993859291077,2.091225400114128,1739502704.1497726,64.38993859291077,0.0,1739502704.1497755,64.38993859291077,0.035791152160448814,1739502704.1497786,64.38993859291077,3.146695823447331,1739502704.149782,64.38993859291077,2.0554342479536793 +1739502704.1696243,64.40993857383728,3.5095240909689966,1739502704.1696277,64.40993857383728,-0.13025277449007877,1739502704.1696317,64.40993857383728,109.1818177456125,1739502704.169637,64.40993857383728,-1.962671083416914,1739502704.1696396,64.40993857383728,0.065,1739502704.1696432,64.40993857383728,3.105926897696744,1739502704.1696465,64.40993857383728,-0.2231756523366671,1739502704.1696496,64.40993857383728,-0.057158360105618825,1739502704.169653,64.40993857383728,2.091225400114128,1739502704.1696563,64.40993857383728,0.0,1739502704.1696596,64.40993857383728,0.035791152160448814,1739502704.169663,64.40993857383728,3.146695823447331,1739502704.1696663,64.40993857383728,2.0554342479536793 +1739502704.1898246,64.4299385547638,3.2832253205519537,1739502704.189828,64.4299385547638,-0.13124710522716043,1739502704.1898324,64.4299385547638,109.2053538120666,1739502704.189838,64.4299385547638,-1.994189912850366,1739502704.1898403,64.4299385547638,0.065,1739502704.1898441,64.4299385547638,3.104423563469736,1739502704.1898475,64.4299385547638,-0.21494492022389952,1739502704.1898506,64.4299385547638,-0.05918196713756528,1739502704.189854,64.4299385547638,2.1050406870134633,1739502704.1898572,64.4299385547638,0.0,1739502704.1898603,64.4299385547638,0.050080473378509294,1739502704.189864,64.4299385547638,3.14513588170116,1739502704.1898673,64.4299385547638,2.0594256294433526 +1739502704.2096581,64.44993853569031,3.2832253205519537,1739502704.2096615,64.44993853569031,-0.13124710522716043,1739502704.2096658,64.44993853569031,109.2053538120666,1739502704.2096705,64.44993853569031,-1.994189912850366,1739502704.2096734,64.44993853569031,0.065,1739502704.209677,64.44993853569031,3.104423563469736,1739502704.2096803,64.44993853569031,-0.21494492022389952,1739502704.2096837,64.44993853569031,-0.05918196713756528,1739502704.2096868,64.44993853569031,2.1050406870134633,1739502704.2096903,64.44993853569031,0.0,1739502704.2096934,64.44993853569031,0.04561505757011064,1739502704.2096968,64.44993853569031,3.14513588170116,1739502704.2097,64.44993853569031,2.0594256294433526 +1739502704.2295275,64.46993851661682,3.2832253205519537,1739502704.2295308,64.46993851661682,-0.13124710522716043,1739502704.2295353,64.46993851661682,109.2053538120666,1739502704.2295403,64.46993851661682,-1.994189912850366,1739502704.229543,64.46993851661682,0.065,1739502704.2295468,64.46993851661682,3.104423563469736,1739502704.22955,64.46993851661682,-0.21494492022389952,1739502704.2295532,64.46993851661682,-0.05918196713756528,1739502704.2295563,64.46993851661682,2.1050406870134633,1739502704.2295597,64.46993851661682,0.0,1739502704.229563,64.46993851661682,0.04561505757011064,1739502704.229566,64.46993851661682,3.14513588170116,1739502704.2295694,64.46993851661682,2.0594256294433526 +1739502704.2492568,64.48993849754333,3.2832253205519537,1739502704.24926,64.48993849754333,-0.13124710522716043,1739502704.2492642,64.48993849754333,109.2053538120666,1739502704.249269,64.48993849754333,-1.994189912850366,1739502704.2492716,64.48993849754333,0.065,1739502704.249275,64.48993849754333,3.104423563469736,1739502704.249278,64.48993849754333,-0.21494492022389952,1739502704.2492812,64.48993849754333,-0.05918196713756528,1739502704.2492843,64.48993849754333,2.1050406870134633,1739502704.2492874,64.48993849754333,0.0,1739502704.2492905,64.48993849754333,0.04561505757011064,1739502704.2492938,64.48993849754333,3.14513588170116,1739502704.2492971,64.48993849754333,2.0594256294433526 +1739502704.270973,64.50993847846985,3.2832253205519537,1739502704.2709765,64.50993847846985,-0.13124710522716043,1739502704.2709808,64.50993847846985,109.2053538120666,1739502704.270986,64.50993847846985,-1.994189912850366,1739502704.2709887,64.50993847846985,0.065,1739502704.2709923,64.50993847846985,3.104423563469736,1739502704.2709956,64.50993847846985,-0.21494492022389952,1739502704.2709987,64.50993847846985,-0.05918196713756528,1739502704.271002,64.50993847846985,2.1050406870134633,1739502704.2710054,64.50993847846985,0.0,1739502704.2710085,64.50993847846985,0.04561505757011064,1739502704.2710118,64.50993847846985,3.14513588170116,1739502704.2710152,64.50993847846985,2.0594256294433526 +1739502704.2898562,64.52993845939636,3.0564418179771966,1739502704.28986,64.52993845939636,-0.13188977703805893,1739502704.2898645,64.52993845939636,109.50939174658738,1739502704.2898695,64.52993845939636,-2.308192847008122,1739502704.2898724,64.52993845939636,0.065,1739502704.2898757,64.52993845939636,3.1049076866693643,1739502704.289879,64.52993845939636,-0.20752898962292887,1739502704.2898824,64.52993845939636,-0.05530009739978756,1739502704.2898858,64.52993845939636,2.1175664749411145,1739502704.289889,64.52993845939636,0.0,1739502704.2898924,64.52993845939636,0.0565871162715442,1739502704.2898958,64.52993845939636,3.1435759399549887,1739502704.289899,64.52993845939636,2.0644081292618455 +1739502704.3092961,64.54993844032288,3.0564418179771966,1739502704.3092997,64.54993844032288,-0.13188977703805893,1739502704.3093038,64.54993844032288,109.50939174658738,1739502704.3093085,64.54993844032288,-2.308192847008122,1739502704.309311,64.54993844032288,0.065,1739502704.3093143,64.54993844032288,3.1049076866693643,1739502704.3093176,64.54993844032288,-0.20752898962292887,1739502704.3093207,64.54993844032288,-0.05530009739978756,1739502704.3093238,64.54993844032288,2.1175664749411145,1739502704.3093271,64.54993844032288,0.0,1739502704.3093302,64.54993844032288,0.053158345679269026,1739502704.3093333,64.54993844032288,3.1435759399549887,1739502704.3093364,64.54993844032288,2.0644081292618455 +1739502704.3293436,64.56993842124939,3.0564418179771966,1739502704.3293464,64.56993842124939,-0.13188977703805893,1739502704.3293505,64.56993842124939,109.50939174658738,1739502704.329355,64.56993842124939,-2.308192847008122,1739502704.3293579,64.56993842124939,0.065,1739502704.3293612,64.56993842124939,3.1049076866693643,1739502704.3293645,64.56993842124939,-0.20752898962292887,1739502704.3293679,64.56993842124939,-0.05530009739978756,1739502704.329371,64.56993842124939,2.1175664749411145,1739502704.3293738,64.56993842124939,0.0,1739502704.329377,64.56993842124939,0.053158345679269026,1739502704.3293803,64.56993842124939,3.1435759399549887,1739502704.3293834,64.56993842124939,2.0644081292618455 +1739502704.3478193,64.5899384021759,3.0564418179771966,1739502704.3478222,64.5899384021759,-0.13188977703805893,1739502704.3478248,64.5899384021759,109.50939174658738,1739502704.3478274,64.5899384021759,-2.308192847008122,1739502704.3478286,64.5899384021759,0.065,1739502704.3478303,64.5899384021759,3.1049076866693643,1739502704.3478317,64.5899384021759,-0.20752898962292887,1739502704.3478332,64.5899384021759,-0.05530009739978756,1739502704.347834,64.5899384021759,2.1175664749411145,1739502704.3478363,64.5899384021759,0.0,1739502704.3478372,64.5899384021759,0.053158345679269026,1739502704.3478386,64.5899384021759,3.1435759399549887,1739502704.34784,64.5899384021759,2.0644081292618455 +1739502704.367746,64.60993838310242,3.0564418179771966,1739502704.367749,64.60993838310242,-0.13188977703805893,1739502704.3677526,64.60993838310242,109.50939174658738,1739502704.367755,64.60993838310242,-2.308192847008122,1739502704.3677564,64.60993838310242,0.065,1739502704.367758,64.60993838310242,3.1049076866693643,1739502704.3677597,64.60993838310242,-0.20752898962292887,1739502704.367761,64.60993838310242,-0.05530009739978756,1739502704.367762,64.60993838310242,2.1175664749411145,1739502704.3677638,64.60993838310242,0.0,1739502704.367765,64.60993838310242,0.053158345679269026,1739502704.3677666,64.60993838310242,3.1435759399549887,1739502704.3677678,64.60993838310242,2.0644081292618455 +1739502704.387737,64.62993836402893,3.0564418179771966,1739502704.3877394,64.62993836402893,-0.13188977703805893,1739502704.387742,64.62993836402893,109.50939174658738,1739502704.3877444,64.62993836402893,-2.308192847008122,1739502704.3877459,64.62993836402893,0.065,1739502704.3877475,64.62993836402893,3.1049076866693643,1739502704.3877494,64.62993836402893,-0.20752898962292887,1739502704.3877506,64.62993836402893,-0.05530009739978756,1739502704.3877518,64.62993836402893,2.1175664749411145,1739502704.3877535,64.62993836402893,0.0,1739502704.3877544,64.62993836402893,0.053158345679269026,1739502704.387756,64.62993836402893,3.1435759399549887,1739502704.3877573,64.62993836402893,2.0644081292618455 +1739502704.4078765,64.64993834495544,2.8290590703242344,1739502704.4078786,64.64993834495544,-0.1321794300237844,1739502704.4078813,64.64993834495544,109.62709741107713,1739502704.4078841,64.64993834495544,-2.437676057107843,1739502704.4078853,64.64993834495544,0.065,1739502704.4078867,64.64993834495544,3.104171485257836,1739502704.4078884,64.64993834495544,-0.19940905626389288,1739502704.40789,64.64993834495544,-0.055127202376807495,1739502704.4078915,64.64993834495544,2.131366848586526,1739502704.407893,64.64993834495544,0.0,1739502704.4078944,64.64993834495544,0.06466613214948479,1739502704.4078956,64.64993834495544,3.1420159982088176,1739502704.407897,64.64993834495544,2.0702969020668265 +1739502704.4278684,64.66993832588196,2.8290590703242344,1739502704.4278708,64.66993832588196,-0.1321794300237844,1739502704.427874,64.66993832588196,109.62709741107713,1739502704.4278767,64.66993832588196,-2.437676057107843,1739502704.4278781,64.66993832588196,0.065,1739502704.4278796,64.66993832588196,3.104171485257836,1739502704.427881,64.66993832588196,-0.19940905626389288,1739502704.4278824,64.66993832588196,-0.055127202376807495,1739502704.4278839,64.66993832588196,2.131366848586526,1739502704.4278853,64.66993832588196,0.0,1739502704.4278865,64.66993832588196,0.061069946519699325,1739502704.4278882,64.66993832588196,3.1420159982088176,1739502704.4278896,64.66993832588196,2.0702969020668265 +1739502704.4478133,64.68993830680847,2.8290590703242344,1739502704.4478157,64.68993830680847,-0.1321794300237844,1739502704.4478183,64.68993830680847,109.62709741107713,1739502704.447821,64.68993830680847,-2.437676057107843,1739502704.4478223,64.68993830680847,0.065,1739502704.4478242,64.68993830680847,3.104171485257836,1739502704.4478254,64.68993830680847,-0.19940905626389288,1739502704.4478269,64.68993830680847,-0.055127202376807495,1739502704.4478283,64.68993830680847,2.131366848586526,1739502704.4478297,64.68993830680847,0.0,1739502704.4478314,64.68993830680847,0.061069946519699325,1739502704.4478328,64.68993830680847,3.1420159982088176,1739502704.447834,64.68993830680847,2.0702969020668265 +1739502704.4680307,64.70993828773499,2.8290590703242344,1739502704.468033,64.70993828773499,-0.1321794300237844,1739502704.468036,64.70993828773499,109.62709741107713,1739502704.4680388,64.70993828773499,-2.437676057107843,1739502704.4680402,64.70993828773499,0.065,1739502704.468042,64.70993828773499,3.104171485257836,1739502704.4680433,64.70993828773499,-0.19940905626389288,1739502704.4680448,64.70993828773499,-0.055127202376807495,1739502704.4680462,64.70993828773499,2.131366848586526,1739502704.4680476,64.70993828773499,0.0,1739502704.468049,64.70993828773499,0.061069946519699325,1739502704.4680505,64.70993828773499,3.1420159982088176,1739502704.468052,64.70993828773499,2.0702969020668265 +1739502704.4882393,64.7299382686615,2.8290590703242344,1739502704.4882421,64.7299382686615,-0.1321794300237844,1739502704.488245,64.7299382686615,109.62709741107713,1739502704.488248,64.7299382686615,-2.437676057107843,1739502704.4882493,64.7299382686615,0.065,1739502704.4882512,64.7299382686615,3.104171485257836,1739502704.4882524,64.7299382686615,-0.19940905626389288,1739502704.488254,64.7299382686615,-0.055127202376807495,1739502704.4882553,64.7299382686615,2.131366848586526,1739502704.4882567,64.7299382686615,0.0,1739502704.4882584,64.7299382686615,0.061069946519699325,1739502704.4882596,64.7299382686615,3.1420159982088176,1739502704.4882612,64.7299382686615,2.0702969020668265 +1739502704.5080638,64.74993824958801,2.6009938006687117,1739502704.5080657,64.74993824958801,-0.13211417190690877,1739502704.5080686,64.74993824958801,110.28876297607985,1739502704.5080712,64.74993824958801,-3.112691027938346,1739502704.5080724,64.74993824958801,0.065,1739502704.5080743,64.74993824958801,3.1071077222582573,1739502704.5080755,64.74993824958801,-0.19061988822228146,1739502704.5080771,64.74993824958801,-0.044786593783934604,1739502704.508078,64.74993824958801,2.1464060124333826,1739502704.5080798,64.74993824958801,0.0,1739502704.508081,64.74993824958801,0.07323643877535904,1739502704.5080824,64.74993824958801,3.1404560564626465,1739502704.5080838,64.74993824958801,2.076971604980723 +1739502704.530672,64.76993823051453,2.6009938006687117,1739502704.5306756,64.76993823051453,-0.13211417190690877,1739502704.5306804,64.76993823051453,110.28876297607985,1739502704.5306852,64.76993823051453,-3.112691027938346,1739502704.530688,64.76993823051453,0.065,1739502704.5306916,64.76993823051453,3.1071077222582573,1739502704.530695,64.76993823051453,-0.19061988822228146,1739502704.5306983,64.76993823051453,-0.044786593783934604,1739502704.5307014,64.76993823051453,2.1464060124333826,1739502704.530705,64.76993823051453,0.0,1739502704.530708,64.76993823051453,0.06943440745265939,1739502704.5307117,64.76993823051453,3.1404560564626465,1739502704.5307145,64.76993823051453,2.076971604980723 +1739502704.549636,64.78993821144104,2.6009938006687117,1739502704.5496387,64.78993821144104,-0.13211417190690877,1739502704.549642,64.78993821144104,110.28876297607985,1739502704.5496447,64.78993821144104,-3.112691027938346,1739502704.5496461,64.78993821144104,0.065,1739502704.5496478,64.78993821144104,3.1071077222582573,1739502704.5496495,64.78993821144104,-0.19061988822228146,1739502704.5496507,64.78993821144104,-0.044786593783934604,1739502704.5496523,64.78993821144104,2.1464060124333826,1739502704.5496538,64.78993821144104,0.0,1739502704.5496552,64.78993821144104,0.06943440745265939,1739502704.5496566,64.78993821144104,3.1404560564626465,1739502704.549658,64.78993821144104,2.076971604980723 +1739502704.5714588,64.80993819236755,2.6009938006687117,1739502704.5714622,64.80993819236755,-0.13211417190690877,1739502704.5714667,64.80993819236755,110.28876297607985,1739502704.5714717,64.80993819236755,-3.112691027938346,1739502704.5714743,64.80993819236755,0.065,1739502704.5714781,64.80993819236755,3.1071077222582573,1739502704.571481,64.80993819236755,-0.19061988822228146,1739502704.5714843,64.80993819236755,-0.044786593783934604,1739502704.5714877,64.80993819236755,2.1464060124333826,1739502704.571491,64.80993819236755,0.0,1739502704.571494,64.80993819236755,0.06943440745265939,1739502704.5714974,64.80993819236755,3.1404560564626465,1739502704.5715008,64.80993819236755,2.076971604980723 +1739502704.5897963,64.82993817329407,2.6009938006687117,1739502704.5897996,64.82993817329407,-0.13211417190690877,1739502704.589804,64.82993817329407,110.28876297607985,1739502704.589809,64.82993817329407,-3.112691027938346,1739502704.5898118,64.82993817329407,0.065,1739502704.5898154,64.82993817329407,3.1071077222582573,1739502704.5898187,64.82993817329407,-0.19061988822228146,1739502704.5898216,64.82993817329407,-0.044786593783934604,1739502704.589825,64.82993817329407,2.1464060124333826,1739502704.5898285,64.82993817329407,0.0,1739502704.5898316,64.82993817329407,0.06943440745265939,1739502704.589835,64.82993817329407,3.1404560564626465,1739502704.5898385,64.82993817329407,2.076971604980723 +1739502704.6099997,64.84993815422058,2.6009938006687117,1739502704.6100032,64.84993815422058,-0.13211417190690877,1739502704.6100075,64.84993815422058,110.28876297607985,1739502704.6100128,64.84993815422058,-3.112691027938346,1739502704.6100154,64.84993815422058,0.065,1739502704.6100194,64.84993815422058,3.1071077222582573,1739502704.6100223,64.84993815422058,-0.19061988822228146,1739502704.6100256,64.84993815422058,-0.044786593783934604,1739502704.6100287,64.84993815422058,2.1464060124333826,1739502704.610032,64.84993815422058,0.0,1739502704.6100354,64.84993815422058,0.06943440745265939,1739502704.6100388,64.84993815422058,3.1404560564626465,1739502704.6100423,64.84993815422058,2.076971604980723 +1739502704.631351,64.8699381351471,2.372139299384786,1739502704.6313543,64.8699381351471,-0.13169167485870403,1739502704.6313586,64.8699381351471,110.8453512604161,1739502704.6313636,64.8699381351471,-3.6846358836149373,1739502704.6313665,64.8699381351471,0.065,1739502704.63137,64.8699381351471,3.109129408917118,1739502704.6313732,64.8699381351471,-0.1803586498199208,1739502704.6313767,64.8699381351471,-0.037716782600405924,1739502704.6313796,64.8699381351471,2.1640983582727653,1739502704.631383,64.8699381351471,0.0,1739502704.6313863,64.8699381351471,0.08400031749431276,1739502704.6313896,64.8699381351471,3.1388961147164753,1739502704.631393,64.8699381351471,2.0846498906508946 +1739502704.6494448,64.88993811607361,2.372139299384786,1739502704.6494472,64.88993811607361,-0.13169167485870403,1739502704.64945,64.88993811607361,110.8453512604161,1739502704.6494527,64.88993811607361,-3.6846358836149373,1739502704.649454,64.88993811607361,0.065,1739502704.6494555,64.88993811607361,3.109129408917118,1739502704.649457,64.88993811607361,-0.1803586498199208,1739502704.6494582,64.88993811607361,-0.037716782600405924,1739502704.6494594,64.88993811607361,2.1640983582727653,1739502704.649461,64.88993811607361,0.0,1739502704.6494622,64.88993811607361,0.07944846762187074,1739502704.649464,64.88993811607361,3.1388961147164753,1739502704.649465,64.88993811607361,2.0846498906508946 +1739502704.6685462,64.90993809700012,2.372139299384786,1739502704.6685498,64.90993809700012,-0.13169167485870403,1739502704.6685545,64.90993809700012,110.8453512604161,1739502704.6685596,64.90993809700012,-3.6846358836149373,1739502704.6685624,64.90993809700012,0.065,1739502704.668566,64.90993809700012,3.109129408917118,1739502704.6685693,64.90993809700012,-0.1803586498199208,1739502704.6685724,64.90993809700012,-0.037716782600405924,1739502704.6685755,64.90993809700012,2.1640983582727653,1739502704.6685789,64.90993809700012,0.0,1739502704.6685822,64.90993809700012,0.07944846762187074,1739502704.6685858,64.90993809700012,3.1388961147164753,1739502704.668589,64.90993809700012,2.0846498906508946 +1739502704.687881,64.92993807792664,2.372139299384786,1739502704.6878836,64.92993807792664,-0.13169167485870403,1739502704.6878862,64.92993807792664,110.8453512604161,1739502704.6878893,64.92993807792664,-3.6846358836149373,1739502704.6878908,64.92993807792664,0.065,1739502704.6878922,64.92993807792664,3.109129408917118,1739502704.6878934,64.92993807792664,-0.1803586498199208,1739502704.6878948,64.92993807792664,-0.037716782600405924,1739502704.687896,64.92993807792664,2.1640983582727653,1739502704.6878977,64.92993807792664,0.0,1739502704.6878989,64.92993807792664,0.07944846762187074,1739502704.6879003,64.92993807792664,3.1388961147164753,1739502704.6879017,64.92993807792664,2.0846498906508946 +1739502704.707839,64.94993805885315,2.372139299384786,1739502704.7078414,64.94993805885315,-0.13169167485870403,1739502704.7078443,64.94993805885315,110.8453512604161,1739502704.707847,64.94993805885315,-3.6846358836149373,1739502704.7078488,64.94993805885315,0.065,1739502704.707851,64.94993805885315,3.109129408917118,1739502704.7078526,64.94993805885315,-0.1803586498199208,1739502704.707854,64.94993805885315,-0.037716782600405924,1739502704.7078557,64.94993805885315,2.1640983582727653,1739502704.7078574,64.94993805885315,0.0,1739502704.7078588,64.94993805885315,0.07944846762187074,1739502704.7078602,64.94993805885315,3.1388961147164753,1739502704.7078617,64.94993805885315,2.0846498906508946 +1739502704.7280219,64.96993803977966,2.142396362894166,1739502704.7280242,64.96993803977966,-0.13090913450562702,1739502704.728027,64.96993803977966,110.86304224906624,1739502704.7280297,64.96993803977966,-3.7196938406021967,1739502704.728031,64.96993803977966,0.065,1739502704.7280328,64.96993803977966,3.1081854146633763,1739502704.728034,64.96993803977966,-0.1709555618078109,1739502704.7280357,64.96993803977966,-0.038162011048326755,1739502704.7280369,64.96993803977966,2.180439108484636,1739502704.7280383,64.96993803977966,0.0,1739502704.7280397,64.96993803977966,0.09058631245875191,1739502704.7280412,64.96993803977966,3.137336172970304,1739502704.7280426,64.96993803977966,2.093333374819455 +1739502704.747807,64.98993802070618,2.142396362894166,1739502704.7478092,64.98993802070618,-0.13090913450562702,1739502704.747812,64.98993802070618,110.86304224906624,1739502704.7478147,64.98993802070618,-3.7196938406021967,1739502704.747816,64.98993802070618,0.065,1739502704.7478178,64.98993802070618,3.1081854146633763,1739502704.747819,64.98993802070618,-0.1709555618078109,1739502704.7478204,64.98993802070618,-0.038162011048326755,1739502704.7478216,64.98993802070618,2.180439108484636,1739502704.747823,64.98993802070618,0.0,1739502704.7478244,64.98993802070618,0.08710573366518126,1739502704.7478259,64.98993802070618,3.137336172970304,1739502704.7478273,64.98993802070618,2.093333374819455 +1739502704.7726653,65.00993800163269,2.142396362894166,1739502704.7727082,65.00993800163269,-0.13090913450562702,1739502704.7727208,65.00993800163269,110.86304224906624,1739502704.7727373,65.00993800163269,-3.7196938406021967,1739502704.7727587,65.00993800163269,0.065,1739502704.7727773,65.00993800163269,3.1081854146633763,1739502704.7727888,65.00993800163269,-0.1709555618078109,1739502704.7728004,65.00993800163269,-0.038162011048326755,1739502704.7728124,65.00993800163269,2.180439108484636,1739502704.7728243,65.00993800163269,0.0,1739502704.7728355,65.00993800163269,0.08710573366518126,1739502704.7728474,65.00993800163269,3.137336172970304,1739502704.772859,65.00993800163269,2.093333374819455 +1739502704.7905772,65.0299379825592,2.142396362894166,1739502704.7905817,65.0299379825592,-0.13090913450562702,1739502704.7905874,65.0299379825592,110.86304224906624,1739502704.7905924,65.0299379825592,-3.7196938406021967,1739502704.7905953,65.0299379825592,0.065,1739502704.7905986,65.0299379825592,3.1081854146633763,1739502704.7906015,65.0299379825592,-0.1709555618078109,1739502704.790604,65.0299379825592,-0.038162011048326755,1739502704.7906065,65.0299379825592,2.180439108484636,1739502704.7906096,65.0299379825592,0.0,1739502704.7906122,65.0299379825592,0.08710573366518126,1739502704.790615,65.0299379825592,3.137336172970304,1739502704.790618,65.0299379825592,2.093333374819455 +1739502704.8138065,65.04993796348572,2.142396362894166,1739502704.8138137,65.04993796348572,-0.13090913450562702,1739502704.8138232,65.04993796348572,110.86304224906624,1739502704.8138337,65.04993796348572,-3.7196938406021967,1739502704.8138394,65.04993796348572,0.065,1739502704.813847,65.04993796348572,3.1081854146633763,1739502704.8138537,65.04993796348572,-0.1709555618078109,1739502704.8138607,65.04993796348572,-0.038162011048326755,1739502704.8138673,65.04993796348572,2.180439108484636,1739502704.8138742,65.04993796348572,0.0,1739502704.8138812,65.04993796348572,0.08710573366518126,1739502704.8138883,65.04993796348572,3.137336172970304,1739502704.813895,65.04993796348572,2.093333374819455 +1739502704.8300743,65.06993794441223,2.142396362894166,1739502704.8300793,65.06993794441223,-0.13090913450562702,1739502704.8300853,65.06993794441223,110.86304224906624,1739502704.8300908,65.06993794441223,-3.7196938406021967,1739502704.8300934,65.06993794441223,0.065,1739502704.830097,65.06993794441223,3.1081854146633763,1739502704.8300998,65.06993794441223,-0.1709555618078109,1739502704.8301022,65.06993794441223,-0.038162011048326755,1739502704.8301048,65.06993794441223,2.180439108484636,1739502704.830108,65.06993794441223,0.0,1739502704.8301108,65.06993794441223,0.08710573366518126,1739502704.8301136,65.06993794441223,3.137336172970304,1739502704.8301163,65.06993794441223,2.093333374819455 +1739502704.8527114,65.08993792533875,1.9116482100809211,1739502704.8527174,65.08993792533875,-0.12976319873784892,1739502704.8527248,65.08993792533875,111.06207247057928,1739502704.8527334,65.08993792533875,-3.937937496014207,1739502704.8527381,65.08993792533875,0.065,1739502704.852744,65.08993792533875,3.1083097363492187,1739502704.8527496,65.08993792533875,-0.16073643496273585,1739502704.8527548,65.08993792533875,-0.03603489557098839,1739502704.8527603,65.08993792533875,2.198337919946936,1739502704.8527663,65.08993792533875,0.0,1739502704.8527715,65.08993792533875,0.0991669656419935,1739502704.8527772,65.08993792533875,3.135776231224133,1739502704.852783,65.08993792533875,2.1029400917689354 +1739502704.8708127,65.10993790626526,1.9116482100809211,1739502704.870816,65.10993790626526,-0.12976319873784892,1739502704.8708205,65.10993790626526,111.06207247057928,1739502704.8708258,65.10993790626526,-3.937937496014207,1739502704.8708286,65.10993790626526,0.065,1739502704.8708324,65.10993790626526,3.1083097363492187,1739502704.8708355,65.10993790626526,-0.16073643496273585,1739502704.8708389,65.10993790626526,-0.03603489557098839,1739502704.8708422,65.10993790626526,2.198337919946936,1739502704.8708456,65.10993790626526,0.0,1739502704.8708487,65.10993790626526,0.09539782817800058,1739502704.8708525,65.10993790626526,3.135776231224133,1739502704.8708556,65.10993790626526,2.1029400917689354 +1739502704.890934,65.12993788719177,1.9116482100809211,1739502704.890956,65.12993788719177,-0.12976319873784892,1739502704.890961,65.12993788719177,111.06207247057928,1739502704.890966,65.12993788719177,-3.937937496014207,1739502704.8909688,65.12993788719177,0.065,1739502704.8909729,65.12993788719177,3.1083097363492187,1739502704.8909762,65.12993788719177,-0.16073643496273585,1739502704.8909795,65.12993788719177,-0.03603489557098839,1739502704.8909829,65.12993788719177,2.198337919946936,1739502704.8909862,65.12993788719177,0.0,1739502704.8909895,65.12993788719177,0.09539782817800058,1739502704.891012,65.12993788719177,3.135776231224133,1739502704.891015,65.12993788719177,2.1029400917689354 +1739502704.9100425,65.14993786811829,1.9116482100809211,1739502704.9100454,65.14993786811829,-0.12976319873784892,1739502704.910048,65.14993786811829,111.06207247057928,1739502704.9100506,65.14993786811829,-3.937937496014207,1739502704.910052,65.14993786811829,0.065,1739502704.9100537,65.14993786811829,3.1083097363492187,1739502704.910055,65.14993786811829,-0.16073643496273585,1739502704.910056,65.14993786811829,-0.03603489557098839,1739502704.9100573,65.14993786811829,2.198337919946936,1739502704.910059,65.14993786811829,0.0,1739502704.91006,65.14993786811829,0.09539782817800058,1739502704.9100614,65.14993786811829,3.135776231224133,1739502704.9100628,65.14993786811829,2.1029400917689354 +1739502704.9287817,65.1699378490448,1.9116482100809211,1739502704.9287841,65.1699378490448,-0.12976319873784892,1739502704.928787,65.1699378490448,111.06207247057928,1739502704.9287899,65.1699378490448,-3.937937496014207,1739502704.928791,65.1699378490448,0.065,1739502704.9287925,65.1699378490448,3.1083097363492187,1739502704.9287941,65.1699378490448,-0.16073643496273585,1739502704.9287953,65.1699378490448,-0.03603489557098839,1739502704.9287965,65.1699378490448,2.198337919946936,1739502704.9287982,65.1699378490448,0.0,1739502704.9287996,65.1699378490448,0.09539782817800058,1739502704.928801,65.1699378490448,3.135776231224133,1739502704.9288025,65.1699378490448,2.1029400917689354 +1739502704.9482656,65.18993782997131,1.679809271786361,1739502704.9482687,65.18993782997131,-0.12825016665506528,1739502704.9482722,65.18993782997131,111.08340316593448,1739502704.9482746,65.18993782997131,-3.9801270676132456,1739502704.9482765,65.18993782997131,0.065,1739502704.9482787,65.18993782997131,3.107462389251528,1739502704.94828,65.18993782997131,-0.15149553655152623,1739502704.9482815,65.18993782997131,-0.036275282296105625,1739502704.948283,65.18993782997131,2.2146498342673566,1739502704.9482846,65.18993782997131,0.0,1739502704.948286,65.18993782997131,0.10395415974399604,1739502704.9482872,65.18993782997131,3.134216289477962,1739502704.9482884,65.18993782997131,2.1133695298908504 +1739502704.9700632,65.20993781089783,1.679809271786361,1739502704.9700675,65.20993781089783,-0.12825016665506528,1739502704.970073,65.20993781089783,111.08340316593448,1739502704.9700785,65.20993781089783,-3.9801270676132456,1739502704.9700818,65.20993781089783,0.065,1739502704.9700856,65.20993781089783,3.107462389251528,1739502704.9700887,65.20993781089783,-0.15149553655152623,1739502704.9700916,65.20993781089783,-0.036275282296105625,1739502704.9700947,65.20993781089783,2.2146498342673566,1739502704.970098,65.20993781089783,0.0,1739502704.9701014,65.20993781089783,0.10128030437650626,1739502704.9701042,65.20993781089783,3.134216289477962,1739502704.9701073,65.20993781089783,2.1133695298908504 +1739502705.0021002,65.2399377822876,1.679809271786361,1739502705.0021048,65.2399377822876,-0.12825016665506528,1739502705.0021102,65.2399377822876,111.08340316593448,1739502705.0021152,65.2399377822876,-3.9801270676132456,1739502705.002118,65.2399377822876,0.065,1739502705.002122,65.2399377822876,3.107462389251528,1739502705.002125,65.2399377822876,-0.15149553655152623,1739502705.002128,65.2399377822876,-0.036275282296105625,1739502705.002131,65.2399377822876,2.2146498342673566,1739502705.0021343,65.2399377822876,0.0,1739502705.0021374,65.2399377822876,0.10128030437650626,1739502705.0021408,65.2399377822876,3.134216289477962,1739502705.002144,65.2399377822876,2.1133695298908504 +1739502705.0282164,65.26993775367737,1.679809271786361,1739502705.0282185,65.26993775367737,-0.12825016665506528,1739502705.0282214,65.26993775367737,111.08340316593448,1739502705.028224,65.26993775367737,-3.9801270676132456,1739502705.0282254,65.26993775367737,0.065,1739502705.028227,65.26993775367737,3.107462389251528,1739502705.0282283,65.26993775367737,-0.15149553655152623,1739502705.0282297,65.26993775367737,-0.036275282296105625,1739502705.0282307,65.26993775367737,2.2146498342673566,1739502705.0282323,65.26993775367737,0.0,1739502705.0282338,65.26993775367737,0.10128030437650626,1739502705.0282352,65.26993775367737,3.134216289477962,1739502705.0282366,65.26993775367737,2.1133695298908504 +1739502705.050959,65.28993773460388,1.679809271786361,1739502705.050962,65.28993773460388,-0.12825016665506528,1739502705.0509653,65.28993773460388,111.08340316593448,1739502705.0509682,65.28993773460388,-3.9801270676132456,1739502705.0509696,65.28993773460388,0.065,1739502705.0509715,65.28993773460388,3.107462389251528,1739502705.0509727,65.28993773460388,-0.15149553655152623,1739502705.050974,65.28993773460388,-0.036275282296105625,1739502705.0509756,65.28993773460388,2.2146498342673566,1739502705.050977,65.28993773460388,0.0,1739502705.050978,65.28993773460388,0.10128030437650626,1739502705.0509796,65.28993773460388,3.134216289477962,1739502705.0509808,65.28993773460388,2.1133695298908504 +1739502705.0695975,65.3099377155304,1.4467857031320621,1739502705.0696006,65.3099377155304,-0.12636587231858876,1739502705.0696042,65.3099377155304,111.104843218545,1739502705.069607,65.3099377155304,-4.023852218526322,1739502705.0696084,65.3099377155304,0.065,1739502705.0696106,65.3099377155304,3.1066263702942973,1739502705.0696118,65.3099377155304,-0.14247158832449025,1739502705.069613,65.3099377155304,-0.03651413372872196,1739502705.0696146,65.3099377155304,2.2306955913692534,1739502705.069616,65.3099377155304,0.0,1739502705.0696175,65.3099377155304,0.1084122453392422,1739502705.069619,65.3099377155304,3.132656347731791,1739502705.0696208,65.3099377155304,2.1245120790421375 +1739502705.0881698,65.32993769645691,1.4467857031320621,1739502705.0881724,65.32993769645691,-0.12636587231858876,1739502705.0881755,65.32993769645691,111.104843218545,1739502705.0881786,65.32993769645691,-4.023852218526322,1739502705.08818,65.32993769645691,0.065,1739502705.0881815,65.32993769645691,3.1066263702942973,1739502705.088183,65.32993769645691,-0.14247158832449025,1739502705.0881844,65.32993769645691,-0.03651413372872196,1739502705.0881855,65.32993769645691,2.2306955913692534,1739502705.0881872,65.32993769645691,0.0,1739502705.0881886,65.32993769645691,0.10618351232711598,1739502705.0881898,65.32993769645691,3.132656347731791,1739502705.0881913,65.32993769645691,2.1245120790421375 +1739502705.1084993,65.34993767738342,1.4467857031320621,1739502705.1085012,65.34993767738342,-0.12636587231858876,1739502705.1085043,65.34993767738342,111.104843218545,1739502705.1085072,65.34993767738342,-4.023852218526322,1739502705.1085086,65.34993767738342,0.065,1739502705.1085103,65.34993767738342,3.1066263702942973,1739502705.1085114,65.34993767738342,-0.14247158832449025,1739502705.1085129,65.34993767738342,-0.03651413372872196,1739502705.1085143,65.34993767738342,2.2306955913692534,1739502705.1085157,65.34993767738342,0.0,1739502705.1085172,65.34993767738342,0.10618351232711598,1739502705.1085184,65.34993767738342,3.132656347731791,1739502705.10852,65.34993767738342,2.1245120790421375 +1739502705.1280694,65.36993765830994,1.4467857031320621,1739502705.1280723,65.36993765830994,-0.12636587231858876,1739502705.1280751,65.36993765830994,111.104843218545,1739502705.1280777,65.36993765830994,-4.023852218526322,1739502705.1280792,65.36993765830994,0.065,1739502705.1280806,65.36993765830994,3.1066263702942973,1739502705.1280823,65.36993765830994,-0.14247158832449025,1739502705.1280837,65.36993765830994,-0.03651413372872196,1739502705.128085,65.36993765830994,2.2306955913692534,1739502705.1280866,65.36993765830994,0.0,1739502705.1280878,65.36993765830994,0.10618351232711598,1739502705.1280894,65.36993765830994,3.132656347731791,1739502705.1280909,65.36993765830994,2.1245120790421375 +1739502705.1480742,65.38993763923645,1.4467857031320621,1739502705.1480765,65.38993763923645,-0.12636587231858876,1739502705.1480794,65.38993763923645,111.104843218545,1739502705.1480823,65.38993763923645,-4.023852218526322,1739502705.1480834,65.38993763923645,0.065,1739502705.1480854,65.38993763923645,3.1066263702942973,1739502705.1480868,65.38993763923645,-0.14247158832449025,1739502705.148088,65.38993763923645,-0.03651413372872196,1739502705.1480896,65.38993763923645,2.2306955913692534,1739502705.148091,65.38993763923645,0.0,1739502705.1480925,65.38993763923645,0.10618351232711598,1739502705.148094,65.38993763923645,3.132656347731791,1739502705.1480951,65.38993763923645,2.1245120790421375 +1739502705.168931,65.40993762016296,1.2125200385432535,1739502705.168934,65.40993762016296,-0.12410605795789564,1739502705.1689372,65.40993762016296,111.73204429385052,1739502705.16894,65.40993762016296,-4.67427674256826,1739502705.1689413,65.40993762016296,0.065,1739502705.1689432,65.40993762016296,3.109479934775411,1739502705.1689446,65.40993762016296,-0.12730749898191793,1739502705.168946,65.40993762016296,-0.028183596272671616,1739502705.1689472,65.40993762016296,2.2579215741602696,1739502705.1689487,65.40993762016296,0.0,1739502705.16895,65.40993762016296,0.12889516771071696,1739502705.1689515,65.40993762016296,3.1310964059856197,1739502705.1689532,65.40993762016296,2.136123803410344 +1739502705.1884995,65.42993760108948,1.2125200385432535,1739502705.1885037,65.42993760108948,-0.12410605795789564,1739502705.1885087,65.42993760108948,111.73204429385052,1739502705.1885126,65.42993760108948,-4.67427674256826,1739502705.1885145,65.42993760108948,0.065,1739502705.1885176,65.42993760108948,3.109479934775411,1739502705.1885195,65.42993760108948,-0.12730749898191793,1739502705.1885216,65.42993760108948,-0.028183596272671616,1739502705.188524,65.42993760108948,2.2579215741602696,1739502705.1885264,65.42993760108948,0.0,1739502705.188528,65.42993760108948,0.1217977707499256,1739502705.1885302,65.42993760108948,3.1310964059856197,1739502705.188532,65.42993760108948,2.136123803410344 +1739502705.2116296,65.44993758201599,1.2125200385432535,1739502705.2116368,65.44993758201599,-0.12410605795789564,1739502705.2116466,65.44993758201599,111.73204429385052,1739502705.2116542,65.44993758201599,-4.67427674256826,1739502705.2116578,65.44993758201599,0.065,1739502705.2116628,65.44993758201599,3.109479934775411,1739502705.2116666,65.44993758201599,-0.12730749898191793,1739502705.2116702,65.44993758201599,-0.028183596272671616,1739502705.211674,65.44993758201599,2.2579215741602696,1739502705.2116783,65.44993758201599,0.0,1739502705.2116823,65.44993758201599,0.1217977707499256,1739502705.2116864,65.44993758201599,3.1310964059856197,1739502705.21169,65.44993758201599,2.136123803410344 +1739502705.2328527,65.4699375629425,1.2125200385432535,1739502705.23286,65.4699375629425,-0.12410605795789564,1739502705.2328691,65.4699375629425,111.73204429385052,1739502705.2328768,65.4699375629425,-4.67427674256826,1739502705.2328804,65.4699375629425,0.065,1739502705.232885,65.4699375629425,3.109479934775411,1739502705.2328892,65.4699375629425,-0.12730749898191793,1739502705.232893,65.4699375629425,-0.028183596272671616,1739502705.2328966,65.4699375629425,2.2579215741602696,1739502705.2329006,65.4699375629425,0.0,1739502705.2329044,65.4699375629425,0.1217977707499256,1739502705.2329082,65.4699375629425,3.1310964059856197,1739502705.2329123,65.4699375629425,2.136123803410344 +1739502705.2556245,65.48993754386902,1.2125200385432535,1739502705.2556329,65.48993754386902,-0.12410605795789564,1739502705.2556431,65.48993754386902,111.73204429385052,1739502705.2556515,65.48993754386902,-4.67427674256826,1739502705.2556562,65.48993754386902,0.065,1739502705.2556624,65.48993754386902,3.109479934775411,1739502705.2556665,65.48993754386902,-0.12730749898191793,1739502705.2556703,65.48993754386902,-0.028183596272671616,1739502705.2556744,65.48993754386902,2.2579215741602696,1739502705.2556798,65.48993754386902,0.0,1739502705.255684,65.48993754386902,0.1217977707499256,1739502705.2556882,65.48993754386902,3.1310964059856197,1739502705.2556922,65.48993754386902,2.136123803410344 +1739502705.2734284,65.50993752479553,1.2125200385432535,1739502705.2734349,65.50993752479553,-0.12410605795789564,1739502705.2734427,65.50993752479553,111.73204429385052,1739502705.2734506,65.50993752479553,-4.67427674256826,1739502705.2734542,65.50993752479553,0.065,1739502705.2734587,65.50993752479553,3.109479934775411,1739502705.2734625,65.50993752479553,-0.12730749898191793,1739502705.273466,65.50993752479553,-0.028183596272671616,1739502705.2734697,65.50993752479553,2.2579215741602696,1739502705.2734742,65.50993752479553,0.0,1739502705.2734787,65.50993752479553,0.1217977707499256,1739502705.2734833,65.50993752479553,3.1310964059856197,1739502705.2734873,65.50993752479553,2.136123803410344 +1739502705.2918854,65.51993751525879,0.9768797817716139,1739502705.2918906,65.51993751525879,-0.12146533422960815,1739502705.2918966,65.51993751525879,111.73958478206721,1739502705.2919023,65.51993751525879,-4.708770145932242,1739502705.291905,65.51993751525879,0.065,1739502705.2919085,65.51993751525879,3.108808622221034,1739502705.2919116,65.51993751525879,-0.11790617132380896,1739502705.2919145,65.51993751525879,-0.027980667530258595,1739502705.2919173,65.51993751525879,2.2749675642189704,1739502705.2919204,65.51993751525879,0.0,1739502705.2919235,65.51993751525879,0.1269898195482718,1739502705.2919264,65.51993751525879,3.1295364642394485,1739502705.291929,65.51993751525879,2.1496002609839864 +1739502705.311102,65.54993748664856,0.9768797817716139,1739502705.311106,65.54993748664856,-0.12146533422960815,1739502705.3111112,65.54993748664856,111.73958478206721,1739502705.3111157,65.54993748664856,-4.708770145932242,1739502705.311118,65.54993748664856,0.065,1739502705.3111207,65.54993748664856,3.108808622221034,1739502705.3111231,65.54993748664856,-0.11790617132380896,1739502705.3111253,65.54993748664856,-0.027980667530258595,1739502705.3111277,65.54993748664856,2.2749675642189704,1739502705.31113,65.54993748664856,0.0,1739502705.3111324,65.54993748664856,0.12536730323498402,1739502705.3111348,65.54993748664856,3.1295364642394485,1739502705.3111372,65.54993748664856,2.1496002609839864 +1739502705.3321009,65.56993746757507,0.9768797817716139,1739502705.3321047,65.56993746757507,-0.12146533422960815,1739502705.33211,65.56993746757507,111.73958478206721,1739502705.3321168,65.56993746757507,-4.708770145932242,1739502705.3321197,65.56993746757507,0.065,1739502705.3321242,65.56993746757507,3.108808622221034,1739502705.3321285,65.56993746757507,-0.11790617132380896,1739502705.332132,65.56993746757507,-0.027980667530258595,1739502705.3321354,65.56993746757507,2.2749675642189704,1739502705.3321393,65.56993746757507,0.0,1739502705.3321438,65.56993746757507,0.12536730323498402,1739502705.3321474,65.56993746757507,3.1295364642394485,1739502705.332151,65.56993746757507,2.1496002609839864 +1739502705.3513243,65.58993744850159,0.9768797817716139,1739502705.3513286,65.58993744850159,-0.12146533422960815,1739502705.3513331,65.58993744850159,111.73958478206721,1739502705.3513384,65.58993744850159,-4.708770145932242,1739502705.3513412,65.58993744850159,0.065,1739502705.3513448,65.58993744850159,3.108808622221034,1739502705.3513482,65.58993744850159,-0.11790617132380896,1739502705.3513513,65.58993744850159,-0.027980667530258595,1739502705.3513544,65.58993744850159,2.2749675642189704,1739502705.3513577,65.58993744850159,0.0,1739502705.3513606,65.58993744850159,0.12536730323498402,1739502705.351364,65.58993744850159,3.1295364642394485,1739502705.3513672,65.58993744850159,2.1496002609839864 +1739502705.3693023,65.6099374294281,0.9768797817716139,1739502705.3693051,65.6099374294281,-0.12146533422960815,1739502705.3693078,65.6099374294281,111.73958478206721,1739502705.3693106,65.6099374294281,-4.708770145932242,1739502705.3693123,65.6099374294281,0.065,1739502705.3693137,65.6099374294281,3.108808622221034,1739502705.3693151,65.6099374294281,-0.11790617132380896,1739502705.3693163,65.6099374294281,-0.027980667530258595,1739502705.3693175,65.6099374294281,2.2749675642189704,1739502705.3693197,65.6099374294281,0.0,1739502705.3693209,65.6099374294281,0.12536730323498402,1739502705.3693223,65.6099374294281,3.1295364642394485,1739502705.3693237,65.6099374294281,2.1496002609839864 +1739502705.391635,65.62993741035461,0.7397511377517079,1739502705.391639,65.62993741035461,-0.11843796712413734,1739502705.3916428,65.62993741035461,111.74717289867584,1739502705.3916461,65.62993741035461,-4.743907604581089,1739502705.3916483,65.62993741035461,0.065,1739502705.3916528,65.62993741035461,3.1081533755282353,1739502705.391655,65.62993741035461,-0.10875705360504968,1739502705.3916569,65.62993741035461,-0.027744679934665346,1739502705.391659,65.62993741035461,2.2916798073629856,1739502705.3916614,65.62993741035461,0.0,1739502705.3916636,65.62993741035461,0.12964013668861438,1739502705.3916657,65.62993741035461,3.1279765224932774,1739502705.3916676,65.62993741035461,2.1633749320040963 +1739502705.4093106,65.64993739128113,0.7397511377517079,1739502705.4093127,65.64993739128113,-0.11843796712413734,1739502705.4093158,65.64993739128113,111.74717289867584,1739502705.4093187,65.64993739128113,-4.743907604581089,1739502705.40932,65.64993739128113,0.065,1739502705.4093218,65.64993739128113,3.1081533755282353,1739502705.4093232,65.64993739128113,-0.10875705360504968,1739502705.4093246,65.64993739128113,-0.027744679934665346,1739502705.4093258,65.64993739128113,2.2916798073629856,1739502705.4093275,65.64993739128113,0.0,1739502705.4093292,65.64993739128113,0.12830487535888935,1739502705.4093304,65.64993739128113,3.1279765224932774,1739502705.409332,65.64993739128113,2.1633749320040963 +1739502705.4308808,65.66993737220764,0.7397511377517079,1739502705.4308846,65.66993737220764,-0.11843796712413734,1739502705.4308894,65.66993737220764,111.74717289867584,1739502705.4308949,65.66993737220764,-4.743907604581089,1739502705.4308982,65.66993737220764,0.065,1739502705.4309022,65.66993737220764,3.1081533755282353,1739502705.4309058,65.66993737220764,-0.10875705360504968,1739502705.4309092,65.66993737220764,-0.027744679934665346,1739502705.4309127,65.66993737220764,2.2916798073629856,1739502705.4309163,65.66993737220764,0.0,1739502705.4309196,65.66993737220764,0.12830487535888935,1739502705.4309232,65.66993737220764,3.1279765224932774,1739502705.4309268,65.66993737220764,2.1633749320040963 +1739502705.4489846,65.68993735313416,0.7397511377517079,1739502705.4489872,65.68993735313416,-0.11843796712413734,1739502705.4489896,65.68993735313416,111.74717289867584,1739502705.4489925,65.68993735313416,-4.743907604581089,1739502705.4489942,65.68993735313416,0.065,1739502705.4489958,65.68993735313416,3.1081533755282353,1739502705.448997,65.68993735313416,-0.10875705360504968,1739502705.4489985,65.68993735313416,-0.027744679934665346,1739502705.4489996,65.68993735313416,2.2916798073629856,1739502705.4490013,65.68993735313416,0.0,1739502705.4490025,65.68993735313416,0.12830487535888935,1739502705.4490037,65.68993735313416,3.1279765224932774,1739502705.4490056,65.68993735313416,2.1633749320040963 +1739502705.4690132,65.70993733406067,0.7397511377517079,1739502705.4690158,65.70993733406067,-0.11843796712413734,1739502705.4690187,65.70993733406067,111.74717289867584,1739502705.4690216,65.70993733406067,-4.743907604581089,1739502705.469023,65.70993733406067,0.065,1739502705.4690247,65.70993733406067,3.1081533755282353,1739502705.4690263,65.70993733406067,-0.10875705360504968,1739502705.4690275,65.70993733406067,-0.027744679934665346,1739502705.469029,65.70993733406067,2.2916798073629856,1739502705.4690304,65.70993733406067,0.0,1739502705.4690316,65.70993733406067,0.12830487535888935,1739502705.469033,65.70993733406067,3.1279765224932774,1739502705.4690344,65.70993733406067,2.1633749320040963 diff --git a/tuning logs/2025-02-13_21-10-39 (fine tuning)/behavior.json b/tuning logs/2025-02-13_21-10-39 (fine tuning)/behavior.json new file mode 100644 index 000000000..88d24e1fd --- /dev/null +++ b/tuning logs/2025-02-13_21-10-39 (fine tuning)/behavior.json @@ -0,0 +1,6605 @@ +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502638.589087, "x": 4.0, "y": 5.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.0, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": 0.0, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": -1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502638.629087} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": -2, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 0, "brake_pedal_position": 0, "brake_pedal_speed": 0, "steering_wheel_angle": 0.0, "steering_wheel_speed": 0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": -1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502638.629087} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.0, "x": 0.0, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.0, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": 0.0, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": -1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502638.659087} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.36000000000000004, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.683742855172885, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.0, "gear": -1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502638.659087} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.0, "x": 0.0, "y": 0.0, "z": null, "yaw": 0.0, "pitch": null, "roll": null}, "v": 0.0, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": 0.0, "steering_wheel_angle": 0.0, "front_wheel_angle": 0.0, "heading_rate": 0.0, "gear": -1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502638.679087} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.36000000000000004, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.683742855172885, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.015995993600000008, "gear": 1, "accelerator_pedal_position": 0.36000000000000004, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.08614717687913853, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502638.679087} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502638.699087, "x": 4.000479839636091, "y": 4.999999993195597, "z": null, "yaw": -4.6415014108958415e-05, "pitch": null, "roll": null}, "v": 0.03197591848874033, "accelerator_pedal_position": 0.36000000000000004, "brake_pedal_position": 0.0, "acceleration": 0.7983909794819313, "steering_wheel_angle": -0.17209949070995442, "front_wheel_angle": -0.007921433607650973, "heading_rate": -9.894547402327468e-05, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502638.699087} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392257443282891, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.551868899589124, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.03197591848874033, "gear": 1, "accelerator_pedal_position": 0.36000000000000004, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.17209949070995442, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502638.699087} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.1099998950958252, "x": 0.00047983963609077307, "y": -6.804403263060976e-09, "z": null, "yaw": 6.283138892165478, "pitch": null, "roll": null}, "v": 0.03197591848874033, "accelerator_pedal_position": 0.36000000000000004, "brake_pedal_position": 0.0, "acceleration": 0.7983909794819313, "steering_wheel_angle": -0.17209949070995442, "front_wheel_angle": -0.007921433607650973, "heading_rate": -9.894547402327468e-05, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502638.719087} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392257443282891, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.551868899589124, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.05197084453690334, "gear": 1, "accelerator_pedal_position": 0.392257443282891, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2575150543639356, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502638.719087} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.1099998950958252, "x": 0.00047983963609077307, "y": -6.804403263060976e-09, "z": null, "yaw": 6.283138892165478, "pitch": null, "roll": null}, "v": 0.03197591848874033, "accelerator_pedal_position": 0.36000000000000004, "brake_pedal_position": 0.0, "acceleration": 0.7983909794819313, "steering_wheel_angle": -0.17209949070995442, "front_wheel_angle": -0.007921433607650973, "heading_rate": -9.894547402327468e-05, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502638.7390869} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392257443282891, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.551868899589124, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.11183287562172607, "gear": 1, "accelerator_pedal_position": 0.392257443282891, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5126018812412664, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502638.7390869} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.1099998950958252, "x": 0.00047983963609077307, "y": -6.804403263060976e-09, "z": null, "yaw": 6.283138892165478, "pitch": null, "roll": null}, "v": 0.03197591848874033, "accelerator_pedal_position": 0.36000000000000004, "brake_pedal_position": 0.0, "acceleration": 0.7983909794819313, "steering_wheel_angle": -0.17209949070995442, "front_wheel_angle": -0.007921433607650973, "heading_rate": -9.894547402327468e-05, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502638.7790868} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392257443282891, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.551868899589124, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.11183287562172607, "gear": 1, "accelerator_pedal_position": 0.392257443282891, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5126018812412664, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502638.7790868} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.1099998950958252, "x": 0.00047983963609077307, "y": -6.804403263060976e-09, "z": null, "yaw": 6.283138892165478, "pitch": null, "roll": null}, "v": 0.03197591848874033, "accelerator_pedal_position": 0.36000000000000004, "brake_pedal_position": 0.0, "acceleration": 0.7983909794819313, "steering_wheel_angle": -0.17209949070995442, "front_wheel_angle": -0.007921433607650973, "heading_rate": -9.894547402327468e-05, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502638.7990868} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.392257443282891, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.551868899589124, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.13174550971148086, "gear": 1, "accelerator_pedal_position": 0.392257443282891, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5972442021721722, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502638.7990868} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502638.8090868, "x": 4.009488760476915, "y": 4.999996419713743, "z": null, "yaw": -0.0008106689266637859, "pitch": null, "roll": null}, "v": 0.1416939914738729, "accelerator_pedal_position": 0.392257443282891, "brake_pedal_position": 0.0, "acceleration": 0.9943235490721771, "steering_wheel_angle": -0.6394928711323367, "front_wheel_angle": -0.0296184321337821, "heading_rate": -0.0016398365249685966, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502638.8290868} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3931656754313427, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.1435982984250344, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.24122759505359873, "gear": 1, "accelerator_pedal_position": 0.3931656754313427, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.056288940593094, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502638.8290868} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.2199997901916504, "x": 0.009488760476915381, "y": -3.58028625679907e-06, "z": null, "yaw": 6.282374638252922, "pitch": null, "roll": null}, "v": 0.1416939914738729, "accelerator_pedal_position": 0.392257443282891, "brake_pedal_position": 0.0, "acceleration": 0.9943235490721771, "steering_wheel_angle": -0.6394928711323367, "front_wheel_angle": -0.0296184321337821, "heading_rate": -0.0016398365249685966, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502638.9090867} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3931656754313427, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.1435982984250344, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.26111497576260423, "gear": 1, "accelerator_pedal_position": 0.3931656754313427, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1386731819129978, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502638.9090867} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502638.9190867, "x": 4.03054701984167, "y": 4.999963086200438, "z": null, "yaw": -0.0025060902395537053, "pitch": null, "roll": null}, "v": 0.2511740168952693, "accelerator_pedal_position": 0.3931656754313427, "brake_pedal_position": 0.0, "acceleration": 0.994095886733495, "steering_wheel_angle": -1.0975046434689273, "front_wheel_angle": -0.05114825033772567, "heading_rate": -0.0050227837994094695, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502638.9390867} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3941103335539835, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.7581640131937317, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.2710504548861251, "gear": 1, "accelerator_pedal_position": 0.3931656754313427, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1797945559253051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502638.9390867} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.3299996852874756, "x": 0.030547019841669965, "y": -3.691379956194396e-05, "z": null, "yaw": 6.280679216940032, "pitch": null, "roll": null}, "v": 0.2511740168952693, "accelerator_pedal_position": 0.3931656754313427, "brake_pedal_position": 0.0, "acceleration": 0.994095886733495, "steering_wheel_angle": -1.0975046434689273, "front_wheel_angle": -0.05114825033772567, "heading_rate": -0.0050227837994094695, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502638.9590867} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3941103335539835, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.7581640131937317, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.291022956459828, "gear": 1, "accelerator_pedal_position": 0.3941103335539835, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1797945559253051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502638.9590867} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.3299996852874756, "x": 0.030547019841669965, "y": -3.691379956194396e-05, "z": null, "yaw": 6.280679216940032, "pitch": null, "roll": null}, "v": 0.2511740168952693, "accelerator_pedal_position": 0.3931656754313427, "brake_pedal_position": 0.0, "acceleration": 0.994095886733495, "steering_wheel_angle": -1.0975046434689273, "front_wheel_angle": -0.05114825033772567, "heading_rate": -0.0050227837994094695, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502638.9790866} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3941103335539835, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.7581640131937317, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.31097320665157313, "gear": 1, "accelerator_pedal_position": 0.3941103335539835, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1797945559253051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502638.9790866} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.3299996852874756, "x": 0.030547019841669965, "y": -3.691379956194396e-05, "z": null, "yaw": 6.280679216940032, "pitch": null, "roll": null}, "v": 0.2511740168952693, "accelerator_pedal_position": 0.3931656754313427, "brake_pedal_position": 0.0, "acceleration": 0.994095886733495, "steering_wheel_angle": -1.0975046434689273, "front_wheel_angle": -0.05114825033772567, "heading_rate": -0.0050227837994094695, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502638.9990866} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3941103335539835, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.7581640131937317, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.3309010710913795, "gear": 1, "accelerator_pedal_position": 0.3941103335539835, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1797945559253051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502638.9990866} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.3299996852874756, "x": 0.030547019841669965, "y": -3.691379956194396e-05, "z": null, "yaw": 6.280679216940032, "pitch": null, "roll": null}, "v": 0.2511740168952693, "accelerator_pedal_position": 0.3931656754313427, "brake_pedal_position": 0.0, "acceleration": 0.994095886733495, "steering_wheel_angle": -1.0975046434689273, "front_wheel_angle": -0.05114825033772567, "heading_rate": -0.0050227837994094695, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.0190866} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3941103335539835, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.7581640131937317, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.35080641609485474, "gear": 1, "accelerator_pedal_position": 0.3941103335539835, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1797945559253051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.0190866} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502639.0290866, "x": 4.063655593446573, "y": 4.9998428022115675, "z": null, "yaw": -0.0048508136236434084, "pitch": null, "roll": null}, "v": 0.36075060221977395, "accelerator_pedal_position": 0.3941103335539835, "brake_pedal_position": 0.0, "acceleration": 0.9938506446313888, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.007764741931406749, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.0390866} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3950942304129613, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4193851803411235, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.37068910866608784, "gear": 1, "accelerator_pedal_position": 0.3941103335539835, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1797945559253051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.0390866} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.4399995803833008, "x": 0.06365559344657257, "y": -0.00015719778843248378, "z": null, "yaw": 6.278334493555943, "pitch": null, "roll": null}, "v": 0.36075060221977395, "accelerator_pedal_position": 0.3941103335539835, "brake_pedal_position": 0.0, "acceleration": 0.9938506446313888, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.007764741931406749, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.0590866} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3950942304129613, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4193851803411235, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.390671968179558, "gear": 1, "accelerator_pedal_position": 0.3950942304129613, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1797945559253051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.0590866} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.4399995803833008, "x": 0.06365559344657257, "y": -0.00015719778843248378, "z": null, "yaw": 6.278334493555943, "pitch": null, "roll": null}, "v": 0.36075060221977395, "accelerator_pedal_position": 0.3941103335539835, "brake_pedal_position": 0.0, "acceleration": 0.9938506446313888, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.007764741931406749, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.0790865} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3950942304129613, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4193851803411235, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.4106317687352455, "gear": 1, "accelerator_pedal_position": 0.3950942304129613, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1797945559253051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.0790865} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.4399995803833008, "x": 0.06365559344657257, "y": -0.00015719778843248378, "z": null, "yaw": 6.278334493555943, "pitch": null, "roll": null}, "v": 0.36075060221977395, "accelerator_pedal_position": 0.3941103335539835, "brake_pedal_position": 0.0, "acceleration": 0.9938506446313888, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.007764741931406749, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.0990865} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3950942304129613, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4193851803411235, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.4305683776306325, "gear": 1, "accelerator_pedal_position": 0.3950942304129613, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1797945559253051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.0990865} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.4399995803833008, "x": 0.06365559344657257, "y": -0.00015719778843248378, "z": null, "yaw": 6.278334493555943, "pitch": null, "roll": null}, "v": 0.36075060221977395, "accelerator_pedal_position": 0.3941103335539835, "brake_pedal_position": 0.0, "acceleration": 0.9938506446313888, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.007764741931406749, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.1190865} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3950942304129613, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4193851803411235, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.45048166287175256, "gear": 1, "accelerator_pedal_position": 0.3950942304129613, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1797945559253051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.1190865} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502639.1390865, "x": 4.108821696674257, "y": 4.999572738443982, "z": null, "yaw": -0.007218437148591534, "pitch": null, "roll": null}, "v": 0.47037149317593346, "accelerator_pedal_position": 0.3950942304129613, "brake_pedal_position": 0.0, "acceleration": 0.993607872006286, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.01012420557007563, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.1390865} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3961169708919556, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1356043896108887, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.47037149317593346, "gear": 1, "accelerator_pedal_position": 0.3950942304129613, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1797945559253051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.1390865} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.549999475479126, "x": 0.10882169667425678, "y": -0.0004272615560179105, "z": null, "yaw": 6.275966870030994, "pitch": null, "roll": null}, "v": 0.47037149317593346, "accelerator_pedal_position": 0.3950942304129613, "brake_pedal_position": 0.0, "acceleration": 0.993607872006286, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.01012420557007563, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.1590865} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3961169708919556, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1356043896108887, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.4903655424329471, "gear": 1, "accelerator_pedal_position": 0.3961169708919556, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1797945559253051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.1590865} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.549999475479126, "x": 0.10882169667425678, "y": -0.0004272615560179105, "z": null, "yaw": 6.275966870030994, "pitch": null, "roll": null}, "v": 0.47037149317593346, "accelerator_pedal_position": 0.3950942304129613, "brake_pedal_position": 0.0, "acceleration": 0.993607872006286, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.01012420557007563, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.1790864} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3961169708919556, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1356043896108887, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5302819038945259, "gear": 1, "accelerator_pedal_position": 0.3961169708919556, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1797945559253051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.1790864} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.549999475479126, "x": 0.10882169667425678, "y": -0.0004272615560179105, "z": null, "yaw": 6.275966870030994, "pitch": null, "roll": null}, "v": 0.47037149317593346, "accelerator_pedal_position": 0.3950942304129613, "brake_pedal_position": 0.0, "acceleration": 0.993607872006286, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.01012420557007563, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.1990864} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3961169708919556, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1356043896108887, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5302819038945259, "gear": 1, "accelerator_pedal_position": 0.3961169708919556, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1797945559253051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.1990864} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.549999475479126, "x": 0.10882169667425678, "y": -0.0004272615560179105, "z": null, "yaw": 6.275966870030994, "pitch": null, "roll": null}, "v": 0.47037149317593346, "accelerator_pedal_position": 0.3950942304129613, "brake_pedal_position": 0.0, "acceleration": 0.993607872006286, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.01012420557007563, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.2190864} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3961169708919556, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1356043896108887, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.550203954868394, "gear": 1, "accelerator_pedal_position": 0.3961169708919556, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1797945559253051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.2190864} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.549999475479126, "x": 0.10882169667425678, "y": -0.0004272615560179105, "z": null, "yaw": 6.275966870030994, "pitch": null, "roll": null}, "v": 0.47037149317593346, "accelerator_pedal_position": 0.3950942304129613, "brake_pedal_position": 0.0, "acceleration": 0.993607872006286, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.01012420557007563, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.2390864} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3961169708919556, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1356043896108887, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.5701017464054556, "gear": 1, "accelerator_pedal_position": 0.3961169708919556, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1797945559253051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.2390864} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502639.2490864, "x": 4.1660506865518885, "y": 4.999095672957929, "z": null, "yaw": -0.00958606067353966, "pitch": null, "roll": null}, "v": 0.5800415046128746, "accelerator_pedal_position": 0.3961169708919556, "brake_pedal_position": 0.0, "acceleration": 0.9933645113733428, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.012484726470615926, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.2590864} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3971786490722207, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9156972606132593, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.589975149726608, "gear": 1, "accelerator_pedal_position": 0.3961169708919556, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1797945559253051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.2590864} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.6599993705749512, "x": 0.16605068655188848, "y": -0.0009043270420709959, "z": null, "yaw": 6.273599246506047, "pitch": null, "roll": null}, "v": 0.5800415046128746, "accelerator_pedal_position": 0.3961169708919556, "brake_pedal_position": 0.0, "acceleration": 0.9933645113733428, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.012484726470615926, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.2790864} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3971786490722207, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9156972606132593, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6099567054251431, "gear": 1, "accelerator_pedal_position": 0.3971786490722207, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1797945559253051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.2790864} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.6599993705749512, "x": 0.16605068655188848, "y": -0.0009043270420709959, "z": null, "yaw": 6.273599246506047, "pitch": null, "roll": null}, "v": 0.5800415046128746, "accelerator_pedal_position": 0.3961169708919556, "brake_pedal_position": 0.0, "acceleration": 0.9933645113733428, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.012484726470615926, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.2990863} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3971786490722207, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9156972606132593, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.629913452058564, "gear": 1, "accelerator_pedal_position": 0.3971786490722207, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1797945559253051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.2990863} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.6599993705749512, "x": 0.16605068655188848, "y": -0.0009043270420709959, "z": null, "yaw": 6.273599246506047, "pitch": null, "roll": null}, "v": 0.5800415046128746, "accelerator_pedal_position": 0.3961169708919556, "brake_pedal_position": 0.0, "acceleration": 0.9933645113733428, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.012484726470615926, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.3190863} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3971786490722207, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9156972606132593, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6498452611708999, "gear": 1, "accelerator_pedal_position": 0.3971786490722207, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1797945559253051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.3190863} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.6599993705749512, "x": 0.16605068655188848, "y": -0.0009043270420709959, "z": null, "yaw": 6.273599246506047, "pitch": null, "roll": null}, "v": 0.5800415046128746, "accelerator_pedal_position": 0.3961169708919556, "brake_pedal_position": 0.0, "acceleration": 0.9933645113733428, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.012484726470615926, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.3390863} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3971786490722207, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9156972606132593, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6796959378524123, "gear": 1, "accelerator_pedal_position": 0.3971786490722207, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1797945559253051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.3390863} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502639.3590863, "x": 4.2353344217403, "y": 4.99835456379934, "z": null, "yaw": -0.011953684198487786, "pitch": null, "roll": null}, "v": 0.6896335567937066, "accelerator_pedal_position": 0.3971786490722207, "brake_pedal_position": 0.0, "acceleration": 0.9931289344351348, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.014843569387803937, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.3590863} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3982780195625992, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7400758668327561, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6896335567937066, "gear": 1, "accelerator_pedal_position": 0.3971786490722207, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1797945559253051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.3590863} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.7699992656707764, "x": 0.2353344217403004, "y": -0.0016454362006603773, "z": null, "yaw": 6.271231622981098, "pitch": null, "roll": null}, "v": 0.6896335567937066, "accelerator_pedal_position": 0.3971786490722207, "brake_pedal_position": 0.0, "acceleration": 0.9931289344351348, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.014843569387803937, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.3790863} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3982780195625992, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7400758668327561, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7295951576453222, "gear": 1, "accelerator_pedal_position": 0.3982780195625992, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1797945559253051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.3790863} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.7699992656707764, "x": 0.2353344217403004, "y": -0.0016454362006603773, "z": null, "yaw": 6.271231622981098, "pitch": null, "roll": null}, "v": 0.6896335567937066, "accelerator_pedal_position": 0.3971786490722207, "brake_pedal_position": 0.0, "acceleration": 0.9931289344351348, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.014843569387803937, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.3990862} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3982780195625992, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7400758668327561, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7395695053797561, "gear": 1, "accelerator_pedal_position": 0.3982780195625992, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1797945559253051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.3990862} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.7699992656707764, "x": 0.2353344217403004, "y": -0.0016454362006603773, "z": null, "yaw": 6.271231622981098, "pitch": null, "roll": null}, "v": 0.6896335567937066, "accelerator_pedal_position": 0.3971786490722207, "brake_pedal_position": 0.0, "acceleration": 0.9931289344351348, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.014843569387803937, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.4190862} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3982780195625992, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7400758668327561, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7495374005443999, "gear": 1, "accelerator_pedal_position": 0.3982780195625992, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1797945559253051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.4190862} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.7699992656707764, "x": 0.2353344217403004, "y": -0.0016454362006603773, "z": null, "yaw": 6.271231622981098, "pitch": null, "roll": null}, "v": 0.6896335567937066, "accelerator_pedal_position": 0.3971786490722207, "brake_pedal_position": 0.0, "acceleration": 0.9931289344351348, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.014843569387803937, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.4390862} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3982780195625992, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7400758668327561, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7794022138243517, "gear": 1, "accelerator_pedal_position": 0.3982780195625992, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1797945559253051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.4390862} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.7699992656707764, "x": 0.2353344217403004, "y": -0.0016454362006603773, "z": null, "yaw": 6.271231622981098, "pitch": null, "roll": null}, "v": 0.6896335567937066, "accelerator_pedal_position": 0.3971786490722207, "brake_pedal_position": 0.0, "acceleration": 0.9931289344351348, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.014843569387803937, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.4590862} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3982780195625992, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7400758668327561, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7893441421590105, "gear": 1, "accelerator_pedal_position": 0.3982780195625992, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1797945559253051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.4590862} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502639.4690862, "x": 4.316676563322144, "y": 4.997292264762089, "z": null, "yaw": -0.014321307723435912, "pitch": null, "roll": null}, "v": 0.7992795398931174, "accelerator_pedal_position": 0.3982780195625992, "brake_pedal_position": 0.0, "acceleration": 0.9928851674426713, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.01720357310600603, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.4790862} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.39941639277177177, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5801172679023778, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8092083915675441, "gear": 1, "accelerator_pedal_position": 0.3982780195625992, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1797945559253051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.4790862} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.8799991607666016, "x": 0.3166765633221438, "y": -0.002707735237910569, "z": null, "yaw": 6.26886399945615, "pitch": null, "roll": null}, "v": 0.7992795398931174, "accelerator_pedal_position": 0.3982780195625992, "brake_pedal_position": 0.0, "acceleration": 0.9928851674426713, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.01720357310600603, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.4990861} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.39941639277177177, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5801172679023778, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.829188644567241, "gear": 1, "accelerator_pedal_position": 0.39941639277177177, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1797945559253051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.4990861} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.8799991607666016, "x": 0.3166765633221438, "y": -0.002707735237910569, "z": null, "yaw": 6.26886399945615, "pitch": null, "roll": null}, "v": 0.7992795398931174, "accelerator_pedal_position": 0.3982780195625992, "brake_pedal_position": 0.0, "acceleration": 0.9928851674426713, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.01720357310600603, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.5190861} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.39941639277177177, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5801172679023778, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8591091882276143, "gear": 1, "accelerator_pedal_position": 0.39941639277177177, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1797945559253051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.5190861} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.8799991607666016, "x": 0.3166765633221438, "y": -0.002707735237910569, "z": null, "yaw": 6.26886399945615, "pitch": null, "roll": null}, "v": 0.7992795398931174, "accelerator_pedal_position": 0.3982780195625992, "brake_pedal_position": 0.0, "acceleration": 0.9928851674426713, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.01720357310600603, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.539086} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.39941639277177177, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5801172679023778, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8889695580719712, "gear": 1, "accelerator_pedal_position": 0.39941639277177177, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1797945559253051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.539086} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.8799991607666016, "x": 0.3166765633221438, "y": -0.002707735237910569, "z": null, "yaw": 6.26886399945615, "pitch": null, "roll": null}, "v": 0.7992795398931174, "accelerator_pedal_position": 0.3982780195625992, "brake_pedal_position": 0.0, "acceleration": 0.9928851674426713, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.01720357310600603, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.559086} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.39941639277177177, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5801172679023778, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8889695580719712, "gear": 1, "accelerator_pedal_position": 0.39941639277177177, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1797945559253051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.559086} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502639.579086, "x": 4.410068133942758, "y": 4.995851794311904, "z": null, "yaw": -0.016688931248384036, "pitch": null, "roll": null}, "v": 0.9088428370746009, "accelerator_pedal_position": 0.39941639277177177, "brake_pedal_position": 0.0, "acceleration": 0.9926503599448252, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.01956179710489479, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.579086} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4005923351805997, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4477938085583233, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9188428370746009, "gear": 1, "accelerator_pedal_position": 0.4005923351805997, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1797945559253051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.579086} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.9899990558624268, "x": 0.4100681339427581, "y": -0.0041482056880957074, "z": null, "yaw": 6.266496375931202, "pitch": null, "roll": null}, "v": 0.9088428370746009, "accelerator_pedal_position": 0.39941639277177177, "brake_pedal_position": 0.0, "acceleration": 0.9926503599448252, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.01956179710489479, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.599086} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4005923351805997, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4477938085583233, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9288360093889267, "gear": 1, "accelerator_pedal_position": 0.4005923351805997, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1797945559253051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.599086} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.9899990558624268, "x": 0.4100681339427581, "y": -0.0041482056880957074, "z": null, "yaw": 6.266496375931202, "pitch": null, "roll": null}, "v": 0.9088428370746009, "accelerator_pedal_position": 0.39941639277177177, "brake_pedal_position": 0.0, "acceleration": 0.9926503599448252, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.01956179710489479, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.619086} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4005923351805997, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4477938085583233, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9488018097408595, "gear": 1, "accelerator_pedal_position": 0.4005923351805997, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1797945559253051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.619086} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.9899990558624268, "x": 0.4100681339427581, "y": -0.0041482056880957074, "z": null, "yaw": 6.266496375931202, "pitch": null, "roll": null}, "v": 0.9088428370746009, "accelerator_pedal_position": 0.39941639277177177, "brake_pedal_position": 0.0, "acceleration": 0.9926503599448252, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.01956179710489479, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.639086} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4005923351805997, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4477938085583233, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9687401162060897, "gear": 1, "accelerator_pedal_position": 0.4005923351805997, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1797945559253051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.639086} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 0.9899990558624268, "x": 0.4100681339427581, "y": -0.0041482056880957074, "z": null, "yaw": 6.266496375931202, "pitch": null, "roll": null}, "v": 0.9088428370746009, "accelerator_pedal_position": 0.39941639277177177, "brake_pedal_position": 0.0, "acceleration": 0.9926503599448252, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.01956179710489479, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.659086} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4005923351805997, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4477938085583233, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9886508076857429, "gear": 1, "accelerator_pedal_position": 0.4005923351805997, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1797945559253051, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.659086} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502639.689086, "x": 4.515512822324933, "y": 4.993975998601396, "z": null, "yaw": -0.019056554773332162, "pitch": null, "roll": null}, "v": 1.0184648039397393, "accelerator_pedal_position": 0.4005923351805997, "brake_pedal_position": 0.0, "acceleration": 0.992406149113121, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.021921283901267387, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.689086} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4018073513225004, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.29744631951598405, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0384577570101314, "gear": 1, "accelerator_pedal_position": 0.4018073513225004, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1407446082810997, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.689086} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.099998950958252, "x": 0.5155128223249328, "y": -0.006024001398603929, "z": null, "yaw": 6.264128752406254, "pitch": null, "roll": null}, "v": 1.0184648039397393, "accelerator_pedal_position": 0.4005923351805997, "brake_pedal_position": 0.0, "acceleration": 0.992406149113121, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.021921283901267387, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.709086} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4018073513225004, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.29744631951598405, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.048443648137973, "gear": 1, "accelerator_pedal_position": 0.4018073513225004, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1407446082810997, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.709086} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.099998950958252, "x": 0.5155128223249328, "y": -0.006024001398603929, "z": null, "yaw": 6.264128752406254, "pitch": null, "roll": null}, "v": 1.0184648039397393, "accelerator_pedal_position": 0.4005923351805997, "brake_pedal_position": 0.0, "acceleration": 0.992406149113121, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.021921283901267387, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.729086} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4018073513225004, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.29744631951598405, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0584224623632283, "gear": 1, "accelerator_pedal_position": 0.4018073513225004, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1407446082810997, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.729086} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.099998950958252, "x": 0.5155128223249328, "y": -0.006024001398603929, "z": null, "yaw": 6.264128752406254, "pitch": null, "roll": null}, "v": 1.0184648039397393, "accelerator_pedal_position": 0.4005923351805997, "brake_pedal_position": 0.0, "acceleration": 0.992406149113121, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.021921283901267387, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.749086} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4018073513225004, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.29744631951598405, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0783588005306795, "gear": 1, "accelerator_pedal_position": 0.4018073513225004, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1407446082810997, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.749086} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.099998950958252, "x": 0.5155128223249328, "y": -0.006024001398603929, "z": null, "yaw": 6.264128752406254, "pitch": null, "roll": null}, "v": 1.0184648039397393, "accelerator_pedal_position": 0.4005923351805997, "brake_pedal_position": 0.0, "acceleration": 0.992406149113121, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.021921283901267387, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.769086} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4018073513225004, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.29744631951598405, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.098266652892293, "gear": 1, "accelerator_pedal_position": 0.4018073513225004, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1407446082810997, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.769086} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.099998950958252, "x": 0.5155128223249328, "y": -0.006024001398603929, "z": null, "yaw": 6.264128752406254, "pitch": null, "roll": null}, "v": 1.0184648039397393, "accelerator_pedal_position": 0.4005923351805997, "brake_pedal_position": 0.0, "acceleration": 0.992406149113121, "steering_wheel_angle": -1.1797945559253051, "front_wheel_angle": -0.0550453933543193, "heading_rate": -0.021921283901267387, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.7890859} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4018073513225004, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.29744631951598405, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.137996429967674, "gear": 1, "accelerator_pedal_position": 0.4018073513225004, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1407446082810997, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.7890859} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502639.7990859, "x": 4.633008456601953, "y": 4.9916113704074645, "z": null, "yaw": -0.021351682213653866, "pitch": null, "roll": null}, "v": 1.1280747631587245, "accelerator_pedal_position": 0.4018073513225004, "brake_pedal_position": 0.0, "acceleration": 0.9921666808949349, "steering_wheel_angle": -1.1407446082810997, "front_wheel_angle": -0.05319492473024455, "heading_rate": -0.02346270221191366, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.8090858} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4030606823793108, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.16681047596192075, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.137996429967674, "gear": 1, "accelerator_pedal_position": 0.4018073513225004, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1407446082810997, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.8090858} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.2099988460540771, "x": 0.6330084566019529, "y": -0.008388629592535501, "z": null, "yaw": 6.2618336249659325, "pitch": null, "roll": null}, "v": 1.1280747631587245, "accelerator_pedal_position": 0.4018073513225004, "brake_pedal_position": 0.0, "acceleration": 0.9921666808949349, "steering_wheel_angle": -1.1407446082810997, "front_wheel_angle": -0.05319492473024455, "heading_rate": -0.02346270221191366, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.8390858} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4030606823793108, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.16681047596192075, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.187887430693919, "gear": 1, "accelerator_pedal_position": 0.4030606823793108, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.0237458350603676, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.8390858} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.2099988460540771, "x": 0.6330084566019529, "y": -0.008388629592535501, "z": null, "yaw": 6.2618336249659325, "pitch": null, "roll": null}, "v": 1.1280747631587245, "accelerator_pedal_position": 0.4018073513225004, "brake_pedal_position": 0.0, "acceleration": 0.9921666808949349, "steering_wheel_angle": -1.1407446082810997, "front_wheel_angle": -0.05319492473024455, "heading_rate": -0.02346270221191366, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.8590858} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4030606823793108, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.16681047596192075, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.187887430693919, "gear": 1, "accelerator_pedal_position": 0.4030606823793108, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.0237458350603676, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.8590858} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.2099988460540771, "x": 0.6330084566019529, "y": -0.008388629592535501, "z": null, "yaw": 6.2618336249659325, "pitch": null, "roll": null}, "v": 1.1280747631587245, "accelerator_pedal_position": 0.4018073513225004, "brake_pedal_position": 0.0, "acceleration": 0.9921666808949349, "steering_wheel_angle": -1.1407446082810997, "front_wheel_angle": -0.05319492473024455, "heading_rate": -0.02346270221191366, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.8790858} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4030606823793108, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.16681047596192075, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2177340799209784, "gear": 1, "accelerator_pedal_position": 0.4030606823793108, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.0237458350603676, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.8790858} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.2099988460540771, "x": 0.6330084566019529, "y": -0.008388629592535501, "z": null, "yaw": 6.2618336249659325, "pitch": null, "roll": null}, "v": 1.1280747631587245, "accelerator_pedal_position": 0.4018073513225004, "brake_pedal_position": 0.0, "acceleration": 0.9921666808949349, "steering_wheel_angle": -1.1407446082810997, "front_wheel_angle": -0.05319492473024455, "heading_rate": -0.02346270221191366, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.8990858} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4030606823793108, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.16681047596192075, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2276682179007847, "gear": 1, "accelerator_pedal_position": 0.4030606823793108, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.0237458350603676, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.8990858} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502639.9090858, "x": 4.762544446194814, "y": 4.988715496391628, "z": null, "yaw": -0.023466234438233532, "pitch": null, "roll": null}, "v": 1.237594959515217, "accelerator_pedal_position": 0.4030606823793108, "brake_pedal_position": 0.0, "acceleration": 0.9919331040567566, "steering_wheel_angle": -1.0237458350603676, "front_wheel_angle": -0.04766269828541294, "heading_rate": -0.02305930602983657, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.9190857} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.40435138573022966, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.045431341580688775, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2475142905557846, "gear": 1, "accelerator_pedal_position": 0.4030606823793108, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.0237458350603676, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.9190857} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.3199987411499023, "x": 0.7625444461948137, "y": -0.011284503608371743, "z": null, "yaw": 6.259719072741353, "pitch": null, "roll": null}, "v": 1.237594959515217, "accelerator_pedal_position": 0.4030606823793108, "brake_pedal_position": 0.0, "acceleration": 0.9919331040567566, "steering_wheel_angle": -1.0237458350603676, "front_wheel_angle": -0.04766269828541294, "heading_rate": -0.02305930602983657, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.9390857} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.40435138573022966, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.045431341580688775, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.277469503706695, "gear": 1, "accelerator_pedal_position": 0.40435138573022966, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.9067418378242836, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.9390857} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.40435138573022966, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.045431341580688775, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.277469503706695, "gear": 1, "accelerator_pedal_position": 0.40435138573022966, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.9067418378242836, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.9490857} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.3199987411499023, "x": 0.7625444461948137, "y": -0.011284503608371743, "z": null, "yaw": 6.259719072741353, "pitch": null, "roll": null}, "v": 1.237594959515217, "accelerator_pedal_position": 0.4030606823793108, "brake_pedal_position": 0.0, "acceleration": 0.9919331040567566, "steering_wheel_angle": -1.0237458350603676, "front_wheel_angle": -0.04766269828541294, "heading_rate": -0.02305930602983657, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.9790857} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.40435138573022966, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.045431341580688775, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3173043298057185, "gear": 1, "accelerator_pedal_position": 0.40435138573022966, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.867656560426274, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.9790857} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.3199987411499023, "x": 0.7625444461948137, "y": -0.011284503608371743, "z": null, "yaw": 6.259719072741353, "pitch": null, "roll": null}, "v": 1.237594959515217, "accelerator_pedal_position": 0.4030606823793108, "brake_pedal_position": 0.0, "acceleration": 0.9919331040567566, "steering_wheel_angle": -1.0237458350603676, "front_wheel_angle": -0.04766269828541294, "heading_rate": -0.02305930602983657, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502639.9990857} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.40435138573022966, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.045431341580688775, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3272441101792225, "gear": 1, "accelerator_pedal_position": 0.40435138573022966, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.867656560426274, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502639.9990857} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502640.0190856, "x": 4.904117469719066, "y": 4.985268174745568, "z": null, "yaw": -0.025299955738351757, "pitch": null, "roll": null}, "v": 1.347100861457992, "accelerator_pedal_position": 0.40435138573022966, "brake_pedal_position": 0.0, "acceleration": 0.9916943104316268, "steering_wheel_angle": -0.867656560426274, "front_wheel_angle": -0.04030992087529883, "heading_rate": -0.021223031092673244, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.0190856} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.40568029606116934, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.06836287461861668, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.347100861457992, "gear": 1, "accelerator_pedal_position": 0.40435138573022966, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.867656560426274, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.0190856} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.4299986362457275, "x": 0.9041174697190657, "y": -0.014731825254432174, "z": null, "yaw": 6.257885351441234, "pitch": null, "roll": null}, "v": 1.347100861457992, "accelerator_pedal_position": 0.40435138573022966, "brake_pedal_position": 0.0, "acceleration": 0.9916943104316268, "steering_wheel_angle": -0.867656560426274, "front_wheel_angle": -0.04030992087529883, "heading_rate": -0.021223031092673244, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.0390856} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.40568029606116934, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.06836287461861668, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.367093157256269, "gear": 1, "accelerator_pedal_position": 0.40568029606116934, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7892303706327148, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.0390856} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.4299986362457275, "x": 0.9041174697190657, "y": -0.014731825254432174, "z": null, "yaw": 6.257885351441234, "pitch": null, "roll": null}, "v": 1.347100861457992, "accelerator_pedal_position": 0.40435138573022966, "brake_pedal_position": 0.0, "acceleration": 0.9916943104316268, "steering_wheel_angle": -0.867656560426274, "front_wheel_angle": -0.04030992087529883, "heading_rate": -0.021223031092673244, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.0590856} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.40568029606116934, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.06836287461861668, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3870545801390484, "gear": 1, "accelerator_pedal_position": 0.40568029606116934, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7892303706327148, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.0590856} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.4299986362457275, "x": 0.9041174697190657, "y": -0.014731825254432174, "z": null, "yaw": 6.257885351441234, "pitch": null, "roll": null}, "v": 1.347100861457992, "accelerator_pedal_position": 0.40435138573022966, "brake_pedal_position": 0.0, "acceleration": 0.9916943104316268, "steering_wheel_angle": -0.867656560426274, "front_wheel_angle": -0.04030992087529883, "heading_rate": -0.021223031092673244, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.0790856} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.40568029606116934, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.06836287461861668, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4069850184600847, "gear": 1, "accelerator_pedal_position": 0.40568029606116934, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7892303706327148, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.0790856} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.4299986362457275, "x": 0.9041174697190657, "y": -0.014731825254432174, "z": null, "yaw": 6.257885351441234, "pitch": null, "roll": null}, "v": 1.347100861457992, "accelerator_pedal_position": 0.40435138573022966, "brake_pedal_position": 0.0, "acceleration": 0.9916943104316268, "steering_wheel_angle": -0.867656560426274, "front_wheel_angle": -0.04030992087529883, "heading_rate": -0.021223031092673244, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.0990856} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.40568029606116934, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.06836287461861668, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4368223379123544, "gear": 1, "accelerator_pedal_position": 0.40568029606116934, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7892303706327148, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.0990856} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.4299986362457275, "x": 0.9041174697190657, "y": -0.014731825254432174, "z": null, "yaw": 6.257885351441234, "pitch": null, "roll": null}, "v": 1.347100861457992, "accelerator_pedal_position": 0.40435138573022966, "brake_pedal_position": 0.0, "acceleration": 0.9916943104316268, "steering_wheel_angle": -0.867656560426274, "front_wheel_angle": -0.04030992087529883, "heading_rate": -0.021223031092673244, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.1190856} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.40568029606116934, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.06836287461861668, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4566748323788168, "gear": 1, "accelerator_pedal_position": 0.40568029606116934, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7892303706327148, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.1190856} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502640.1290855, "x": 5.057733673796732, "y": 4.981266344334359, "z": null, "yaw": -0.026896104036239907, "pitch": null, "roll": null}, "v": 1.4566748323788168, "accelerator_pedal_position": 0.40568029606116934, "brake_pedal_position": 0.0, "acceleration": 0.9914490930905087, "steering_wheel_angle": -0.7892303706327148, "front_wheel_angle": -0.03662744785490479, "heading_rate": -0.020850841318412184, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.1390855} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3986025404824454, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.17871005704156534, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.485510357561833, "gear": 1, "accelerator_pedal_position": 0.3986025404824454, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7104062261326988, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.1390855} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.5399985313415527, "x": 1.057733673796732, "y": -0.018733655665641002, "z": null, "yaw": 6.256289203143346, "pitch": null, "roll": null}, "v": 1.4566748323788168, "accelerator_pedal_position": 0.40568029606116934, "brake_pedal_position": 0.0, "acceleration": 0.9914490930905087, "steering_wheel_angle": -0.7892303706327148, "front_wheel_angle": -0.03662744785490479, "heading_rate": -0.020850841318412184, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.1590855} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4070484411666879, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.17871005704156534, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4949595870609624, "gear": 1, "accelerator_pedal_position": 0.3986025404824454, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6709306175229047, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.1590855} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.5399985313415527, "x": 1.057733673796732, "y": -0.018733655665641002, "z": null, "yaw": 6.256289203143346, "pitch": null, "roll": null}, "v": 1.4566748323788168, "accelerator_pedal_position": 0.40568029606116934, "brake_pedal_position": 0.0, "acceleration": 0.9914490930905087, "steering_wheel_angle": -0.7892303706327148, "front_wheel_angle": -0.03662744785490479, "heading_rate": -0.020850841318412184, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.1890855} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4070484411666879, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.17871005704156534, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.514890726251388, "gear": 1, "accelerator_pedal_position": 0.4070484411666879, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6709306175229047, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.1890855} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.5399985313415527, "x": 1.057733673796732, "y": -0.018733655665641002, "z": null, "yaw": 6.256289203143346, "pitch": null, "roll": null}, "v": 1.4566748323788168, "accelerator_pedal_position": 0.40568029606116934, "brake_pedal_position": 0.0, "acceleration": 0.9914490930905087, "steering_wheel_angle": -0.7892303706327148, "front_wheel_angle": -0.03662744785490479, "heading_rate": -0.020850841318412184, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.2090855} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4070484411666879, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.17871005704156534, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.534789909463575, "gear": 1, "accelerator_pedal_position": 0.4070484411666879, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6709306175229047, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.2090855} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.5399985313415527, "x": 1.057733673796732, "y": -0.018733655665641002, "z": null, "yaw": 6.256289203143346, "pitch": null, "roll": null}, "v": 1.4566748323788168, "accelerator_pedal_position": 0.40568029606116934, "brake_pedal_position": 0.0, "acceleration": 0.9914490930905087, "steering_wheel_angle": -0.7892303706327148, "front_wheel_angle": -0.03662744785490479, "heading_rate": -0.020850841318412184, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.2290854} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4070484411666879, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.17871005704156534, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.554657029606017, "gear": 1, "accelerator_pedal_position": 0.4070484411666879, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6709306175229047, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.2290854} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502640.2390854, "x": 5.223257022434613, "y": 4.976702662887181, "z": null, "yaw": -0.028297323564877165, "pitch": null, "roll": null}, "v": 1.5645785328161617, "accelerator_pedal_position": 0.4070484411666879, "brake_pedal_position": 0.0, "acceleration": 0.9913447707974994, "steering_wheel_angle": -0.6709306175229047, "front_wheel_angle": -0.0310876255498557, "heading_rate": -0.019005744742388843, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.2490854} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.38029893986951396, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.26484427208034017, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5744919805241366, "gear": 1, "accelerator_pedal_position": 0.4070484411666879, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6709306175229047, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.2490854} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.649998426437378, "x": 1.2232570224346127, "y": -0.023297337112818894, "z": null, "yaw": 6.254887983614709, "pitch": null, "roll": null}, "v": 1.5645785328161617, "accelerator_pedal_position": 0.4070484411666879, "brake_pedal_position": 0.0, "acceleration": 0.9913447707974994, "steering_wheel_angle": -0.6709306175229047, "front_wheel_angle": -0.0310876255498557, "heading_rate": -0.019005744742388843, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.2690854} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3894796959152692, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.26484427208034017, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5909523347541736, "gear": 1, "accelerator_pedal_position": 0.38029893986951396, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5916711940647781, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.2690854} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.649998426437378, "x": 1.2232570224346127, "y": -0.023297337112818894, "z": null, "yaw": 6.254887983614709, "pitch": null, "roll": null}, "v": 1.5645785328161617, "accelerator_pedal_position": 0.4070484411666879, "brake_pedal_position": 0.0, "acceleration": 0.9913447707974994, "steering_wheel_angle": -0.6709306175229047, "front_wheel_angle": -0.0310876255498557, "heading_rate": -0.019005744742388843, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.2890854} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3894796959152692, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.26484427208034017, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6085329157307675, "gear": 1, "accelerator_pedal_position": 0.3894796959152692, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5916711940647781, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.2890854} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.649998426437378, "x": 1.2232570224346127, "y": -0.023297337112818894, "z": null, "yaw": 6.254887983614709, "pitch": null, "roll": null}, "v": 1.5645785328161617, "accelerator_pedal_position": 0.4070484411666879, "brake_pedal_position": 0.0, "acceleration": 0.9913447707974994, "steering_wheel_angle": -0.6709306175229047, "front_wheel_angle": -0.0310876255498557, "heading_rate": -0.019005744742388843, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.3090854} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3894796959152692, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.26484427208034017, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6260846473145067, "gear": 1, "accelerator_pedal_position": 0.3894796959152692, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5916711940647781, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.3090854} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.649998426437378, "x": 1.2232570224346127, "y": -0.023297337112818894, "z": null, "yaw": 6.254887983614709, "pitch": null, "roll": null}, "v": 1.5645785328161617, "accelerator_pedal_position": 0.4070484411666879, "brake_pedal_position": 0.0, "acceleration": 0.9913447707974994, "steering_wheel_angle": -0.6709306175229047, "front_wheel_angle": -0.0310876255498557, "heading_rate": -0.019005744742388843, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.3290854} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3894796959152692, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.26484427208034017, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6436074536721759, "gear": 1, "accelerator_pedal_position": 0.3894796959152692, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5916711940647781, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.3290854} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502640.3490853, "x": 5.40013567806967, "y": 4.971595014687976, "z": null, "yaw": -0.029510537955780052, "pitch": null, "roll": null}, "v": 1.6611012597038548, "accelerator_pedal_position": 0.3894796959152692, "brake_pedal_position": 0.0, "acceleration": 0.8736004625353424, "steering_wheel_angle": -0.5916711940647781, "front_wheel_angle": -0.027385960225383893, "heading_rate": -0.017774308209128127, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.3490853} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.360673015762224, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3395022059286818, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6611012597038548, "gear": 1, "accelerator_pedal_position": 0.3894796959152692, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5916711940647781, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.3490853} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.7599983215332031, "x": 1.4001356780696703, "y": -0.028404985312024067, "z": null, "yaw": 6.253674769223807, "pitch": null, "roll": null}, "v": 1.6611012597038548, "accelerator_pedal_position": 0.3894796959152692, "brake_pedal_position": 0.0, "acceleration": 0.8736004625353424, "steering_wheel_angle": -0.5916711940647781, "front_wheel_angle": -0.027385960225383893, "heading_rate": -0.017774308209128127, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.3690853} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3700720919946048, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3395022059286818, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6749666571891373, "gear": 1, "accelerator_pedal_position": 0.360673015762224, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5120832145906543, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.3690853} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.7599983215332031, "x": 1.4001356780696703, "y": -0.028404985312024067, "z": null, "yaw": 6.253674769223807, "pitch": null, "roll": null}, "v": 1.6611012597038548, "accelerator_pedal_position": 0.3894796959152692, "brake_pedal_position": 0.0, "acceleration": 0.8736004625353424, "steering_wheel_angle": -0.5916711940647781, "front_wheel_angle": -0.027385960225383893, "heading_rate": -0.017774308209128127, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.3890853} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3700720919946048, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3395022059286818, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6899833217002447, "gear": 1, "accelerator_pedal_position": 0.3700720919946048, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5120832145906543, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.3890853} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.7599983215332031, "x": 1.4001356780696703, "y": -0.028404985312024067, "z": null, "yaw": 6.253674769223807, "pitch": null, "roll": null}, "v": 1.6611012597038548, "accelerator_pedal_position": 0.3894796959152692, "brake_pedal_position": 0.0, "acceleration": 0.8736004625353424, "steering_wheel_angle": -0.5916711940647781, "front_wheel_angle": -0.027385960225383893, "heading_rate": -0.017774308209128127, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.4090853} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3700720919946048, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3395022059286818, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7049748514676437, "gear": 1, "accelerator_pedal_position": 0.3700720919946048, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5120832145906543, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.4090853} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.7599983215332031, "x": 1.4001356780696703, "y": -0.028404985312024067, "z": null, "yaw": 6.253674769223807, "pitch": null, "roll": null}, "v": 1.6611012597038548, "accelerator_pedal_position": 0.3894796959152692, "brake_pedal_position": 0.0, "acceleration": 0.8736004625353424, "steering_wheel_angle": -0.5916711940647781, "front_wheel_angle": -0.027385960225383893, "heading_rate": -0.017774308209128127, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.4290853} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3700720919946048, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3395022059286818, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7199411987010031, "gear": 1, "accelerator_pedal_position": 0.3700720919946048, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5120832145906543, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.4290853} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.7599983215332031, "x": 1.4001356780696703, "y": -0.028404985312024067, "z": null, "yaw": 6.253674769223807, "pitch": null, "roll": null}, "v": 1.6611012597038548, "accelerator_pedal_position": 0.3894796959152692, "brake_pedal_position": 0.0, "acceleration": 0.8736004625353424, "steering_wheel_angle": -0.5916711940647781, "front_wheel_angle": -0.027385960225383893, "heading_rate": -0.017774308209128127, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.4490852} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3700720919946048, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3395022059286818, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.734882316142702, "gear": 1, "accelerator_pedal_position": 0.3700720919946048, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5120832145906543, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.4490852} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502640.4590852, "x": 5.586788894306497, "y": 4.965994434070277, "z": null, "yaw": -0.030549842397879546, "pitch": null, "roll": null}, "v": 1.742343399069207, "accelerator_pedal_position": 0.3700720919946048, "brake_pedal_position": 0.0, "acceleration": 0.745475799810019, "steering_wheel_angle": -0.5120832145906543, "front_wheel_angle": -0.02367692324113134, "heading_rate": -0.016117594326344496, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.4690852} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3485524708696682, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4067163021019893, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7497981570673071, "gear": 1, "accelerator_pedal_position": 0.3700720919946048, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5120832145906543, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.4690852} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.8699982166290283, "x": 1.5867888943064967, "y": -0.03400556592972315, "z": null, "yaw": 6.252635464781707, "pitch": null, "roll": null}, "v": 1.742343399069207, "accelerator_pedal_position": 0.3700720919946048, "brake_pedal_position": 0.0, "acceleration": 0.745475799810019, "steering_wheel_angle": -0.5120832145906543, "front_wheel_angle": -0.02367692324113134, "heading_rate": -0.016117594326344496, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.4890852} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.35561871401525946, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4067163021019893, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7619998676386863, "gear": 1, "accelerator_pedal_position": 0.3485524708696682, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4321806685856667, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.4890852} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.8699982166290283, "x": 1.5867888943064967, "y": -0.03400556592972315, "z": null, "yaw": 6.252635464781707, "pitch": null, "roll": null}, "v": 1.742343399069207, "accelerator_pedal_position": 0.3700720919946048, "brake_pedal_position": 0.0, "acceleration": 0.745475799810019, "steering_wheel_angle": -0.5120832145906543, "front_wheel_angle": -0.02367692324113134, "heading_rate": -0.016117594326344496, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.5090852} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.35561871401525946, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4067163021019893, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.775063703863348, "gear": 1, "accelerator_pedal_position": 0.35561871401525946, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4321806685856667, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.5090852} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.8699982166290283, "x": 1.5867888943064967, "y": -0.03400556592972315, "z": null, "yaw": 6.252635464781707, "pitch": null, "roll": null}, "v": 1.742343399069207, "accelerator_pedal_position": 0.3700720919946048, "brake_pedal_position": 0.0, "acceleration": 0.745475799810019, "steering_wheel_angle": -0.5120832145906543, "front_wheel_angle": -0.02367692324113134, "heading_rate": -0.016117594326344496, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.5290852} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.35561871401525946, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4067163021019893, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7881052272045255, "gear": 1, "accelerator_pedal_position": 0.35561871401525946, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4321806685856667, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.5290852} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.8699982166290283, "x": 1.5867888943064967, "y": -0.03400556592972315, "z": null, "yaw": 6.252635464781707, "pitch": null, "roll": null}, "v": 1.742343399069207, "accelerator_pedal_position": 0.3700720919946048, "brake_pedal_position": 0.0, "acceleration": 0.745475799810019, "steering_wheel_angle": -0.5120832145906543, "front_wheel_angle": -0.02367692324113134, "heading_rate": -0.016117594326344496, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.5490851} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.35561871401525946, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4067163021019893, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8011244077689847, "gear": 1, "accelerator_pedal_position": 0.35561871401525946, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4321806685856667, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.5490851} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502640.5690851, "x": 5.7819622468259055, "y": 4.959947382555641, "z": null, "yaw": -0.03144396792533213, "pitch": null, "roll": null}, "v": 1.8141212160639495, "accelerator_pedal_position": 0.35561871401525946, "brake_pedal_position": 0.0, "acceleration": 0.6490005439264406, "steering_wheel_angle": -0.4321806685856667, "front_wheel_angle": -0.01996121178409785, "heading_rate": -0.014147214112136009, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.5690851} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.332741986403961, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.47792069430194456, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8141212160639495, "gear": 1, "accelerator_pedal_position": 0.35561871401525946, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4321806685856667, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.5690851} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.9799981117248535, "x": 1.7819622468259055, "y": -0.04005261744435895, "z": null, "yaw": 6.251741339254254, "pitch": null, "roll": null}, "v": 1.8141212160639495, "accelerator_pedal_position": 0.35561871401525946, "brake_pedal_position": 0.0, "acceleration": 0.6490005439264406, "steering_wheel_angle": -0.4321806685856667, "front_wheel_angle": -0.01996121178409785, "heading_rate": -0.014147214112136009, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.589085} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.34019805084670207, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.47792069430194456, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.824237267358661, "gear": 1, "accelerator_pedal_position": 0.332741986403961, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3519532324444116, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.589085} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.9799981117248535, "x": 1.7819622468259055, "y": -0.04005261744435895, "z": null, "yaw": 6.251741339254254, "pitch": null, "roll": null}, "v": 1.8141212160639495, "accelerator_pedal_position": 0.35561871401525946, "brake_pedal_position": 0.0, "acceleration": 0.6490005439264406, "steering_wheel_angle": -0.4321806685856667, "front_wheel_angle": -0.01996121178409785, "heading_rate": -0.014147214112136009, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.609085} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.34019805084670207, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.47792069430194456, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8352674433068277, "gear": 1, "accelerator_pedal_position": 0.34019805084670207, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3519532324444116, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.609085} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.9799981117248535, "x": 1.7819622468259055, "y": -0.04005261744435895, "z": null, "yaw": 6.251741339254254, "pitch": null, "roll": null}, "v": 1.8141212160639495, "accelerator_pedal_position": 0.35561871401525946, "brake_pedal_position": 0.0, "acceleration": 0.6490005439264406, "steering_wheel_angle": -0.4321806685856667, "front_wheel_angle": -0.01996121178409785, "heading_rate": -0.014147214112136009, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.629085} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.34019805084670207, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.47792069430194456, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8462785122033998, "gear": 1, "accelerator_pedal_position": 0.34019805084670207, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3519532324444116, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.629085} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.9799981117248535, "x": 1.7819622468259055, "y": -0.04005261744435895, "z": null, "yaw": 6.251741339254254, "pitch": null, "roll": null}, "v": 1.8141212160639495, "accelerator_pedal_position": 0.35561871401525946, "brake_pedal_position": 0.0, "acceleration": 0.6490005439264406, "steering_wheel_angle": -0.4321806685856667, "front_wheel_angle": -0.01996121178409785, "heading_rate": -0.014147214112136009, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.649085} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.34019805084670207, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.47792069430194456, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8572704586702233, "gear": 1, "accelerator_pedal_position": 0.34019805084670207, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3519532324444116, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.649085} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 1.9799981117248535, "x": 1.7819622468259055, "y": -0.04005261744435895, "z": null, "yaw": 6.251741339254254, "pitch": null, "roll": null}, "v": 1.8141212160639495, "accelerator_pedal_position": 0.35561871401525946, "brake_pedal_position": 0.0, "acceleration": 0.6490005439264406, "steering_wheel_angle": -0.4321806685856667, "front_wheel_angle": -0.01996121178409785, "heading_rate": -0.014147214112136009, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.669085} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.34019805084670207, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.47792069430194456, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.86824326760825, "gear": 1, "accelerator_pedal_position": 0.34019805084670207, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3519532324444116, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.669085} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502640.679085, "x": 5.984356637505177, "y": 4.953512668578091, "z": null, "yaw": -0.03216359292291094, "pitch": null, "roll": null}, "v": 1.8737224908616685, "accelerator_pedal_position": 0.34019805084670207, "brake_pedal_position": 0.0, "acceleration": 0.5474433335211958, "steering_wheel_angle": -0.3519532324444116, "front_wheel_angle": -0.016238390157444264, "heading_rate": -0.01188629353623964, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.689085} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.32403757131639066, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5448423961189416, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8791969241968804, "gear": 1, "accelerator_pedal_position": 0.34019805084670207, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3519532324444116, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.689085} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.0899980068206787, "x": 1.9843566375051767, "y": -0.04648733142190942, "z": null, "yaw": 6.251021714256675, "pitch": null, "roll": null}, "v": 1.8737224908616685, "accelerator_pedal_position": 0.34019805084670207, "brake_pedal_position": 0.0, "acceleration": 0.5474433335211958, "steering_wheel_angle": -0.3519532324444116, "front_wheel_angle": -0.016238390157444264, "heading_rate": -0.01188629353623964, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.709085} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3293466279305898, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5448423961189416, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8881122395789236, "gear": 1, "accelerator_pedal_position": 0.32403757131639066, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3117023927185367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.709085} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.0899980068206787, "x": 1.9843566375051767, "y": -0.04648733142190942, "z": null, "yaw": 6.251021714256675, "pitch": null, "roll": null}, "v": 1.8737224908616685, "accelerator_pedal_position": 0.34019805084670207, "brake_pedal_position": 0.0, "acceleration": 0.5474433335211958, "steering_wheel_angle": -0.3519532324444116, "front_wheel_angle": -0.016238390157444264, "heading_rate": -0.01188629353623964, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.729085} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3293466279305898, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5448423961189416, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8976752617718284, "gear": 1, "accelerator_pedal_position": 0.3293466279305898, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3117023927185367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.729085} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.0899980068206787, "x": 1.9843566375051767, "y": -0.04648733142190942, "z": null, "yaw": 6.251021714256675, "pitch": null, "roll": null}, "v": 1.8737224908616685, "accelerator_pedal_position": 0.34019805084670207, "brake_pedal_position": 0.0, "acceleration": 0.5474433335211958, "steering_wheel_angle": -0.3519532324444116, "front_wheel_angle": -0.016238390157444264, "heading_rate": -0.01188629353623964, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.749085} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3293466279305898, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5448423961189416, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9072214784771742, "gear": 1, "accelerator_pedal_position": 0.3293466279305898, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3117023927185367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.749085} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.0899980068206787, "x": 1.9843566375051767, "y": -0.04648733142190942, "z": null, "yaw": 6.251021714256675, "pitch": null, "roll": null}, "v": 1.8737224908616685, "accelerator_pedal_position": 0.34019805084670207, "brake_pedal_position": 0.0, "acceleration": 0.5474433335211958, "steering_wheel_angle": -0.3519532324444116, "front_wheel_angle": -0.016238390157444264, "heading_rate": -0.01188629353623964, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.769085} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3293466279305898, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5448423961189416, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9167508827918767, "gear": 1, "accelerator_pedal_position": 0.3293466279305898, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3117023927185367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.769085} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502640.789085, "x": 6.192998476012089, "y": 4.94673811761934, "z": null, "yaw": -0.03279582385818046, "pitch": null, "roll": null}, "v": 1.926263468017414, "accelerator_pedal_position": 0.3293466279305898, "brake_pedal_position": 0.0, "acceleration": 0.47499834168313054, "steering_wheel_angle": -0.3117023927185367, "front_wheel_angle": -0.01437361941300669, "heading_rate": -0.010816126907073322, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.789085} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3115670314501999, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5902408259748769, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.926263468017414, "gear": 1, "accelerator_pedal_position": 0.3293466279305898, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3117023927185367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.789085} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.199997901916504, "x": 2.1929984760120886, "y": -0.0532618823806601, "z": null, "yaw": 6.250389483321406, "pitch": null, "roll": null}, "v": 1.926263468017414, "accelerator_pedal_position": 0.3293466279305898, "brake_pedal_position": 0.0, "acceleration": 0.47499834168313054, "steering_wheel_angle": -0.3117023927185367, "front_wheel_angle": -0.01437361941300669, "heading_rate": -0.010816126907073322, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.809085} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3173543390753945, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5902408259748769, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9335377627460868, "gear": 1, "accelerator_pedal_position": 0.3115670314501999, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.27135885559125744, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.809085} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.199997901916504, "x": 2.1929984760120886, "y": -0.0532618823806601, "z": null, "yaw": 6.250389483321406, "pitch": null, "roll": null}, "v": 1.926263468017414, "accelerator_pedal_position": 0.3293466279305898, "brake_pedal_position": 0.0, "acceleration": 0.47499834168313054, "steering_wheel_angle": -0.3117023927185367, "front_wheel_angle": -0.01437361941300669, "heading_rate": -0.010816126907073322, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.8290849} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3173543390753945, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5902408259748769, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9415222605884248, "gear": 1, "accelerator_pedal_position": 0.3173543390753945, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.27135885559125744, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.8290849} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.199997901916504, "x": 2.1929984760120886, "y": -0.0532618823806601, "z": null, "yaw": 6.250389483321406, "pitch": null, "roll": null}, "v": 1.926263468017414, "accelerator_pedal_position": 0.3293466279305898, "brake_pedal_position": 0.0, "acceleration": 0.47499834168313054, "steering_wheel_angle": -0.3117023927185367, "front_wheel_angle": -0.01437361941300669, "heading_rate": -0.010816126907073322, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.8490849} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3173543390753945, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5902408259748769, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.94949258577363, "gear": 1, "accelerator_pedal_position": 0.3173543390753945, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.27135885559125744, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.8490849} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.199997901916504, "x": 2.1929984760120886, "y": -0.0532618823806601, "z": null, "yaw": 6.250389483321406, "pitch": null, "roll": null}, "v": 1.926263468017414, "accelerator_pedal_position": 0.3293466279305898, "brake_pedal_position": 0.0, "acceleration": 0.47499834168313054, "steering_wheel_angle": -0.3117023927185367, "front_wheel_angle": -0.01437361941300669, "heading_rate": -0.010816126907073322, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.8690848} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3173543390753945, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5902408259748769, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.95744873805934, "gear": 1, "accelerator_pedal_position": 0.3173543390753945, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.27135885559125744, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.8690848} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.199997901916504, "x": 2.1929984760120886, "y": -0.0532618823806601, "z": null, "yaw": 6.250389483321406, "pitch": null, "roll": null}, "v": 1.926263468017414, "accelerator_pedal_position": 0.3293466279305898, "brake_pedal_position": 0.0, "acceleration": 0.47499834168313054, "steering_wheel_angle": -0.3117023927185367, "front_wheel_angle": -0.01437361941300669, "heading_rate": -0.010816126907073322, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.8890848} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3173543390753945, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5902408259748769, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9653907173390566, "gear": 1, "accelerator_pedal_position": 0.3173543390753945, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.27135885559125744, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.8890848} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502640.8990848, "x": 6.406896542279541, "y": 4.939666697009486, "z": null, "yaw": -0.0333405376086837, "pitch": null, "roll": null}, "v": 1.969356392105419, "accelerator_pedal_position": 0.3173543390753945, "brake_pedal_position": 0.0, "acceleration": 0.39621315362467996, "steering_wheel_angle": -0.27135885559125744, "front_wheel_angle": -0.012506558968784396, "heading_rate": -0.009621545344206147, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.9090848} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3025241227527877, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.637236262518994, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9733185236416657, "gear": 1, "accelerator_pedal_position": 0.3173543390753945, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.27135885559125744, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.9090848} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.309997797012329, "x": 2.406896542279541, "y": -0.060333302990514426, "z": null, "yaw": 6.2498447695709025, "pitch": null, "roll": null}, "v": 1.969356392105419, "accelerator_pedal_position": 0.3173543390753945, "brake_pedal_position": 0.0, "acceleration": 0.39621315362467996, "steering_wheel_angle": -0.27135885559125744, "front_wheel_angle": -0.012506558968784396, "heading_rate": -0.009621545344206147, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.9290848} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3073502376535239, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.637236262518994, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9793792099920684, "gear": 1, "accelerator_pedal_position": 0.3025241227527877, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.19043878436691025, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.9290848} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.309997797012329, "x": 2.406896542279541, "y": -0.060333302990514426, "z": null, "yaw": 6.2498447695709025, "pitch": null, "roll": null}, "v": 1.969356392105419, "accelerator_pedal_position": 0.3173543390753945, "brake_pedal_position": 0.0, "acceleration": 0.39621315362467996, "steering_wheel_angle": -0.27135885559125744, "front_wheel_angle": -0.012506558968784396, "heading_rate": -0.009621545344206147, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.9490848} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3073502376535239, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.637236262518994, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9860320395792532, "gear": 1, "accelerator_pedal_position": 0.3073502376535239, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.19043878436691025, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.9490848} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.309997797012329, "x": 2.406896542279541, "y": -0.060333302990514426, "z": null, "yaw": 6.2498447695709025, "pitch": null, "roll": null}, "v": 1.969356392105419, "accelerator_pedal_position": 0.3173543390753945, "brake_pedal_position": 0.0, "acceleration": 0.39621315362467996, "steering_wheel_angle": -0.27135885559125744, "front_wheel_angle": -0.012506558968784396, "heading_rate": -0.009621545344206147, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.9690847} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3073502376535239, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.637236262518994, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9926729410231807, "gear": 1, "accelerator_pedal_position": 0.3073502376535239, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.19043878436691025, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.9690847} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.309997797012329, "x": 2.406896542279541, "y": -0.060333302990514426, "z": null, "yaw": 6.2498447695709025, "pitch": null, "roll": null}, "v": 1.969356392105419, "accelerator_pedal_position": 0.3173543390753945, "brake_pedal_position": 0.0, "acceleration": 0.39621315362467996, "steering_wheel_angle": -0.27135885559125744, "front_wheel_angle": -0.012506558968784396, "heading_rate": -0.009621545344206147, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502640.9890847} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3073502376535239, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.637236262518994, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9993019180776197, "gear": 1, "accelerator_pedal_position": 0.3073502376535239, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.19043878436691025, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502640.9890847} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502641.0090847, "x": 6.625244380468361, "y": 4.932339920735235, "z": null, "yaw": -0.03375380002388734, "pitch": null, "roll": null}, "v": 2.005918974584547, "accelerator_pedal_position": 0.3073502376535239, "brake_pedal_position": 0.0, "acceleration": 0.3304059272793134, "steering_wheel_angle": -0.19043878436691025, "front_wheel_angle": -0.008767679774268141, "heading_rate": -0.006870197614528951, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.0090847} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2906735039473695, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6479939915490437, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.005918974584547, "gear": 1, "accelerator_pedal_position": 0.3073502376535239, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.19043878436691025, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.0090847} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.4199976921081543, "x": 2.625244380468361, "y": -0.06766007926476458, "z": null, "yaw": 6.249431507155699, "pitch": null, "roll": null}, "v": 2.005918974584547, "accelerator_pedal_position": 0.3073502376535239, "brake_pedal_position": 0.0, "acceleration": 0.3304059272793134, "steering_wheel_angle": -0.19043878436691025, "front_wheel_angle": -0.008767679774268141, "heading_rate": -0.006870197614528951, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.0290847} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2960490663779699, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6479939915490437, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0104404626407684, "gear": 1, "accelerator_pedal_position": 0.2906735039473695, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.19043878436691025, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.0290847} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.4199976921081543, "x": 2.625244380468361, "y": -0.06766007926476458, "z": null, "yaw": 6.249431507155699, "pitch": null, "roll": null}, "v": 2.005918974584547, "accelerator_pedal_position": 0.3073502376535239, "brake_pedal_position": 0.0, "acceleration": 0.3304059272793134, "steering_wheel_angle": -0.19043878436691025, "front_wheel_angle": -0.008767679774268141, "heading_rate": -0.006870197614528951, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.0490847} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2960490663779699, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6479939915490437, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.015625440922703, "gear": 1, "accelerator_pedal_position": 0.2960490663779699, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.19043878436691025, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.0490847} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.4199976921081543, "x": 2.625244380468361, "y": -0.06766007926476458, "z": null, "yaw": 6.249431507155699, "pitch": null, "roll": null}, "v": 2.005918974584547, "accelerator_pedal_position": 0.3073502376535239, "brake_pedal_position": 0.0, "acceleration": 0.3304059272793134, "steering_wheel_angle": -0.19043878436691025, "front_wheel_angle": -0.008767679774268141, "heading_rate": -0.006870197614528951, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.0690846} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2960490663779699, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6479939915490437, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0208010607529343, "gear": 1, "accelerator_pedal_position": 0.2960490663779699, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.19043878436691025, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.0690846} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.4199976921081543, "x": 2.625244380468361, "y": -0.06766007926476458, "z": null, "yaw": 6.249431507155699, "pitch": null, "roll": null}, "v": 2.005918974584547, "accelerator_pedal_position": 0.3073502376535239, "brake_pedal_position": 0.0, "acceleration": 0.3304059272793134, "steering_wheel_angle": -0.19043878436691025, "front_wheel_angle": -0.008767679774268141, "heading_rate": -0.006870197614528951, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.0890846} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2960490663779699, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6479939915490437, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0259673283127086, "gear": 1, "accelerator_pedal_position": 0.2960490663779699, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.19043878436691025, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.0890846} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.4199976921081543, "x": 2.625244380468361, "y": -0.06766007926476458, "z": null, "yaw": 6.249431507155699, "pitch": null, "roll": null}, "v": 2.005918974584547, "accelerator_pedal_position": 0.3073502376535239, "brake_pedal_position": 0.0, "acceleration": 0.3304059272793134, "steering_wheel_angle": -0.19043878436691025, "front_wheel_angle": -0.008767679774268141, "heading_rate": -0.006870197614528951, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.1090846} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2960490663779699, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6479939915490437, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0311242498301425, "gear": 1, "accelerator_pedal_position": 0.2960490663779699, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.19043878436691025, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.1090846} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502641.1190846, "x": 6.847129021323694, "y": 4.924809488539774, "z": null, "yaw": -0.034130545918000396, "pitch": null, "roll": null}, "v": 2.0336992077820257, "accelerator_pedal_position": 0.2960490663779699, "brake_pedal_position": 0.0, "acceleration": 0.2572623797958782, "steering_wheel_angle": -0.19043878436691025, "front_wheel_angle": -0.008767679774268141, "heading_rate": -0.006965343876298525, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.1290846} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28279054617741145, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6714079145261908, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0362718315799846, "gear": 1, "accelerator_pedal_position": 0.2960490663779699, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.19043878436691025, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.1290846} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.5299975872039795, "x": 2.8471290213236937, "y": -0.07519051146022626, "z": null, "yaw": 6.249054761261585, "pitch": null, "roll": null}, "v": 2.0336992077820257, "accelerator_pedal_position": 0.2960490663779699, "brake_pedal_position": 0.0, "acceleration": 0.2572623797958782, "steering_wheel_angle": -0.19043878436691025, "front_wheel_angle": -0.008767679774268141, "heading_rate": -0.006965343876298525, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.1490846} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2870593978895244, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6714079145261908, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0397535170187613, "gear": 1, "accelerator_pedal_position": 0.28279054617741145, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.19043878436691025, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.1490846} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.5299975872039795, "x": 2.8471290213236937, "y": -0.07519051146022626, "z": null, "yaw": 6.249054761261585, "pitch": null, "roll": null}, "v": 2.0336992077820257, "accelerator_pedal_position": 0.2960490663779699, "brake_pedal_position": 0.0, "acceleration": 0.2572623797958782, "steering_wheel_angle": -0.19043878436691025, "front_wheel_angle": -0.008767679774268141, "heading_rate": -0.006965343876298525, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.1690845} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2870593978895244, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6714079145261908, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.043762248261874, "gear": 1, "accelerator_pedal_position": 0.2870593978895244, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.19043878436691025, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.1690845} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.5299975872039795, "x": 2.8471290213236937, "y": -0.07519051146022626, "z": null, "yaw": 6.249054761261585, "pitch": null, "roll": null}, "v": 2.0336992077820257, "accelerator_pedal_position": 0.2960490663779699, "brake_pedal_position": 0.0, "acceleration": 0.2572623797958782, "steering_wheel_angle": -0.19043878436691025, "front_wheel_angle": -0.008767679774268141, "heading_rate": -0.006965343876298525, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.1890845} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2870593978895244, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6714079145261908, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.047763698533108, "gear": 1, "accelerator_pedal_position": 0.2870593978895244, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.19043878436691025, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.1890845} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.5299975872039795, "x": 2.8471290213236937, "y": -0.07519051146022626, "z": null, "yaw": 6.249054761261585, "pitch": null, "roll": null}, "v": 2.0336992077820257, "accelerator_pedal_position": 0.2960490663779699, "brake_pedal_position": 0.0, "acceleration": 0.2572623797958782, "steering_wheel_angle": -0.19043878436691025, "front_wheel_angle": -0.008767679774268141, "heading_rate": -0.006965343876298525, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.2090845} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2870593978895244, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6714079145261908, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.051757874655004, "gear": 1, "accelerator_pedal_position": 0.2870593978895244, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.19043878436691025, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.2090845} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502641.2290845, "x": 7.071817351510738, "y": 4.9170991769563255, "z": null, "yaw": -0.034507291812113455, "pitch": null, "roll": null}, "v": 2.055744783472604, "accelerator_pedal_position": 0.2870593978895244, "brake_pedal_position": 0.0, "acceleration": 0.19907313148814898, "steering_wheel_angle": -0.19043878436691025, "front_wheel_angle": -0.008767679774268141, "heading_rate": -0.007040849150160194, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.2290845} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28164814736982113, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7401422442002977, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.055744783472604, "gear": 1, "accelerator_pedal_position": 0.2870593978895244, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.19043878436691025, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.2290845} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.6399974822998047, "x": 3.071817351510738, "y": -0.08290082304367452, "z": null, "yaw": 6.248678015367473, "pitch": null, "roll": null}, "v": 2.055744783472604, "accelerator_pedal_position": 0.2870593978895244, "brake_pedal_position": 0.0, "acceleration": 0.19907313148814898, "steering_wheel_angle": -0.19043878436691025, "front_wheel_angle": -0.008767679774268141, "heading_rate": -0.007040849150160194, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.2490845} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2834393553443831, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7401422442002977, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0590483338150127, "gear": 1, "accelerator_pedal_position": 0.28164814736982113, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.10911745138502597, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.2490845} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.6399974822998047, "x": 3.071817351510738, "y": -0.08290082304367452, "z": null, "yaw": 6.248678015367473, "pitch": null, "roll": null}, "v": 2.055744783472604, "accelerator_pedal_position": 0.2870593978895244, "brake_pedal_position": 0.0, "acceleration": 0.19907313148814898, "steering_wheel_angle": -0.19043878436691025, "front_wheel_angle": -0.008767679774268141, "heading_rate": -0.007040849150160194, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.2690845} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2834393553443831, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7401422442002977, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.062569662457643, "gear": 1, "accelerator_pedal_position": 0.2834393553443831, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.10911745138502597, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.2690845} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.6399974822998047, "x": 3.071817351510738, "y": -0.08290082304367452, "z": null, "yaw": 6.248678015367473, "pitch": null, "roll": null}, "v": 2.055744783472604, "accelerator_pedal_position": 0.2870593978895244, "brake_pedal_position": 0.0, "acceleration": 0.19907313148814898, "steering_wheel_angle": -0.19043878436691025, "front_wheel_angle": -0.008767679774268141, "heading_rate": -0.007040849150160194, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.2890844} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2834393553443831, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7401422442002977, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.066084568748933, "gear": 1, "accelerator_pedal_position": 0.2834393553443831, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.10911745138502597, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.2890844} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.6399974822998047, "x": 3.071817351510738, "y": -0.08290082304367452, "z": null, "yaw": 6.248678015367473, "pitch": null, "roll": null}, "v": 2.055744783472604, "accelerator_pedal_position": 0.2870593978895244, "brake_pedal_position": 0.0, "acceleration": 0.19907313148814898, "steering_wheel_angle": -0.19043878436691025, "front_wheel_angle": -0.008767679774268141, "heading_rate": -0.007040849150160194, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.3090844} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2834393553443831, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7401422442002977, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.069593059462673, "gear": 1, "accelerator_pedal_position": 0.2834393553443831, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.10911745138502597, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.3090844} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.6399974822998047, "x": 3.071817351510738, "y": -0.08290082304367452, "z": null, "yaw": 6.248678015367473, "pitch": null, "roll": null}, "v": 2.055744783472604, "accelerator_pedal_position": 0.2870593978895244, "brake_pedal_position": 0.0, "acceleration": 0.19907313148814898, "steering_wheel_angle": -0.19043878436691025, "front_wheel_angle": -0.008767679774268141, "heading_rate": -0.007040849150160194, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.3290844} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2834393553443831, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7401422442002977, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0730951413873315, "gear": 1, "accelerator_pedal_position": 0.2834393553443831, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.10911745138502597, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.3290844} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502641.3390844, "x": 7.298759796063872, "y": 4.90923820085875, "z": null, "yaw": -0.0347448943453936, "pitch": null, "roll": null}, "v": 2.0748437811791374, "accelerator_pedal_position": 0.2834393553443831, "brake_pedal_position": 0.0, "acceleration": 0.17470401468045993, "steering_wheel_angle": -0.10911745138502597, "front_wheel_angle": -0.00501831746056114, "heading_rate": -0.0040673094458455045, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.3490844} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27798512712019996, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8008589239660826, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.076590821325942, "gear": 1, "accelerator_pedal_position": 0.2834393553443831, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.10911745138502597, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.3490844} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.74999737739563, "x": 3.298759796063872, "y": -0.09076179914124971, "z": null, "yaw": 6.248440412834193, "pitch": null, "roll": null}, "v": 2.0748437811791374, "accelerator_pedal_position": 0.2834393553443831, "brake_pedal_position": 0.0, "acceleration": 0.17470401468045993, "steering_wheel_angle": -0.10911745138502597, "front_wheel_angle": -0.00501831746056114, "heading_rate": -0.0040673094458455045, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.3690844} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2797767671599757, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8008589239660826, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.07939863969748, "gear": 1, "accelerator_pedal_position": 0.27798512712019996, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.027486007190446405, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.3690844} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.74999737739563, "x": 3.298759796063872, "y": -0.09076179914124971, "z": null, "yaw": 6.248440412834193, "pitch": null, "roll": null}, "v": 2.0748437811791374, "accelerator_pedal_position": 0.2834393553443831, "brake_pedal_position": 0.0, "acceleration": 0.17470401468045993, "steering_wheel_angle": -0.10911745138502597, "front_wheel_angle": -0.00501831746056114, "heading_rate": -0.0040673094458455045, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.3890843} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2797767671599757, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8008589239660826, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0824251703788828, "gear": 1, "accelerator_pedal_position": 0.2797767671599757, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.027486007190446405, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.3890843} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.74999737739563, "x": 3.298759796063872, "y": -0.09076179914124971, "z": null, "yaw": 6.248440412834193, "pitch": null, "roll": null}, "v": 2.0748437811791374, "accelerator_pedal_position": 0.2834393553443831, "brake_pedal_position": 0.0, "acceleration": 0.17470401468045993, "steering_wheel_angle": -0.10911745138502597, "front_wheel_angle": -0.00501831746056114, "heading_rate": -0.0040673094458455045, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.4090843} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2797767671599757, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8008589239660826, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.085446156977823, "gear": 1, "accelerator_pedal_position": 0.2797767671599757, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.027486007190446405, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.4090843} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.74999737739563, "x": 3.298759796063872, "y": -0.09076179914124971, "z": null, "yaw": 6.248440412834193, "pitch": null, "roll": null}, "v": 2.0748437811791374, "accelerator_pedal_position": 0.2834393553443831, "brake_pedal_position": 0.0, "acceleration": 0.17470401468045993, "steering_wheel_angle": -0.10911745138502597, "front_wheel_angle": -0.00501831746056114, "heading_rate": -0.0040673094458455045, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.4290843} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2797767671599757, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8008589239660826, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0884616060012324, "gear": 1, "accelerator_pedal_position": 0.2797767671599757, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.027486007190446405, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.4290843} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502641.4490843, "x": 7.527690424979127, "y": 4.901268131757438, "z": null, "yaw": -0.03483582827024726, "pitch": null, "roll": null}, "v": 2.091471523964178, "accelerator_pedal_position": 0.2797767671599757, "brake_pedal_position": 0.0, "acceleration": 0.1502886871961086, "steering_wheel_angle": -0.027486007190446405, "front_wheel_angle": -0.0012627283722048076, "heading_rate": -0.0010316257174313843, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.4490843} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.267048691126001, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7836121012683116, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.091471523964178, "gear": 1, "accelerator_pedal_position": 0.2797767671599757, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.027486007190446405, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.4490843} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.859997272491455, "x": 3.527690424979127, "y": -0.09873186824256219, "z": null, "yaw": 6.248349478909339, "pitch": null, "roll": null}, "v": 2.091471523964178, "accelerator_pedal_position": 0.2797767671599757, "brake_pedal_position": 0.0, "acceleration": 0.1502886871961086, "steering_wheel_angle": -0.027486007190446405, "front_wheel_angle": -0.0012627283722048076, "heading_rate": -0.0010316257174313843, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.4690843} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2711024251110435, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7836121012683116, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0928856385688426, "gear": 1, "accelerator_pedal_position": 0.267048691126001, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.027486007190446405, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.4690843} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.859997272491455, "x": 3.527690424979127, "y": -0.09873186824256219, "z": null, "yaw": 6.248349478909339, "pitch": null, "roll": null}, "v": 2.091471523964178, "accelerator_pedal_position": 0.2797767671599757, "brake_pedal_position": 0.0, "acceleration": 0.1502886871961086, "steering_wheel_angle": -0.027486007190446405, "front_wheel_angle": -0.0012627283722048076, "heading_rate": -0.0010316257174313843, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.4890842} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2711024251110435, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7836121012683116, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.094803640596656, "gear": 1, "accelerator_pedal_position": 0.2711024251110435, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.027486007190446405, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.4890842} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.859997272491455, "x": 3.527690424979127, "y": -0.09873186824256219, "z": null, "yaw": 6.248349478909339, "pitch": null, "roll": null}, "v": 2.091471523964178, "accelerator_pedal_position": 0.2797767671599757, "brake_pedal_position": 0.0, "acceleration": 0.1502886871961086, "steering_wheel_angle": -0.027486007190446405, "front_wheel_angle": -0.0012627283722048076, "heading_rate": -0.0010316257174313843, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.5090842} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2711024251110435, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7836121012683116, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0967181194748243, "gear": 1, "accelerator_pedal_position": 0.2711024251110435, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.027486007190446405, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.5090842} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.859997272491455, "x": 3.527690424979127, "y": -0.09873186824256219, "z": null, "yaw": 6.248349478909339, "pitch": null, "roll": null}, "v": 2.091471523964178, "accelerator_pedal_position": 0.2797767671599757, "brake_pedal_position": 0.0, "acceleration": 0.1502886871961086, "steering_wheel_angle": -0.027486007190446405, "front_wheel_angle": -0.0012627283722048076, "heading_rate": -0.0010316257174313843, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.5290842} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2711024251110435, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7836121012683116, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0986290802095513, "gear": 1, "accelerator_pedal_position": 0.2711024251110435, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.027486007190446405, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.5290842} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.859997272491455, "x": 3.527690424979127, "y": -0.09873186824256219, "z": null, "yaw": 6.248349478909339, "pitch": null, "roll": null}, "v": 2.091471523964178, "accelerator_pedal_position": 0.2797767671599757, "brake_pedal_position": 0.0, "acceleration": 0.1502886871961086, "steering_wheel_angle": -0.027486007190446405, "front_wheel_angle": -0.0012627283722048076, "heading_rate": -0.0010316257174313843, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.5490842} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2711024251110435, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7836121012683116, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1005365278059176, "gear": 1, "accelerator_pedal_position": 0.2711024251110435, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.027486007190446405, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.5490842} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502641.5590842, "x": 7.758091227316167, "y": 4.893232986476363, "z": null, "yaw": -0.0348900861588282, "pitch": null, "roll": null}, "v": 2.1014889357409903, "accelerator_pedal_position": 0.2711024251110435, "brake_pedal_position": 0.0, "acceleration": 0.09515315268655422, "steering_wheel_angle": -0.027486007190446405, "front_wheel_angle": -0.0012627283722048076, "heading_rate": -0.0010365668411773448, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.5690842} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26836943427445964, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8424013848910704, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1024404672678556, "gear": 1, "accelerator_pedal_position": 0.2711024251110435, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.027486007190446405, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.5690842} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.9699971675872803, "x": 3.758091227316167, "y": -0.10676701352363693, "z": null, "yaw": 6.248295221020758, "pitch": null, "roll": null}, "v": 2.1014889357409903, "accelerator_pedal_position": 0.2711024251110435, "brake_pedal_position": 0.0, "acceleration": 0.09515315268655422, "steering_wheel_angle": -0.027486007190446405, "front_wheel_angle": -0.0012627283722048076, "heading_rate": -0.0010365668411773448, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.5890841} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2692695393362334, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8424013848910704, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1039994370034507, "gear": 1, "accelerator_pedal_position": 0.26836943427445964, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.013437279784330465, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.5890841} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.9699971675872803, "x": 3.758091227316167, "y": -0.10676701352363693, "z": null, "yaw": 6.248295221020758, "pitch": null, "roll": null}, "v": 2.1014889357409903, "accelerator_pedal_position": 0.2711024251110435, "brake_pedal_position": 0.0, "acceleration": 0.09515315268655422, "steering_wheel_angle": -0.027486007190446405, "front_wheel_angle": -0.0012627283722048076, "heading_rate": -0.0010365668411773448, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.6090841} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2692695393362334, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8424013848910704, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1056679986280726, "gear": 1, "accelerator_pedal_position": 0.2692695393362334, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.013437279784330465, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.6090841} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.9699971675872803, "x": 3.758091227316167, "y": -0.10676701352363693, "z": null, "yaw": 6.248295221020758, "pitch": null, "roll": null}, "v": 2.1014889357409903, "accelerator_pedal_position": 0.2711024251110435, "brake_pedal_position": 0.0, "acceleration": 0.09515315268655422, "steering_wheel_angle": -0.027486007190446405, "front_wheel_angle": -0.0012627283722048076, "heading_rate": -0.0010365668411773448, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.629084} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2692695393362334, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8424013848910704, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.107333488010378, "gear": 1, "accelerator_pedal_position": 0.2692695393362334, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.013437279784330465, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.629084} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 2.9699971675872803, "x": 3.758091227316167, "y": -0.10676701352363693, "z": null, "yaw": 6.248295221020758, "pitch": null, "roll": null}, "v": 2.1014889357409903, "accelerator_pedal_position": 0.2711024251110435, "brake_pedal_position": 0.0, "acceleration": 0.09515315268655422, "steering_wheel_angle": -0.027486007190446405, "front_wheel_angle": -0.0012627283722048076, "heading_rate": -0.0010365668411773448, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.649084} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2692695393362334, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8424013848910704, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.108995909698107, "gear": 1, "accelerator_pedal_position": 0.2692695393362334, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.013437279784330465, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.649084} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502641.669084, "x": 7.989574984388282, "y": 4.885153074897152, "z": null, "yaw": -0.034878252602318284, "pitch": null, "roll": null}, "v": 2.110655268236752, "accelerator_pedal_position": 0.2692695393362334, "brake_pedal_position": 0.0, "acceleration": 0.08285320082626535, "steering_wheel_angle": 0.013437279784330465, "front_wheel_angle": 0.0006172053164278363, "heading_rate": 0.0005088702414535276, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.669084} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2668931456056679, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9060995092860595, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.110655268236752, "gear": 1, "accelerator_pedal_position": 0.2692695393362334, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.013437279784330465, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.669084} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.0799970626831055, "x": 3.989574984388282, "y": -0.11484692510284766, "z": null, "yaw": 6.248307054577268, "pitch": null, "roll": null}, "v": 2.110655268236752, "accelerator_pedal_position": 0.2692695393362334, "brake_pedal_position": 0.0, "acceleration": 0.08285320082626535, "steering_wheel_angle": 0.013437279784330465, "front_wheel_angle": 0.0006172053164278363, "heading_rate": 0.0005088702414535276, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.689084} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26767798994944, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9060995092860595, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.112014655934775, "gear": 1, "accelerator_pedal_position": 0.2668931456056679, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.054408102801085864, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.689084} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.0799970626831055, "x": 3.989574984388282, "y": -0.11484692510284766, "z": null, "yaw": 6.248307054577268, "pitch": null, "roll": null}, "v": 2.110655268236752, "accelerator_pedal_position": 0.2692695393362334, "brake_pedal_position": 0.0, "acceleration": 0.08285320082626535, "steering_wheel_angle": 0.013437279784330465, "front_wheel_angle": 0.0006172053164278363, "heading_rate": 0.0005088702414535276, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.709084} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26767798994944, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9060995092860595, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.113469597457368, "gear": 1, "accelerator_pedal_position": 0.26767798994944, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.054408102801085864, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.709084} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.0799970626831055, "x": 3.989574984388282, "y": -0.11484692510284766, "z": null, "yaw": 6.248307054577268, "pitch": null, "roll": null}, "v": 2.110655268236752, "accelerator_pedal_position": 0.2692695393362334, "brake_pedal_position": 0.0, "acceleration": 0.08285320082626535, "steering_wheel_angle": 0.013437279784330465, "front_wheel_angle": 0.0006172053164278363, "heading_rate": 0.0005088702414535276, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.729084} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26767798994944, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9060995092860595, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.114921855498841, "gear": 1, "accelerator_pedal_position": 0.26767798994944, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.054408102801085864, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.729084} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.0799970626831055, "x": 3.989574984388282, "y": -0.11484692510284766, "z": null, "yaw": 6.248307054577268, "pitch": null, "roll": null}, "v": 2.110655268236752, "accelerator_pedal_position": 0.2692695393362334, "brake_pedal_position": 0.0, "acceleration": 0.08285320082626535, "steering_wheel_angle": 0.013437279784330465, "front_wheel_angle": 0.0006172053164278363, "heading_rate": 0.0005088702414535276, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.749084} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26767798994944, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9060995092860595, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1163714341653503, "gear": 1, "accelerator_pedal_position": 0.26767798994944, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.054408102801085864, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.749084} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.0799970626831055, "x": 3.989574984388282, "y": -0.11484692510284766, "z": null, "yaw": 6.248307054577268, "pitch": null, "roll": null}, "v": 2.110655268236752, "accelerator_pedal_position": 0.2692695393362334, "brake_pedal_position": 0.0, "acceleration": 0.08285320082626535, "steering_wheel_angle": 0.013437279784330465, "front_wheel_angle": 0.0006172053164278363, "heading_rate": 0.0005088702414535276, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.769084} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26767798994944, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9060995092860595, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1178183375601436, "gear": 1, "accelerator_pedal_position": 0.26767798994944, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.054408102801085864, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.769084} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502641.779084, "x": 8.221996556602605, "y": 4.877053143585977, "z": null, "yaw": -0.034778168266129214, "pitch": null, "roll": null}, "v": 2.1185407873121127, "accelerator_pedal_position": 0.26767798994944, "brake_pedal_position": 0.0, "acceleration": 0.07217824714334387, "steering_wheel_angle": 0.054408102801085864, "front_wheel_angle": 0.002500433255905069, "heading_rate": 0.0020692503431321905, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.789084} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.265802489568141, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9749783595168136, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.119262569783546, "gear": 1, "accelerator_pedal_position": 0.26767798994944, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.054408102801085864, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.789084} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.1899969577789307, "x": 4.221996556602605, "y": -0.12294685641402303, "z": null, "yaw": 6.248407138913457, "pitch": null, "roll": null}, "v": 2.1185407873121127, "accelerator_pedal_position": 0.26767798994944, "brake_pedal_position": 0.0, "acceleration": 0.07217824714334387, "steering_wheel_angle": 0.054408102801085864, "front_wheel_angle": 0.002500433255905069, "heading_rate": 0.0020692503431321905, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.809084} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2664249723462016, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9749783595168136, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.120469805693678, "gear": 1, "accelerator_pedal_position": 0.265802489568141, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.13637301299728508, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.809084} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.1899969577789307, "x": 4.221996556602605, "y": -0.12294685641402303, "z": null, "yaw": 6.248407138913457, "pitch": null, "roll": null}, "v": 2.1185407873121127, "accelerator_pedal_position": 0.26767798994944, "brake_pedal_position": 0.0, "acceleration": 0.07217824714334387, "steering_wheel_angle": 0.054408102801085864, "front_wheel_angle": 0.002500433255905069, "heading_rate": 0.0020692503431321905, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.829084} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2664249723462016, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9749783595168136, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1217525859719544, "gear": 1, "accelerator_pedal_position": 0.2664249723462016, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.13637301299728508, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.829084} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.1899969577789307, "x": 4.221996556602605, "y": -0.12294685641402303, "z": null, "yaw": 6.248407138913457, "pitch": null, "roll": null}, "v": 2.1185407873121127, "accelerator_pedal_position": 0.26767798994944, "brake_pedal_position": 0.0, "acceleration": 0.07217824714334387, "steering_wheel_angle": 0.054408102801085864, "front_wheel_angle": 0.002500433255905069, "heading_rate": 0.0020692503431321905, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.849084} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2664249723462016, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9749783595168136, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1230329960335177, "gear": 1, "accelerator_pedal_position": 0.2664249723462016, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.13637301299728508, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.849084} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.1899969577789307, "x": 4.221996556602605, "y": -0.12294685641402303, "z": null, "yaw": 6.248407138913457, "pitch": null, "roll": null}, "v": 2.1185407873121127, "accelerator_pedal_position": 0.26767798994944, "brake_pedal_position": 0.0, "acceleration": 0.07217824714334387, "steering_wheel_angle": 0.054408102801085864, "front_wheel_angle": 0.002500433255905069, "heading_rate": 0.0020692503431321905, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.869084} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2664249723462016, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9749783595168136, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.124311039602384, "gear": 1, "accelerator_pedal_position": 0.2664249723462016, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.13637301299728508, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.869084} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502641.8890839, "x": 8.455249790099751, "y": 4.868959186220881, "z": null, "yaw": -0.034545429095979026, "pitch": null, "roll": null}, "v": 2.125586720399321, "accelerator_pedal_position": 0.2664249723462016, "brake_pedal_position": 0.0, "acceleration": 0.06369555208441452, "steering_wheel_angle": 0.13637301299728508, "front_wheel_angle": 0.006274052617707953, "heading_rate": 0.005209460123255481, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.8890839} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2612891134525636, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9794231838866834, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.125586720399321, "gear": 1, "accelerator_pedal_position": 0.2664249723462016, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.13637301299728508, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.8890839} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.299996852874756, "x": 4.455249790099751, "y": -0.13104081377911925, "z": null, "yaw": 6.248639878083607, "pitch": null, "roll": null}, "v": 2.125586720399321, "accelerator_pedal_position": 0.2664249723462016, "brake_pedal_position": 0.0, "acceleration": 0.06369555208441452, "steering_wheel_angle": 0.13637301299728508, "front_wheel_angle": 0.006274052617707953, "heading_rate": 0.005209460123255481, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.9090838} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26292663718240417, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9794231838866834, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.12621835676523, "gear": 1, "accelerator_pedal_position": 0.2612891134525636, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.13637301299728508, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.9090838} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.299996852874756, "x": 4.455249790099751, "y": -0.13104081377911925, "z": null, "yaw": 6.248639878083607, "pitch": null, "roll": null}, "v": 2.125586720399321, "accelerator_pedal_position": 0.2664249723462016, "brake_pedal_position": 0.0, "acceleration": 0.06369555208441452, "steering_wheel_angle": 0.13637301299728508, "front_wheel_angle": 0.006274052617707953, "heading_rate": 0.005209460123255481, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.9290838} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26292663718240417, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9794231838866834, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.127053420641093, "gear": 1, "accelerator_pedal_position": 0.26292663718240417, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.13637301299728508, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.9290838} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.299996852874756, "x": 4.455249790099751, "y": -0.13104081377911925, "z": null, "yaw": 6.248639878083607, "pitch": null, "roll": null}, "v": 2.125586720399321, "accelerator_pedal_position": 0.2664249723462016, "brake_pedal_position": 0.0, "acceleration": 0.06369555208441452, "steering_wheel_angle": 0.13637301299728508, "front_wheel_angle": 0.006274052617707953, "heading_rate": 0.005209460123255481, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.9490838} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26292663718240417, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9794231838866834, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1278869397477282, "gear": 1, "accelerator_pedal_position": 0.26292663718240417, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.13637301299728508, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.9490838} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.299996852874756, "x": 4.455249790099751, "y": -0.13104081377911925, "z": null, "yaw": 6.248639878083607, "pitch": null, "roll": null}, "v": 2.125586720399321, "accelerator_pedal_position": 0.2664249723462016, "brake_pedal_position": 0.0, "acceleration": 0.06369555208441452, "steering_wheel_angle": 0.13637301299728508, "front_wheel_angle": 0.006274052617707953, "heading_rate": 0.005209460123255481, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.9690838} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26292663718240417, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9794231838866834, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.128718916665002, "gear": 1, "accelerator_pedal_position": 0.26292663718240417, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.13637301299728508, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.9690838} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.299996852874756, "x": 4.455249790099751, "y": -0.13104081377911925, "z": null, "yaw": 6.248639878083607, "pitch": null, "roll": null}, "v": 2.125586720399321, "accelerator_pedal_position": 0.2664249723462016, "brake_pedal_position": 0.0, "acceleration": 0.06369555208441452, "steering_wheel_angle": 0.13637301299728508, "front_wheel_angle": 0.006274052617707953, "heading_rate": 0.005209460123255481, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502641.9890838} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26292663718240417, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9794231838866834, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.129549353969549, "gear": 1, "accelerator_pedal_position": 0.26292663718240417, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.13637301299728508, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502641.9890838} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502641.9990838, "x": 8.689135754434787, "y": 4.860904985406072, "z": null, "yaw": -0.03427583736017332, "pitch": null, "roll": null}, "v": 2.1299639960713654, "accelerator_pedal_position": 0.26292663718240417, "brake_pedal_position": 0.0, "acceleration": 0.04142581634085468, "steering_wheel_angle": 0.13637301299728508, "front_wheel_angle": 0.006274052617707953, "heading_rate": 0.005220188099132998, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.0090837} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26019254613353937, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0183881190989668, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.130378254234774, "gear": 1, "accelerator_pedal_position": 0.26292663718240417, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.13637301299728508, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.0090837} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.409996747970581, "x": 4.689135754434787, "y": -0.13909501459392803, "z": null, "yaw": 6.248909469819413, "pitch": null, "roll": null}, "v": 2.1299639960713654, "accelerator_pedal_position": 0.26292663718240417, "brake_pedal_position": 0.0, "acceleration": 0.04142581634085468, "steering_wheel_angle": 0.13637301299728508, "front_wheel_angle": 0.006274052617707953, "heading_rate": 0.005220188099132998, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.0290837} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26106720720827337, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0183881190989668, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1308640169094106, "gear": 1, "accelerator_pedal_position": 0.26019254613353937, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.17733828785346603, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.0290837} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.409996747970581, "x": 4.689135754434787, "y": -0.13909501459392803, "z": null, "yaw": 6.248909469819413, "pitch": null, "roll": null}, "v": 2.1299639960713654, "accelerator_pedal_position": 0.26292663718240417, "brake_pedal_position": 0.0, "acceleration": 0.04142581634085468, "steering_wheel_angle": 0.13637301299728508, "front_wheel_angle": 0.006274052617707953, "heading_rate": 0.005220188099132998, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.0490837} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26106720720827337, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0183881190989668, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.131458162224897, "gear": 1, "accelerator_pedal_position": 0.26106720720827337, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.17733828785346603, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.0490837} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.409996747970581, "x": 4.689135754434787, "y": -0.13909501459392803, "z": null, "yaw": 6.248909469819413, "pitch": null, "roll": null}, "v": 2.1299639960713654, "accelerator_pedal_position": 0.26292663718240417, "brake_pedal_position": 0.0, "acceleration": 0.04142581634085468, "steering_wheel_angle": 0.13637301299728508, "front_wheel_angle": 0.006274052617707953, "heading_rate": 0.005220188099132998, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.0690837} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26106720720827337, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0183881190989668, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1320512073817857, "gear": 1, "accelerator_pedal_position": 0.26106720720827337, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.17733828785346603, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.0690837} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.409996747970581, "x": 4.689135754434787, "y": -0.13909501459392803, "z": null, "yaw": 6.248909469819413, "pitch": null, "roll": null}, "v": 2.1299639960713654, "accelerator_pedal_position": 0.26292663718240417, "brake_pedal_position": 0.0, "acceleration": 0.04142581634085468, "steering_wheel_angle": 0.13637301299728508, "front_wheel_angle": 0.006274052617707953, "heading_rate": 0.005220188099132998, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.0890837} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26106720720827337, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0183881190989668, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.132643154276587, "gear": 1, "accelerator_pedal_position": 0.26106720720827337, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.17733828785346603, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.0890837} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502642.1090837, "x": 8.923461037747035, "y": 4.852904567404205, "z": null, "yaw": -0.03393982926155971, "pitch": null, "roll": null}, "v": 2.13323400480308, "accelerator_pedal_position": 0.26106720720827337, "brake_pedal_position": 0.0, "acceleration": 0.029501471619072628, "steering_wheel_angle": 0.17733828785346603, "front_wheel_angle": 0.00816313015830927, "heading_rate": 0.006802442832221776, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.1090837} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2576387205961097, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0411191043669976, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.13323400480308, "gear": 1, "accelerator_pedal_position": 0.26106720720827337, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.17733828785346603, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.1090837} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.5199966430664062, "x": 4.923461037747035, "y": -0.14709543259579494, "z": null, "yaw": 6.249245477918026, "pitch": null, "roll": null}, "v": 2.13323400480308, "accelerator_pedal_position": 0.26106720720827337, "brake_pedal_position": 0.0, "acceleration": 0.029501471619072628, "steering_wheel_angle": 0.17733828785346603, "front_wheel_angle": 0.00816313015830927, "heading_rate": 0.006802442832221776, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.1290836} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25872526874398055, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0411191043669976, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1333953985961056, "gear": 1, "accelerator_pedal_position": 0.2576387205961097, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.21828501541926934, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.1290836} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.5199966430664062, "x": 4.923461037747035, "y": -0.14709543259579494, "z": null, "yaw": 6.249245477918026, "pitch": null, "roll": null}, "v": 2.13323400480308, "accelerator_pedal_position": 0.26106720720827337, "brake_pedal_position": 0.0, "acceleration": 0.029501471619072628, "steering_wheel_angle": 0.17733828785346603, "front_wheel_angle": 0.00816313015830927, "heading_rate": 0.006802442832221776, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.1490836} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25872526874398055, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0411191043669976, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.133692248996664, "gear": 1, "accelerator_pedal_position": 0.25872526874398055, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.21828501541926934, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.1490836} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.5199966430664062, "x": 4.923461037747035, "y": -0.14709543259579494, "z": null, "yaw": 6.249245477918026, "pitch": null, "roll": null}, "v": 2.13323400480308, "accelerator_pedal_position": 0.26106720720827337, "brake_pedal_position": 0.0, "acceleration": 0.029501471619072628, "steering_wheel_angle": 0.17733828785346603, "front_wheel_angle": 0.00816313015830927, "heading_rate": 0.006802442832221776, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.1690836} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25872526874398055, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0411191043669976, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1339885494556188, "gear": 1, "accelerator_pedal_position": 0.25872526874398055, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.21828501541926934, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.1690836} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.5199966430664062, "x": 4.923461037747035, "y": -0.14709543259579494, "z": null, "yaw": 6.249245477918026, "pitch": null, "roll": null}, "v": 2.13323400480308, "accelerator_pedal_position": 0.26106720720827337, "brake_pedal_position": 0.0, "acceleration": 0.029501471619072628, "steering_wheel_angle": 0.17733828785346603, "front_wheel_angle": 0.00816313015830927, "heading_rate": 0.006802442832221776, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.1890836} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25872526874398055, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0411191043669976, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.134284300956684, "gear": 1, "accelerator_pedal_position": 0.25872526874398055, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.21828501541926934, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.1890836} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.5199966430664062, "x": 4.923461037747035, "y": -0.14709543259579494, "z": null, "yaw": 6.249245477918026, "pitch": null, "roll": null}, "v": 2.13323400480308, "accelerator_pedal_position": 0.26106720720827337, "brake_pedal_position": 0.0, "acceleration": 0.029501471619072628, "steering_wheel_angle": 0.17733828785346603, "front_wheel_angle": 0.00816313015830927, "heading_rate": 0.006802442832221776, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.2090836} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25872526874398055, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0411191043669976, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.134579504481946, "gear": 1, "accelerator_pedal_position": 0.25872526874398055, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.21828501541926934, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.2090836} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502642.2190835, "x": 9.15805178025884, "y": 4.8449840859451125, "z": null, "yaw": -0.033515217215993896, "pitch": null, "roll": null}, "v": 2.1347269010601084, "accelerator_pedal_position": 0.25872526874398055, "brake_pedal_position": 0.0, "acceleration": 0.014725995175775997, "steering_wheel_angle": 0.21828501541926934, "front_wheel_angle": 0.010053398502594419, "heading_rate": 0.00838358722481706, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.2290835} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25524366629961837, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.040032359871897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.134874161011866, "gear": 1, "accelerator_pedal_position": 0.25872526874398055, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.21828501541926934, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.2290835} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.6299965381622314, "x": 5.158051780258839, "y": -0.15501591405488746, "z": null, "yaw": 6.249670089963592, "pitch": null, "roll": null}, "v": 2.1347269010601084, "accelerator_pedal_position": 0.25872526874398055, "brake_pedal_position": 0.0, "acceleration": 0.014725995175775997, "steering_wheel_angle": 0.21828501541926934, "front_wheel_angle": 0.010053398502594419, "heading_rate": 0.00838358722481706, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.2490835} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25633858583344005, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.040032359871897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1347332729312702, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.21828501541926934, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.2490835} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.6299965381622314, "x": 5.158051780258839, "y": -0.15501591405488746, "z": null, "yaw": 6.249670089963592, "pitch": null, "roll": null}, "v": 2.1347269010601084, "accelerator_pedal_position": 0.25872526874398055, "brake_pedal_position": 0.0, "acceleration": 0.014725995175775997, "steering_wheel_angle": 0.21828501541926934, "front_wheel_angle": 0.010053398502594419, "heading_rate": 0.00838358722481706, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.2690835} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25633858583344005, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.040032359871897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1347294474320457, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.21828501541926934, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.2690835} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.6299965381622314, "x": 5.158051780258839, "y": -0.15501591405488746, "z": null, "yaw": 6.249670089963592, "pitch": null, "roll": null}, "v": 2.1347269010601084, "accelerator_pedal_position": 0.25872526874398055, "brake_pedal_position": 0.0, "acceleration": 0.014725995175775997, "steering_wheel_angle": 0.21828501541926934, "front_wheel_angle": 0.010053398502594419, "heading_rate": 0.00838358722481706, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.2890835} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25633858583344005, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.040032359871897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.134725629021597, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.21828501541926934, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.2890835} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.6299965381622314, "x": 5.158051780258839, "y": -0.15501591405488746, "z": null, "yaw": 6.249670089963592, "pitch": null, "roll": null}, "v": 2.1347269010601084, "accelerator_pedal_position": 0.25872526874398055, "brake_pedal_position": 0.0, "acceleration": 0.014725995175775997, "steering_wheel_angle": 0.21828501541926934, "front_wheel_angle": 0.010053398502594419, "heading_rate": 0.00838358722481706, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.3090835} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25633858583344005, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.040032359871897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.134721817686783, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.21828501541926934, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.3090835} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502642.3290834, "x": 9.392743621505659, "y": 4.837161527182354, "z": null, "yaw": -0.03308322069490637, "pitch": null, "roll": null}, "v": 2.134718013414486, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3523061106386872, "steering_wheel_angle": 0.21828501541926934, "front_wheel_angle": 0.010053398502594419, "heading_rate": 0.008383552320889883, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.3290834} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2570016068815075, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1135893825671224, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.134718013414486, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.21828501541926934, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.3290834} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.7399964332580566, "x": 5.392743621505659, "y": -0.16283847281764618, "z": null, "yaw": 6.25010208648468, "pitch": null, "roll": null}, "v": 2.134718013414486, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3523061106386872, "steering_wheel_angle": 0.21828501541926934, "front_wheel_angle": 0.010053398502594419, "heading_rate": 0.008383552320889883, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.3490834} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25679437147634154, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1135893825671224, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.134797055411021, "gear": 1, "accelerator_pedal_position": 0.2570016068815075, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2592697901959386, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.3490834} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.7399964332580566, "x": 5.392743621505659, "y": -0.16283847281764618, "z": null, "yaw": 6.25010208648468, "pitch": null, "roll": null}, "v": 2.134718013414486, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3523061106386872, "steering_wheel_angle": 0.21828501541926934, "front_wheel_angle": 0.010053398502594419, "heading_rate": 0.008383552320889883, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.3690834} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25679437147634154, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1135893825671224, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.134850058519268, "gear": 1, "accelerator_pedal_position": 0.25679437147634154, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2592697901959386, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.3690834} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.7399964332580566, "x": 5.392743621505659, "y": -0.16283847281764618, "z": null, "yaw": 6.25010208648468, "pitch": null, "roll": null}, "v": 2.134718013414486, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3523061106386872, "steering_wheel_angle": 0.21828501541926934, "front_wheel_angle": 0.010053398502594419, "heading_rate": 0.008383552320889883, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.3890834} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25679437147634154, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1135893825671224, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1349029634087557, "gear": 1, "accelerator_pedal_position": 0.25679437147634154, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2592697901959386, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.3890834} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.7399964332580566, "x": 5.392743621505659, "y": -0.16283847281764618, "z": null, "yaw": 6.25010208648468, "pitch": null, "roll": null}, "v": 2.134718013414486, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3523061106386872, "steering_wheel_angle": 0.21828501541926934, "front_wheel_angle": 0.010053398502594419, "heading_rate": 0.008383552320889883, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.4090834} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25679437147634154, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1135893825671224, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.134955770260373, "gear": 1, "accelerator_pedal_position": 0.25679437147634154, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2592697901959386, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.4090834} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.7399964332580566, "x": 5.392743621505659, "y": -0.16283847281764618, "z": null, "yaw": 6.25010208648468, "pitch": null, "roll": null}, "v": 2.134718013414486, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3523061106386872, "steering_wheel_angle": 0.21828501541926934, "front_wheel_angle": 0.010053398502594419, "heading_rate": 0.008383552320889883, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.4290833} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25679437147634154, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1135893825671224, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1350084792546777, "gear": 1, "accelerator_pedal_position": 0.25679437147634154, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2592697901959386, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.4290833} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25679437147634154, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1135893825671224, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1350347971116728, "gear": 1, "accelerator_pedal_position": 0.25679437147634154, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2592697901959386, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.4390833} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502642.4390833, "x": 9.627452886215226, "y": 4.829447006871201, "z": null, "yaw": -0.03257722770093844, "pitch": null, "roll": null}, "v": 2.1350347971116728, "accelerator_pedal_position": 0.25679437147634154, "brake_pedal_position": 0.0, "acceleration": 0.002629346022774093, "steering_wheel_angle": 0.2592697901959386, "front_wheel_angle": 0.01194747842136914, "heading_rate": 0.009964646851478005, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.4690833} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2515867373724662, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0577428377234444, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.135113604391944, "gear": 1, "accelerator_pedal_position": 0.25679437147634154, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2592697901959386, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.4690833} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.849996328353882, "x": 5.6274528862152255, "y": -0.17055299312879857, "z": null, "yaw": 6.250608079478647, "pitch": null, "roll": null}, "v": 2.1350347971116728, "accelerator_pedal_position": 0.25679437147634154, "brake_pedal_position": 0.0, "acceleration": 0.002629346022774093, "steering_wheel_angle": 0.2592697901959386, "front_wheel_angle": 0.01194747842136914, "heading_rate": 0.009964646851478005, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.4890833} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25321559235117147, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0577428377234444, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1343184695992115, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2592697901959386, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.4890833} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.849996328353882, "x": 5.6274528862152255, "y": -0.17055299312879857, "z": null, "yaw": 6.250608079478647, "pitch": null, "roll": null}, "v": 2.1350347971116728, "accelerator_pedal_position": 0.25679437147634154, "brake_pedal_position": 0.0, "acceleration": 0.002629346022774093, "steering_wheel_angle": 0.2592697901959386, "front_wheel_angle": 0.01194747842136914, "heading_rate": 0.009964646851478005, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.5090833} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25321559235117147, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0577428377234444, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.134121753353393, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2592697901959386, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.5090833} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.849996328353882, "x": 5.6274528862152255, "y": -0.17055299312879857, "z": null, "yaw": 6.250608079478647, "pitch": null, "roll": null}, "v": 2.1350347971116728, "accelerator_pedal_position": 0.25679437147634154, "brake_pedal_position": 0.0, "acceleration": 0.002629346022774093, "steering_wheel_angle": 0.2592697901959386, "front_wheel_angle": 0.01194747842136914, "heading_rate": 0.009964646851478005, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.5290833} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25321559235117147, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0577428377234444, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1337288676608694, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2592697901959386, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.5290833} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502642.5490832, "x": 9.862122618578281, "y": 4.821854223530829, "z": null, "yaw": -0.032063835059682466, "pitch": null, "roll": null}, "v": 2.1333367098566516, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35217809066905265, "steering_wheel_angle": 0.2592697901959386, "front_wheel_angle": 0.01194747842136914, "heading_rate": 0.009956721528742201, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.5490832} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25466357082110647, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.131896160429709, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1333367098566516, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2592697901959386, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.5490832} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.959996223449707, "x": 5.862122618578281, "y": -0.1781457764691714, "z": null, "yaw": 6.2511214721199035, "pitch": null, "roll": null}, "v": 2.1333367098566516, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35217809066905265, "steering_wheel_angle": 0.2592697901959386, "front_wheel_angle": 0.01194747842136914, "heading_rate": 0.009956721528742201, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.5690832} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.254203207995649, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.131896160429709, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1331261919800344, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3002308808762563, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.5690832} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.959996223449707, "x": 5.862122618578281, "y": -0.1781457764691714, "z": null, "yaw": 6.2511214721199035, "pitch": null, "roll": null}, "v": 2.1333367098566516, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35217809066905265, "steering_wheel_angle": 0.2592697901959386, "front_wheel_angle": 0.01194747842136914, "heading_rate": 0.009956721528742201, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.5890832} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.254203207995649, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.131896160429709, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1328585453770628, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3002308808762563, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.5890832} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.959996223449707, "x": 5.862122618578281, "y": -0.1781457764691714, "z": null, "yaw": 6.2511214721199035, "pitch": null, "roll": null}, "v": 2.1333367098566516, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35217809066905265, "steering_wheel_angle": 0.2592697901959386, "front_wheel_angle": 0.01194747842136914, "heading_rate": 0.009956721528742201, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.6090832} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.254203207995649, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.131896160429709, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1325913945390083, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3002308808762563, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.6090832} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.959996223449707, "x": 5.862122618578281, "y": -0.1781457764691714, "z": null, "yaw": 6.2511214721199035, "pitch": null, "roll": null}, "v": 2.1333367098566516, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35217809066905265, "steering_wheel_angle": 0.2592697901959386, "front_wheel_angle": 0.01194747842136914, "heading_rate": 0.009956721528742201, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.6290832} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.254203207995649, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.131896160429709, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1323247385190247, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3002308808762563, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.6290832} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 3.959996223449707, "x": 5.862122618578281, "y": -0.1781457764691714, "z": null, "yaw": 6.2511214721199035, "pitch": null, "roll": null}, "v": 2.1333367098566516, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35217809066905265, "steering_wheel_angle": 0.2592697901959386, "front_wheel_angle": 0.01194747842136914, "heading_rate": 0.009956721528742201, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.6490831} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.254203207995649, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.131896160429709, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1320585763721787, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3002308808762563, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.6490831} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502642.6590831, "x": 10.096602949372915, "y": 4.814395183066751, "z": null, "yaw": -0.03147640483522101, "pitch": null, "roll": null}, "v": 2.1319256802064124, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35204735506955637, "steering_wheel_angle": 0.3002308808762563, "front_wheel_angle": 0.013842524838651653, "heading_rate": 0.011528562212293847, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.669083} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2515765347012109, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0952570979006788, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.131792907155445, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3002308808762563, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.669083} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.069996118545532, "x": 6.096602949372915, "y": -0.1856048169332487, "z": null, "yaw": 6.251708902344365, "pitch": null, "roll": null}, "v": 2.1319256802064124, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35204735506955637, "steering_wheel_angle": 0.3002308808762563, "front_wheel_angle": 0.013842524838651653, "heading_rate": 0.011528562212293847, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.689083} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2523908338596441, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0952570979006788, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.131199547836431, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3002308808762563, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.689083} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.069996118545532, "x": 6.096602949372915, "y": -0.1856048169332487, "z": null, "yaw": 6.251708902344365, "pitch": null, "roll": null}, "v": 2.1319256802064124, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35204735506955637, "steering_wheel_angle": 0.3002308808762563, "front_wheel_angle": 0.013842524838651653, "heading_rate": 0.011528562212293847, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.709083} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2523908338596441, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0952570979006788, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1307090274875042, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3002308808762563, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.709083} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.069996118545532, "x": 6.096602949372915, "y": -0.1856048169332487, "z": null, "yaw": 6.251708902344365, "pitch": null, "roll": null}, "v": 2.1319256802064124, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35204735506955637, "steering_wheel_angle": 0.3002308808762563, "front_wheel_angle": 0.013842524838651653, "heading_rate": 0.011528562212293847, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.729083} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2523908338596441, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0952570979006788, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1302194153246923, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3002308808762563, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.729083} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.069996118545532, "x": 6.096602949372915, "y": -0.1856048169332487, "z": null, "yaw": 6.251708902344365, "pitch": null, "roll": null}, "v": 2.1319256802064124, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35204735506955637, "steering_wheel_angle": 0.3002308808762563, "front_wheel_angle": 0.013842524838651653, "heading_rate": 0.011528562212293847, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.749083} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2523908338596441, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0952570979006788, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1297307095706675, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3002308808762563, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.749083} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502642.769083, "x": 10.330868366519734, "y": 4.807082301621625, "z": null, "yaw": -0.03088157085243903, "pitch": null, "roll": null}, "v": 2.1292429084519253, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35179889905452444, "steering_wheel_angle": 0.3002308808762563, "front_wheel_angle": 0.013842524838651653, "heading_rate": 0.011514054904951878, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.769083} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25412339704589015, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.166948328376467, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1292429084519253, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3002308808762563, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.769083} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.179996013641357, "x": 6.330868366519734, "y": -0.19291769837837514, "z": null, "yaw": 6.252303736327147, "pitch": null, "roll": null}, "v": 2.1292429084519253, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35179889905452444, "steering_wheel_angle": 0.3002308808762563, "front_wheel_angle": 0.013842524838651653, "heading_rate": 0.011514054904951878, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.789083} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25356954788630487, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.166948328376467, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.128972480345459, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3411873861498764, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.789083} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.179996013641357, "x": 6.330868366519734, "y": -0.19291769837837514, "z": null, "yaw": 6.252303736327147, "pitch": null, "roll": null}, "v": 2.1292429084519253, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35179889905452444, "steering_wheel_angle": 0.3002308808762563, "front_wheel_angle": 0.013842524838651653, "heading_rate": 0.011514054904951878, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.809083} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25356954788630487, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.166948328376467, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1286333536371282, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3411873861498764, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.809083} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.179996013641357, "x": 6.330868366519734, "y": -0.19291769837837514, "z": null, "yaw": 6.252303736327147, "pitch": null, "roll": null}, "v": 2.1292429084519253, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35179889905452444, "steering_wheel_angle": 0.3002308808762563, "front_wheel_angle": 0.013842524838651653, "heading_rate": 0.011514054904951878, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.829083} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25356954788630487, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.166948328376467, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1281258399437992, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3411873861498764, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.829083} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.179996013641357, "x": 6.330868366519734, "y": -0.19291769837837514, "z": null, "yaw": 6.252303736327147, "pitch": null, "roll": null}, "v": 2.1292429084519253, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35179889905452444, "steering_wheel_angle": 0.3002308808762563, "front_wheel_angle": 0.013842524838651653, "heading_rate": 0.011514054904951878, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.839083} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25356954788630487, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.166948328376467, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1279569818076576, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3411873861498764, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.839083} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.179996013641357, "x": 6.330868366519734, "y": -0.19291769837837514, "z": null, "yaw": 6.252303736327147, "pitch": null, "roll": null}, "v": 2.1292429084519253, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35179889905452444, "steering_wheel_angle": 0.3002308808762563, "front_wheel_angle": 0.013842524838651653, "heading_rate": 0.011514054904951878, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.869083} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25356954788630487, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.166948328376467, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1276197342744787, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3411873861498764, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.869083} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502642.879083, "x": 10.56488898159465, "y": 4.7999235042026145, "z": null, "yaw": -0.030212622934581546, "pitch": null, "roll": null}, "v": 2.127451344576868, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35163305946426265, "steering_wheel_angle": 0.3411873861498764, "front_wheel_angle": 0.015739425956103358, "heading_rate": 0.013081104785278729, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.889083} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2532404816634855, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1943453621147595, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1272831107251196, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3411873861498764, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.889083} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.289995908737183, "x": 6.564888981594651, "y": -0.2000764957973855, "z": null, "yaw": 6.252972684245004, "pitch": null, "roll": null}, "v": 2.127451344576868, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35163305946426265, "steering_wheel_angle": 0.3411873861498764, "front_wheel_angle": 0.015739425956103358, "heading_rate": 0.013081104785278729, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.909083} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25333502294058957, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1943453621147595, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1269059957147105, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3411873861498764, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.909083} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.289995908737183, "x": 6.564888981594651, "y": -0.2000764957973855, "z": null, "yaw": 6.252972684245004, "pitch": null, "roll": null}, "v": 2.127451344576868, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35163305946426265, "steering_wheel_angle": 0.3411873861498764, "front_wheel_angle": 0.015739425956103358, "heading_rate": 0.013081104785278729, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.9290829} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25333502294058957, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1943453621147595, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1263593409477504, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3411873861498764, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.9290829} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.289995908737183, "x": 6.564888981594651, "y": -0.2000764957973855, "z": null, "yaw": 6.252972684245004, "pitch": null, "roll": null}, "v": 2.127451344576868, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35163305946426265, "steering_wheel_angle": 0.3411873861498764, "front_wheel_angle": 0.015739425956103358, "heading_rate": 0.013081104785278729, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.9390829} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25333502294058957, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1943453621147595, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1263593409477504, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3411873861498764, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.9390829} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.289995908737183, "x": 6.564888981594651, "y": -0.2000764957973855, "z": null, "yaw": 6.252972684245004, "pitch": null, "roll": null}, "v": 2.127451344576868, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35163305946426265, "steering_wheel_angle": 0.3411873861498764, "front_wheel_angle": 0.015739425956103358, "heading_rate": 0.013081104785278729, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.9690828} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25333502294058957, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1943453621147595, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1258142022199102, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3411873861498764, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.9690828} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502642.9890828, "x": 10.79870417991751, "y": 4.792929119450943, "z": null, "yaw": -0.02953626362321651, "pitch": null, "roll": null}, "v": 2.1254516164805497, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3514480265640253, "steering_wheel_angle": 0.3411873861498764, "front_wheel_angle": 0.015739425956103358, "heading_rate": 0.01306880901511379, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502642.9890828} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25288953804901415, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2013157563996724, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1254516164805497, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3411873861498764, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502642.9890828} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.399995803833008, "x": 6.798704179917509, "y": -0.20707088054905665, "z": null, "yaw": 6.253649043556369, "pitch": null, "roll": null}, "v": 2.1254516164805497, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3514480265640253, "steering_wheel_angle": 0.3411873861498764, "front_wheel_angle": 0.015739425956103358, "heading_rate": 0.01306880901511379, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.0090828} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2530195005178296, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2013157563996724, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1250340414377273, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3821385081000015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.0090828} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.399995803833008, "x": 6.798704179917509, "y": -0.20707088054905665, "z": null, "yaw": 6.253649043556369, "pitch": null, "roll": null}, "v": 2.1254516164805497, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3514480265640253, "steering_wheel_angle": 0.3411873861498764, "front_wheel_angle": 0.015739425956103358, "heading_rate": 0.01306880901511379, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.0290828} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2530195005178296, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2013157563996724, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1246334763699792, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3821385081000015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.0290828} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.399995803833008, "x": 6.798704179917509, "y": -0.20707088054905665, "z": null, "yaw": 6.253649043556369, "pitch": null, "roll": null}, "v": 2.1254516164805497, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3514480265640253, "steering_wheel_angle": 0.3411873861498764, "front_wheel_angle": 0.015739425956103358, "heading_rate": 0.01306880901511379, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.0490828} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2530195005178296, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2013157563996724, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1242336519622387, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3821385081000015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.0490828} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.399995803833008, "x": 6.798704179917509, "y": -0.20707088054905665, "z": null, "yaw": 6.253649043556369, "pitch": null, "roll": null}, "v": 2.1254516164805497, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3514480265640253, "steering_wheel_angle": 0.3411873861498764, "front_wheel_angle": 0.015739425956103358, "heading_rate": 0.01306880901511379, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.0690827} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2530195005178296, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2013157563996724, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1238345667810825, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3821385081000015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.0690827} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.399995803833008, "x": 6.798704179917509, "y": -0.20707088054905665, "z": null, "yaw": 6.253649043556369, "pitch": null, "roll": null}, "v": 2.1254516164805497, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3514480265640253, "steering_wheel_angle": 0.3411873861498764, "front_wheel_angle": 0.015739425956103358, "heading_rate": 0.01306880901511379, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.0890827} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2530195005178296, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2013157563996724, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.123436219396093, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3821385081000015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.0890827} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502643.0990827, "x": 11.032292593177704, "y": 4.786106739397997, "z": null, "yaw": -0.02878571468773155, "pitch": null, "roll": null}, "v": 2.1232373219309753, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35124323334895496, "steering_wheel_angle": 0.3821385081000015, "front_wheel_angle": 0.017638150839687557, "heading_rate": 0.014630415724003863, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.1090827} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25270388739237304, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2150920898485726, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1230386083798503, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3821385081000015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.1090827} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.509995698928833, "x": 7.032292593177704, "y": -0.21389326060200275, "z": null, "yaw": 6.254399592491855, "pitch": null, "roll": null}, "v": 2.1232373219309753, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35124323334895496, "steering_wheel_angle": 0.3821385081000015, "front_wheel_angle": 0.017638150839687557, "heading_rate": 0.014630415724003863, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.1290827} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25279227689127737, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2150920898485726, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1226022989050652, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3821385081000015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.1290827} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.509995698928833, "x": 7.032292593177704, "y": -0.21389326060200275, "z": null, "yaw": 6.254399592491855, "pitch": null, "roll": null}, "v": 2.1232373219309753, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35124323334895496, "steering_wheel_angle": 0.3821385081000015, "front_wheel_angle": 0.017638150839687557, "heading_rate": 0.014630415724003863, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.1490827} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25279227689127737, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2150920898485726, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.122177839410682, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3821385081000015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.1490827} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.509995698928833, "x": 7.032292593177704, "y": -0.21389326060200275, "z": null, "yaw": 6.254399592491855, "pitch": null, "roll": null}, "v": 2.1232373219309753, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35124323334895496, "steering_wheel_angle": 0.3821385081000015, "front_wheel_angle": 0.017638150839687557, "heading_rate": 0.014630415724003863, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.1690826} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25279227689127737, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2150920898485726, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1217541643424793, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3821385081000015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.1690826} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.509995698928833, "x": 7.032292593177704, "y": -0.21389326060200275, "z": null, "yaw": 6.254399592491855, "pitch": null, "roll": null}, "v": 2.1232373219309753, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35124323334895496, "steering_wheel_angle": 0.3821385081000015, "front_wheel_angle": 0.017638150839687557, "heading_rate": 0.014630415724003863, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.1890826} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25279227689127737, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2150920898485726, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1213312721790243, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3821385081000015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.1890826} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502643.2090826, "x": 11.265637983431096, "y": 4.77946831411495, "z": null, "yaw": -0.028027746789834596, "pitch": null, "roll": null}, "v": 2.1209091614020936, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.351028014779298, "steering_wheel_angle": 0.3821385081000015, "front_wheel_angle": 0.017638150839687557, "heading_rate": 0.014614373260894377, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.2090826} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25324859477747996, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2328716954350258, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1209091614020936, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3821385081000015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.2090826} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.619995594024658, "x": 7.2656379834310965, "y": -0.22053168588505034, "z": null, "yaw": 6.255157560389752, "pitch": null, "roll": null}, "v": 2.1209091614020936, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.351028014779298, "steering_wheel_angle": 0.3821385081000015, "front_wheel_angle": 0.017638150839687557, "heading_rate": 0.014614373260894377, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.2290826} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2530952344090079, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2328716954350258, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1205448438760173, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3821385081000015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.2290826} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.619995594024658, "x": 7.2656379834310965, "y": -0.22053168588505034, "z": null, "yaw": 6.255157560389752, "pitch": null, "roll": null}, "v": 2.1209091614020936, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.351028014779298, "steering_wheel_angle": 0.3821385081000015, "front_wheel_angle": 0.017638150839687557, "heading_rate": 0.014614373260894377, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.2490826} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2530952344090079, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2328716954350258, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.120162038201464, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3821385081000015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.2490826} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.619995594024658, "x": 7.2656379834310965, "y": -0.22053168588505034, "z": null, "yaw": 6.255157560389752, "pitch": null, "roll": null}, "v": 2.1209091614020936, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.351028014779298, "steering_wheel_angle": 0.3821385081000015, "front_wheel_angle": 0.017638150839687557, "heading_rate": 0.014614373260894377, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.2690825} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2530952344090079, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2328716954350258, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1197799396644026, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3821385081000015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.2690825} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.619995594024658, "x": 7.2656379834310965, "y": -0.22053168588505034, "z": null, "yaw": 6.255157560389752, "pitch": null, "roll": null}, "v": 2.1209091614020936, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.351028014779298, "steering_wheel_angle": 0.3821385081000015, "front_wheel_angle": 0.017638150839687557, "heading_rate": 0.014614373260894377, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.2890825} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2530952344090079, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2328716954350258, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.119398546900202, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3821385081000015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.2890825} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.619995594024658, "x": 7.2656379834310965, "y": -0.22053168588505034, "z": null, "yaw": 6.255157560389752, "pitch": null, "roll": null}, "v": 2.1209091614020936, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.351028014779298, "steering_wheel_angle": 0.3821385081000015, "front_wheel_angle": 0.017638150839687557, "heading_rate": 0.014614373260894377, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.3090825} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2530952344090079, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2328716954350258, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1190178585470734, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3821385081000015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.3090825} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502643.3190825, "x": 11.498745235178198, "y": 4.773013492349493, "z": null, "yaw": -0.027269778891937643, "pitch": null, "roll": null}, "v": 2.1188277780998788, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35083570043747064, "steering_wheel_angle": 0.3821385081000015, "front_wheel_angle": 0.017638150839687557, "heading_rate": 0.014600031245200765, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.3290825} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2505153023462759, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.148705227759269, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.118637873246067, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3821385081000015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.3290825} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.729995489120483, "x": 7.498745235178198, "y": -0.22698650765050665, "z": null, "yaw": 6.255915528287648, "pitch": null, "roll": null}, "v": 2.1188277780998788, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35083570043747064, "steering_wheel_angle": 0.3821385081000015, "front_wheel_angle": 0.017638150839687557, "heading_rate": 0.014600031245200765, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.3490825} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25131191592108887, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.148705227759269, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.117936247071652, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3821385081000015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.3490825} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.729995489120483, "x": 7.498745235178198, "y": -0.22698650765050665, "z": null, "yaw": 6.255915528287648, "pitch": null, "roll": null}, "v": 2.1188277780998788, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35083570043747064, "steering_wheel_angle": 0.3821385081000015, "front_wheel_angle": 0.017638150839687557, "heading_rate": 0.014600031245200765, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.3690825} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25131191592108887, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.148705227759269, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.117335447090131, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3821385081000015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.3690825} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.729995489120483, "x": 7.498745235178198, "y": -0.22698650765050665, "z": null, "yaw": 6.255915528287648, "pitch": null, "roll": null}, "v": 2.1188277780998788, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35083570043747064, "steering_wheel_angle": 0.3821385081000015, "front_wheel_angle": 0.017638150839687557, "heading_rate": 0.014600031245200765, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.3890824} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25131191592108887, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.148705227759269, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1167357562703524, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3821385081000015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.3890824} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.729995489120483, "x": 7.498745235178198, "y": -0.22698650765050665, "z": null, "yaw": 6.255915528287648, "pitch": null, "roll": null}, "v": 2.1188277780998788, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35083570043747064, "steering_wheel_angle": 0.3821385081000015, "front_wheel_angle": 0.017638150839687557, "heading_rate": 0.014600031245200765, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.4090824} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25131191592108887, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.148705227759269, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.116137172420862, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3821385081000015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.4090824} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502643.4290824, "x": 11.731569238083926, "y": 4.76674310988472, "z": null, "yaw": -0.02651181099404069, "pitch": null, "roll": null}, "v": 2.1155396933550468, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35053206660936, "steering_wheel_angle": 0.3821385081000015, "front_wheel_angle": 0.017638150839687557, "heading_rate": 0.014577374311726697, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.4290824} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2535888401903464, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2221937543772068, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.11538367520085, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3821385081000015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.4290824} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.839995384216309, "x": 7.731569238083926, "y": -0.23325689011528006, "z": null, "yaw": 6.256673496185545, "pitch": null, "roll": null}, "v": 2.1155396933550468, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35053206660936, "steering_wheel_angle": 0.3821385081000015, "front_wheel_angle": 0.017638150839687557, "heading_rate": 0.014577374311726697, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.4390824} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25286211918832247, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2221937543772068, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.11538367520085, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3821385081000015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.4390824} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.839995384216309, "x": 7.731569238083926, "y": -0.23325689011528006, "z": null, "yaw": 6.256673496185545, "pitch": null, "roll": null}, "v": 2.1155396933550468, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35053206660936, "steering_wheel_angle": 0.3821385081000015, "front_wheel_angle": 0.017638150839687557, "heading_rate": 0.014577374311726697, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.4690824} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25286211918832247, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2221937543772068, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1147803498460815, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3821385081000015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.4690824} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.839995384216309, "x": 7.731569238083926, "y": -0.23325689011528006, "z": null, "yaw": 6.256673496185545, "pitch": null, "roll": null}, "v": 2.1155396933550468, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35053206660936, "steering_wheel_angle": 0.3821385081000015, "front_wheel_angle": 0.017638150839687557, "heading_rate": 0.014577374311726697, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.4890823} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25286211918832247, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2221937543772068, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1143790604768538, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3821385081000015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.4890823} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.839995384216309, "x": 7.731569238083926, "y": -0.23325689011528006, "z": null, "yaw": 6.256673496185545, "pitch": null, "roll": null}, "v": 2.1155396933550468, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35053206660936, "steering_wheel_angle": 0.3821385081000015, "front_wheel_angle": 0.017638150839687557, "heading_rate": 0.014577374311726697, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.5090823} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25286211918832247, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2221937543772068, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1139785114624488, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3821385081000015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.5090823} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.839995384216309, "x": 7.731569238083926, "y": -0.23325689011528006, "z": null, "yaw": 6.256673496185545, "pitch": null, "roll": null}, "v": 2.1155396933550468, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35053206660936, "steering_wheel_angle": 0.3821385081000015, "front_wheel_angle": 0.017638150839687557, "heading_rate": 0.014577374311726697, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.5290823} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25286211918832247, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2221937543772068, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.11357870137281, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3821385081000015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.5290823} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502643.5390823, "x": 11.964093006505637, "y": 4.760657191119084, "z": null, "yaw": -0.025753843096143737, "pitch": null, "roll": null}, "v": 2.113379072978704, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3503326647099785, "steering_wheel_angle": 0.3821385081000015, "front_wheel_angle": 0.017638150839687557, "heading_rate": 0.01456248630368297, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.5490823} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25243300322061557, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1950346124705062, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1131796287808746, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3821385081000015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.5490823} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.949995279312134, "x": 7.964093006505637, "y": -0.23934280888091575, "z": null, "yaw": 6.257431464083442, "pitch": null, "roll": null}, "v": 2.113379072978704, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3503326647099785, "steering_wheel_angle": 0.3821385081000015, "front_wheel_angle": 0.017638150839687557, "heading_rate": 0.01456248630368297, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.5690823} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25255713194694007, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1950346124705062, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.112727677510324, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3821385081000015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.5690823} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.949995279312134, "x": 7.964093006505637, "y": -0.23934280888091575, "z": null, "yaw": 6.257431464083442, "pitch": null, "roll": null}, "v": 2.113379072978704, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3503326647099785, "steering_wheel_angle": 0.3821385081000015, "front_wheel_angle": 0.017638150839687557, "heading_rate": 0.01456248630368297, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.5890822} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25255713194694007, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1950346124705062, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1122920687007767, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3821385081000015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.5890822} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.949995279312134, "x": 7.964093006505637, "y": -0.23934280888091575, "z": null, "yaw": 6.257431464083442, "pitch": null, "roll": null}, "v": 2.113379072978704, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3503326647099785, "steering_wheel_angle": 0.3821385081000015, "front_wheel_angle": 0.017638150839687557, "heading_rate": 0.01456248630368297, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.6090822} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25255713194694007, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1950346124705062, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.111857263201547, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3821385081000015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.6090822} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 4.949995279312134, "x": 7.964093006505637, "y": -0.23934280888091575, "z": null, "yaw": 6.257431464083442, "pitch": null, "roll": null}, "v": 2.113379072978704, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3503326647099785, "steering_wheel_angle": 0.3821385081000015, "front_wheel_angle": 0.017638150839687557, "heading_rate": 0.01456248630368297, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.6290822} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25255713194694007, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1950346124705062, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1114232594556546, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3821385081000015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.6290822} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502643.6490822, "x": 12.196370433155991, "y": 4.754753894408984, "z": null, "yaw": -0.024995875198246784, "pitch": null, "roll": null}, "v": 2.1109900559094092, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3501122929569546, "steering_wheel_angle": 0.3821385081000015, "front_wheel_angle": 0.017638150839687557, "heading_rate": 0.014546024501446122, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.6490822} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2544948686038667, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2703169854615255, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1109900559094092, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3821385081000015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.6490822} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.059995174407959, "x": 8.196370433155991, "y": -0.24524610559101578, "z": null, "yaw": 6.258189431981339, "pitch": null, "roll": null}, "v": 2.1109900559094092, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3501122929569546, "steering_wheel_angle": 0.3821385081000015, "front_wheel_angle": 0.017638150839687557, "heading_rate": 0.014546024501446122, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.6690822} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2538783069066766, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2703169854615255, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1107997564122343, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.6690822} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.059995174407959, "x": 8.196370433155991, "y": -0.24524610559101578, "z": null, "yaw": 6.258189431981339, "pitch": null, "roll": null}, "v": 2.1109900559094092, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3501122929569546, "steering_wheel_angle": 0.3821385081000015, "front_wheel_angle": 0.017638150839687557, "heading_rate": 0.014546024501446122, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.6890821} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2538783069066766, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2703169854615255, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1105327730525048, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.6890821} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.059995174407959, "x": 8.196370433155991, "y": -0.24524610559101578, "z": null, "yaw": 6.258189431981339, "pitch": null, "roll": null}, "v": 2.1109900559094092, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3501122929569546, "steering_wheel_angle": 0.3821385081000015, "front_wheel_angle": 0.017638150839687557, "heading_rate": 0.014546024501446122, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.7090821} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2538783069066766, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2703169854615255, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.110266281847101, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.7090821} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.059995174407959, "x": 8.196370433155991, "y": -0.24524610559101578, "z": null, "yaw": 6.258189431981339, "pitch": null, "roll": null}, "v": 2.1109900559094092, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3501122929569546, "steering_wheel_angle": 0.3821385081000015, "front_wheel_angle": 0.017638150839687557, "heading_rate": 0.014546024501446122, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.729082} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2538783069066766, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2703169854615255, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.110000281860397, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.729082} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.059995174407959, "x": 8.196370433155991, "y": -0.24524610559101578, "z": null, "yaw": 6.258189431981339, "pitch": null, "roll": null}, "v": 2.1109900559094092, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3501122929569546, "steering_wheel_angle": 0.3821385081000015, "front_wheel_angle": 0.017638150839687557, "heading_rate": 0.014546024501446122, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.749082} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2538783069066766, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2703169854615255, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1097347721586486, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.749082} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502643.759082, "x": 12.428442919754117, "y": 4.749038887642488, "z": null, "yaw": -0.024163568994927845, "pitch": null, "roll": null}, "v": 2.109602200873351, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34998432450296446, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016104703850863364, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.769082} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25260805876863096, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2222551159996506, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1094697518099887, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.769082} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.169995069503784, "x": 8.428442919754117, "y": -0.25096111235751195, "z": null, "yaw": 6.259021738184658, "pitch": null, "roll": null}, "v": 2.109602200873351, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34998432450296446, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016104703850863364, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.789082} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2529986131451381, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2222551159996506, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1090465120540665, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.789082} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.169995069503784, "x": 8.428442919754117, "y": -0.25096111235751195, "z": null, "yaw": 6.259021738184658, "pitch": null, "roll": null}, "v": 2.109602200873351, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34998432450296446, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016104703850863364, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.809082} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2529986131451381, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2222551159996506, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.108672849046091, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.809082} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.169995069503784, "x": 8.428442919754117, "y": -0.25096111235751195, "z": null, "yaw": 6.259021738184658, "pitch": null, "roll": null}, "v": 2.109602200873351, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34998432450296446, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016104703850863364, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.829082} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2529986131451381, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2222551159996506, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1082998745708337, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.829082} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.169995069503784, "x": 8.428442919754117, "y": -0.25096111235751195, "z": null, "yaw": 6.259021738184658, "pitch": null, "roll": null}, "v": 2.109602200873351, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34998432450296446, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016104703850863364, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.849082} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2529986131451381, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2222551159996506, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.107927587303946, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.849082} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502643.869082, "x": 12.660332101796328, "y": 4.743523073727132, "z": null, "yaw": -0.023323828961066707, "pitch": null, "roll": null}, "v": 2.1075559859238275, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34979572163422495, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016089083045308816, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.869082} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25243057350229997, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1689258842677388, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1075559859238275, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.869082} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.279994964599609, "x": 8.660332101796328, "y": -0.25647692627286833, "z": null, "yaw": 6.25986147821852, "pitch": null, "roll": null}, "v": 2.1075559859238275, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34979572163422495, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016089083045308816, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.889082} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2525986558574533, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1689258842677388, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.106893457684487, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.889082} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.279994964599609, "x": 8.660332101796328, "y": -0.25647692627286833, "z": null, "yaw": 6.25986147821852, "pitch": null, "roll": null}, "v": 2.1075559859238275, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34979572163422495, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016089083045308816, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.909082} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2525986558574533, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1689258842677388, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.106683526942532, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.909082} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.279994964599609, "x": 8.660332101796328, "y": -0.25647692627286833, "z": null, "yaw": 6.25986147821852, "pitch": null, "roll": null}, "v": 2.1075559859238275, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34979572163422495, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016089083045308816, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.929082} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2525986558574533, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1689258842677388, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1062642455355265, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.929082} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.279994964599609, "x": 8.660332101796328, "y": -0.25647692627286833, "z": null, "yaw": 6.25986147821852, "pitch": null, "roll": null}, "v": 2.1075559859238275, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34979572163422495, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016089083045308816, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.949082} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2525986558574533, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1689258842677388, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1058457363186265, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.949082} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.279994964599609, "x": 8.660332101796328, "y": -0.25647692627286833, "z": null, "yaw": 6.25986147821852, "pitch": null, "roll": null}, "v": 2.1075559859238275, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34979572163422495, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016089083045308816, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.9690819} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2525986558574533, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1689258842677388, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.105427997799663, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.9690819} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502643.9790819, "x": 12.891983971707562, "y": 4.738207536213969, "z": null, "yaw": -0.02248408892720557, "pitch": null, "roll": null}, "v": 2.105219417086462, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3495804587951018, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016071245678085107, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502643.9890819} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25474076460660716, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.237528335222172, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.105011028489602, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502643.9890819} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.389994859695435, "x": 8.891983971707562, "y": -0.2617924637860307, "z": null, "yaw": 6.260701218252381, "pitch": null, "roll": null}, "v": 2.105219417086462, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3495804587951018, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016071245678085107, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.0090818} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25406059203458453, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.237528335222172, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1048624671945317, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.0090818} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.389994859695435, "x": 8.891983971707562, "y": -0.2617924637860307, "z": null, "yaw": 6.260701218252381, "pitch": null, "roll": null}, "v": 2.105219417086462, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3495804587951018, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016071245678085107, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.0290818} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25406059203458453, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.237528335222172, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.104512722994321, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.0290818} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.389994859695435, "x": 8.891983971707562, "y": -0.2617924637860307, "z": null, "yaw": 6.260701218252381, "pitch": null, "roll": null}, "v": 2.105219417086462, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3495804587951018, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016071245678085107, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.0490818} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25406059203458453, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.237528335222172, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.104396356254861, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.0490818} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.389994859695435, "x": 8.891983971707562, "y": -0.2617924637860307, "z": null, "yaw": 6.260701218252381, "pitch": null, "roll": null}, "v": 2.105219417086462, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3495804587951018, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016071245678085107, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.0690818} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25406059203458453, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.237528335222172, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1041639441577695, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.0690818} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502644.0890818, "x": 13.123435475612741, "y": 4.733091062421746, "z": null, "yaw": -0.02164434889334443, "pitch": null, "roll": null}, "v": 2.1039319598943664, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3494618949133678, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016061417229484332, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.0890818} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.253562120474135, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2168565299008323, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.103784973474866, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.0890818} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.49999475479126, "x": 9.123435475612741, "y": -0.26690893757825407, "z": null, "yaw": 6.261540958286242, "pitch": null, "roll": null}, "v": 2.1039319598943664, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3494618949133678, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016061417229484332, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.1090817} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2537119647409344, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2168565299008323, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1036381223963003, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.1090817} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.49999475479126, "x": 9.123435475612741, "y": -0.26690893757825407, "z": null, "yaw": 6.261540958286242, "pitch": null, "roll": null}, "v": 2.1039319598943664, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3494618949133678, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016061417229484332, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.1290817} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2537119647409344, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2168565299008323, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.103363547657126, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.1290817} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.49999475479126, "x": 9.123435475612741, "y": -0.26690893757825407, "z": null, "yaw": 6.261540958286242, "pitch": null, "roll": null}, "v": 2.1039319598943664, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3494618949133678, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016061417229484332, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.1490817} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2537119647409344, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2168565299008323, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.103089478279686, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.1490817} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.49999475479126, "x": 9.123435475612741, "y": -0.26690893757825407, "z": null, "yaw": 6.261540958286242, "pitch": null, "roll": null}, "v": 2.1039319598943664, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3494618949133678, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016061417229484332, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.1690817} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2537119647409344, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2168565299008323, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1028159133038162, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.1690817} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.49999475479126, "x": 9.123435475612741, "y": -0.26690893757825407, "z": null, "yaw": 6.261540958286242, "pitch": null, "roll": null}, "v": 2.1039319598943664, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3494618949133678, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016061417229484332, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.1890817} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2537119647409344, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2168565299008323, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1025428517712874, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.1890817} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502644.1990817, "x": 13.354738432921286, "y": 4.728172195951682, "z": null, "yaw": -0.020804608859483292, "pitch": null, "roll": null}, "v": 2.1024065094973565, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3493214567866364, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01604977194068398, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.2090816} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25390723699865614, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1873271797318827, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1022702927257986, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.2090816} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.609994649887085, "x": 9.354738432921286, "y": -0.27182780404831774, "z": null, "yaw": 6.262380698320103, "pitch": null, "roll": null}, "v": 2.1024065094973565, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3493214567866364, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01604977194068398, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.2290816} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.253839192467168, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1873271797318827, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.102022633011809, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.2290816} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.609994649887085, "x": 9.354738432921286, "y": -0.27182780404831774, "z": null, "yaw": 6.262380698320103, "pitch": null, "roll": null}, "v": 2.1024065094973565, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3493214567866364, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01604977194068398, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.2490816} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.253839192467168, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1873271797318827, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1017669273361284, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.2490816} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.609994649887085, "x": 9.354738432921286, "y": -0.27182780404831774, "z": null, "yaw": 6.262380698320103, "pitch": null, "roll": null}, "v": 2.1024065094973565, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3493214567866364, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01604977194068398, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.2690816} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.253839192467168, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1873271797318827, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.101511692129556, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.2690816} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.609994649887085, "x": 9.354738432921286, "y": -0.27182780404831774, "z": null, "yaw": 6.262380698320103, "pitch": null, "roll": null}, "v": 2.1024065094973565, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3493214567866364, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01604977194068398, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.2890816} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.253839192467168, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1873271797318827, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.101256926500437, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.2890816} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502644.3090816, "x": 13.585884505922996, "y": 4.723450853649149, "z": null, "yaw": -0.019964868825622154, "pitch": null, "roll": null}, "v": 2.1010026295589004, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34919225197207915, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01603905472080165, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.3090816} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25583138615915735, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.255843596491743, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1010026295589004, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.3090816} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.71999454498291, "x": 9.585884505922996, "y": -0.2765491463508507, "z": null, "yaw": 6.263220438353964, "pitch": null, "roll": null}, "v": 2.1010026295589004, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34919225197207915, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01603905472080165, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.3290815} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2552023649772644, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.255843596491743, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1009559398721476, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.3290815} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.71999454498291, "x": 9.585884505922996, "y": -0.2765491463508507, "z": null, "yaw": 6.263220438353964, "pitch": null, "roll": null}, "v": 2.1010026295589004, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34919225197207915, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01603905472080165, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.3490815} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2552023649772644, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.255843596491743, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.100914208127162, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.3490815} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.71999454498291, "x": 9.585884505922996, "y": -0.2765491463508507, "z": null, "yaw": 6.263220438353964, "pitch": null, "roll": null}, "v": 2.1010026295589004, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34919225197207915, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01603905472080165, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.3690815} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2552023649772644, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.255843596491743, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.100830859804537, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.3690815} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.71999454498291, "x": 9.585884505922996, "y": -0.2765491463508507, "z": null, "yaw": 6.263220438353964, "pitch": null, "roll": null}, "v": 2.1010026295589004, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34919225197207915, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01603905472080165, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.3890815} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2552023649772644, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.255843596491743, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1007476648006485, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.3890815} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.71999454498291, "x": 9.585884505922996, "y": -0.2765491463508507, "z": null, "yaw": 6.263220438353964, "pitch": null, "roll": null}, "v": 2.1010026295589004, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34919225197207915, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01603905472080165, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.4090815} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2552023649772644, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.255843596491743, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1006646228307004, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.4090815} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502644.4190814, "x": 13.816935004920976, "y": 4.718925571147037, "z": null, "yaw": -0.019125128791761016, "pitch": null, "roll": null}, "v": 2.100623159144603, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3491573345245767, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016036157843542093, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.4290814} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25406665563568187, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1957863488103657, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1005817336104364, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.4290814} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.829994440078735, "x": 9.816935004920976, "y": -0.2810744288529632, "z": null, "yaw": 6.264060178387825, "pitch": null, "roll": null}, "v": 2.100623159144603, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3491573345245767, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016036157843542093, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.4490814} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25441981916410333, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1957863488103657, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.100357098498893, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.4490814} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.829994440078735, "x": 9.816935004920976, "y": -0.2810744288529632, "z": null, "yaw": 6.264060178387825, "pitch": null, "roll": null}, "v": 2.100623159144603, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3491573345245767, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016036157843542093, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.4690814} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25441981916410333, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1957863488103657, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1001770016959442, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.4690814} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.829994440078735, "x": 9.816935004920976, "y": -0.2810744288529632, "z": null, "yaw": 6.264060178387825, "pitch": null, "roll": null}, "v": 2.100623159144603, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3491573345245767, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016036157843542093, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.4890814} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25441981916410333, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1957863488103657, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0999972361346604, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.4890814} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.829994440078735, "x": 9.816935004920976, "y": -0.2810744288529632, "z": null, "yaw": 6.264060178387825, "pitch": null, "roll": null}, "v": 2.100623159144603, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3491573345245767, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016036157843542093, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.5090814} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25441981916410333, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1957863488103657, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0998178011928874, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.5090814} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502644.5290813, "x": 14.047914550342588, "y": 4.714595707703617, "z": null, "yaw": -0.018285388757899878, "pitch": null, "roll": null}, "v": 2.0996386962496865, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3490667613603752, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016028642453499255, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.5290813} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2562437743147492, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2658300597120653, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0996632645307547, "gear": 1, "accelerator_pedal_position": 0.2562437743147492, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.5290813} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.9399943351745605, "x": 10.047914550342588, "y": -0.2854042922963833, "z": null, "yaw": 6.264899918421686, "pitch": null, "roll": null}, "v": 2.0996386962496865, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3490667613603752, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016028642453499255, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.5490813} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2556692592952809, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2658300597120653, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0996878102107193, "gear": 1, "accelerator_pedal_position": 0.2562437743147492, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.5490813} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.9399943351745605, "x": 10.047914550342588, "y": -0.2854042922963833, "z": null, "yaw": 6.264899918421686, "pitch": null, "roll": null}, "v": 2.0996386962496865, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3490667613603752, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016028642453499255, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.5690813} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2556692592952809, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2658300597120653, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0996650525049874, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.5690813} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.9399943351745605, "x": 10.047914550342588, "y": -0.2854042922963833, "z": null, "yaw": 6.264899918421686, "pitch": null, "roll": null}, "v": 2.0996386962496865, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3490667613603752, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016028642453499255, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.5890813} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2556692592952809, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2658300597120653, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.099642336651178, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.5890813} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.9399943351745605, "x": 10.047914550342588, "y": -0.2854042922963833, "z": null, "yaw": 6.264899918421686, "pitch": null, "roll": null}, "v": 2.0996386962496865, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3490667613603752, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016028642453499255, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.6090813} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2556692592952809, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2658300597120653, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0996196625721173, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.6090813} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 5.9399943351745605, "x": 10.047914550342588, "y": -0.2854042922963833, "z": null, "yaw": 6.264899918421686, "pitch": null, "roll": null}, "v": 2.0996386962496865, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3490667613603752, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016028642453499255, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.6290812} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2556692592952809, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2658300597120653, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.099597030190776, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.6290812} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502644.6390812, "x": 14.278838361300004, "y": 4.710460877294299, "z": null, "yaw": -0.01744564872403874, "pitch": null, "roll": null}, "v": 2.0995857296127167, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3490618888405695, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01602823810617632, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.6490812} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2532075678172948, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1136629252580543, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.099574439430266, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.6490812} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.049994230270386, "x": 10.278838361300004, "y": -0.28953912270570115, "z": null, "yaw": 6.265739658455548, "pitch": null, "roll": null}, "v": 2.0995857296127167, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3490618888405695, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01602823810617632, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.6690812} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25397660328239413, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1136629252580543, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0992443203105466, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.6690812} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.049994230270386, "x": 10.278838361300004, "y": -0.28953912270570115, "z": null, "yaw": 6.265739658455548, "pitch": null, "roll": null}, "v": 2.0995857296127167, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3490618888405695, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01602823810617632, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.6890812} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25397660328239413, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1136629252580543, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0990108934640097, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.6890812} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.049994230270386, "x": 10.278838361300004, "y": -0.28953912270570115, "z": null, "yaw": 6.265739658455548, "pitch": null, "roll": null}, "v": 2.0995857296127167, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3490618888405695, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01602823810617632, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.7090812} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25397660328239413, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1136629252580543, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0987778958384755, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.7090812} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.049994230270386, "x": 10.278838361300004, "y": -0.28953912270570115, "z": null, "yaw": 6.265739658455548, "pitch": null, "roll": null}, "v": 2.0995857296127167, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3490618888405695, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01602823810617632, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.7290812} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25397660328239413, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1136629252580543, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.098545326622995, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.7290812} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502644.7490811, "x": 14.509697345387606, "y": 4.70652111887258, "z": null, "yaw": -0.0166059086901776, "pitch": null, "roll": null}, "v": 2.09831318500823, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34894484147420535, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016018523500273947, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.7490811} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25604962148469773, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1792737637433677, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.09831318500823, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.7490811} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.159994125366211, "x": 10.509697345387606, "y": -0.29347888112742027, "z": null, "yaw": 6.266579398489409, "pitch": null, "roll": null}, "v": 2.09831318500823, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34894484147420535, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016018523500273947, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.769081} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2553959504995795, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1792737637433677, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.098340478308227, "gear": 1, "accelerator_pedal_position": 0.25604962148469773, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.769081} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.159994125366211, "x": 10.509697345387606, "y": -0.29347888112742027, "z": null, "yaw": 6.266579398489409, "pitch": null, "roll": null}, "v": 2.09831318500823, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34894484147420535, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016018523500273947, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.789081} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2553959504995795, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1792737637433677, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.098286050129155, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.789081} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.159994125366211, "x": 10.509697345387606, "y": -0.29347888112742027, "z": null, "yaw": 6.266579398489409, "pitch": null, "roll": null}, "v": 2.09831318500823, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34894484147420535, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016018523500273947, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.809081} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2553959504995795, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1792737637433677, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.098231722014879, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.809081} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.159994125366211, "x": 10.509697345387606, "y": -0.29347888112742027, "z": null, "yaw": 6.266579398489409, "pitch": null, "roll": null}, "v": 2.09831318500823, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34894484147420535, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016018523500273947, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.829081} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2553959504995795, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1792737637433677, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.098177493780254, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.829081} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.159994125366211, "x": 10.509697345387606, "y": -0.29347888112742027, "z": null, "yaw": 6.266579398489409, "pitch": null, "roll": null}, "v": 2.09831318500823, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34894484147420535, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016018523500273947, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.849081} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2553959504995795, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1792737637433677, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0981233652404803, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.849081} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502644.859081, "x": 14.740474224886462, "y": 4.702776616223692, "z": null, "yaw": -0.015766168656316464, "pitch": null, "roll": null}, "v": 2.098096338298507, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3489248993627414, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01601686809242517, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.869081} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2571616067168739, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2523231330276907, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.098069336211103, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.869081} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.269994020462036, "x": 10.740474224886462, "y": -0.2972233837763083, "z": null, "yaw": 6.26741913852327, "pitch": null, "roll": null}, "v": 2.098096338298507, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3489248993627414, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01601686809242517, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.889081} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2566088416809752, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2523231330276907, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.098236012051933, "gear": 1, "accelerator_pedal_position": 0.2571616067168739, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.889081} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.269994020462036, "x": 10.740474224886462, "y": -0.2972233837763083, "z": null, "yaw": 6.26741913852327, "pitch": null, "roll": null}, "v": 2.098096338298507, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3489248993627414, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01601686809242517, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.909081} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2566088416809752, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2523231330276907, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0983333176133345, "gear": 1, "accelerator_pedal_position": 0.2566088416809752, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.909081} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.269994020462036, "x": 10.740474224886462, "y": -0.2972233837763083, "z": null, "yaw": 6.26741913852327, "pitch": null, "roll": null}, "v": 2.098096338298507, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3489248993627414, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01601686809242517, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.929081} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2566088416809752, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2523231330276907, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0984304442806203, "gear": 1, "accelerator_pedal_position": 0.2566088416809752, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.929081} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.269994020462036, "x": 10.740474224886462, "y": -0.2972233837763083, "z": null, "yaw": 6.26741913852327, "pitch": null, "roll": null}, "v": 2.098096338298507, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3489248993627414, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01601686809242517, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.949081} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2566088416809752, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2523231330276907, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0985273923789114, "gear": 1, "accelerator_pedal_position": 0.2566088416809752, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.949081} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502644.969081, "x": 14.971262572664498, "y": 4.699225784328202, "z": null, "yaw": -0.014926428622455308, "pitch": null, "roll": null}, "v": 2.0986241622327517, "accelerator_pedal_position": 0.2566088416809752, "brake_pedal_position": 0.0, "acceleration": 0.0048318186513860995, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016020897500501674, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.969081} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25655252886272134, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2279626041404486, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0986241622327517, "gear": 1, "accelerator_pedal_position": 0.2566088416809752, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.969081} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.379993915557861, "x": 10.971262572664498, "y": -0.3007742156717983, "z": null, "yaw": 6.2682588785571305, "pitch": null, "roll": null}, "v": 2.0986241622327517, "accelerator_pedal_position": 0.2566088416809752, "brake_pedal_position": 0.0, "acceleration": 0.0048318186513860995, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016020897500501674, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502644.989081} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2565725537561534, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2279626041404486, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0987137183008793, "gear": 1, "accelerator_pedal_position": 0.25655252886272134, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502644.989081} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.379993915557861, "x": 10.971262572664498, "y": -0.3007742156717983, "z": null, "yaw": 6.2682588785571305, "pitch": null, "roll": null}, "v": 2.0986241622327517, "accelerator_pedal_position": 0.2566088416809752, "brake_pedal_position": 0.0, "acceleration": 0.0048318186513860995, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016020897500501674, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.009081} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2565725537561534, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2279626041404486, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0988056116690372, "gear": 1, "accelerator_pedal_position": 0.2565725537561534, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.009081} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.379993915557861, "x": 10.971262572664498, "y": -0.3007742156717983, "z": null, "yaw": 6.2682588785571305, "pitch": null, "roll": null}, "v": 2.0986241622327517, "accelerator_pedal_position": 0.2566088416809752, "brake_pedal_position": 0.0, "acceleration": 0.0048318186513860995, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016020897500501674, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.0290809} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2565725537561534, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2279626041404486, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0988973360758827, "gear": 1, "accelerator_pedal_position": 0.2565725537561534, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.0290809} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.379993915557861, "x": 10.971262572664498, "y": -0.3007742156717983, "z": null, "yaw": 6.2682588785571305, "pitch": null, "roll": null}, "v": 2.0986241622327517, "accelerator_pedal_position": 0.2566088416809752, "brake_pedal_position": 0.0, "acceleration": 0.0048318186513860995, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016020897500501674, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.0490808} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2565725537561534, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2279626041404486, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.098988891828715, "gear": 1, "accelerator_pedal_position": 0.2565725537561534, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.0490808} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.379993915557861, "x": 10.971262572664498, "y": -0.3007742156717983, "z": null, "yaw": 6.2682588785571305, "pitch": null, "roll": null}, "v": 2.0986241622327517, "accelerator_pedal_position": 0.2566088416809752, "brake_pedal_position": 0.0, "acceleration": 0.0048318186513860995, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016020897500501674, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.0690808} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2565725537561534, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2279626041404486, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0990802792342884, "gear": 1, "accelerator_pedal_position": 0.2565725537561534, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.0690808} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502645.0790808, "x": 15.202111824689917, "y": 4.695867911657978, "z": null, "yaw": -0.01408668858859415, "pitch": null, "roll": null}, "v": 2.099125909902564, "accelerator_pedal_position": 0.2565725537561534, "brake_pedal_position": 0.0, "acceleration": 0.004558869624587847, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01602472784236747, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.0890808} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25380877012667535, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0401400900379085, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.09917149859881, "gear": 1, "accelerator_pedal_position": 0.2565725537561534, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.0890808} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.4899938106536865, "x": 11.202111824689917, "y": -0.30413208834202177, "z": null, "yaw": 6.269098618590992, "pitch": null, "roll": null}, "v": 2.099125909902564, "accelerator_pedal_position": 0.2565725537561534, "brake_pedal_position": 0.0, "acceleration": 0.004558869624587847, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01602472784236747, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.1090808} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2546747605535079, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0401400900379085, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0989172361617836, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.1090808} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.4899938106536865, "x": 11.202111824689917, "y": -0.30413208834202177, "z": null, "yaw": 6.269098618590992, "pitch": null, "roll": null}, "v": 2.099125909902564, "accelerator_pedal_position": 0.2565725537561534, "brake_pedal_position": 0.0, "acceleration": 0.004558869624587847, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01602472784236747, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.1290808} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2546747605535079, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0401400900379085, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.098771640270581, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.1290808} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.4899938106536865, "x": 11.202111824689917, "y": -0.30413208834202177, "z": null, "yaw": 6.269098618590992, "pitch": null, "roll": null}, "v": 2.099125909902564, "accelerator_pedal_position": 0.2565725537561534, "brake_pedal_position": 0.0, "acceleration": 0.004558869624587847, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01602472784236747, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.1490808} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2546747605535079, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0401400900379085, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.098553748222009, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.1490808} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.4899938106536865, "x": 11.202111824689917, "y": -0.30413208834202177, "z": null, "yaw": 6.269098618590992, "pitch": null, "roll": null}, "v": 2.099125909902564, "accelerator_pedal_position": 0.2565725537561534, "brake_pedal_position": 0.0, "acceleration": 0.004558869624587847, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01602472784236747, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.1690807} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2546747605535079, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0401400900379085, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.098481251099075, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.1690807} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502645.1890807, "x": 15.432956577504482, "y": 4.692703982342059, "z": null, "yaw": -0.013246948554732994, "pitch": null, "roll": null}, "v": 2.0983364568184073, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34894698170105265, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016018701157280005, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.1890807} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2567337463148242, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0991627643194117, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0983364568184073, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.1890807} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.599993705749512, "x": 11.432956577504482, "y": -0.3072960176579409, "z": null, "yaw": 6.269938358624853, "pitch": null, "roll": null}, "v": 2.0983364568184073, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34894698170105265, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016018701157280005, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.2090807} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25608668235764875, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0991627643194117, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.098449183614001, "gear": 1, "accelerator_pedal_position": 0.2567337463148242, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.2090807} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.599993705749512, "x": 11.432956577504482, "y": -0.3072960176579409, "z": null, "yaw": 6.269938358624853, "pitch": null, "roll": null}, "v": 2.0983364568184073, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34894698170105265, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016018701157280005, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.2290807} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25608668235764875, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0991627643194117, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.098480857358115, "gear": 1, "accelerator_pedal_position": 0.25608668235764875, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.2290807} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.599993705749512, "x": 11.432956577504482, "y": -0.3072960176579409, "z": null, "yaw": 6.269938358624853, "pitch": null, "roll": null}, "v": 2.0983364568184073, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34894698170105265, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016018701157280005, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.2490807} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25608668235764875, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0991627643194117, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.098512472868678, "gear": 1, "accelerator_pedal_position": 0.25608668235764875, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.2490807} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.599993705749512, "x": 11.432956577504482, "y": -0.3072960176579409, "z": null, "yaw": 6.269938358624853, "pitch": null, "roll": null}, "v": 2.0983364568184073, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34894698170105265, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016018701157280005, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.2690806} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25608668235764875, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0991627643194117, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.098544030252355, "gear": 1, "accelerator_pedal_position": 0.25608668235764875, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.2690806} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.599993705749512, "x": 11.432956577504482, "y": -0.3072960176579409, "z": null, "yaw": 6.269938358624853, "pitch": null, "roll": null}, "v": 2.0983364568184073, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34894698170105265, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016018701157280005, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.2890806} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25608668235764875, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0991627643194117, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.098575529615617, "gear": 1, "accelerator_pedal_position": 0.25608668235764875, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.2890806} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502645.2990806, "x": 15.6637708791411, "y": 4.689734336903604, "z": null, "yaw": -0.012407208520871836, "pitch": null, "roll": null}, "v": 2.0985912575728123, "accelerator_pedal_position": 0.25608668235764875, "brake_pedal_position": 0.0, "acceleration": 0.0015713491930536283, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016020646306317565, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.3090806} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.257841451525215, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1647948084021835, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.098606971064743, "gear": 1, "accelerator_pedal_position": 0.25608668235764875, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.3090806} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.709993600845337, "x": 11.6637708791411, "y": -0.3102656630963958, "z": null, "yaw": 6.270778098658714, "pitch": null, "roll": null}, "v": 2.0985912575728123, "accelerator_pedal_position": 0.25608668235764875, "brake_pedal_position": 0.0, "acceleration": 0.0015713491930536283, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016020646306317565, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.3290806} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2572942574936421, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1647948084021835, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0988575999815438, "gear": 1, "accelerator_pedal_position": 0.257841451525215, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.3290806} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.709993600845337, "x": 11.6637708791411, "y": -0.3102656630963958, "z": null, "yaw": 6.270778098658714, "pitch": null, "roll": null}, "v": 2.0985912575728123, "accelerator_pedal_position": 0.25608668235764875, "brake_pedal_position": 0.0, "acceleration": 0.0015713491930536283, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016020646306317565, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.3490806} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2572942574936421, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1647948084021835, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0990394002766055, "gear": 1, "accelerator_pedal_position": 0.2572942574936421, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.3490806} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.709993600845337, "x": 11.6637708791411, "y": -0.3102656630963958, "z": null, "yaw": 6.270778098658714, "pitch": null, "roll": null}, "v": 2.0985912575728123, "accelerator_pedal_position": 0.25608668235764875, "brake_pedal_position": 0.0, "acceleration": 0.0015713491930536283, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016020646306317565, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.3590806} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2572942574936421, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1647948084021835, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0991301750294284, "gear": 1, "accelerator_pedal_position": 0.2572942574936421, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.3590806} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.709993600845337, "x": 11.6637708791411, "y": -0.3102656630963958, "z": null, "yaw": 6.270778098658714, "pitch": null, "roll": null}, "v": 2.0985912575728123, "accelerator_pedal_position": 0.25608668235764875, "brake_pedal_position": 0.0, "acceleration": 0.0015713491930536283, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016020646306317565, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.3790805} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2572942574936421, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1647948084021835, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0994924398303825, "gear": 1, "accelerator_pedal_position": 0.2572942574936421, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.3790805} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.709993600845337, "x": 11.6637708791411, "y": -0.3102656630963958, "z": null, "yaw": 6.270778098658714, "pitch": null, "roll": null}, "v": 2.0985912575728123, "accelerator_pedal_position": 0.25608668235764875, "brake_pedal_position": 0.0, "acceleration": 0.0015713491930536283, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016020646306317565, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.3990805} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2572942574936421, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1647948084021835, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0995827978533295, "gear": 1, "accelerator_pedal_position": 0.2572942574936421, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.3990805} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502645.4090805, "x": 15.894647508316831, "y": 4.686957802080887, "z": null, "yaw": -0.01156746848701068, "pitch": null, "roll": null}, "v": 2.0995827978533295, "accelerator_pedal_position": 0.2572942574936421, "brake_pedal_position": 0.0, "acceleration": 0.00902749019218041, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016028215725124258, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.4290805} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2588158048693522, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2383079516814433, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.099948470206269, "gear": 1, "accelerator_pedal_position": 0.2588158048693522, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.4290805} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.819993495941162, "x": 11.894647508316831, "y": -0.31304219791911336, "z": null, "yaw": 6.271617838692576, "pitch": null, "roll": null}, "v": 2.0995827978533295, "accelerator_pedal_position": 0.2572942574936421, "brake_pedal_position": 0.0, "acceleration": 0.00902749019218041, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016028215725124258, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.4490805} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25834488118572274, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2383079516814433, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.100133505417748, "gear": 1, "accelerator_pedal_position": 0.2588158048693522, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.4490805} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.819993495941162, "x": 11.894647508316831, "y": -0.31304219791911336, "z": null, "yaw": 6.271617838692576, "pitch": null, "roll": null}, "v": 2.0995827978533295, "accelerator_pedal_position": 0.2572942574936421, "brake_pedal_position": 0.0, "acceleration": 0.00902749019218041, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016028215725124258, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.4690804} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25834488118572274, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2383079516814433, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.100444226908196, "gear": 1, "accelerator_pedal_position": 0.25834488118572274, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.4690804} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.819993495941162, "x": 11.894647508316831, "y": -0.31304219791911336, "z": null, "yaw": 6.271617838692576, "pitch": null, "roll": null}, "v": 2.0995827978533295, "accelerator_pedal_position": 0.2572942574936421, "brake_pedal_position": 0.0, "acceleration": 0.00902749019218041, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016028215725124258, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.4890804} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25834488118572274, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2383079516814433, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1007543768885855, "gear": 1, "accelerator_pedal_position": 0.25834488118572274, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.4890804} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.819993495941162, "x": 11.894647508316831, "y": -0.31304219791911336, "z": null, "yaw": 6.271617838692576, "pitch": null, "roll": null}, "v": 2.0995827978533295, "accelerator_pedal_position": 0.2572942574936421, "brake_pedal_position": 0.0, "acceleration": 0.00902749019218041, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016028215725124258, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.5090804} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25834488118572274, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2383079516814433, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1010639563716347, "gear": 1, "accelerator_pedal_position": 0.25834488118572274, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.5090804} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502645.5190804, "x": 16.12566466057755, "y": 4.684373602851725, "z": null, "yaw": -0.010727728453149522, "pitch": null, "roll": null}, "v": 2.10121853249268, "accelerator_pedal_position": 0.25834488118572274, "brake_pedal_position": 0.0, "acceleration": 0.015443387573226108, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016040702923864586, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.5290804} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25755060135269126, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1644981061528523, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1013729663684124, "gear": 1, "accelerator_pedal_position": 0.25834488118572274, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.5290804} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.929993391036987, "x": 12.125664660577549, "y": -0.3156263971482751, "z": null, "yaw": 6.272457578726437, "pitch": null, "roll": null}, "v": 2.10121853249268, "accelerator_pedal_position": 0.25834488118572274, "brake_pedal_position": 0.0, "acceleration": 0.015443387573226108, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016040702923864586, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.5490804} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25780633900291117, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1644981061528523, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.101582168595217, "gear": 1, "accelerator_pedal_position": 0.25755060135269126, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.5490804} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.929993391036987, "x": 12.125664660577549, "y": -0.3156263971482751, "z": null, "yaw": 6.272457578726437, "pitch": null, "roll": null}, "v": 2.10121853249268, "accelerator_pedal_position": 0.25834488118572274, "brake_pedal_position": 0.0, "acceleration": 0.015443387573226108, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016040702923864586, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.5690804} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25780633900291117, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1644981061528523, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1018229384350375, "gear": 1, "accelerator_pedal_position": 0.25780633900291117, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.5690804} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.929993391036987, "x": 12.125664660577549, "y": -0.3156263971482751, "z": null, "yaw": 6.272457578726437, "pitch": null, "roll": null}, "v": 2.10121853249268, "accelerator_pedal_position": 0.25834488118572274, "brake_pedal_position": 0.0, "acceleration": 0.015443387573226108, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016040702923864586, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.5890803} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25780633900291117, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1644981061528523, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1020632652925326, "gear": 1, "accelerator_pedal_position": 0.25780633900291117, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.5890803} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 6.929993391036987, "x": 12.125664660577549, "y": -0.3156263971482751, "z": null, "yaw": 6.272457578726437, "pitch": null, "roll": null}, "v": 2.10121853249268, "accelerator_pedal_position": 0.25834488118572274, "brake_pedal_position": 0.0, "acceleration": 0.015443387573226108, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016040702923864586, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.6090803} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25780633900291117, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1644981061528523, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.102303149959635, "gear": 1, "accelerator_pedal_position": 0.25780633900291117, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.6090803} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502645.6290803, "x": 16.356853206070472, "y": 4.681981644211641, "z": null, "yaw": -0.009887988419288365, "pitch": null, "roll": null}, "v": 2.1025425932269473, "accelerator_pedal_position": 0.25780633900291117, "brake_pedal_position": 0.0, "acceleration": 0.011955635543512366, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016050810803917567, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.6290803} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2586503480495873, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1928159931384612, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1025425932269473, "gear": 1, "accelerator_pedal_position": 0.25780633900291117, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.6290803} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.0399932861328125, "x": 12.356853206070472, "y": -0.31801835578835913, "z": null, "yaw": 6.273297318760298, "pitch": null, "roll": null}, "v": 2.1025425932269473, "accelerator_pedal_position": 0.25780633900291117, "brake_pedal_position": 0.0, "acceleration": 0.011955635543512366, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016050810803917567, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.6490803} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25839268822292316, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1928159931384612, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1028870484556945, "gear": 1, "accelerator_pedal_position": 0.2586503480495873, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.6490803} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.0399932861328125, "x": 12.356853206070472, "y": -0.31801835578835913, "z": null, "yaw": 6.273297318760298, "pitch": null, "roll": null}, "v": 2.1025425932269473, "accelerator_pedal_position": 0.25780633900291117, "brake_pedal_position": 0.0, "acceleration": 0.011955635543512366, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016050810803917567, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.6690803} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25839268822292316, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1928159931384612, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1031986771397433, "gear": 1, "accelerator_pedal_position": 0.25839268822292316, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.6690803} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.0399932861328125, "x": 12.356853206070472, "y": -0.31801835578835913, "z": null, "yaw": 6.273297318760298, "pitch": null, "roll": null}, "v": 2.1025425932269473, "accelerator_pedal_position": 0.25780633900291117, "brake_pedal_position": 0.0, "acceleration": 0.011955635543512366, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016050810803917567, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.6890802} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25839268822292316, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1928159931384612, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1036650451305223, "gear": 1, "accelerator_pedal_position": 0.25839268822292316, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.6890802} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.0399932861328125, "x": 12.356853206070472, "y": -0.31801835578835913, "z": null, "yaw": 6.273297318760298, "pitch": null, "roll": null}, "v": 2.1025425932269473, "accelerator_pedal_position": 0.25780633900291117, "brake_pedal_position": 0.0, "acceleration": 0.011955635543512366, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016050810803917567, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.6990802} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25839268822292316, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1928159931384612, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.103820214959679, "gear": 1, "accelerator_pedal_position": 0.25839268822292316, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.6990802} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.0399932861328125, "x": 12.356853206070472, "y": -0.31801835578835913, "z": null, "yaw": 6.273297318760298, "pitch": null, "roll": null}, "v": 2.1025425932269473, "accelerator_pedal_position": 0.25780633900291117, "brake_pedal_position": 0.0, "acceleration": 0.011955635543512366, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016050810803917567, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.7290802} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25839268822292316, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1928159931384612, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1041301261275596, "gear": 1, "accelerator_pedal_position": 0.25839268822292316, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.7290802} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502645.7390802, "x": 16.588211153110645, "y": 4.679782235821813, "z": null, "yaw": -0.009048248385427208, "pitch": null, "roll": null}, "v": 2.104284867719661, "accelerator_pedal_position": 0.25839268822292316, "brake_pedal_position": 0.0, "acceleration": 0.015459909962147078, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01606411132793126, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.7490802} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25708464477874277, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.165179340273655, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1044394668192825, "gear": 1, "accelerator_pedal_position": 0.25839268822292316, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.7490802} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.149993181228638, "x": 12.588211153110645, "y": -0.3202177641781869, "z": null, "yaw": 6.274137058794159, "pitch": null, "roll": null}, "v": 2.104284867719661, "accelerator_pedal_position": 0.25839268822292316, "brake_pedal_position": 0.0, "acceleration": 0.015459909962147078, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01606411132793126, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.7690802} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2575014290386362, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.165179340273655, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1045848079031257, "gear": 1, "accelerator_pedal_position": 0.25708464477874277, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.7690802} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.149993181228638, "x": 12.588211153110645, "y": -0.3202177641781869, "z": null, "yaw": 6.274137058794159, "pitch": null, "roll": null}, "v": 2.104284867719661, "accelerator_pedal_position": 0.25839268822292316, "brake_pedal_position": 0.0, "acceleration": 0.015459909962147078, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01606411132793126, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.7890801} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2575014290386362, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.165179340273655, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.104781955461264, "gear": 1, "accelerator_pedal_position": 0.2575014290386362, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.7890801} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.149993181228638, "x": 12.588211153110645, "y": -0.3202177641781869, "z": null, "yaw": 6.274137058794159, "pitch": null, "roll": null}, "v": 2.104284867719661, "accelerator_pedal_position": 0.25839268822292316, "brake_pedal_position": 0.0, "acceleration": 0.015459909962147078, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01606411132793126, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.8090801} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2575014290386362, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.165179340273655, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1049787400618922, "gear": 1, "accelerator_pedal_position": 0.2575014290386362, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.8090801} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.149993181228638, "x": 12.588211153110645, "y": -0.3202177641781869, "z": null, "yaw": 6.274137058794159, "pitch": null, "roll": null}, "v": 2.104284867719661, "accelerator_pedal_position": 0.25839268822292316, "brake_pedal_position": 0.0, "acceleration": 0.015459909962147078, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01606411132793126, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.82908} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2575014290386362, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.165179340273655, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1051751623577495, "gear": 1, "accelerator_pedal_position": 0.2575014290386362, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.82908} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502645.84908, "x": 16.81972916386827, "y": 4.67777573161186, "z": null, "yaw": -0.00820850835156605, "pitch": null, "roll": null}, "v": 2.105371223000458, "accelerator_pedal_position": 0.2575014290386362, "brake_pedal_position": 0.0, "acceleration": 0.009789490475068885, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016072404564479278, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.84908} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25424480020580936, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1332937022274265, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.105371223000458, "gear": 1, "accelerator_pedal_position": 0.2575014290386362, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.84908} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.259993076324463, "x": 12.81972916386827, "y": -0.32222426838813956, "z": null, "yaw": 6.27497679882802, "pitch": null, "roll": null}, "v": 2.105371223000458, "accelerator_pedal_position": 0.2575014290386362, "brake_pedal_position": 0.0, "acceleration": 0.009789490475068885, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016072404564479278, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.86908} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25526749986586617, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1332937022274265, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1051600315110734, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.86908} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.259993076324463, "x": 12.81972916386827, "y": -0.32222426838813956, "z": null, "yaw": 6.27497679882802, "pitch": null, "roll": null}, "v": 2.105371223000458, "accelerator_pedal_position": 0.2575014290386362, "brake_pedal_position": 0.0, "acceleration": 0.009789490475068885, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016072404564479278, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.88908} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25526749986586617, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1332937022274265, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.105077007462487, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.88908} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.259993076324463, "x": 12.81972916386827, "y": -0.32222426838813956, "z": null, "yaw": 6.27497679882802, "pitch": null, "roll": null}, "v": 2.105371223000458, "accelerator_pedal_position": 0.2575014290386362, "brake_pedal_position": 0.0, "acceleration": 0.009789490475068885, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016072404564479278, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.90908} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25526749986586617, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1332937022274265, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1049941362770177, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.90908} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.259993076324463, "x": 12.81972916386827, "y": -0.32222426838813956, "z": null, "yaw": 6.27497679882802, "pitch": null, "roll": null}, "v": 2.105371223000458, "accelerator_pedal_position": 0.2575014290386362, "brake_pedal_position": 0.0, "acceleration": 0.009789490475068885, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016072404564479278, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.92908} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25526749986586617, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1332937022274265, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1048288513591853, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.92908} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.259993076324463, "x": 12.81972916386827, "y": -0.32222426838813956, "z": null, "yaw": 6.27497679882802, "pitch": null, "roll": null}, "v": 2.105371223000458, "accelerator_pedal_position": 0.2575014290386362, "brake_pedal_position": 0.0, "acceleration": 0.009789490475068885, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016072404564479278, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.94908} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25526749986586617, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1332937022274265, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.104787625225771, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.94908} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502645.95908, "x": 17.051277916417405, "y": 4.675963402734362, "z": null, "yaw": -0.007368768317704893, "pitch": null, "roll": null}, "v": 2.104787625225771, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.349540690734324, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016067949378887673, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.97908} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25677733422837073, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.191766330514595, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.104811742407016, "gear": 1, "accelerator_pedal_position": 0.25677733422837073, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.97908} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.369992971420288, "x": 13.051277916417405, "y": -0.32403659726563827, "z": null, "yaw": 6.275816538861881, "pitch": null, "roll": null}, "v": 2.104787625225771, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.349540690734324, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016067949378887673, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502645.99908} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2563028231648702, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.191766330514595, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.104811742407016, "gear": 1, "accelerator_pedal_position": 0.25677733422837073, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502645.99908} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.369992971420288, "x": 13.051277916417405, "y": -0.32403659726563827, "z": null, "yaw": 6.275816538861881, "pitch": null, "roll": null}, "v": 2.104787625225771, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.349540690734324, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016067949378887673, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.01908} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2563028231648702, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.191766330514595, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.104858715425812, "gear": 1, "accelerator_pedal_position": 0.2563028231648702, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.01908} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.369992971420288, "x": 13.051277916417405, "y": -0.32403659726563827, "z": null, "yaw": 6.275816538861881, "pitch": null, "roll": null}, "v": 2.104787625225771, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.349540690734324, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016067949378887673, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.03908} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2563028231648702, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.191766330514595, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.104905601963025, "gear": 1, "accelerator_pedal_position": 0.2563028231648702, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.03908} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.369992971420288, "x": 13.051277916417405, "y": -0.32403659726563827, "z": null, "yaw": 6.275816538861881, "pitch": null, "roll": null}, "v": 2.104787625225771, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.349540690734324, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016067949378887673, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.05908} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2563028231648702, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.191766330514595, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.104952402176995, "gear": 1, "accelerator_pedal_position": 0.2563028231648702, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.05908} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502646.0690799, "x": 17.28280398584204, "y": 4.6743456898181925, "z": null, "yaw": -0.006529028283843736, "pitch": null, "roll": null}, "v": 2.104975769962168, "accelerator_pedal_position": 0.2563028231648702, "brake_pedal_position": 0.0, "acceleration": 0.0023346263610519724, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016069385675863242, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.0790799} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25378760901170117, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1499019082593922, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1048652401029653, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.0790799} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.479992866516113, "x": 13.28280398584204, "y": -0.32565431018180746, "z": null, "yaw": 6.276656278895742, "pitch": null, "roll": null}, "v": 2.104975769962168, "accelerator_pedal_position": 0.2563028231648702, "brake_pedal_position": 0.0, "acceleration": 0.0023346263610519724, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016069385675863242, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.0990798} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2545744803347327, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1499019082593922, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.104731487278246, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.0990798} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.479992866516113, "x": 13.28280398584204, "y": -0.32565431018180746, "z": null, "yaw": 6.276656278895742, "pitch": null, "roll": null}, "v": 2.104975769962168, "accelerator_pedal_position": 0.2563028231648702, "brake_pedal_position": 0.0, "acceleration": 0.0023346263610519724, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016069385675863242, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.1190798} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2545744803347327, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1499019082593922, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.104562664679474, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.1190798} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.479992866516113, "x": 13.28280398584204, "y": -0.32565431018180746, "z": null, "yaw": 6.276656278895742, "pitch": null, "roll": null}, "v": 2.104975769962168, "accelerator_pedal_position": 0.2563028231648702, "brake_pedal_position": 0.0, "acceleration": 0.0023346263610519724, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016069385675863242, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.1390798} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2545744803347327, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1499019082593922, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.10439415288207, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.1390798} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.479992866516113, "x": 13.28280398584204, "y": -0.32565431018180746, "z": null, "yaw": 6.276656278895742, "pitch": null, "roll": null}, "v": 2.104975769962168, "accelerator_pedal_position": 0.2563028231648702, "brake_pedal_position": 0.0, "acceleration": 0.0023346263610519724, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016069385675863242, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.1590798} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2545744803347327, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1499019082593922, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1042259513024977, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.1590798} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502646.1790798, "x": 17.51430292254529, "y": 4.672922564474975, "z": null, "yaw": -0.005689288249982579, "pitch": null, "roll": null}, "v": 2.104058059358356, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34947350613942635, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016062379872831246, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.1790798} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25628814684213386, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.216906073013514, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.104058059358356, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.1790798} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.5899927616119385, "x": 13.51430292254529, "y": -0.327077435525025, "z": null, "yaw": 6.277496018929604, "pitch": null, "roll": null}, "v": 2.104058059358356, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34947350613942635, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016062379872831246, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.1990798} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25574840009068744, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.216906073013514, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.104104586159704, "gear": 1, "accelerator_pedal_position": 0.25628814684213386, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.1990798} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.5899927616119385, "x": 13.51430292254529, "y": -0.327077435525025, "z": null, "yaw": 6.277496018929604, "pitch": null, "roll": null}, "v": 2.104058059358356, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34947350613942635, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016062379872831246, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.2290797} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25574840009068744, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.216906073013514, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1040626325582203, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.2290797} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.5899927616119385, "x": 13.51430292254529, "y": -0.327077435525025, "z": null, "yaw": 6.277496018929604, "pitch": null, "roll": null}, "v": 2.104058059358356, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34947350613942635, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016062379872831246, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.2390797} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25574840009068744, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.216906073013514, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1040521682914366, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.2390797} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.5899927616119385, "x": 13.51430292254529, "y": -0.327077435525025, "z": null, "yaw": 6.277496018929604, "pitch": null, "roll": null}, "v": 2.104058059358356, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34947350613942635, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016062379872831246, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.2690797} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25574840009068744, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.216906073013514, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.104031268655825, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.2690797} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502646.2890797, "x": 17.745746689569607, "y": 4.6716941442061, "z": null, "yaw": -0.0048495482161214215, "pitch": null, "roll": null}, "v": 2.1040104074915673, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3494691183229067, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016062016098465512, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.2890797} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2553113747691821, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.227349110988929, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1039349817132167, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.2890797} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.699992656707764, "x": 13.745746689569607, "y": -0.32830585579390004, "z": null, "yaw": 6.278335758963465, "pitch": null, "roll": null}, "v": 2.1040104074915673, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3494691183229067, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016062016098465512, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.3090796} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2554477258807253, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.227349110988929, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1039349817132167, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.3090796} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.699992656707764, "x": 13.745746689569607, "y": -0.32830585579390004, "z": null, "yaw": 6.278335758963465, "pitch": null, "roll": null}, "v": 2.1040104074915673, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3494691183229067, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016062016098465512, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.3290796} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2554477258807253, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.227349110988929, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.103789555450413, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.3290796} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.699992656707764, "x": 13.745746689569607, "y": -0.32830585579390004, "z": null, "yaw": 6.278335758963465, "pitch": null, "roll": null}, "v": 2.1040104074915673, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3494691183229067, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016062016098465512, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.3590796} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2554477258807253, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.227349110988929, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.103789555450413, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.3590796} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.699992656707764, "x": 13.745746689569607, "y": -0.32830585579390004, "z": null, "yaw": 6.278335758963465, "pitch": null, "roll": null}, "v": 2.1040104074915673, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3494691183229067, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016062016098465512, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.3890796} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2554477258807253, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.227349110988929, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.103702620666414, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.3890796} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502646.3990796, "x": 17.977167884735906, "y": 4.670660180023287, "z": null, "yaw": -0.004009808182260264, "pitch": null, "roll": null}, "v": 2.1036736957520064, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3494381149695894, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01605944564094205, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.4090796} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2560561745725128, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2237390571578228, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.103644797469856, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.4090796} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.809992551803589, "x": 13.977167884735906, "y": -0.32933981997671324, "z": null, "yaw": 6.279175498997326, "pitch": null, "roll": null}, "v": 2.1036736957520064, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3494381149695894, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01605944564094205, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.4290795} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25586448406298123, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2237390571578228, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1036631017766236, "gear": 1, "accelerator_pedal_position": 0.2560561745725128, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.4290795} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.809992551803589, "x": 13.977167884735906, "y": -0.32933981997671324, "z": null, "yaw": 6.279175498997326, "pitch": null, "roll": null}, "v": 2.1036736957520064, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3494381149695894, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01605944564094205, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.4490795} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25586448406298123, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2237390571578228, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1036574221094955, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.4490795} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.809992551803589, "x": 13.977167884735906, "y": -0.32933981997671324, "z": null, "yaw": 6.279175498997326, "pitch": null, "roll": null}, "v": 2.1036736957520064, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3494381149695894, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01605944564094205, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.4690795} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25586448406298123, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2237390571578228, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.103651752896452, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.4690795} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.809992551803589, "x": 13.977167884735906, "y": -0.32933981997671324, "z": null, "yaw": 6.279175498997326, "pitch": null, "roll": null}, "v": 2.1036736957520064, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3494381149695894, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01605944564094205, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.4890795} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25586448406298123, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2237390571578228, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.103646094118239, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.4890795} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502646.5090795, "x": 18.208568333558958, "y": 4.669820630336017, "z": null, "yaw": -0.003170068148399107, "pitch": null, "roll": null}, "v": 2.1036404457556364, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34943505353797155, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01605919181045953, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.5090795} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2564481292951369, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.175716579196709, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1036404457556364, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.5090795} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.919992446899414, "x": 14.208568333558958, "y": -0.3301793696639832, "z": null, "yaw": 6.280015239031187, "pitch": null, "roll": null}, "v": 2.1036404457556364, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34943505353797155, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01605919181045953, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.5290794} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2562655869688233, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.175716579196709, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.103707729857208, "gear": 1, "accelerator_pedal_position": 0.2564481292951369, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.5290794} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.919992446899414, "x": 14.208568333558958, "y": -0.3301793696639832, "z": null, "yaw": 6.280015239031187, "pitch": null, "roll": null}, "v": 2.1036404457556364, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34943505353797155, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01605919181045953, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.5490794} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2562655869688233, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.175716579196709, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1037520828276564, "gear": 1, "accelerator_pedal_position": 0.2562655869688233, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.5490794} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.919992446899414, "x": 14.208568333558958, "y": -0.3301793696639832, "z": null, "yaw": 6.280015239031187, "pitch": null, "roll": null}, "v": 2.1036404457556364, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34943505353797155, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01605919181045953, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.5690794} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2562655869688233, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.175716579196709, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.103796354159871, "gear": 1, "accelerator_pedal_position": 0.2562655869688233, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.5690794} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.919992446899414, "x": 14.208568333558958, "y": -0.3301793696639832, "z": null, "yaw": 6.280015239031187, "pitch": null, "roll": null}, "v": 2.1036404457556364, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34943505353797155, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01605919181045953, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.5890794} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2562655869688233, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.175716579196709, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1038405440033356, "gear": 1, "accelerator_pedal_position": 0.2562655869688233, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.5890794} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 7.919992446899414, "x": 14.208568333558958, "y": -0.3301793696639832, "z": null, "yaw": 6.280015239031187, "pitch": null, "roll": null}, "v": 2.1036404457556364, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34943505353797155, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01605919181045953, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.6090794} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2562655869688233, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.175716579196709, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1038846525072628, "gear": 1, "accelerator_pedal_position": 0.2562655869688233, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.6090794} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502646.6190794, "x": 18.43998223845049, "y": 4.66917536348668, "z": null, "yaw": -0.00233032811453795, "pitch": null, "roll": null}, "v": 2.103906676303455, "accelerator_pedal_position": 0.2562655869688233, "brake_pedal_position": 0.0, "acceleration": 0.002200351714030213, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016061224214543528, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.6290793} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2568546890621573, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.127978206109691, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.103928679820595, "gear": 1, "accelerator_pedal_position": 0.2562655869688233, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.6290793} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.02999234199524, "x": 14.43998223845049, "y": -0.33082463651332006, "z": null, "yaw": 6.280854979065048, "pitch": null, "roll": null}, "v": 2.103906676303455, "accelerator_pedal_position": 0.2562655869688233, "brake_pedal_position": 0.0, "acceleration": 0.002200351714030213, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016061224214543528, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.6490793} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25667182020324947, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.127978206109691, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.104046229951075, "gear": 1, "accelerator_pedal_position": 0.2568546890621573, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.6490793} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.02999234199524, "x": 14.43998223845049, "y": -0.33082463651332006, "z": null, "yaw": 6.280854979065048, "pitch": null, "roll": null}, "v": 2.103906676303455, "accelerator_pedal_position": 0.2562655869688233, "brake_pedal_position": 0.0, "acceleration": 0.002200351714030213, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016061224214543528, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.6690793} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25667182020324947, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.127978206109691, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1041407156170773, "gear": 1, "accelerator_pedal_position": 0.25667182020324947, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.6690793} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.02999234199524, "x": 14.43998223845049, "y": -0.33082463651332006, "z": null, "yaw": 6.280854979065048, "pitch": null, "roll": null}, "v": 2.103906676303455, "accelerator_pedal_position": 0.2562655869688233, "brake_pedal_position": 0.0, "acceleration": 0.002200351714030213, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016061224214543528, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.6890793} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25667182020324947, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.127978206109691, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.104235027353968, "gear": 1, "accelerator_pedal_position": 0.25667182020324947, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.6890793} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.02999234199524, "x": 14.43998223845049, "y": -0.33082463651332006, "z": null, "yaw": 6.280854979065048, "pitch": null, "roll": null}, "v": 2.103906676303455, "accelerator_pedal_position": 0.2562655869688233, "brake_pedal_position": 0.0, "acceleration": 0.002200351714030213, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016061224214543528, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.7090793} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25667182020324947, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.127978206109691, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1043291654783594, "gear": 1, "accelerator_pedal_position": 0.25667182020324947, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.7090793} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502646.7290792, "x": 18.671436928797736, "y": 4.668724347852609, "z": null, "yaw": -0.0014905880806767927, "pitch": null, "roll": null}, "v": 2.1044231303063, "accelerator_pedal_position": 0.25667182020324947, "brake_pedal_position": 0.0, "acceleration": 0.004691752641312441, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016065166824560228, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.7290792} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25834135963645427, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.188473534275868, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1044231303063, "gear": 1, "accelerator_pedal_position": 0.25667182020324947, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.7290792} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.139992237091064, "x": 14.671436928797736, "y": -0.33127565214739096, "z": null, "yaw": 6.281694719098909, "pitch": null, "roll": null}, "v": 2.1044231303063, "accelerator_pedal_position": 0.25667182020324947, "brake_pedal_position": 0.0, "acceleration": 0.004691752641312441, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016065166824560228, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.7490792} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2578220060624571, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.188473534275868, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1047255184895355, "gear": 1, "accelerator_pedal_position": 0.25834135963645427, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.7490792} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.139992237091064, "x": 14.671436928797736, "y": -0.33127565214739096, "z": null, "yaw": 6.281694719098909, "pitch": null, "roll": null}, "v": 2.1044231303063, "accelerator_pedal_position": 0.25667182020324947, "brake_pedal_position": 0.0, "acceleration": 0.004691752641312441, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016065166824560228, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.7690792} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2578220060624571, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.188473534275868, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1049624606701776, "gear": 1, "accelerator_pedal_position": 0.2578220060624571, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.7690792} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.139992237091064, "x": 14.671436928797736, "y": -0.33127565214739096, "z": null, "yaw": 6.281694719098909, "pitch": null, "roll": null}, "v": 2.1044231303063, "accelerator_pedal_position": 0.25667182020324947, "brake_pedal_position": 0.0, "acceleration": 0.004691752641312441, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016065166824560228, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.7890792} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2578220060624571, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.188473534275868, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.105198966613473, "gear": 1, "accelerator_pedal_position": 0.2578220060624571, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.7890792} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.139992237091064, "x": 14.671436928797736, "y": -0.33127565214739096, "z": null, "yaw": 6.281694719098909, "pitch": null, "roll": null}, "v": 2.1044231303063, "accelerator_pedal_position": 0.25667182020324947, "brake_pedal_position": 0.0, "acceleration": 0.004691752641312441, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016065166824560228, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.8090792} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2578220060624571, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.188473534275868, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1054350371002206, "gear": 1, "accelerator_pedal_position": 0.2578220060624571, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.8090792} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.139992237091064, "x": 14.671436928797736, "y": -0.33127565214739096, "z": null, "yaw": 6.281694719098909, "pitch": null, "roll": null}, "v": 2.1044231303063, "accelerator_pedal_position": 0.25667182020324947, "brake_pedal_position": 0.0, "acceleration": 0.004691752641312441, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016065166824560228, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.8290792} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2578220060624571, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.188473534275868, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1056706729099046, "gear": 1, "accelerator_pedal_position": 0.2578220060624571, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.8290792} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502646.8390791, "x": 18.902994629275767, "y": 4.668467586454433, "z": null, "yaw": -0.000650848046815636, "pitch": null, "roll": null}, "v": 2.105788328054078, "accelerator_pedal_position": 0.2578220060624571, "brake_pedal_position": 0.0, "acceleration": 0.011754676661964891, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016075588744587012, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.8490791} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2583602179808584, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.094912395586726, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1059058748206976, "gear": 1, "accelerator_pedal_position": 0.2578220060624571, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.8490791} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.24999213218689, "x": 14.902994629275767, "y": -0.33153241354556684, "z": null, "yaw": 6.282534459132771, "pitch": null, "roll": null}, "v": 2.105788328054078, "accelerator_pedal_position": 0.2578220060624571, "brake_pedal_position": 0.0, "acceleration": 0.011754676661964891, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016075588744587012, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.869079} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2581983135301749, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.094912395586726, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1062078891114404, "gear": 1, "accelerator_pedal_position": 0.2583602179808584, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.869079} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.24999213218689, "x": 14.902994629275767, "y": -0.33153241354556684, "z": null, "yaw": 6.282534459132771, "pitch": null, "roll": null}, "v": 2.105788328054078, "accelerator_pedal_position": 0.2578220060624571, "brake_pedal_position": 0.0, "acceleration": 0.011754676661964891, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016075588744587012, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.889079} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2581983135301749, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.094912395586726, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.106489118477401, "gear": 1, "accelerator_pedal_position": 0.2581983135301749, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.889079} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.24999213218689, "x": 14.902994629275767, "y": -0.33153241354556684, "z": null, "yaw": 6.282534459132771, "pitch": null, "roll": null}, "v": 2.105788328054078, "accelerator_pedal_position": 0.2578220060624571, "brake_pedal_position": 0.0, "acceleration": 0.011754676661964891, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016075588744587012, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.909079} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2581983135301749, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.094912395586726, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.106769829897966, "gear": 1, "accelerator_pedal_position": 0.2581983135301749, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.909079} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.24999213218689, "x": 14.902994629275767, "y": -0.33153241354556684, "z": null, "yaw": 6.282534459132771, "pitch": null, "roll": null}, "v": 2.105788328054078, "accelerator_pedal_position": 0.2578220060624571, "brake_pedal_position": 0.0, "acceleration": 0.011754676661964891, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016075588744587012, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.929079} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2581983135301749, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.094912395586726, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.10705002429554, "gear": 1, "accelerator_pedal_position": 0.2581983135301749, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.929079} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502646.949079, "x": 19.134708074566767, "y": 4.668405233105053, "z": null, "yaw": 0.00018889198704552008, "pitch": null, "roll": null}, "v": 2.1073297025910027, "accelerator_pedal_position": 0.2581983135301749, "brake_pedal_position": 0.0, "acceleration": 0.013964589679820172, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016087355598276374, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.949079} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2596708166654187, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1518318584506897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1073297025910027, "gear": 1, "accelerator_pedal_position": 0.2581983135301749, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.949079} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.359992027282715, "x": 15.134708074566767, "y": -0.3315947668949466, "z": null, "yaw": 0.00018889198704552008, "pitch": null, "roll": null}, "v": 2.1073297025910027, "accelerator_pedal_position": 0.2581983135301749, "brake_pedal_position": 0.0, "acceleration": 0.013964589679820172, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016087355598276374, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.969079} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2592177595713767, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1518318584506897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.107792843788357, "gear": 1, "accelerator_pedal_position": 0.2596708166654187, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.969079} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.359992027282715, "x": 15.134708074566767, "y": -0.3315947668949466, "z": null, "yaw": 0.00018889198704552008, "pitch": null, "roll": null}, "v": 2.1073297025910027, "accelerator_pedal_position": 0.2581983135301749, "brake_pedal_position": 0.0, "acceleration": 0.013964589679820172, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016087355598276374, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502646.989079} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2592177595713767, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1518318584506897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.108198525736394, "gear": 1, "accelerator_pedal_position": 0.2592177595713767, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502646.989079} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.359992027282715, "x": 15.134708074566767, "y": -0.3315947668949466, "z": null, "yaw": 0.00018889198704552008, "pitch": null, "roll": null}, "v": 2.1073297025910027, "accelerator_pedal_position": 0.2581983135301749, "brake_pedal_position": 0.0, "acceleration": 0.013964589679820172, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016087355598276374, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.009079} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2592177595713767, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1518318584506897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1086034602602943, "gear": 1, "accelerator_pedal_position": 0.2592177595713767, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.009079} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.359992027282715, "x": 15.134708074566767, "y": -0.3315947668949466, "z": null, "yaw": 0.00018889198704552008, "pitch": null, "roll": null}, "v": 2.1073297025910027, "accelerator_pedal_position": 0.2581983135301749, "brake_pedal_position": 0.0, "acceleration": 0.013964589679820172, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016087355598276374, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.029079} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2592177595713767, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1518318584506897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.109007648671545, "gear": 1, "accelerator_pedal_position": 0.2592177595713767, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.029079} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.359992027282715, "x": 15.134708074566767, "y": -0.3315947668949466, "z": null, "yaw": 0.00018889198704552008, "pitch": null, "roll": null}, "v": 2.1073297025910027, "accelerator_pedal_position": 0.2581983135301749, "brake_pedal_position": 0.0, "acceleration": 0.013964589679820172, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016087355598276374, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.049079} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2592177595713767, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1518318584506897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1094110922795792, "gear": 1, "accelerator_pedal_position": 0.2592177595713767, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.049079} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502647.059079, "x": 19.3666311963349, "y": 4.668537583902912, "z": null, "yaw": 0.0010286320209066762, "pitch": null, "roll": null}, "v": 2.1096125351910273, "accelerator_pedal_position": 0.2592177595713767, "brake_pedal_position": 0.0, "acceleration": 0.020125720075201914, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016104782743047684, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.069079} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2601446398849194, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0525976065196636, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1098137923917792, "gear": 1, "accelerator_pedal_position": 0.2592177595713767, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.069079} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.46999192237854, "x": 15.3666311963349, "y": -0.3314624160970876, "z": null, "yaw": 0.0010286320209066762, "pitch": null, "roll": null}, "v": 2.1096125351910273, "accelerator_pedal_position": 0.2592177595713767, "brake_pedal_position": 0.0, "acceleration": 0.020125720075201914, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016104782743047684, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.089079} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.259865509972032, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0525976065196636, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.110331556940684, "gear": 1, "accelerator_pedal_position": 0.2601446398849194, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.089079} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.46999192237854, "x": 15.3666311963349, "y": -0.3314624160970876, "z": null, "yaw": 0.0010286320209066762, "pitch": null, "roll": null}, "v": 2.1096125351910273, "accelerator_pedal_position": 0.2592177595713767, "brake_pedal_position": 0.0, "acceleration": 0.020125720075201914, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016104782743047684, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.109079} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.259865509972032, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0525976065196636, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1108134919778747, "gear": 1, "accelerator_pedal_position": 0.259865509972032, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.109079} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.46999192237854, "x": 15.3666311963349, "y": -0.3314624160970876, "z": null, "yaw": 0.0010286320209066762, "pitch": null, "roll": null}, "v": 2.1096125351910273, "accelerator_pedal_position": 0.2592177595713767, "brake_pedal_position": 0.0, "acceleration": 0.020125720075201914, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016104782743047684, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.1290789} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.259865509972032, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0525976065196636, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.111294538603082, "gear": 1, "accelerator_pedal_position": 0.259865509972032, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.1290789} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.46999192237854, "x": 15.3666311963349, "y": -0.3314624160970876, "z": null, "yaw": 0.0010286320209066762, "pitch": null, "roll": null}, "v": 2.1096125351910273, "accelerator_pedal_position": 0.2592177595713767, "brake_pedal_position": 0.0, "acceleration": 0.020125720075201914, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016104782743047684, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.1490788} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.259865509972032, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0525976065196636, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1117746983615087, "gear": 1, "accelerator_pedal_position": 0.259865509972032, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.1490788} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502647.1690788, "x": 19.598819852072186, "y": 4.668865067561588, "z": null, "yaw": 0.0018683720547678334, "pitch": null, "roll": null}, "v": 2.11225397279602, "accelerator_pedal_position": 0.259865509972032, "brake_pedal_position": 0.0, "acceleration": 0.023930570229473258, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01612494747853731, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.1690788} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2609872063633647, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0279960980718108, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.11225397279602, "gear": 1, "accelerator_pedal_position": 0.259865509972032, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.1690788} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.579991817474365, "x": 15.598819852072186, "y": -0.3311349324384123, "z": null, "yaw": 0.0018683720547678334, "pitch": null, "roll": null}, "v": 2.11225397279602, "accelerator_pedal_position": 0.259865509972032, "brake_pedal_position": 0.0, "acceleration": 0.023930570229473258, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01612494747853731, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.1890788} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26064885551172434, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0279960980718108, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.112872510822859, "gear": 1, "accelerator_pedal_position": 0.2609872063633647, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.1890788} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.579991817474365, "x": 15.598819852072186, "y": -0.3311349324384123, "z": null, "yaw": 0.0018683720547678334, "pitch": null, "roll": null}, "v": 2.11225397279602, "accelerator_pedal_position": 0.259865509972032, "brake_pedal_position": 0.0, "acceleration": 0.023930570229473258, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01612494747853731, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.2090788} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26064885551172434, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0279960980718108, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1134476337740034, "gear": 1, "accelerator_pedal_position": 0.26064885551172434, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.2090788} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.579991817474365, "x": 15.598819852072186, "y": -0.3311349324384123, "z": null, "yaw": 0.0018683720547678334, "pitch": null, "roll": null}, "v": 2.11225397279602, "accelerator_pedal_position": 0.259865509972032, "brake_pedal_position": 0.0, "acceleration": 0.023930570229473258, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01612494747853731, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.2290788} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26064885551172434, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0279960980718108, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1140216959279963, "gear": 1, "accelerator_pedal_position": 0.26064885551172434, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.2290788} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.579991817474365, "x": 15.598819852072186, "y": -0.3311349324384123, "z": null, "yaw": 0.0018683720547678334, "pitch": null, "roll": null}, "v": 2.11225397279602, "accelerator_pedal_position": 0.259865509972032, "brake_pedal_position": 0.0, "acceleration": 0.023930570229473258, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01612494747853731, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.2490788} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26064885551172434, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0279960980718108, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.114594699109688, "gear": 1, "accelerator_pedal_position": 0.26064885551172434, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.2490788} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.579991817474365, "x": 15.598819852072186, "y": -0.3311349324384123, "z": null, "yaw": 0.0018683720547678334, "pitch": null, "roll": null}, "v": 2.11225397279602, "accelerator_pedal_position": 0.259865509972032, "brake_pedal_position": 0.0, "acceleration": 0.023930570229473258, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01612494747853731, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.2690787} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26064885551172434, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0279960980718108, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1151666451412923, "gear": 1, "accelerator_pedal_position": 0.26064885551172434, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.2690787} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502647.2790787, "x": 19.83132930344762, "y": 4.669388255796627, "z": null, "yaw": 0.0027081120886289904, "pitch": null, "roll": null}, "v": 2.1154522222945324, "accelerator_pedal_position": 0.26064885551172434, "brake_pedal_position": 0.0, "acceleration": 0.028531354785441665, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01614936291619347, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.2890787} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2618136974141813, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0782560407773343, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1157375358423867, "gear": 1, "accelerator_pedal_position": 0.26064885551172434, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.2890787} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.68999171257019, "x": 15.831329303447621, "y": -0.3306117442033729, "z": null, "yaw": 0.0027081120886289904, "pitch": null, "roll": null}, "v": 2.1154522222945324, "accelerator_pedal_position": 0.26064885551172434, "brake_pedal_position": 0.0, "acceleration": 0.028531354785441665, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01614936291619347, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.3090787} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26146444034402816, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0782560407773343, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1164529110554873, "gear": 1, "accelerator_pedal_position": 0.2618136974141813, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.3090787} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.68999171257019, "x": 15.831329303447621, "y": -0.3306117442033729, "z": null, "yaw": 0.0027081120886289904, "pitch": null, "roll": null}, "v": 2.1154522222945324, "accelerator_pedal_position": 0.26064885551172434, "brake_pedal_position": 0.0, "acceleration": 0.028531354785441665, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01614936291619347, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.3290787} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26146444034402816, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0782560407773343, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.117123328953032, "gear": 1, "accelerator_pedal_position": 0.26146444034402816, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.3290787} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.68999171257019, "x": 15.831329303447621, "y": -0.3306117442033729, "z": null, "yaw": 0.0027081120886289904, "pitch": null, "roll": null}, "v": 2.1154522222945324, "accelerator_pedal_position": 0.26064885551172434, "brake_pedal_position": 0.0, "acceleration": 0.028531354785441665, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01614936291619347, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.3490787} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26146444034402816, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0782560407773343, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1177925093063297, "gear": 1, "accelerator_pedal_position": 0.26146444034402816, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.3490787} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.68999171257019, "x": 15.831329303447621, "y": -0.3306117442033729, "z": null, "yaw": 0.0027081120886289904, "pitch": null, "roll": null}, "v": 2.1154522222945324, "accelerator_pedal_position": 0.26064885551172434, "brake_pedal_position": 0.0, "acceleration": 0.028531354785441665, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01614936291619347, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.3690786} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26146444034402816, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0782560407773343, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.118460454220762, "gear": 1, "accelerator_pedal_position": 0.26146444034402816, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.3690786} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502647.3890786, "x": 20.064210997905523, "y": 4.670107847043696, "z": null, "yaw": 0.0035478521224901476, "pitch": null, "roll": null}, "v": 2.1191271657988153, "accelerator_pedal_position": 0.26146444034402816, "brake_pedal_position": 0.0, "acceleration": 0.03328939441196993, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016177417436036415, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.3890786} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2625168046955354, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9157615482225673, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1191271657988153, "gear": 1, "accelerator_pedal_position": 0.26146444034402816, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.3890786} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.799991607666016, "x": 16.064210997905523, "y": -0.3298921529563037, "z": null, "yaw": 0.0035478521224901476, "pitch": null, "roll": null}, "v": 2.1191271657988153, "accelerator_pedal_position": 0.26146444034402816, "brake_pedal_position": 0.0, "acceleration": 0.03328939441196993, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016177417436036415, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.4090786} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26220490890996306, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9157615482225673, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.119924130916648, "gear": 1, "accelerator_pedal_position": 0.2625168046955354, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.4090786} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.799991607666016, "x": 16.064210997905523, "y": -0.3298921529563037, "z": null, "yaw": 0.0035478521224901476, "pitch": null, "roll": null}, "v": 2.1191271657988153, "accelerator_pedal_position": 0.26146444034402816, "brake_pedal_position": 0.0, "acceleration": 0.03328939441196993, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016177417436036415, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.4290786} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26220490890996306, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9157615482225673, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1206806550510247, "gear": 1, "accelerator_pedal_position": 0.26220490890996306, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.4290786} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.799991607666016, "x": 16.064210997905523, "y": -0.3298921529563037, "z": null, "yaw": 0.0035478521224901476, "pitch": null, "roll": null}, "v": 2.1191271657988153, "accelerator_pedal_position": 0.26146444034402816, "brake_pedal_position": 0.0, "acceleration": 0.03328939441196993, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016177417436036415, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.4490786} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26220490890996306, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9157615482225673, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1214357816261273, "gear": 1, "accelerator_pedal_position": 0.26220490890996306, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.4490786} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.799991607666016, "x": 16.064210997905523, "y": -0.3298921529563037, "z": null, "yaw": 0.0035478521224901476, "pitch": null, "roll": null}, "v": 2.1191271657988153, "accelerator_pedal_position": 0.26146444034402816, "brake_pedal_position": 0.0, "acceleration": 0.03328939441196993, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016177417436036415, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.4690785} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26220490890996306, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9157615482225673, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1221895129957455, "gear": 1, "accelerator_pedal_position": 0.26220490890996306, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.4690785} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.799991607666016, "x": 16.064210997905523, "y": -0.3298921529563037, "z": null, "yaw": 0.0035478521224901476, "pitch": null, "roll": null}, "v": 2.1191271657988153, "accelerator_pedal_position": 0.26146444034402816, "brake_pedal_position": 0.0, "acceleration": 0.03328939441196993, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016177417436036415, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.4890785} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26220490890996306, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9157615482225673, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1229418515105833, "gear": 1, "accelerator_pedal_position": 0.26220490890996306, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.4890785} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502647.4990785, "x": 20.2975248353152, "y": 4.671024702565715, "z": null, "yaw": 0.004387592156351304, "pitch": null, "roll": null}, "v": 2.123317499181211, "accelerator_pedal_position": 0.26220490890996306, "brake_pedal_position": 0.0, "acceleration": 0.037530033704916976, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01620940644236753, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.5090785} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26320729959271955, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9506380807604925, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.12369279951826, "gear": 1, "accelerator_pedal_position": 0.26220490890996306, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.5090785} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.90999150276184, "x": 16.2975248353152, "y": -0.328975297434285, "z": null, "yaw": 0.004387592156351304, "pitch": null, "roll": null}, "v": 2.123317499181211, "accelerator_pedal_position": 0.26220490890996306, "brake_pedal_position": 0.0, "acceleration": 0.037530033704916976, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01620940644236753, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.5290785} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26291341677388086, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9506380807604925, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.124986026258664, "gear": 1, "accelerator_pedal_position": 0.26291341677388086, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.5290785} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26291341677388086, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9506380807604925, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.124986026258664, "gear": 1, "accelerator_pedal_position": 0.26291341677388086, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.5390785} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.90999150276184, "x": 16.2975248353152, "y": -0.328975297434285, "z": null, "yaw": 0.004387592156351304, "pitch": null, "roll": null}, "v": 2.123317499181211, "accelerator_pedal_position": 0.26220490890996306, "brake_pedal_position": 0.0, "acceleration": 0.037530033704916976, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01620940644236753, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.5690784} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26291341677388086, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9506380807604925, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1262389833965774, "gear": 1, "accelerator_pedal_position": 0.26291341677388086, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.5690784} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 8.90999150276184, "x": 16.2975248353152, "y": -0.328975297434285, "z": null, "yaw": 0.004387592156351304, "pitch": null, "roll": null}, "v": 2.123317499181211, "accelerator_pedal_position": 0.26220490890996306, "brake_pedal_position": 0.0, "acceleration": 0.037530033704916976, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01620940644236753, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.5890784} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26291341677388086, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9506380807604925, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.127488466020853, "gear": 1, "accelerator_pedal_position": 0.26291341677388086, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.5890784} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502647.6090784, "x": 20.531315927187865, "y": 4.6721397642586515, "z": null, "yaw": 0.0052273321902124616, "pitch": null, "roll": null}, "v": 2.127904189618905, "accelerator_pedal_position": 0.26291341677388086, "brake_pedal_position": 0.0, "acceleration": 0.04153388295383309, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.0162444212385808, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.6090784} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26374389775248497, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9572684270061307, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.127904189618905, "gear": 1, "accelerator_pedal_position": 0.26291341677388086, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.6090784} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.019991397857666, "x": 16.531315927187865, "y": -0.3278602357413485, "z": null, "yaw": 0.0052273321902124616, "pitch": null, "roll": null}, "v": 2.127904189618905, "accelerator_pedal_position": 0.26291341677388086, "brake_pedal_position": 0.0, "acceleration": 0.04153388295383309, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.0162444212385808, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.6290784} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.263505588535452, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9572684270061307, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1288382449064835, "gear": 1, "accelerator_pedal_position": 0.26374389775248497, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.6290784} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.019991397857666, "x": 16.531315927187865, "y": -0.3278602357413485, "z": null, "yaw": 0.0052273321902124616, "pitch": null, "roll": null}, "v": 2.127904189618905, "accelerator_pedal_position": 0.26291341677388086, "brake_pedal_position": 0.0, "acceleration": 0.04153388295383309, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.0162444212385808, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.6490784} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.263505588535452, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9572684270061307, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1297407967833837, "gear": 1, "accelerator_pedal_position": 0.263505588535452, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.6490784} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.019991397857666, "x": 16.531315927187865, "y": -0.3278602357413485, "z": null, "yaw": 0.0052273321902124616, "pitch": null, "roll": null}, "v": 2.127904189618905, "accelerator_pedal_position": 0.26291341677388086, "brake_pedal_position": 0.0, "acceleration": 0.04153388295383309, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.0162444212385808, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.6690784} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.263505588535452, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9572684270061307, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1306416780830375, "gear": 1, "accelerator_pedal_position": 0.263505588535452, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.6690784} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.019991397857666, "x": 16.531315927187865, "y": -0.3278602357413485, "z": null, "yaw": 0.0052273321902124616, "pitch": null, "roll": null}, "v": 2.127904189618905, "accelerator_pedal_position": 0.26291341677388086, "brake_pedal_position": 0.0, "acceleration": 0.04153388295383309, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.0162444212385808, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.6890783} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.263505588535452, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9572684270061307, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1315408915731138, "gear": 1, "accelerator_pedal_position": 0.263505588535452, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.6890783} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.019991397857666, "x": 16.531315927187865, "y": -0.3278602357413485, "z": null, "yaw": 0.0052273321902124616, "pitch": null, "roll": null}, "v": 2.127904189618905, "accelerator_pedal_position": 0.26291341677388086, "brake_pedal_position": 0.0, "acceleration": 0.04153388295383309, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.0162444212385808, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.7090783} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.263505588535452, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9572684270061307, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.132438440017958, "gear": 1, "accelerator_pedal_position": 0.263505588535452, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.7090783} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502647.7190783, "x": 20.76563261632459, "y": 4.673454105882934, "z": null, "yaw": 0.006067072224073619, "pitch": null, "roll": null}, "v": 2.1328865907113683, "accelerator_pedal_position": 0.263505588535452, "brake_pedal_position": 0.0, "acceleration": 0.04477354672264272, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016282456890054392, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.7290783} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26459284138618827, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9603808717669758, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.133334326178595, "gear": 1, "accelerator_pedal_position": 0.263505588535452, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.7290783} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.129991292953491, "x": 16.76563261632459, "y": -0.326545894117066, "z": null, "yaw": 0.006067072224073619, "pitch": null, "roll": null}, "v": 2.1328865907113683, "accelerator_pedal_position": 0.263505588535452, "brake_pedal_position": 0.0, "acceleration": 0.04477354672264272, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016282456890054392, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.7490783} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26427614514974146, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9603808717669758, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1343643964424497, "gear": 1, "accelerator_pedal_position": 0.26459284138618827, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.7490783} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.129991292953491, "x": 16.76563261632459, "y": -0.326545894117066, "z": null, "yaw": 0.006067072224073619, "pitch": null, "roll": null}, "v": 2.1328865907113683, "accelerator_pedal_position": 0.263505588535452, "brake_pedal_position": 0.0, "acceleration": 0.04477354672264272, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016282456890054392, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.7690783} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26427614514974146, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9603808717669758, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1353529895274166, "gear": 1, "accelerator_pedal_position": 0.26427614514974146, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.7690783} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.129991292953491, "x": 16.76563261632459, "y": -0.326545894117066, "z": null, "yaw": 0.006067072224073619, "pitch": null, "roll": null}, "v": 2.1328865907113683, "accelerator_pedal_position": 0.263505588535452, "brake_pedal_position": 0.0, "acceleration": 0.04477354672264272, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016282456890054392, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.7890782} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26427614514974146, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9603808717669758, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1363397505685606, "gear": 1, "accelerator_pedal_position": 0.26427614514974146, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.7890782} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.129991292953491, "x": 16.76563261632459, "y": -0.326545894117066, "z": null, "yaw": 0.006067072224073619, "pitch": null, "roll": null}, "v": 2.1328865907113683, "accelerator_pedal_position": 0.263505588535452, "brake_pedal_position": 0.0, "acceleration": 0.04477354672264272, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016282456890054392, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.8090782} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26427614514974146, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9603808717669758, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1373246825716965, "gear": 1, "accelerator_pedal_position": 0.26427614514974146, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.8090782} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502647.8290782, "x": 21.000515792780938, "y": 4.674968876592769, "z": null, "yaw": 0.006906812257934776, "pitch": null, "roll": null}, "v": 2.1383077885392305, "accelerator_pedal_position": 0.26427614514974146, "brake_pedal_position": 0.0, "acceleration": 0.049086915773647155, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01632384231594109, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.8290782} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2654521715359147, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9326463875378538, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1383077885392305, "gear": 1, "accelerator_pedal_position": 0.26427614514974146, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.8290782} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.239991188049316, "x": 17.000515792780938, "y": -0.32503112340723117, "z": null, "yaw": 0.006906812257934776, "pitch": null, "roll": null}, "v": 2.1383077885392305, "accelerator_pedal_position": 0.26427614514974146, "brake_pedal_position": 0.0, "acceleration": 0.049086915773647155, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01632384231594109, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.8490782} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2651097935551703, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9326463875378538, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.139436006576022, "gear": 1, "accelerator_pedal_position": 0.2654521715359147, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.8490782} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.239991188049316, "x": 17.000515792780938, "y": -0.32503112340723117, "z": null, "yaw": 0.006906812257934776, "pitch": null, "roll": null}, "v": 2.1383077885392305, "accelerator_pedal_position": 0.26427614514974146, "brake_pedal_position": 0.0, "acceleration": 0.049086915773647155, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01632384231594109, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.8690782} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2651097935551703, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9326463875378538, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1405193546035366, "gear": 1, "accelerator_pedal_position": 0.2651097935551703, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.8690782} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.239991188049316, "x": 17.000515792780938, "y": -0.32503112340723117, "z": null, "yaw": 0.006906812257934776, "pitch": null, "roll": null}, "v": 2.1383077885392305, "accelerator_pedal_position": 0.26427614514974146, "brake_pedal_position": 0.0, "acceleration": 0.049086915773647155, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01632384231594109, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.8890781} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2651097935551703, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9326463875378538, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1416006927625366, "gear": 1, "accelerator_pedal_position": 0.2651097935551703, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.8890781} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.239991188049316, "x": 17.000515792780938, "y": -0.32503112340723117, "z": null, "yaw": 0.006906812257934776, "pitch": null, "roll": null}, "v": 2.1383077885392305, "accelerator_pedal_position": 0.26427614514974146, "brake_pedal_position": 0.0, "acceleration": 0.049086915773647155, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01632384231594109, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.9090781} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2651097935551703, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9326463875378538, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.143218938630687, "gear": 1, "accelerator_pedal_position": 0.2651097935551703, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.9090781} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.239991188049316, "x": 17.000515792780938, "y": -0.32503112340723117, "z": null, "yaw": 0.006906812257934776, "pitch": null, "roll": null}, "v": 2.1383077885392305, "accelerator_pedal_position": 0.26427614514974146, "brake_pedal_position": 0.0, "acceleration": 0.049086915773647155, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01632384231594109, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.929078} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2651097935551703, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9326463875378538, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1442952663789723, "gear": 1, "accelerator_pedal_position": 0.2651097935551703, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.929078} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502647.939078, "x": 21.23602524136425, "y": 4.676685466127454, "z": null, "yaw": 0.007746552291795933, "pitch": null, "roll": null}, "v": 2.1442952663789723, "accelerator_pedal_position": 0.2651097935551703, "brake_pedal_position": 0.0, "acceleration": 0.053741424506712876, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016369550723612798, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.949078} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2656776351041094, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8959803662682757, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1448326806240394, "gear": 1, "accelerator_pedal_position": 0.2651097935551703, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.949078} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.349991083145142, "x": 17.23602524136425, "y": -0.32331453387254605, "z": null, "yaw": 0.007746552291795933, "pitch": null, "roll": null}, "v": 2.1442952663789723, "accelerator_pedal_position": 0.2651097935551703, "brake_pedal_position": 0.0, "acceleration": 0.053741424506712876, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016369550723612798, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.969078} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2655279742119838, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8959803662682757, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.145976959107878, "gear": 1, "accelerator_pedal_position": 0.2656776351041094, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.969078} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.349991083145142, "x": 17.23602524136425, "y": -0.32331453387254605, "z": null, "yaw": 0.007746552291795933, "pitch": null, "roll": null}, "v": 2.1442952663789723, "accelerator_pedal_position": 0.2651097935551703, "brake_pedal_position": 0.0, "acceleration": 0.053741424506712876, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016369550723612798, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502647.989078} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2655279742119838, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8959803662682757, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.147100413275037, "gear": 1, "accelerator_pedal_position": 0.2655279742119838, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502647.989078} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.349991083145142, "x": 17.23602524136425, "y": -0.32331453387254605, "z": null, "yaw": 0.007746552291795933, "pitch": null, "roll": null}, "v": 2.1442952663789723, "accelerator_pedal_position": 0.2651097935551703, "brake_pedal_position": 0.0, "acceleration": 0.053741424506712876, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016369550723612798, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.009078} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2655279742119838, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8959803662682757, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1482217802170864, "gear": 1, "accelerator_pedal_position": 0.2655279742119838, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.009078} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.349991083145142, "x": 17.23602524136425, "y": -0.32331453387254605, "z": null, "yaw": 0.007746552291795933, "pitch": null, "roll": null}, "v": 2.1442952663789723, "accelerator_pedal_position": 0.2651097935551703, "brake_pedal_position": 0.0, "acceleration": 0.053741424506712876, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016369550723612798, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.029078} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2655279742119838, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8959803662682757, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.151016088102442, "gear": 1, "accelerator_pedal_position": 0.2655279742119838, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.029078} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502648.049078, "x": 21.47219798369533, "y": 4.678605227221576, "z": null, "yaw": 0.00858629232565709, "pitch": null, "roll": null}, "v": 2.1504582659225018, "accelerator_pedal_position": 0.2655279742119838, "brake_pedal_position": 0.0, "acceleration": 0.055782217994029604, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01641659906402525, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.059078} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26650163816048533, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8616705296229272, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.151016088102442, "gear": 1, "accelerator_pedal_position": 0.2655279742119838, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.059078} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.459990978240967, "x": 17.47219798369533, "y": -0.3213947727784241, "z": null, "yaw": 0.00858629232565709, "pitch": null, "roll": null}, "v": 2.1504582659225018, "accelerator_pedal_position": 0.2655279742119838, "brake_pedal_position": 0.0, "acceleration": 0.055782217994029604, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01641659906402525, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.079078} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.266226009776751, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8616705296229272, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1522518276920053, "gear": 1, "accelerator_pedal_position": 0.26650163816048533, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.079078} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.459990978240967, "x": 17.47219798369533, "y": -0.3213947727784241, "z": null, "yaw": 0.00858629232565709, "pitch": null, "roll": null}, "v": 2.1504582659225018, "accelerator_pedal_position": 0.2655279742119838, "brake_pedal_position": 0.0, "acceleration": 0.055782217994029604, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01641659906402525, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.099078} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.266226009776751, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8616705296229272, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.153450831398111, "gear": 1, "accelerator_pedal_position": 0.266226009776751, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.099078} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.459990978240967, "x": 17.47219798369533, "y": -0.3213947727784241, "z": null, "yaw": 0.00858629232565709, "pitch": null, "roll": null}, "v": 2.1504582659225018, "accelerator_pedal_position": 0.2655279742119838, "brake_pedal_position": 0.0, "acceleration": 0.055782217994029604, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01641659906402525, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.119078} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.266226009776751, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8616705296229272, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.154647604484552, "gear": 1, "accelerator_pedal_position": 0.266226009776751, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.119078} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.459990978240967, "x": 17.47219798369533, "y": -0.3213947727784241, "z": null, "yaw": 0.00858629232565709, "pitch": null, "roll": null}, "v": 2.1504582659225018, "accelerator_pedal_position": 0.2655279742119838, "brake_pedal_position": 0.0, "acceleration": 0.055782217994029604, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01641659906402525, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.139078} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.266226009776751, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8616705296229272, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.156438589526503, "gear": 1, "accelerator_pedal_position": 0.266226009776751, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.139078} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502648.159078, "x": 21.70906730956616, "y": 4.680729576878797, "z": null, "yaw": 0.009426032359518248, "pitch": null, "roll": null}, "v": 2.1570344731037467, "accelerator_pedal_position": 0.266226009776751, "brake_pedal_position": 0.0, "acceleration": 0.05953286026792659, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01646680183167122, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.159078} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26742567748428814, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8045939456125569, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1570344731037467, "gear": 1, "accelerator_pedal_position": 0.266226009776751, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.159078} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.569990873336792, "x": 17.70906730956616, "y": -0.31927042312120335, "z": null, "yaw": 0.009426032359518248, "pitch": null, "roll": null}, "v": 2.1570344731037467, "accelerator_pedal_position": 0.266226009776751, "brake_pedal_position": 0.0, "acceleration": 0.05953286026792659, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01646680183167122, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.1790779} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.267081385100242, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8045939456125569, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1583744643982774, "gear": 1, "accelerator_pedal_position": 0.26742567748428814, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.1790779} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.569990873336792, "x": 17.70906730956616, "y": -0.31927042312120335, "z": null, "yaw": 0.009426032359518248, "pitch": null, "roll": null}, "v": 2.1570344731037467, "accelerator_pedal_position": 0.266226009776751, "brake_pedal_position": 0.0, "acceleration": 0.05953286026792659, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01646680183167122, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.1990778} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.267081385100242, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8045939456125569, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1596689436657903, "gear": 1, "accelerator_pedal_position": 0.267081385100242, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.1990778} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.569990873336792, "x": 17.70906730956616, "y": -0.31927042312120335, "z": null, "yaw": 0.009426032359518248, "pitch": null, "roll": null}, "v": 2.1570344731037467, "accelerator_pedal_position": 0.266226009776751, "brake_pedal_position": 0.0, "acceleration": 0.05953286026792659, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01646680183167122, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.2190778} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.267081385100242, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8045939456125569, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.160961011487112, "gear": 1, "accelerator_pedal_position": 0.267081385100242, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.2190778} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.569990873336792, "x": 17.70906730956616, "y": -0.31927042312120335, "z": null, "yaw": 0.009426032359518248, "pitch": null, "roll": null}, "v": 2.1570344731037467, "accelerator_pedal_position": 0.266226009776751, "brake_pedal_position": 0.0, "acceleration": 0.05953286026792659, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01646680183167122, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.2390778} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.267081385100242, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8045939456125569, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.162894600123189, "gear": 1, "accelerator_pedal_position": 0.267081385100242, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.2390778} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.569990873336792, "x": 17.70906730956616, "y": -0.31927042312120335, "z": null, "yaw": 0.009426032359518248, "pitch": null, "roll": null}, "v": 2.1570344731037467, "accelerator_pedal_position": 0.266226009776751, "brake_pedal_position": 0.0, "acceleration": 0.05953286026792659, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01646680183167122, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.2590778} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.267081385100242, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8045939456125569, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.163537928086768, "gear": 1, "accelerator_pedal_position": 0.267081385100242, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.2590778} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502648.2690778, "x": 21.946689576017263, "y": 4.683060241686394, "z": null, "yaw": 0.010265772393379405, "pitch": null, "roll": null}, "v": 2.164180656054863, "accelerator_pedal_position": 0.267081385100242, "brake_pedal_position": 0.0, "acceleration": 0.06421284495334861, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01652135579451984, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.2790778} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26821920246773806, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7550669954905098, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.165535427497547, "gear": 1, "accelerator_pedal_position": 0.26821920246773806, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.2790778} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.679990768432617, "x": 17.946689576017263, "y": -0.3169397583136062, "z": null, "yaw": 0.010265772393379405, "pitch": null, "roll": null}, "v": 2.164180656054863, "accelerator_pedal_position": 0.267081385100242, "brake_pedal_position": 0.0, "acceleration": 0.06421284495334861, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01652135579451984, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.2990777} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26789693988342356, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7550669954905098, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.166247405569257, "gear": 1, "accelerator_pedal_position": 0.26821920246773806, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.2990777} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.679990768432617, "x": 17.946689576017263, "y": -0.3169397583136062, "z": null, "yaw": 0.010265772393379405, "pitch": null, "roll": null}, "v": 2.164180656054863, "accelerator_pedal_position": 0.267081385100242, "brake_pedal_position": 0.0, "acceleration": 0.06421284495334861, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01652135579451984, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.3190777} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26789693988342356, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7550669954905098, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.167629105000766, "gear": 1, "accelerator_pedal_position": 0.26789693988342356, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.3190777} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.679990768432617, "x": 17.946689576017263, "y": -0.3169397583136062, "z": null, "yaw": 0.010265772393379405, "pitch": null, "roll": null}, "v": 2.164180656054863, "accelerator_pedal_position": 0.267081385100242, "brake_pedal_position": 0.0, "acceleration": 0.06421284495334861, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01652135579451984, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.3390777} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26789693988342356, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7550669954905098, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.169008226123013, "gear": 1, "accelerator_pedal_position": 0.26789693988342356, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.3390777} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.679990768432617, "x": 17.946689576017263, "y": -0.3169397583136062, "z": null, "yaw": 0.010265772393379405, "pitch": null, "roll": null}, "v": 2.164180656054863, "accelerator_pedal_position": 0.267081385100242, "brake_pedal_position": 0.0, "acceleration": 0.06421284495334861, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01652135579451984, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.3590777} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26789693988342356, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7550669954905098, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.170384772986796, "gear": 1, "accelerator_pedal_position": 0.26789693988342356, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.3590777} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502648.3790777, "x": 22.185114401325777, "y": 4.685599017464579, "z": null, "yaw": 0.011105512427240562, "pitch": null, "roll": null}, "v": 2.171758749639611, "accelerator_pedal_position": 0.26789693988342356, "brake_pedal_position": 0.0, "acceleration": 0.06860257612305454, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01657920696327856, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.3790777} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26878618647485, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7191865282891233, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.171758749639611, "gear": 1, "accelerator_pedal_position": 0.26789693988342356, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.3790777} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.789990663528442, "x": 18.185114401325777, "y": -0.31440098253542104, "z": null, "yaw": 0.011105512427240562, "pitch": null, "roll": null}, "v": 2.171758749639611, "accelerator_pedal_position": 0.26789693988342356, "brake_pedal_position": 0.0, "acceleration": 0.06860257612305454, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01657920696327856, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.3990777} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26854367106728266, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7191865282891233, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.173241264012313, "gear": 1, "accelerator_pedal_position": 0.26878618647485, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.3990777} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.789990663528442, "x": 18.185114401325777, "y": -0.31440098253542104, "z": null, "yaw": 0.011105512427240562, "pitch": null, "roll": null}, "v": 2.171758749639611, "accelerator_pedal_position": 0.26789693988342356, "brake_pedal_position": 0.0, "acceleration": 0.06860257612305454, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01657920696327856, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.4190776} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26854367106728266, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7191865282891233, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1754144145035745, "gear": 1, "accelerator_pedal_position": 0.26854367106728266, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.4190776} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.789990663528442, "x": 18.185114401325777, "y": -0.31440098253542104, "z": null, "yaw": 0.011105512427240562, "pitch": null, "roll": null}, "v": 2.171758749639611, "accelerator_pedal_position": 0.26789693988342356, "brake_pedal_position": 0.0, "acceleration": 0.06860257612305454, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01657920696327856, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.4390776} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26854367106728266, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7191865282891233, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.178302477534404, "gear": 1, "accelerator_pedal_position": 0.26854367106728266, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.4390776} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.789990663528442, "x": 18.185114401325777, "y": -0.31440098253542104, "z": null, "yaw": 0.011105512427240562, "pitch": null, "roll": null}, "v": 2.171758749639611, "accelerator_pedal_position": 0.26789693988342356, "brake_pedal_position": 0.0, "acceleration": 0.06860257612305454, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01657920696327856, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.4690776} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26854367106728266, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7191865282891233, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.178302477534404, "gear": 1, "accelerator_pedal_position": 0.26854367106728266, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.4690776} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502648.4890776, "x": 22.424393363773532, "y": 4.688347847556337, "z": null, "yaw": 0.01194525246110172, "pitch": null, "roll": null}, "v": 2.1797424595691806, "accelerator_pedal_position": 0.26854367106728266, "brake_pedal_position": 0.0, "acceleration": 0.07189804929157051, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016640154607338514, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.4890776} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2691529180980447, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7124279571080151, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1804995180015188, "gear": 1, "accelerator_pedal_position": 0.2691529180980447, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.4890776} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.899990558624268, "x": 18.424393363773532, "y": -0.3116521524436626, "z": null, "yaw": 0.01194525246110172, "pitch": null, "roll": null}, "v": 2.1797424595691806, "accelerator_pedal_position": 0.26854367106728266, "brake_pedal_position": 0.0, "acceleration": 0.07189804929157051, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016640154607338514, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.5090775} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2689998581371078, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7124279571080151, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1812558678088454, "gear": 1, "accelerator_pedal_position": 0.2691529180980447, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.5090775} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.899990558624268, "x": 18.424393363773532, "y": -0.3116521524436626, "z": null, "yaw": 0.01194525246110172, "pitch": null, "roll": null}, "v": 2.1797424595691806, "accelerator_pedal_position": 0.26854367106728266, "brake_pedal_position": 0.0, "acceleration": 0.07189804929157051, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016640154607338514, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.5290775} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2689998581371078, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7124279571080151, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.182747320206295, "gear": 1, "accelerator_pedal_position": 0.2689998581371078, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.5290775} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.899990558624268, "x": 18.424393363773532, "y": -0.3116521524436626, "z": null, "yaw": 0.01194525246110172, "pitch": null, "roll": null}, "v": 2.1797424595691806, "accelerator_pedal_position": 0.26854367106728266, "brake_pedal_position": 0.0, "acceleration": 0.07189804929157051, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016640154607338514, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.5490775} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2689998581371078, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7124279571080151, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1842359804963865, "gear": 1, "accelerator_pedal_position": 0.2689998581371078, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.5490775} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.899990558624268, "x": 18.424393363773532, "y": -0.3116521524436626, "z": null, "yaw": 0.01194525246110172, "pitch": null, "roll": null}, "v": 2.1797424595691806, "accelerator_pedal_position": 0.26854367106728266, "brake_pedal_position": 0.0, "acceleration": 0.07189804929157051, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016640154607338514, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.5690775} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2689998581371078, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7124279571080151, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.185721853020119, "gear": 1, "accelerator_pedal_position": 0.2689998581371078, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.5690775} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 9.899990558624268, "x": 18.424393363773532, "y": -0.3116521524436626, "z": null, "yaw": 0.01194525246110172, "pitch": null, "roll": null}, "v": 2.1797424595691806, "accelerator_pedal_position": 0.26854367106728266, "brake_pedal_position": 0.0, "acceleration": 0.07189804929157051, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016640154607338514, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.5890775} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2689998581371078, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7124279571080151, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1872049421153394, "gear": 1, "accelerator_pedal_position": 0.2689998581371078, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.5890775} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502648.5990775, "x": 22.66455855678383, "y": 4.691308565051115, "z": null, "yaw": 0.012784992494962876, "pitch": null, "roll": null}, "v": 2.1879454442319695, "accelerator_pedal_position": 0.2689998581371078, "brake_pedal_position": 0.0, "acceleration": 0.0739807884759709, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01670277619477936, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.6090775} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27058927897965923, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.660149257051786, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1886852521167293, "gear": 1, "accelerator_pedal_position": 0.2689998581371078, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.6090775} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.009990453720093, "x": 18.66455855678383, "y": -0.3086914349488854, "z": null, "yaw": 0.012784992494962876, "pitch": null, "roll": null}, "v": 2.1879454442319695, "accelerator_pedal_position": 0.2689998581371078, "brake_pedal_position": 0.0, "acceleration": 0.0739807884759709, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01670277619477936, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.6290774} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27013100616599517, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.660149257051786, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.190361371791763, "gear": 1, "accelerator_pedal_position": 0.27058927897965923, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.6290774} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.009990453720093, "x": 18.66455855678383, "y": -0.3086914349488854, "z": null, "yaw": 0.012784992494962876, "pitch": null, "roll": null}, "v": 2.1879454442319695, "accelerator_pedal_position": 0.2689998581371078, "brake_pedal_position": 0.0, "acceleration": 0.0739807884759709, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01670277619477936, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.6490774} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27013100616599517, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.660149257051786, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1919770913510797, "gear": 1, "accelerator_pedal_position": 0.27013100616599517, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.6490774} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.009990453720093, "x": 18.66455855678383, "y": -0.3086914349488854, "z": null, "yaw": 0.012784992494962876, "pitch": null, "roll": null}, "v": 2.1879454442319695, "accelerator_pedal_position": 0.2689998581371078, "brake_pedal_position": 0.0, "acceleration": 0.0739807884759709, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01670277619477936, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.6690774} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27013100616599517, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.660149257051786, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1935897802264455, "gear": 1, "accelerator_pedal_position": 0.27013100616599517, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.6690774} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.009990453720093, "x": 18.66455855678383, "y": -0.3086914349488854, "z": null, "yaw": 0.012784992494962876, "pitch": null, "roll": null}, "v": 2.1879454442319695, "accelerator_pedal_position": 0.2689998581371078, "brake_pedal_position": 0.0, "acceleration": 0.0739807884759709, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01670277619477936, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.6890774} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27013100616599517, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.660149257051786, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.195199443062843, "gear": 1, "accelerator_pedal_position": 0.27013100616599517, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.6890774} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502648.7090774, "x": 22.90565398542263, "y": 4.694483245851452, "z": null, "yaw": 0.013624732528824034, "pitch": null, "roll": null}, "v": 2.196806084502393, "accelerator_pedal_position": 0.27013100616599517, "brake_pedal_position": 0.0, "acceleration": 0.08021891458328273, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01677041832533133, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.7090774} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2710401300451377, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6020421417641109, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.196806084502393, "gear": 1, "accelerator_pedal_position": 0.27013100616599517, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.7090774} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.119990348815918, "x": 18.90565398542263, "y": -0.30551675414854795, "z": null, "yaw": 0.013624732528824034, "pitch": null, "roll": null}, "v": 2.196806084502393, "accelerator_pedal_position": 0.27013100616599517, "brake_pedal_position": 0.0, "acceleration": 0.08021891458328273, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01677041832533133, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.7290773} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2707976061275563, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6020421417641109, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1985232962850576, "gear": 1, "accelerator_pedal_position": 0.2710401300451377, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.7290773} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.119990348815918, "x": 18.90565398542263, "y": -0.30551675414854795, "z": null, "yaw": 0.013624732528824034, "pitch": null, "roll": null}, "v": 2.196806084502393, "accelerator_pedal_position": 0.27013100616599517, "brake_pedal_position": 0.0, "acceleration": 0.08021891458328273, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01677041832533133, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.7490773} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2707976061275563, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6020421417641109, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.200206981291696, "gear": 1, "accelerator_pedal_position": 0.2707976061275563, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.7490773} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.119990348815918, "x": 18.90565398542263, "y": -0.30551675414854795, "z": null, "yaw": 0.013624732528824034, "pitch": null, "roll": null}, "v": 2.196806084502393, "accelerator_pedal_position": 0.27013100616599517, "brake_pedal_position": 0.0, "acceleration": 0.08021891458328273, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01677041832533133, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.7690773} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2707976061275563, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6020421417641109, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.201887502602306, "gear": 1, "accelerator_pedal_position": 0.2707976061275563, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.7690773} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.119990348815918, "x": 18.90565398542263, "y": -0.30551675414854795, "z": null, "yaw": 0.013624732528824034, "pitch": null, "roll": null}, "v": 2.196806084502393, "accelerator_pedal_position": 0.27013100616599517, "brake_pedal_position": 0.0, "acceleration": 0.08021891458328273, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01677041832533133, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.7890773} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2707976061275563, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6020421417641109, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2044023631714564, "gear": 1, "accelerator_pedal_position": 0.2707976061275563, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.7890773} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.119990348815918, "x": 18.90565398542263, "y": -0.30551675414854795, "z": null, "yaw": 0.013624732528824034, "pitch": null, "roll": null}, "v": 2.196806084502393, "accelerator_pedal_position": 0.27013100616599517, "brake_pedal_position": 0.0, "acceleration": 0.08021891458328273, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01677041832533133, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.7990773} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2707976061275563, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6020421417641109, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2044023631714564, "gear": 1, "accelerator_pedal_position": 0.2707976061275563, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.7990773} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502648.8190773, "x": 23.147744578853096, "y": 4.697874363902222, "z": null, "yaw": 0.014464472562685191, "pitch": null, "roll": null}, "v": 2.2060749963041597, "accelerator_pedal_position": 0.2707976061275563, "brake_pedal_position": 0.0, "acceleration": 0.08351361958883496, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016841177200879257, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.8290772} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2727714806946578, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5298673068854388, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.206910132500048, "gear": 1, "accelerator_pedal_position": 0.2707976061275563, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.8290772} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.229990243911743, "x": 19.147744578853096, "y": -0.3021256360977782, "z": null, "yaw": 0.014464472562685191, "pitch": null, "roll": null}, "v": 2.2060749963041597, "accelerator_pedal_position": 0.2707976061275563, "brake_pedal_position": 0.0, "acceleration": 0.08351361958883496, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016841177200879257, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.8490772} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.272198221754291, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5298673068854388, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2088246653182715, "gear": 1, "accelerator_pedal_position": 0.2727714806946578, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.8490772} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.229990243911743, "x": 19.147744578853096, "y": -0.3021256360977782, "z": null, "yaw": 0.014464472562685191, "pitch": null, "roll": null}, "v": 2.2060749963041597, "accelerator_pedal_position": 0.2707976061275563, "brake_pedal_position": 0.0, "acceleration": 0.08351361958883496, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016841177200879257, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.8690772} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.272198221754291, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5298673068854388, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2106639705025364, "gear": 1, "accelerator_pedal_position": 0.272198221754291, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.8690772} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.229990243911743, "x": 19.147744578853096, "y": -0.3021256360977782, "z": null, "yaw": 0.014464472562685191, "pitch": null, "roll": null}, "v": 2.2060749963041597, "accelerator_pedal_position": 0.2707976061275563, "brake_pedal_position": 0.0, "acceleration": 0.08351361958883496, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016841177200879257, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.8890772} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.272198221754291, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5298673068854388, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2124998119180748, "gear": 1, "accelerator_pedal_position": 0.272198221754291, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.8890772} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.229990243911743, "x": 19.147744578853096, "y": -0.3021256360977782, "z": null, "yaw": 0.014464472562685191, "pitch": null, "roll": null}, "v": 2.2060749963041597, "accelerator_pedal_position": 0.2707976061275563, "brake_pedal_position": 0.0, "acceleration": 0.08351361958883496, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016841177200879257, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.9090772} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.272198221754291, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5298673068854388, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2143321947403445, "gear": 1, "accelerator_pedal_position": 0.272198221754291, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.9090772} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502648.9290771, "x": 23.390889414743697, "y": 4.701484476732939, "z": null, "yaw": 0.015304212596546348, "pitch": null, "roll": null}, "v": 2.2161611241426686, "accelerator_pedal_position": 0.272198221754291, "brake_pedal_position": 0.0, "acceleration": 0.0913171284755721, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016918174703903232, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.9290771} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2727416792699258, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5134641937581695, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2161611241426686, "gear": 1, "accelerator_pedal_position": 0.272198221754291, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.9290771} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.339990139007568, "x": 19.390889414743697, "y": -0.2985155232670609, "z": null, "yaw": 0.015304212596546348, "pitch": null, "roll": null}, "v": 2.2161611241426686, "accelerator_pedal_position": 0.272198221754291, "brake_pedal_position": 0.0, "acceleration": 0.0913171284755721, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016918174703903232, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.9490771} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2726193656551126, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5134641937581695, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.21805450544143, "gear": 1, "accelerator_pedal_position": 0.2727416792699258, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.9490771} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.339990139007568, "x": 19.390889414743697, "y": -0.2985155232670609, "z": null, "yaw": 0.015304212596546348, "pitch": null, "roll": null}, "v": 2.2161611241426686, "accelerator_pedal_position": 0.272198221754291, "brake_pedal_position": 0.0, "acceleration": 0.0913171284755721, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016918174703903232, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.969077} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2726193656551126, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5134641937581695, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2199290335670305, "gear": 1, "accelerator_pedal_position": 0.2726193656551126, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.969077} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.339990139007568, "x": 19.390889414743697, "y": -0.2985155232670609, "z": null, "yaw": 0.015304212596546348, "pitch": null, "roll": null}, "v": 2.2161611241426686, "accelerator_pedal_position": 0.272198221754291, "brake_pedal_position": 0.0, "acceleration": 0.0913171284755721, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016918174703903232, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502648.989077} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2726193656551126, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5134641937581695, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.22180002465837, "gear": 1, "accelerator_pedal_position": 0.2726193656551126, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502648.989077} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.339990139007568, "x": 19.390889414743697, "y": -0.2985155232670609, "z": null, "yaw": 0.015304212596546348, "pitch": null, "roll": null}, "v": 2.2161611241426686, "accelerator_pedal_position": 0.272198221754291, "brake_pedal_position": 0.0, "acceleration": 0.0913171284755721, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016918174703903232, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.009077} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2726193656551126, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5134641937581695, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2236674839898716, "gear": 1, "accelerator_pedal_position": 0.2726193656551126, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.009077} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.339990139007568, "x": 19.390889414743697, "y": -0.2985155232670609, "z": null, "yaw": 0.015304212596546348, "pitch": null, "roll": null}, "v": 2.2161611241426686, "accelerator_pedal_position": 0.272198221754291, "brake_pedal_position": 0.0, "acceleration": 0.0913171284755721, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016918174703903232, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.029077} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2726193656551126, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5134641937581695, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.225531416833927, "gear": 1, "accelerator_pedal_position": 0.2726193656551126, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.029077} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502649.039077, "x": 23.63515378414241, "y": 4.705316379210313, "z": null, "yaw": 0.016143952630407493, "pitch": null, "roll": null}, "v": 2.2264620624702234, "accelerator_pedal_position": 0.2726193656551126, "brake_pedal_position": 0.0, "acceleration": 0.09297659906475075, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016996812070266713, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.049077} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2777700552682761, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.35407772775433866, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.227391828460871, "gear": 1, "accelerator_pedal_position": 0.2726193656551126, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.049077} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.449990034103394, "x": 19.63515378414241, "y": -0.29468362078968724, "z": null, "yaw": 0.016143952630407493, "pitch": null, "roll": null}, "v": 2.2264620624702234, "accelerator_pedal_position": 0.2726193656551126, "brake_pedal_position": 0.0, "acceleration": 0.09297659906475075, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016996812070266713, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.069077} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27620909768026675, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.35407772775433866, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.229892255903829, "gear": 1, "accelerator_pedal_position": 0.2777700552682761, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.069077} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.449990034103394, "x": 19.63515378414241, "y": -0.29468362078968724, "z": null, "yaw": 0.016143952630407493, "pitch": null, "roll": null}, "v": 2.2264620624702234, "accelerator_pedal_position": 0.2726193656551126, "brake_pedal_position": 0.0, "acceleration": 0.09297659906475075, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016996812070266713, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.089077} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27620909768026675, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.35407772775433866, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.233341631736856, "gear": 1, "accelerator_pedal_position": 0.27620909768026675, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.089077} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.449990034103394, "x": 19.63515378414241, "y": -0.29468362078968724, "z": null, "yaw": 0.016143952630407493, "pitch": null, "roll": null}, "v": 2.2264620624702234, "accelerator_pedal_position": 0.2726193656551126, "brake_pedal_position": 0.0, "acceleration": 0.09297659906475075, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016996812070266713, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.109077} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27620909768026675, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.35407772775433866, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.234489248041599, "gear": 1, "accelerator_pedal_position": 0.27620909768026675, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.109077} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.449990034103394, "x": 19.63515378414241, "y": -0.29468362078968724, "z": null, "yaw": 0.016143952630407493, "pitch": null, "roll": null}, "v": 2.2264620624702234, "accelerator_pedal_position": 0.2726193656551126, "brake_pedal_position": 0.0, "acceleration": 0.09297659906475075, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.016996812070266713, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.129077} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27620909768026675, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.35407772775433866, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2390688554804985, "gear": 1, "accelerator_pedal_position": 0.27620909768026675, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.129077} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502649.149077, "x": 23.880658231328745, "y": 4.709373967027376, "z": null, "yaw": 0.01698369266426863, "pitch": null, "roll": null}, "v": 2.2390688554804985, "accelerator_pedal_position": 0.27620909768026675, "brake_pedal_position": 0.0, "acceleration": 0.11421912433181469, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017093052331987886, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.149077} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27609497515964787, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3492332555259885, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2390688554804985, "gear": 1, "accelerator_pedal_position": 0.27620909768026675, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.149077} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.559989929199219, "x": 19.880658231328745, "y": -0.29062603297262424, "z": null, "yaw": 0.01698369266426863, "pitch": null, "roll": null}, "v": 2.2390688554804985, "accelerator_pedal_position": 0.27620909768026675, "brake_pedal_position": 0.0, "acceleration": 0.11421912433181469, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017093052331987886, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.179077} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2761903035043509, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3492332555259885, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.242470804141474, "gear": 1, "accelerator_pedal_position": 0.27609497515964787, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.179077} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.559989929199219, "x": 19.880658231328745, "y": -0.29062603297262424, "z": null, "yaw": 0.01698369266426863, "pitch": null, "roll": null}, "v": 2.2390688554804985, "accelerator_pedal_position": 0.27620909768026675, "brake_pedal_position": 0.0, "acceleration": 0.11421912433181469, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017093052331987886, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.199077} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2761903035043509, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3492332555259885, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.24474530689628, "gear": 1, "accelerator_pedal_position": 0.2761903035043509, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.199077} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.559989929199219, "x": 19.880658231328745, "y": -0.29062603297262424, "z": null, "yaw": 0.01698369266426863, "pitch": null, "roll": null}, "v": 2.2390688554804985, "accelerator_pedal_position": 0.27620909768026675, "brake_pedal_position": 0.0, "acceleration": 0.11421912433181469, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017093052331987886, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.2190769} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2761903035043509, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3492332555259885, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2470154954418677, "gear": 1, "accelerator_pedal_position": 0.2761903035043509, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.2190769} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.559989929199219, "x": 19.880658231328745, "y": -0.29062603297262424, "z": null, "yaw": 0.01698369266426863, "pitch": null, "roll": null}, "v": 2.2390688554804985, "accelerator_pedal_position": 0.27620909768026675, "brake_pedal_position": 0.0, "acceleration": 0.11421912433181469, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017093052331987886, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.2390769} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2761903035043509, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3492332555259885, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2492813759007757, "gear": 1, "accelerator_pedal_position": 0.2761903035043509, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.2390769} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502649.2590768, "x": 24.127542741543518, "y": 4.713661739800347, "z": null, "yaw": 0.01782343269812977, "pitch": null, "roll": null}, "v": 2.2515429543956538, "accelerator_pedal_position": 0.2761903035043509, "brake_pedal_position": 0.0, "acceleration": 0.11291779242752342, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017188279606946067, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.2590768} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2760666523850467, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.34372825757861963, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2515429543956538, "gear": 1, "accelerator_pedal_position": 0.2761903035043509, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.2590768} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.669989824295044, "x": 20.127542741543518, "y": -0.2863382601996527, "z": null, "yaw": 0.01782343269812977, "pitch": null, "roll": null}, "v": 2.2515429543956538, "accelerator_pedal_position": 0.2761903035043509, "brake_pedal_position": 0.0, "acceleration": 0.11291779242752342, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017188279606946067, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.2790768} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27616448683921535, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.34372825757861963, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.253784788005214, "gear": 1, "accelerator_pedal_position": 0.2760666523850467, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.2790768} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.669989824295044, "x": 20.127542741543518, "y": -0.2863382601996527, "z": null, "yaw": 0.01782343269812977, "pitch": null, "roll": null}, "v": 2.2515429543956538, "accelerator_pedal_position": 0.2761903035043509, "brake_pedal_position": 0.0, "acceleration": 0.11291779242752342, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017188279606946067, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.2990768} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27616448683921535, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.34372825757861963, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2560345847576424, "gear": 1, "accelerator_pedal_position": 0.27616448683921535, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.2990768} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.669989824295044, "x": 20.127542741543518, "y": -0.2863382601996527, "z": null, "yaw": 0.01782343269812977, "pitch": null, "roll": null}, "v": 2.2515429543956538, "accelerator_pedal_position": 0.2761903035043509, "brake_pedal_position": 0.0, "acceleration": 0.11291779242752342, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017188279606946067, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.3190768} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27616448683921535, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.34372825757861963, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.258280104007127, "gear": 1, "accelerator_pedal_position": 0.27616448683921535, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.3190768} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.669989824295044, "x": 20.127542741543518, "y": -0.2863382601996527, "z": null, "yaw": 0.01782343269812977, "pitch": null, "roll": null}, "v": 2.2515429543956538, "accelerator_pedal_position": 0.2761903035043509, "brake_pedal_position": 0.0, "acceleration": 0.11291779242752342, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017188279606946067, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.3390768} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27616448683921535, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.34372825757861963, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.260521351870432, "gear": 1, "accelerator_pedal_position": 0.27616448683921535, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.3390768} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.669989824295044, "x": 20.127542741543518, "y": -0.2863382601996527, "z": null, "yaw": 0.01782343269812977, "pitch": null, "roll": null}, "v": 2.2515429543956538, "accelerator_pedal_position": 0.2761903035043509, "brake_pedal_position": 0.0, "acceleration": 0.11291779242752342, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017188279606946067, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.3590767} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27616448683921535, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.34372825757861963, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.262758334464191, "gear": 1, "accelerator_pedal_position": 0.27616448683921535, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.3590767} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502649.3690767, "x": 24.375788551839143, "y": 4.718181681299291, "z": null, "yaw": 0.018663172731990908, "pitch": null, "roll": null}, "v": 2.263875228196391, "accelerator_pedal_position": 0.27616448683921535, "brake_pedal_position": 0.0, "acceleration": 0.11158297084686364, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017282424188937124, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.3790767} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2791923640399333, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.2510895976343659, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2649910579048598, "gear": 1, "accelerator_pedal_position": 0.27616448683921535, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.3790767} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.77998971939087, "x": 20.375788551839143, "y": -0.28181831870070884, "z": null, "yaw": 0.018663172731990908, "pitch": null, "roll": null}, "v": 2.263875228196391, "accelerator_pedal_position": 0.27616448683921535, "brake_pedal_position": 0.0, "acceleration": 0.11158297084686364, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017282424188937124, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.3990767} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27830482520397126, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.2510895976343659, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.267597832565395, "gear": 1, "accelerator_pedal_position": 0.2791923640399333, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.3990767} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.77998971939087, "x": 20.375788551839143, "y": -0.28181831870070884, "z": null, "yaw": 0.018663172731990908, "pitch": null, "roll": null}, "v": 2.263875228196391, "accelerator_pedal_position": 0.27616448683921535, "brake_pedal_position": 0.0, "acceleration": 0.11158297084686364, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017282424188937124, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.4190767} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27830482520397126, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.2510895976343659, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.270088749606413, "gear": 1, "accelerator_pedal_position": 0.27830482520397126, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.4190767} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.77998971939087, "x": 20.375788551839143, "y": -0.28181831870070884, "z": null, "yaw": 0.018663172731990908, "pitch": null, "roll": null}, "v": 2.263875228196391, "accelerator_pedal_position": 0.27616448683921535, "brake_pedal_position": 0.0, "acceleration": 0.11158297084686364, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017282424188937124, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.4390767} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27830482520397126, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.2510895976343659, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2750563406620423, "gear": 1, "accelerator_pedal_position": 0.27830482520397126, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.4390767} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.77998971939087, "x": 20.375788551839143, "y": -0.28181831870070884, "z": null, "yaw": 0.018663172731990908, "pitch": null, "roll": null}, "v": 2.263875228196391, "accelerator_pedal_position": 0.27616448683921535, "brake_pedal_position": 0.0, "acceleration": 0.11158297084686364, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017282424188937124, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.4590766} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27830482520397126, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.2510895976343659, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2775330278506005, "gear": 1, "accelerator_pedal_position": 0.27830482520397126, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.4590766} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502649.4790766, "x": 24.625450928566682, "y": 4.722937149327967, "z": null, "yaw": 0.019502912765852046, "pitch": null, "roll": null}, "v": 2.2775330278506005, "accelerator_pedal_position": 0.27830482520397126, "brake_pedal_position": 0.0, "acceleration": 0.12365693920278703, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01738668783570162, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.4890766} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27785772154930394, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.24100555304958743, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2787695972426283, "gear": 1, "accelerator_pedal_position": 0.27830482520397126, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.4890766} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27785772154930394, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.24100555304958743, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.279977040953107, "gear": 1, "accelerator_pedal_position": 0.27785772154930394, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.4990766} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.889989614486694, "x": 20.625450928566682, "y": -0.2770628506720332, "z": null, "yaw": 0.019502912765852046, "pitch": null, "roll": null}, "v": 2.2775330278506005, "accelerator_pedal_position": 0.27830482520397126, "brake_pedal_position": 0.0, "acceleration": 0.12365693920278703, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01738668783570162, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.5290766} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2780625988969056, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.24100555304958743, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2848080871017373, "gear": 1, "accelerator_pedal_position": 0.2780625988969056, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.5290766} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.889989614486694, "x": 20.625450928566682, "y": -0.2770628506720332, "z": null, "yaw": 0.019502912765852046, "pitch": null, "roll": null}, "v": 2.2775330278506005, "accelerator_pedal_position": 0.27830482520397126, "brake_pedal_position": 0.0, "acceleration": 0.12365693920278703, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01738668783570162, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.5390766} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2780625988969056, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.24100555304958743, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2848080871017373, "gear": 1, "accelerator_pedal_position": 0.2780625988969056, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.5390766} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.889989614486694, "x": 20.625450928566682, "y": -0.2770628506720332, "z": null, "yaw": 0.019502912765852046, "pitch": null, "roll": null}, "v": 2.2775330278506005, "accelerator_pedal_position": 0.27830482520397126, "brake_pedal_position": 0.0, "acceleration": 0.12365693920278703, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01738668783570162, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.5590765} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2780625988969056, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.24100555304958743, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.287235871925668, "gear": 1, "accelerator_pedal_position": 0.2780625988969056, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.5590765} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.889989614486694, "x": 20.625450928566682, "y": -0.2770628506720332, "z": null, "yaw": 0.019502912765852046, "pitch": null, "roll": null}, "v": 2.2775330278506005, "accelerator_pedal_position": 0.27830482520397126, "brake_pedal_position": 0.0, "acceleration": 0.12365693920278703, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01738668783570162, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.5790765} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2780625988969056, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.24100555304958743, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2908688397001153, "gear": 1, "accelerator_pedal_position": 0.2780625988969056, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.5790765} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502649.5890765, "x": 24.87659743430749, "y": 4.7279318603681, "z": null, "yaw": 0.020342652799713184, "pitch": null, "roll": null}, "v": 2.2908688397001153, "accelerator_pedal_position": 0.2780625988969056, "brake_pedal_position": 0.0, "acceleration": 0.1208670007135646, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017488493427465963, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.5990765} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2776584686384961, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.2295771930015559, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.292077509707251, "gear": 1, "accelerator_pedal_position": 0.2780625988969056, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.5990765} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.99998950958252, "x": 20.87659743430749, "y": -0.2720681396318998, "z": null, "yaw": 0.020342652799713184, "pitch": null, "roll": null}, "v": 2.2908688397001153, "accelerator_pedal_position": 0.2780625988969056, "brake_pedal_position": 0.0, "acceleration": 0.1208670007135646, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017488493427465963, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.6190765} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27784856067238617, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.2295771930015559, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2944408836853007, "gear": 1, "accelerator_pedal_position": 0.2776584686384961, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.6190765} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.99998950958252, "x": 20.87659743430749, "y": -0.2720681396318998, "z": null, "yaw": 0.020342652799713184, "pitch": null, "roll": null}, "v": 2.2908688397001153, "accelerator_pedal_position": 0.2780625988969056, "brake_pedal_position": 0.0, "acceleration": 0.1208670007135646, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017488493427465963, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.6390765} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27784856067238617, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.2295771930015559, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.299201503683212, "gear": 1, "accelerator_pedal_position": 0.27784856067238617, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.6390765} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.99998950958252, "x": 20.87659743430749, "y": -0.2720681396318998, "z": null, "yaw": 0.020342652799713184, "pitch": null, "roll": null}, "v": 2.2908688397001153, "accelerator_pedal_position": 0.2780625988969056, "brake_pedal_position": 0.0, "acceleration": 0.1208670007135646, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017488493427465963, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.6590765} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27784856067238617, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.2295771930015559, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.299201503683212, "gear": 1, "accelerator_pedal_position": 0.27784856067238617, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.6590765} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 10.99998950958252, "x": 20.87659743430749, "y": -0.2720681396318998, "z": null, "yaw": 0.020342652799713184, "pitch": null, "roll": null}, "v": 2.2908688397001153, "accelerator_pedal_position": 0.2780625988969056, "brake_pedal_position": 0.0, "acceleration": 0.1208670007135646, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017488493427465963, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.6790764} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27784856067238617, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.2295771930015559, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3027599898174986, "gear": 1, "accelerator_pedal_position": 0.27784856067238617, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.6790764} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502649.6990764, "x": 25.1291935858373, "y": 4.7331676015448, "z": null, "yaw": 0.021182392833574322, "pitch": null, "roll": null}, "v": 2.3039438745075436, "accelerator_pedal_position": 0.27784856067238617, "brake_pedal_position": 0.0, "acceleration": 0.11827473670822797, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017588308247210742, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.6990764} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2777135956283312, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.20476266596205814, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3039438745075436, "gear": 1, "accelerator_pedal_position": 0.27784856067238617, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.6990764} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.109989404678345, "x": 21.1291935858373, "y": -0.26683239845520035, "z": null, "yaw": 0.021182392833574322, "pitch": null, "roll": null}, "v": 2.3039438745075436, "accelerator_pedal_position": 0.27784856067238617, "brake_pedal_position": 0.0, "acceleration": 0.11827473670822797, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017588308247210742, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.7190764} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2778184985284826, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.20476266596205814, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3062913702074628, "gear": 1, "accelerator_pedal_position": 0.2777135956283312, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.7190764} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.109989404678345, "x": 21.1291935858373, "y": -0.26683239845520035, "z": null, "yaw": 0.021182392833574322, "pitch": null, "roll": null}, "v": 2.3039438745075436, "accelerator_pedal_position": 0.27784856067238617, "brake_pedal_position": 0.0, "acceleration": 0.11827473670822797, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017588308247210742, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.7390764} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2778184985284826, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.20476266596205814, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3086474620865416, "gear": 1, "accelerator_pedal_position": 0.2778184985284826, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.7390764} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.109989404678345, "x": 21.1291935858373, "y": -0.26683239845520035, "z": null, "yaw": 0.021182392833574322, "pitch": null, "roll": null}, "v": 2.3039438745075436, "accelerator_pedal_position": 0.27784856067238617, "brake_pedal_position": 0.0, "acceleration": 0.11827473670822797, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017588308247210742, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.7590764} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2778184985284826, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.20476266596205814, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.310999024853581, "gear": 1, "accelerator_pedal_position": 0.2778184985284826, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.7590764} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.109989404678345, "x": 21.1291935858373, "y": -0.26683239845520035, "z": null, "yaw": 0.021182392833574322, "pitch": null, "roll": null}, "v": 2.3039438745075436, "accelerator_pedal_position": 0.27784856067238617, "brake_pedal_position": 0.0, "acceleration": 0.11827473670822797, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017588308247210742, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.7790763} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2778184985284826, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.20476266596205814, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.313346065004011, "gear": 1, "accelerator_pedal_position": 0.2778184985284826, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.7790763} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.109989404678345, "x": 21.1291935858373, "y": -0.26683239845520035, "z": null, "yaw": 0.021182392833574322, "pitch": null, "roll": null}, "v": 2.3039438745075436, "accelerator_pedal_position": 0.27784856067238617, "brake_pedal_position": 0.0, "acceleration": 0.11827473670822797, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017588308247210742, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.7990763} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2778184985284826, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.20476266596205814, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3156885890335235, "gear": 1, "accelerator_pedal_position": 0.2778184985284826, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.7990763} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502649.8090763, "x": 25.383214697320167, "y": 4.738646284291756, "z": null, "yaw": 0.02202213286743546, "pitch": null, "roll": null}, "v": 2.3168581595328988, "accelerator_pedal_position": 0.2778184985284826, "brake_pedal_position": 0.0, "acceleration": 0.11684439051242962, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017686895903069693, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.8190763} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.278927772249075, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.15432646379466586, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3180266034380232, "gear": 1, "accelerator_pedal_position": 0.2778184985284826, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.8190763} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.21998929977417, "x": 21.383214697320167, "y": -0.2613537157082444, "z": null, "yaw": 0.02202213286743546, "pitch": null, "roll": null}, "v": 2.3168581595328988, "accelerator_pedal_position": 0.2778184985284826, "brake_pedal_position": 0.0, "acceleration": 0.11684439051242962, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017686895903069693, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.8390763} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2786432469146606, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.15432646379466586, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3204987071056076, "gear": 1, "accelerator_pedal_position": 0.278927772249075, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.8390763} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.21998929977417, "x": 21.383214697320167, "y": -0.2613537157082444, "z": null, "yaw": 0.02202213286743546, "pitch": null, "roll": null}, "v": 2.3168581595328988, "accelerator_pedal_position": 0.2778184985284826, "brake_pedal_position": 0.0, "acceleration": 0.11684439051242962, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017686895903069693, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.8590763} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2786432469146606, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.15432646379466586, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3229304984547863, "gear": 1, "accelerator_pedal_position": 0.2786432469146606, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.8590763} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.21998929977417, "x": 21.383214697320167, "y": -0.2613537157082444, "z": null, "yaw": 0.02202213286743546, "pitch": null, "roll": null}, "v": 2.3168581595328988, "accelerator_pedal_position": 0.2778184985284826, "brake_pedal_position": 0.0, "acceleration": 0.11684439051242962, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017686895903069693, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.8790762} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2786432469146606, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.15432646379466586, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.325357601313377, "gear": 1, "accelerator_pedal_position": 0.2786432469146606, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.8790762} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.21998929977417, "x": 21.383214697320167, "y": -0.2613537157082444, "z": null, "yaw": 0.02202213286743546, "pitch": null, "roll": null}, "v": 2.3168581595328988, "accelerator_pedal_position": 0.2778184985284826, "brake_pedal_position": 0.0, "acceleration": 0.11684439051242962, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017686895903069693, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.8990762} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2786432469146606, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.15432646379466586, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.327780022365589, "gear": 1, "accelerator_pedal_position": 0.2786432469146606, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.8990762} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502649.9190762, "x": 25.638671898580018, "y": 4.744370564604746, "z": null, "yaw": 0.022861872901296598, "pitch": null, "roll": null}, "v": 2.3301977682963644, "accelerator_pedal_position": 0.2786432469146606, "brake_pedal_position": 0.0, "acceleration": 0.12071218840807674, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017788730480476304, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.9190762} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28001125116388387, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.10331760234166865, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3301977682963644, "gear": 1, "accelerator_pedal_position": 0.2786432469146606, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.9190762} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.329989194869995, "x": 21.638671898580018, "y": -0.25562943539525396, "z": null, "yaw": 0.022861872901296598, "pitch": null, "roll": null}, "v": 2.3301977682963644, "accelerator_pedal_position": 0.2786432469146606, "brake_pedal_position": 0.0, "acceleration": 0.12071218840807674, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017788730480476304, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.9390762} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27964809357379516, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.10331760234166865, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3327817637044674, "gear": 1, "accelerator_pedal_position": 0.28001125116388387, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.9390762} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.329989194869995, "x": 21.638671898580018, "y": -0.25562943539525396, "z": null, "yaw": 0.022861872901296598, "pitch": null, "roll": null}, "v": 2.3301977682963644, "accelerator_pedal_position": 0.2786432469146606, "brake_pedal_position": 0.0, "acceleration": 0.12071218840807674, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017788730480476304, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.9590762} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27964809357379516, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.10331760234166865, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.335315394284956, "gear": 1, "accelerator_pedal_position": 0.27964809357379516, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.9590762} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.329989194869995, "x": 21.638671898580018, "y": -0.25562943539525396, "z": null, "yaw": 0.022861872901296598, "pitch": null, "roll": null}, "v": 2.3301977682963644, "accelerator_pedal_position": 0.2786432469146606, "brake_pedal_position": 0.0, "acceleration": 0.12071218840807674, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017788730480476304, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.9790761} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27964809357379516, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.10331760234166865, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3391066597835106, "gear": 1, "accelerator_pedal_position": 0.27964809357379516, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.9790761} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.329989194869995, "x": 21.638671898580018, "y": -0.25562943539525396, "z": null, "yaw": 0.022861872901296598, "pitch": null, "roll": null}, "v": 2.3301977682963644, "accelerator_pedal_position": 0.2786432469146606, "brake_pedal_position": 0.0, "acceleration": 0.12071218840807674, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017788730480476304, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502649.9990761} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27964809357379516, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.10331760234166865, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3403679703053966, "gear": 1, "accelerator_pedal_position": 0.27964809357379516, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502649.9990761} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.329989194869995, "x": 21.638671898580018, "y": -0.25562943539525396, "z": null, "yaw": 0.022861872901296598, "pitch": null, "roll": null}, "v": 2.3301977682963644, "accelerator_pedal_position": 0.2786432469146606, "brake_pedal_position": 0.0, "acceleration": 0.12071218840807674, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017788730480476304, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.019076} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27964809357379516, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.10331760234166865, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3428869295662405, "gear": 1, "accelerator_pedal_position": 0.27964809357379516, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.019076} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502650.029076, "x": 25.895624948068637, "y": 4.750344253801164, "z": null, "yaw": 0.023701612935157736, "pitch": null, "roll": null}, "v": 2.3441445800333462, "accelerator_pedal_position": 0.27964809357379516, "brake_pedal_position": 0.0, "acceleration": 0.12564321771355524, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017895200445569654, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.039076} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28064524525226947, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.06105401635280549, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3467185489418356, "gear": 1, "accelerator_pedal_position": 0.28064524525226947, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.039076} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.43998908996582, "x": 21.895624948068637, "y": -0.2496557461988358, "z": null, "yaw": 0.023701612935157736, "pitch": null, "roll": null}, "v": 2.3441445800333462, "accelerator_pedal_position": 0.27964809357379516, "brake_pedal_position": 0.0, "acceleration": 0.12564321771355524, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017895200445569654, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.059076} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2804010983083767, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.06105401635280549, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3480348087008367, "gear": 1, "accelerator_pedal_position": 0.28064524525226947, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.059076} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.43998908996582, "x": 21.895624948068637, "y": -0.2496557461988358, "z": null, "yaw": 0.023701612935157736, "pitch": null, "roll": null}, "v": 2.3441445800333462, "accelerator_pedal_position": 0.27964809357379516, "brake_pedal_position": 0.0, "acceleration": 0.12564321771355524, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017895200445569654, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.079076} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2804010983083767, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.06105401635280549, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3519302018940897, "gear": 1, "accelerator_pedal_position": 0.2804010983083767, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.079076} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.43998908996582, "x": 21.895624948068637, "y": -0.2496557461988358, "z": null, "yaw": 0.023701612935157736, "pitch": null, "roll": null}, "v": 2.3441445800333462, "accelerator_pedal_position": 0.27964809357379516, "brake_pedal_position": 0.0, "acceleration": 0.12564321771355524, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017895200445569654, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.099076} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2804010983083767, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.06105401635280549, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.353226147869958, "gear": 1, "accelerator_pedal_position": 0.2804010983083767, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.099076} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.43998908996582, "x": 21.895624948068637, "y": -0.2496557461988358, "z": null, "yaw": 0.023701612935157736, "pitch": null, "roll": null}, "v": 2.3441445800333462, "accelerator_pedal_position": 0.27964809357379516, "brake_pedal_position": 0.0, "acceleration": 0.12564321771355524, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.017895200445569654, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.119076} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2804010983083767, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.06105401635280549, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3558142674994453, "gear": 1, "accelerator_pedal_position": 0.2804010983083767, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.119076} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502650.139076, "x": 26.15411859962384, "y": 4.756570950254567, "z": null, "yaw": 0.024541352969018874, "pitch": null, "roll": null}, "v": 2.3583973632681583, "accelerator_pedal_position": 0.2804010983083767, "brake_pedal_position": 0.0, "acceleration": 0.1289666150332442, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018004006197171622, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.139076} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28143948003705305, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.01818852090329962, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3583973632681583, "gear": 1, "accelerator_pedal_position": 0.2804010983083767, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.139076} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.549988985061646, "x": 22.15411859962384, "y": -0.24342904974543256, "z": null, "yaw": 0.024541352969018874, "pitch": null, "roll": null}, "v": 2.3583973632681583, "accelerator_pedal_position": 0.2804010983083767, "brake_pedal_position": 0.0, "acceleration": 0.1289666150332442, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018004006197171622, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.159076} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2811841296929932, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.01818852090329962, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3611051768984104, "gear": 1, "accelerator_pedal_position": 0.28143948003705305, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.159076} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.549988985061646, "x": 22.15411859962384, "y": -0.24342904974543256, "z": null, "yaw": 0.024541352969018874, "pitch": null, "roll": null}, "v": 2.3583973632681583, "accelerator_pedal_position": 0.2804010983083767, "brake_pedal_position": 0.0, "acceleration": 0.1289666150332442, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018004006197171622, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.179076} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2811841296929932, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.01818852090329962, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.363775825361594, "gear": 1, "accelerator_pedal_position": 0.2811841296929932, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.179076} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.549988985061646, "x": 22.15411859962384, "y": -0.24342904974543256, "z": null, "yaw": 0.024541352969018874, "pitch": null, "roll": null}, "v": 2.3583973632681583, "accelerator_pedal_position": 0.2804010983083767, "brake_pedal_position": 0.0, "acceleration": 0.1289666150332442, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018004006197171622, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.199076} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2811841296929932, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.01818852090329962, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3664412812906015, "gear": 1, "accelerator_pedal_position": 0.2811841296929932, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.199076} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.549988985061646, "x": 22.15411859962384, "y": -0.24342904974543256, "z": null, "yaw": 0.024541352969018874, "pitch": null, "roll": null}, "v": 2.3583973632681583, "accelerator_pedal_position": 0.2804010983083767, "brake_pedal_position": 0.0, "acceleration": 0.1289666150332442, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018004006197171622, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.219076} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2811841296929932, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.01818852090329962, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.369101551940781, "gear": 1, "accelerator_pedal_position": 0.2811841296929932, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.219076} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.549988985061646, "x": 22.15411859962384, "y": -0.24342904974543256, "z": null, "yaw": 0.024541352969018874, "pitch": null, "roll": null}, "v": 2.3583973632681583, "accelerator_pedal_position": 0.2804010983083767, "brake_pedal_position": 0.0, "acceleration": 0.1289666150332442, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018004006197171622, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.239076} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2811841296929932, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.01818852090329962, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.373082251395364, "gear": 1, "accelerator_pedal_position": 0.2811841296929932, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.239076} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502650.249076, "x": 26.414198612209045, "y": 4.763054392756411, "z": null, "yaw": 0.025381093002880013, "pitch": null, "roll": null}, "v": 2.373082251395364, "accelerator_pedal_position": 0.2811841296929932, "brake_pedal_position": 0.0, "acceleration": 0.13243150429256245, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018116110637655145, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.2590759} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27617212449492906, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.034510731928342704, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3744065664382896, "gear": 1, "accelerator_pedal_position": 0.2811841296929932, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.2590759} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.65998888015747, "x": 22.414198612209045, "y": -0.23694560724358915, "z": null, "yaw": 0.025381093002880013, "pitch": null, "roll": null}, "v": 2.373082251395364, "accelerator_pedal_position": 0.2811841296929932, "brake_pedal_position": 0.0, "acceleration": 0.13243150429256245, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018116110637655145, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.2790759} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2778098300378143, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.034510731928342704, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3764251296135535, "gear": 1, "accelerator_pedal_position": 0.27617212449492906, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.2790759} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.65998888015747, "x": 22.414198612209045, "y": -0.23694560724358915, "z": null, "yaw": 0.025381093002880013, "pitch": null, "roll": null}, "v": 2.373082251395364, "accelerator_pedal_position": 0.2811841296929932, "brake_pedal_position": 0.0, "acceleration": 0.13243150429256245, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018116110637655145, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.2990758} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2778098300378143, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.034510731928342704, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3786443711115455, "gear": 1, "accelerator_pedal_position": 0.2778098300378143, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.2990758} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.65998888015747, "x": 22.414198612209045, "y": -0.23694560724358915, "z": null, "yaw": 0.025381093002880013, "pitch": null, "roll": null}, "v": 2.373082251395364, "accelerator_pedal_position": 0.2811841296929932, "brake_pedal_position": 0.0, "acceleration": 0.13243150429256245, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018116110637655145, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.3190758} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2778098300378143, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.034510731928342704, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.380859284458605, "gear": 1, "accelerator_pedal_position": 0.2778098300378143, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.3190758} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.65998888015747, "x": 22.414198612209045, "y": -0.23694560724358915, "z": null, "yaw": 0.025381093002880013, "pitch": null, "roll": null}, "v": 2.373082251395364, "accelerator_pedal_position": 0.2811841296929932, "brake_pedal_position": 0.0, "acceleration": 0.13243150429256245, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018116110637655145, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.3390758} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2778098300378143, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.034510731928342704, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3830698761344755, "gear": 1, "accelerator_pedal_position": 0.2778098300378143, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.3390758} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502650.3590758, "x": 26.675765076082964, "y": 4.769794658972169, "z": null, "yaw": 0.02622083303674115, "pitch": null, "roll": null}, "v": 2.385276152617737, "accelerator_pedal_position": 0.2778098300378143, "brake_pedal_position": 0.0, "acceleration": 0.11015220686298366, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018209198883340372, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.3590758} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2724164025582796, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.06518162014874586, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.385276152617737, "gear": 1, "accelerator_pedal_position": 0.2778098300378143, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.3590758} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.769988775253296, "x": 22.675765076082964, "y": -0.23020534102783063, "z": null, "yaw": 0.02622083303674115, "pitch": null, "roll": null}, "v": 2.385276152617737, "accelerator_pedal_position": 0.2778098300378143, "brake_pedal_position": 0.0, "acceleration": 0.11015220686298366, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018209198883340372, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.3790758} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2741613460189438, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.06518162014874586, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3868042713685034, "gear": 1, "accelerator_pedal_position": 0.2724164025582796, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.3790758} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.769988775253296, "x": 22.675765076082964, "y": -0.23020534102783063, "z": null, "yaw": 0.02622083303674115, "pitch": null, "roll": null}, "v": 2.385276152617737, "accelerator_pedal_position": 0.2778098300378143, "brake_pedal_position": 0.0, "acceleration": 0.11015220686298366, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018209198883340372, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.3990757} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2741613460189438, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.06518162014874586, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3885474160902747, "gear": 1, "accelerator_pedal_position": 0.2741613460189438, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.3990757} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.769988775253296, "x": 22.675765076082964, "y": -0.23020534102783063, "z": null, "yaw": 0.02622083303674115, "pitch": null, "roll": null}, "v": 2.385276152617737, "accelerator_pedal_position": 0.2778098300378143, "brake_pedal_position": 0.0, "acceleration": 0.11015220686298366, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018209198883340372, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.4190757} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2741613460189438, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.06518162014874586, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.390287154203802, "gear": 1, "accelerator_pedal_position": 0.2741613460189438, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.4190757} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.769988775253296, "x": 22.675765076082964, "y": -0.23020534102783063, "z": null, "yaw": 0.02622083303674115, "pitch": null, "roll": null}, "v": 2.385276152617737, "accelerator_pedal_position": 0.2778098300378143, "brake_pedal_position": 0.0, "acceleration": 0.11015220686298366, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018209198883340372, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.4390757} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2741613460189438, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.06518162014874586, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3920234911564977, "gear": 1, "accelerator_pedal_position": 0.2741613460189438, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.4390757} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.769988775253296, "x": 22.675765076082964, "y": -0.23020534102783063, "z": null, "yaw": 0.02622083303674115, "pitch": null, "roll": null}, "v": 2.385276152617737, "accelerator_pedal_position": 0.2778098300378143, "brake_pedal_position": 0.0, "acceleration": 0.11015220686298366, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018209198883340372, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.4590757} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2741613460189438, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.06518162014874586, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.393756432392221, "gear": 1, "accelerator_pedal_position": 0.2741613460189438, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.4590757} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502650.4690757, "x": 26.938510823365796, "y": 4.776786082628924, "z": null, "yaw": 0.02706057307060229, "pitch": null, "roll": null}, "v": 2.394621631316447, "accelerator_pedal_position": 0.2741613460189438, "brake_pedal_position": 0.0, "acceleration": 0.08643520348089001, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01828054227060313, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.4790757} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2678198327747935, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.10873020970169016, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.395485983351256, "gear": 1, "accelerator_pedal_position": 0.2741613460189438, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.4790757} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.879988670349121, "x": 22.938510823365796, "y": -0.22321391737107632, "z": null, "yaw": 0.02706057307060229, "pitch": null, "roll": null}, "v": 2.394621631316447, "accelerator_pedal_position": 0.2741613460189438, "brake_pedal_position": 0.0, "acceleration": 0.08643520348089001, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01828054227060313, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.4990757} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2698472559060803, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.10873020970169016, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.396419848427376, "gear": 1, "accelerator_pedal_position": 0.2678198327747935, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.4990757} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.879988670349121, "x": 22.938510823365796, "y": -0.22321391737107632, "z": null, "yaw": 0.02706057307060229, "pitch": null, "roll": null}, "v": 2.394621631316447, "accelerator_pedal_position": 0.2741613460189438, "brake_pedal_position": 0.0, "acceleration": 0.08643520348089001, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01828054227060313, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.5190756} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2698472559060803, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.10873020970169016, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3976051892370935, "gear": 1, "accelerator_pedal_position": 0.2698472559060803, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.5190756} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.879988670349121, "x": 22.938510823365796, "y": -0.22321391737107632, "z": null, "yaw": 0.02706057307060229, "pitch": null, "roll": null}, "v": 2.394621631316447, "accelerator_pedal_position": 0.2741613460189438, "brake_pedal_position": 0.0, "acceleration": 0.08643520348089001, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01828054227060313, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.5390756} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2698472559060803, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.10873020970169016, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3987882091920136, "gear": 1, "accelerator_pedal_position": 0.2698472559060803, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.5390756} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.879988670349121, "x": 22.938510823365796, "y": -0.22321391737107632, "z": null, "yaw": 0.02706057307060229, "pitch": null, "roll": null}, "v": 2.394621631316447, "accelerator_pedal_position": 0.2741613460189438, "brake_pedal_position": 0.0, "acceleration": 0.08643520348089001, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01828054227060313, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.5590756} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2698472559060803, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.10873020970169016, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.399968912276747, "gear": 1, "accelerator_pedal_position": 0.2698472559060803, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.5590756} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502650.5790756, "x": 27.20215141180437, "y": 4.784022845082385, "z": null, "yaw": 0.027900313104463427, "pitch": null, "roll": null}, "v": 2.4011473024713865, "accelerator_pedal_position": 0.2698472559060803, "brake_pedal_position": 0.0, "acceleration": 0.05883290060777613, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018330359246208728, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.5790756} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26359426851997847, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.15870174788201433, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4011473024713865, "gear": 1, "accelerator_pedal_position": 0.2698472559060803, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.5790756} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.989988565444946, "x": 23.20215141180437, "y": -0.21597715491761527, "z": null, "yaw": 0.027900313104463427, "pitch": null, "roll": null}, "v": 2.4011473024713865, "accelerator_pedal_position": 0.2698472559060803, "brake_pedal_position": 0.0, "acceleration": 0.05883290060777613, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018330359246208728, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.5990756} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2655802903636585, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.15870174788201433, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.401542143444107, "gear": 1, "accelerator_pedal_position": 0.26359426851997847, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.5990756} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.989988565444946, "x": 23.20215141180437, "y": -0.21597715491761527, "z": null, "yaw": 0.027900313104463427, "pitch": null, "roll": null}, "v": 2.4011473024713865, "accelerator_pedal_position": 0.2698472559060803, "brake_pedal_position": 0.0, "acceleration": 0.05883290060777613, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018330359246208728, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.6190755} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2655802903636585, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.15870174788201433, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.40218434172189, "gear": 1, "accelerator_pedal_position": 0.2655802903636585, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.6190755} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.989988565444946, "x": 23.20215141180437, "y": -0.21597715491761527, "z": null, "yaw": 0.027900313104463427, "pitch": null, "roll": null}, "v": 2.4011473024713865, "accelerator_pedal_position": 0.2698472559060803, "brake_pedal_position": 0.0, "acceleration": 0.05883290060777613, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018330359246208728, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.6390755} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2655802903636585, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.15870174788201433, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4031452799622217, "gear": 1, "accelerator_pedal_position": 0.2655802903636585, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.6390755} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.989988565444946, "x": 23.20215141180437, "y": -0.21597715491761527, "z": null, "yaw": 0.027900313104463427, "pitch": null, "roll": null}, "v": 2.4011473024713865, "accelerator_pedal_position": 0.2698472559060803, "brake_pedal_position": 0.0, "acceleration": 0.05883290060777613, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018330359246208728, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.6590755} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2655802903636585, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.15870174788201433, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4034649647463087, "gear": 1, "accelerator_pedal_position": 0.2655802903636585, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.6590755} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 11.989988565444946, "x": 23.20215141180437, "y": -0.21597715491761527, "z": null, "yaw": 0.027900313104463427, "pitch": null, "roll": null}, "v": 2.4011473024713865, "accelerator_pedal_position": 0.2698472559060803, "brake_pedal_position": 0.0, "acceleration": 0.05883290060777613, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018330359246208728, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.6790755} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2655802903636585, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.15870174788201433, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4041033940942893, "gear": 1, "accelerator_pedal_position": 0.2655802903636585, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.6790755} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502650.6890755, "x": 27.466324817989975, "y": 4.791496219096074, "z": null, "yaw": 0.028740053138324565, "pitch": null, "roll": null}, "v": 2.4044221392320213, "accelerator_pedal_position": 0.2655802903636585, "brake_pedal_position": 0.0, "acceleration": 0.031843249574973476, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018355359351047505, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.6990755} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25997619082543266, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.20854487637869124, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4047405717277712, "gear": 1, "accelerator_pedal_position": 0.2655802903636585, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.6990755} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.099988460540771, "x": 23.466324817989975, "y": -0.20850378090392585, "z": null, "yaw": 0.028740053138324565, "pitch": null, "roll": null}, "v": 2.4044221392320213, "accelerator_pedal_position": 0.2655802903636585, "brake_pedal_position": 0.0, "acceleration": 0.031843249574973476, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018355359351047505, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.7190754} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2617435289095187, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.20854487637869124, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4046763310894845, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.7190754} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.099988460540771, "x": 23.466324817989975, "y": -0.20850378090392585, "z": null, "yaw": 0.028740053138324565, "pitch": null, "roll": null}, "v": 2.4044221392320213, "accelerator_pedal_position": 0.2655802903636585, "brake_pedal_position": 0.0, "acceleration": 0.031843249574973476, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018355359351047505, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.7390754} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2617435289095187, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.20854487637869124, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4048330253288444, "gear": 1, "accelerator_pedal_position": 0.2617435289095187, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.7390754} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.099988460540771, "x": 23.466324817989975, "y": -0.20850378090392585, "z": null, "yaw": 0.028740053138324565, "pitch": null, "roll": null}, "v": 2.4044221392320213, "accelerator_pedal_position": 0.2655802903636585, "brake_pedal_position": 0.0, "acceleration": 0.031843249574973476, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018355359351047505, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.7590754} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2617435289095187, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.20854487637869124, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4049894122978124, "gear": 1, "accelerator_pedal_position": 0.2617435289095187, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.7590754} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.099988460540771, "x": 23.466324817989975, "y": -0.20850378090392585, "z": null, "yaw": 0.028740053138324565, "pitch": null, "roll": null}, "v": 2.4044221392320213, "accelerator_pedal_position": 0.2655802903636585, "brake_pedal_position": 0.0, "acceleration": 0.031843249574973476, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018355359351047505, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.7790754} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2617435289095187, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.20854487637869124, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.405145492589154, "gear": 1, "accelerator_pedal_position": 0.2617435289095187, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.7790754} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502650.7990754, "x": 27.73074736810815, "y": 4.799198850641209, "z": null, "yaw": 0.029579793172185703, "pitch": null, "roll": null}, "v": 2.40530126679453, "accelerator_pedal_position": 0.2617435289095187, "brake_pedal_position": 0.0, "acceleration": 0.007777250504331479, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018362070611130318, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.7990754} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25659435073529546, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.2578094738731477, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.40530126679453, "gear": 1, "accelerator_pedal_position": 0.2617435289095187, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.7990754} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.209988355636597, "x": 23.73074736810815, "y": -0.20080114935879134, "z": null, "yaw": 0.029579793172185703, "pitch": null, "roll": null}, "v": 2.40530126679453, "accelerator_pedal_position": 0.2617435289095187, "brake_pedal_position": 0.0, "acceleration": 0.007777250504331479, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018362070611130318, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.8190753} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2582077819717016, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.2578094738731477, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.404813403955747, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.8190753} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.209988355636597, "x": 23.73074736810815, "y": -0.20080114935879134, "z": null, "yaw": 0.029579793172185703, "pitch": null, "roll": null}, "v": 2.40530126679453, "accelerator_pedal_position": 0.2617435289095187, "brake_pedal_position": 0.0, "acceleration": 0.007777250504331479, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018362070611130318, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.8390753} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2582077819717016, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.2578094738731477, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.404528077810472, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.8390753} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.209988355636597, "x": 23.73074736810815, "y": -0.20080114935879134, "z": null, "yaw": 0.029579793172185703, "pitch": null, "roll": null}, "v": 2.40530126679453, "accelerator_pedal_position": 0.2617435289095187, "brake_pedal_position": 0.0, "acceleration": 0.007777250504331479, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018362070611130318, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.8590753} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2582077819717016, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.2578094738731477, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4042433111548367, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.8590753} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.209988355636597, "x": 23.73074736810815, "y": -0.20080114935879134, "z": null, "yaw": 0.029579793172185703, "pitch": null, "roll": null}, "v": 2.40530126679453, "accelerator_pedal_position": 0.2617435289095187, "brake_pedal_position": 0.0, "acceleration": 0.007777250504331479, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018362070611130318, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.8790753} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2582077819717016, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.2578094738731477, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.403959102859329, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.8790753} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.209988355636597, "x": 23.73074736810815, "y": -0.20080114935879134, "z": null, "yaw": 0.029579793172185703, "pitch": null, "roll": null}, "v": 2.40530126679453, "accelerator_pedal_position": 0.2617435289095187, "brake_pedal_position": 0.0, "acceleration": 0.007777250504331479, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018362070611130318, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.8990753} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2582077819717016, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.2578094738731477, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.403675451796843, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.8990753} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502650.9090753, "x": 27.995114181233742, "y": 4.807122033072656, "z": null, "yaw": 0.03041953320604684, "pitch": null, "roll": null}, "v": 2.4035338348764186, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3779464406977784, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018348578035323387, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.9190753} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.253463614756991, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.3086641940917309, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.403392356842672, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.9190753} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.319988250732422, "x": 23.995114181233742, "y": -0.1928779669273437, "z": null, "yaw": 0.03041953320604684, "pitch": null, "roll": null}, "v": 2.4035338348764186, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3779464406977784, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018348578035323387, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.9390752} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25493749975382324, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.3086641940917309, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4025170867369083, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.9390752} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.319988250732422, "x": 23.995114181233742, "y": -0.1928779669273437, "z": null, "yaw": 0.03041953320604684, "pitch": null, "roll": null}, "v": 2.4035338348764186, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3779464406977784, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018348578035323387, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.9590752} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25493749975382324, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.3086641940917309, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4018276775868794, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.9590752} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.319988250732422, "x": 23.995114181233742, "y": -0.1928779669273437, "z": null, "yaw": 0.03041953320604684, "pitch": null, "roll": null}, "v": 2.4035338348764186, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3779464406977784, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018348578035323387, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.9790752} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25493749975382324, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.3086641940917309, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.401139619567694, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.9790752} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.319988250732422, "x": 23.995114181233742, "y": -0.1928779669273437, "z": null, "yaw": 0.03041953320604684, "pitch": null, "roll": null}, "v": 2.4035338348764186, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3779464406977784, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018348578035323387, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502650.9990752} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25493749975382324, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.3086641940917309, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4004529098420773, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502650.9990752} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502651.0190752, "x": 28.259192655593292, "y": 4.815258519363193, "z": null, "yaw": 0.03125927323990798, "pitch": null, "roll": null}, "v": 2.3997675455794254, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3775772200071343, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01831982618167077, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.0190752} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2508561383182843, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.3622832606541105, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3997675455794254, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.0190752} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.429988145828247, "x": 24.259192655593292, "y": -0.18474148063680662, "z": null, "yaw": 0.03125927323990798, "pitch": null, "roll": null}, "v": 2.3997675455794254, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3775772200071343, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01831982618167077, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.0390751} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25211310355648864, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.3622832606541105, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3985736037239125, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.0390751} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.429988145828247, "x": 24.259192655593292, "y": -0.18474148063680662, "z": null, "yaw": 0.03125927323990798, "pitch": null, "roll": null}, "v": 2.3997675455794254, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3775772200071343, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01831982618167077, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.059075} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25211310355648864, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.3622832606541105, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3975390440065234, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.059075} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.429988145828247, "x": 24.259192655593292, "y": -0.18474148063680662, "z": null, "yaw": 0.03125927323990798, "pitch": null, "roll": null}, "v": 2.3997675455794254, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3775772200071343, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01831982618167077, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.079075} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25211310355648864, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.3622832606541105, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3965065101221636, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.079075} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.429988145828247, "x": 24.259192655593292, "y": -0.18474148063680662, "z": null, "yaw": 0.03125927323990798, "pitch": null, "roll": null}, "v": 2.3997675455794254, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3775772200071343, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01831982618167077, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.099075} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25211310355648864, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.3622832606541105, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.395475997677687, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.099075} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.429988145828247, "x": 24.259192655593292, "y": -0.18474148063680662, "z": null, "yaw": 0.03125927323990798, "pitch": null, "roll": null}, "v": 2.3997675455794254, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3775772200071343, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01831982618167077, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.119075} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25211310355648864, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.3622832606541105, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.393934009628063, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.119075} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502651.129075, "x": 28.522735786790708, "y": 4.8236000202147595, "z": null, "yaw": 0.032099013273769156, "pitch": null, "roll": null}, "v": 2.393934009628063, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3770059009059421, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01827529296642234, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.139075} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24644835598948361, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4183336214891365, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3925544849131293, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.139075} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.539988040924072, "x": 24.522735786790708, "y": -0.17639997978524047, "z": null, "yaw": 0.032099013273769156, "pitch": null, "roll": null}, "v": 2.393934009628063, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3770059009059421, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01827529296642234, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.149075} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24819002479104013, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4183336214891365, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3908239585431637, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.149075} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.539988040924072, "x": 24.522735786790708, "y": -0.17639997978524047, "z": null, "yaw": 0.032099013273769156, "pitch": null, "roll": null}, "v": 2.393934009628063, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3770059009059421, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01827529296642234, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.179075} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24819002479104013, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4183336214891365, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3893144184370527, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.179075} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.539988040924072, "x": 24.522735786790708, "y": -0.17639997978524047, "z": null, "yaw": 0.032099013273769156, "pitch": null, "roll": null}, "v": 2.393934009628063, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3770059009059421, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01827529296642234, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.199075} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24819002479104013, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4183336214891365, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.388560755438259, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.199075} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.539988040924072, "x": 24.522735786790708, "y": -0.17639997978524047, "z": null, "yaw": 0.032099013273769156, "pitch": null, "roll": null}, "v": 2.393934009628063, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3770059009059421, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.01827529296642234, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.219075} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24819002479104013, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4183336214891365, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.387055639373501, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.219075} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502651.239075, "x": 28.78551244520974, "y": 4.832138130915861, "z": null, "yaw": 0.03293875330763033, "pitch": null, "roll": null}, "v": 2.385553464331664, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37618632652843126, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018211315881049857, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.239075} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24796643653463657, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4808879218706883, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3848034776158196, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4231240351196229, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.239075} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.649987936019897, "x": 24.78551244520974, "y": -0.16786186908413914, "z": null, "yaw": 0.03293875330763033, "pitch": null, "roll": null}, "v": 2.385553464331664, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37618632652843126, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018211315881049857, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.259075} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24799532916483064, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4808879218706883, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3840402493977417, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.38306202037943926, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.259075} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.649987936019897, "x": 24.78551244520974, "y": -0.16786186908413914, "z": null, "yaw": 0.03293875330763033, "pitch": null, "roll": null}, "v": 2.385553464331664, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37618632652843126, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018211315881049857, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.279075} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24799532916483064, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4808879218706883, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.381760446959782, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.38306202037943926, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.279075} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.649987936019897, "x": 24.78551244520974, "y": -0.16786186908413914, "z": null, "yaw": 0.03293875330763033, "pitch": null, "roll": null}, "v": 2.385553464331664, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37618632652843126, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018211315881049857, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.299075} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24799532916483064, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4808879218706883, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3810019965264337, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.38306202037943926, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.299075} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.649987936019897, "x": 24.78551244520974, "y": -0.16786186908413914, "z": null, "yaw": 0.03293875330763033, "pitch": null, "roll": null}, "v": 2.385553464331664, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37618632652843126, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018211315881049857, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.3190749} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24799532916483064, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4808879218706883, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.379487316193387, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.38306202037943926, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.3190749} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.649987936019897, "x": 24.78551244520974, "y": -0.16786186908413914, "z": null, "yaw": 0.03293875330763033, "pitch": null, "roll": null}, "v": 2.385553464331664, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37618632652843126, "steering_wheel_angle": 0.4231240351196229, "front_wheel_angle": 0.01954055333062798, "heading_rate": 0.018211315881049857, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.3390749} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24799532916483064, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4808879218706883, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3779755909924987, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.38306202037943926, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.3390749} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502651.3490748, "x": 29.047361193182127, "y": 4.840859987916795, "z": null, "yaw": 0.033713095542334405, "pitch": null, "roll": null}, "v": 2.3772208344786687, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3753728306827281, "steering_wheel_angle": 0.38306202037943926, "front_wheel_angle": 0.01768099402969328, "heading_rate": 0.016420315574571968, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.3590748} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24393898467048497, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5355169979005797, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3764668142446435, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.38306202037943926, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.3590748} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.759987831115723, "x": 25.047361193182127, "y": -0.15914001208320538, "z": null, "yaw": 0.033713095542334405, "pitch": null, "roll": null}, "v": 2.3772208344786687, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3753728306827281, "steering_wheel_angle": 0.38306202037943926, "front_wheel_angle": 0.01768099402969328, "heading_rate": 0.016420315574571968, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.3790748} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24516591833712323, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5355169979005797, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.374454183440521, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3026910460343449, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.3790748} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.759987831115723, "x": 25.047361193182127, "y": -0.15914001208320538, "z": null, "yaw": 0.033713095542334405, "pitch": null, "roll": null}, "v": 2.3772208344786687, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3753728306827281, "steering_wheel_angle": 0.38306202037943926, "front_wheel_angle": 0.01768099402969328, "heading_rate": 0.016420315574571968, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.3990748} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24516591833712323, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5355169979005797, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.372598767284351, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3026910460343449, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.3990748} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.759987831115723, "x": 25.047361193182127, "y": -0.15914001208320538, "z": null, "yaw": 0.033713095542334405, "pitch": null, "roll": null}, "v": 2.3772208344786687, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3753728306827281, "steering_wheel_angle": 0.38306202037943926, "front_wheel_angle": 0.01768099402969328, "heading_rate": 0.016420315574571968, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.4190748} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24516591833712323, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5355169979005797, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3707469659895923, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3026910460343449, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.4190748} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.759987831115723, "x": 25.047361193182127, "y": -0.15914001208320538, "z": null, "yaw": 0.033713095542334405, "pitch": null, "roll": null}, "v": 2.3772208344786687, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3753728306827281, "steering_wheel_angle": 0.38306202037943926, "front_wheel_angle": 0.01768099402969328, "heading_rate": 0.016420315574571968, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.4390748} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24516591833712323, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5355169979005797, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.367976023514207, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3026910460343449, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.4390748} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502651.4590747, "x": 29.308198643252975, "y": 4.8497360329938, "z": null, "yaw": 0.034349205762641145, "pitch": null, "roll": null}, "v": 2.3670541743537266, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3743821633609404, "steering_wheel_angle": 0.3026910460343449, "front_wheel_angle": 0.01395640901180994, "heading_rate": 0.012905359875882495, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.4590747} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23908296813808233, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5911006262830726, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3670541743537266, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3026910460343449, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.4590747} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.869987726211548, "x": 25.308198643252975, "y": -0.15026396700620026, "z": null, "yaw": 0.034349205762641145, "pitch": null, "roll": null}, "v": 2.3670541743537266, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3743821633609404, "steering_wheel_angle": 0.3026910460343449, "front_wheel_angle": 0.01395640901180994, "heading_rate": 0.012905359875882495, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.4790747} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24093435792305895, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5911006262830726, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3620885329748877, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2623805324665846, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.4790747} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.869987726211548, "x": 25.308198643252975, "y": -0.15026396700620026, "z": null, "yaw": 0.034349205762641145, "pitch": null, "roll": null}, "v": 2.3670541743537266, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3743821633609404, "steering_wheel_angle": 0.3026910460343449, "front_wheel_angle": 0.01395640901180994, "heading_rate": 0.012905359875882495, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.4990747} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24093435792305895, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5911006262830726, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3620885329748877, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2623805324665846, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.4990747} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.869987726211548, "x": 25.308198643252975, "y": -0.15026396700620026, "z": null, "yaw": 0.034349205762641145, "pitch": null, "roll": null}, "v": 2.3670541743537266, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3743821633609404, "steering_wheel_angle": 0.3026910460343449, "front_wheel_angle": 0.01395640901180994, "heading_rate": 0.012905359875882495, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.5190747} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24093435792305895, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5911006262830726, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.359728494625047, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2623805324665846, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.5190747} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.869987726211548, "x": 25.308198643252975, "y": -0.15026396700620026, "z": null, "yaw": 0.034349205762641145, "pitch": null, "roll": null}, "v": 2.3670541743537266, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3743821633609404, "steering_wheel_angle": 0.3026910460343449, "front_wheel_angle": 0.01395640901180994, "heading_rate": 0.012905359875882495, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.5390747} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24093435792305895, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5911006262830726, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3573730422606833, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2623805324665846, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.5390747} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.869987726211548, "x": 25.308198643252975, "y": -0.15026396700620026, "z": null, "yaw": 0.034349205762641145, "pitch": null, "roll": null}, "v": 2.3670541743537266, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3743821633609404, "steering_wheel_angle": 0.3026910460343449, "front_wheel_angle": 0.01395640901180994, "heading_rate": 0.012905359875882495, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.5590746} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24093435792305895, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5911006262830726, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.355022164752203, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2623805324665846, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.5590746} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502651.5690746, "x": 29.567747256830724, "y": 4.858717859015007, "z": null, "yaw": 0.03487606685398633, "pitch": null, "roll": null}, "v": 2.353848438100371, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3730984466004941, "steering_wheel_angle": 0.2623805324665846, "front_wheel_angle": 0.0120913231299291, "heading_rate": 0.011118175450114204, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.5790746} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24238931045796372, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6594204436138558, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.352675851004557, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.2623805324665846, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.5790746} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.979987621307373, "x": 25.567747256830724, "y": -0.14128214098499292, "z": null, "yaw": 0.03487606685398633, "pitch": null, "roll": null}, "v": 2.353848438100371, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3730984466004941, "steering_wheel_angle": 0.2623805324665846, "front_wheel_angle": 0.0120913231299291, "heading_rate": 0.011118175450114204, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.5990746} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2418704516125933, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6594204436138558, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.350515870789282, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.18148031453007718, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.5990746} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.979987621307373, "x": 25.567747256830724, "y": -0.14128214098499292, "z": null, "yaw": 0.03487606685398633, "pitch": null, "roll": null}, "v": 2.353848438100371, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3730984466004941, "steering_wheel_angle": 0.2623805324665846, "front_wheel_angle": 0.0120913231299291, "heading_rate": 0.011118175450114204, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.6190746} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2418704516125933, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6594204436138558, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3482952539112927, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.18148031453007718, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.6190746} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.979987621307373, "x": 25.567747256830724, "y": -0.14128214098499292, "z": null, "yaw": 0.03487606685398633, "pitch": null, "roll": null}, "v": 2.353848438100371, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3730984466004941, "steering_wheel_angle": 0.2623805324665846, "front_wheel_angle": 0.0120913231299291, "heading_rate": 0.011118175450114204, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.6390746} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2418704516125933, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6594204436138558, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3460789419207764, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.18148031453007718, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.6390746} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 12.979987621307373, "x": 25.567747256830724, "y": -0.14128214098499292, "z": null, "yaw": 0.03487606685398633, "pitch": null, "roll": null}, "v": 2.353848438100371, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3730984466004941, "steering_wheel_angle": 0.2623805324665846, "front_wheel_angle": 0.0120913231299291, "heading_rate": 0.011118175450114204, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.6590745} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2418704516125933, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6594204436138558, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.343866924508414, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.18148031453007718, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.6590745} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502651.6790745, "x": 29.825900456715573, "y": 4.867774901671174, "z": null, "yaw": 0.03527154545501697, "pitch": null, "roll": null}, "v": 2.341659191396282, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37191663725632096, "steering_wheel_angle": 0.18148031453007718, "front_wheel_angle": 0.00835424993395996, "heading_rate": 0.007641898936186072, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.6790745} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23983865750857716, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7218832841614157, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.341659191396282, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.18148031453007718, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.6790745} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.089987516403198, "x": 25.825900456715573, "y": -0.132225098328826, "z": null, "yaw": 0.03527154545501697, "pitch": null, "roll": null}, "v": 2.341659191396282, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37191663725632096, "steering_wheel_angle": 0.18148031453007718, "front_wheel_angle": 0.00835424993395996, "heading_rate": 0.007641898936186072, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.6990745} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2404145030764273, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7218832841614157, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3392018810108035, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.14089634271035242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.6990745} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.089987516403198, "x": 25.825900456715573, "y": -0.132225098328826, "z": null, "yaw": 0.03527154545501697, "pitch": null, "roll": null}, "v": 2.341659191396282, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37191663725632096, "steering_wheel_angle": 0.18148031453007718, "front_wheel_angle": 0.00835424993395996, "heading_rate": 0.007641898936186072, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.7190745} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2404145030764273, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7218832841614157, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.336821271367257, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.14089634271035242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.7190745} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.089987516403198, "x": 25.825900456715573, "y": -0.132225098328826, "z": null, "yaw": 0.03527154545501697, "pitch": null, "roll": null}, "v": 2.341659191396282, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37191663725632096, "steering_wheel_angle": 0.18148031453007718, "front_wheel_angle": 0.00835424993395996, "heading_rate": 0.007641898936186072, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.7390745} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2404145030764273, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7218832841614157, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3344452658957526, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.14089634271035242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.7390745} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.089987516403198, "x": 25.825900456715573, "y": -0.132225098328826, "z": null, "yaw": 0.03527154545501697, "pitch": null, "roll": null}, "v": 2.341659191396282, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37191663725632096, "steering_wheel_angle": 0.18148031453007718, "front_wheel_angle": 0.00835424993395996, "heading_rate": 0.007641898936186072, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.7590744} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2404145030764273, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7218832841614157, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3320738534346095, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.14089634271035242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.7590744} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.089987516403198, "x": 25.825900456715573, "y": -0.132225098328826, "z": null, "yaw": 0.03527154545501697, "pitch": null, "roll": null}, "v": 2.341659191396282, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37191663725632096, "steering_wheel_angle": 0.18148031453007718, "front_wheel_angle": 0.00835424993395996, "heading_rate": 0.007641898936186072, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.7790744} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2404145030764273, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7218832841614157, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.329707022856815, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.14089634271035242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.7790744} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502651.7890744, "x": 30.082660758141525, "y": 4.876869217002136, "z": null, "yaw": 0.035557407832536796, "pitch": null, "roll": null}, "v": 2.3285253223064286, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.370646567881544, "steering_wheel_angle": 0.14089634271035242, "front_wheel_angle": 0.006482541627269961, "heading_rate": 0.005896474132694437, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.7990744} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22943087960732184, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7538579894088178, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.32734476306989, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.14089634271035242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.7990744} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.199987411499023, "x": 26.082660758141525, "y": -0.12313078299786362, "z": null, "yaw": 0.035557407832536796, "pitch": null, "roll": null}, "v": 2.3285253223064286, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.370646567881544, "steering_wheel_angle": 0.14089634271035242, "front_wheel_angle": 0.006482541627269961, "heading_rate": 0.005896474132694437, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.8190744} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23279976068148903, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7538579894088178, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3236147726447762, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1002334571097898, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.8190744} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.199987411499023, "x": 26.082660758141525, "y": -0.12313078299786362, "z": null, "yaw": 0.035557407832536796, "pitch": null, "roll": null}, "v": 2.3285253223064286, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.370646567881544, "steering_wheel_angle": 0.14089634271035242, "front_wheel_angle": 0.006482541627269961, "heading_rate": 0.005896474132694437, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.8390744} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23279976068148903, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7538579894088178, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.320312884034528, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1002334571097898, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.8390744} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.199987411499023, "x": 26.082660758141525, "y": -0.12313078299786362, "z": null, "yaw": 0.035557407832536796, "pitch": null, "roll": null}, "v": 2.3285253223064286, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.370646567881544, "steering_wheel_angle": 0.14089634271035242, "front_wheel_angle": 0.006482541627269961, "heading_rate": 0.005896474132694437, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.8590744} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23279976068148903, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7538579894088178, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3170173598996544, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1002334571097898, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.8590744} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.199987411499023, "x": 26.082660758141525, "y": -0.12313078299786362, "z": null, "yaw": 0.035557407832536796, "pitch": null, "roll": null}, "v": 2.3285253223064286, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.370646567881544, "steering_wheel_angle": 0.14089634271035242, "front_wheel_angle": 0.006482541627269961, "heading_rate": 0.005896474132694437, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.8790743} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23279976068148903, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7538579894088178, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.313728183630363, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1002334571097898, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.8790743} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502651.8990743, "x": 30.337739563265007, "y": 4.885969168449787, "z": null, "yaw": 0.0357700968551492, "pitch": null, "roll": null}, "v": 2.310445338673953, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36890384356369965, "steering_wheel_angle": 0.1002334571097898, "front_wheel_angle": 0.004609203461379754, "heading_rate": 0.004159917213673361, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.8990743} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2346995491562875, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8126228432467358, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.310445338673953, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1002334571097898, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.8990743} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.309987306594849, "x": 26.337739563265007, "y": -0.11403083155021321, "z": null, "yaw": 0.0357700968551492, "pitch": null, "roll": null}, "v": 2.310445338673953, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36890384356369965, "steering_wheel_angle": 0.1002334571097898, "front_wheel_angle": 0.004609203461379754, "heading_rate": 0.004159917213673361, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.9190743} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23401872859564002, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8126228432467358, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.307406167896072, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.018646035287163226, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.9190743} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.309987306594849, "x": 26.337739563265007, "y": -0.11403083155021321, "z": null, "yaw": 0.0357700968551492, "pitch": null, "roll": null}, "v": 2.310445338673953, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36890384356369965, "steering_wheel_angle": 0.1002334571097898, "front_wheel_angle": 0.004609203461379754, "heading_rate": 0.004159917213673361, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.9390743} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23401872859564002, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8126228432467358, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3042877777722763, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.018646035287163226, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.9390743} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.309987306594849, "x": 26.337739563265007, "y": -0.11403083155021321, "z": null, "yaw": 0.0357700968551492, "pitch": null, "roll": null}, "v": 2.310445338673953, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36890384356369965, "steering_wheel_angle": 0.1002334571097898, "front_wheel_angle": 0.004609203461379754, "heading_rate": 0.004159917213673361, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.9590743} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23401872859564002, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8126228432467358, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3011753783988267, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.018646035287163226, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.9590743} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.309987306594849, "x": 26.337739563265007, "y": -0.11403083155021321, "z": null, "yaw": 0.0357700968551492, "pitch": null, "roll": null}, "v": 2.310445338673953, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36890384356369965, "steering_wheel_angle": 0.1002334571097898, "front_wheel_angle": 0.004609203461379754, "heading_rate": 0.004159917213673361, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.9790742} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23401872859564002, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8126228432467358, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.298068954393918, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.018646035287163226, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.9790742} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.309987306594849, "x": 26.337739563265007, "y": -0.11403083155021321, "z": null, "yaw": 0.0357700968551492, "pitch": null, "roll": null}, "v": 2.310445338673953, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36890384356369965, "steering_wheel_angle": 0.1002334571097898, "front_wheel_angle": 0.004609203461379754, "heading_rate": 0.004159917213673361, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502651.9990742} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23401872859564002, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8126228432467358, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.294968490427586, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.018646035287163226, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502651.9990742} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502652.0090742, "x": 30.59087714125104, "y": 4.895036917933571, "z": null, "yaw": 0.03582888876619402, "pitch": null, "roll": null}, "v": 2.2934204886823943, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3672687998132017, "steering_wheel_angle": 0.018646035287163226, "front_wheel_angle": 0.0008565139690646242, "heading_rate": 0.0007673231116619004, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.0190742} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23458828703352483, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8553004495516543, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2918739712214897, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.018646035287163226, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.0190742} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.419987201690674, "x": 26.59087714125104, "y": -0.1049630820664289, "z": null, "yaw": 0.03582888876619402, "pitch": null, "roll": null}, "v": 2.2934204886823943, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3672687998132017, "steering_wheel_angle": 0.018646035287163226, "front_wheel_angle": 0.0008565139690646242, "heading_rate": 0.0007673231116619004, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.0390742} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23432854766386252, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8553004495516543, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.288856542248648, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.02224807173931206, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.0390742} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.419987201690674, "x": 26.59087714125104, "y": -0.1049630820664289, "z": null, "yaw": 0.03582888876619402, "pitch": null, "roll": null}, "v": 2.2934204886823943, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3672687998132017, "steering_wheel_angle": 0.018646035287163226, "front_wheel_angle": 0.0008565139690646242, "heading_rate": 0.0007673231116619004, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.0590742} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23432854766386252, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8553004495516543, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.28581243955374, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.02224807173931206, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.0590742} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.419987201690674, "x": 26.59087714125104, "y": -0.1049630820664289, "z": null, "yaw": 0.03582888876619402, "pitch": null, "roll": null}, "v": 2.2934204886823943, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3672687998132017, "steering_wheel_angle": 0.018646035287163226, "front_wheel_angle": 0.0008565139690646242, "heading_rate": 0.0007673231116619004, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.0790741} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23432854766386252, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8553004495516543, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2827741623979767, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.02224807173931206, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.0790741} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.419987201690674, "x": 26.59087714125104, "y": -0.1049630820664289, "z": null, "yaw": 0.03582888876619402, "pitch": null, "roll": null}, "v": 2.2934204886823943, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3672687998132017, "steering_wheel_angle": 0.018646035287163226, "front_wheel_angle": 0.0008565139690646242, "heading_rate": 0.0007673231116619004, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.0990741} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23432854766386252, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8553004495516543, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2797416959422607, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.02224807173931206, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.0990741} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502652.119074, "x": 30.84215538640039, "y": 4.904041964420242, "z": null, "yaw": 0.03579964976111607, "pitch": null, "roll": null}, "v": 2.2767150253970527, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36567006433853966, "steering_wheel_angle": -0.02224807173931206, "front_wheel_angle": -0.0010220233838201293, "heading_rate": -0.0009089284392223138, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.129074} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23094750708295017, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8523774919155308, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2752038589826586, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.02224807173931206, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.129074} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.529987096786499, "x": 26.84215538640039, "y": -0.09595803557975824, "z": null, "yaw": 0.03579964976111607, "pitch": null, "roll": null}, "v": 2.2767150253970527, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36567006433853966, "steering_wheel_angle": -0.02224807173931206, "front_wheel_angle": -0.0010220233838201293, "heading_rate": -0.0009089284392223138, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.129074} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.529987096786499, "x": 26.84215538640039, "y": -0.09595803557975824, "z": null, "yaw": 0.03579964976111607, "pitch": null, "roll": null}, "v": 2.2767150253970527, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36567006433853966, "steering_wheel_angle": -0.02224807173931206, "front_wheel_angle": -0.0010220233838201293, "heading_rate": -0.0009089284392223138, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.149074} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23192414613108664, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8523774919155308, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2718854479603414, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.02224807173931206, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.149074} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.529987096786499, "x": 26.84215538640039, "y": -0.09595803557975824, "z": null, "yaw": 0.03579964976111607, "pitch": null, "roll": null}, "v": 2.2767150253970527, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36567006433853966, "steering_wheel_angle": -0.02224807173931206, "front_wheel_angle": -0.0010220233838201293, "heading_rate": -0.0009089284392223138, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.169074} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23192414613108664, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8523774919155308, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2685733690470635, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.02224807173931206, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.169074} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.529987096786499, "x": 26.84215538640039, "y": -0.09595803557975824, "z": null, "yaw": 0.03579964976111607, "pitch": null, "roll": null}, "v": 2.2767150253970527, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36567006433853966, "steering_wheel_angle": -0.02224807173931206, "front_wheel_angle": -0.0010220233838201293, "heading_rate": -0.0009089284392223138, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.189074} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23192414613108664, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8523774919155308, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2652676057741963, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.02224807173931206, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.189074} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.529987096786499, "x": 26.84215538640039, "y": -0.09595803557975824, "z": null, "yaw": 0.03579964976111607, "pitch": null, "roll": null}, "v": 2.2767150253970527, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36567006433853966, "steering_wheel_angle": -0.02224807173931206, "front_wheel_angle": -0.0010220233838201293, "heading_rate": -0.0009089284392223138, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.209074} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23192414613108664, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8523774919155308, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.261968141729608, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.02224807173931206, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.209074} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502652.229074, "x": 31.091538107593223, "y": 4.912968617288109, "z": null, "yaw": 0.03575573467855233, "pitch": null, "roll": null}, "v": 2.2586749605574217, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3639498738023618, "steering_wheel_angle": -0.02224807173931206, "front_wheel_angle": -0.0010220233838201293, "heading_rate": -0.0009017263397960603, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.229074} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23374662829546075, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8888953691604239, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2586749605574217, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.02224807173931206, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.229074} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.639986991882324, "x": 27.091538107593223, "y": -0.08703138271189115, "z": null, "yaw": 0.03575573467855233, "pitch": null, "roll": null}, "v": 2.2586749605574217, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3639498738023618, "steering_wheel_angle": -0.02224807173931206, "front_wheel_angle": -0.0010220233838201293, "heading_rate": -0.0009017263397960603, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.249074} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2330910926624823, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8888953691604239, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.255615747856979, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.06314509513433528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.249074} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.639986991882324, "x": 27.091538107593223, "y": -0.08703138271189115, "z": null, "yaw": 0.03575573467855233, "pitch": null, "roll": null}, "v": 2.2586749605574217, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3639498738023618, "steering_wheel_angle": -0.02224807173931206, "front_wheel_angle": -0.0010220233838201293, "heading_rate": -0.0009017263397960603, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.269074} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2330910926624823, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8888953691604239, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2524804497021735, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.06314509513433528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.269074} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.639986991882324, "x": 27.091538107593223, "y": -0.08703138271189115, "z": null, "yaw": 0.03575573467855233, "pitch": null, "roll": null}, "v": 2.2586749605574217, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3639498738023618, "steering_wheel_angle": -0.02224807173931206, "front_wheel_angle": -0.0010220233838201293, "heading_rate": -0.0009017263397960603, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.289074} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2330910926624823, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8888953691604239, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2493511098746213, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.06314509513433528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.289074} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.639986991882324, "x": 27.091538107593223, "y": -0.08703138271189115, "z": null, "yaw": 0.03575573467855233, "pitch": null, "roll": null}, "v": 2.2586749605574217, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3639498738023618, "steering_wheel_angle": -0.02224807173931206, "front_wheel_angle": -0.0010220233838201293, "heading_rate": -0.0009017263397960603, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.309074} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2330910926624823, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8888953691604239, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2462277131358555, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.06314509513433528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.309074} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.639986991882324, "x": 27.091538107593223, "y": -0.08703138271189115, "z": null, "yaw": 0.03575573467855233, "pitch": null, "roll": null}, "v": 2.2586749605574217, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3639498738023618, "steering_wheel_angle": -0.02224807173931206, "front_wheel_angle": -0.0010220233838201293, "heading_rate": -0.0009017263397960603, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.329074} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2330910926624823, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8888953691604239, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.241553728111109, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.06314509513433528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.329074} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502652.339074, "x": 31.338980532388167, "y": 4.9218075041989255, "z": null, "yaw": 0.035638371293744635, "pitch": null, "roll": null}, "v": 2.241553728111109, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36232331756564357, "steering_wheel_angle": -0.06314509513433528, "front_wheel_angle": -0.0029022921281251597, "heading_rate": -0.0025412742211940566, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.349074} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2372700101387549, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9651153917644871, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2399986882268577, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.06314509513433528, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.349074} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.74998688697815, "x": 27.338980532388167, "y": -0.07819249580107446, "z": null, "yaw": 0.035638371293744635, "pitch": null, "roll": null}, "v": 2.241553728111109, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36232331756564357, "steering_wheel_angle": -0.06314509513433528, "front_wheel_angle": -0.0029022921281251597, "heading_rate": -0.0025412742211940566, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.3690739} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2358827697060381, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9651153917644871, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2374151469931594, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.14497858869563646, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.3690739} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.74998688697815, "x": 27.338980532388167, "y": -0.07819249580107446, "z": null, "yaw": 0.035638371293744635, "pitch": null, "roll": null}, "v": 2.241553728111109, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36232331756564357, "steering_wheel_angle": -0.06314509513433528, "front_wheel_angle": -0.0029022921281251597, "heading_rate": -0.0025412742211940566, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.3890738} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2358827697060381, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9651153917644871, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.233289146468975, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.14497858869563646, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.3890738} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.74998688697815, "x": 27.338980532388167, "y": -0.07819249580107446, "z": null, "yaw": 0.035638371293744635, "pitch": null, "roll": null}, "v": 2.241553728111109, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36232331756564357, "steering_wheel_angle": -0.06314509513433528, "front_wheel_angle": -0.0029022921281251597, "heading_rate": -0.0025412742211940566, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.4090738} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2358827697060381, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9651153917644871, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.231916416961194, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.14497858869563646, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.4090738} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.74998688697815, "x": 27.338980532388167, "y": -0.07819249580107446, "z": null, "yaw": 0.035638371293744635, "pitch": null, "roll": null}, "v": 2.241553728111109, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36232331756564357, "steering_wheel_angle": -0.06314509513433528, "front_wheel_angle": -0.0029022921281251597, "heading_rate": -0.0025412742211940566, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.4290738} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2358827697060381, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9651153917644871, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.227806017915935, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.14497858869563646, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.4290738} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502652.4490738, "x": 31.58463638556982, "y": 4.930541546102588, "z": null, "yaw": 0.035388536495359654, "pitch": null, "roll": null}, "v": 2.2264384760482585, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3608922066786938, "steering_wheel_angle": -0.14497858869563646, "front_wheel_angle": -0.0066707216039725015, "heading_rate": -0.005801629508852215, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.4490738} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23990853577486512, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0464766659494806, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2264384760482585, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.14497858869563646, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.4490738} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.859986782073975, "x": 27.58463638556982, "y": -0.06945845389741212, "z": null, "yaw": 0.035388536495359654, "pitch": null, "roll": null}, "v": 2.2264384760482585, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3608922066786938, "steering_wheel_angle": -0.14497858869563646, "front_wheel_angle": -0.0066707216039725015, "heading_rate": -0.005801629508852215, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.4690738} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23857892746225004, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0464766659494806, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.224210252416436, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2268192194304395, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.4690738} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.859986782073975, "x": 27.58463638556982, "y": -0.06945845389741212, "z": null, "yaw": 0.035388536495359654, "pitch": null, "roll": null}, "v": 2.2264384760482585, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3608922066786938, "steering_wheel_angle": -0.14497858869563646, "front_wheel_angle": -0.0066707216039725015, "heading_rate": -0.005801629508852215, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.4890738} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23857892746225004, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0464766659494806, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.218243367894741, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2268192194304395, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.4890738} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.859986782073975, "x": 27.58463638556982, "y": -0.06945845389741212, "z": null, "yaw": 0.035388536495359654, "pitch": null, "roll": null}, "v": 2.2264384760482585, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3608922066786938, "steering_wheel_angle": -0.14497858869563646, "front_wheel_angle": -0.0066707216039725015, "heading_rate": -0.005801629508852215, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.5190737} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23857892746225004, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0464766659494806, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2170533688132634, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2268192194304395, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.5190737} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.859986782073975, "x": 27.58463638556982, "y": -0.06945845389741212, "z": null, "yaw": 0.035388536495359654, "pitch": null, "roll": null}, "v": 2.2264384760482585, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3608922066786938, "steering_wheel_angle": -0.14497858869563646, "front_wheel_angle": -0.0066707216039725015, "heading_rate": -0.005801629508852215, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.5490737} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23857892746225004, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0464766659494806, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2134901029987133, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2268192194304395, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.5490737} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502652.5590737, "x": 31.828752100396937, "y": 4.939138980365528, "z": null, "yaw": 0.03496173063127122, "pitch": null, "roll": null}, "v": 2.2134901029987133, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3596698895106682, "steering_wheel_angle": -0.2268192194304395, "front_wheel_angle": -0.010447630475150904, "heading_rate": -0.009033815666908487, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.5690737} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24261774015171667, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1304861721591302, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.212304587069997, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2268192194304395, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.5690737} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.9699866771698, "x": 27.828752100396937, "y": -0.06086101963447188, "z": null, "yaw": 0.03496173063127122, "pitch": null, "roll": null}, "v": 2.2134901029987133, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3596698895106682, "steering_wheel_angle": -0.2268192194304395, "front_wheel_angle": -0.010447630475150904, "heading_rate": -0.009033815666908487, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.5890737} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24129449446026957, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1304861721591302, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.208416634048157, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.30867305820430213, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.5890737} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.9699866771698, "x": 27.828752100396937, "y": -0.06086101963447188, "z": null, "yaw": 0.03496173063127122, "pitch": null, "roll": null}, "v": 2.2134901029987133, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3596698895106682, "steering_wheel_angle": -0.2268192194304395, "front_wheel_angle": -0.010447630475150904, "heading_rate": -0.009033815666908487, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.6090736} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24129449446026957, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1304861721591302, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.208416634048157, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.30867305820430213, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.6090736} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.9699866771698, "x": 27.828752100396937, "y": -0.06086101963447188, "z": null, "yaw": 0.03496173063127122, "pitch": null, "roll": null}, "v": 2.2134901029987133, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3596698895106682, "steering_wheel_angle": -0.2268192194304395, "front_wheel_angle": -0.010447630475150904, "heading_rate": -0.009033815666908487, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.6390736} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24129449446026957, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1304861721591302, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.20337107848732, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.30867305820430213, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.6390736} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 13.9699866771698, "x": 27.828752100396937, "y": -0.06086101963447188, "z": null, "yaw": 0.03496173063127122, "pitch": null, "roll": null}, "v": 2.2134901029987133, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3596698895106682, "steering_wheel_angle": -0.2268192194304395, "front_wheel_angle": -0.010447630475150904, "heading_rate": -0.009033815666908487, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.6590736} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24129449446026957, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1304861721591302, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.20337107848732, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.30867305820430213, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.6590736} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502652.6690736, "x": 32.0715296456771, "y": 4.947570361488407, "z": null, "yaw": 0.034387075665919024, "pitch": null, "roll": null}, "v": 2.202364814440892, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35862234848091723, "steering_wheel_angle": -0.30867305820430213, "front_wheel_angle": -0.01423335508064699, "heading_rate": -0.012245764625586885, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.6890736} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24044630301081726, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1038620413109053, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2003551246517445, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.30867305820430213, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.6890736} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.079986572265625, "x": 28.071529645677103, "y": -0.05242963851159299, "z": null, "yaw": 0.034387075665919024, "pitch": null, "roll": null}, "v": 2.202364814440892, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35862234848091723, "steering_wheel_angle": -0.30867305820430213, "front_wheel_angle": -0.01423335508064699, "heading_rate": -0.012245764625586885, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.6990736} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24065898592672935, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1038620413109053, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.199298684760137, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.30867305820430213, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.6990736} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.079986572265625, "x": 28.071529645677103, "y": -0.05242963851159299, "z": null, "yaw": 0.034387075665919024, "pitch": null, "roll": null}, "v": 2.202364814440892, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35862234848091723, "steering_wheel_angle": -0.30867305820430213, "front_wheel_angle": -0.01423335508064699, "heading_rate": -0.012245764625586885, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.7190735} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24065898592672935, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1038620413109053, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1972153557454166, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.30867305820430213, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.7190735} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.079986572265625, "x": 28.071529645677103, "y": -0.05242963851159299, "z": null, "yaw": 0.034387075665919024, "pitch": null, "roll": null}, "v": 2.202364814440892, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35862234848091723, "steering_wheel_angle": -0.30867305820430213, "front_wheel_angle": -0.01423335508064699, "heading_rate": -0.012245764625586885, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.7390735} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24065898592672935, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1038620413109053, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1940976961351137, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.30867305820430213, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.7390735} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.079986572265625, "x": 28.071529645677103, "y": -0.05242963851159299, "z": null, "yaw": 0.034387075665919024, "pitch": null, "roll": null}, "v": 2.202364814440892, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35862234848091723, "steering_wheel_angle": -0.30867305820430213, "front_wheel_angle": -0.01423335508064699, "heading_rate": -0.012245764625586885, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.7590735} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24065898592672935, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1038620413109053, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.193060427437448, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.30867305820430213, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.7590735} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502652.7790735, "x": 32.31308249056445, "y": 4.9558127625440465, "z": null, "yaw": 0.033775444886139885, "pitch": null, "roll": null}, "v": 2.190988810014791, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3575537601568399, "steering_wheel_angle": -0.30867305820430213, "front_wheel_angle": -0.01423335508064699, "heading_rate": -0.012182510857787736, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.7790735} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2399176657521917, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0706804667169607, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.190988810014791, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.30867305820430213, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.7790735} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.18998646736145, "x": 28.313082490564447, "y": -0.04418723745595354, "z": null, "yaw": 0.033775444886139885, "pitch": null, "roll": null}, "v": 2.190988810014791, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3575537601568399, "steering_wheel_angle": -0.30867305820430213, "front_wheel_angle": -0.01423335508064699, "heading_rate": -0.012182510857787736, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.7990735} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24009589900738967, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0706804667169607, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1888284568087246, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.30867305820430213, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.7990735} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.18998646736145, "x": 28.313082490564447, "y": -0.04418723745595354, "z": null, "yaw": 0.033775444886139885, "pitch": null, "roll": null}, "v": 2.190988810014791, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3575537601568399, "steering_wheel_angle": -0.30867305820430213, "front_wheel_angle": -0.01423335508064699, "heading_rate": -0.012182510857787736, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.8190734} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24009589900738967, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0706804667169607, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.186694422692539, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.30867305820430213, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.8190734} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.18998646736145, "x": 28.313082490564447, "y": -0.04418723745595354, "z": null, "yaw": 0.033775444886139885, "pitch": null, "roll": null}, "v": 2.190988810014791, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3575537601568399, "steering_wheel_angle": -0.30867305820430213, "front_wheel_angle": -0.01423335508064699, "heading_rate": -0.012182510857787736, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.8390734} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24009589900738967, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0706804667169607, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.184564387782894, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.30867305820430213, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.8390734} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.18998646736145, "x": 28.313082490564447, "y": -0.04418723745595354, "z": null, "yaw": 0.033775444886139885, "pitch": null, "roll": null}, "v": 2.190988810014791, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3575537601568399, "steering_wheel_angle": -0.30867305820430213, "front_wheel_angle": -0.01423335508064699, "heading_rate": -0.012182510857787736, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.8590734} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24009589900738967, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0706804667169607, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.182438342771258, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.30867305820430213, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.8590734} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.18998646736145, "x": 28.313082490564447, "y": -0.04418723745595354, "z": null, "yaw": 0.033775444886139885, "pitch": null, "roll": null}, "v": 2.190988810014791, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3575537601568399, "steering_wheel_angle": -0.30867305820430213, "front_wheel_angle": -0.01423335508064699, "heading_rate": -0.012182510857787736, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.8790734} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24009589900738967, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0706804667169607, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1792567360181256, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.30867305820430213, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.8790734} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502652.8890734, "x": 32.553367675768996, "y": 4.963864776056965, "z": null, "yaw": 0.033163814106360746, "pitch": null, "roll": null}, "v": 2.1792567360181256, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35645443601571003, "steering_wheel_angle": -0.30867305820430213, "front_wheel_angle": -0.01423335508064699, "heading_rate": -0.012117277243542219, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.8990734} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24396543562785994, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.142299607521185, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1781981853459302, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.30867305820430213, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.8990734} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.299986362457275, "x": 28.553367675768996, "y": -0.03613522394303459, "z": null, "yaw": 0.033163814106360746, "pitch": null, "roll": null}, "v": 2.1792567360181256, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35645443601571003, "steering_wheel_angle": -0.30867305820430213, "front_wheel_angle": -0.01423335508064699, "heading_rate": -0.012117277243542219, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.9190733} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2427012383980342, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.142299607521185, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.176567520295043, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.30867305820430213, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.9190733} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.299986362457275, "x": 28.553367675768996, "y": -0.03613522394303459, "z": null, "yaw": 0.033163814106360746, "pitch": null, "roll": null}, "v": 2.1792567360181256, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35645443601571003, "steering_wheel_angle": -0.30867305820430213, "front_wheel_angle": -0.01423335508064699, "heading_rate": -0.012117277243542219, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.9390733} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2427012383980342, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.142299607521185, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1747819536835764, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.30867305820430213, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.9390733} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.299986362457275, "x": 28.553367675768996, "y": -0.03613522394303459, "z": null, "yaw": 0.033163814106360746, "pitch": null, "roll": null}, "v": 2.1792567360181256, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35645443601571003, "steering_wheel_angle": -0.30867305820430213, "front_wheel_angle": -0.01423335508064699, "heading_rate": -0.012117277243542219, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.9590733} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2427012383980342, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.142299607521185, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1729997246837733, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.30867305820430213, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.9590733} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.299986362457275, "x": 28.553367675768996, "y": -0.03613522394303459, "z": null, "yaw": 0.033163814106360746, "pitch": null, "roll": null}, "v": 2.1792567360181256, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35645443601571003, "steering_wheel_angle": -0.30867305820430213, "front_wheel_angle": -0.01423335508064699, "heading_rate": -0.012117277243542219, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.9790733} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2427012383980342, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.142299607521185, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1712208257869694, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.30867305820430213, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.9790733} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502652.9990733, "x": 32.79246247079454, "y": 4.97173048951879, "z": null, "yaw": 0.03255218332658161, "pitch": null, "roll": null}, "v": 2.1694452495056504, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35553718938130885, "steering_wheel_angle": -0.30867305820430213, "front_wheel_angle": -0.01423335508064699, "heading_rate": -0.012062722633120242, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502652.9990733} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24142636323639471, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1078380073892418, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1694452495056504, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.30867305820430213, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502652.9990733} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.4099862575531, "x": 28.79246247079454, "y": -0.02826951048121007, "z": null, "yaw": 0.03255218332658161, "pitch": null, "roll": null}, "v": 2.1694452495056504, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35553718938130885, "steering_wheel_angle": -0.30867305820430213, "front_wheel_angle": -0.01423335508064699, "heading_rate": -0.012062722633120242, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.0190732} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24177889962382787, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1078380073892418, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1675137033754073, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.30867305820430213, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.0190732} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.4099862575531, "x": 28.79246247079454, "y": -0.02826951048121007, "z": null, "yaw": 0.03255218332658161, "pitch": null, "roll": null}, "v": 2.1694452495056504, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35553718938130885, "steering_wheel_angle": -0.30867305820430213, "front_wheel_angle": -0.01423335508064699, "heading_rate": -0.012062722633120242, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.0390732} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24177889962382787, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1078380073892418, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1656298086263623, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.30867305820430213, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.0390732} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.4099862575531, "x": 28.79246247079454, "y": -0.02826951048121007, "z": null, "yaw": 0.03255218332658161, "pitch": null, "roll": null}, "v": 2.1694452495056504, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35553718938130885, "steering_wheel_angle": -0.30867305820430213, "front_wheel_angle": -0.01423335508064699, "heading_rate": -0.012062722633120242, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.0590732} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24177889962382787, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1078380073892418, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1637494284139036, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.30867305820430213, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.0590732} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.4099862575531, "x": 28.79246247079454, "y": -0.02826951048121007, "z": null, "yaw": 0.03255218332658161, "pitch": null, "roll": null}, "v": 2.1694452495056504, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35553718938130885, "steering_wheel_angle": -0.30867305820430213, "front_wheel_angle": -0.01423335508064699, "heading_rate": -0.012062722633120242, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.0790732} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24177889962382787, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1078380073892418, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1618725547677466, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.30867305820430213, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.0790732} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.4099862575531, "x": 28.79246247079454, "y": -0.02826951048121007, "z": null, "yaw": 0.03255218332658161, "pitch": null, "roll": null}, "v": 2.1694452495056504, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35553718938130885, "steering_wheel_angle": -0.30867305820430213, "front_wheel_angle": -0.01423335508064699, "heading_rate": -0.012062722633120242, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.0990732} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24177889962382787, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1078380073892418, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1599991797403786, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.30867305820430213, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.0990732} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502653.1090732, "x": 33.030455416387014, "y": 4.979414239872165, "z": null, "yaw": 0.03194055254680247, "pitch": null, "roll": null}, "v": 2.15906380173135, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3545687550860338, "steering_wheel_angle": -0.30867305820430213, "front_wheel_angle": -0.01423335508064699, "heading_rate": -0.012004998878598136, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.1190732} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2453101476203484, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1814088138247745, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1581292954069786, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.30867305820430213, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.1190732} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.519986152648926, "x": 29.030455416387014, "y": -0.020585760127834973, "z": null, "yaw": 0.03194055254680247, "pitch": null, "roll": null}, "v": 2.15906380173135, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3545687550860338, "steering_wheel_angle": -0.30867305820430213, "front_wheel_angle": -0.01423335508064699, "heading_rate": -0.012004998878598136, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.1390731} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2441582101514029, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1814088138247745, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1567040942886204, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.34959118768706327, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.1390731} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.519986152648926, "x": 29.030455416387014, "y": -0.020585760127834973, "z": null, "yaw": 0.03194055254680247, "pitch": null, "roll": null}, "v": 2.15906380173135, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3545687550860338, "steering_wheel_angle": -0.30867305820430213, "front_wheel_angle": -0.01423335508064699, "heading_rate": -0.012004998878598136, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.159073} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2441582101514029, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1814088138247745, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.155137621691543, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.34959118768706327, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.159073} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.519986152648926, "x": 29.030455416387014, "y": -0.020585760127834973, "z": null, "yaw": 0.03194055254680247, "pitch": null, "roll": null}, "v": 2.15906380173135, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3545687550860338, "steering_wheel_angle": -0.30867305820430213, "front_wheel_angle": -0.01423335508064699, "heading_rate": -0.012004998878598136, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.179073} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2441582101514029, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1814088138247745, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.153574064840105, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.34959118768706327, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.179073} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.519986152648926, "x": 29.030455416387014, "y": -0.020585760127834973, "z": null, "yaw": 0.03194055254680247, "pitch": null, "roll": null}, "v": 2.15906380173135, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3545687550860338, "steering_wheel_angle": -0.30867305820430213, "front_wheel_angle": -0.01423335508064699, "heading_rate": -0.012004998878598136, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.199073} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2441582101514029, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1814088138247745, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.152013417329669, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.34959118768706327, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.199073} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502653.219073, "x": 33.267400193838746, "y": 4.986913325115141, "z": null, "yaw": 0.031262265984093325, "pitch": null, "roll": null}, "v": 2.1504556727729724, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35376737964426325, "steering_wheel_angle": -0.34959118768706327, "front_wheel_angle": -0.016128904298900893, "heading_rate": -0.013549805345395707, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.219073} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2473615911292718, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2607850755094827, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1504556727729724, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.34959118768706327, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.219073} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.629986047744751, "x": 29.267400193838746, "y": -0.013086674884858596, "z": null, "yaw": 0.031262265984093325, "pitch": null, "roll": null}, "v": 2.1504556727729724, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35376737964426325, "steering_wheel_angle": -0.34959118768706327, "front_wheel_angle": -0.016128904298900893, "heading_rate": -0.013549805345395707, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.239073} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24632046511898384, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2607850755094827, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1486594902688068, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.43147486109095406, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.239073} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.629986047744751, "x": 29.267400193838746, "y": -0.013086674884858596, "z": null, "yaw": 0.031262265984093325, "pitch": null, "roll": null}, "v": 2.1504556727729724, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35376737964426325, "steering_wheel_angle": -0.34959118768706327, "front_wheel_angle": -0.016128904298900893, "heading_rate": -0.013549805345395707, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.259073} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24632046511898384, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2607850755094827, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1480185158330967, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.43147486109095406, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.259073} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.629986047744751, "x": 29.267400193838746, "y": -0.013086674884858596, "z": null, "yaw": 0.031262265984093325, "pitch": null, "roll": null}, "v": 2.1504556727729724, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35376737964426325, "steering_wheel_angle": -0.34959118768706327, "front_wheel_angle": -0.016128904298900893, "heading_rate": -0.013549805345395707, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.279073} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24632046511898384, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2607850755094827, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.146099165342398, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.43147486109095406, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.279073} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.629986047744751, "x": 29.267400193838746, "y": -0.013086674884858596, "z": null, "yaw": 0.031262265984093325, "pitch": null, "roll": null}, "v": 2.1504556727729724, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35376737964426325, "steering_wheel_angle": -0.34959118768706327, "front_wheel_angle": -0.016128904298900893, "heading_rate": -0.013549805345395707, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.299073} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24632046511898384, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2607850755094827, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.145460570666915, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.43147486109095406, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.299073} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.629986047744751, "x": 29.267400193838746, "y": -0.013086674884858596, "z": null, "yaw": 0.031262265984093325, "pitch": null, "roll": null}, "v": 2.1504556727729724, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35376737964426325, "steering_wheel_angle": -0.34959118768706327, "front_wheel_angle": -0.016128904298900893, "heading_rate": -0.013549805345395707, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.319073} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24632046511898384, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2607850755094827, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.144185160745356, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.43147486109095406, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.319073} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502653.329073, "x": 33.50349744868285, "y": 4.994209347695843, "z": null, "yaw": 0.030428123429082722, "pitch": null, "roll": null}, "v": 2.1435483442345635, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3531254122524356, "steering_wheel_angle": -0.43147486109095406, "front_wheel_angle": -0.019928425085213565, "heading_rate": -0.016688749402990283, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.339073} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24579733643905552, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2302523090001514, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1429121191819758, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.43147486109095406, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.339073} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.739985942840576, "x": 29.50349744868285, "y": -0.0057906523041566516, "z": null, "yaw": 0.030428123429082722, "pitch": null, "roll": null}, "v": 2.1435483442345635, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3531254122524356, "steering_wheel_angle": -0.43147486109095406, "front_wheel_angle": -0.019928425085213565, "heading_rate": -0.016688749402990283, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.359073} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2459287158680808, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2302523090001514, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.141576080202177, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.43147486109095406, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.359073} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.739985942840576, "x": 29.50349744868285, "y": -0.0057906523041566516, "z": null, "yaw": 0.030428123429082722, "pitch": null, "roll": null}, "v": 2.1435483442345635, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3531254122524356, "steering_wheel_angle": -0.43147486109095406, "front_wheel_angle": -0.019928425085213565, "heading_rate": -0.016688749402990283, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.379073} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2459287158680808, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2302523090001514, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1402589355871884, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.43147486109095406, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.379073} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.739985942840576, "x": 29.50349744868285, "y": -0.0057906523041566516, "z": null, "yaw": 0.030428123429082722, "pitch": null, "roll": null}, "v": 2.1435483442345635, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3531254122524356, "steering_wheel_angle": -0.43147486109095406, "front_wheel_angle": -0.019928425085213565, "heading_rate": -0.016688749402990283, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.399073} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2459287158680808, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2302523090001514, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.138944234768003, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.43147486109095406, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.399073} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.739985942840576, "x": 29.50349744868285, "y": -0.0057906523041566516, "z": null, "yaw": 0.030428123429082722, "pitch": null, "roll": null}, "v": 2.1435483442345635, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3531254122524356, "steering_wheel_angle": -0.43147486109095406, "front_wheel_angle": -0.019928425085213565, "heading_rate": -0.016688749402990283, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.4190729} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2459287158680808, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2302523090001514, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.137631972519412, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.43147486109095406, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.4190729} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502653.4390728, "x": 33.738820215381054, "y": 5.0012803550960765, "z": null, "yaw": 0.02957171053815513, "pitch": null, "roll": null}, "v": 2.1363221436297417, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35245483019511487, "steering_wheel_angle": -0.43147486109095406, "front_wheel_angle": -0.019928425085213565, "heading_rate": -0.01663248929980485, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.4390728} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.249332681366634, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3138341146792594, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.135440041337928, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.4390728} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.849985837936401, "x": 29.738820215381054, "y": 0.001280355096076491, "z": null, "yaw": 0.02957171053815513, "pitch": null, "roll": null}, "v": 2.1363221436297417, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35245483019511487, "steering_wheel_angle": -0.43147486109095406, "front_wheel_angle": -0.019928425085213565, "heading_rate": -0.01663248929980485, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.4590728} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24823541232604446, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3138341146792594, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.135440041337928, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.4590728} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.849985837936401, "x": 29.738820215381054, "y": 0.001280355096076491, "z": null, "yaw": 0.02957171053815513, "pitch": null, "roll": null}, "v": 2.1363221436297417, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35245483019511487, "steering_wheel_angle": -0.43147486109095406, "front_wheel_angle": -0.019928425085213565, "heading_rate": -0.01663248929980485, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.4790728} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24823541232604446, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3138341146792594, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.133406801979329, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.4790728} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.849985837936401, "x": 29.738820215381054, "y": 0.001280355096076491, "z": null, "yaw": 0.02957171053815513, "pitch": null, "roll": null}, "v": 2.1363221436297417, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35245483019511487, "steering_wheel_angle": -0.43147486109095406, "front_wheel_angle": -0.019928425085213565, "heading_rate": -0.01663248929980485, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.4990728} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24823541232604446, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3138341146792594, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.132899669390444, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.4990728} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.849985837936401, "x": 29.738820215381054, "y": 0.001280355096076491, "z": null, "yaw": 0.02957171053815513, "pitch": null, "roll": null}, "v": 2.1363221436297417, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35245483019511487, "steering_wheel_angle": -0.43147486109095406, "front_wheel_angle": -0.019928425085213565, "heading_rate": -0.01663248929980485, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.5290728} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24823541232604446, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3138341146792594, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.131886813499659, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.5290728} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502653.5490727, "x": 33.97344925528266, "y": 5.008122249336927, "z": null, "yaw": 0.028640945272488866, "pitch": null, "roll": null}, "v": 2.1308758334157445, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35195010984513964, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.018174443445816108, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.5490727} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24306865107983722, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1336334305696467, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1308758334157445, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.5490727} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.959985733032227, "x": 29.97344925528266, "y": 0.00812224933692729, "z": null, "yaw": 0.028640945272488866, "pitch": null, "roll": null}, "v": 2.1308758334157445, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35195010984513964, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.018174443445816108, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.5690727} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24465802899385558, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1336334305696467, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.129221179140134, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.5690727} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.959985733032227, "x": 29.97344925528266, "y": 0.00812224933692729, "z": null, "yaw": 0.028640945272488866, "pitch": null, "roll": null}, "v": 2.1308758334157445, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35195010984513964, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.018174443445816108, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.5890727} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24465802899385558, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1336334305696467, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.127768167908988, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.5890727} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.959985733032227, "x": 29.97344925528266, "y": 0.00812224933692729, "z": null, "yaw": 0.028640945272488866, "pitch": null, "roll": null}, "v": 2.1308758334157445, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35195010984513964, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.018174443445816108, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.6090727} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24465802899385558, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1336334305696467, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1263178453237965, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.6090727} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.959985733032227, "x": 29.97344925528266, "y": 0.00812224933692729, "z": null, "yaw": 0.028640945272488866, "pitch": null, "roll": null}, "v": 2.1308758334157445, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35195010984513964, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.018174443445816108, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.6290727} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24465802899385558, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1336334305696467, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1248702055685142, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.6290727} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 14.959985733032227, "x": 29.97344925528266, "y": 0.00812224933692729, "z": null, "yaw": 0.028640945272488866, "pitch": null, "roll": null}, "v": 2.1308758334157445, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35195010984513964, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.018174443445816108, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.6490726} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24465802899385558, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1336334305696467, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.123425242842523, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.6490726} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502653.6590726, "x": 34.20733416786992, "y": 5.014723013834773, "z": null, "yaw": 0.027702744769348735, "pitch": null, "roll": null}, "v": 2.122703763557024, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35119390085604274, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.018104743081696583, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.6690726} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24843115284706307, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1962824257098796, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1219829513605792, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.6690726} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.069985628128052, "x": 30.207334167869917, "y": 0.014723013834773369, "z": null, "yaw": 0.027702744769348735, "pitch": null, "roll": null}, "v": 2.122703763557024, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35119390085604274, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.018104743081696583, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.6890726} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2472142403956109, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1962824257098796, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.121014747871393, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.6890726} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.069985628128052, "x": 30.207334167869917, "y": 0.014723013834773369, "z": null, "yaw": 0.027702744769348735, "pitch": null, "roll": null}, "v": 2.122703763557024, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35119390085604274, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.018104743081696583, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.7090726} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2472142403956109, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1962824257098796, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.11989628950972, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.7090726} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.069985628128052, "x": 30.207334167869917, "y": 0.014723013834773369, "z": null, "yaw": 0.027702744769348735, "pitch": null, "roll": null}, "v": 2.122703763557024, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35119390085604274, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.018104743081696583, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.7290726} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2472142403956109, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1962824257098796, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.118779897182868, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.7290726} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.069985628128052, "x": 30.207334167869917, "y": 0.014723013834773369, "z": null, "yaw": 0.027702744769348735, "pitch": null, "roll": null}, "v": 2.122703763557024, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35119390085604274, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.018104743081696583, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.7490726} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2472142403956109, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1962824257098796, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.117665566576121, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.7490726} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502653.7690725, "x": 34.44043408423429, "y": 5.021082743776419, "z": null, "yaw": 0.026764544266208605, "pitch": null, "roll": null}, "v": 2.1165532933854907, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3506256431066842, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.018052285134337667, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.7690725} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2504454779540754, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2648629303549646, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1165532933854907, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.7690725} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.179985523223877, "x": 30.44043408423429, "y": 0.021082743776418944, "z": null, "yaw": 0.026764544266208605, "pitch": null, "roll": null}, "v": 2.1165532933854907, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3506256431066842, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.018052285134337667, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.7890725} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24940730264890654, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2648629303549646, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.115846791566094, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.7890725} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.179985523223877, "x": 30.44043408423429, "y": 0.021082743776418944, "z": null, "yaw": 0.026764544266208605, "pitch": null, "roll": null}, "v": 2.1165532933854907, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3506256431066842, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.018052285134337667, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.8090725} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24940730264890654, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2648629303549646, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1150118816187224, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.8090725} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.179985523223877, "x": 30.44043408423429, "y": 0.021082743776418944, "z": null, "yaw": 0.026764544266208605, "pitch": null, "roll": null}, "v": 2.1165532933854907, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3506256431066842, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.018052285134337667, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.8290725} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24940730264890654, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2648629303549646, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1141785122774697, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.8290725} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.179985523223877, "x": 30.44043408423429, "y": 0.021082743776418944, "z": null, "yaw": 0.026764544266208605, "pitch": null, "roll": null}, "v": 2.1165532933854907, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3506256431066842, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.018052285134337667, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.8490725} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24940730264890654, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2648629303549646, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1133466804218792, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.8490725} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.179985523223877, "x": 30.44043408423429, "y": 0.021082743776418944, "z": null, "yaw": 0.026764544266208605, "pitch": null, "roll": null}, "v": 2.1165532933854907, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3506256431066842, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.018052285134337667, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.8690724} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24940730264890654, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2648629303549646, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1125163829387894, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.8690724} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502653.8790724, "x": 34.67295711456359, "y": 5.02720841099401, "z": null, "yaw": 0.025826343763068475, "pitch": null, "roll": null}, "v": 2.112101808616058, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3502148309303952, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.018014317995697648, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.8890724} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2503275084745925, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2669554287891478, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.111687616722311, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.8890724} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.289985418319702, "x": 30.672957114563587, "y": 0.02720841099401028, "z": null, "yaw": 0.025826343763068475, "pitch": null, "roll": null}, "v": 2.112101808616058, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3502148309303952, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.018014317995697648, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.9090724} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25001940334324174, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2669554287891478, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1109753513601754, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.9090724} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.289985418319702, "x": 30.672957114563587, "y": 0.02720841099401028, "z": null, "yaw": 0.025826343763068475, "pitch": null, "roll": null}, "v": 2.112101808616058, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3502148309303952, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.018014317995697648, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.9290724} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25001940334324174, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2669554287891478, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.110225903753707, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.9290724} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.289985418319702, "x": 30.672957114563587, "y": 0.02720841099401028, "z": null, "yaw": 0.025826343763068475, "pitch": null, "roll": null}, "v": 2.112101808616058, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3502148309303952, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.018014317995697648, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.9490724} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25001940334324174, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2669554287891478, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1094778376153323, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.9490724} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.289985418319702, "x": 30.672957114563587, "y": 0.02720841099401028, "z": null, "yaw": 0.025826343763068475, "pitch": null, "roll": null}, "v": 2.112101808616058, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3502148309303952, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.018014317995697648, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.9690723} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25001940334324174, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2669554287891478, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1087311501748314, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.9690723} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502653.9890723, "x": 34.90500668906021, "y": 5.033103747227124, "z": null, "yaw": 0.024888143259928344, "pitch": null, "roll": null}, "v": 2.1079858386683274, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3498353348936785, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.017979212495007914, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502653.9890723} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2500482078098386, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2340188547404383, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1079858386683274, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502653.9890723} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.399985313415527, "x": 30.905006689060208, "y": 0.03310374722712428, "z": null, "yaw": 0.024888143259928344, "pitch": null, "roll": null}, "v": 2.1079858386683274, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3498353348936785, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.017979212495007914, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.0090723} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2500202315938486, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2340188547404383, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.107245499237596, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.0090723} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.399985313415527, "x": 30.905006689060208, "y": 0.03310374722712428, "z": null, "yaw": 0.024888143259928344, "pitch": null, "roll": null}, "v": 2.1079858386683274, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3498353348936785, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.017979212495007914, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.0290723} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2500202315938486, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2340188547404383, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1065030281872925, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.0290723} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.399985313415527, "x": 30.905006689060208, "y": 0.03310374722712428, "z": null, "yaw": 0.024888143259928344, "pitch": null, "roll": null}, "v": 2.1079858386683274, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3498353348936785, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.017979212495007914, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.0490723} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2500202315938486, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2340188547404383, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.105761924639941, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.0490723} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.399985313415527, "x": 30.905006689060208, "y": 0.03310374722712428, "z": null, "yaw": 0.024888143259928344, "pitch": null, "roll": null}, "v": 2.1079858386683274, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3498353348936785, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.017979212495007914, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.0690722} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2500202315938486, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2340188547404383, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1050221858572455, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.0690722} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.399985313415527, "x": 30.905006689060208, "y": 0.03310374722712428, "z": null, "yaw": 0.024888143259928344, "pitch": null, "roll": null}, "v": 2.1079858386683274, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3498353348936785, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.017979212495007914, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.0890722} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2500202315938486, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2340188547404383, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.104283809107166, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.0890722} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502654.0990722, "x": 35.13661205810854, "y": 5.038770370663106, "z": null, "yaw": 0.023949942756788214, "pitch": null, "roll": null}, "v": 2.1039151306423007, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34946034530157116, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.017944493037570144, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.1090722} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25271040872936124, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.305298655788238, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1035467916639004, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.1090722} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.509985208511353, "x": 31.13661205810854, "y": 0.03877037066310596, "z": null, "yaw": 0.023949942756788214, "pitch": null, "roll": null}, "v": 2.1039151306423007, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34946034530157116, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.017944493037570144, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.1290722} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25185097833142167, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.305298655788238, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.103147248154903, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.1290722} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.509985208511353, "x": 31.13661205810854, "y": 0.03877037066310596, "z": null, "yaw": 0.023949942756788214, "pitch": null, "roll": null}, "v": 2.1039151306423007, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34946034530157116, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.017944493037570144, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.1490722} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25185097833142167, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.305298655788238, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1026410606351513, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.1490722} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.509985208511353, "x": 31.13661205810854, "y": 0.03877037066310596, "z": null, "yaw": 0.023949942756788214, "pitch": null, "roll": null}, "v": 2.1039151306423007, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34946034530157116, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.017944493037570144, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.1690722} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25185097833142167, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.305298655788238, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.102135804631866, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.1690722} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.509985208511353, "x": 31.13661205810854, "y": 0.03877037066310596, "z": null, "yaw": 0.023949942756788214, "pitch": null, "roll": null}, "v": 2.1039151306423007, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34946034530157116, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.017944493037570144, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.1890721} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25185097833142167, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.305298655788238, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.101631478328749, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.1890721} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502654.209072, "x": 35.36783715951906, "y": 5.0442106183065, "z": null, "yaw": 0.023011742253648083, "pitch": null, "roll": null}, "v": 2.101128079913406, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34920379607767627, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.01792072201578718, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.209072} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25103713648692605, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2314927356380632, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.101128079913406, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.209072} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.619985103607178, "x": 31.367837159519063, "y": 0.04421061830649986, "z": null, "yaw": 0.023011742253648083, "pitch": null, "roll": null}, "v": 2.101128079913406, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34920379607767627, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.01792072201578718, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.229072} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2512786347604748, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2314927356380632, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1005239241513456, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.229072} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.619985103607178, "x": 31.367837159519063, "y": 0.04421061830649986, "z": null, "yaw": 0.023011742253648083, "pitch": null, "roll": null}, "v": 2.101128079913406, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34920379607767627, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.01792072201578718, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.249072} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2512786347604748, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2314927356380632, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0999510530848586, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.249072} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.619985103607178, "x": 31.367837159519063, "y": 0.04421061830649986, "z": null, "yaw": 0.023011742253648083, "pitch": null, "roll": null}, "v": 2.101128079913406, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34920379607767627, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.01792072201578718, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.269072} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2512786347604748, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2314927356380632, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0993792356378536, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.269072} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.619985103607178, "x": 31.367837159519063, "y": 0.04421061830649986, "z": null, "yaw": 0.023011742253648083, "pitch": null, "roll": null}, "v": 2.101128079913406, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34920379607767627, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.01792072201578718, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.289072} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2512786347604748, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2314927356380632, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.098808469741792, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.289072} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.619985103607178, "x": 31.367837159519063, "y": 0.04421061830649986, "z": null, "yaw": 0.023011742253648083, "pitch": null, "roll": null}, "v": 2.101128079913406, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34920379607767627, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.01792072201578718, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.309072} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2512786347604748, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2314927356380632, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.098238753332662, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.309072} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502654.319072, "x": 35.59874199576605, "y": 5.049426584330255, "z": null, "yaw": 0.022073541750507953, "pitch": null, "roll": null}, "v": 2.0979542880419264, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3489118363492314, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.01789365244187187, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.329072} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25383552674264004, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3008274736423704, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.097670084350964, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.329072} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.729984998703003, "x": 31.598741995766048, "y": 0.04942658433025482, "z": null, "yaw": 0.022073541750507953, "pitch": null, "roll": null}, "v": 2.0979542880419264, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3489118363492314, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.01789365244187187, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.349072} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25302189947833553, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3008274736423704, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0974219252991713, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.349072} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.729984998703003, "x": 31.598741995766048, "y": 0.04942658433025482, "z": null, "yaw": 0.022073541750507953, "pitch": null, "roll": null}, "v": 2.0979542880419264, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3489118363492314, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.01789365244187187, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.369072} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25302189947833553, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3008274736423704, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.097072565748265, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.369072} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.729984998703003, "x": 31.598741995766048, "y": 0.04942658433025482, "z": null, "yaw": 0.022073541750507953, "pitch": null, "roll": null}, "v": 2.0979542880419264, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3489118363492314, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.01789365244187187, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.389072} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25302189947833553, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3008274736423704, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.096723848326719, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.389072} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.729984998703003, "x": 31.598741995766048, "y": 0.04942658433025482, "z": null, "yaw": 0.022073541750507953, "pitch": null, "roll": null}, "v": 2.0979542880419264, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3489118363492314, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.01789365244187187, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.409072} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25302189947833553, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3008274736423704, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0963757718056693, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.409072} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502654.429072, "x": 35.82936455629971, "y": 5.054419686825118, "z": null, "yaw": 0.021135341247367823, "pitch": null, "roll": null}, "v": 2.096028334958777, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3487347645574395, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.017877225804129735, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.429072} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25365480889740366, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2985653671977035, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.096028334958777, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.429072} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.839984893798828, "x": 31.82936455629971, "y": 0.054419686825117886, "z": null, "yaw": 0.021135341247367823, "pitch": null, "roll": null}, "v": 2.096028334958777, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3487347645574395, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.017877225804129735, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.449072} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2534481709788729, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2985653671977035, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0957606138799543, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.449072} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.839984893798828, "x": 31.82936455629971, "y": 0.054419686825117886, "z": null, "yaw": 0.021135341247367823, "pitch": null, "roll": null}, "v": 2.096028334958777, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3487347645574395, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.017877225804129735, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.4690719} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2534481709788729, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2985653671977035, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.095467566865461, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.4690719} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.839984893798828, "x": 31.82936455629971, "y": 0.054419686825117886, "z": null, "yaw": 0.021135341247367823, "pitch": null, "roll": null}, "v": 2.096028334958777, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3487347645574395, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.017877225804129735, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.4890718} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2534481709788729, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2985653671977035, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0948830871217305, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.4890718} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.839984893798828, "x": 31.82936455629971, "y": 0.054419686825117886, "z": null, "yaw": 0.021135341247367823, "pitch": null, "roll": null}, "v": 2.096028334958777, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3487347645574395, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.017877225804129735, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.5090718} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2534481709788729, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2985653671977035, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0947373027494782, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.5090718} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.839984893798828, "x": 31.82936455629971, "y": 0.054419686825117886, "z": null, "yaw": 0.021135341247367823, "pitch": null, "roll": null}, "v": 2.096028334958777, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3487347645574395, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.017877225804129735, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.5290718} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2534481709788729, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2985653671977035, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0944461357885276, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.5290718} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502654.5390718, "x": 36.059800149762985, "y": 5.059192447236019, "z": null, "yaw": 0.020197140744227692, "pitch": null, "roll": null}, "v": 2.0944461357885276, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34858935294662136, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.017863731076333406, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.5490718} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2548167100852971, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3259858802203757, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.094155503690569, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4724103096794242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.5490718} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.949984788894653, "x": 32.059800149762985, "y": 0.05919244723601924, "z": null, "yaw": 0.020197140744227692, "pitch": null, "roll": null}, "v": 2.0944461357885276, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34858935294662136, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.017863731076333406, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.5690718} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25438177074883017, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3259858802203757, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0940363942383438, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.5690718} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.949984788894653, "x": 32.059800149762985, "y": 0.05919244723601924, "z": null, "yaw": 0.020197140744227692, "pitch": null, "roll": null}, "v": 2.0944461357885276, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34858935294662136, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.017863731076333406, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.5890718} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25438177074883017, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3259858802203757, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0938631611233802, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.5890718} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.949984788894653, "x": 32.059800149762985, "y": 0.05919244723601924, "z": null, "yaw": 0.020197140744227692, "pitch": null, "roll": null}, "v": 2.0944461357885276, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34858935294662136, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.017863731076333406, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.6090717} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25438177074883017, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3259858802203757, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0937766639208695, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.6090717} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 15.949984788894653, "x": 32.059800149762985, "y": 0.05919244723601924, "z": null, "yaw": 0.020197140744227692, "pitch": null, "roll": null}, "v": 2.0944461357885276, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34858935294662136, "steering_wheel_angle": -0.4724103096794242, "front_wheel_angle": -0.021831015603921974, "heading_rate": -0.017863731076333406, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.6290717} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25438177074883017, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3259858802203757, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0935176488384593, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.6290717} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502654.6490717, "x": 36.290089571891365, "y": 5.0637416671326285, "z": null, "yaw": 0.01919943307295354, "pitch": null, "roll": null}, "v": 2.093431469071242, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3484961266105399, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01941225411710648, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.6490717} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25421905879888973, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.256028963738333, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.093431469071242, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.6490717} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.05998468399048, "x": 32.290089571891365, "y": 0.06374166713262852, "z": null, "yaw": 0.01919943307295354, "pitch": null, "roll": null}, "v": 2.093431469071242, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3484961266105399, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01941225411710648, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.6690717} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2542652449967241, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.256028963738333, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.093239017329979, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.6690717} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.05998468399048, "x": 32.290089571891365, "y": 0.06374166713262852, "z": null, "yaw": 0.01919943307295354, "pitch": null, "roll": null}, "v": 2.093431469071242, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3484961266105399, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01941225411710648, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.6890717} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2542652449967241, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.256028963738333, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.093052689643725, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.6890717} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.05998468399048, "x": 32.290089571891365, "y": 0.06374166713262852, "z": null, "yaw": 0.01919943307295354, "pitch": null, "roll": null}, "v": 2.093431469071242, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3484961266105399, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01941225411710648, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.7090716} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2542652449967241, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.256028963738333, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0928667041288618, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.7090716} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.05998468399048, "x": 32.290089571891365, "y": 0.06374166713262852, "z": null, "yaw": 0.01919943307295354, "pitch": null, "roll": null}, "v": 2.093431469071242, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3484961266105399, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01941225411710648, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.7290716} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2542652449967241, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.256028963738333, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.092681060143197, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.7290716} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.05998468399048, "x": 32.290089571891365, "y": 0.06374166713262852, "z": null, "yaw": 0.01919943307295354, "pitch": null, "roll": null}, "v": 2.093431469071242, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3484961266105399, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01941225411710648, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.7490716} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2542652449967241, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.256028963738333, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0924957570457945, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.7490716} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502654.7590716, "x": 36.52027485063812, "y": 5.068054883553334, "z": null, "yaw": 0.018179410213629132, "pitch": null, "roll": null}, "v": 2.0924032331302413, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34840167455665094, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019402719351973755, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.7690716} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25221898015206917, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.089940982720259, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0923107941969703, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.7690716} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.169984579086304, "x": 32.52027485063812, "y": 0.06805488355333367, "z": null, "yaw": 0.018179410213629132, "pitch": null, "roll": null}, "v": 2.0924032331302413, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34840167455665094, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019402719351973755, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.7890716} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25285371572949444, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.089940982720259, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0918705053122624, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.7890716} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.169984579086304, "x": 32.52027485063812, "y": 0.06805488355333367, "z": null, "yaw": 0.018179410213629132, "pitch": null, "roll": null}, "v": 2.0924032331302413, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34840167455665094, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019402719351973755, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.8090715} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25285371572949444, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.089940982720259, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0915103302913747, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.8090715} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.169984579086304, "x": 32.52027485063812, "y": 0.06805488355333367, "z": null, "yaw": 0.018179410213629132, "pitch": null, "roll": null}, "v": 2.0924032331302413, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34840167455665094, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019402719351973755, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.8290715} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25285371572949444, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.089940982720259, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.091150816478657, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.8290715} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.169984579086304, "x": 32.52027485063812, "y": 0.06805488355333367, "z": null, "yaw": 0.018179410213629132, "pitch": null, "roll": null}, "v": 2.0924032331302413, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34840167455665094, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019402719351973755, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.8490715} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25285371572949444, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.089940982720259, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.09079196260859, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.8490715} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502654.8690715, "x": 36.75030606930743, "y": 5.072130507314262, "z": null, "yaw": 0.017159387354304723, "pitch": null, "roll": null}, "v": 2.0904337674182605, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34822082173053803, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019384456624274883, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.8690715} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2523969330641441, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0498231688508057, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0904337674182605, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.8690715} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.27998447418213, "x": 32.75030606930743, "y": 0.07213050731426218, "z": null, "yaw": 0.017159387354304723, "pitch": null, "roll": null}, "v": 2.0904337674182605, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34822082173053803, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019384456624274883, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.8890715} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25253063509342233, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0498231688508057, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0900191580234675, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.8890715} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.27998447418213, "x": 32.75030606930743, "y": 0.07213050731426218, "z": null, "yaw": 0.017159387354304723, "pitch": null, "roll": null}, "v": 2.0904337674182605, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34822082173053803, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019384456624274883, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.9090714} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25253063509342233, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0498231688508057, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.089423716274936, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.9090714} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.27998447418213, "x": 32.75030606930743, "y": 0.07213050731426218, "z": null, "yaw": 0.017159387354304723, "pitch": null, "roll": null}, "v": 2.0904337674182605, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34822082173053803, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019384456624274883, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.9290714} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25253063509342233, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0498231688508057, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.089225599963524, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.9290714} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.27998447418213, "x": 32.75030606930743, "y": 0.07213050731426218, "z": null, "yaw": 0.017159387354304723, "pitch": null, "roll": null}, "v": 2.0904337674182605, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34822082173053803, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019384456624274883, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.9490714} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25253063509342233, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0498231688508057, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0886323413945687, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.9490714} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.27998447418213, "x": 32.75030606930743, "y": 0.07213050731426218, "z": null, "yaw": 0.017159387354304723, "pitch": null, "roll": null}, "v": 2.0904337674182605, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34822082173053803, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019384456624274883, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.9690714} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25253063509342233, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0498231688508057, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0884349514114584, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.9690714} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502654.9790714, "x": 36.98011098646312, "y": 5.075967647464951, "z": null, "yaw": 0.016139364494980313, "pitch": null, "roll": null}, "v": 2.088237742574464, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3480192558238482, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019364093028453818, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502654.9890714} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25483523724761026, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.094604966054896, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0880407147095643, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502654.9890714} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.389984369277954, "x": 32.98011098646312, "y": 0.07596764746495133, "z": null, "yaw": 0.016139364494980313, "pitch": null, "roll": null}, "v": 2.088237742574464, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3480192558238482, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019364093028453818, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.0090714} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2541049703002917, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.094604966054896, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0879351443036347, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.0090714} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.389984369277954, "x": 32.98011098646312, "y": 0.07596764746495133, "z": null, "yaw": 0.016139364494980313, "pitch": null, "roll": null}, "v": 2.088237742574464, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3480192558238482, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019364093028453818, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.0290713} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2541049703002917, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.094604966054896, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.087640352226534, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.0290713} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.389984369277954, "x": 32.98011098646312, "y": 0.07596764746495133, "z": null, "yaw": 0.016139364494980313, "pitch": null, "roll": null}, "v": 2.088237742574464, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3480192558238482, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019364093028453818, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.0490713} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2541049703002917, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.094604966054896, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.087444274707433, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.0490713} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.389984369277954, "x": 32.98011098646312, "y": 0.07596764746495133, "z": null, "yaw": 0.016139364494980313, "pitch": null, "roll": null}, "v": 2.088237742574464, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3480192558238482, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019364093028453818, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.0690713} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2541049703002917, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.094604966054896, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.087248556824996, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.0690713} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502655.0890713, "x": 37.209732747748575, "y": 5.0795674378286595, "z": null, "yaw": 0.015119341635655915, "pitch": null, "roll": null}, "v": 2.087150832536555, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34791952760440814, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01935401418222931, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.0890713} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25609078645813665, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1432120604874951, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0870531979042792, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.0890713} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.49998426437378, "x": 33.209732747748575, "y": 0.07956743782865949, "z": null, "yaw": 0.015119341635655915, "pitch": null, "roll": null}, "v": 2.087150832536555, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34791952760440814, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01935401418222931, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.1090713} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25546523208769273, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1432120604874951, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.087106310429217, "gear": 1, "accelerator_pedal_position": 0.25609078645813665, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.1090713} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.49998426437378, "x": 33.209732747748575, "y": 0.07956743782865949, "z": null, "yaw": 0.015119341635655915, "pitch": null, "roll": null}, "v": 2.087150832536555, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34791952760440814, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01935401418222931, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.1290712} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25546523208769273, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1432120604874951, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0870937330043797, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.1290712} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.49998426437378, "x": 33.209732747748575, "y": 0.07956743782865949, "z": null, "yaw": 0.015119341635655915, "pitch": null, "roll": null}, "v": 2.087150832536555, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34791952760440814, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01935401418222931, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.1490712} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25546523208769273, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1432120604874951, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0870560699200946, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.1490712} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.49998426437378, "x": 33.209732747748575, "y": 0.07956743782865949, "z": null, "yaw": 0.015119341635655915, "pitch": null, "roll": null}, "v": 2.087150832536555, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34791952760440814, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01935401418222931, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.1690712} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25546523208769273, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1432120604874951, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0870435385867165, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.1690712} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.49998426437378, "x": 33.209732747748575, "y": 0.07956743782865949, "z": null, "yaw": 0.015119341635655915, "pitch": null, "roll": null}, "v": 2.087150832536555, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34791952760440814, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01935401418222931, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.1890712} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25546523208769273, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1432120604874951, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.087006013522499, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.1890712} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502655.1990712, "x": 37.43928591044376, "y": 5.082931940743201, "z": null, "yaw": 0.014099318776331525, "pitch": null, "roll": null}, "v": 2.087006013522499, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34790624168091566, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019352671284912925, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.2090712} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2571740645409922, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1961795172659186, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.086981054153958, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.2090712} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.609984159469604, "x": 33.43928591044376, "y": 0.08293194074320098, "z": null, "yaw": 0.014099318776331525, "pitch": null, "roll": null}, "v": 2.087006013522499, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34790624168091566, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019352671284912925, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.2290711} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25663938975260137, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1961795172659186, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0871696466357452, "gear": 1, "accelerator_pedal_position": 0.2571740645409922, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.2290711} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.609984159469604, "x": 33.43928591044376, "y": 0.08293194074320098, "z": null, "yaw": 0.014099318776331525, "pitch": null, "roll": null}, "v": 2.087006013522499, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34790624168091566, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019352671284912925, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.2490711} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25663938975260137, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1961795172659186, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0872910895475583, "gear": 1, "accelerator_pedal_position": 0.25663938975260137, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.2490711} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.609984159469604, "x": 33.43928591044376, "y": 0.08293194074320098, "z": null, "yaw": 0.014099318776331525, "pitch": null, "roll": null}, "v": 2.087006013522499, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34790624168091566, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019352671284912925, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.269071} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25663938975260137, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1961795172659186, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0874123097254724, "gear": 1, "accelerator_pedal_position": 0.25663938975260137, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.269071} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.609984159469604, "x": 33.43928591044376, "y": 0.08293194074320098, "z": null, "yaw": 0.014099318776331525, "pitch": null, "roll": null}, "v": 2.087006013522499, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34790624168091566, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019352671284912925, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.289071} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25663938975260137, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1961795172659186, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.087472836415068, "gear": 1, "accelerator_pedal_position": 0.25663938975260137, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.289071} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502655.309071, "x": 37.668859729520925, "y": 5.086062522024406, "z": null, "yaw": 0.013079295917007135, "pitch": null, "roll": null}, "v": 2.08759372324685, "accelerator_pedal_position": 0.25663938975260137, "brake_pedal_position": 0.0, "acceleration": 0.006036024258019523, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01935812107903552, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.309071} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2522366296833689, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0974386800922724, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.08759372324685, "gear": 1, "accelerator_pedal_position": 0.25663938975260137, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.309071} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.71998405456543, "x": 33.668859729520925, "y": 0.08606252202440601, "z": null, "yaw": 0.013079295917007135, "pitch": null, "roll": null}, "v": 2.08759372324685, "accelerator_pedal_position": 0.25663938975260137, "brake_pedal_position": 0.0, "acceleration": 0.006036024258019523, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01935812107903552, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.329071} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25361518910959924, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0974386800922724, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.086949877540551, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.329071} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.71998405456543, "x": 33.668859729520925, "y": 0.08606252202440601, "z": null, "yaw": 0.013079295917007135, "pitch": null, "roll": null}, "v": 2.08759372324685, "accelerator_pedal_position": 0.25663938975260137, "brake_pedal_position": 0.0, "acceleration": 0.006036024258019523, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01935812107903552, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.349071} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25361518910959924, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0974386800922724, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.086821815941994, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.349071} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.71998405456543, "x": 33.668859729520925, "y": 0.08606252202440601, "z": null, "yaw": 0.013079295917007135, "pitch": null, "roll": null}, "v": 2.08759372324685, "accelerator_pedal_position": 0.25663938975260137, "brake_pedal_position": 0.0, "acceleration": 0.006036024258019523, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01935812107903552, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.369071} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25361518910959924, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0974386800922724, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0864383355869562, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.369071} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.71998405456543, "x": 33.668859729520925, "y": 0.08606252202440601, "z": null, "yaw": 0.013079295917007135, "pitch": null, "roll": null}, "v": 2.08759372324685, "accelerator_pedal_position": 0.25663938975260137, "brake_pedal_position": 0.0, "acceleration": 0.006036024258019523, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01935812107903552, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.389071} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25361518910959924, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0974386800922724, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.086183267941681, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.389071} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.71998405456543, "x": 33.668859729520925, "y": 0.08606252202440601, "z": null, "yaw": 0.013079295917007135, "pitch": null, "roll": null}, "v": 2.08759372324685, "accelerator_pedal_position": 0.25663938975260137, "brake_pedal_position": 0.0, "acceleration": 0.006036024258019523, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01935812107903552, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.409071} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25361518910959924, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0974386800922724, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0860559095643163, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.409071} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502655.419071, "x": 37.89838302137313, "y": 5.088958276100554, "z": null, "yaw": 0.012059273057682745, "pitch": null, "roll": null}, "v": 2.0859286680031013, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.347807417480127, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01934268112984769, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.429071} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25620760526826764, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1546471629310826, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.08580154314765, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.429071} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.829983949661255, "x": 33.89838302137313, "y": 0.08895827610055385, "z": null, "yaw": 0.012059273057682745, "pitch": null, "roll": null}, "v": 2.0859286680031013, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.347807417480127, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01934268112984769, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.449071} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25538983747173283, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1546471629310826, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.085906500075682, "gear": 1, "accelerator_pedal_position": 0.25620760526826764, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.449071} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.829983949661255, "x": 33.89838302137313, "y": 0.08895827610055385, "z": null, "yaw": 0.012059273057682745, "pitch": null, "roll": null}, "v": 2.0859286680031013, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.347807417480127, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01934268112984769, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.469071} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25538983747173283, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1546471629310826, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0858741369223837, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.469071} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.829983949661255, "x": 33.89838302137313, "y": 0.08895827610055385, "z": null, "yaw": 0.012059273057682745, "pitch": null, "roll": null}, "v": 2.0859286680031013, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.347807417480127, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01934268112984769, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.489071} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25538983747173283, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1546471629310826, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0858579776043977, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.489071} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.829983949661255, "x": 33.89838302137313, "y": 0.08895827610055385, "z": null, "yaw": 0.012059273057682745, "pitch": null, "roll": null}, "v": 2.0859286680031013, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.347807417480127, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01934268112984769, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.5090709} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25538983747173283, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1546471629310826, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.085809588521232, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.5090709} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502655.5290709, "x": 38.12781202998568, "y": 5.091618768893678, "z": null, "yaw": 0.011039250198358354, "pitch": null, "roll": null}, "v": 2.085793488404998, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34779501918297684, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01934142761820969, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.5290709} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25755013613756705, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2177953680762732, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0859124217217664, "gear": 1, "accelerator_pedal_position": 0.25755013613756705, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.5290709} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.93998384475708, "x": 34.12781202998568, "y": 0.09161876889367804, "z": null, "yaw": 0.011039250198358354, "pitch": null, "roll": null}, "v": 2.085793488404998, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34779501918297684, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01934142761820969, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.5490708} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25687442244660397, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2177953680762732, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.086031245956394, "gear": 1, "accelerator_pedal_position": 0.25755013613756705, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.5490708} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.93998384475708, "x": 34.12781202998568, "y": 0.09161876889367804, "z": null, "yaw": 0.011039250198358354, "pitch": null, "roll": null}, "v": 2.085793488404998, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34779501918297684, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01934142761820969, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.5690708} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25687442244660397, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2177953680762732, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0861841420930394, "gear": 1, "accelerator_pedal_position": 0.25687442244660397, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.5690708} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.93998384475708, "x": 34.12781202998568, "y": 0.09161876889367804, "z": null, "yaw": 0.011039250198358354, "pitch": null, "roll": null}, "v": 2.085793488404998, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34779501918297684, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01934142761820969, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.5890708} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25687442244660397, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2177953680762732, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.086489093812188, "gear": 1, "accelerator_pedal_position": 0.25687442244660397, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.5890708} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 16.93998384475708, "x": 34.12781202998568, "y": 0.09161876889367804, "z": null, "yaw": 0.011039250198358354, "pitch": null, "roll": null}, "v": 2.085793488404998, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34779501918297684, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01934142761820969, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.6090708} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25687442244660397, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2177953680762732, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.086489093812188, "gear": 1, "accelerator_pedal_position": 0.25687442244660397, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.6090708} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502655.6390707, "x": 38.357286533327894, "y": 5.094045682387615, "z": null, "yaw": 0.010019227339033964, "pitch": null, "roll": null}, "v": 2.086717074101968, "accelerator_pedal_position": 0.25687442244660397, "brake_pedal_position": 0.0, "acceleration": 0.007585405112689569, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01934999196842291, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.6390707} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25871437687264665, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2880894359466672, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.086717074101968, "gear": 1, "accelerator_pedal_position": 0.25687442244660397, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.6390707} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.049983739852905, "x": 34.357286533327894, "y": 0.09404568238761524, "z": null, "yaw": 0.010019227339033964, "pitch": null, "roll": null}, "v": 2.086717074101968, "accelerator_pedal_position": 0.25687442244660397, "brake_pedal_position": 0.0, "acceleration": 0.007585405112689569, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01934999196842291, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.6590707} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25814362654007567, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2880894359466672, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.08709860142774, "gear": 1, "accelerator_pedal_position": 0.25871437687264665, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.6590707} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.049983739852905, "x": 34.357286533327894, "y": 0.09404568238761524, "z": null, "yaw": 0.010019227339033964, "pitch": null, "roll": null}, "v": 2.086717074101968, "accelerator_pedal_position": 0.25687442244660397, "brake_pedal_position": 0.0, "acceleration": 0.007585405112689569, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01934999196842291, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.6790707} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25814362654007567, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2880894359466672, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0874081179835544, "gear": 1, "accelerator_pedal_position": 0.25814362654007567, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.6790707} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.049983739852905, "x": 34.357286533327894, "y": 0.09404568238761524, "z": null, "yaw": 0.010019227339033964, "pitch": null, "roll": null}, "v": 2.086717074101968, "accelerator_pedal_position": 0.25687442244660397, "brake_pedal_position": 0.0, "acceleration": 0.007585405112689569, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01934999196842291, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.6990707} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25814362654007567, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2880894359466672, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0877170668579828, "gear": 1, "accelerator_pedal_position": 0.25814362654007567, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.6990707} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.049983739852905, "x": 34.357286533327894, "y": 0.09404568238761524, "z": null, "yaw": 0.010019227339033964, "pitch": null, "roll": null}, "v": 2.086717074101968, "accelerator_pedal_position": 0.25687442244660397, "brake_pedal_position": 0.0, "acceleration": 0.007585405112689569, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01934999196842291, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.7190707} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25814362654007567, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2880894359466672, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0880254490540415, "gear": 1, "accelerator_pedal_position": 0.25814362654007567, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.7190707} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.049983739852905, "x": 34.357286533327894, "y": 0.09404568238761524, "z": null, "yaw": 0.010019227339033964, "pitch": null, "roll": null}, "v": 2.086717074101968, "accelerator_pedal_position": 0.25687442244660397, "brake_pedal_position": 0.0, "acceleration": 0.007585405112689569, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01934999196842291, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.7390707} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25814362654007567, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2880894359466672, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.088333265573118, "gear": 1, "accelerator_pedal_position": 0.25814362654007567, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.7390707} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502655.7490706, "x": 38.586906783510294, "y": 5.096239887755492, "z": null, "yaw": 0.008999204479709574, "pitch": null, "roll": null}, "v": 2.0884869620162765, "accelerator_pedal_position": 0.25814362654007567, "brake_pedal_position": 0.0, "acceleration": 0.015355539869539248, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01936640402415961, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.7590706} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25727974260888803, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.271679626913811, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.088640517414972, "gear": 1, "accelerator_pedal_position": 0.25814362654007567, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.7590706} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.15998363494873, "x": 34.586906783510294, "y": 0.09623988775549197, "z": null, "yaw": 0.008999204479709574, "pitch": null, "roll": null}, "v": 2.0884869620162765, "accelerator_pedal_position": 0.25814362654007567, "brake_pedal_position": 0.0, "acceleration": 0.015355539869539248, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01936640402415961, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.7790706} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2575578260610773, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.271679626913811, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0888392696383633, "gear": 1, "accelerator_pedal_position": 0.25727974260888803, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.7790706} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.15998363494873, "x": 34.586906783510294, "y": 0.09623988775549197, "z": null, "yaw": 0.008999204479709574, "pitch": null, "roll": null}, "v": 2.0884869620162765, "accelerator_pedal_position": 0.25814362654007567, "brake_pedal_position": 0.0, "acceleration": 0.015355539869539248, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01936640402415961, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.7990706} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2575578260610773, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.271679626913811, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0890724016964537, "gear": 1, "accelerator_pedal_position": 0.2575578260610773, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.7990706} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.15998363494873, "x": 34.586906783510294, "y": 0.09623988775549197, "z": null, "yaw": 0.008999204479709574, "pitch": null, "roll": null}, "v": 2.0884869620162765, "accelerator_pedal_position": 0.25814362654007567, "brake_pedal_position": 0.0, "acceleration": 0.015355539869539248, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01936640402415961, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.8190706} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2575578260610773, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.271679626913811, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.089305106012406, "gear": 1, "accelerator_pedal_position": 0.2575578260610773, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.8190706} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.15998363494873, "x": 34.586906783510294, "y": 0.09623988775549197, "z": null, "yaw": 0.008999204479709574, "pitch": null, "roll": null}, "v": 2.0884869620162765, "accelerator_pedal_position": 0.25814362654007567, "brake_pedal_position": 0.0, "acceleration": 0.015355539869539248, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01936640402415961, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.8390706} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2575578260610773, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.271679626913811, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0895373833493744, "gear": 1, "accelerator_pedal_position": 0.2575578260610773, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.8390706} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502655.8590705, "x": 38.8166968120731, "y": 5.098201309732753, "z": null, "yaw": 0.007979181620385184, "pitch": null, "roll": null}, "v": 2.089769234469234, "accelerator_pedal_position": 0.2575578260610773, "brake_pedal_position": 0.0, "acceleration": 0.011576596624930102, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019378294453376868, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.8590705} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2574813448212617, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2553519424699235, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.089769234469234, "gear": 1, "accelerator_pedal_position": 0.2575578260610773, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.8590705} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.269983530044556, "x": 34.8166968120731, "y": 0.09820130973275276, "z": null, "yaw": 0.007979181620385184, "pitch": null, "roll": null}, "v": 2.089769234469234, "accelerator_pedal_position": 0.2575578260610773, "brake_pedal_position": 0.0, "acceleration": 0.011576596624930102, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019378294453376868, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.8790705} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2575111297407761, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2553519424699235, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0899911043656, "gear": 1, "accelerator_pedal_position": 0.2574813448212617, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.8790705} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.269983530044556, "x": 34.8166968120731, "y": 0.09820130973275276, "z": null, "yaw": 0.007979181620385184, "pitch": null, "roll": null}, "v": 2.089769234469234, "accelerator_pedal_position": 0.2575578260610773, "brake_pedal_position": 0.0, "acceleration": 0.011576596624930102, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019378294453376868, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.8990705} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2575111297407761, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2553519424699235, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.090216288507512, "gear": 1, "accelerator_pedal_position": 0.2575111297407761, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.8990705} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.269983530044556, "x": 34.8166968120731, "y": 0.09820130973275276, "z": null, "yaw": 0.007979181620385184, "pitch": null, "roll": null}, "v": 2.089769234469234, "accelerator_pedal_position": 0.2575578260610773, "brake_pedal_position": 0.0, "acceleration": 0.011576596624930102, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019378294453376868, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.9190705} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2575111297407761, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2553519424699235, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0904410593867118, "gear": 1, "accelerator_pedal_position": 0.2575111297407761, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.9190705} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.269983530044556, "x": 34.8166968120731, "y": 0.09820130973275276, "z": null, "yaw": 0.007979181620385184, "pitch": null, "roll": null}, "v": 2.089769234469234, "accelerator_pedal_position": 0.2575578260610773, "brake_pedal_position": 0.0, "acceleration": 0.011576596624930102, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019378294453376868, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.9390705} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2575111297407761, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2553519424699235, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.090889364308648, "gear": 1, "accelerator_pedal_position": 0.2575111297407761, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.9390705} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.269983530044556, "x": 34.8166968120731, "y": 0.09820130973275276, "z": null, "yaw": 0.007979181620385184, "pitch": null, "roll": null}, "v": 2.089769234469234, "accelerator_pedal_position": 0.2575578260610773, "brake_pedal_position": 0.0, "acceleration": 0.011576596624930102, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019378294453376868, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.9590704} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2575111297407761, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2553519424699235, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.090889364308648, "gear": 1, "accelerator_pedal_position": 0.2575111297407761, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.9590704} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502655.9690704, "x": 39.046626467485424, "y": 5.099929375170972, "z": null, "yaw": 0.006959158761060786, "pitch": null, "roll": null}, "v": 2.091001183401914, "accelerator_pedal_position": 0.2575111297407761, "brake_pedal_position": 0.0, "acceleration": 0.01117164221987288, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019389718235857358, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502655.9890704} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25786128498159916, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2418659815005195, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0913579097248784, "gear": 1, "accelerator_pedal_position": 0.25786128498159916, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502655.9890704} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.37998342514038, "x": 35.046626467485424, "y": 0.099929375170972, "z": null, "yaw": 0.006959158761060786, "pitch": null, "roll": null}, "v": 2.091001183401914, "accelerator_pedal_position": 0.2575111297407761, "brake_pedal_position": 0.0, "acceleration": 0.01117164221987288, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019389718235857358, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.0090704} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2577575165209648, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2418659815005195, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0914911832907093, "gear": 1, "accelerator_pedal_position": 0.25786128498159916, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.0090704} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.37998342514038, "x": 35.046626467485424, "y": 0.099929375170972, "z": null, "yaw": 0.006959158761060786, "pitch": null, "roll": null}, "v": 2.091001183401914, "accelerator_pedal_position": 0.2575111297407761, "brake_pedal_position": 0.0, "acceleration": 0.01117164221987288, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019389718235857358, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.0290704} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2577575165209648, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2418659815005195, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0917443982801314, "gear": 1, "accelerator_pedal_position": 0.2577575165209648, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.0290704} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.37998342514038, "x": 35.046626467485424, "y": 0.099929375170972, "z": null, "yaw": 0.006959158761060786, "pitch": null, "roll": null}, "v": 2.091001183401914, "accelerator_pedal_position": 0.2575111297407761, "brake_pedal_position": 0.0, "acceleration": 0.01117164221987288, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019389718235857358, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.0490704} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2577575165209648, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2418659815005195, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0919971484101114, "gear": 1, "accelerator_pedal_position": 0.2577575165209648, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.0490704} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.37998342514038, "x": 35.046626467485424, "y": 0.099929375170972, "z": null, "yaw": 0.006959158761060786, "pitch": null, "roll": null}, "v": 2.091001183401914, "accelerator_pedal_position": 0.2575111297407761, "brake_pedal_position": 0.0, "acceleration": 0.01117164221987288, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019389718235857358, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.0690703} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2577575165209648, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2418659815005195, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0922494345085103, "gear": 1, "accelerator_pedal_position": 0.2577575165209648, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.0690703} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502656.0790703, "x": 39.27669951101676, "y": 5.101423825534585, "z": null, "yaw": 0.005939135901736386, "pitch": null, "roll": null}, "v": 2.0923754038041964, "accelerator_pedal_position": 0.2577575165209648, "brake_pedal_position": 0.0, "acceleration": 0.012585359761372317, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019402461292439888, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.0890703} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25735803948042624, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1899135225011024, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.09250125740181, "gear": 1, "accelerator_pedal_position": 0.2577575165209648, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.0890703} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.489983320236206, "x": 35.27669951101676, "y": 0.10142382553458518, "z": null, "yaw": 0.005939135901736386, "pitch": null, "roll": null}, "v": 2.0923754038041964, "accelerator_pedal_position": 0.2577575165209648, "brake_pedal_position": 0.0, "acceleration": 0.012585359761372317, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019402461292439888, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.1090703} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25748918613331495, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1899135225011024, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0927027062180983, "gear": 1, "accelerator_pedal_position": 0.25735803948042624, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.1090703} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.489983320236206, "x": 35.27669951101676, "y": 0.10142382553458518, "z": null, "yaw": 0.005939135901736386, "pitch": null, "roll": null}, "v": 2.0923754038041964, "accelerator_pedal_position": 0.2577575165209648, "brake_pedal_position": 0.0, "acceleration": 0.012585359761372317, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019402461292439888, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.1290703} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25748918613331495, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1899135225011024, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.092920170933069, "gear": 1, "accelerator_pedal_position": 0.25748918613331495, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.1290703} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.489983320236206, "x": 35.27669951101676, "y": 0.10142382553458518, "z": null, "yaw": 0.005939135901736386, "pitch": null, "roll": null}, "v": 2.0923754038041964, "accelerator_pedal_position": 0.2577575165209648, "brake_pedal_position": 0.0, "acceleration": 0.012585359761372317, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019402461292439888, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.1490703} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25748918613331495, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1899135225011024, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.093137236317032, "gear": 1, "accelerator_pedal_position": 0.25748918613331495, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.1490703} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.489983320236206, "x": 35.27669951101676, "y": 0.10142382553458518, "z": null, "yaw": 0.005939135901736386, "pitch": null, "roll": null}, "v": 2.0923754038041964, "accelerator_pedal_position": 0.2577575165209648, "brake_pedal_position": 0.0, "acceleration": 0.012585359761372317, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019402461292439888, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.1690702} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25748918613331495, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1899135225011024, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0933539030844424, "gear": 1, "accelerator_pedal_position": 0.25748918613331495, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.1690702} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502656.1890702, "x": 39.50691745660158, "y": 5.1026843829960296, "z": null, "yaw": 0.004919113042411986, "pitch": null, "roll": null}, "v": 2.093570171948545, "accelerator_pedal_position": 0.25748918613331495, "brake_pedal_position": 0.0, "acceleration": 0.010798544087064488, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019413540299883777, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.1890702} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2547308114617358, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0514419178423036, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.093570171948545, "gear": 1, "accelerator_pedal_position": 0.25748918613331495, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.1890702} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.59998321533203, "x": 35.50691745660158, "y": 0.10268438299602956, "z": null, "yaw": 0.004919113042411986, "pitch": null, "roll": null}, "v": 2.093570171948545, "accelerator_pedal_position": 0.25748918613331495, "brake_pedal_position": 0.0, "acceleration": 0.010798544087064488, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019413540299883777, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.2090702} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25559829165294345, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0514419178423036, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.093441405173029, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.2090702} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.59998321533203, "x": 35.50691745660158, "y": 0.10268438299602956, "z": null, "yaw": 0.004919113042411986, "pitch": null, "roll": null}, "v": 2.093570171948545, "accelerator_pedal_position": 0.25748918613331495, "brake_pedal_position": 0.0, "acceleration": 0.010798544087064488, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019413540299883777, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.2290702} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25559829165294345, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0514419178423036, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.093421260098859, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.2290702} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.59998321533203, "x": 35.50691745660158, "y": 0.10268438299602956, "z": null, "yaw": 0.004919113042411986, "pitch": null, "roll": null}, "v": 2.093570171948545, "accelerator_pedal_position": 0.25748918613331495, "brake_pedal_position": 0.0, "acceleration": 0.010798544087064488, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019413540299883777, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.2490702} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25559829165294345, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0514419178423036, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0934011520216527, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.2490702} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.59998321533203, "x": 35.50691745660158, "y": 0.10268438299602956, "z": null, "yaw": 0.004919113042411986, "pitch": null, "roll": null}, "v": 2.093570171948545, "accelerator_pedal_position": 0.25748918613331495, "brake_pedal_position": 0.0, "acceleration": 0.010798544087064488, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019413540299883777, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.2690701} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25559829165294345, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0514419178423036, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.093381080873302, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.2690701} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.59998321533203, "x": 35.50691745660158, "y": 0.10268438299602956, "z": null, "yaw": 0.004919113042411986, "pitch": null, "roll": null}, "v": 2.093570171948545, "accelerator_pedal_position": 0.25748918613331495, "brake_pedal_position": 0.0, "acceleration": 0.010798544087064488, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019413540299883777, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.2890701} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25559829165294345, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0514419178423036, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.093361046585826, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.2890701} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502656.2990701, "x": 39.7371920268243, "y": 5.103710372099999, "z": null, "yaw": 0.0038990901830875868, "pitch": null, "roll": null}, "v": 2.0933510432437057, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3484887380646804, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019411508333628594, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.30907} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25763639943208905, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0981992716966804, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.093341049091368, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.30907} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.709983110427856, "x": 35.7371920268243, "y": 0.10371037209999923, "z": null, "yaw": 0.0038990901830875868, "pitch": null, "roll": null}, "v": 2.0933510432437057, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3484887380646804, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019411508333628594, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.32907} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2569984837737823, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0981992716966804, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0935757347716715, "gear": 1, "accelerator_pedal_position": 0.25763639943208905, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.32907} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.709983110427856, "x": 35.7371920268243, "y": 0.10371037209999923, "z": null, "yaw": 0.0038990901830875868, "pitch": null, "roll": null}, "v": 2.0933510432437057, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3484887380646804, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019411508333628594, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.34907} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2569984837737823, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0981992716966804, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0937302866093956, "gear": 1, "accelerator_pedal_position": 0.2569984837737823, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.34907} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.709983110427856, "x": 35.7371920268243, "y": 0.10371037209999923, "z": null, "yaw": 0.0038990901830875868, "pitch": null, "roll": null}, "v": 2.0933510432437057, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3484887380646804, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019411508333628594, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.36907} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2569984837737823, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0981992716966804, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0938845545921803, "gear": 1, "accelerator_pedal_position": 0.2569984837737823, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.36907} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.709983110427856, "x": 35.7371920268243, "y": 0.10371037209999923, "z": null, "yaw": 0.0038990901830875868, "pitch": null, "roll": null}, "v": 2.0933510432437057, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3484887380646804, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019411508333628594, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.38907} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2569984837737823, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0981992716966804, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.094038539231848, "gear": 1, "accelerator_pedal_position": 0.2569984837737823, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.38907} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502656.40907, "x": 39.967499829500596, "y": 5.104501576393245, "z": null, "yaw": 0.002879067323763187, "pitch": null, "roll": null}, "v": 2.094192241039333, "accelerator_pedal_position": 0.2569984837737823, "brake_pedal_position": 0.0, "acceleration": 0.007674500109879301, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019419308706180895, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.40907} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2587357923225668, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1492267783056795, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.094192241039333, "gear": 1, "accelerator_pedal_position": 0.2569984837737823, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.40907} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.81998300552368, "x": 35.967499829500596, "y": 0.10450157639324509, "z": null, "yaw": 0.002879067323763187, "pitch": null, "roll": null}, "v": 2.094192241039333, "accelerator_pedal_position": 0.2569984837737823, "brake_pedal_position": 0.0, "acceleration": 0.007674500109879301, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019419308706180895, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.42907} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2581967473182252, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1492267783056795, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0945627243213183, "gear": 1, "accelerator_pedal_position": 0.2587357923225668, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.42907} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.81998300552368, "x": 35.967499829500596, "y": 0.10450157639324509, "z": null, "yaw": 0.002879067323763187, "pitch": null, "roll": null}, "v": 2.094192241039333, "accelerator_pedal_position": 0.2569984837737823, "brake_pedal_position": 0.0, "acceleration": 0.007674500109879301, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019419308706180895, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.44907} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2581967473182252, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1492267783056795, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0948651773804294, "gear": 1, "accelerator_pedal_position": 0.2581967473182252, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.44907} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.81998300552368, "x": 35.967499829500596, "y": 0.10450157639324509, "z": null, "yaw": 0.002879067323763187, "pitch": null, "roll": null}, "v": 2.094192241039333, "accelerator_pedal_position": 0.2569984837737823, "brake_pedal_position": 0.0, "acceleration": 0.007674500109879301, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019419308706180895, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.46907} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2581967473182252, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1492267783056795, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0951670748116977, "gear": 1, "accelerator_pedal_position": 0.2581967473182252, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.46907} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.81998300552368, "x": 35.967499829500596, "y": 0.10450157639324509, "z": null, "yaw": 0.002879067323763187, "pitch": null, "roll": null}, "v": 2.094192241039333, "accelerator_pedal_position": 0.2569984837737823, "brake_pedal_position": 0.0, "acceleration": 0.007674500109879301, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019419308706180895, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.48907} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2581967473182252, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1492267783056795, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.095468417599411, "gear": 1, "accelerator_pedal_position": 0.2581967473182252, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.48907} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.81998300552368, "x": 35.967499829500596, "y": 0.10450157639324509, "z": null, "yaw": 0.002879067323763187, "pitch": null, "roll": null}, "v": 2.094192241039333, "accelerator_pedal_position": 0.2569984837737823, "brake_pedal_position": 0.0, "acceleration": 0.007674500109879301, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019419308706180895, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.50907} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2581967473182252, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1492267783056795, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0957692067262492, "gear": 1, "accelerator_pedal_position": 0.2581967473182252, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.50907} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502656.51907, "x": 40.197949840600515, "y": 5.105058195337708, "z": null, "yaw": 0.0018590444644387876, "pitch": null, "roll": null}, "v": 2.095919393973489, "accelerator_pedal_position": 0.2581967473182252, "brake_pedal_position": 0.0, "acceleration": 0.01500491997989084, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01943532448322079, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.52907} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.258267178989954, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1320154207909272, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.096069443173288, "gear": 1, "accelerator_pedal_position": 0.2581967473182252, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.52907} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.929982900619507, "x": 36.197949840600515, "y": 0.10505819533770833, "z": null, "yaw": 0.0018590444644387876, "pitch": null, "roll": null}, "v": 2.095919393973489, "accelerator_pedal_position": 0.2581967473182252, "brake_pedal_position": 0.0, "acceleration": 0.01500491997989084, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01943532448322079, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.54907} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2582531054474492, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1320154207909272, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.09637792783247, "gear": 1, "accelerator_pedal_position": 0.258267178989954, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.54907} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.929982900619507, "x": 36.197949840600515, "y": 0.10505819533770833, "z": null, "yaw": 0.0018590444644387876, "pitch": null, "roll": null}, "v": 2.095919393973489, "accelerator_pedal_position": 0.2581967473182252, "brake_pedal_position": 0.0, "acceleration": 0.01500491997989084, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01943532448322079, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.5690699} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2582531054474492, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1320154207909272, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0966840872128287, "gear": 1, "accelerator_pedal_position": 0.2582531054474492, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.5690699} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.929982900619507, "x": 36.197949840600515, "y": 0.10505819533770833, "z": null, "yaw": 0.0018590444644387876, "pitch": null, "roll": null}, "v": 2.095919393973489, "accelerator_pedal_position": 0.2581967473182252, "brake_pedal_position": 0.0, "acceleration": 0.01500491997989084, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01943532448322079, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.5890698} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2582531054474492, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1320154207909272, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0969896839341353, "gear": 1, "accelerator_pedal_position": 0.2582531054474492, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.5890698} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 17.929982900619507, "x": 36.197949840600515, "y": 0.10505819533770833, "z": null, "yaw": 0.0018590444644387876, "pitch": null, "roll": null}, "v": 2.095919393973489, "accelerator_pedal_position": 0.2581967473182252, "brake_pedal_position": 0.0, "acceleration": 0.01500491997989084, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01943532448322079, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.6090698} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2582531054474492, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1320154207909272, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0972947189931053, "gear": 1, "accelerator_pedal_position": 0.2582531054474492, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.6090698} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502656.6290698, "x": 40.42858476959887, "y": 5.105380007397418, "z": null, "yaw": 0.000839021605114388, "pitch": null, "roll": null}, "v": 2.0975991933848275, "accelerator_pedal_position": 0.2582531054474492, "brake_pedal_position": 0.0, "acceleration": 0.015202725616429436, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019450901154117562, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.6290698} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25980498037485256, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1881428000686045, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0975991933848275, "gear": 1, "accelerator_pedal_position": 0.2582531054474492, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.6290698} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.039982795715332, "x": 36.42858476959887, "y": 0.10538000739741804, "z": null, "yaw": 0.000839021605114388, "pitch": null, "roll": null}, "v": 2.0975991933848275, "accelerator_pedal_position": 0.2582531054474492, "brake_pedal_position": 0.0, "acceleration": 0.015202725616429436, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019450901154117562, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.6490698} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.259327740780692, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1881428000686045, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.098097003278566, "gear": 1, "accelerator_pedal_position": 0.25980498037485256, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.6490698} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.039982795715332, "x": 36.42858476959887, "y": 0.10538000739741804, "z": null, "yaw": 0.000839021605114388, "pitch": null, "roll": null}, "v": 2.0975991933848275, "accelerator_pedal_position": 0.2582531054474492, "brake_pedal_position": 0.0, "acceleration": 0.015202725616429436, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019450901154117562, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.6690698} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.259327740780692, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1881428000686045, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.098534270508848, "gear": 1, "accelerator_pedal_position": 0.259327740780692, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.6690698} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.039982795715332, "x": 36.42858476959887, "y": 0.10538000739741804, "z": null, "yaw": 0.000839021605114388, "pitch": null, "roll": null}, "v": 2.0975991933848275, "accelerator_pedal_position": 0.2582531054474492, "brake_pedal_position": 0.0, "acceleration": 0.015202725616429436, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019450901154117562, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.6890697} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.259327740780692, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1881428000686045, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0989707338127714, "gear": 1, "accelerator_pedal_position": 0.259327740780692, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.6890697} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.039982795715332, "x": 36.42858476959887, "y": 0.10538000739741804, "z": null, "yaw": 0.000839021605114388, "pitch": null, "roll": null}, "v": 2.0975991933848275, "accelerator_pedal_position": 0.2582531054474492, "brake_pedal_position": 0.0, "acceleration": 0.015202725616429436, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019450901154117562, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.7090697} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.259327740780692, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1881428000686045, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.099406394592209, "gear": 1, "accelerator_pedal_position": 0.259327740780692, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.7090697} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.039982795715332, "x": 36.42858476959887, "y": 0.10538000739741804, "z": null, "yaw": 0.000839021605114388, "pitch": null, "roll": null}, "v": 2.0975991933848275, "accelerator_pedal_position": 0.2582531054474492, "brake_pedal_position": 0.0, "acceleration": 0.015202725616429436, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019450901154117562, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.7290697} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.259327740780692, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1881428000686045, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0998412542468756, "gear": 1, "accelerator_pedal_position": 0.259327740780692, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.7290697} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502656.7390697, "x": 40.65944652333276, "y": 5.105466644449983, "z": null, "yaw": -0.0001810012542100112, "pitch": null, "roll": null}, "v": 2.1000583840892415, "accelerator_pedal_position": 0.259327740780692, "brake_pedal_position": 0.0, "acceleration": 0.021693008509027556, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019473705069880658, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.7490697} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.256281952380739, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.030632267996983, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1002753141743318, "gear": 1, "accelerator_pedal_position": 0.259327740780692, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.7490697} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.149982690811157, "x": 36.65944652333276, "y": 0.105466644449983, "z": null, "yaw": 6.283004305925377, "pitch": null, "roll": null}, "v": 2.1000583840892415, "accelerator_pedal_position": 0.259327740780692, "brake_pedal_position": 0.0, "acceleration": 0.021693008509027556, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019473705069880658, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.7690697} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2572450712842027, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.030632267996983, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1003280273679334, "gear": 1, "accelerator_pedal_position": 0.256281952380739, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.7690697} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.149982690811157, "x": 36.65944652333276, "y": 0.105466644449983, "z": null, "yaw": 6.283004305925377, "pitch": null, "roll": null}, "v": 2.1000583840892415, "accelerator_pedal_position": 0.259327740780692, "brake_pedal_position": 0.0, "acceleration": 0.021693008509027556, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019473705069880658, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.7890697} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2572450712842027, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.030632267996983, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1005009780862105, "gear": 1, "accelerator_pedal_position": 0.2572450712842027, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.7890697} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.149982690811157, "x": 36.65944652333276, "y": 0.105466644449983, "z": null, "yaw": 6.283004305925377, "pitch": null, "roll": null}, "v": 2.1000583840892415, "accelerator_pedal_position": 0.259327740780692, "brake_pedal_position": 0.0, "acceleration": 0.021693008509027556, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019473705069880658, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.8090696} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2572450712842027, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.030632267996983, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.100673610689915, "gear": 1, "accelerator_pedal_position": 0.2572450712842027, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.8090696} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.149982690811157, "x": 36.65944652333276, "y": 0.105466644449983, "z": null, "yaw": 6.283004305925377, "pitch": null, "roll": null}, "v": 2.1000583840892415, "accelerator_pedal_position": 0.259327740780692, "brake_pedal_position": 0.0, "acceleration": 0.021693008509027556, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019473705069880658, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.8290696} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2572450712842027, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.030632267996983, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1008459257522523, "gear": 1, "accelerator_pedal_position": 0.2572450712842027, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.8290696} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502656.8490696, "x": 40.89050324110286, "y": 5.105317685933983, "z": null, "yaw": -0.0012010241135344106, "pitch": null, "roll": null}, "v": 2.101017923845437, "accelerator_pedal_position": 0.2572450712842027, "brake_pedal_position": 0.0, "acceleration": 0.00858803617079712, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019482602819751112, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.8490696} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2590889937953027, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.076632691018016, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.101017923845437, "gear": 1, "accelerator_pedal_position": 0.2572450712842027, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.8490696} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.259982585906982, "x": 36.89050324110286, "y": 0.10531768593398283, "z": null, "yaw": 6.281984283066052, "pitch": null, "roll": null}, "v": 2.101017923845437, "accelerator_pedal_position": 0.2572450712842027, "brake_pedal_position": 0.0, "acceleration": 0.00858803617079712, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019482602819751112, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.8690696} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25851718203493357, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.076632691018016, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.101419989802272, "gear": 1, "accelerator_pedal_position": 0.2590889937953027, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.8690696} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.259982585906982, "x": 36.89050324110286, "y": 0.10531768593398283, "z": null, "yaw": 6.281984283066052, "pitch": null, "roll": null}, "v": 2.101017923845437, "accelerator_pedal_position": 0.2572450712842027, "brake_pedal_position": 0.0, "acceleration": 0.00858803617079712, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019482602819751112, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.8890696} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25851718203493357, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.076632691018016, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1017498725066384, "gear": 1, "accelerator_pedal_position": 0.25851718203493357, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.8890696} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.259982585906982, "x": 36.89050324110286, "y": 0.10531768593398283, "z": null, "yaw": 6.281984283066052, "pitch": null, "roll": null}, "v": 2.101017923845437, "accelerator_pedal_position": 0.2572450712842027, "brake_pedal_position": 0.0, "acceleration": 0.00858803617079712, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019482602819751112, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.9090695} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25851718203493357, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.076632691018016, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.10207914828623, "gear": 1, "accelerator_pedal_position": 0.25851718203493357, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.9090695} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.259982585906982, "x": 36.89050324110286, "y": 0.10531768593398283, "z": null, "yaw": 6.281984283066052, "pitch": null, "roll": null}, "v": 2.101017923845437, "accelerator_pedal_position": 0.2572450712842027, "brake_pedal_position": 0.0, "acceleration": 0.00858803617079712, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019482602819751112, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.9290695} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25851718203493357, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.076632691018016, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1024078182143304, "gear": 1, "accelerator_pedal_position": 0.25851718203493357, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.9290695} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.259982585906982, "x": 36.89050324110286, "y": 0.10531768593398283, "z": null, "yaw": 6.281984283066052, "pitch": null, "roll": null}, "v": 2.101017923845437, "accelerator_pedal_position": 0.2572450712842027, "brake_pedal_position": 0.0, "acceleration": 0.00858803617079712, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019482602819751112, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.9490695} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25851718203493357, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.076632691018016, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.102735883362487, "gear": 1, "accelerator_pedal_position": 0.25851718203493357, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.9490695} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502656.9590695, "x": 41.1217123584171, "y": 5.104932781238462, "z": null, "yaw": -0.00222104697285881, "pitch": null, "roll": null}, "v": 2.102899689478471, "accelerator_pedal_position": 0.25851718203493357, "brake_pedal_position": 0.0, "acceleration": 0.01636553220432463, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019500052310310982, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.9690695} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2600863594262879, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.127136101784425, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1030633448005145, "gear": 1, "accelerator_pedal_position": 0.25851718203493357, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.9690695} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.369982481002808, "x": 37.1217123584171, "y": 0.10493278123846217, "z": null, "yaw": 6.280964260206727, "pitch": null, "roll": null}, "v": 2.102899689478471, "accelerator_pedal_position": 0.25851718203493357, "brake_pedal_position": 0.0, "acceleration": 0.01636553220432463, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019500052310310982, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502656.9890695} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.259604650983584, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.127136101784425, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1040781069343812, "gear": 1, "accelerator_pedal_position": 0.259604650983584, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502656.9890695} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.369982481002808, "x": 37.1217123584171, "y": 0.10493278123846217, "z": null, "yaw": 6.280964260206727, "pitch": null, "roll": null}, "v": 2.102899689478471, "accelerator_pedal_position": 0.25851718203493357, "brake_pedal_position": 0.0, "acceleration": 0.01636553220432463, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019500052310310982, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.0090694} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.259604650983584, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.127136101784425, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1045389689768412, "gear": 1, "accelerator_pedal_position": 0.259604650983584, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.0090694} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.369982481002808, "x": 37.1217123584171, "y": 0.10493278123846217, "z": null, "yaw": 6.280964260206727, "pitch": null, "roll": null}, "v": 2.102899689478471, "accelerator_pedal_position": 0.25851718203493357, "brake_pedal_position": 0.0, "acceleration": 0.01636553220432463, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019500052310310982, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.0390694} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.259604650983584, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.127136101784425, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.104998982608481, "gear": 1, "accelerator_pedal_position": 0.259604650983584, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.0390694} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.369982481002808, "x": 37.1217123584171, "y": 0.10493278123846217, "z": null, "yaw": 6.280964260206727, "pitch": null, "roll": null}, "v": 2.102899689478471, "accelerator_pedal_position": 0.25851718203493357, "brake_pedal_position": 0.0, "acceleration": 0.01636553220432463, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019500052310310982, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.0590694} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.259604650983584, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.127136101784425, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1052286717319726, "gear": 1, "accelerator_pedal_position": 0.259604650983584, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.0590694} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502657.0690694, "x": 41.35315795462964, "y": 5.1043113950152454, "z": null, "yaw": -0.0032410698321832096, "pitch": null, "roll": null}, "v": 2.1054581493065525, "accelerator_pedal_position": 0.259604650983584, "brake_pedal_position": 0.0, "acceleration": 0.02292662099725845, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019523776742213766, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.0790694} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25821412877294153, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0357190537000218, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1056874155165253, "gear": 1, "accelerator_pedal_position": 0.259604650983584, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.0790694} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.479982376098633, "x": 37.35315795462964, "y": 0.10431139501524544, "z": null, "yaw": 6.279944237347403, "pitch": null, "roll": null}, "v": 2.1054581493065525, "accelerator_pedal_position": 0.259604650983584, "brake_pedal_position": 0.0, "acceleration": 0.02292662099725845, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019523776742213766, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.0990694} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25866044686320283, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0357190537000218, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.105971579359943, "gear": 1, "accelerator_pedal_position": 0.25821412877294153, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.0990694} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.479982376098633, "x": 37.35315795462964, "y": 0.10431139501524544, "z": null, "yaw": 6.279944237347403, "pitch": null, "roll": null}, "v": 2.1054581493065525, "accelerator_pedal_position": 0.259604650983584, "brake_pedal_position": 0.0, "acceleration": 0.02292662099725845, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019523776742213766, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.1190693} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25866044686320283, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0357190537000218, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1063109839761456, "gear": 1, "accelerator_pedal_position": 0.25866044686320283, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.1190693} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.479982376098633, "x": 37.35315795462964, "y": 0.10431139501524544, "z": null, "yaw": 6.279944237347403, "pitch": null, "roll": null}, "v": 2.1054581493065525, "accelerator_pedal_position": 0.259604650983584, "brake_pedal_position": 0.0, "acceleration": 0.02292662099725845, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019523776742213766, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.1390693} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25866044686320283, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0357190537000218, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1068189192552054, "gear": 1, "accelerator_pedal_position": 0.25866044686320283, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.1390693} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.479982376098633, "x": 37.35315795462964, "y": 0.10431139501524544, "z": null, "yaw": 6.279944237347403, "pitch": null, "roll": null}, "v": 2.1054581493065525, "accelerator_pedal_position": 0.259604650983584, "brake_pedal_position": 0.0, "acceleration": 0.02292662099725845, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019523776742213766, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.1590693} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25866044686320283, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0357190537000218, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1069879191286747, "gear": 1, "accelerator_pedal_position": 0.25866044686320283, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.1590693} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502657.1790693, "x": 41.58485128328884, "y": 5.103453015946671, "z": null, "yaw": -0.004261092691507609, "pitch": null, "roll": null}, "v": 2.1073254518737237, "accelerator_pedal_position": 0.25866044686320283, "brake_pedal_position": 0.0, "acceleration": 0.016853314700183475, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01954109211770276, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.1790693} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2603370462194979, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0817389352310713, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.107598772480494, "gear": 1, "accelerator_pedal_position": 0.2603370462194979, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.1790693} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.589982271194458, "x": 37.58485128328884, "y": 0.10345301594667067, "z": null, "yaw": 6.278924214488079, "pitch": null, "roll": null}, "v": 2.1073254518737237, "accelerator_pedal_position": 0.25866044686320283, "brake_pedal_position": 0.0, "acceleration": 0.016853314700183475, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01954109211770276, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.1990693} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25982171011000965, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0817389352310713, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.107871841224396, "gear": 1, "accelerator_pedal_position": 0.2603370462194979, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.1990693} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.589982271194458, "x": 37.58485128328884, "y": 0.10345301594667067, "z": null, "yaw": 6.278924214488079, "pitch": null, "roll": null}, "v": 2.1073254518737237, "accelerator_pedal_position": 0.25866044686320283, "brake_pedal_position": 0.0, "acceleration": 0.016853314700183475, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01954109211770276, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.2190692} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25982171011000965, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0817389352310713, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.108352836662618, "gear": 1, "accelerator_pedal_position": 0.25982171011000965, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.2190692} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.589982271194458, "x": 37.58485128328884, "y": 0.10345301594667067, "z": null, "yaw": 6.278924214488079, "pitch": null, "roll": null}, "v": 2.1073254518737237, "accelerator_pedal_position": 0.25866044686320283, "brake_pedal_position": 0.0, "acceleration": 0.016853314700183475, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01954109211770276, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.2390692} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25982171011000965, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0817389352310713, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.108832945893882, "gear": 1, "accelerator_pedal_position": 0.25982171011000965, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.2390692} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.589982271194458, "x": 37.58485128328884, "y": 0.10345301594667067, "z": null, "yaw": 6.278924214488079, "pitch": null, "roll": null}, "v": 2.1073254518737237, "accelerator_pedal_position": 0.25866044686320283, "brake_pedal_position": 0.0, "acceleration": 0.016853314700183475, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01954109211770276, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.2590692} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25982171011000965, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0817389352310713, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.109312170458815, "gear": 1, "accelerator_pedal_position": 0.25982171011000965, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.2590692} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.589982271194458, "x": 37.58485128328884, "y": 0.10345301594667067, "z": null, "yaw": 6.278924214488079, "pitch": null, "roll": null}, "v": 2.1073254518737237, "accelerator_pedal_position": 0.25866044686320283, "brake_pedal_position": 0.0, "acceleration": 0.016853314700183475, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.01954109211770276, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.2790692} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25982171011000965, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0817389352310713, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1100293519212348, "gear": 1, "accelerator_pedal_position": 0.25982171011000965, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.2790692} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502657.2890692, "x": 41.8167928253646, "y": 5.102357119534158, "z": null, "yaw": -0.005281115550832009, "pitch": null, "roll": null}, "v": 2.1100293519212348, "accelerator_pedal_position": 0.25982171011000965, "brake_pedal_position": 0.0, "acceleration": 0.023861981931807053, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019566165207319033, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.2990692} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2610293098962597, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0878575618767448, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.110267971740553, "gear": 1, "accelerator_pedal_position": 0.25982171011000965, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.2990692} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.699982166290283, "x": 37.8167928253646, "y": 0.10235711953415816, "z": null, "yaw": 6.277904191628754, "pitch": null, "roll": null}, "v": 2.1100293519212348, "accelerator_pedal_position": 0.25982171011000965, "brake_pedal_position": 0.0, "acceleration": 0.023861981931807053, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019566165207319033, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.3190691} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26066439612684644, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0878575618767448, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.110895431904103, "gear": 1, "accelerator_pedal_position": 0.2610293098962597, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.3190691} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.699982166290283, "x": 37.8167928253646, "y": 0.10235711953415816, "z": null, "yaw": 6.277904191628754, "pitch": null, "roll": null}, "v": 2.1100293519212348, "accelerator_pedal_position": 0.25982171011000965, "brake_pedal_position": 0.0, "acceleration": 0.023861981931807053, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019566165207319033, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.3390691} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26066439612684644, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0878575618767448, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.111766095728694, "gear": 1, "accelerator_pedal_position": 0.26066439612684644, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.3390691} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.699982166290283, "x": 37.8167928253646, "y": 0.10235711953415816, "z": null, "yaw": 6.277904191628754, "pitch": null, "roll": null}, "v": 2.1100293519212348, "accelerator_pedal_position": 0.25982171011000965, "brake_pedal_position": 0.0, "acceleration": 0.023861981931807053, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019566165207319033, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.359069} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26066439612684644, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0878575618767448, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1120557818344508, "gear": 1, "accelerator_pedal_position": 0.26066439612684644, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.359069} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.699982166290283, "x": 37.8167928253646, "y": 0.10235711953415816, "z": null, "yaw": 6.277904191628754, "pitch": null, "roll": null}, "v": 2.1100293519212348, "accelerator_pedal_position": 0.25982171011000965, "brake_pedal_position": 0.0, "acceleration": 0.023861981931807053, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019566165207319033, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.379069} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26066439612684644, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0878575618767448, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.112634352671753, "gear": 1, "accelerator_pedal_position": 0.26066439612684644, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.379069} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502657.399069, "x": 42.04905059597657, "y": 5.10102280937973, "z": null, "yaw": -0.006301138410156408, "pitch": null, "roll": null}, "v": 2.113211856540623, "accelerator_pedal_position": 0.26066439612684644, "brake_pedal_position": 0.0, "acceleration": 0.02883523945952038, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019595676366061594, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.399069} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25990769189633145, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9508221857616033, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.113211856540623, "gear": 1, "accelerator_pedal_position": 0.26066439612684644, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.399069} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.80998206138611, "x": 38.04905059597657, "y": 0.10102280937972985, "z": null, "yaw": 6.2768841687694295, "pitch": null, "roll": null}, "v": 2.113211856540623, "accelerator_pedal_position": 0.26066439612684644, "brake_pedal_position": 0.0, "acceleration": 0.02883523945952038, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019595676366061594, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.419069} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2601588386369078, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9508221857616033, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.113693750884513, "gear": 1, "accelerator_pedal_position": 0.25990769189633145, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.419069} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.80998206138611, "x": 38.04905059597657, "y": 0.10102280937972985, "z": null, "yaw": 6.2768841687694295, "pitch": null, "roll": null}, "v": 2.113211856540623, "accelerator_pedal_position": 0.26066439612684644, "brake_pedal_position": 0.0, "acceleration": 0.02883523945952038, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019595676366061594, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.439069} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2601588386369078, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9508221857616033, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1142061351946175, "gear": 1, "accelerator_pedal_position": 0.2601588386369078, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.439069} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.80998206138611, "x": 38.04905059597657, "y": 0.10102280937972985, "z": null, "yaw": 6.2768841687694295, "pitch": null, "roll": null}, "v": 2.113211856540623, "accelerator_pedal_position": 0.26066439612684644, "brake_pedal_position": 0.0, "acceleration": 0.02883523945952038, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019595676366061594, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.459069} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2601588386369078, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9508221857616033, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1147175742685977, "gear": 1, "accelerator_pedal_position": 0.2601588386369078, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.459069} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.80998206138611, "x": 38.04905059597657, "y": 0.10102280937972985, "z": null, "yaw": 6.2768841687694295, "pitch": null, "roll": null}, "v": 2.113211856540623, "accelerator_pedal_position": 0.26066439612684644, "brake_pedal_position": 0.0, "acceleration": 0.02883523945952038, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019595676366061594, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.479069} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2601588386369078, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9508221857616033, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1152280697456263, "gear": 1, "accelerator_pedal_position": 0.2601588386369078, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.479069} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.80998206138611, "x": 38.04905059597657, "y": 0.10102280937972985, "z": null, "yaw": 6.2768841687694295, "pitch": null, "roll": null}, "v": 2.113211856540623, "accelerator_pedal_position": 0.26066439612684644, "brake_pedal_position": 0.0, "acceleration": 0.02883523945952038, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019595676366061594, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.499069} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2601588386369078, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9508221857616033, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.11573762326243, "gear": 1, "accelerator_pedal_position": 0.2601588386369078, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.499069} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502657.509069, "x": 42.28163642249572, "y": 5.099449366349305, "z": null, "yaw": -0.007321161269480808, "pitch": null, "roll": null}, "v": 2.1159920472965568, "accelerator_pedal_position": 0.2601588386369078, "brake_pedal_position": 0.0, "acceleration": 0.025418915673623144, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019621456894464637, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.519069} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2616858524066491, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9897298709441593, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.116246236453293, "gear": 1, "accelerator_pedal_position": 0.2601588386369078, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.519069} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.919981956481934, "x": 38.28163642249572, "y": 0.09944936634930457, "z": null, "yaw": 6.275864145910106, "pitch": null, "roll": null}, "v": 2.1159920472965568, "accelerator_pedal_position": 0.2601588386369078, "brake_pedal_position": 0.0, "acceleration": 0.025418915673623144, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019621456894464637, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.539069} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2612214897728341, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9897298709441593, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1169446995521226, "gear": 1, "accelerator_pedal_position": 0.2616858524066491, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.539069} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.919981956481934, "x": 38.28163642249572, "y": 0.09944936634930457, "z": null, "yaw": 6.275864145910106, "pitch": null, "roll": null}, "v": 2.1159920472965568, "accelerator_pedal_position": 0.2601588386369078, "brake_pedal_position": 0.0, "acceleration": 0.025418915673623144, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019621456894464637, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.559069} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2612214897728341, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9897298709441593, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1175838548609773, "gear": 1, "accelerator_pedal_position": 0.2612214897728341, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.559069} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.919981956481934, "x": 38.28163642249572, "y": 0.09944936634930457, "z": null, "yaw": 6.275864145910106, "pitch": null, "roll": null}, "v": 2.1159920472965568, "accelerator_pedal_position": 0.2601588386369078, "brake_pedal_position": 0.0, "acceleration": 0.025418915673623144, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019621456894464637, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.579069} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2612214897728341, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9897298709441593, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.118221830214496, "gear": 1, "accelerator_pedal_position": 0.2612214897728341, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.579069} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 18.919981956481934, "x": 38.28163642249572, "y": 0.09944936634930457, "z": null, "yaw": 6.275864145910106, "pitch": null, "roll": null}, "v": 2.1159920472965568, "accelerator_pedal_position": 0.2601588386369078, "brake_pedal_position": 0.0, "acceleration": 0.025418915673623144, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019621456894464637, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.5990689} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2612214897728341, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9897298709441593, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.118858627628284, "gear": 1, "accelerator_pedal_position": 0.2612214897728341, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.5990689} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502657.6190689, "x": 42.51456262701955, "y": 5.097636011105622, "z": null, "yaw": -0.008341184128805202, "pitch": null, "roll": null}, "v": 2.1194942491151263, "accelerator_pedal_position": 0.2612214897728341, "brake_pedal_position": 0.0, "acceleration": 0.03173703990413579, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019653932584581982, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.6190689} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2625723775210014, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.031818180720427, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1194942491151263, "gear": 1, "accelerator_pedal_position": 0.2612214897728341, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.6190689} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.02998185157776, "x": 38.51456262701955, "y": 0.09763601110562181, "z": null, "yaw": 6.274844123050781, "pitch": null, "roll": null}, "v": 2.1194942491151263, "accelerator_pedal_position": 0.2612214897728341, "brake_pedal_position": 0.0, "acceleration": 0.03173703990413579, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019653932584581982, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.6390688} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26216639710196893, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.031818180720427, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1202974796422116, "gear": 1, "accelerator_pedal_position": 0.2625723775210014, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.6390688} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.02998185157776, "x": 38.51456262701955, "y": 0.09763601110562181, "z": null, "yaw": 6.274844123050781, "pitch": null, "roll": null}, "v": 2.1194942491151263, "accelerator_pedal_position": 0.2612214897728341, "brake_pedal_position": 0.0, "acceleration": 0.03173703990413579, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019653932584581982, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.6590688} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26216639710196893, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.031818180720427, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.121048502350531, "gear": 1, "accelerator_pedal_position": 0.26216639710196893, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.6590688} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.02998185157776, "x": 38.51456262701955, "y": 0.09763601110562181, "z": null, "yaw": 6.274844123050781, "pitch": null, "roll": null}, "v": 2.1194942491151263, "accelerator_pedal_position": 0.2612214897728341, "brake_pedal_position": 0.0, "acceleration": 0.03173703990413579, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019653932584581982, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.6790688} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26216639710196893, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.031818180720427, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1217981375517794, "gear": 1, "accelerator_pedal_position": 0.26216639710196893, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.6790688} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.02998185157776, "x": 38.51456262701955, "y": 0.09763601110562181, "z": null, "yaw": 6.274844123050781, "pitch": null, "roll": null}, "v": 2.1194942491151263, "accelerator_pedal_position": 0.2612214897728341, "brake_pedal_position": 0.0, "acceleration": 0.03173703990413579, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019653932584581982, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.6990688} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26216639710196893, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.031818180720427, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.122546387584685, "gear": 1, "accelerator_pedal_position": 0.26216639710196893, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.6990688} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.02998185157776, "x": 38.51456262701955, "y": 0.09763601110562181, "z": null, "yaw": 6.274844123050781, "pitch": null, "roll": null}, "v": 2.1194942491151263, "accelerator_pedal_position": 0.2612214897728341, "brake_pedal_position": 0.0, "acceleration": 0.03173703990413579, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019653932584581982, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.7190688} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26216639710196893, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.031818180720427, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1232932547849, "gear": 1, "accelerator_pedal_position": 0.26216639710196893, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.7190688} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502657.7290688, "x": 42.74790920273608, "y": 5.095581342310276, "z": null, "yaw": -0.009361206988129592, "pitch": null, "roll": null}, "v": 2.1236661705517994, "accelerator_pedal_position": 0.26216639710196893, "brake_pedal_position": 0.0, "acceleration": 0.03725709332025434, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019692618541243004, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.7390687} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2630547698281597, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9935924419571067, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.124038741485002, "gear": 1, "accelerator_pedal_position": 0.26216639710196893, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.7390687} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.139981746673584, "x": 38.74790920273608, "y": 0.09558134231027626, "z": null, "yaw": 6.273824100191456, "pitch": null, "roll": null}, "v": 2.1236661705517994, "accelerator_pedal_position": 0.26216639710196893, "brake_pedal_position": 0.0, "acceleration": 0.03725709332025434, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019692618541243004, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.7590687} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26279643405139563, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9935924419571067, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.12489384525245, "gear": 1, "accelerator_pedal_position": 0.2630547698281597, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.7590687} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.139981746673584, "x": 38.74790920273608, "y": 0.09558134231027626, "z": null, "yaw": 6.273824100191456, "pitch": null, "roll": null}, "v": 2.1236661705517994, "accelerator_pedal_position": 0.26216639710196893, "brake_pedal_position": 0.0, "acceleration": 0.03725709332025434, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019692618541243004, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.7790687} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26279643405139563, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9935924419571067, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1261251440009, "gear": 1, "accelerator_pedal_position": 0.26279643405139563, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.7790687} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.139981746673584, "x": 38.74790920273608, "y": 0.09558134231027626, "z": null, "yaw": 6.273824100191456, "pitch": null, "roll": null}, "v": 2.1236661705517994, "accelerator_pedal_position": 0.26216639710196893, "brake_pedal_position": 0.0, "acceleration": 0.03725709332025434, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019692618541243004, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.7990687} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26279643405139563, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9935924419571067, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1265348177443166, "gear": 1, "accelerator_pedal_position": 0.26279643405139563, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.7990687} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.139981746673584, "x": 38.74790920273608, "y": 0.09558134231027626, "z": null, "yaw": 6.273824100191456, "pitch": null, "roll": null}, "v": 2.1236661705517994, "accelerator_pedal_position": 0.26216639710196893, "brake_pedal_position": 0.0, "acceleration": 0.03725709332025434, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019692618541243004, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.8190687} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26279643405139563, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9935924419571067, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1273530283768056, "gear": 1, "accelerator_pedal_position": 0.26279643405139563, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.8190687} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502657.8390687, "x": 42.98172594357323, "y": 5.093284011131108, "z": null, "yaw": -0.010381229847453982, "pitch": null, "roll": null}, "v": 2.128169725317225, "accelerator_pedal_position": 0.26279643405139563, "brake_pedal_position": 0.0, "acceleration": 0.040778162757793446, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019734379712233487, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.8390687} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2640113931423123, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8783464097028003, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.128169725317225, "gear": 1, "accelerator_pedal_position": 0.26279643405139563, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.8390687} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.24998164176941, "x": 38.98172594357323, "y": 0.09328401113110818, "z": null, "yaw": 6.2728040773321325, "pitch": null, "roll": null}, "v": 2.128169725317225, "accelerator_pedal_position": 0.26279643405139563, "brake_pedal_position": 0.0, "acceleration": 0.040778162757793446, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019734379712233487, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.8590686} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26365255126594467, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8783464097028003, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1291367106908696, "gear": 1, "accelerator_pedal_position": 0.2640113931423123, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.8590686} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.24998164176941, "x": 38.98172594357323, "y": 0.09328401113110818, "z": null, "yaw": 6.2728040773321325, "pitch": null, "roll": null}, "v": 2.128169725317225, "accelerator_pedal_position": 0.26279643405139563, "brake_pedal_position": 0.0, "acceleration": 0.040778162757793446, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019734379712233487, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.8790686} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26365255126594467, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8783464097028003, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1300570719955085, "gear": 1, "accelerator_pedal_position": 0.26365255126594467, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.8790686} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.24998164176941, "x": 38.98172594357323, "y": 0.09328401113110818, "z": null, "yaw": 6.2728040773321325, "pitch": null, "roll": null}, "v": 2.128169725317225, "accelerator_pedal_position": 0.26279643405139563, "brake_pedal_position": 0.0, "acceleration": 0.040778162757793446, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019734379712233487, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.8990686} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26365255126594467, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8783464097028003, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.130975729643875, "gear": 1, "accelerator_pedal_position": 0.26365255126594467, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.8990686} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.24998164176941, "x": 38.98172594357323, "y": 0.09328401113110818, "z": null, "yaw": 6.2728040773321325, "pitch": null, "roll": null}, "v": 2.128169725317225, "accelerator_pedal_position": 0.26279643405139563, "brake_pedal_position": 0.0, "acceleration": 0.040778162757793446, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019734379712233487, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.9190686} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26365255126594467, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8783464097028003, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.131892686452145, "gear": 1, "accelerator_pedal_position": 0.26365255126594467, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.9190686} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.24998164176941, "x": 38.98172594357323, "y": 0.09328401113110818, "z": null, "yaw": 6.2728040773321325, "pitch": null, "roll": null}, "v": 2.128169725317225, "accelerator_pedal_position": 0.26279643405139563, "brake_pedal_position": 0.0, "acceleration": 0.040778162757793446, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019734379712233487, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.9390686} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26365255126594467, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8783464097028003, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.132807945233155, "gear": 1, "accelerator_pedal_position": 0.26365255126594467, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.9390686} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502657.9490685, "x": 43.21606807144092, "y": 5.090742452887189, "z": null, "yaw": -0.011401252706778373, "pitch": null, "roll": null}, "v": 2.1332649387415348, "accelerator_pedal_position": 0.26365255126594467, "brake_pedal_position": 0.0, "acceleration": 0.04565700548643814, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019781627295560145, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.9590685} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26488483961750997, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9092609618337026, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.133721508796399, "gear": 1, "accelerator_pedal_position": 0.26365255126594467, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.9590685} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.359981536865234, "x": 39.21606807144092, "y": 0.09074245288718874, "z": null, "yaw": 6.271784054472808, "pitch": null, "roll": null}, "v": 2.1332649387415348, "accelerator_pedal_position": 0.26365255126594467, "brake_pedal_position": 0.0, "acceleration": 0.04565700548643814, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019781627295560145, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.9790685} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26452334376374503, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9092609618337026, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1347873446083434, "gear": 1, "accelerator_pedal_position": 0.26488483961750997, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.9790685} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.359981536865234, "x": 39.21606807144092, "y": 0.09074245288718874, "z": null, "yaw": 6.271784054472808, "pitch": null, "roll": null}, "v": 2.1332649387415348, "accelerator_pedal_position": 0.26365255126594467, "brake_pedal_position": 0.0, "acceleration": 0.04565700548643814, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019781627295560145, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502657.9990685} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26452334376374503, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9092609618337026, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.13580603944456, "gear": 1, "accelerator_pedal_position": 0.26452334376374503, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502657.9990685} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.359981536865234, "x": 39.21606807144092, "y": 0.09074245288718874, "z": null, "yaw": 6.271784054472808, "pitch": null, "roll": null}, "v": 2.1332649387415348, "accelerator_pedal_position": 0.26365255126594467, "brake_pedal_position": 0.0, "acceleration": 0.04565700548643814, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019781627295560145, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.0190685} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26452334376374503, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9092609618337026, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1368228462715315, "gear": 1, "accelerator_pedal_position": 0.26452334376374503, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.0190685} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.359981536865234, "x": 39.21606807144092, "y": 0.09074245288718874, "z": null, "yaw": 6.271784054472808, "pitch": null, "roll": null}, "v": 2.1332649387415348, "accelerator_pedal_position": 0.26365255126594467, "brake_pedal_position": 0.0, "acceleration": 0.04565700548643814, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019781627295560145, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.0390685} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26452334376374503, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9092609618337026, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1378377681750536, "gear": 1, "accelerator_pedal_position": 0.26452334376374503, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.0390685} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502658.0590684, "x": 43.45098934205834, "y": 5.087954952728666, "z": null, "yaw": -0.012421275566102763, "pitch": null, "roll": null}, "v": 2.1388508082375, "accelerator_pedal_position": 0.26452334376374503, "brake_pedal_position": 0.0, "acceleration": 0.05058153031254925, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019833424700788214, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.0590684} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2656146183191462, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9376918904823034, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1388508082375, "gear": 1, "accelerator_pedal_position": 0.26452334376374503, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.0590684} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.46998143196106, "x": 39.45098934205834, "y": 0.0879549527286656, "z": null, "yaw": 6.270764031613483, "pitch": null, "roll": null}, "v": 2.1388508082375, "accelerator_pedal_position": 0.26452334376374503, "brake_pedal_position": 0.0, "acceleration": 0.05058153031254925, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019833424700788214, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.0790684} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26529949122822694, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9376918904823034, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1399983155716327, "gear": 1, "accelerator_pedal_position": 0.2656146183191462, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.0790684} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.46998143196106, "x": 39.45098934205834, "y": 0.0879549527286656, "z": null, "yaw": 6.270764031613483, "pitch": null, "roll": null}, "v": 2.1388508082375, "accelerator_pedal_position": 0.26452334376374503, "brake_pedal_position": 0.0, "acceleration": 0.05058153031254925, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019833424700788214, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.0990684} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26529949122822694, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9376918904823034, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1411043216459746, "gear": 1, "accelerator_pedal_position": 0.26529949122822694, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.0990684} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.46998143196106, "x": 39.45098934205834, "y": 0.0879549527286656, "z": null, "yaw": 6.270764031613483, "pitch": null, "roll": null}, "v": 2.1388508082375, "accelerator_pedal_position": 0.26452334376374503, "brake_pedal_position": 0.0, "acceleration": 0.05058153031254925, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019833424700788214, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.1190684} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26529949122822694, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9376918904823034, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.142208275559684, "gear": 1, "accelerator_pedal_position": 0.26529949122822694, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.1190684} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.46998143196106, "x": 39.45098934205834, "y": 0.0879549527286656, "z": null, "yaw": 6.270764031613483, "pitch": null, "roll": null}, "v": 2.1388508082375, "accelerator_pedal_position": 0.26452334376374503, "brake_pedal_position": 0.0, "acceleration": 0.05058153031254925, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019833424700788214, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.1390684} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26529949122822694, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9376918904823034, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.143310180633223, "gear": 1, "accelerator_pedal_position": 0.26529949122822694, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.1390684} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.46998143196106, "x": 39.45098934205834, "y": 0.0879549527286656, "z": null, "yaw": 6.270764031613483, "pitch": null, "roll": null}, "v": 2.1388508082375, "accelerator_pedal_position": 0.26452334376374503, "brake_pedal_position": 0.0, "acceleration": 0.05058153031254925, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019833424700788214, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.1590683} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26529949122822694, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9376918904823034, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.144410040183604, "gear": 1, "accelerator_pedal_position": 0.26529949122822694, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.1590683} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502658.1690683, "x": 43.68655112322249, "y": 5.084919532932893, "z": null, "yaw": -0.013441298425427153, "pitch": null, "roll": null}, "v": 2.1449592039232326, "accelerator_pedal_position": 0.26529949122822694, "brake_pedal_position": 0.0, "acceleration": 0.054865360115306794, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019890067457454086, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.1790683} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2736887809949696, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6877222486740463, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1455078575243856, "gear": 1, "accelerator_pedal_position": 0.26529949122822694, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.1790683} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.579981327056885, "x": 39.68655112322249, "y": 0.08491953293289267, "z": null, "yaw": 6.269744008754159, "pitch": null, "roll": null}, "v": 2.1449592039232326, "accelerator_pedal_position": 0.26529949122822694, "brake_pedal_position": 0.0, "acceleration": 0.054865360115306794, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019890067457454086, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.1990683} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2710954808350752, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6877222486740463, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1476518099451414, "gear": 1, "accelerator_pedal_position": 0.2736887809949696, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.1990683} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.579981327056885, "x": 39.68655112322249, "y": 0.08491953293289267, "z": null, "yaw": 6.269744008754159, "pitch": null, "roll": null}, "v": 2.1449592039232326, "accelerator_pedal_position": 0.26529949122822694, "brake_pedal_position": 0.0, "acceleration": 0.054865360115306794, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019890067457454086, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.2190683} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2710954808350752, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6877222486740463, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1494677671115685, "gear": 1, "accelerator_pedal_position": 0.2710954808350752, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.2190683} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.579981327056885, "x": 39.68655112322249, "y": 0.08491953293289267, "z": null, "yaw": 6.269744008754159, "pitch": null, "roll": null}, "v": 2.1449592039232326, "accelerator_pedal_position": 0.26529949122822694, "brake_pedal_position": 0.0, "acceleration": 0.054865360115306794, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019890067457454086, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.2390683} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2710954808350752, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6877222486740463, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1530895602232953, "gear": 1, "accelerator_pedal_position": 0.2710954808350752, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.2390683} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.579981327056885, "x": 39.68655112322249, "y": 0.08491953293289267, "z": null, "yaw": 6.269744008754159, "pitch": null, "roll": null}, "v": 2.1449592039232326, "accelerator_pedal_position": 0.26529949122822694, "brake_pedal_position": 0.0, "acceleration": 0.054865360115306794, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019890067457454086, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.2590683} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2710954808350752, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6877222486740463, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1530895602232953, "gear": 1, "accelerator_pedal_position": 0.2710954808350752, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.2590683} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502658.2790682, "x": 43.92296475340714, "y": 5.081631908464363, "z": null, "yaw": -0.014461321284751543, "pitch": null, "roll": null}, "v": 2.154895406087523, "accelerator_pedal_position": 0.2710954808350752, "brake_pedal_position": 0.0, "acceleration": 0.09016624280307256, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019982205215112674, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.2790682} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28505772963983866, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.44841166640435354, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.154895406087523, "gear": 1, "accelerator_pedal_position": 0.2710954808350752, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.2790682} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.68998122215271, "x": 39.92296475340714, "y": 0.08163190846436308, "z": null, "yaw": 6.268723985894835, "pitch": null, "roll": null}, "v": 2.154895406087523, "accelerator_pedal_position": 0.2710954808350752, "brake_pedal_position": 0.0, "acceleration": 0.09016624280307256, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019982205215112674, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.2990682} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28074072667565414, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.44841166640435354, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.158442359890408, "gear": 1, "accelerator_pedal_position": 0.28505772963983866, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.2990682} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.68998122215271, "x": 39.92296475340714, "y": 0.08163190846436308, "z": null, "yaw": 6.268723985894835, "pitch": null, "roll": null}, "v": 2.154895406087523, "accelerator_pedal_position": 0.2710954808350752, "brake_pedal_position": 0.0, "acceleration": 0.09016624280307256, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019982205215112674, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.3190682} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28074072667565414, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.44841166640435354, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1614433348168998, "gear": 1, "accelerator_pedal_position": 0.28074072667565414, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.3190682} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.68998122215271, "x": 39.92296475340714, "y": 0.08163190846436308, "z": null, "yaw": 6.268723985894835, "pitch": null, "roll": null}, "v": 2.154895406087523, "accelerator_pedal_position": 0.2710954808350752, "brake_pedal_position": 0.0, "acceleration": 0.09016624280307256, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019982205215112674, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.3390682} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28074072667565414, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.44841166640435354, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1644387177020623, "gear": 1, "accelerator_pedal_position": 0.28074072667565414, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.3390682} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.68998122215271, "x": 39.92296475340714, "y": 0.08163190846436308, "z": null, "yaw": 6.268723985894835, "pitch": null, "roll": null}, "v": 2.154895406087523, "accelerator_pedal_position": 0.2710954808350752, "brake_pedal_position": 0.0, "acceleration": 0.09016624280307256, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019982205215112674, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.3590682} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28074072667565414, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.44841166640435354, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.167428515378896, "gear": 1, "accelerator_pedal_position": 0.28074072667565414, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.3590682} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.68998122215271, "x": 39.92296475340714, "y": 0.08163190846436308, "z": null, "yaw": 6.268723985894835, "pitch": null, "roll": null}, "v": 2.154895406087523, "accelerator_pedal_position": 0.2710954808350752, "brake_pedal_position": 0.0, "acceleration": 0.09016624280307256, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.019982205215112674, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.3790681} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28074072667565414, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.44841166640435354, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.170412734687725, "gear": 1, "accelerator_pedal_position": 0.28074072667565414, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.3790681} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502658.3890681, "x": 44.160852959886405, "y": 5.0780810146413335, "z": null, "yaw": -0.015481344144075933, "pitch": null, "roll": null}, "v": 2.17190275459372, "accelerator_pedal_position": 0.28074072667565414, "brake_pedal_position": 0.0, "acceleration": 0.14886278823903443, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.02013991325377465, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.399068} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28060817833430174, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4397439462532978, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1733913824761104, "gear": 1, "accelerator_pedal_position": 0.28074072667565414, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.399068} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.799981117248535, "x": 40.160852959886405, "y": 0.07808101464133355, "z": null, "yaw": 6.26770396303551, "pitch": null, "roll": null}, "v": 2.17190275459372, "accelerator_pedal_position": 0.28074072667565414, "brake_pedal_position": 0.0, "acceleration": 0.14886278823903443, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.02013991325377465, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.419068} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2807289118235162, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4397439462532978, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.176347904801686, "gear": 1, "accelerator_pedal_position": 0.28060817833430174, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.419068} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.799981117248535, "x": 40.160852959886405, "y": 0.07808101464133355, "z": null, "yaw": 6.26770396303551, "pitch": null, "roll": null}, "v": 2.17190275459372, "accelerator_pedal_position": 0.28074072667565414, "brake_pedal_position": 0.0, "acceleration": 0.14886278823903443, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.02013991325377465, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.439068} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2807289118235162, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4397439462532978, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.180794943974859, "gear": 1, "accelerator_pedal_position": 0.2807289118235162, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.439068} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.799981117248535, "x": 40.160852959886405, "y": 0.07808101464133355, "z": null, "yaw": 6.26770396303551, "pitch": null, "roll": null}, "v": 2.17190275459372, "accelerator_pedal_position": 0.28074072667565414, "brake_pedal_position": 0.0, "acceleration": 0.14886278823903443, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.02013991325377465, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.459068} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2807289118235162, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4397439462532978, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1822745168330746, "gear": 1, "accelerator_pedal_position": 0.2807289118235162, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.459068} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.799981117248535, "x": 40.160852959886405, "y": 0.07808101464133355, "z": null, "yaw": 6.26770396303551, "pitch": null, "roll": null}, "v": 2.17190275459372, "accelerator_pedal_position": 0.28074072667565414, "brake_pedal_position": 0.0, "acceleration": 0.14886278823903443, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.02013991325377465, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.479068} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2807289118235162, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4397439462532978, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1852295074063584, "gear": 1, "accelerator_pedal_position": 0.2807289118235162, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.479068} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502658.499068, "x": 44.40054661975757, "y": 5.07425862647786, "z": null, "yaw": -0.01650136700340034, "pitch": null, "roll": null}, "v": 2.1881789635234625, "accelerator_pedal_position": 0.2807289118235162, "brake_pedal_position": 0.0, "acceleration": 0.14726547895673708, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.020290841482606257, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.499068} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2806750837736217, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4304856816785004, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1881789635234625, "gear": 1, "accelerator_pedal_position": 0.2807289118235162, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.499068} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.90998101234436, "x": 40.40054661975757, "y": 0.07425862647786019, "z": null, "yaw": 6.266683940176186, "pitch": null, "roll": null}, "v": 2.1881789635234625, "accelerator_pedal_position": 0.2807289118235162, "brake_pedal_position": 0.0, "acceleration": 0.14726547895673708, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.020290841482606257, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.519068} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28076807842300755, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4304856816785004, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.191116166721082, "gear": 1, "accelerator_pedal_position": 0.2806750837736217, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.519068} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.90998101234436, "x": 40.40054661975757, "y": 0.07425862647786019, "z": null, "yaw": 6.266683940176186, "pitch": null, "roll": null}, "v": 2.1881789635234625, "accelerator_pedal_position": 0.2807289118235162, "brake_pedal_position": 0.0, "acceleration": 0.14726547895673708, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.020290841482606257, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.539068} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28076807842300755, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4304856816785004, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.194059480738318, "gear": 1, "accelerator_pedal_position": 0.28076807842300755, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.539068} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.90998101234436, "x": 40.40054661975757, "y": 0.07425862647786019, "z": null, "yaw": 6.266683940176186, "pitch": null, "roll": null}, "v": 2.1881789635234625, "accelerator_pedal_position": 0.2807289118235162, "brake_pedal_position": 0.0, "acceleration": 0.14726547895673708, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.020290841482606257, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.559068} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28076807842300755, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4304856816785004, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.196997271779171, "gear": 1, "accelerator_pedal_position": 0.28076807842300755, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.559068} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.90998101234436, "x": 40.40054661975757, "y": 0.07425862647786019, "z": null, "yaw": 6.266683940176186, "pitch": null, "roll": null}, "v": 2.1881789635234625, "accelerator_pedal_position": 0.2807289118235162, "brake_pedal_position": 0.0, "acceleration": 0.14726547895673708, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.020290841482606257, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.579068} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28076807842300755, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4304856816785004, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1999295467565942, "gear": 1, "accelerator_pedal_position": 0.28076807842300755, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.579068} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 19.90998101234436, "x": 40.40054661975757, "y": 0.07425862647786019, "z": null, "yaw": 6.266683940176186, "pitch": null, "roll": null}, "v": 2.1881789635234625, "accelerator_pedal_position": 0.2807289118235162, "brake_pedal_position": 0.0, "acceleration": 0.14726547895673708, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.020290841482606257, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.599068} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28076807842300755, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4304856816785004, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.202856312589995, "gear": 1, "accelerator_pedal_position": 0.28076807842300755, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.599068} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502658.609068, "x": 44.6420194662428, "y": 5.070161493477429, "z": null, "yaw": -0.017521389862724748, "pitch": null, "roll": null}, "v": 2.204317631741746, "accelerator_pedal_position": 0.28076807842300755, "brake_pedal_position": 0.0, "acceleration": 0.1459944463406344, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.020440494305349, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.619068} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2807036392139631, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4197839358357152, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2057775762051524, "gear": 1, "accelerator_pedal_position": 0.28076807842300755, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.619068} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.019980907440186, "x": 40.6420194662428, "y": 0.07016149347742928, "z": null, "yaw": 6.265663917316862, "pitch": null, "roll": null}, "v": 2.204317631741746, "accelerator_pedal_position": 0.28076807842300755, "brake_pedal_position": 0.0, "acceleration": 0.1459944463406344, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.020440494305349, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.639068} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28079956772283127, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4197839358357152, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.210143094688064, "gear": 1, "accelerator_pedal_position": 0.28079956772283127, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.639068} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.019980907440186, "x": 40.6420194662428, "y": 0.07016149347742928, "z": null, "yaw": 6.265663917316862, "pitch": null, "roll": null}, "v": 2.204317631741746, "accelerator_pedal_position": 0.28076807842300755, "brake_pedal_position": 0.0, "acceleration": 0.1459944463406344, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.020440494305349, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.6690679} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28079956772283127, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4197839358357152, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2130545788497797, "gear": 1, "accelerator_pedal_position": 0.28079956772283127, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.6690679} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.019980907440186, "x": 40.6420194662428, "y": 0.07016149347742928, "z": null, "yaw": 6.265663917316862, "pitch": null, "roll": null}, "v": 2.204317631741746, "accelerator_pedal_position": 0.28076807842300755, "brake_pedal_position": 0.0, "acceleration": 0.1459944463406344, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.020440494305349, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.6890678} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28079956772283127, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4197839358357152, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2174115222178443, "gear": 1, "accelerator_pedal_position": 0.28079956772283127, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.6890678} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.019980907440186, "x": 40.6420194662428, "y": 0.07016149347742928, "z": null, "yaw": 6.265663917316862, "pitch": null, "roll": null}, "v": 2.204317631741746, "accelerator_pedal_position": 0.28076807842300755, "brake_pedal_position": 0.0, "acceleration": 0.1459944463406344, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.020440494305349, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.7090678} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28079956772283127, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4197839358357152, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2188610980535257, "gear": 1, "accelerator_pedal_position": 0.28079956772283127, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.7090678} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502658.7190678, "x": 44.88525562182719, "y": 5.065786262191647, "z": null, "yaw": -0.018541412722049157, "pitch": null, "roll": null}, "v": 2.2203093060299306, "accelerator_pedal_position": 0.28079956772283127, "brake_pedal_position": 0.0, "acceleration": 0.1446840988217677, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.020588784062920074, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.7290678} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29564437078188066, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.178971657072768, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2217561470181484, "gear": 1, "accelerator_pedal_position": 0.28079956772283127, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.7290678} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.12998080253601, "x": 40.88525562182719, "y": 0.06578626219164718, "z": null, "yaw": 6.264643894457537, "pitch": null, "roll": null}, "v": 2.2203093060299306, "accelerator_pedal_position": 0.28079956772283127, "brake_pedal_position": 0.0, "acceleration": 0.1446840988217677, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.020588784062920074, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.7490678} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29108072461590634, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.178971657072768, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.226500455375036, "gear": 1, "accelerator_pedal_position": 0.29564437078188066, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.7490678} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.12998080253601, "x": 40.88525562182719, "y": 0.06578626219164718, "z": null, "yaw": 6.264643894457537, "pitch": null, "roll": null}, "v": 2.2203093060299306, "accelerator_pedal_position": 0.28079956772283127, "brake_pedal_position": 0.0, "acceleration": 0.1446840988217677, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.020588784062920074, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.7690678} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29108072461590634, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.178971657072768, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2306656146131307, "gear": 1, "accelerator_pedal_position": 0.29108072461590634, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.7690678} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.12998080253601, "x": 40.88525562182719, "y": 0.06578626219164718, "z": null, "yaw": 6.264643894457537, "pitch": null, "roll": null}, "v": 2.2203093060299306, "accelerator_pedal_position": 0.28079956772283127, "brake_pedal_position": 0.0, "acceleration": 0.1446840988217677, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.020588784062920074, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.7890677} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29108072461590634, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.178971657072768, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2348228977235403, "gear": 1, "accelerator_pedal_position": 0.29108072461590634, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.7890677} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.12998080253601, "x": 40.88525562182719, "y": 0.06578626219164718, "z": null, "yaw": 6.264643894457537, "pitch": null, "roll": null}, "v": 2.2203093060299306, "accelerator_pedal_position": 0.28079956772283127, "brake_pedal_position": 0.0, "acceleration": 0.1446840988217677, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.020588784062920074, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.8090677} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29108072461590634, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.178971657072768, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2389723126897354, "gear": 1, "accelerator_pedal_position": 0.29108072461590634, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.8090677} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502658.8290677, "x": 45.130575577449626, "y": 5.061123165583551, "z": null, "yaw": -0.019561435581373566, "pitch": null, "roll": null}, "v": 2.243113867519301, "accelerator_pedal_position": 0.29108072461590634, "brake_pedal_position": 0.0, "acceleration": 0.20678323724687553, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.02080024928124759, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.8290677} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29085092957988234, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.1357944972936403, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.243113867519301, "gear": 1, "accelerator_pedal_position": 0.29108072461590634, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.8290677} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.239980697631836, "x": 41.130575577449626, "y": 0.06112316558355069, "z": null, "yaw": 6.263623871598213, "pitch": null, "roll": null}, "v": 2.243113867519301, "accelerator_pedal_position": 0.29108072461590634, "brake_pedal_position": 0.0, "acceleration": 0.20678323724687553, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.02080024928124759, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.8490677} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29103064525430117, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.1357944972936403, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2472188594944815, "gear": 1, "accelerator_pedal_position": 0.29085092957988234, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.8490677} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.239980697631836, "x": 41.130575577449626, "y": 0.06112316558355069, "z": null, "yaw": 6.263623871598213, "pitch": null, "roll": null}, "v": 2.243113867519301, "accelerator_pedal_position": 0.29108072461590634, "brake_pedal_position": 0.0, "acceleration": 0.20678323724687553, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.02080024928124759, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.8690677} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29103064525430117, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.1357944972936403, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2513385157265606, "gear": 1, "accelerator_pedal_position": 0.29103064525430117, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.8690677} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.239980697631836, "x": 41.130575577449626, "y": 0.06112316558355069, "z": null, "yaw": 6.263623871598213, "pitch": null, "roll": null}, "v": 2.243113867519301, "accelerator_pedal_position": 0.29108072461590634, "brake_pedal_position": 0.0, "acceleration": 0.20678323724687553, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.02080024928124759, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.8890676} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29103064525430117, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.1357944972936403, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2554503478225434, "gear": 1, "accelerator_pedal_position": 0.29103064525430117, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.8890676} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.239980697631836, "x": 41.130575577449626, "y": 0.06112316558355069, "z": null, "yaw": 6.263623871598213, "pitch": null, "roll": null}, "v": 2.243113867519301, "accelerator_pedal_position": 0.29108072461590634, "brake_pedal_position": 0.0, "acceleration": 0.20678323724687553, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.02080024928124759, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.9090676} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29103064525430117, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.1357944972936403, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2595543638825384, "gear": 1, "accelerator_pedal_position": 0.29103064525430117, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.9090676} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.239980697631836, "x": 41.130575577449626, "y": 0.06112316558355069, "z": null, "yaw": 6.263623871598213, "pitch": null, "roll": null}, "v": 2.243113867519301, "accelerator_pedal_position": 0.29108072461590634, "brake_pedal_position": 0.0, "acceleration": 0.20678323724687553, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.02080024928124759, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.9290676} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29103064525430117, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.1357944972936403, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2636505720297957, "gear": 1, "accelerator_pedal_position": 0.29103064525430117, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.9290676} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502658.9390676, "x": 45.37839862243923, "y": 5.056159615641147, "z": null, "yaw": -0.020581458440697975, "pitch": null, "roll": null}, "v": 2.2656957506809494, "accelerator_pedal_position": 0.29103064525430117, "brake_pedal_position": 0.0, "acceleration": 0.2043229729587976, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.021009649617897353, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.9490676} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29096469401081576, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.07718871766117479, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2677389804105372, "gear": 1, "accelerator_pedal_position": 0.29103064525430117, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.9490676} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.34998059272766, "x": 41.37839862243923, "y": 0.05615961564114702, "z": null, "yaw": 6.262603848738888, "pitch": null, "roll": null}, "v": 2.2656957506809494, "accelerator_pedal_position": 0.29103064525430117, "brake_pedal_position": 0.0, "acceleration": 0.2043229729587976, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.021009649617897353, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.9690676} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29109266727221306, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.07718871766117479, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.271811357220511, "gear": 1, "accelerator_pedal_position": 0.29096469401081576, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.9690676} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.34998059272766, "x": 41.37839862243923, "y": 0.05615961564114702, "z": null, "yaw": 6.262603848738888, "pitch": null, "roll": null}, "v": 2.2656957506809494, "accelerator_pedal_position": 0.29103064525430117, "brake_pedal_position": 0.0, "acceleration": 0.2043229729587976, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.021009649617897353, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502658.9890676} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29109266727221306, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.07718871766117479, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.275891955372815, "gear": 1, "accelerator_pedal_position": 0.29109266727221306, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502658.9890676} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.34998059272766, "x": 41.37839862243923, "y": 0.05615961564114702, "z": null, "yaw": 6.262603848738888, "pitch": null, "roll": null}, "v": 2.2656957506809494, "accelerator_pedal_position": 0.29103064525430117, "brake_pedal_position": 0.0, "acceleration": 0.2043229729587976, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.021009649617897353, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.0090675} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29109266727221306, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.07718871766117479, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2799647635140934, "gear": 1, "accelerator_pedal_position": 0.29109266727221306, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.0090675} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.34998059272766, "x": 41.37839862243923, "y": 0.05615961564114702, "z": null, "yaw": 6.262603848738888, "pitch": null, "roll": null}, "v": 2.2656957506809494, "accelerator_pedal_position": 0.29103064525430117, "brake_pedal_position": 0.0, "acceleration": 0.2043229729587976, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.021009649617897353, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.0290675} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29109266727221306, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.07718871766117479, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2840297898838235, "gear": 1, "accelerator_pedal_position": 0.29109266727221306, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.0290675} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502659.0490675, "x": 45.62869065371662, "y": 5.050891207946068, "z": null, "yaw": -0.021601481300022384, "pitch": null, "roll": null}, "v": 2.2880870427437467, "accelerator_pedal_position": 0.29109266727221306, "brake_pedal_position": 0.0, "acceleration": 0.20257139516242595, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.021217282615659736, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.0490675} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24423739596169775, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5022090373020178, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2880870427437467, "gear": 1, "accelerator_pedal_position": 0.29109266727221306, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5133147570961638, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.0490675} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.459980487823486, "x": 41.62869065371662, "y": 0.050891207946068384, "z": null, "yaw": 6.261583825879564, "pitch": null, "roll": null}, "v": 2.2880870427437467, "accelerator_pedal_position": 0.29109266727221306, "brake_pedal_position": 0.0, "acceleration": 0.20257139516242595, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.021217282615659736, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.0690675} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25898663868700694, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5022090373020178, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2862824261317103, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4332093910525168, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.0690675} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.459980487823486, "x": 41.62869065371662, "y": 0.050891207946068384, "z": null, "yaw": 6.261583825879564, "pitch": null, "roll": null}, "v": 2.2880870427437467, "accelerator_pedal_position": 0.29109266727221306, "brake_pedal_position": 0.0, "acceleration": 0.20257139516242595, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.021217282615659736, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.0890675} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25898663868700694, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5022090373020178, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2863240361497366, "gear": 1, "accelerator_pedal_position": 0.25898663868700694, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3529316420907091, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.0890675} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.459980487823486, "x": 41.62869065371662, "y": 0.050891207946068384, "z": null, "yaw": 6.261583825879564, "pitch": null, "roll": null}, "v": 2.2880870427437467, "accelerator_pedal_position": 0.29109266727221306, "brake_pedal_position": 0.0, "acceleration": 0.20257139516242595, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.021217282615659736, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.1090674} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25898663868700694, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5022090373020178, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.286365566542454, "gear": 1, "accelerator_pedal_position": 0.25898663868700694, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3529316420907091, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.1090674} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.459980487823486, "x": 41.62869065371662, "y": 0.050891207946068384, "z": null, "yaw": 6.261583825879564, "pitch": null, "roll": null}, "v": 2.2880870427437467, "accelerator_pedal_position": 0.29109266727221306, "brake_pedal_position": 0.0, "acceleration": 0.20257139516242595, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.021217282615659736, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.1290674} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25898663868700694, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5022090373020178, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2864070174615443, "gear": 1, "accelerator_pedal_position": 0.25898663868700694, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3529316420907091, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.1290674} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.459980487823486, "x": 41.62869065371662, "y": 0.050891207946068384, "z": null, "yaw": 6.261583825879564, "pitch": null, "roll": null}, "v": 2.2880870427437467, "accelerator_pedal_position": 0.29109266727221306, "brake_pedal_position": 0.0, "acceleration": 0.20257139516242595, "steering_wheel_angle": -0.5133147570961638, "front_wheel_angle": -0.02373425619239704, "heading_rate": -0.021217282615659736, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.1490674} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25898663868700694, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5022090373020178, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2864483890584033, "gear": 1, "accelerator_pedal_position": 0.25898663868700694, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3529316420907091, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.1490674} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502659.1590674, "x": 45.880155505141815, "y": 5.045363353823047, "z": null, "yaw": -0.02237402093052993, "pitch": null, "roll": null}, "v": 2.2864690451582295, "accelerator_pedal_position": 0.25898663868700694, "brake_pedal_position": 0.0, "acceleration": 0.0020636325912139486, "steering_wheel_angle": -0.3529316420907091, "front_wheel_angle": -0.016283743572151333, "heading_rate": -0.014545143283832792, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.1690674} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25684202343715656, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5741949583017796, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2864896814841416, "gear": 1, "accelerator_pedal_position": 0.25898663868700694, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3529316420907091, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.1690674} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.56998038291931, "x": 41.880155505141815, "y": 0.04536335382304735, "z": null, "yaw": 6.260811286249056, "pitch": null, "roll": null}, "v": 2.2864690451582295, "accelerator_pedal_position": 0.25898663868700694, "brake_pedal_position": 0.0, "acceleration": 0.0020636325912139486, "steering_wheel_angle": -0.3529316420907091, "front_wheel_angle": -0.016283743572151333, "heading_rate": -0.014545143283832792, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.1890674} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25750447033275253, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5741949583017796, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.286262946296843, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.27232490002694176, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.1890674} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.56998038291931, "x": 41.880155505141815, "y": 0.04536335382304735, "z": null, "yaw": 6.260811286249056, "pitch": null, "roll": null}, "v": 2.2864690451582295, "accelerator_pedal_position": 0.25898663868700694, "brake_pedal_position": 0.0, "acceleration": 0.0020636325912139486, "steering_wheel_angle": -0.3529316420907091, "front_wheel_angle": -0.016283743572151333, "heading_rate": -0.014545143283832792, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.2090673} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25750447033275253, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5741949583017796, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2861194112222605, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.27232490002694176, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.2090673} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.56998038291931, "x": 41.880155505141815, "y": 0.04536335382304735, "z": null, "yaw": 6.260811286249056, "pitch": null, "roll": null}, "v": 2.2864690451582295, "accelerator_pedal_position": 0.25898663868700694, "brake_pedal_position": 0.0, "acceleration": 0.0020636325912139486, "steering_wheel_angle": -0.3529316420907091, "front_wheel_angle": -0.016283743572151333, "heading_rate": -0.014545143283832792, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.2290673} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25750447033275253, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5741949583017796, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.285976150808622, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.27232490002694176, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.2290673} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.56998038291931, "x": 41.880155505141815, "y": 0.04536335382304735, "z": null, "yaw": 6.260811286249056, "pitch": null, "roll": null}, "v": 2.2864690451582295, "accelerator_pedal_position": 0.25898663868700694, "brake_pedal_position": 0.0, "acceleration": 0.0020636325912139486, "steering_wheel_angle": -0.3529316420907091, "front_wheel_angle": -0.016283743572151333, "heading_rate": -0.014545143283832792, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.2490673} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25750447033275253, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5741949583017796, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2858331645221455, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.27232490002694176, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.2490673} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502659.2690673, "x": 46.13156532001124, "y": 5.039668035544989, "z": null, "yaw": -0.022949818105578744, "pitch": null, "roll": null}, "v": 2.285690451830118, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3665283310073796, "steering_wheel_angle": -0.27232490002694176, "front_wheel_angle": -0.012551243178401608, "heading_rate": -0.011206938766482615, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.2690673} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23508526738213165, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8390876015885809, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.285690451830118, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.27232490002694176, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.2690673} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.679980278015137, "x": 42.13156532001124, "y": 0.03966803554498899, "z": null, "yaw": 6.260235489074008, "pitch": null, "roll": null}, "v": 2.285690451830118, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3665283310073796, "steering_wheel_angle": -0.27232490002694176, "front_wheel_angle": -0.012551243178401608, "heading_rate": -0.011206938766482615, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.2890673} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24208754648549263, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8390876015885809, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2827469527578286, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.1909595867181437, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.2890673} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.679980278015137, "x": 42.13156532001124, "y": 0.03966803554498899, "z": null, "yaw": 6.260235489074008, "pitch": null, "roll": null}, "v": 2.285690451830118, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3665283310073796, "steering_wheel_angle": -0.27232490002694176, "front_wheel_angle": -0.012551243178401608, "heading_rate": -0.011206938766482615, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.3090672} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24208754648549263, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8390876015885809, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2806839494335573, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.109418704344607, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.3090672} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.679980278015137, "x": 42.13156532001124, "y": 0.03966803554498899, "z": null, "yaw": 6.260235489074008, "pitch": null, "roll": null}, "v": 2.285690451830118, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3665283310073796, "steering_wheel_angle": -0.27232490002694176, "front_wheel_angle": -0.012551243178401608, "heading_rate": -0.011206938766482615, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.3290672} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24208754648549263, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8390876015885809, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2786248896754397, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.02770225290633157, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.3290672} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.679980278015137, "x": 42.13156532001124, "y": 0.03966803554498899, "z": null, "yaw": 6.260235489074008, "pitch": null, "roll": null}, "v": 2.285690451830118, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3665283310073796, "steering_wheel_angle": -0.27232490002694176, "front_wheel_angle": -0.012551243178401608, "heading_rate": -0.011206938766482615, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.3490672} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24208754648549263, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8390876015885809, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2765697642500093, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.013217232987496627, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.3490672} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.679980278015137, "x": 42.13156532001124, "y": 0.03966803554498899, "z": null, "yaw": 6.260235489074008, "pitch": null, "roll": null}, "v": 2.285690451830118, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3665283310073796, "steering_wheel_angle": -0.27232490002694176, "front_wheel_angle": -0.012551243178401608, "heading_rate": -0.011206938766482615, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.3690672} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24208754648549263, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8390876015885809, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2745185639511605, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.013217232987496627, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.3690672} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502659.3790672, "x": 46.38227410688138, "y": 5.0338787909292195, "z": null, "yaw": -0.023129336670811965, "pitch": null, "roll": null}, "v": 2.2734944328547524, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36536249100495316, "steering_wheel_angle": 0.013217232987496627, "front_wheel_angle": 0.0006070963076827579, "heading_rate": 0.0005391524395672043, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.3890672} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3146090898023577, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.272471279600046, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.013217232987496627, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.3890672} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.789980173110962, "x": 42.38227410688138, "y": 0.03387879092921953, "z": null, "yaw": 6.260055970508774, "pitch": null, "roll": null}, "v": 2.2734944328547524, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36536249100495316, "steering_wheel_angle": 0.013217232987496627, "front_wheel_angle": 0.0006070963076827579, "heading_rate": 0.0005391524395672043, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.4090672} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3146090898023577, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2651694682746775, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.09605129563692612, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.4090672} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.789980173110962, "x": 42.38227410688138, "y": 0.03387879092921953, "z": null, "yaw": 6.260055970508774, "pitch": null, "roll": null}, "v": 2.2734944328547524, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36536249100495316, "steering_wheel_angle": 0.013217232987496627, "front_wheel_angle": 0.0006070963076827579, "heading_rate": 0.0005391524395672043, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.4290671} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3146090898023577, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2578815733937243, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.17870508597973944, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.4290671} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.789980173110962, "x": 42.38227410688138, "y": 0.03387879092921953, "z": null, "yaw": 6.260055970508774, "pitch": null, "roll": null}, "v": 2.2734944328547524, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36536249100495316, "steering_wheel_angle": 0.013217232987496627, "front_wheel_angle": 0.0006070963076827579, "heading_rate": 0.0005391524395672043, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.449067} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3146090898023577, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2506075471987175, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.26117860401593657, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.449067} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.789980173110962, "x": 42.38227410688138, "y": 0.03387879092921953, "z": null, "yaw": 6.260055970508774, "pitch": null, "roll": null}, "v": 2.2734944328547524, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36536249100495316, "steering_wheel_angle": 0.013217232987496627, "front_wheel_angle": 0.0006070963076827579, "heading_rate": 0.0005391524395672043, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.469067} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3146090898023577, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.243347342143348, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3434718497455176, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.469067} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502659.489067, "x": 46.63055076206798, "y": 5.028158289059372, "z": null, "yaw": -0.022768406064869757, "pitch": null, "roll": null}, "v": 2.2361009108922802, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36180651838154687, "steering_wheel_angle": 0.42558482316848234, "front_wheel_angle": 0.01965484081046068, "heading_rate": 0.017170260868413976, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.489067} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22656280754309205, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3625886585178872, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2361009108922802, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.42558482316848234, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.489067} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.899980068206787, "x": 42.63055076206798, "y": 0.028158289059372343, "z": null, "yaw": 6.260416901114716, "pitch": null, "roll": null}, "v": 2.2361009108922802, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36180651838154687, "steering_wheel_angle": 0.42558482316848234, "front_wheel_angle": 0.01965484081046068, "heading_rate": 0.017170260868413976, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.509067} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22152120117517687, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3625886585178872, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2321869856368526, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5076283563940936, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.509067} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.899980068206787, "x": 42.63055076206798, "y": 0.028158289059372343, "z": null, "yaw": 6.260416901114716, "pitch": null, "roll": null}, "v": 2.2361009108922802, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36180651838154687, "steering_wheel_angle": 0.42558482316848234, "front_wheel_angle": 0.01965484081046068, "heading_rate": 0.017170260868413976, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.529067} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22152120117517687, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3625886585178872, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2276505642708986, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5485823376726022, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.529067} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.899980068206787, "x": 42.63055076206798, "y": 0.028158289059372343, "z": null, "yaw": 6.260416901114716, "pitch": null, "roll": null}, "v": 2.2361009108922802, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36180651838154687, "steering_wheel_angle": 0.42558482316848234, "front_wheel_angle": 0.01965484081046068, "heading_rate": 0.017170260868413976, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.549067} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22152120117517687, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3625886585178872, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2231227195522103, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5485823376726022, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.549067} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.899980068206787, "x": 42.63055076206798, "y": 0.028158289059372343, "z": null, "yaw": 6.260416901114716, "pitch": null, "roll": null}, "v": 2.2361009108922802, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36180651838154687, "steering_wheel_angle": 0.42558482316848234, "front_wheel_angle": 0.01965484081046068, "heading_rate": 0.017170260868413976, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.569067} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22152120117517687, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3625886585178872, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.218603427068929, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5485823376726022, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.569067} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 20.899980068206787, "x": 42.63055076206798, "y": 0.028158289059372343, "z": null, "yaw": 6.260416901114716, "pitch": null, "roll": null}, "v": 2.2361009108922802, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36180651838154687, "steering_wheel_angle": 0.42558482316848234, "front_wheel_angle": 0.01965484081046068, "heading_rate": 0.017170260868413976, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.589067} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22152120117517687, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3625886585178872, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2140926625017614, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5485823376726022, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.589067} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502659.599067, "x": 46.87527395127038, "y": 5.022697224619581, "z": null, "yaw": -0.021722485832598615, "pitch": null, "roll": null}, "v": 2.211840470612145, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3595144062049848, "steering_wheel_angle": 0.5485823376726022, "front_wheel_angle": 0.025376902572899887, "heading_rate": 0.02193035631302009, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.609067} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2331604672567738, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.4154510994080107, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2095904016235437, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5485823376726022, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.609067} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.009979963302612, "x": 42.87527395127038, "y": 0.02269722461958068, "z": null, "yaw": 6.261462821346988, "pitch": null, "roll": null}, "v": 2.211840470612145, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3595144062049848, "steering_wheel_angle": 0.5485823376726022, "front_wheel_angle": 0.025376902572899887, "heading_rate": 0.02193035631302009, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.629067} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22940858853752327, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.4154510994080107, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2065508436309416, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5895523105158035, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.629067} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.009979963302612, "x": 42.87527395127038, "y": 0.02269722461958068, "z": null, "yaw": 6.261462821346988, "pitch": null, "roll": null}, "v": 2.211840470612145, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3595144062049848, "steering_wheel_angle": 0.5485823376726022, "front_wheel_angle": 0.025376902572899887, "heading_rate": 0.02193035631302009, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.649067} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22940858853752327, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.4154510994080107, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2030482420157638, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5895523105158035, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.649067} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.009979963302612, "x": 42.87527395127038, "y": 0.02269722461958068, "z": null, "yaw": 6.261462821346988, "pitch": null, "roll": null}, "v": 2.211840470612145, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3595144062049848, "steering_wheel_angle": 0.5485823376726022, "front_wheel_angle": 0.025376902572899887, "heading_rate": 0.02193035631302009, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.669067} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22940858853752327, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.4154510994080107, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.199552227689663, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5895523105158035, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.669067} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.009979963302612, "x": 42.87527395127038, "y": 0.02269722461958068, "z": null, "yaw": 6.261462821346988, "pitch": null, "roll": null}, "v": 2.211840470612145, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3595144062049848, "steering_wheel_angle": 0.5485823376726022, "front_wheel_angle": 0.025376902572899887, "heading_rate": 0.02193035631302009, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.689067} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22940858853752327, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.4154510994080107, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1960627833774744, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5895523105158035, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.689067} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502659.7090669, "x": 47.117548869564786, "y": 5.017559468562168, "z": null, "yaw": -0.020564635560362778, "pitch": null, "roll": null}, "v": 2.192579891864054, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35770306041526856, "steering_wheel_angle": 0.5895523105158035, "front_wheel_angle": 0.027287110645736048, "heading_rate": 0.023376571821027346, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.7090669} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.9350945517560276, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.192579891864054, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5895523105158035, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.7090669} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.119979858398438, "x": 43.117548869564786, "y": 0.017559468562168057, "z": null, "yaw": 6.262620671619223, "pitch": null, "roll": null}, "v": 2.192579891864054, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35770306041526856, "steering_wheel_angle": 0.5895523105158035, "front_wheel_angle": 0.027287110645736048, "heading_rate": 0.023376571821027346, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.7290668} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.9350945517560276, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.185429186476611, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.6725863671022435, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.7290668} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.119979858398438, "x": 43.117548869564786, "y": 0.017559468562168057, "z": null, "yaw": 6.262620671619223, "pitch": null, "roll": null}, "v": 2.192579891864054, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35770306041526856, "steering_wheel_angle": 0.5895523105158035, "front_wheel_angle": 0.027287110645736048, "heading_rate": 0.023376571821027346, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.7490668} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.9350945517560276, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.178291881570271, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.7554336216961034, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.7490668} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.119979858398438, "x": 43.117548869564786, "y": 0.017559468562168057, "z": null, "yaw": 6.262620671619223, "pitch": null, "roll": null}, "v": 2.192579891864054, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35770306041526856, "steering_wheel_angle": 0.5895523105158035, "front_wheel_angle": 0.027287110645736048, "heading_rate": 0.023376571821027346, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.7690668} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.9350945517560276, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.171167931665497, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.8380940742973836, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.7690668} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.119979858398438, "x": 43.117548869564786, "y": 0.017559468562168057, "z": null, "yaw": 6.262620671619223, "pitch": null, "roll": null}, "v": 2.192579891864054, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35770306041526856, "steering_wheel_angle": 0.5895523105158035, "front_wheel_angle": 0.027287110645736048, "heading_rate": 0.023376571821027346, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.7890668} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.9350945517560276, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.164057291482223, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.9205677249060837, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.7890668} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.119979858398438, "x": 43.117548869564786, "y": 0.017559468562168057, "z": null, "yaw": 6.262620671619223, "pitch": null, "roll": null}, "v": 2.192579891864054, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35770306041526856, "steering_wheel_angle": 0.5895523105158035, "front_wheel_angle": 0.027287110645736048, "heading_rate": 0.023376571821027346, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.8090668} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.9350945517560276, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1569599159387542, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.002854573522204, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.8090668} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502659.8190668, "x": 47.35672332394124, "y": 5.012794452863626, "z": null, "yaw": -0.018974783487599227, "pitch": null, "roll": null}, "v": 2.1534161883728884, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35404282222210864, "steering_wheel_angle": 1.043927947083047, "front_wheel_angle": 0.04861571737874103, "heading_rate": 0.040926729927091184, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.8290668} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.03270414014979029, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.560128081155279, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1498757601506675, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.0849546201457445, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.8290668} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.229979753494263, "x": 43.35672332394124, "y": 0.012794452863626127, "z": null, "yaw": 6.264210523691987, "pitch": null, "roll": null}, "v": 2.1534161883728884, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35404282222210864, "steering_wheel_angle": 1.043927947083047, "front_wheel_angle": 0.04861571737874103, "heading_rate": 0.040926729927091184, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.8490667} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.022094389204309388, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.560128081155279, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1375745475933923, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.03270414014979029, "steering_wheel_angle": 1.1684026313132372, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.8490667} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.229979753494263, "x": 43.35672332394124, "y": 0.012794452863626127, "z": null, "yaw": 6.264210523691987, "pitch": null, "roll": null}, "v": 2.1534161883728884, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35404282222210864, "steering_wheel_angle": 1.043927947083047, "front_wheel_angle": 0.04861571737874103, "heading_rate": 0.040926729927091184, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.8690667} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.022094389204309388, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.560128081155279, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.126992932560354, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.022094389204309388, "steering_wheel_angle": 1.2516567665900236, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.8690667} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.229979753494263, "x": 43.35672332394124, "y": 0.012794452863626127, "z": null, "yaw": 6.264210523691987, "pitch": null, "roll": null}, "v": 2.1534161883728884, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35404282222210864, "steering_wheel_angle": 1.043927947083047, "front_wheel_angle": 0.04861571737874103, "heading_rate": 0.040926729927091184, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.8890667} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.022094389204309388, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.560128081155279, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.116430904080678, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.022094389204309388, "steering_wheel_angle": 1.334717025976103, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.8890667} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.229979753494263, "x": 43.35672332394124, "y": 0.012794452863626127, "z": null, "yaw": 6.264210523691987, "pitch": null, "roll": null}, "v": 2.1534161883728884, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35404282222210864, "steering_wheel_angle": 1.043927947083047, "front_wheel_angle": 0.04861571737874103, "heading_rate": 0.040926729927091184, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.9090667} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.022094389204309388, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.560128081155279, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.105888381297687, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.022094389204309388, "steering_wheel_angle": 1.4175834094714752, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.9090667} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502659.9290667, "x": 47.59068245067479, "y": 5.008602700397869, "z": null, "yaw": -0.016459895357891233, "pitch": null, "roll": null}, "v": 2.095365283751279, "accelerator_pedal_position": 0, "brake_pedal_position": 0.022094389204309388, "acceleration": -0.5254289345455398, "steering_wheel_angle": 1.5002559170761414, "front_wheel_angle": 0.07030804042266567, "heading_rate": 0.057642287026921965, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.9290667} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.568668417459568, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.095365283751279, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.022094389204309388, "steering_wheel_angle": 1.5002559170761414, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.9290667} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.339979648590088, "x": 43.59068245067479, "y": 0.008602700397869256, "z": null, "yaw": 6.266725411821695, "pitch": null, "roll": null}, "v": 2.095365283751279, "accelerator_pedal_position": 0, "brake_pedal_position": 0.022094389204309388, "acceleration": -0.5254289345455398, "steering_wheel_angle": 1.5002559170761414, "front_wheel_angle": 0.07030804042266567, "heading_rate": 0.057642287026921965, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.9490666} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.568668417459568, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0883950106844673, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.5827558703083306, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.9490666} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.339979648590088, "x": 43.59068245067479, "y": 0.008602700397869256, "z": null, "yaw": 6.266725411821695, "pitch": null, "roll": null}, "v": 2.095365283751279, "accelerator_pedal_position": 0, "brake_pedal_position": 0.022094389204309388, "acceleration": -0.5254289345455398, "steering_wheel_angle": 1.5002559170761414, "front_wheel_angle": 0.07030804042266567, "heading_rate": 0.057642287026921965, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.9690666} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.568668417459568, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.081437529550451, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.665061847281289, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.9690666} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.339979648590088, "x": 43.59068245067479, "y": 0.008602700397869256, "z": null, "yaw": 6.266725411821695, "pitch": null, "roll": null}, "v": 2.095365283751279, "accelerator_pedal_position": 0, "brake_pedal_position": 0.022094389204309388, "acceleration": -0.5254289345455398, "steering_wheel_angle": 1.5002559170761414, "front_wheel_angle": 0.07030804042266567, "heading_rate": 0.057642287026921965, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502659.9890666} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.568668417459568, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0744927975195586, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.747173847995016, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502659.9890666} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.339979648590088, "x": 43.59068245067479, "y": 0.008602700397869256, "z": null, "yaw": 6.266725411821695, "pitch": null, "roll": null}, "v": 2.095365283751279, "accelerator_pedal_position": 0, "brake_pedal_position": 0.022094389204309388, "acceleration": -0.5254289345455398, "steering_wheel_angle": 1.5002559170761414, "front_wheel_angle": 0.07030804042266567, "heading_rate": 0.057642287026921965, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.0090666} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.568668417459568, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0675607719470364, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.7881571072546676, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.0090666} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.339979648590088, "x": 43.59068245067479, "y": 0.008602700397869256, "z": null, "yaw": 6.266725411821695, "pitch": null, "roll": null}, "v": 2.095365283751279, "accelerator_pedal_position": 0, "brake_pedal_position": 0.022094389204309388, "acceleration": -0.5254289345455398, "steering_wheel_angle": 1.5002559170761414, "front_wheel_angle": 0.07030804042266567, "heading_rate": 0.057642287026921965, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.0290666} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.568668417459568, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.060641410372039, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.7881571072546676, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.0290666} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502660.0390666, "x": 47.81923445255131, "y": 5.005179654825905, "z": null, "yaw": -0.013053465477430425, "pitch": null, "roll": null}, "v": 2.057186465364639, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34517948480102656, "steering_wheel_angle": 1.7881571072546676, "front_wheel_angle": 0.08413897028971594, "heading_rate": 0.06777311157539678, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.0490665} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.5946751992376633, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.053734670516629, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.7881571072546676, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.0490665} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.449979543685913, "x": 43.81923445255131, "y": 0.005179654825904656, "z": null, "yaw": 6.270131841702156, "pitch": null, "roll": null}, "v": 2.057186465364639, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34517948480102656, "steering_wheel_angle": 1.7881571072546676, "front_wheel_angle": 0.08413897028971594, "heading_rate": 0.06777311157539678, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.0690665} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.5946751992376633, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0468405102847815, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.7881571072546676, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.0690665} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.449979543685913, "x": 43.81923445255131, "y": 0.005179654825904656, "z": null, "yaw": 6.270131841702156, "pitch": null, "roll": null}, "v": 2.057186465364639, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34517948480102656, "steering_wheel_angle": 1.7881571072546676, "front_wheel_angle": 0.08413897028971594, "heading_rate": 0.06777311157539678, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.0890665} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.5946751992376633, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0399588877613977, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.7881571072546676, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.0890665} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.449979543685913, "x": 43.81923445255131, "y": 0.005179654825904656, "z": null, "yaw": 6.270131841702156, "pitch": null, "roll": null}, "v": 2.057186465364639, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34517948480102656, "steering_wheel_angle": 1.7881571072546676, "front_wheel_angle": 0.08413897028971594, "heading_rate": 0.06777311157539678, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.1090665} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.5946751992376633, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0330897612113223, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.7881571072546676, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.1090665} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.449979543685913, "x": 43.81923445255131, "y": 0.005179654825904656, "z": null, "yaw": 6.270131841702156, "pitch": null, "roll": null}, "v": 2.057186465364639, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34517948480102656, "steering_wheel_angle": 1.7881571072546676, "front_wheel_angle": 0.08413897028971594, "heading_rate": 0.06777311157539678, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.1290665} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.5946751992376633, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.026233089078368, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.7881571072546676, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.1290665} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502660.1490664, "x": 48.043616915300525, "y": 5.002618938349344, "z": null, "yaw": -0.00942956341565392, "pitch": null, "roll": null}, "v": 2.019388829984348, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.341748753965873, "steering_wheel_angle": 1.7881571072546676, "front_wheel_angle": 0.08413897028971594, "heading_rate": 0.0665278849500794, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.1490664} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.97231792864781, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.019388829984348, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.7881571072546676, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.1490664} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.55997943878174, "x": 44.043616915300525, "y": 0.0026189383493440133, "z": null, "yaw": 6.273755743763933, "pitch": null, "roll": null}, "v": 2.019388829984348, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.341748753965873, "steering_wheel_angle": 1.7881571072546676, "front_wheel_angle": 0.08413897028971594, "heading_rate": 0.0665278849500794, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.1690664} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.97231792864781, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.012556942728111, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.8709966816536787, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.1690664} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.55997943878174, "x": 44.043616915300525, "y": 0.0026189383493440133, "z": null, "yaw": 6.273755743763933, "pitch": null, "roll": null}, "v": 2.019388829984348, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.341748753965873, "steering_wheel_angle": 1.7881571072546676, "front_wheel_angle": 0.08413897028971594, "heading_rate": 0.0665278849500794, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.1890664} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.97231792864781, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0057373862845873, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.9536374144850583, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.1890664} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.55997943878174, "x": 44.043616915300525, "y": 0.0026189383493440133, "z": null, "yaw": 6.273755743763933, "pitch": null, "roll": null}, "v": 2.019388829984348, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.341748753965873, "steering_wheel_angle": 1.7881571072546676, "front_wheel_angle": 0.08413897028971594, "heading_rate": 0.0665278849500794, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.2090664} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.97231792864781, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9989301198038356, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.036079305748806, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.2090664} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.55997943878174, "x": 44.043616915300525, "y": 0.0026189383493440133, "z": null, "yaw": 6.273755743763933, "pitch": null, "roll": null}, "v": 2.019388829984348, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.341748753965873, "steering_wheel_angle": 1.7881571072546676, "front_wheel_angle": 0.08413897028971594, "heading_rate": 0.0665278849500794, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.2290664} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.97231792864781, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9921351026101022, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.118322355444921, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.2290664} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.55997943878174, "x": 44.043616915300525, "y": 0.0026189383493440133, "z": null, "yaw": 6.273755743763933, "pitch": null, "roll": null}, "v": 2.019388829984348, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.341748753965873, "steering_wheel_angle": 1.7881571072546676, "front_wheel_angle": 0.08413897028971594, "heading_rate": 0.0665278849500794, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.2490664} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.97231792864781, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9853522942008803, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.2003665635734055, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.2490664} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502660.2590663, "x": 48.26386852039332, "y": 5.0009294907662944, "z": null, "yaw": -0.005372271510060315, "pitch": null, "roll": null}, "v": 1.981965455680571, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.33838014345913947, "steering_wheel_angle": 2.2003665635734055, "front_wheel_angle": 0.1041436977205166, "heading_rate": 0.08092136519675153, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.2690663} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.054013307997451715, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.9620177541994455, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9785816542459795, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.2003665635734055, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.2690663} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.669979333877563, "x": 44.26386852039332, "y": 0.0009294907662944496, "z": null, "yaw": 6.277813035669526, "pitch": null, "roll": null}, "v": 1.981965455680571, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.33838014345913947, "steering_wheel_angle": 2.2003665635734055, "front_wheel_angle": 0.1041436977205166, "heading_rate": 0.08092136519675153, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.2890663} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.03706519720565103, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.9620177541994455, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9631848789663071, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.054013307997451715, "steering_wheel_angle": 2.28484764841897, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.2890663} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.669979333877563, "x": 44.26386852039332, "y": 0.0009294907662944496, "z": null, "yaw": 6.277813035669526, "pitch": null, "roll": null}, "v": 1.981965455680571, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.33838014345913947, "steering_wheel_angle": 2.2003665635734055, "front_wheel_angle": 0.1041436977205166, "heading_rate": 0.08092136519675153, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.3090663} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.03706519720565103, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.9620177541994455, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9505260919225984, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.03706519720565103, "steering_wheel_angle": 2.3691168620441854, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.3090663} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.669979333877563, "x": 44.26386852039332, "y": 0.0009294907662944496, "z": null, "yaw": 6.277813035669526, "pitch": null, "roll": null}, "v": 1.981965455680571, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.33838014345913947, "steering_wheel_angle": 2.2003665635734055, "front_wheel_angle": 0.1041436977205166, "heading_rate": 0.08092136519675153, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.3290663} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.03706519720565103, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.9620177541994455, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9378898461716583, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.03706519720565103, "steering_wheel_angle": 2.45317420444905, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.3290663} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.669979333877563, "x": 44.26386852039332, "y": 0.0009294907662944496, "z": null, "yaw": 6.277813035669526, "pitch": null, "roll": null}, "v": 1.981965455680571, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.33838014345913947, "steering_wheel_angle": 2.2003665635734055, "front_wheel_angle": 0.1041436977205166, "heading_rate": 0.08092136519675153, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.3490663} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.03706519720565103, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.9620177541994455, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.925276037733016, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.03706519720565103, "steering_wheel_angle": 2.5370196756335655, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.3490663} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502660.3690662, "x": 48.478466370170636, "y": 5.000230708206152, "z": null, "yaw": -0.0005136227506359298, "pitch": null, "roll": null}, "v": 1.9126845631511535, "accelerator_pedal_position": 0, "brake_pedal_position": 0.03706519720565103, "acceleration": -0.6287394281839331, "steering_wheel_angle": 2.6206532755977308, "front_wheel_angle": 0.1247934588979218, "heading_rate": 0.09372553318049479, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.3690662} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.9551958124865076, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9126845631511535, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.03706519720565103, "steering_wheel_angle": 2.6206532755977308, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.3690662} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.77997922897339, "x": 44.478466370170636, "y": 0.0002307082061516752, "z": null, "yaw": 6.2826716844289505, "pitch": null, "roll": null}, "v": 1.9126845631511535, "accelerator_pedal_position": 0, "brake_pedal_position": 0.03706519720565103, "acceleration": -0.6287394281839331, "steering_wheel_angle": 2.6206532755977308, "front_wheel_angle": 0.1247934588979218, "heading_rate": 0.09372553318049479, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.3890662} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.01626682828020963, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.9551958124865076, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9060431369818533, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.7040561946984236, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.3890662} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.77997922897339, "x": 44.478466370170636, "y": 0.0002307082061516752, "z": null, "yaw": 6.2826716844289505, "pitch": null, "roll": null}, "v": 1.9126845631511535, "accelerator_pedal_position": 0, "brake_pedal_position": 0.03706519720565103, "acceleration": -0.6287394281839331, "steering_wheel_angle": 2.6206532755977308, "front_wheel_angle": 0.1247934588979218, "heading_rate": 0.09372553318049479, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.4090662} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.01626682828020963, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.9551958124865076, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.896811868228515, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.01626682828020963, "steering_wheel_angle": 2.787247338233407, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.4090662} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.77997922897339, "x": 44.478466370170636, "y": 0.0002307082061516752, "z": null, "yaw": 6.2826716844289505, "pitch": null, "roll": null}, "v": 1.9126845631511535, "accelerator_pedal_position": 0, "brake_pedal_position": 0.03706519720565103, "acceleration": -0.6287394281839331, "steering_wheel_angle": 2.6206532755977308, "front_wheel_angle": 0.1247934588979218, "heading_rate": 0.09372553318049479, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.4290662} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.01626682828020963, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.9551958124865076, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.887596836115526, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.01626682828020963, "steering_wheel_angle": 2.8702267062026774, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.4290662} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.77997922897339, "x": 44.478466370170636, "y": 0.0002307082061516752, "z": null, "yaw": 6.2826716844289505, "pitch": null, "roll": null}, "v": 1.9126845631511535, "accelerator_pedal_position": 0, "brake_pedal_position": 0.03706519720565103, "acceleration": -0.6287394281839331, "steering_wheel_angle": 2.6206532755977308, "front_wheel_angle": 0.1247934588979218, "heading_rate": 0.09372553318049479, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.4490662} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.01626682828020963, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.9551958124865076, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8783979781328415, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.01626682828020963, "steering_wheel_angle": 2.952994298606237, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.4490662} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.77997922897339, "x": 44.478466370170636, "y": 0.0002307082061516752, "z": null, "yaw": 6.2826716844289505, "pitch": null, "roll": null}, "v": 1.9126845631511535, "accelerator_pedal_position": 0, "brake_pedal_position": 0.03706519720565103, "acceleration": -0.6287394281839331, "steering_wheel_angle": 2.6206532755977308, "front_wheel_angle": 0.1247934588979218, "heading_rate": 0.09372553318049479, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.4690661} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.01626682828020963, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.9551958124865076, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.869215232059005, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.01626682828020963, "steering_wheel_angle": 3.035550115444086, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.4690661} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502660.4790661, "x": 48.6865710430066, "y": 5.000656727512066, "z": null, "yaw": 0.005327987419951665, "pitch": null, "roll": null}, "v": 1.8646298816221825, "accelerator_pedal_position": 0, "brake_pedal_position": 0.01626682828020963, "acceleration": -0.45813456627716975, "steering_wheel_angle": 3.0767486080258686, "front_wheel_angle": 0.1475030680419279, "heading_rate": 0.10822297970491074, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.4890661} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.958883919613041, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8600485359594108, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.01626682828020963, "steering_wheel_angle": 3.1178941567162233, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.4890661} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.889979124069214, "x": 44.6865710430066, "y": 0.0006567275120659133, "z": null, "yaw": 0.005327987419951665, "pitch": null, "roll": null}, "v": 1.8646298816221825, "accelerator_pedal_position": 0, "brake_pedal_position": 0.01626682828020963, "acceleration": -0.45813456627716975, "steering_wheel_angle": 3.0767486080258686, "front_wheel_angle": 0.1475030680419279, "heading_rate": 0.10822297970491074, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.509066} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.958883919613041, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8534993869448342, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.2000364346930636, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.509066} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.889979124069214, "x": 44.6865710430066, "y": 0.0006567275120659133, "z": null, "yaw": 0.005327987419951665, "pitch": null, "roll": null}, "v": 1.8646298816221825, "accelerator_pedal_position": 0, "brake_pedal_position": 0.01626682828020963, "acceleration": -0.45813456627716975, "steering_wheel_angle": 3.0767486080258686, "front_wheel_angle": 0.1475030680419279, "heading_rate": 0.10822297970491074, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.529066} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.958883919613041, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8469616419389823, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.2000364346930636, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.529066} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.889979124069214, "x": 44.6865710430066, "y": 0.0006567275120659133, "z": null, "yaw": 0.005327987419951665, "pitch": null, "roll": null}, "v": 1.8646298816221825, "accelerator_pedal_position": 0, "brake_pedal_position": 0.01626682828020963, "acceleration": -0.45813456627716975, "steering_wheel_angle": 3.0767486080258686, "front_wheel_angle": 0.1475030680419279, "heading_rate": 0.10822297970491074, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.549066} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.958883919613041, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8404352639946788, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.2000364346930636, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.549066} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.889979124069214, "x": 44.6865710430066, "y": 0.0006567275120659133, "z": null, "yaw": 0.005327987419951665, "pitch": null, "roll": null}, "v": 1.8646298816221825, "accelerator_pedal_position": 0, "brake_pedal_position": 0.01626682828020963, "acceleration": -0.45813456627716975, "steering_wheel_angle": 3.0767486080258686, "front_wheel_angle": 0.1475030680419279, "heading_rate": 0.10822297970491074, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.569066} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.958883919613041, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8339202163181598, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.2000364346930636, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.569066} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502660.589066, "x": 48.88974404350032, "y": 5.002343285409414, "z": null, "yaw": 0.011935142161647386, "pitch": null, "roll": null}, "v": 1.8274164622682683, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.32476533237910415, "steering_wheel_angle": 3.2000364346930636, "front_wheel_angle": 0.15369710180329701, "heading_rate": 0.11058646408835184, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.589066} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22739380475318652, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.955562264630508, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8274164622682683, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.2000364346930636, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.589066} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.99997901916504, "x": 44.88974404350032, "y": 0.0023432854094140865, "z": null, "yaw": 0.011935142161647386, "pitch": null, "roll": null}, "v": 1.8274164622682683, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.32476533237910415, "steering_wheel_angle": 3.2000364346930636, "front_wheel_angle": 0.15369710180329701, "heading_rate": 0.11058646408835184, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.609066} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21874975272958788, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.955562264630508, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.824346709963717, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.2000364346930636, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.609066} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.99997901916504, "x": 44.88974404350032, "y": 0.0023432854094140865, "z": null, "yaw": 0.011935142161647386, "pitch": null, "roll": null}, "v": 1.8274164622682683, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.32476533237910415, "steering_wheel_angle": 3.2000364346930636, "front_wheel_angle": 0.15369710180329701, "heading_rate": 0.11058646408835184, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.629066} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21874975272958788, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.955562264630508, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.820202226724943, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.2000364346930636, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.629066} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.99997901916504, "x": 44.88974404350032, "y": 0.0023432854094140865, "z": null, "yaw": 0.011935142161647386, "pitch": null, "roll": null}, "v": 1.8274164622682683, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.32476533237910415, "steering_wheel_angle": 3.2000364346930636, "front_wheel_angle": 0.15369710180329701, "heading_rate": 0.11058646408835184, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.649066} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21874975272958788, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.955562264630508, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8160649041112573, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.2000364346930636, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.649066} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.99997901916504, "x": 44.88974404350032, "y": 0.0023432854094140865, "z": null, "yaw": 0.011935142161647386, "pitch": null, "roll": null}, "v": 1.8274164622682683, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.32476533237910415, "steering_wheel_angle": 3.2000364346930636, "front_wheel_angle": 0.15369710180329701, "heading_rate": 0.11058646408835184, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.669066} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21874975272958788, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.955562264630508, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8119347229068772, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.2000364346930636, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.669066} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 21.99997901916504, "x": 44.88974404350032, "y": 0.0023432854094140865, "z": null, "yaw": 0.011935142161647386, "pitch": null, "roll": null}, "v": 1.8274164622682683, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.32476533237910415, "steering_wheel_angle": 3.2000364346930636, "front_wheel_angle": 0.15369710180329701, "heading_rate": 0.11058646408835184, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.689066} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21874975272958788, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.955562264630508, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.807811663964637, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.2000364346930636, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.689066} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502660.699066, "x": 49.089700668006536, "y": 5.005333708707709, "z": null, "yaw": 0.018591813643428594, "pitch": null, "roll": null}, "v": 1.8057527993770173, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.32289507169343024, "steering_wheel_angle": 3.2000364346930636, "front_wheel_angle": 0.15369710180329701, "heading_rate": 0.10927548329781446, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.709066} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.04876090534354788, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.516549204557914, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8036957082056821, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.2000364346930636, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.709066} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.109978914260864, "x": 45.089700668006536, "y": 0.005333708707708773, "z": null, "yaw": 0.018591813643428594, "pitch": null, "roll": null}, "v": 1.8057527993770173, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.32289507169343024, "steering_wheel_angle": 3.2000364346930636, "front_wheel_angle": 0.15369710180329701, "heading_rate": 0.10927548329781446, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.729066} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.04876090534354788, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.516549204557914, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7894457343134844, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.04876090534354788, "steering_wheel_angle": 3.286542123980042, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.729066} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.109978914260864, "x": 45.089700668006536, "y": 0.005333708707708773, "z": null, "yaw": 0.018591813643428594, "pitch": null, "roll": null}, "v": 1.8057527993770173, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.32289507169343024, "steering_wheel_angle": 3.2000364346930636, "front_wheel_angle": 0.15369710180329701, "heading_rate": 0.10927548329781446, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.7490659} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.04876090534354788, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.516549204557914, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7752202200270313, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.04876090534354788, "steering_wheel_angle": 3.3728116331624345, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.7490659} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.109978914260864, "x": 45.089700668006536, "y": 0.005333708707708773, "z": null, "yaw": 0.018591813643428594, "pitch": null, "roll": null}, "v": 1.8057527993770173, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.32289507169343024, "steering_wheel_angle": 3.2000364346930636, "front_wheel_angle": 0.15369710180329701, "heading_rate": 0.10927548329781446, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.7690659} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.04876090534354788, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.516549204557914, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7610190424506973, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.04876090534354788, "steering_wheel_angle": 3.4588449622402435, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.7690659} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.109978914260864, "x": 45.089700668006536, "y": 0.005333708707708773, "z": null, "yaw": 0.018591813643428594, "pitch": null, "roll": null}, "v": 1.8057527993770173, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.32289507169343024, "steering_wheel_angle": 3.2000364346930636, "front_wheel_angle": 0.15369710180329701, "heading_rate": 0.10927548329781446, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.7890658} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.04876090534354788, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.516549204557914, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7468420793147177, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.04876090534354788, "steering_wheel_angle": 3.544642111213466, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.7890658} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502660.8090658, "x": 49.284881159392306, "y": 5.009567485870006, "z": null, "yaw": 0.025641794650124266, "pitch": null, "roll": null}, "v": 1.7326892089706283, "accelerator_pedal_position": 0, "brake_pedal_position": 0.04876090534354788, "acceleration": -0.706743822145747, "steering_wheel_angle": 3.630203080082104, "front_wheel_angle": 0.1754993211415088, "heading_rate": 0.12001823298099505, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.8090658} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.01928453816409896, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.553670605946441, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7326892089706283, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.04876090534354788, "steering_wheel_angle": 3.630203080082104, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.8090658} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.21997880935669, "x": 45.284881159392306, "y": 0.00956748587000611, "z": null, "yaw": 0.025641794650124266, "pitch": null, "roll": null}, "v": 1.7326892089706283, "accelerator_pedal_position": 0, "brake_pedal_position": 0.04876090534354788, "acceleration": -0.706743822145747, "steering_wheel_angle": 3.630203080082104, "front_wheel_angle": 0.1754993211415088, "heading_rate": 0.12001823298099505, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.8290658} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.028739600212213598, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.553670605946441, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7232745356837258, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.01928453816409896, "steering_wheel_angle": 3.7156448334301535, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.8290658} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.21997880935669, "x": 45.284881159392306, "y": 0.00956748587000611, "z": null, "yaw": 0.025641794650124266, "pitch": null, "roll": null}, "v": 1.7326892089706283, "accelerator_pedal_position": 0, "brake_pedal_position": 0.04876090534354788, "acceleration": -0.706743822145747, "steering_wheel_angle": 3.630203080082104, "front_wheel_angle": 0.1754993211415088, "heading_rate": 0.12001823298099505, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.8490658} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.028739600212213598, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.553670605946441, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7123635970448676, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.028739600212213598, "steering_wheel_angle": 3.8008497578110014, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.8490658} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.21997880935669, "x": 45.284881159392306, "y": 0.00956748587000611, "z": null, "yaw": 0.025641794650124266, "pitch": null, "roll": null}, "v": 1.7326892089706283, "accelerator_pedal_position": 0, "brake_pedal_position": 0.04876090534354788, "acceleration": -0.706743822145747, "steering_wheel_angle": 3.630203080082104, "front_wheel_angle": 0.1754993211415088, "heading_rate": 0.12001823298099505, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.8690658} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.028739600212213598, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.553670605946441, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7014710468979917, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.028739600212213598, "steering_wheel_angle": 3.885817853224647, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.8690658} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.21997880935669, "x": 45.284881159392306, "y": 0.00956748587000611, "z": null, "yaw": 0.025641794650124266, "pitch": null, "roll": null}, "v": 1.7326892089706283, "accelerator_pedal_position": 0, "brake_pedal_position": 0.04876090534354788, "acceleration": -0.706743822145747, "steering_wheel_angle": 3.630203080082104, "front_wheel_angle": 0.1754993211415088, "heading_rate": 0.12001823298099505, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.8890657} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.028739600212213598, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.553670605946441, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6905968068133521, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.028739600212213598, "steering_wheel_angle": 3.970549119671091, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.8890657} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.21997880935669, "x": 45.284881159392306, "y": 0.00956748587000611, "z": null, "yaw": 0.025641794650124266, "pitch": null, "roll": null}, "v": 1.7326892089706283, "accelerator_pedal_position": 0, "brake_pedal_position": 0.04876090534354788, "acceleration": -0.706743822145747, "steering_wheel_angle": 3.630203080082104, "front_wheel_angle": 0.1754993211415088, "heading_rate": 0.12001823298099505, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.9090657} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.028739600212213598, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.553670605946441, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6797407987324284, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.028739600212213598, "steering_wheel_angle": 4.0550435571503325, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.9090657} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502660.9190657, "x": 49.47254100391904, "y": 5.0150514142279246, "z": null, "yaw": 0.033746324119567524, "pitch": null, "roll": null}, "v": 1.6743196074009925, "accelerator_pedal_position": 0, "brake_pedal_position": 0.028739600212213598, "acceleration": -0.5416662435450326, "steering_wheel_angle": 4.097201965027253, "front_wheel_angle": 0.19951468355290852, "heading_rate": 0.1322482443640357, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.9290657} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.02490302895387092, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.892460241357465, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6689029449655421, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.028739600212213598, "steering_wheel_angle": 4.139301165662373, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.9290657} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.329978704452515, "x": 45.47254100391904, "y": 0.015051414227924553, "z": null, "yaw": 0.033746324119567524, "pitch": null, "roll": null}, "v": 1.6743196074009925, "accelerator_pedal_position": 0, "brake_pedal_position": 0.028739600212213598, "acceleration": -0.5416662435450326, "steering_wheel_angle": 4.097201965027253, "front_wheel_angle": 0.19951468355290852, "heading_rate": 0.1322482443640357, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.9490657} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.026293643444409362, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.892460241357465, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6586967640049377, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.02490302895387092, "steering_wheel_angle": 4.2243939924510965, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.9490657} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.329978704452515, "x": 45.47254100391904, "y": 0.015051414227924553, "z": null, "yaw": 0.033746324119567524, "pitch": null, "roll": null}, "v": 1.6743196074009925, "accelerator_pedal_position": 0, "brake_pedal_position": 0.028739600212213598, "acceleration": -0.5416662435450326, "steering_wheel_angle": 4.097201965027253, "front_wheel_angle": 0.19951468355290852, "heading_rate": 0.1322482443640357, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.9690657} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.026293643444409362, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.892460241357465, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6482851582579465, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.026293643444409362, "steering_wheel_angle": 4.309243899419114, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.9690657} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.329978704452515, "x": 45.47254100391904, "y": 0.015051414227924553, "z": null, "yaw": 0.033746324119567524, "pitch": null, "roll": null}, "v": 1.6743196074009925, "accelerator_pedal_position": 0, "brake_pedal_position": 0.028739600212213598, "acceleration": -0.5416662435450326, "steering_wheel_angle": 4.097201965027253, "front_wheel_angle": 0.19951468355290852, "heading_rate": 0.1322482443640357, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502660.9890656} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.026293643444409362, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.892460241357465, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6378908323038177, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.026293643444409362, "steering_wheel_angle": 4.3938508865664225, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502660.9890656} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.329978704452515, "x": 45.47254100391904, "y": 0.015051414227924553, "z": null, "yaw": 0.033746324119567524, "pitch": null, "roll": null}, "v": 1.6743196074009925, "accelerator_pedal_position": 0, "brake_pedal_position": 0.028739600212213598, "acceleration": -0.5416662435450326, "steering_wheel_angle": 4.097201965027253, "front_wheel_angle": 0.19951468355290852, "heading_rate": 0.1322482443640357, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.0090656} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.026293643444409362, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.892460241357465, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6275137142649216, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.026293643444409362, "steering_wheel_angle": 4.478214953893027, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.0090656} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502661.0290656, "x": 49.65372096552338, "y": 5.021904041544273, "z": null, "yaw": 0.04292973668914304, "pitch": null, "roll": null}, "v": 1.6171537325973075, "accelerator_pedal_position": 0, "brake_pedal_position": 0.026293643444409362, "acceleration": -0.5173586961336742, "steering_wheel_angle": 4.562336101398923, "front_wheel_angle": 0.22380900729963252, "heading_rate": 0.1437891796593677, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.0290656} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.01560539321511805, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.123547496212532, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6171537325973075, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.026293643444409362, "steering_wheel_angle": 4.562336101398923, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.0290656} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.43997859954834, "x": 45.65372096552338, "y": 0.021904041544273056, "z": null, "yaw": 0.04292973668914304, "pitch": null, "roll": null}, "v": 1.6171537325973075, "accelerator_pedal_position": 0, "brake_pedal_position": 0.026293643444409362, "acceleration": -0.5173586961336742, "steering_wheel_angle": 4.562336101398923, "front_wheel_angle": 0.22380900729963252, "heading_rate": 0.1437891796593677, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.0490656} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.01913062580391154, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.123547496212532, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6085202328542176, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.01560539321511805, "steering_wheel_angle": 4.646958776329224, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.0490656} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.43997859954834, "x": 45.65372096552338, "y": 0.021904041544273056, "z": null, "yaw": 0.04292973668914304, "pitch": null, "roll": null}, "v": 1.6171537325973075, "accelerator_pedal_position": 0, "brake_pedal_position": 0.026293643444409362, "acceleration": -0.5173586961336742, "steering_wheel_angle": 4.562336101398923, "front_wheel_angle": 0.22380900729963252, "heading_rate": 0.1437891796593677, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.0690656} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.01913062580391154, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.123547496212532, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.599337117366317, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.01913062580391154, "steering_wheel_angle": 4.7313341939500715, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.0690656} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.43997859954834, "x": 45.65372096552338, "y": 0.021904041544273056, "z": null, "yaw": 0.04292973668914304, "pitch": null, "roll": null}, "v": 1.6171537325973075, "accelerator_pedal_position": 0, "brake_pedal_position": 0.026293643444409362, "acceleration": -0.5173586961336742, "steering_wheel_angle": 4.562336101398923, "front_wheel_angle": 0.22380900729963252, "heading_rate": 0.1437891796593677, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.0890656} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.01913062580391154, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.123547496212532, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5901690620096567, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.01913062580391154, "steering_wheel_angle": 4.8154623542614665, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.0890656} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.43997859954834, "x": 45.65372096552338, "y": 0.021904041544273056, "z": null, "yaw": 0.04292973668914304, "pitch": null, "roll": null}, "v": 1.6171537325973075, "accelerator_pedal_position": 0, "brake_pedal_position": 0.026293643444409362, "acceleration": -0.5173586961336742, "steering_wheel_angle": 4.562336101398923, "front_wheel_angle": 0.22380900729963252, "heading_rate": 0.1437891796593677, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.1090655} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.01913062580391154, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.123547496212532, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5810160084783584, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.01913062580391154, "steering_wheel_angle": 4.899343257263408, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.1090655} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.43997859954834, "x": 45.65372096552338, "y": 0.021904041544273056, "z": null, "yaw": 0.04292973668914304, "pitch": null, "roll": null}, "v": 1.6171537325973075, "accelerator_pedal_position": 0, "brake_pedal_position": 0.026293643444409362, "acceleration": -0.5173586961336742, "steering_wheel_angle": 4.562336101398923, "front_wheel_angle": 0.22380900729963252, "heading_rate": 0.1437891796593677, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.1290655} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.01913062580391154, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.123547496212532, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5718778987270217, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.01913062580391154, "steering_wheel_angle": 4.9829769029558975, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.1290655} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502661.1390655, "x": 49.82893869301794, "y": 5.030230827506924, "z": null, "yaw": 0.05321632636998234, "pitch": null, "roll": null}, "v": 1.5673144297004946, "accelerator_pedal_position": 0, "brake_pedal_position": 0.01913062580391154, "acceleration": -0.45597547313179093, "steering_wheel_angle": 5.024701004311098, "front_wheel_angle": 0.24834741082035416, "heading_rate": 0.15525126446535648, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.1490655} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.085755733928949, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5627546749691767, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.01913062580391154, "steering_wheel_angle": 5.066363291338933, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.1490655} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.549978494644165, "x": 45.82893869301794, "y": 0.030230827506923852, "z": null, "yaw": 0.05321632636998234, "pitch": null, "roll": null}, "v": 1.5673144297004946, "accelerator_pedal_position": 0, "brake_pedal_position": 0.01913062580391154, "acceleration": -0.45597547313179093, "steering_wheel_angle": 5.024701004311098, "front_wheel_angle": 0.24834741082035416, "heading_rate": 0.15525126446535648, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.1690655} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.085755733928949, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.556705937396078, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.149381480496018, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.1690655} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.549978494644165, "x": 45.82893869301794, "y": 0.030230827506923852, "z": null, "yaw": 0.05321632636998234, "pitch": null, "roll": null}, "v": 1.5673144297004946, "accelerator_pedal_position": 0, "brake_pedal_position": 0.01913062580391154, "acceleration": -0.45597547313179093, "steering_wheel_angle": 5.024701004311098, "front_wheel_angle": 0.24834741082035416, "heading_rate": 0.15525126446535648, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.1890655} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.085755733928949, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5506670146783372, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.232153132255578, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.1890655} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.549978494644165, "x": 45.82893869301794, "y": 0.030230827506923852, "z": null, "yaw": 0.05321632636998234, "pitch": null, "roll": null}, "v": 1.5673144297004946, "accelerator_pedal_position": 0, "brake_pedal_position": 0.01913062580391154, "acceleration": -0.45597547313179093, "steering_wheel_angle": 5.024701004311098, "front_wheel_angle": 0.24834741082035416, "heading_rate": 0.15525126446535648, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.2090654} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.085755733928949, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.544637876308557, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.314678246617617, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.2090654} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.549978494644165, "x": 45.82893869301794, "y": 0.030230827506923852, "z": null, "yaw": 0.05321632636998234, "pitch": null, "roll": null}, "v": 1.5673144297004946, "accelerator_pedal_position": 0, "brake_pedal_position": 0.01913062580391154, "acceleration": -0.45597547313179093, "steering_wheel_angle": 5.024701004311098, "front_wheel_angle": 0.24834741082035416, "heading_rate": 0.15525126446535648, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.2290654} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.085755733928949, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5386184918996713, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.3969568235821335, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.2290654} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502661.2490654, "x": 49.99923811296317, "y": 5.040168485396333, "z": null, "yaw": 0.06461462367847921, "pitch": null, "roll": null}, "v": 1.5326088311843409, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3001193398534594, "steering_wheel_angle": 5.3969568235821335, "front_wheel_angle": 0.26839828720879905, "heading_rate": 0.16465637000952535, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.2490654} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22814554525844294, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.045121920026441, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5326088311843409, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.3969568235821335, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.2490654} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.65997838973999, "x": 45.99923811296317, "y": 0.04016848539633333, "z": null, "yaw": 0.06461462367847921, "pitch": null, "roll": null}, "v": 1.5326088311843409, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3001193398534594, "steering_wheel_angle": 5.3969568235821335, "front_wheel_angle": 0.26839828720879905, "heading_rate": 0.16465637000952535, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.2690654} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21893032557707792, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.045121920026441, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5301256391684177, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.3969568235821335, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.2690654} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.65997838973999, "x": 45.99923811296317, "y": 0.04016848539633333, "z": null, "yaw": 0.06461462367847921, "pitch": null, "roll": null}, "v": 1.5326088311843409, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3001193398534594, "steering_wheel_angle": 5.3969568235821335, "front_wheel_angle": 0.26839828720879905, "heading_rate": 0.16465637000952535, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.2890654} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21893032557707792, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.045121920026441, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.526495010780897, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.3969568235821335, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.2890654} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.65997838973999, "x": 45.99923811296317, "y": 0.04016848539633333, "z": null, "yaw": 0.06461462367847921, "pitch": null, "roll": null}, "v": 1.5326088311843409, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3001193398534594, "steering_wheel_angle": 5.3969568235821335, "front_wheel_angle": 0.26839828720879905, "heading_rate": 0.16465637000952535, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.3090653} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21893032557707792, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.045121920026441, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5228702288393405, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.3969568235821335, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.3090653} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.65997838973999, "x": 45.99923811296317, "y": 0.04016848539633333, "z": null, "yaw": 0.06461462367847921, "pitch": null, "roll": null}, "v": 1.5326088311843409, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3001193398534594, "steering_wheel_angle": 5.3969568235821335, "front_wheel_angle": 0.26839828720879905, "heading_rate": 0.16465637000952535, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.3290653} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21893032557707792, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.045121920026441, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5192512786756387, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.3969568235821335, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.3290653} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.65997838973999, "x": 45.99923811296317, "y": 0.04016848539633333, "z": null, "yaw": 0.06461462367847921, "pitch": null, "roll": null}, "v": 1.5326088311843409, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3001193398534594, "steering_wheel_angle": 5.3969568235821335, "front_wheel_angle": 0.26839828720879905, "heading_rate": 0.16465637000952535, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.3490653} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21893032557707792, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.045121920026441, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5156381456706434, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.3969568235821335, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.3490653} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502661.3590653, "x": 50.16652527096918, "y": 5.051893402585271, "z": null, "yaw": 0.07643251245251903, "pitch": null, "roll": null}, "v": 1.5138337560475141, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29860861421186496, "steering_wheel_angle": 5.3969568235821335, "front_wheel_angle": 0.26839828720879905, "heading_rate": 0.16263926319415026, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.3690653} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24086274095880852, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.032649595710259, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5120308152539628, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.3969568235821335, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.3690653} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.769978284835815, "x": 46.16652527096918, "y": 0.05189340258527064, "z": null, "yaw": 0.07643251245251903, "pitch": null, "roll": null}, "v": 1.5138337560475141, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29860861421186496, "steering_wheel_angle": 5.3969568235821335, "front_wheel_angle": 0.26839828720879905, "heading_rate": 0.16263926319415026, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.3890653} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23393332032665579, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.032649595710259, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5111697252133829, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.3969568235821335, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.3890653} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.769978284835815, "x": 46.16652527096918, "y": 0.05189340258527064, "z": null, "yaw": 0.07643251245251903, "pitch": null, "roll": null}, "v": 1.5138337560475141, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29860861421186496, "steering_wheel_angle": 5.3969568235821335, "front_wheel_angle": 0.26839828720879905, "heading_rate": 0.16263926319415026, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.4090652} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23393332032665579, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.032649595710259, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5094441860875663, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.3969568235821335, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.4090652} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.769978284835815, "x": 46.16652527096918, "y": 0.05189340258527064, "z": null, "yaw": 0.07643251245251903, "pitch": null, "roll": null}, "v": 1.5138337560475141, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29860861421186496, "steering_wheel_angle": 5.3969568235821335, "front_wheel_angle": 0.26839828720879905, "heading_rate": 0.16263926319415026, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.4290652} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23393332032665579, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.032649595710259, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5077214135309391, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.3969568235821335, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.4290652} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.769978284835815, "x": 46.16652527096918, "y": 0.05189340258527064, "z": null, "yaw": 0.07643251245251903, "pitch": null, "roll": null}, "v": 1.5138337560475141, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29860861421186496, "steering_wheel_angle": 5.3969568235821335, "front_wheel_angle": 0.26839828720879905, "heading_rate": 0.16263926319415026, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.4490652} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23393332032665579, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.032649595710259, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5060014019211385, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.3969568235821335, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.4490652} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502661.4690652, "x": 50.33199612346015, "y": 5.065458927522394, "z": null, "yaw": 0.08825040122655885, "pitch": null, "roll": null}, "v": 1.504284145650518, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.297842915191081, "steering_wheel_angle": 5.3969568235821335, "front_wheel_angle": 0.26839828720879905, "heading_rate": 0.16161329743499467, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.4690652} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25133081164422855, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.049107507884381, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.504284145650518, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.3969568235821335, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.4690652} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.87997817993164, "x": 46.33199612346015, "y": 0.06545892752239357, "z": null, "yaw": 0.08825040122655885, "pitch": null, "roll": null}, "v": 1.504284145650518, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.297842915191081, "steering_wheel_angle": 5.3969568235821335, "front_wheel_angle": 0.26839828720879905, "heading_rate": 0.16161329743499467, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.4890652} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2458558070667551, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.049107507884381, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5047434548028322, "gear": 1, "accelerator_pedal_position": 0.25133081164422855, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.3969568235821335, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.4890652} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.87997817993164, "x": 46.33199612346015, "y": 0.06545892752239357, "z": null, "yaw": 0.08825040122655885, "pitch": null, "roll": null}, "v": 1.504284145650518, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.297842915191081, "steering_wheel_angle": 5.3969568235821335, "front_wheel_angle": 0.26839828720879905, "heading_rate": 0.16161329743499467, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.5090652} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2458558070667551, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.049107507884381, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5045179270114255, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.3969568235821335, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.5090652} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.87997817993164, "x": 46.33199612346015, "y": 0.06545892752239357, "z": null, "yaw": 0.08825040122655885, "pitch": null, "roll": null}, "v": 1.504284145650518, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.297842915191081, "steering_wheel_angle": 5.3969568235821335, "front_wheel_angle": 0.26839828720879905, "heading_rate": 0.16161329743499467, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.5290651} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2458558070667551, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.049107507884381, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5042927603324725, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.3969568235821335, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.5290651} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.87997817993164, "x": 46.33199612346015, "y": 0.06545892752239357, "z": null, "yaw": 0.08825040122655885, "pitch": null, "roll": null}, "v": 1.504284145650518, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.297842915191081, "steering_wheel_angle": 5.3969568235821335, "front_wheel_angle": 0.26839828720879905, "heading_rate": 0.16161329743499467, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.549065} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2458558070667551, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.049107507884381, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5040679541674924, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.3969568235821335, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.549065} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.87997817993164, "x": 46.33199612346015, "y": 0.06545892752239357, "z": null, "yaw": 0.08825040122655885, "pitch": null, "roll": null}, "v": 1.504284145650518, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.297842915191081, "steering_wheel_angle": 5.3969568235821335, "front_wheel_angle": 0.26839828720879905, "heading_rate": 0.16161329743499467, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.569065} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2458558070667551, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.049107507884381, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5038435079190597, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.3969568235821335, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.569065} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502661.579065, "x": 50.49674486524493, "y": 5.080928203469078, "z": null, "yaw": 0.10006829000059866, "pitch": null, "roll": null}, "v": 1.5037314195771414, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2977986528010919, "steering_wheel_angle": 5.3969568235821335, "front_wheel_angle": 0.26839828720879905, "heading_rate": 0.16155391511447034, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.589065} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2199474519699499, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.624804258878803, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5036194209908027, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.3969568235821335, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.589065} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.989978075027466, "x": 46.49674486524493, "y": 0.08092820346907814, "z": null, "yaw": 0.10006829000059866, "pitch": null, "roll": null}, "v": 1.5037314195771414, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2977986528010919, "steering_wheel_angle": 5.3969568235821335, "front_wheel_angle": 0.26839828720879905, "heading_rate": 0.16155391511447034, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.609065} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22804160512514243, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.624804258878803, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5001584446917744, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.480744517515055, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.609065} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.989978075027466, "x": 46.49674486524493, "y": 0.08092820346907814, "z": null, "yaw": 0.10006829000059866, "pitch": null, "roll": null}, "v": 1.5037314195771414, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2977986528010919, "steering_wheel_angle": 5.3969568235821335, "front_wheel_angle": 0.26839828720879905, "heading_rate": 0.16155391511447034, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.629065} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22804160512514243, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.624804258878803, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4977143697263233, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.564274991739866, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.629065} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.989978075027466, "x": 46.49674486524493, "y": 0.08092820346907814, "z": null, "yaw": 0.10006829000059866, "pitch": null, "roll": null}, "v": 1.5037314195771414, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2977986528010919, "steering_wheel_angle": 5.3969568235821335, "front_wheel_angle": 0.26839828720879905, "heading_rate": 0.16155391511447034, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.649065} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22804160512514243, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.624804258878803, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4952742020810066, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.64754824625657, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.649065} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 22.989978075027466, "x": 46.49674486524493, "y": 0.08092820346907814, "z": null, "yaw": 0.10006829000059866, "pitch": null, "roll": null}, "v": 1.5037314195771414, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2977986528010919, "steering_wheel_angle": 5.3969568235821335, "front_wheel_angle": 0.26839828720879905, "heading_rate": 0.16155391511447034, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.669065} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22804160512514243, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.624804258878803, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.492837933128411, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.730564281065164, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.669065} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502661.689065, "x": 50.66059047426573, "y": 5.09828417760623, "z": null, "yaw": 0.11231812695984851, "pitch": null, "roll": null}, "v": 1.490405554266321, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2967333648751951, "steering_wheel_angle": 5.813323096165648, "front_wheel_angle": 0.291150894434217, "heading_rate": 0.17446279858586525, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.689065} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21875470816287204, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.038505213274327, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.490405554266321, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.813323096165648, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.689065} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.09997797012329, "x": 46.66059047426573, "y": 0.09828417760622976, "z": null, "yaw": 0.11231812695984851, "pitch": null, "roll": null}, "v": 1.490405554266321, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2967333648751951, "steering_wheel_angle": 5.813323096165648, "front_wheel_angle": 0.291150894434217, "heading_rate": 0.17446279858586525, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.709065} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22160360093516634, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.038505213274327, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4868166578537039, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.8972293943338165, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.709065} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.09997797012329, "x": 46.66059047426573, "y": 0.09828417760622976, "z": null, "yaw": 0.11231812695984851, "pitch": null, "roll": null}, "v": 1.490405554266321, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2967333648751951, "steering_wheel_angle": 5.813323096165648, "front_wheel_angle": 0.291150894434217, "heading_rate": 0.17446279858586525, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.729065} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22160360093516634, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.038505213274327, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4835894534376406, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.980869625044013, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.729065} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.09997797012329, "x": 46.66059047426573, "y": 0.09828417760622976, "z": null, "yaw": 0.11231812695984851, "pitch": null, "roll": null}, "v": 1.490405554266321, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2967333648751951, "steering_wheel_angle": 5.813323096165648, "front_wheel_angle": 0.291150894434217, "heading_rate": 0.17446279858586525, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.749065} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22160360093516634, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.038505213274327, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4803673903571388, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.064243788296234, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.749065} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.09997797012329, "x": 46.66059047426573, "y": 0.09828417760622976, "z": null, "yaw": 0.11231812695984851, "pitch": null, "roll": null}, "v": 1.490405554266321, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2967333648751951, "steering_wheel_angle": 5.813323096165648, "front_wheel_angle": 0.291150894434217, "heading_rate": 0.17446279858586525, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.769065} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22160360093516634, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.038505213274327, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.477150456270391, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.147351884090481, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.769065} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.09997797012329, "x": 46.66059047426573, "y": 0.09828417760622976, "z": null, "yaw": 0.11231812695984851, "pitch": null, "roll": null}, "v": 1.490405554266321, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2967333648751951, "steering_wheel_angle": 5.813323096165648, "front_wheel_angle": 0.291150894434217, "heading_rate": 0.17446279858586525, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.789065} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22160360093516634, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.038505213274327, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4739386388750628, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.230193912426757, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.789065} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502661.7990649, "x": 50.82247335614242, "y": 5.11752572921933, "z": null, "yaw": 0.1257389312373576, "pitch": null, "roll": null}, "v": 1.4723346451029562, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2952944253268523, "steering_wheel_angle": 6.2715151512981535, "front_wheel_angle": 0.31660557284006163, "heading_rate": 0.18842802143751153, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.8090649} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.06301149252982435, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.628730411005295, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4707319259081355, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.312769873305057, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.8090649} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.209977865219116, "x": 46.82247335614242, "y": 0.11752572921932991, "z": null, "yaw": 0.1257389312373576, "pitch": null, "roll": null}, "v": 1.4723346451029562, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2952944253268523, "steering_wheel_angle": 6.2715151512981535, "front_wheel_angle": 0.31660557284006163, "heading_rate": 0.18842802143751153, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.8290648} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.038102276724044724, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.628730411005295, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4547530855966653, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.06301149252982435, "steering_wheel_angle": 6.40111770847626, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.8290648} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.209977865219116, "x": 46.82247335614242, "y": 0.11752572921932991, "z": null, "yaw": 0.1257389312373576, "pitch": null, "roll": null}, "v": 1.4723346451029562, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2952944253268523, "steering_wheel_angle": 6.2715151512981535, "front_wheel_angle": 0.31660557284006163, "heading_rate": 0.18842802143751153, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.8490648} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.038102276724044724, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.628730411005295, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4427834389136664, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.038102276724044724, "steering_wheel_angle": 6.489158936218649, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.8490648} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.209977865219116, "x": 46.82247335614242, "y": 0.11752572921932991, "z": null, "yaw": 0.1257389312373576, "pitch": null, "roll": null}, "v": 1.4723346451029562, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2952944253268523, "steering_wheel_angle": 6.2715151512981535, "front_wheel_angle": 0.31660557284006163, "heading_rate": 0.18842802143751153, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.8690648} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.038102276724044724, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.628730411005295, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4308326765991595, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.038102276724044724, "steering_wheel_angle": 6.576893556532226, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.8690648} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.209977865219116, "x": 46.82247335614242, "y": 0.11752572921932991, "z": null, "yaw": 0.1257389312373576, "pitch": null, "roll": null}, "v": 1.4723346451029562, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2952944253268523, "steering_wheel_angle": 6.2715151512981535, "front_wheel_angle": 0.31660557284006163, "heading_rate": 0.18842802143751153, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.8890648} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.038102276724044724, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.628730411005295, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4189007117536525, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.038102276724044724, "steering_wheel_angle": 6.664321569416991, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.8890648} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502661.9090648, "x": 50.979850334782334, "y": 5.138459434422154, "z": null, "yaw": 0.14040364357366894, "pitch": null, "roll": null}, "v": 1.4069874578840114, "accelerator_pedal_position": 0, "brake_pedal_position": 0.038102276724044724, "acceleration": -0.5949637237529875, "steering_wheel_angle": 6.751442974872943, "front_wheel_angle": 0.34376070949892945, "heading_rate": 0.19674401403768907, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.9090648} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.01494396540518829, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.68495930535984, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4069874578840114, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.038102276724044724, "steering_wheel_angle": 6.751442974872943, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.9090648} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.31997776031494, "x": 46.979850334782334, "y": 0.13845943442215436, "z": null, "yaw": 0.14040364357366894, "pitch": null, "roll": null}, "v": 1.4069874578840114, "accelerator_pedal_position": 0, "brake_pedal_position": 0.038102276724044724, "acceleration": -0.5949637237529875, "steering_wheel_angle": 6.751442974872943, "front_wheel_angle": 0.34376070949892945, "heading_rate": 0.19674401403768907, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.9290648} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.022382072075626758, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.68495930535984, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3987967129053536, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.01494396540518829, "steering_wheel_angle": 6.838492166597783, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.9290648} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.31997776031494, "x": 46.979850334782334, "y": 0.13845943442215436, "z": null, "yaw": 0.14040364357366894, "pitch": null, "roll": null}, "v": 1.4069874578840114, "accelerator_pedal_position": 0, "brake_pedal_position": 0.038102276724044724, "acceleration": -0.5949637237529875, "steering_wheel_angle": 6.751442974872943, "front_wheel_angle": 0.34376070949892945, "heading_rate": 0.19674401403768907, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.9490647} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.022382072075626758, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.68495930535984, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3894291096777303, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.022382072075626758, "steering_wheel_angle": 6.925233090078158, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.9490647} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.31997776031494, "x": 46.979850334782334, "y": 0.13845943442215436, "z": null, "yaw": 0.14040364357366894, "pitch": null, "roll": null}, "v": 1.4069874578840114, "accelerator_pedal_position": 0, "brake_pedal_position": 0.038102276724044724, "acceleration": -0.5949637237529875, "steering_wheel_angle": 6.751442974872943, "front_wheel_angle": 0.34376070949892945, "heading_rate": 0.19674401403768907, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.9690647} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.022382072075626758, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.68495930535984, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3800760834049672, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.022382072075626758, "steering_wheel_angle": 7.011665745314071, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.9690647} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.31997776031494, "x": 46.979850334782334, "y": 0.13845943442215436, "z": null, "yaw": 0.14040364357366894, "pitch": null, "roll": null}, "v": 1.4069874578840114, "accelerator_pedal_position": 0, "brake_pedal_position": 0.038102276724044724, "acceleration": -0.5949637237529875, "steering_wheel_angle": 6.751442974872943, "front_wheel_angle": 0.34376070949892945, "heading_rate": 0.19674401403768907, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502661.9890647} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.022382072075626758, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.68495930535984, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3707375764257486, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.022382072075626758, "steering_wheel_angle": 7.09779013230552, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502661.9890647} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.31997776031494, "x": 46.979850334782334, "y": 0.13845943442215436, "z": null, "yaw": 0.14040364357366894, "pitch": null, "roll": null}, "v": 1.4069874578840114, "accelerator_pedal_position": 0, "brake_pedal_position": 0.038102276724044724, "acceleration": -0.5949637237529875, "steering_wheel_angle": 6.751442974872943, "front_wheel_angle": 0.34376070949892945, "heading_rate": 0.19674401403768907, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.0090647} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.022382072075626758, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.68495930535984, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3614135313312645, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.022382072075626758, "steering_wheel_angle": 7.183606251052504, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.0090647} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502662.0190647, "x": 51.1305013800405, "y": 5.1608449667153655, "z": null, "yaw": 0.1563929095303462, "pitch": null, "roll": null}, "v": 1.3567569141192195, "accelerator_pedal_position": 0, "brake_pedal_position": 0.022382072075626758, "acceleration": -0.46530231555107815, "steering_wheel_angle": 7.226398709834323, "front_wheel_angle": 0.3711597988694116, "heading_rate": 0.20626841042836974, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.0290647} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.575886189797833, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3521038909637086, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.022382072075626758, "steering_wheel_angle": 7.269114101555026, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.0290647} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.429977655410767, "x": 47.1305013800405, "y": 0.16084496671536552, "z": null, "yaw": 0.1563929095303462, "pitch": null, "roll": null}, "v": 1.3567569141192195, "accelerator_pedal_position": 0, "brake_pedal_position": 0.022382072075626758, "acceleration": -0.46530231555107815, "steering_wheel_angle": 7.226398709834323, "front_wheel_angle": 0.3711597988694116, "heading_rate": 0.20626841042836974, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.0490646} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.575886189797833, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.346388351802227, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.353870365175435, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.0490646} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.429977655410767, "x": 47.1305013800405, "y": 0.16084496671536552, "z": null, "yaw": 0.1563929095303462, "pitch": null, "roll": null}, "v": 1.3567569141192195, "accelerator_pedal_position": 0, "brake_pedal_position": 0.022382072075626758, "acceleration": -0.46530231555107815, "steering_wheel_angle": 7.226398709834323, "front_wheel_angle": 0.3711597988694116, "heading_rate": 0.20626841042836974, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.0690646} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.575886189797833, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3406816061971407, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.4383215659806785, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.0690646} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.429977655410767, "x": 47.1305013800405, "y": 0.16084496671536552, "z": null, "yaw": 0.1563929095303462, "pitch": null, "roll": null}, "v": 1.3567569141192195, "accelerator_pedal_position": 0, "brake_pedal_position": 0.022382072075626758, "acceleration": -0.46530231555107815, "steering_wheel_angle": 7.226398709834323, "front_wheel_angle": 0.3711597988694116, "heading_rate": 0.20626841042836974, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.0890646} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.575886189797833, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3349836275974774, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.5224677039707535, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.0890646} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.429977655410767, "x": 47.1305013800405, "y": 0.16084496671536552, "z": null, "yaw": 0.1563929095303462, "pitch": null, "roll": null}, "v": 1.3567569141192195, "accelerator_pedal_position": 0, "brake_pedal_position": 0.022382072075626758, "acceleration": -0.46530231555107815, "steering_wheel_angle": 7.226398709834323, "front_wheel_angle": 0.3711597988694116, "heading_rate": 0.20626841042836974, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.1090646} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.575886189797833, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3292943895530904, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.606308779145661, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.1090646} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502662.1290646, "x": 51.27601153586769, "y": 5.1849440898256045, "z": null, "yaw": 0.17373407954622683, "pitch": null, "roll": null}, "v": 1.323613865714171, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2837002299408167, "steering_wheel_angle": 7.689844791505401, "front_wheel_angle": 0.3984290495104766, "heading_rate": 0.2176428009916121, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.1290646} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22704866439674892, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.456038917783701, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.323613865714171, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.689844791505401, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.1290646} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.539977550506592, "x": 47.27601153586769, "y": 0.1849440898256045, "z": null, "yaw": 0.17373407954622683, "pitch": null, "roll": null}, "v": 1.323613865714171, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2837002299408167, "steering_wheel_angle": 7.689844791505401, "front_wheel_angle": 0.3984290495104766, "heading_rate": 0.2176428009916121, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.1490645} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21732499096955613, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.456038917783701, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3213218207581738, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.772605166468362, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.1490645} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.539977550506592, "x": 47.27601153586769, "y": 0.1849440898256045, "z": null, "yaw": 0.17373407954622683, "pitch": null, "roll": null}, "v": 1.323613865714171, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2837002299408167, "steering_wheel_angle": 7.689844791505401, "front_wheel_angle": 0.3984290495104766, "heading_rate": 0.2176428009916121, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.1690645} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21732499096955613, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.456038917783701, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3178182835567018, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.81387224766803, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.1690645} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.539977550506592, "x": 47.27601153586769, "y": 0.1849440898256045, "z": null, "yaw": 0.17373407954622683, "pitch": null, "roll": null}, "v": 1.323613865714171, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2837002299408167, "steering_wheel_angle": 7.689844791505401, "front_wheel_angle": 0.3984290495104766, "heading_rate": 0.2176428009916121, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.1890645} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21732499096955613, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.456038917783701, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3143200958869268, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.81387224766803, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.1890645} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.539977550506592, "x": 47.27601153586769, "y": 0.1849440898256045, "z": null, "yaw": 0.17373407954622683, "pitch": null, "roll": null}, "v": 1.323613865714171, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2837002299408167, "steering_wheel_angle": 7.689844791505401, "front_wheel_angle": 0.3984290495104766, "heading_rate": 0.2176428009916121, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.2090645} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21732499096955613, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.456038917783701, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3108272446876168, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.81387224766803, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.2090645} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.539977550506592, "x": 47.27601153586769, "y": 0.1849440898256045, "z": null, "yaw": 0.17373407954622683, "pitch": null, "roll": null}, "v": 1.323613865714171, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2837002299408167, "steering_wheel_angle": 7.689844791505401, "front_wheel_angle": 0.3984290495104766, "heading_rate": 0.2176428009916121, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.2290645} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21732499096955613, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.456038917783701, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3073397169398633, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.81387224766803, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.2290645} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502662.2390645, "x": 51.41836759433695, "y": 5.211149709389604, "z": null, "yaw": 0.19212827218315282, "pitch": null, "roll": null}, "v": 1.3055979453034419, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2823257572129778, "steering_wheel_angle": 7.81387224766803, "front_wheel_angle": 0.4058204721018434, "heading_rate": 0.21913193008224344, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.2490644} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.102309843733334, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3038574996669094, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.81387224766803, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.2490644} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.649977445602417, "x": 47.41836759433695, "y": 0.21114970938960376, "z": null, "yaw": 0.19212827218315282, "pitch": null, "roll": null}, "v": 1.3055979453034419, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2823257572129778, "steering_wheel_angle": 7.81387224766803, "front_wheel_angle": 0.4058204721018434, "heading_rate": 0.21913193008224344, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.2690644} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.102309843733334, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2982157793413682, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.898802772515228, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.2690644} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.649977445602417, "x": 47.41836759433695, "y": 0.21114970938960376, "z": null, "yaw": 0.19212827218315282, "pitch": null, "roll": null}, "v": 1.3055979453034419, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2823257572129778, "steering_wheel_angle": 7.81387224766803, "front_wheel_angle": 0.4058204721018434, "heading_rate": 0.21913193008224344, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.2890644} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.102309843733334, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.292582630330385, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.983412116017765, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.2890644} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.649977445602417, "x": 47.41836759433695, "y": 0.21114970938960376, "z": null, "yaw": 0.19212827218315282, "pitch": null, "roll": null}, "v": 1.3055979453034419, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2823257572129778, "steering_wheel_angle": 7.81387224766803, "front_wheel_angle": 0.4058204721018434, "heading_rate": 0.21913193008224344, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.3090644} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.102309843733334, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2869580269236542, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.067700278175643, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.3090644} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.649977445602417, "x": 47.41836759433695, "y": 0.21114970938960376, "z": null, "yaw": 0.19212827218315282, "pitch": null, "roll": null}, "v": 1.3055979453034419, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2823257572129778, "steering_wheel_angle": 7.81387224766803, "front_wheel_angle": 0.4058204721018434, "heading_rate": 0.21913193008224344, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.3290644} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.102309843733334, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2813419435076396, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.151667258988859, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.3290644} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502662.3490644, "x": 51.55768861257462, "y": 5.2394803239679, "z": null, "yaw": 0.21112387268005653, "pitch": null, "roll": null}, "v": 1.275734354565109, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.280061699162432, "steering_wheel_angle": 8.235313058457418, "front_wheel_angle": 0.4312450765634152, "heading_rate": 0.2292977235553572, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.3490644} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22450102191759114, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.97704137683517, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.275734354565109, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.235313058457418, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.3490644} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.759977340698242, "x": 47.55768861257462, "y": 0.23948032396789998, "z": null, "yaw": 0.21112387268005653, "pitch": null, "roll": null}, "v": 1.275734354565109, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.280061699162432, "steering_wheel_angle": 8.235313058457418, "front_wheel_angle": 0.4312450765634152, "heading_rate": 0.2292977235553572, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.3690643} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.97704137683517, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2731967066707268, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.318119734307803, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.3690643} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.759977340698242, "x": 47.55768861257462, "y": 0.23948032396789998, "z": null, "yaw": 0.21112387268005653, "pitch": null, "roll": null}, "v": 1.275734354565109, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.280061699162432, "steering_wheel_angle": 8.235313058457418, "front_wheel_angle": 0.4312450765634152, "heading_rate": 0.2292977235553572, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.3890643} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.97704137683517, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2676014152201425, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.359404124767671, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.3890643} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.759977340698242, "x": 47.55768861257462, "y": 0.23948032396789998, "z": null, "yaw": 0.21112387268005653, "pitch": null, "roll": null}, "v": 1.275734354565109, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.280061699162432, "steering_wheel_angle": 8.235313058457418, "front_wheel_angle": 0.4312450765634152, "heading_rate": 0.2292977235553572, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.4090643} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.97704137683517, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2620145560533353, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.359404124767671, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.4090643} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.759977340698242, "x": 47.55768861257462, "y": 0.23948032396789998, "z": null, "yaw": 0.21112387268005653, "pitch": null, "roll": null}, "v": 1.275734354565109, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.280061699162432, "steering_wheel_angle": 8.235313058457418, "front_wheel_angle": 0.4312450765634152, "heading_rate": 0.2292977235553572, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.4290643} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.97704137683517, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2564361039820782, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.359404124767671, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.4290643} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.759977340698242, "x": 47.55768861257462, "y": 0.23948032396789998, "z": null, "yaw": 0.21112387268005653, "pitch": null, "roll": null}, "v": 1.275734354565109, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.280061699162432, "steering_wheel_angle": 8.235313058457418, "front_wheel_angle": 0.4312450765634152, "heading_rate": 0.2292977235553572, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.4490643} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.97704137683517, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2508660339124102, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.359404124767671, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.4490643} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502662.4590642, "x": 51.6934121698956, "y": 5.269858118877879, "z": null, "yaw": 0.23121901277838186, "pitch": null, "roll": null}, "v": 1.2480841343119744, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2779813467788114, "steering_wheel_angle": 8.359404124767671, "front_wheel_angle": 0.4388249554438734, "heading_rate": 0.22882152472932987, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.4690642} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.516628728760285, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2453043208441863, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.359404124767671, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.4690642} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.869977235794067, "x": 47.6934121698956, "y": 0.26985811887787925, "z": null, "yaw": 0.23121901277838186, "pitch": null, "roll": null}, "v": 1.2480841343119744, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2779813467788114, "steering_wheel_angle": 8.359404124767671, "front_wheel_angle": 0.4388249554438734, "heading_rate": 0.22882152472932987, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.4890642} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.516628728760285, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2397509398706288, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.444024674646164, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.4890642} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.869977235794067, "x": 47.6934121698956, "y": 0.26985811887787925, "z": null, "yaw": 0.23121901277838186, "pitch": null, "roll": null}, "v": 1.2480841343119744, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2779813467788114, "steering_wheel_angle": 8.359404124767671, "front_wheel_angle": 0.4388249554438734, "heading_rate": 0.22882152472932987, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.5090642} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.516628728760285, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2342058661778823, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.528310107371242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.5090642} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.869977235794067, "x": 47.6934121698956, "y": 0.26985811887787925, "z": null, "yaw": 0.23121901277838186, "pitch": null, "roll": null}, "v": 1.2480841343119744, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2779813467788114, "steering_wheel_angle": 8.359404124767671, "front_wheel_angle": 0.4388249554438734, "heading_rate": 0.22882152472932987, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.5290642} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.516628728760285, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2286690750445703, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.612260422942905, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.5290642} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.869977235794067, "x": 47.6934121698956, "y": 0.26985811887787925, "z": null, "yaw": 0.23121901277838186, "pitch": null, "roll": null}, "v": 1.2480841343119744, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2779813467788114, "steering_wheel_angle": 8.359404124767671, "front_wheel_angle": 0.4388249554438734, "heading_rate": 0.22882152472932987, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.5490642} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.516628728760285, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2231405418413552, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.69587562136115, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.5490642} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502662.5690641, "x": 51.825266873290325, "y": 5.302192196517178, "z": null, "yaw": 0.2519476846163402, "pitch": null, "roll": null}, "v": 1.2176202420305, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27570700263954917, "steering_wheel_angle": 8.77915570262598, "front_wheel_angle": 0.46479528007446297, "heading_rate": 0.23849918325728464, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.5690641} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.67666518507491, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2176202420305, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.77915570262598, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.5690641} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.979977130889893, "x": 47.825266873290325, "y": 0.3021921965171783, "z": null, "yaw": 0.2519476846163402, "pitch": null, "roll": null}, "v": 1.2176202420305, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27570700263954917, "steering_wheel_angle": 8.77915570262598, "front_wheel_angle": 0.46479528007446297, "heading_rate": 0.23849918325728464, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.5890641} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.67666518507491, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2121081511654332, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.862803159432758, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.5890641} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.979977130889893, "x": 47.825266873290325, "y": 0.3021921965171783, "z": null, "yaw": 0.2519476846163402, "pitch": null, "roll": null}, "v": 1.2176202420305, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27570700263954917, "steering_wheel_angle": 8.77915570262598, "front_wheel_angle": 0.46479528007446297, "heading_rate": 0.23849918325728464, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.609064} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.67666518507491, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2066042448903158, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.94610978689045, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.609064} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.979977130889893, "x": 47.825266873290325, "y": 0.3021921965171783, "z": null, "yaw": 0.2519476846163402, "pitch": null, "roll": null}, "v": 1.2176202420305, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27570700263954917, "steering_wheel_angle": 8.77915570262598, "front_wheel_angle": 0.46479528007446297, "heading_rate": 0.23849918325728464, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.629064} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.67666518507491, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2011084989396101, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.02907558499905, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.629064} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.979977130889893, "x": 47.825266873290325, "y": 0.3021921965171783, "z": null, "yaw": 0.2519476846163402, "pitch": null, "roll": null}, "v": 1.2176202420305, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27570700263954917, "steering_wheel_angle": 8.77915570262598, "front_wheel_angle": 0.46479528007446297, "heading_rate": 0.23849918325728464, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.649064} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.67666518507491, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1956208891376527, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.070430673047444, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.649064} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 23.979977130889893, "x": 47.825266873290325, "y": 0.3021921965171783, "z": null, "yaw": 0.2519476846163402, "pitch": null, "roll": null}, "v": 1.2176202420305, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27570700263954917, "steering_wheel_angle": 8.77915570262598, "front_wheel_angle": 0.46479528007446297, "heading_rate": 0.23849918325728464, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.669064} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.67666518507491, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1901413913982277, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.070430673047444, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.669064} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502662.679064, "x": 51.95317430929381, "y": 5.336476482153712, "z": null, "yaw": 0.27412601182778307, "pitch": null, "roll": null}, "v": 1.1874046770493767, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27346953252325623, "steering_wheel_angle": 9.070430673047444, "front_wheel_angle": 0.48312878847088486, "heading_rate": 0.24332247810442317, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.689064} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23399148530840708, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.458152522260749, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1846699817241442, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.070430673047444, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.689064} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.089977025985718, "x": 47.95317430929381, "y": 0.33647648215371184, "z": null, "yaw": 0.27412601182778307, "pitch": null, "roll": null}, "v": 1.1874046770493767, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27346953252325623, "steering_wheel_angle": 9.070430673047444, "front_wheel_angle": 0.48312878847088486, "heading_rate": 0.24332247810442317, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.709064} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22416994831726333, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.458152522260749, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1834540069875576, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.070430673047444, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.709064} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.089977025985718, "x": 47.95317430929381, "y": 0.33647648215371184, "z": null, "yaw": 0.27412601182778307, "pitch": null, "roll": null}, "v": 1.1874046770493767, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27346953252325623, "steering_wheel_angle": 9.070430673047444, "front_wheel_angle": 0.48312878847088486, "heading_rate": 0.24332247810442317, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.729064} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22416994831726333, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.458152522260749, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1810125833122709, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.070430673047444, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.729064} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.089977025985718, "x": 47.95317430929381, "y": 0.33647648215371184, "z": null, "yaw": 0.27412601182778307, "pitch": null, "roll": null}, "v": 1.1874046770493767, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27346953252325623, "steering_wheel_angle": 9.070430673047444, "front_wheel_angle": 0.48312878847088486, "heading_rate": 0.24332247810442317, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.749064} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22416994831726333, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.458152522260749, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.17857475367409, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.070430673047444, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.749064} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.089977025985718, "x": 47.95317430929381, "y": 0.33647648215371184, "z": null, "yaw": 0.27412601182778307, "pitch": null, "roll": null}, "v": 1.1874046770493767, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27346953252325623, "steering_wheel_angle": 9.070430673047444, "front_wheel_angle": 0.48312878847088486, "heading_rate": 0.24332247810442317, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.769064} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22416994831726333, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.458152522260749, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1761405104058762, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.070430673047444, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.769064} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502662.789064, "x": 52.07785180542216, "y": 5.3729161926955085, "z": null, "yaw": 0.29666716659062037, "pitch": null, "roll": null}, "v": 1.173709845862259, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27246144031585307, "steering_wheel_angle": 9.070430673047444, "front_wheel_angle": 0.48312878847088486, "heading_rate": 0.2405161389295164, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.789064} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2485686327656828, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.249984898590888, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.173709845862259, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.070430673047444, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.789064} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.199976921081543, "x": 48.07785180542216, "y": 0.37291619269550846, "z": null, "yaw": 0.29666716659062037, "pitch": null, "roll": null}, "v": 1.173709845862259, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27246144031585307, "steering_wheel_angle": 9.070430673047444, "front_wheel_angle": 0.48312878847088486, "heading_rate": 0.2405161389295164, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.809064} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2408936342330604, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.249984898590888, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1743314676922318, "gear": 1, "accelerator_pedal_position": 0.2485686327656828, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.070430673047444, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.809064} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.199976921081543, "x": 48.07785180542216, "y": 0.37291619269550846, "z": null, "yaw": 0.29666716659062037, "pitch": null, "roll": null}, "v": 1.173709845862259, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27246144031585307, "steering_wheel_angle": 9.070430673047444, "front_wheel_angle": 0.48312878847088486, "heading_rate": 0.2405161389295164, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.829064} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2408936342330604, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.249984898590888, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1739931539749704, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.070430673047444, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.829064} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.199976921081543, "x": 48.07785180542216, "y": 0.37291619269550846, "z": null, "yaw": 0.29666716659062037, "pitch": null, "roll": null}, "v": 1.173709845862259, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27246144031585307, "steering_wheel_angle": 9.070430673047444, "front_wheel_angle": 0.48312878847088486, "heading_rate": 0.2405161389295164, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.8490639} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2408936342330604, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.249984898590888, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1736553372713974, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.070430673047444, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.8490639} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.199976921081543, "x": 48.07785180542216, "y": 0.37291619269550846, "z": null, "yaw": 0.29666716659062037, "pitch": null, "roll": null}, "v": 1.173709845862259, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27246144031585307, "steering_wheel_angle": 9.070430673047444, "front_wheel_angle": 0.48312878847088486, "heading_rate": 0.2405161389295164, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.8690639} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2408936342330604, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.249984898590888, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1733180168057231, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.070430673047444, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.8690639} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.199976921081543, "x": 48.07785180542216, "y": 0.37291619269550846, "z": null, "yaw": 0.29666716659062037, "pitch": null, "roll": null}, "v": 1.173709845862259, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27246144031585307, "steering_wheel_angle": 9.070430673047444, "front_wheel_angle": 0.48312878847088486, "heading_rate": 0.2405161389295164, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.8890638} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2408936342330604, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.249984898590888, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1728129648595307, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.070430673047444, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.8890638} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502662.8990638, "x": 52.20092257108941, "y": 5.411920418508863, "z": null, "yaw": 0.31920832135345767, "pitch": null, "roll": null}, "v": 1.1728129648595307, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27239555074840255, "steering_wheel_angle": 9.070430673047444, "front_wheel_angle": 0.48312878847088486, "heading_rate": 0.24033235044327686, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.9090638} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2593866701297724, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.073650420051983, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.172644861491613, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.070430673047444, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.9090638} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.309976816177368, "x": 48.20092257108941, "y": 0.4119204185088634, "z": null, "yaw": 0.31920832135345767, "pitch": null, "roll": null}, "v": 1.1728129648595307, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27239555074840255, "steering_wheel_angle": 9.070430673047444, "front_wheel_angle": 0.48312878847088486, "heading_rate": 0.24033235044327686, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.9290638} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2536042981424589, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.073650420051983, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1746198055112036, "gear": 1, "accelerator_pedal_position": 0.2593866701297724, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.070430673047444, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.9290638} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.309976816177368, "x": 48.20092257108941, "y": 0.4119204185088634, "z": null, "yaw": 0.31920832135345767, "pitch": null, "roll": null}, "v": 1.1728129648595307, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27239555074840255, "steering_wheel_angle": 9.070430673047444, "front_wheel_angle": 0.48312878847088486, "heading_rate": 0.24033235044327686, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.9490638} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2536042981424589, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.073650420051983, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.175869317280074, "gear": 1, "accelerator_pedal_position": 0.2536042981424589, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.070430673047444, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.9490638} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.309976816177368, "x": 48.20092257108941, "y": 0.4119204185088634, "z": null, "yaw": 0.31920832135345767, "pitch": null, "roll": null}, "v": 1.1728129648595307, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27239555074840255, "steering_wheel_angle": 9.070430673047444, "front_wheel_angle": 0.48312878847088486, "heading_rate": 0.24033235044327686, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.9690638} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2536042981424589, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.073650420051983, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.177116992663563, "gear": 1, "accelerator_pedal_position": 0.2536042981424589, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.070430673047444, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.9690638} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.309976816177368, "x": 48.20092257108941, "y": 0.4119204185088634, "z": null, "yaw": 0.31920832135345767, "pitch": null, "roll": null}, "v": 1.1728129648595307, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27239555074840255, "steering_wheel_angle": 9.070430673047444, "front_wheel_angle": 0.48312878847088486, "heading_rate": 0.24033235044327686, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502662.9890637} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2536042981424589, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.073650420051983, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1783628337381244, "gear": 1, "accelerator_pedal_position": 0.2536042981424589, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.070430673047444, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502662.9890637} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502663.0090637, "x": 52.3232989772473, "y": 5.453764344822384, "z": null, "yaw": 0.34174947611629497, "pitch": null, "roll": null}, "v": 1.1796068425799053, "accelerator_pedal_position": 0.2536042981424589, "brake_pedal_position": 0.0, "acceleration": 0.06213179823075937, "steering_wheel_angle": 9.070430673047444, "front_wheel_angle": 0.48312878847088486, "heading_rate": 0.24172454907177465, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.0090637} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2684590839995283, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.919546332895194, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1796068425799053, "gear": 1, "accelerator_pedal_position": 0.2536042981424589, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.070430673047444, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.0090637} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.419976711273193, "x": 48.3232989772473, "y": 0.4537643448223836, "z": null, "yaw": 0.34174947611629497, "pitch": null, "roll": null}, "v": 1.1796068425799053, "accelerator_pedal_position": 0.2536042981424589, "brake_pedal_position": 0.0, "acceleration": 0.06213179823075937, "steering_wheel_angle": 9.070430673047444, "front_wheel_angle": 0.48312878847088486, "heading_rate": 0.24172454907177465, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.0290637} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26384193611251633, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.919546332895194, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.182705186048158, "gear": 1, "accelerator_pedal_position": 0.2684590839995283, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.070430673047444, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.0290637} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.419976711273193, "x": 48.3232989772473, "y": 0.4537643448223836, "z": null, "yaw": 0.34174947611629497, "pitch": null, "roll": null}, "v": 1.1796068425799053, "accelerator_pedal_position": 0.2536042981424589, "brake_pedal_position": 0.0, "acceleration": 0.06213179823075937, "steering_wheel_angle": 9.070430673047444, "front_wheel_angle": 0.48312878847088486, "heading_rate": 0.24172454907177465, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.0490637} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26384193611251633, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.919546332895194, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1852220371826732, "gear": 1, "accelerator_pedal_position": 0.26384193611251633, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.070430673047444, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.0490637} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.419976711273193, "x": 48.3232989772473, "y": 0.4537643448223836, "z": null, "yaw": 0.34174947611629497, "pitch": null, "roll": null}, "v": 1.1796068425799053, "accelerator_pedal_position": 0.2536042981424589, "brake_pedal_position": 0.0, "acceleration": 0.06213179823075937, "steering_wheel_angle": 9.070430673047444, "front_wheel_angle": 0.48312878847088486, "heading_rate": 0.24172454907177465, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.0690637} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26384193611251633, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.919546332895194, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1877351802555427, "gear": 1, "accelerator_pedal_position": 0.26384193611251633, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.070430673047444, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.0690637} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.419976711273193, "x": 48.3232989772473, "y": 0.4537643448223836, "z": null, "yaw": 0.34174947611629497, "pitch": null, "roll": null}, "v": 1.1796068425799053, "accelerator_pedal_position": 0.2536042981424589, "brake_pedal_position": 0.0, "acceleration": 0.06213179823075937, "steering_wheel_angle": 9.070430673047444, "front_wheel_angle": 0.48312878847088486, "heading_rate": 0.24172454907177465, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.0890636} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26384193611251633, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.919546332895194, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1902446182044073, "gear": 1, "accelerator_pedal_position": 0.26384193611251633, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.070430673047444, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.0890636} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.419976711273193, "x": 48.3232989772473, "y": 0.4537643448223836, "z": null, "yaw": 0.34174947611629497, "pitch": null, "roll": null}, "v": 1.1796068425799053, "accelerator_pedal_position": 0.2536042981424589, "brake_pedal_position": 0.0, "acceleration": 0.06213179823075937, "steering_wheel_angle": 9.070430673047444, "front_wheel_angle": 0.48312878847088486, "heading_rate": 0.24172454907177465, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.1090636} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26384193611251633, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.919546332895194, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1927503539737443, "gear": 1, "accelerator_pedal_position": 0.26384193611251633, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.070430673047444, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.1090636} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502663.1190636, "x": 52.44579730899187, "y": 5.498760045060176, "z": null, "yaw": 0.36429063087913227, "pitch": null, "roll": null}, "v": 1.1940018344630992, "accelerator_pedal_position": 0.26384193611251633, "brake_pedal_position": 0.0, "acceleration": 0.12505560517305958, "steering_wheel_angle": 9.070430673047444, "front_wheel_angle": 0.48312878847088486, "heading_rate": 0.24467436488858244, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.1290636} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.021604878434488772, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.340128926147996, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1952523905148298, "gear": 1, "accelerator_pedal_position": 0.26384193611251633, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.070430673047444, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.1290636} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.52997660636902, "x": 48.44579730899187, "y": 0.4987600450601759, "z": null, "yaw": 0.36429063087913227, "pitch": null, "roll": null}, "v": 1.1940018344630992, "accelerator_pedal_position": 0.26384193611251633, "brake_pedal_position": 0.0, "acceleration": 0.12505560517305958, "steering_wheel_angle": 9.070430673047444, "front_wheel_angle": 0.48312878847088486, "heading_rate": 0.24467436488858244, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.1490636} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.340128926147996, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1863179326496838, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.021604878434488772, "steering_wheel_angle": 9.155956053125985, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.1490636} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.52997660636902, "x": 48.44579730899187, "y": 0.4987600450601759, "z": null, "yaw": 0.36429063087913227, "pitch": null, "roll": null}, "v": 1.1940018344630992, "accelerator_pedal_position": 0.26384193611251633, "brake_pedal_position": 0.0, "acceleration": 0.12505560517305958, "steering_wheel_angle": 9.070430673047444, "front_wheel_angle": 0.48312878847088486, "heading_rate": 0.24467436488858244, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.1690636} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.340128926147996, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1808521595226396, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.241114687767215, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.1690636} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.52997660636902, "x": 48.44579730899187, "y": 0.4987600450601759, "z": null, "yaw": 0.36429063087913227, "pitch": null, "roll": null}, "v": 1.1940018344630992, "accelerator_pedal_position": 0.26384193611251633, "brake_pedal_position": 0.0, "acceleration": 0.12505560517305958, "steering_wheel_angle": 9.070430673047444, "front_wheel_angle": 0.48312878847088486, "heading_rate": 0.24467436488858244, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.1890635} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.340128926147996, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.175394433900931, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.325906576971134, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.1890635} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.52997660636902, "x": 48.44579730899187, "y": 0.4987600450601759, "z": null, "yaw": 0.36429063087913227, "pitch": null, "roll": null}, "v": 1.1940018344630992, "accelerator_pedal_position": 0.26384193611251633, "brake_pedal_position": 0.0, "acceleration": 0.12505560517305958, "steering_wheel_angle": 9.070430673047444, "front_wheel_angle": 0.48312878847088486, "heading_rate": 0.24467436488858244, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.2090635} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.340128926147996, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1699447320255194, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.410331720737743, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.2090635} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502663.2290635, "x": 52.566723563991665, "y": 5.546308734635975, "z": null, "yaw": 0.38744640035374084, "pitch": null, "roll": null}, "v": 1.1645030302248467, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27178582458527084, "steering_wheel_angle": 9.494390119067042, "front_wheel_angle": 0.5102970224571116, "heading_rate": 0.25462074186382233, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.2290635} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2176876251595622, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.321859200160748, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1645030302248467, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.494390119067042, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.2290635} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.639976501464844, "x": 48.566723563991665, "y": 0.546308734635975, "z": null, "yaw": 0.38744640035374084, "pitch": null, "roll": null}, "v": 1.1645030302248467, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27178582458527084, "steering_wheel_angle": 9.494390119067042, "front_wheel_angle": 0.5102970224571116, "heading_rate": 0.25462074186382233, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.2490635} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.321859200160748, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1612794483336146, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.577994481550679, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.2490635} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.639976501464844, "x": 48.566723563991665, "y": 0.546308734635975, "z": null, "yaw": 0.38744640035374084, "pitch": null, "roll": null}, "v": 1.1645030302248467, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27178582458527084, "steering_wheel_angle": 9.494390119067042, "front_wheel_angle": 0.5102970224571116, "heading_rate": 0.25462074186382233, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.2690635} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.321859200160748, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1558504425949307, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.661232864905543, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.2690635} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.639976501464844, "x": 48.566723563991665, "y": 0.546308734635975, "z": null, "yaw": 0.38744640035374084, "pitch": null, "roll": null}, "v": 1.1645030302248467, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27178582458527084, "steering_wheel_angle": 9.494390119067042, "front_wheel_angle": 0.5102970224571116, "heading_rate": 0.25462074186382233, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.2890635} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.321859200160748, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.150429375953393, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.74410526913163, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.2890635} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.639976501464844, "x": 48.566723563991665, "y": 0.546308734635975, "z": null, "yaw": 0.38744640035374084, "pitch": null, "roll": null}, "v": 1.1645030302248467, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27178582458527084, "steering_wheel_angle": 9.494390119067042, "front_wheel_angle": 0.5102970224571116, "heading_rate": 0.25462074186382233, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.3090634} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.321859200160748, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1450162250483786, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.74410526913163, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.3090634} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.639976501464844, "x": 48.566723563991665, "y": 0.546308734635975, "z": null, "yaw": 0.38744640035374084, "pitch": null, "roll": null}, "v": 1.1645030302248467, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.27178582458527084, "steering_wheel_angle": 9.494390119067042, "front_wheel_angle": 0.5102970224571116, "heading_rate": 0.25462074186382233, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.3290634} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.321859200160748, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1396109666048708, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.74410526913163, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.3290634} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502663.3390634, "x": 52.683595931475715, "y": 5.595518708180422, "z": null, "yaw": 0.41212970365060864, "pitch": null, "roll": null}, "v": 1.1369112898060478, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26977123729918695, "steering_wheel_angle": 9.74410526913163, "front_wheel_angle": 0.5265809236705252, "heading_rate": 0.2581736066880822, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.3490634} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22939180587261251, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.257400234553558, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.134213577433056, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.74410526913163, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.3490634} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.74997639656067, "x": 48.683595931475715, "y": 0.5955187081804221, "z": null, "yaw": 0.41212970365060864, "pitch": null, "roll": null}, "v": 1.1369112898060478, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26977123729918695, "steering_wheel_angle": 9.74410526913163, "front_wheel_angle": 0.5265809236705252, "heading_rate": 0.2581736066880822, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.3690634} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22396910814292678, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.257400234553558, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1324966756137111, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.74410526913163, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.3690634} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.74997639656067, "x": 48.683595931475715, "y": 0.5955187081804221, "z": null, "yaw": 0.41212970365060864, "pitch": null, "roll": null}, "v": 1.1369112898060478, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26977123729918695, "steering_wheel_angle": 9.74410526913163, "front_wheel_angle": 0.5265809236705252, "heading_rate": 0.2581736066880822, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.3890634} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22396910814292678, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.257400234553558, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1301046767772325, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.74410526913163, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.3890634} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.74997639656067, "x": 48.683595931475715, "y": 0.5955187081804221, "z": null, "yaw": 0.41212970365060864, "pitch": null, "roll": null}, "v": 1.1369112898060478, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26977123729918695, "steering_wheel_angle": 9.74410526913163, "front_wheel_angle": 0.5265809236705252, "heading_rate": 0.2581736066880822, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.4090633} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22396910814292678, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.257400234553558, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.127716150534339, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.74410526913163, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.4090633} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.74997639656067, "x": 48.683595931475715, "y": 0.5955187081804221, "z": null, "yaw": 0.41212970365060864, "pitch": null, "roll": null}, "v": 1.1369112898060478, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26977123729918695, "steering_wheel_angle": 9.74410526913163, "front_wheel_angle": 0.5265809236705252, "heading_rate": 0.2581736066880822, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.4290633} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22396910814292678, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.257400234553558, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1253310895624837, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.74410526913163, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.4290633} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502663.4490633, "x": 52.79692305836316, "y": 5.646598502087921, "z": null, "yaw": 0.43710887044253477, "pitch": null, "roll": null}, "v": 1.1229494865596739, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2687576298216301, "steering_wheel_angle": 9.74410526913163, "front_wheel_angle": 0.5265809236705252, "heading_rate": 0.2550031138516528, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.4490633} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23121164714312586, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.276025676227368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1229494865596739, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.74410526913163, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.4490633} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.859976291656494, "x": 48.79692305836316, "y": 0.6465985020879206, "z": null, "yaw": 0.43710887044253477, "pitch": null, "roll": null}, "v": 1.1229494865596739, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2687576298216301, "steering_wheel_angle": 9.74410526913163, "front_wheel_angle": 0.5265809236705252, "heading_rate": 0.2550031138516528, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.4690633} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22889767181452536, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.276025676227368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.121476323714709, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.74410526913163, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.4690633} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.859976291656494, "x": 48.79692305836316, "y": 0.6465985020879206, "z": null, "yaw": 0.43710887044253477, "pitch": null, "roll": null}, "v": 1.1229494865596739, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2687576298216301, "steering_wheel_angle": 9.74410526913163, "front_wheel_angle": 0.5265809236705252, "heading_rate": 0.2550031138516528, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.4890633} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22889767181452536, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.276025676227368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1197161521342422, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.74410526913163, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.4890633} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.859976291656494, "x": 48.79692305836316, "y": 0.6465985020879206, "z": null, "yaw": 0.43710887044253477, "pitch": null, "roll": null}, "v": 1.1229494865596739, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2687576298216301, "steering_wheel_angle": 9.74410526913163, "front_wheel_angle": 0.5265809236705252, "heading_rate": 0.2550031138516528, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.5090632} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22889767181452536, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.276025676227368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1179585284695888, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.74410526913163, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.5090632} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.859976291656494, "x": 48.79692305836316, "y": 0.6465985020879206, "z": null, "yaw": 0.43710887044253477, "pitch": null, "roll": null}, "v": 1.1229494865596739, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2687576298216301, "steering_wheel_angle": 9.74410526913163, "front_wheel_angle": 0.5265809236705252, "heading_rate": 0.2550031138516528, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.5290632} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22889767181452536, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.276025676227368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1162034477972933, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.74410526913163, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.5290632} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.859976291656494, "x": 48.79692305836316, "y": 0.6465985020879206, "z": null, "yaw": 0.43710887044253477, "pitch": null, "roll": null}, "v": 1.1229494865596739, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2687576298216301, "steering_wheel_angle": 9.74410526913163, "front_wheel_angle": 0.5265809236705252, "heading_rate": 0.2550031138516528, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.5490632} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22889767181452536, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.276025676227368, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1144509052063858, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.74410526913163, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.5490632} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502663.5590632, "x": 52.907819569870256, "y": 5.699955178982982, "z": null, "yaw": 0.4620880372344609, "pitch": null, "roll": null}, "v": 1.1135755841601789, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26807928502438577, "steering_wheel_angle": 9.74410526913163, "front_wheel_angle": 0.5265809236705252, "heading_rate": 0.2528744568377599, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.5690632} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23031181781787274, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.367050996379675, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1127008957983429, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.74410526913163, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.5690632} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.96997618675232, "x": 48.907819569870256, "y": 0.6999551789829823, "z": null, "yaw": 0.4620880372344609, "pitch": null, "roll": null}, "v": 1.1135755841601789, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26807928502438577, "steering_wheel_angle": 9.74410526913163, "front_wheel_angle": 0.5265809236705252, "heading_rate": 0.2528744568377599, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.5890632} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22983597963998065, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.367050996379675, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1111301190910536, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.785511252914395, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.5890632} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.96997618675232, "x": 48.907819569870256, "y": 0.6999551789829823, "z": null, "yaw": 0.4620880372344609, "pitch": null, "roll": null}, "v": 1.1135755841601789, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26807928502438577, "steering_wheel_angle": 9.74410526913163, "front_wheel_angle": 0.5265809236705252, "heading_rate": 0.2528744568377599, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.6090631} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22983597963998065, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.367050996379675, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1095021524246351, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.785511252914395, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.6090631} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.96997618675232, "x": 48.907819569870256, "y": 0.6999551789829823, "z": null, "yaw": 0.4620880372344609, "pitch": null, "roll": null}, "v": 1.1135755841601789, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26807928502438577, "steering_wheel_angle": 9.74410526913163, "front_wheel_angle": 0.5265809236705252, "heading_rate": 0.2528744568377599, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.6290631} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22983597963998065, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.367050996379675, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.107876535634424, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.785511252914395, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.6290631} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 24.96997618675232, "x": 48.907819569870256, "y": 0.6999551789829823, "z": null, "yaw": 0.4620880372344609, "pitch": null, "roll": null}, "v": 1.1135755841601789, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26807928502438577, "steering_wheel_angle": 9.74410526913163, "front_wheel_angle": 0.5265809236705252, "heading_rate": 0.2528744568377599, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.649063} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22983597963998065, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.367050996379675, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1062532642718386, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.785511252914395, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.649063} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502663.669063, "x": 53.01643531628282, "y": 5.755603553972554, "z": null, "yaw": 0.48719539662995837, "pitch": null, "roll": null}, "v": 1.1046323338992892, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26743374262592234, "steering_wheel_angle": 9.785511252914395, "front_wheel_angle": 0.5293019481555268, "heading_rate": 0.2524169903571838, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.669063} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22583675821801802, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.54257964736771, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1046323338992892, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.785511252914395, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.669063} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.079976081848145, "x": 49.01643531628282, "y": 0.7556035539725539, "z": null, "yaw": 0.48719539662995837, "pitch": null, "roll": null}, "v": 1.1046323338992892, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26743374262592234, "steering_wheel_angle": 9.785511252914395, "front_wheel_angle": 0.5293019481555268, "heading_rate": 0.2524169903571838, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.689063} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2270542385907005, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.54257964736771, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1025140175622161, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.868890984052669, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.689063} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.079976081848145, "x": 49.01643531628282, "y": 0.7556035539725539, "z": null, "yaw": 0.48719539662995837, "pitch": null, "roll": null}, "v": 1.1046323338992892, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26743374262592234, "steering_wheel_angle": 9.785511252914395, "front_wheel_angle": 0.5293019481555268, "heading_rate": 0.2524169903571838, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.709063} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2270542385907005, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.54257964736771, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1005508833169888, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.951895258215732, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.709063} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.079976081848145, "x": 49.01643531628282, "y": 0.7556035539725539, "z": null, "yaw": 0.48719539662995837, "pitch": null, "roll": null}, "v": 1.1046323338992892, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26743374262592234, "steering_wheel_angle": 9.785511252914395, "front_wheel_angle": 0.5293019481555268, "heading_rate": 0.2524169903571838, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.729063} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2270542385907005, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.54257964736771, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0985905757849084, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.951895258215732, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.729063} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.079976081848145, "x": 49.01643531628282, "y": 0.7556035539725539, "z": null, "yaw": 0.48719539662995837, "pitch": null, "roll": null}, "v": 1.1046323338992892, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26743374262592234, "steering_wheel_angle": 9.785511252914395, "front_wheel_angle": 0.5293019481555268, "heading_rate": 0.2524169903571838, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.749063} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2270542385907005, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.54257964736771, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0966330893592262, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.951895258215732, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.749063} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.079976081848145, "x": 49.01643531628282, "y": 0.7556035539725539, "z": null, "yaw": 0.48719539662995837, "pitch": null, "roll": null}, "v": 1.1046323338992892, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26743374262592234, "steering_wheel_angle": 9.785511252914395, "front_wheel_angle": 0.5293019481555268, "heading_rate": 0.2524169903571838, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.769063} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2270542385907005, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.54257964736771, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0946784184478981, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.951895258215732, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.769063} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502663.779063, "x": 53.12265197621588, "y": 5.813460601648707, "z": null, "yaw": 0.5128242215510951, "pitch": null, "roll": null}, "v": 1.0937021370666113, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2666469504995713, "steering_wheel_angle": 9.951895258215732, "front_wheel_angle": 0.5402975531287564, "heading_rate": 0.25626558870097105, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.789063} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23422695792296108, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.549657281949427, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0927265574735343, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.951895258215732, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.789063} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.18997597694397, "x": 49.12265197621588, "y": 0.8134606016487069, "z": null, "yaw": 0.5128242215510951, "pitch": null, "roll": null}, "v": 1.0937021370666113, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2666469504995713, "steering_wheel_angle": 9.951895258215732, "front_wheel_angle": 0.5402975531287564, "heading_rate": 0.25626558870097105, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.809063} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23194614202989267, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.549657281949427, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.091673768736955, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.993273763815132, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.809063} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.18997597694397, "x": 49.12265197621588, "y": 0.8134606016487069, "z": null, "yaw": 0.5128242215510951, "pitch": null, "roll": null}, "v": 1.0937021370666113, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2666469504995713, "steering_wheel_angle": 9.951895258215732, "front_wheel_angle": 0.5402975531287564, "heading_rate": 0.25626558870097105, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.829063} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23194614202989267, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.549657281949427, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0903374924730798, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.993273763815132, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.829063} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.18997597694397, "x": 49.12265197621588, "y": 0.8134606016487069, "z": null, "yaw": 0.5128242215510951, "pitch": null, "roll": null}, "v": 1.0937021370666113, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2666469504995713, "steering_wheel_angle": 9.951895258215732, "front_wheel_angle": 0.5402975531287564, "heading_rate": 0.25626558870097105, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.849063} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23194614202989267, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.549657281949427, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0890031347717997, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.993273763815132, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.849063} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.18997597694397, "x": 49.12265197621588, "y": 0.8134606016487069, "z": null, "yaw": 0.5128242215510951, "pitch": null, "roll": null}, "v": 1.0937021370666113, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2666469504995713, "steering_wheel_angle": 9.951895258215732, "front_wheel_angle": 0.5402975531287564, "heading_rate": 0.25626558870097105, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.869063} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23194614202989267, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.549657281949427, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0876706921665846, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.993273763815132, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.869063} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502663.889063, "x": 53.22645589044781, "y": 5.8735267995967755, "z": null, "yaw": 0.5387300305509897, "pitch": null, "roll": null}, "v": 1.0863401611989445, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2661183575182847, "steering_wheel_angle": 9.993273763815132, "front_wheel_angle": 0.5430475964576865, "heading_rate": 0.2561300963851827, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.889063} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22788726542757837, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.692335255396786, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0863401611989445, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.993273763815132, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.889063} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.299975872039795, "x": 49.22645589044781, "y": 0.8735267995967755, "z": null, "yaw": 0.5387300305509897, "pitch": null, "roll": null}, "v": 1.0863401611989445, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2661183575182847, "steering_wheel_angle": 9.993273763815132, "front_wheel_angle": 0.5430475964576865, "heading_rate": 0.2561300963851827, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.9090629} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2291292355310363, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.692335255396786, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0845043607593683, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.07644705614864, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.9090629} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.299975872039795, "x": 49.22645589044781, "y": 0.8735267995967755, "z": null, "yaw": 0.5387300305509897, "pitch": null, "roll": null}, "v": 1.0863401611989445, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2661183575182847, "steering_wheel_angle": 9.993273763815132, "front_wheel_angle": 0.5430475964576865, "heading_rate": 0.2561300963851827, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.9290628} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2291292355310363, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.692335255396786, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0828263825155298, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.117890387785016, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.9290628} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.299975872039795, "x": 49.22645589044781, "y": 0.8735267995967755, "z": null, "yaw": 0.5387300305509897, "pitch": null, "roll": null}, "v": 1.0863401611989445, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2661183575182847, "steering_wheel_angle": 9.993273763815132, "front_wheel_angle": 0.5430475964576865, "heading_rate": 0.2561300963851827, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.9490628} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2291292355310363, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.692335255396786, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0811508084534553, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.117890387785016, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.9490628} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.299975872039795, "x": 49.22645589044781, "y": 0.8735267995967755, "z": null, "yaw": 0.5387300305509897, "pitch": null, "roll": null}, "v": 1.0863401611989445, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2661183575182847, "steering_wheel_angle": 9.993273763815132, "front_wheel_angle": 0.5430475964576865, "heading_rate": 0.2561300963851827, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.9690628} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2291292355310363, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.692335255396786, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0794776340058525, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.117890387785016, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.9690628} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.299975872039795, "x": 49.22645589044781, "y": 0.8735267995967755, "z": null, "yaw": 0.5387300305509897, "pitch": null, "roll": null}, "v": 1.0863401611989445, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2661183575182847, "steering_wheel_angle": 9.993273763815132, "front_wheel_angle": 0.5430475964576865, "heading_rate": 0.2561300963851827, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502663.9890628} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2291292355310363, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.692335255396786, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0778068546167932, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.117890387785016, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502663.9890628} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502663.9990628, "x": 53.327881343302934, "y": 5.935801606005048, "z": null, "yaw": 0.5650660921102498, "pitch": null, "roll": null}, "v": 1.0769723616485887, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2654473127599788, "steering_wheel_angle": 10.117890387785016, "front_wheel_angle": 0.5513677201434594, "heading_rate": 0.25872100196405745, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.0090628} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23842402878288338, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.641835080473687, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0761384657416786, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.117890387785016, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.0090628} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.40997576713562, "x": 49.327881343302934, "y": 0.9358016060050476, "z": null, "yaw": 0.5650660921102498, "pitch": null, "roll": null}, "v": 1.0769723616485887, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2654473127599788, "steering_wheel_angle": 10.117890387785016, "front_wheel_angle": 0.5513677201434594, "heading_rate": 0.25872100196405745, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.0290627} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23548585172734687, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.641835080473687, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0756338965734082, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.117890387785016, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.0290627} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.40997576713562, "x": 49.327881343302934, "y": 0.9358016060050476, "z": null, "yaw": 0.5650660921102498, "pitch": null, "roll": null}, "v": 1.0769723616485887, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2654473127599788, "steering_wheel_angle": 10.117890387785016, "front_wheel_angle": 0.5513677201434594, "heading_rate": 0.25872100196405745, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.0490627} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23548585172734687, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.641835080473687, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0747629080128949, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.117890387785016, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.0490627} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.40997576713562, "x": 49.327881343302934, "y": 0.9358016060050476, "z": null, "yaw": 0.5650660921102498, "pitch": null, "roll": null}, "v": 1.0769723616485887, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2654473127599788, "steering_wheel_angle": 10.117890387785016, "front_wheel_angle": 0.5513677201434594, "heading_rate": 0.25872100196405745, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.0690627} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23548585172734687, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.641835080473687, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0738931645140442, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.117890387785016, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.0690627} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.40997576713562, "x": 49.327881343302934, "y": 0.9358016060050476, "z": null, "yaw": 0.5650660921102498, "pitch": null, "roll": null}, "v": 1.0769723616485887, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2654473127599788, "steering_wheel_angle": 10.117890387785016, "front_wheel_angle": 0.5513677201434594, "heading_rate": 0.25872100196405745, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.0890627} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23548585172734687, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.641835080473687, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0730246639945906, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.117890387785016, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.0890627} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502664.1090627, "x": 53.426953670347736, "y": 6.000296330387909, "z": null, "yaw": 0.5914913851163595, "pitch": null, "roll": null}, "v": 1.0721574043765414, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2651030852164215, "steering_wheel_angle": 10.117890387785016, "front_wheel_angle": 0.5513677201434594, "heading_rate": 0.2575643050847325, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.1090627} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2428009709190308, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.601276199619413, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0721574043765414, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.117890387785016, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.1090627} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.519975662231445, "x": 49.426953670347736, "y": 1.0002963303879087, "z": null, "yaw": 0.5914913851163595, "pitch": null, "roll": null}, "v": 1.0721574043765414, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2651030852164215, "steering_wheel_angle": 10.117890387785016, "front_wheel_angle": 0.5513677201434594, "heading_rate": 0.2575643050847325, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.1290627} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24049778328436422, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.601276199619413, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0722054468693667, "gear": 1, "accelerator_pedal_position": 0.2428009709190308, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.117890387785016, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.1290627} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.519975662231445, "x": 49.426953670347736, "y": 1.0002963303879087, "z": null, "yaw": 0.5914913851163595, "pitch": null, "roll": null}, "v": 1.0721574043765414, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2651030852164215, "steering_wheel_angle": 10.117890387785016, "front_wheel_angle": 0.5513677201434594, "heading_rate": 0.2575643050847325, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.1490626} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24049778328436422, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.601276199619413, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0719656251274112, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.117890387785016, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.1490626} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.519975662231445, "x": 49.426953670347736, "y": 1.0002963303879087, "z": null, "yaw": 0.5914913851163595, "pitch": null, "roll": null}, "v": 1.0721574043765414, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2651030852164215, "steering_wheel_angle": 10.117890387785016, "front_wheel_angle": 0.5513677201434594, "heading_rate": 0.2575643050847325, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.1690626} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24049778328436422, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.601276199619413, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0717261459228178, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.117890387785016, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.1690626} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.519975662231445, "x": 49.426953670347736, "y": 1.0002963303879087, "z": null, "yaw": 0.5914913851163595, "pitch": null, "roll": null}, "v": 1.0721574043765414, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2651030852164215, "steering_wheel_angle": 10.117890387785016, "front_wheel_angle": 0.5513677201434594, "heading_rate": 0.2575643050847325, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.1890626} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24049778328436422, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.601276199619413, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.071487008743408, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.117890387785016, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.1890626} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.519975662231445, "x": 49.426953670347736, "y": 1.0002963303879087, "z": null, "yaw": 0.5914913851163595, "pitch": null, "roll": null}, "v": 1.0721574043765414, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2651030852164215, "steering_wheel_angle": 10.117890387785016, "front_wheel_angle": 0.5513677201434594, "heading_rate": 0.2575643050847325, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.2090626} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24049778328436422, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.601276199619413, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0712482130778342, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.117890387785016, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.2090626} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502664.2190626, "x": 53.524023287387024, "y": 6.067205273138756, "z": null, "yaw": 0.6179166781224691, "pitch": null, "roll": null}, "v": 1.0711289431531659, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2650296192862625, "steering_wheel_angle": 10.117890387785016, "front_wheel_angle": 0.5513677201434594, "heading_rate": 0.2573172379104314, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.2290626} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24234990116992877, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.632576047846722, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.071009758415576, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.117890387785016, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.2290626} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.62997555732727, "x": 49.524023287387024, "y": 1.0672052731387556, "z": null, "yaw": 0.6179166781224691, "pitch": null, "roll": null}, "v": 1.0711289431531659, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2650296192862625, "steering_wheel_angle": 10.117890387785016, "front_wheel_angle": 0.5513677201434594, "heading_rate": 0.2573172379104314, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.2490625} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24176744065229103, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.632576047846722, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.071003076309915, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.117890387785016, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.2490625} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.62997555732727, "x": 49.524023287387024, "y": 1.0672052731387556, "z": null, "yaw": 0.6179166781224691, "pitch": null, "roll": null}, "v": 1.0711289431531659, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2650296192862625, "steering_wheel_angle": 10.117890387785016, "front_wheel_angle": 0.5513677201434594, "heading_rate": 0.2573172379104314, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.2690625} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24176744065229103, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.632576047846722, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0709236221803202, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.117890387785016, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.2690625} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.62997555732727, "x": 49.524023287387024, "y": 1.0672052731387556, "z": null, "yaw": 0.6179166781224691, "pitch": null, "roll": null}, "v": 1.0711289431531659, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2650296192862625, "steering_wheel_angle": 10.117890387785016, "front_wheel_angle": 0.5513677201434594, "heading_rate": 0.2573172379104314, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.2890625} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24176744065229103, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.632576047846722, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0708442815006813, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.117890387785016, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.2890625} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.62997555732727, "x": 49.524023287387024, "y": 1.0672052731387556, "z": null, "yaw": 0.6179166781224691, "pitch": null, "roll": null}, "v": 1.0711289431531659, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2650296192862625, "steering_wheel_angle": 10.117890387785016, "front_wheel_angle": 0.5513677201434594, "heading_rate": 0.2573172379104314, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.3090625} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24176744065229103, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.632576047846722, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0707650541064901, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.117890387785016, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.3090625} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502664.3290625, "x": 53.61921169543759, "y": 6.136597953711866, "z": null, "yaw": 0.6443419711285787, "pitch": null, "roll": null}, "v": 1.0706859398334834, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2649979808092453, "steering_wheel_angle": 10.117890387785016, "front_wheel_angle": 0.5513677201434594, "heading_rate": 0.25721081525111056, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.3290625} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23801695273214843, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.750632574914366, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0706859398334834, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.117890387785016, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.3290625} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.739975452423096, "x": 49.61921169543759, "y": 1.136597953711866, "z": null, "yaw": 0.6443419711285787, "pitch": null, "roll": null}, "v": 1.0706859398334834, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2649979808092453, "steering_wheel_angle": 10.117890387785016, "front_wheel_angle": 0.5513677201434594, "heading_rate": 0.25721081525111056, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.3490624} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23918739905074654, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.750632574914366, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0701382949179596, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.200778807951238, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.3490624} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.739975452423096, "x": 49.61921169543759, "y": 1.136597953711866, "z": null, "yaw": 0.6443419711285787, "pitch": null, "roll": null}, "v": 1.0706859398334834, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2649979808092453, "steering_wheel_angle": 10.117890387785016, "front_wheel_angle": 0.5513677201434594, "heading_rate": 0.25721081525111056, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.3690624} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23918739905074654, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.750632574914366, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0697376853805431, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.200778807951238, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.3690624} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.739975452423096, "x": 49.61921169543759, "y": 1.136597953711866, "z": null, "yaw": 0.6443419711285787, "pitch": null, "roll": null}, "v": 1.0706859398334834, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2649979808092453, "steering_wheel_angle": 10.117890387785016, "front_wheel_angle": 0.5513677201434594, "heading_rate": 0.25721081525111056, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.3890624} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23918739905074654, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.750632574914366, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0693376476833556, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.200778807951238, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.3890624} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.739975452423096, "x": 49.61921169543759, "y": 1.136597953711866, "z": null, "yaw": 0.6443419711285787, "pitch": null, "roll": null}, "v": 1.0706859398334834, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2649979808092453, "steering_wheel_angle": 10.117890387785016, "front_wheel_angle": 0.5513677201434594, "heading_rate": 0.25721081525111056, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.4090624} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23918739905074654, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.750632574914366, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0689381809461487, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.200778807951238, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.4090624} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.739975452423096, "x": 49.61921169543759, "y": 1.136597953711866, "z": null, "yaw": 0.6443419711285787, "pitch": null, "roll": null}, "v": 1.0706859398334834, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2649979808092453, "steering_wheel_angle": 10.117890387785016, "front_wheel_angle": 0.5513677201434594, "heading_rate": 0.25721081525111056, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.4290624} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23918739905074654, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.750632574914366, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0685392842902042, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.200778807951238, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.4290624} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502664.4390624, "x": 53.71240745943211, "y": 6.208400368869333, "z": null, "yaw": 0.6710528977786145, "pitch": null, "roll": null}, "v": 1.0683400494685236, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26483050708641026, "steering_wheel_angle": 10.200778807951238, "front_wheel_angle": 0.5569338799933807, "heading_rate": 0.25985969925836855, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.4490623} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24019110178846273, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.798874361321507, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.068140956838331, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.200778807951238, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.4490623} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.84997534751892, "x": 49.71240745943211, "y": 1.2084003688693334, "z": null, "yaw": 0.6710528977786145, "pitch": null, "roll": null}, "v": 1.0683400494685236, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26483050708641026, "steering_wheel_angle": 10.200778807951238, "front_wheel_angle": 0.5569338799933807, "heading_rate": 0.25985969925836855, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.4690623} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23986907078564468, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.798874361321507, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0678686157922692, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.242198890096242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.4690623} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.84997534751892, "x": 49.71240745943211, "y": 1.2084003688693334, "z": null, "yaw": 0.6710528977786145, "pitch": null, "roll": null}, "v": 1.0683400494685236, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26483050708641026, "steering_wheel_angle": 10.200778807951238, "front_wheel_angle": 0.5569338799933807, "heading_rate": 0.25985969925836855, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.4890623} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23986907078564468, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.798874361321507, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.067556423771891, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.242198890096242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.4890623} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.84997534751892, "x": 49.71240745943211, "y": 1.2084003688693334, "z": null, "yaw": 0.6710528977786145, "pitch": null, "roll": null}, "v": 1.0683400494685236, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26483050708641026, "steering_wheel_angle": 10.200778807951238, "front_wheel_angle": 0.5569338799933807, "heading_rate": 0.25985969925836855, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.5090623} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23986907078564468, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.798874361321507, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0672446771073785, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.242198890096242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.5090623} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.84997534751892, "x": 49.71240745943211, "y": 1.2084003688693334, "z": null, "yaw": 0.6710528977786145, "pitch": null, "roll": null}, "v": 1.0683400494685236, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26483050708641026, "steering_wheel_angle": 10.200778807951238, "front_wheel_angle": 0.5569338799933807, "heading_rate": 0.25985969925836855, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.5290623} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23986907078564468, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.798874361321507, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0669333751245507, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.242198890096242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.5290623} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502664.5490623, "x": 53.803474371849575, "y": 6.2825351033675005, "z": null, "yaw": 0.6979453675196218, "pitch": null, "roll": null}, "v": 1.0666225171503554, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26470796179843936, "steering_wheel_angle": 10.242198890096242, "front_wheel_angle": 0.5597250687411017, "heading_rate": 0.2610586125154011, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.5490623} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24156186014983982, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.831956439609591, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0666225171503554, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.242198890096242, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.5490623} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.959975242614746, "x": 49.803474371849575, "y": 1.2825351033675005, "z": null, "yaw": 0.6979453675196218, "pitch": null, "roll": null}, "v": 1.0666225171503554, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26470796179843936, "steering_wheel_angle": 10.242198890096242, "front_wheel_angle": 0.5597250687411017, "heading_rate": 0.2610586125154011, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.5690622} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24102673585827547, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.831956439609591, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0665236257162976, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.283605034976686, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.5690622} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.959975242614746, "x": 49.803474371849575, "y": 1.2825351033675005, "z": null, "yaw": 0.6979453675196218, "pitch": null, "roll": null}, "v": 1.0666225171503554, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26470796179843936, "steering_wheel_angle": 10.242198890096242, "front_wheel_angle": 0.5597250687411017, "heading_rate": 0.2610586125154011, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.5890622} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24102673585827547, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.831956439609591, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0663580086321356, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.283605034976686, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.5890622} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.959975242614746, "x": 49.803474371849575, "y": 1.2825351033675005, "z": null, "yaw": 0.6979453675196218, "pitch": null, "roll": null}, "v": 1.0666225171503554, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26470796179843936, "steering_wheel_angle": 10.242198890096242, "front_wheel_angle": 0.5597250687411017, "heading_rate": 0.2610586125154011, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.6090622} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24102673585827547, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.831956439609591, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0661926277263825, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.283605034976686, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.6090622} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.959975242614746, "x": 49.803474371849575, "y": 1.2825351033675005, "z": null, "yaw": 0.6979453675196218, "pitch": null, "roll": null}, "v": 1.0666225171503554, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26470796179843936, "steering_wheel_angle": 10.242198890096242, "front_wheel_angle": 0.5597250687411017, "heading_rate": 0.2610586125154011, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.6290622} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24102673585827547, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.831956439609591, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0660274826512997, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.283605034976686, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.6290622} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 25.959975242614746, "x": 49.803474371849575, "y": 1.2825351033675005, "z": null, "yaw": 0.6979453675196218, "pitch": null, "roll": null}, "v": 1.0666225171503554, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26470796179843936, "steering_wheel_angle": 10.242198890096242, "front_wheel_angle": 0.5597250687411017, "heading_rate": 0.2610586125154011, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.6490622} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24102673585827547, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.831956439609591, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0658625730596905, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.283605034976686, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.6490622} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502664.6590621, "x": 53.89240079607856, "y": 6.359007578204368, "z": null, "yaw": 0.7250205582208973, "pitch": null, "roll": null}, "v": 1.0657802064618378, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26464788480795026, "steering_wheel_angle": 10.283605034976686, "front_wheel_angle": 0.5625218593050793, "heading_rate": 0.2624767778758382, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.6690621} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23335387233415397, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0656978986049006, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.283605034976686, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.6690621} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.06997513771057, "x": 49.89240079607856, "y": 1.359007578204368, "z": null, "yaw": 0.7250205582208973, "pitch": null, "roll": null}, "v": 1.0657802064618378, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26464788480795026, "steering_wheel_angle": 10.283605034976686, "front_wheel_angle": 0.5625218593050793, "heading_rate": 0.2624767778758382, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.689062} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23574863990604947, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0645746929583322, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.366891721050093, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.689062} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.06997513771057, "x": 49.89240079607856, "y": 1.359007578204368, "z": null, "yaw": 0.7250205582208973, "pitch": null, "roll": null}, "v": 1.0657802064618378, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26464788480795026, "steering_wheel_angle": 10.283605034976686, "front_wheel_angle": 0.5625218593050793, "heading_rate": 0.2624767778758382, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.709062} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23574863990604947, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0637523276241219, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.709062} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.06997513771057, "x": 49.89240079607856, "y": 1.359007578204368, "z": null, "yaw": 0.7250205582208973, "pitch": null, "roll": null}, "v": 1.0657802064618378, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26464788480795026, "steering_wheel_angle": 10.283605034976686, "front_wheel_angle": 0.5625218593050793, "heading_rate": 0.2624767778758382, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.729062} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23574863990604947, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.062931134222293, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.729062} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.06997513771057, "x": 49.89240079607856, "y": 1.359007578204368, "z": null, "yaw": 0.7250205582208973, "pitch": null, "roll": null}, "v": 1.0657802064618378, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26464788480795026, "steering_wheel_angle": 10.283605034976686, "front_wheel_angle": 0.5625218593050793, "heading_rate": 0.2624767778758382, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.749062} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23574863990604947, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0621111108131063, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.749062} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502664.769062, "x": 53.97901293903882, "y": 6.437687220711942, "z": null, "yaw": 0.7524827019597181, "pitch": null, "roll": null}, "v": 1.0612922554607394, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2643280252880464, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26630417011238827, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.769062} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2327153876928454, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0612922554607394, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.769062} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.179975032806396, "x": 49.97901293903882, "y": 1.4376872207119424, "z": null, "yaw": 0.7524827019597181, "pitch": null, "roll": null}, "v": 1.0612922554607394, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2643280252880464, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26630417011238827, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.789062} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23364728664447704, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.060095544716244, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.789062} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.179975032806396, "x": 49.97901293903882, "y": 1.4376872207119424, "z": null, "yaw": 0.7524827019597181, "pitch": null, "roll": null}, "v": 1.0612922554607394, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2643280252880464, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26630417011238827, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.809062} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23364728664447704, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0590169835750083, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.809062} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.179975032806396, "x": 49.97901293903882, "y": 1.4376872207119424, "z": null, "yaw": 0.7524827019597181, "pitch": null, "roll": null}, "v": 1.0612922554607394, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2643280252880464, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26630417011238827, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.829062} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23364728664447704, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0579399574505601, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.829062} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.179975032806396, "x": 49.97901293903882, "y": 1.4376872207119424, "z": null, "yaw": 0.7524827019597181, "pitch": null, "roll": null}, "v": 1.0612922554607394, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2643280252880464, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26630417011238827, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.849062} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23364728664447704, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0568644636944224, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.849062} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.179975032806396, "x": 49.97901293903882, "y": 1.4376872207119424, "z": null, "yaw": 0.7524827019597181, "pitch": null, "roll": null}, "v": 1.0612922554607394, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2643280252880464, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26630417011238827, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.869062} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23364728664447704, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0557904996638658, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.869062} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502664.879062, "x": 54.063002851029964, "y": 6.518321272529326, "z": null, "yaw": 0.7800843909022661, "pitch": null, "roll": null}, "v": 1.0552540904713956, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26389831647813594, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26478904691402777, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.889062} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24335506812075086, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0547180627218942, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.889062} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.28997492790222, "x": 50.063002851029964, "y": 1.5183212725293256, "z": null, "yaw": 0.7800843909022661, "pitch": null, "roll": null}, "v": 1.0552540904713956, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26389831647813594, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26478904691402777, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.909062} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2402998989657948, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0548601915946214, "gear": 1, "accelerator_pedal_position": 0.24335506812075086, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.909062} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.28997492790222, "x": 50.063002851029964, "y": 1.5183212725293256, "z": null, "yaw": 0.7800843909022661, "pitch": null, "roll": null}, "v": 1.0552540904713956, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26389831647813594, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26478904691402777, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.929062} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2402998989657948, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0546203580553382, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.929062} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.28997492790222, "x": 50.063002851029964, "y": 1.5183212725293256, "z": null, "yaw": 0.7800843909022661, "pitch": null, "roll": null}, "v": 1.0552540904713956, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26389831647813594, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26478904691402777, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.9490619} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2402998989657948, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0543808654074625, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.9490619} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.28997492790222, "x": 50.063002851029964, "y": 1.5183212725293256, "z": null, "yaw": 0.7800843909022661, "pitch": null, "roll": null}, "v": 1.0552540904713956, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26389831647813594, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26478904691402777, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.9690619} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2402998989657948, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.054141713143528, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.9690619} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502664.9890618, "x": 54.144431524686674, "y": 6.600936003455046, "z": null, "yaw": 0.8076860798448141, "pitch": null, "roll": null}, "v": 1.0539029007568874, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2638022582800822, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2644500003849166, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502664.9890618} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26000665854078553, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.765073905190201, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0539029007568874, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502664.9890618} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.399974822998047, "x": 50.144431524686674, "y": 1.600936003455046, "z": null, "yaw": 0.8076860798448141, "pitch": null, "roll": null}, "v": 1.0539029007568874, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2638022582800822, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2644500003849166, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.0090618} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2538434892228095, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.765073905190201, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0561268971173907, "gear": 1, "accelerator_pedal_position": 0.26000665854078553, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.0090618} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.399974822998047, "x": 50.144431524686674, "y": 1.600936003455046, "z": null, "yaw": 0.8076860798448141, "pitch": null, "roll": null}, "v": 1.0539029007568874, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2638022582800822, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2644500003849166, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.0290618} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2538434892228095, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.765073905190201, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.057577609440657, "gear": 1, "accelerator_pedal_position": 0.2538434892228095, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.0290618} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.399974822998047, "x": 50.144431524686674, "y": 1.600936003455046, "z": null, "yaw": 0.8076860798448141, "pitch": null, "roll": null}, "v": 1.0539029007568874, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2638022582800822, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2644500003849166, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.0490618} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2538434892228095, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.765073905190201, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.059026258300063, "gear": 1, "accelerator_pedal_position": 0.2538434892228095, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.0490618} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.399974822998047, "x": 50.144431524686674, "y": 1.600936003455046, "z": null, "yaw": 0.8076860798448141, "pitch": null, "roll": null}, "v": 1.0539029007568874, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2638022582800822, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2644500003849166, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.0690618} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2538434892228095, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.765073905190201, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0604728457915027, "gear": 1, "accelerator_pedal_position": 0.2538434892228095, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.0690618} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.399974822998047, "x": 50.144431524686674, "y": 1.600936003455046, "z": null, "yaw": 0.8076860798448141, "pitch": null, "roll": null}, "v": 1.0539029007568874, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2638022582800822, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2644500003849166, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.0890617} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2538434892228095, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.765073905190201, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.06191737401147, "gear": 1, "accelerator_pedal_position": 0.2538434892228095, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.0890617} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502665.0990617, "x": 54.22381918923415, "y": 6.6860596163655, "z": null, "yaw": 0.8352877687873621, "pitch": null, "roll": null}, "v": 1.062638866549967, "accelerator_pedal_position": 0.2538434892228095, "brake_pedal_position": 0.0, "acceleration": 0.0720978507080351, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26664206775249233, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.1090617} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22020808490874705, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0633598450570474, "gear": 1, "accelerator_pedal_position": 0.2538434892228095, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.1090617} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.509974718093872, "x": 50.22381918923415, "y": 1.6860596163655002, "z": null, "yaw": 0.8352877687873621, "pitch": null, "roll": null}, "v": 1.062638866549967, "accelerator_pedal_position": 0.2538434892228095, "brake_pedal_position": 0.0, "acceleration": 0.0720978507080351, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26664206775249233, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.1290617} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23075024060158958, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0605973335357355, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.1290617} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.509974718093872, "x": 50.22381918923415, "y": 1.6860596163655002, "z": null, "yaw": 0.8352877687873621, "pitch": null, "roll": null}, "v": 1.062638866549967, "accelerator_pedal_position": 0.2538434892228095, "brake_pedal_position": 0.0, "acceleration": 0.0720978507080351, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26664206775249233, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.1490617} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23075024060158958, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0591560562482252, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.1490617} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.509974718093872, "x": 50.22381918923415, "y": 1.6860596163655002, "z": null, "yaw": 0.8352877687873621, "pitch": null, "roll": null}, "v": 1.062638866549967, "accelerator_pedal_position": 0.2538434892228095, "brake_pedal_position": 0.0, "acceleration": 0.0720978507080351, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26664206775249233, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.1690617} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23075024060158958, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0577168303303828, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.1690617} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.509974718093872, "x": 50.22381918923415, "y": 1.6860596163655002, "z": null, "yaw": 0.8352877687873621, "pitch": null, "roll": null}, "v": 1.062638866549967, "accelerator_pedal_position": 0.2538434892228095, "brake_pedal_position": 0.0, "acceleration": 0.0720978507080351, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26664206775249233, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.1890616} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23075024060158958, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0562796520342408, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.1890616} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502665.2090616, "x": 54.3009130074523, "y": 6.773432351662795, "z": null, "yaw": 0.8628894577299101, "pitch": null, "roll": null}, "v": 1.0548445176206989, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26386919544457943, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2646862750738073, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.2090616} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24129565108748577, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0548445176206989, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.2090616} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.619974613189697, "x": 50.3009130074523, "y": 1.7734323516627946, "z": null, "yaw": 0.8628894577299101, "pitch": null, "roll": null}, "v": 1.0548445176206989, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26386919544457943, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2646862750738073, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.2290616} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23797247005729869, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0547291311300997, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.2290616} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.619974613189697, "x": 50.3009130074523, "y": 1.7734323516627946, "z": null, "yaw": 0.8628894577299101, "pitch": null, "roll": null}, "v": 1.0548445176206989, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26386919544457943, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2646862750738073, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.2490616} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23797247005729869, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0541986586767216, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.2490616} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.619974613189697, "x": 50.3009130074523, "y": 1.7734323516627946, "z": null, "yaw": 0.8628894577299101, "pitch": null, "roll": null}, "v": 1.0548445176206989, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26386919544457943, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2646862750738073, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.2690616} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23797247005729869, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0536689401452226, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.2690616} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.619974613189697, "x": 50.3009130074523, "y": 1.7734323516627946, "z": null, "yaw": 0.8628894577299101, "pitch": null, "roll": null}, "v": 1.0548445176206989, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26386919544457943, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2646862750738073, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.2890615} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23797247005729869, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0531399743519074, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.2890615} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.619974613189697, "x": 50.3009130074523, "y": 1.7734323516627946, "z": null, "yaw": 0.8628894577299101, "pitch": null, "roll": null}, "v": 1.0548445176206989, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26386919544457943, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2646862750738073, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.3090615} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23797247005729869, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0526117601152414, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.3090615} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502665.3190615, "x": 54.375180971341145, "y": 6.862440183237372, "z": null, "yaw": 0.8904911466724581, "pitch": null, "roll": null}, "v": 1.0523479344620117, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2636917584747652, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26405982133048655, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.3390615} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23748836387798727, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.051234013068664, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.3390615} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.729974508285522, "x": 50.375180971341145, "y": 1.8624401832373723, "z": null, "yaw": 0.8904911466724581, "pitch": null, "roll": null}, "v": 1.0523479344620117, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2636917584747652, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26405982133048655, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.3590615} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23763077530390359, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.051234013068664, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.3590615} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.729974508285522, "x": 50.375180971341145, "y": 1.8624401832373723, "z": null, "yaw": 0.8904911466724581, "pitch": null, "roll": null}, "v": 1.0523479344620117, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2636917584747652, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26405982133048655, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.3790615} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23763077530390359, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.050382009912236, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.3790615} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.729974508285522, "x": 50.375180971341145, "y": 1.8624401832373723, "z": null, "yaw": 0.8904911466724581, "pitch": null, "roll": null}, "v": 1.0523479344620117, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2636917584747652, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26405982133048655, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.3990614} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23763077530390359, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.050098412127099, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.3990614} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.729974508285522, "x": 50.375180971341145, "y": 1.8624401832373723, "z": null, "yaw": 0.8904911466724581, "pitch": null, "roll": null}, "v": 1.0523479344620117, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2636917584747652, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26405982133048655, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.4190614} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23763077530390359, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0495318205019324, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.4190614} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502665.4290614, "x": 54.44676490348642, "y": 6.9532108640644354, "z": null, "yaw": 0.9180928356150061, "pitch": null, "roll": null}, "v": 1.0492488263439508, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26347167231303914, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2632821793461771, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.4390614} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23454894728524658, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0489660330773143, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.4390614} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.839974403381348, "x": 50.44676490348642, "y": 1.9532108640644354, "z": null, "yaw": 0.9180928356150061, "pitch": null, "roll": null}, "v": 1.0492488263439508, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26347167231303914, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2632821793461771, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.4590614} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23550101485721472, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0480159567831484, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.4590614} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.839974403381348, "x": 50.44676490348642, "y": 1.9532108640644354, "z": null, "yaw": 0.9180928356150061, "pitch": null, "roll": null}, "v": 1.0492488263439508, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26347167231303914, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2632821793461771, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.4790614} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23550101485721472, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.04718619468256, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.4790614} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.839974403381348, "x": 50.44676490348642, "y": 1.9532108640644354, "z": null, "yaw": 0.9180928356150061, "pitch": null, "roll": null}, "v": 1.0492488263439508, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26347167231303914, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2632821793461771, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.4990613} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23550101485721472, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0463576095614446, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.4990613} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.839974403381348, "x": 50.44676490348642, "y": 1.9532108640644354, "z": null, "yaw": 0.9180928356150061, "pitch": null, "roll": null}, "v": 1.0492488263439508, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26347167231303914, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2632821793461771, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.5190613} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23550101485721472, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0455301994757868, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.5190613} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502665.5390613, "x": 54.515570507517864, "y": 7.045591690671431, "z": null, "yaw": 0.9456945245575541, "pitch": null, "roll": null}, "v": 1.0447039624854961, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2631492618166038, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26214176190520166, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.5390613} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24243460152006116, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0447039624854961, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.5390613} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.949974298477173, "x": 50.515570507517864, "y": 2.045591690671431, "z": null, "yaw": 0.9456945245575541, "pitch": null, "roll": null}, "v": 1.0447039624854961, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2631492618166038, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26214176190520166, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.5590613} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24025173373190023, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0447452877853391, "gear": 1, "accelerator_pedal_position": 0.24243460152006116, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.5590613} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.949974298477173, "x": 50.515570507517864, "y": 2.045591690671431, "z": null, "yaw": 0.9456945245575541, "pitch": null, "roll": null}, "v": 1.0447039624854961, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2631492618166038, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26214176190520166, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.5790613} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24025173373190023, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0445137927576194, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.5790613} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.949974298477173, "x": 50.515570507517864, "y": 2.045591690671431, "z": null, "yaw": 0.9456945245575541, "pitch": null, "roll": null}, "v": 1.0447039624854961, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2631492618166038, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26214176190520166, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.5990613} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24025173373190023, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0441671652589128, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.5990613} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.949974298477173, "x": 50.515570507517864, "y": 2.045591690671431, "z": null, "yaw": 0.9456945245575541, "pitch": null, "roll": null}, "v": 1.0447039624854961, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2631492618166038, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26214176190520166, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.6190612} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24025173373190023, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0440517865276266, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.6190612} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 26.949974298477173, "x": 50.515570507517864, "y": 2.045591690671431, "z": null, "yaw": 0.9456945245575541, "pitch": null, "roll": null}, "v": 1.0447039624854961, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2631492618166038, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26214176190520166, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.6390612} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24025173373190023, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.043706140789126, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.6390612} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502665.6490612, "x": 54.58161993948238, "y": 7.139581040507427, "z": null, "yaw": 0.9732962135001021, "pitch": null, "roll": null}, "v": 1.043706140789126, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26307853212266563, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26189138404989865, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.6590612} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23575379601873617, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.043591088826143, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.6590612} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.059974193572998, "x": 50.58161993948238, "y": 2.1395810405074274, "z": null, "yaw": 0.9732962135001021, "pitch": null, "roll": null}, "v": 1.043706140789126, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26307853212266563, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26189138404989865, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.6790612} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23715586598867175, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0424912854858446, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.6790612} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.059974193572998, "x": 50.58161993948238, "y": 2.1395810405074274, "z": null, "yaw": 0.9732962135001021, "pitch": null, "roll": null}, "v": 1.043706140789126, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26307853212266563, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26189138404989865, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.6990612} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23715586598867175, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0421836026593623, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.6990612} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.059974193572998, "x": 50.58161993948238, "y": 2.1395810405074274, "z": null, "yaw": 0.9732962135001021, "pitch": null, "roll": null}, "v": 1.043706140789126, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26307853212266563, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26189138404989865, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.7190611} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23715586598867175, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0415688907828882, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.7190611} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.059974193572998, "x": 50.58161993948238, "y": 2.1395810405074274, "z": null, "yaw": 0.9732962135001021, "pitch": null, "roll": null}, "v": 1.043706140789126, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26307853212266563, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26189138404989865, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.739061} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23715586598867175, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.040648454811632, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.739061} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502665.759061, "x": 54.64491993074157, "y": 7.235159529806492, "z": null, "yaw": 1.00089790244265, "pitch": null, "roll": null}, "v": 1.040342077287868, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2628402202421498, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26104725828312864, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.759061} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23417659854198275, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.040342077287868, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.759061} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.169974088668823, "x": 50.64491993074157, "y": 2.2351595298064924, "z": null, "yaw": 1.00089790244265, "pitch": null, "roll": null}, "v": 1.040342077287868, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2628402202421498, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26104725828312864, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.779061} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23509570462766016, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0389234725534795, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.779061} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.169974088668823, "x": 50.64491993074157, "y": 2.2351595298064924, "z": null, "yaw": 1.00089790244265, "pitch": null, "roll": null}, "v": 1.040342077287868, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2628402202421498, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26104725828312864, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.799061} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23509570462766016, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0384895561582492, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.799061} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.169974088668823, "x": 50.64491993074157, "y": 2.2351595298064924, "z": null, "yaw": 1.00089790244265, "pitch": null, "roll": null}, "v": 1.040342077287868, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2628402202421498, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26104725828312864, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.819061} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23509570462766016, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0371896485562904, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.819061} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.169974088668823, "x": 50.64491993074157, "y": 2.2351595298064924, "z": null, "yaw": 1.00089790244265, "pitch": null, "roll": null}, "v": 1.040342077287868, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2628402202421498, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26104725828312864, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.839061} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23509570462766016, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0363245755950345, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.839061} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.169974088668823, "x": 50.64491993074157, "y": 2.2351595298064924, "z": null, "yaw": 1.00089790244265, "pitch": null, "roll": null}, "v": 1.040342077287868, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2628402202421498, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.26104725828312864, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.859061} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23509570462766016, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0358924979838675, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.859061} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502665.869061, "x": 54.70531779948901, "y": 7.332062505839323, "z": null, "yaw": 1.0284995913851993, "pitch": null, "roll": null}, "v": 1.0354607259473665, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2624948254471628, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25982240790749395, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.879061} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2453095760536653, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0350292592321235, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.879061} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.27997398376465, "x": 50.70531779948901, "y": 2.332062505839323, "z": null, "yaw": 1.0284995913851993, "pitch": null, "roll": null}, "v": 1.0354607259473665, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2624948254471628, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25982240790749395, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.899061} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24210046938923505, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0354435233664412, "gear": 1, "accelerator_pedal_position": 0.2453095760536653, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.899061} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.27997398376465, "x": 50.70531779948901, "y": 2.332062505839323, "z": null, "yaw": 1.0284995913851993, "pitch": null, "roll": null}, "v": 1.0354607259473665, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2624948254471628, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25982240790749395, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.919061} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24210046938923505, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0354562053734713, "gear": 1, "accelerator_pedal_position": 0.24210046938923505, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.919061} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.27997398376465, "x": 50.70531779948901, "y": 2.332062505839323, "z": null, "yaw": 1.0284995913851993, "pitch": null, "roll": null}, "v": 1.0354607259473665, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2624948254471628, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25982240790749395, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.939061} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24210046938923505, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0354751947763265, "gear": 1, "accelerator_pedal_position": 0.24210046938923505, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.939061} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.27997398376465, "x": 50.70531779948901, "y": 2.332062505839323, "z": null, "yaw": 1.0284995913851993, "pitch": null, "roll": null}, "v": 1.0354607259473665, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2624948254471628, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25982240790749395, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.959061} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24210046938923505, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0354815156278658, "gear": 1, "accelerator_pedal_position": 0.24210046938923505, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.959061} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502665.979061, "x": 54.76286888730258, "y": 7.430342805226212, "z": null, "yaw": 1.0561012803277485, "pitch": null, "roll": null}, "v": 1.0354941439257566, "accelerator_pedal_position": 0.24210046938923505, "brake_pedal_position": 0.0, "acceleration": 0.000630745265385757, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2598307932951723, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.979061} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23188947381791758, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.034862264155203, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.979061} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.389973878860474, "x": 50.76286888730258, "y": 2.4303428052262124, "z": null, "yaw": 1.0561012803277485, "pitch": null, "roll": null}, "v": 1.0354941439257566, "accelerator_pedal_position": 0.24210046938923505, "brake_pedal_position": 0.0, "acceleration": 0.000630745265385757, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2598307932951723, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502665.9990609} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2350805301746824, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.034230831146168, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502665.9990609} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.389973878860474, "x": 50.76286888730258, "y": 2.4303428052262124, "z": null, "yaw": 1.0561012803277485, "pitch": null, "roll": null}, "v": 1.0354941439257566, "accelerator_pedal_position": 0.24210046938923505, "brake_pedal_position": 0.0, "acceleration": 0.000630745265385757, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2598307932951723, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.0190609} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2350805301746824, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0333680449221831, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.0190609} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.389973878860474, "x": 50.76286888730258, "y": 2.4303428052262124, "z": null, "yaw": 1.0561012803277485, "pitch": null, "roll": null}, "v": 1.0354941439257566, "accelerator_pedal_position": 0.24210046938923505, "brake_pedal_position": 0.0, "acceleration": 0.000630745265385757, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2598307932951723, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.0390608} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2350805301746824, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0320761506926337, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.0390608} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.389973878860474, "x": 50.76286888730258, "y": 2.4303428052262124, "z": null, "yaw": 1.0561012803277485, "pitch": null, "roll": null}, "v": 1.0354941439257566, "accelerator_pedal_position": 0.24210046938923505, "brake_pedal_position": 0.0, "acceleration": 0.000630745265385757, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2598307932951723, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.0590608} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2350805301746824, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.031646127635122, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.0590608} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.389973878860474, "x": 50.76286888730258, "y": 2.4303428052262124, "z": null, "yaw": 1.0561012803277485, "pitch": null, "roll": null}, "v": 1.0354941439257566, "accelerator_pedal_position": 0.24210046938923505, "brake_pedal_position": 0.0, "acceleration": 0.000630745265385757, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2598307932951723, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.0790608} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2350805301746824, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.030357879994875, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.0790608} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502666.0890608, "x": 54.81755918070452, "y": 7.529940810389744, "z": null, "yaw": 1.0837029692702977, "pitch": null, "roll": null}, "v": 1.030357879994875, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2621342676084191, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2585419791192902, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.0990608} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2275224800548705, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0299290704547084, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.0990608} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.4999737739563, "x": 50.81755918070452, "y": 2.5299408103897436, "z": null, "yaw": 1.0837029692702977, "pitch": null, "roll": null}, "v": 1.030357879994875, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2621342676084191, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2585419791192902, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.1190608} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22986622621354574, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0281279365438938, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.1190608} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.4999737739563, "x": 50.81755918070452, "y": 2.5299408103897436, "z": null, "yaw": 1.0837029692702977, "pitch": null, "roll": null}, "v": 1.030357879994875, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2621342676084191, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2585419791192902, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.1390607} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22986622621354574, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.026622208844013, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.1390607} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.4999737739563, "x": 50.81755918070452, "y": 2.5299408103897436, "z": null, "yaw": 1.0837029692702977, "pitch": null, "roll": null}, "v": 1.030357879994875, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2621342676084191, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2585419791192902, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.1590607} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22986622621354574, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0251186046747993, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.1590607} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.4999737739563, "x": 50.81755918070452, "y": 2.5299408103897436, "z": null, "yaw": 1.0837029692702977, "pitch": null, "roll": null}, "v": 1.030357879994875, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2621342676084191, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2585419791192902, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.1790607} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22986622621354574, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0236171201374213, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.1790607} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502666.1990607, "x": 54.86916246364028, "y": 7.630390385483864, "z": null, "yaw": 1.111304658212847, "pitch": null, "roll": null}, "v": 1.0221177513423683, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2615531345432102, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2564743294109896, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.1990607} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23206464454424763, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0221177513423683, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.1990607} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.609973669052124, "x": 50.86916246364028, "y": 2.6303903854838637, "z": null, "yaw": 1.111304658212847, "pitch": null, "roll": null}, "v": 1.0221177513423683, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2615531345432102, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2564743294109896, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.2190607} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23134858169315548, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0208951999308473, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.2190607} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.609973669052124, "x": 50.86916246364028, "y": 2.6303903854838637, "z": null, "yaw": 1.111304658212847, "pitch": null, "roll": null}, "v": 1.0221177513423683, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2615531345432102, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2564743294109896, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.2390606} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23134858169315548, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.01893043207896, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.2390606} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.609973669052124, "x": 50.86916246364028, "y": 2.6303903854838637, "z": null, "yaw": 1.111304658212847, "pitch": null, "roll": null}, "v": 1.0221177513423683, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2615531345432102, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2564743294109896, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.2590606} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23134858169315548, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0182764312962012, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.2590606} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.609973669052124, "x": 50.86916246364028, "y": 2.6303903854838637, "z": null, "yaw": 1.111304658212847, "pitch": null, "roll": null}, "v": 1.0221177513423683, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2615531345432102, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2564743294109896, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.2790606} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23134858169315548, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.016317188714354, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.2790606} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.609973669052124, "x": 50.86916246364028, "y": 2.6303903854838637, "z": null, "yaw": 1.111304658212847, "pitch": null, "roll": null}, "v": 1.0221177513423683, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2615531345432102, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2564743294109896, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.2990606} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23134858169315548, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0156650264130114, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.2990606} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502666.3090606, "x": 54.91760553420527, "y": 7.731458116057944, "z": null, "yaw": 1.1389063471553962, "pitch": null, "roll": null}, "v": 1.0150133227110392, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.261053186588361, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2546916546001125, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.3190606} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23971670960569363, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0143620772009778, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.3190606} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.71997356414795, "x": 50.91760553420527, "y": 2.7314581160579436, "z": null, "yaw": 1.1389063471553962, "pitch": null, "roll": null}, "v": 1.0150133227110392, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.261053186588361, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2546916546001125, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.3390605} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23707667050433848, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0138140049325688, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.3390605} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.71997356414795, "x": 50.91760553420527, "y": 2.7314581160579436, "z": null, "yaw": 1.1389063471553962, "pitch": null, "roll": null}, "v": 1.0150133227110392, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.261053186588361, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2546916546001125, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.3590605} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23707667050433848, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0135216079529639, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.3590605} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.71997356414795, "x": 50.91760553420527, "y": 2.7314581160579436, "z": null, "yaw": 1.1389063471553962, "pitch": null, "roll": null}, "v": 1.0150133227110392, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.261053186588361, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2546916546001125, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.3790605} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23707667050433848, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0129374302637897, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.3790605} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.71997356414795, "x": 50.91760553420527, "y": 2.7314581160579436, "z": null, "yaw": 1.1389063471553962, "pitch": null, "roll": null}, "v": 1.0150133227110392, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.261053186588361, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2546916546001125, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.3990605} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23707667050433848, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0123540731922307, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.3990605} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502666.4190605, "x": 54.962996274365544, "y": 7.833278131538733, "z": null, "yaw": 1.1665080360979454, "pitch": null, "roll": null}, "v": 1.0117715354494585, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2608253931719305, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25387821093091195, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.4190605} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2385714448099956, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0117715354494585, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.4190605} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.829973459243774, "x": 50.962996274365544, "y": 2.8332781315387328, "z": null, "yaw": 1.1665080360979454, "pitch": null, "roll": null}, "v": 1.0117715354494585, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2608253931719305, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25387821093091195, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.4390604} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2380929378549226, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0111494289808647, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.4390604} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.829973459243774, "x": 50.962996274365544, "y": 2.8332781315387328, "z": null, "yaw": 1.1665080360979454, "pitch": null, "roll": null}, "v": 1.0117715354494585, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2608253931719305, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25387821093091195, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.4590604} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2380929378549226, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.010922420565534, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.4590604} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.829973459243774, "x": 50.962996274365544, "y": 2.8332781315387328, "z": null, "yaw": 1.1665080360979454, "pitch": null, "roll": null}, "v": 1.0117715354494585, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2608253931719305, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25387821093091195, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.4790604} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2380929378549226, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0104688818334613, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.4790604} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.829973459243774, "x": 50.962996274365544, "y": 2.8332781315387328, "z": null, "yaw": 1.1665080360979454, "pitch": null, "roll": null}, "v": 1.0117715354494585, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2608253931719305, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25387821093091195, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.4990604} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2380929378549226, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.010015979751828, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.4990604} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.829973459243774, "x": 50.962996274365544, "y": 2.8332781315387328, "z": null, "yaw": 1.1665080360979454, "pitch": null, "roll": null}, "v": 1.0117715354494585, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2608253931719305, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25387821093091195, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.5190604} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2380929378549226, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0093378182150528, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.5190604} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502666.5290604, "x": 55.00544228915263, "y": 7.936028286973913, "z": null, "yaw": 1.1941097250404946, "pitch": null, "roll": null}, "v": 1.0093378182150528, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2606545192235439, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2532675317847466, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.5390604} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23636901304481056, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0087787581939003, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.5390604} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.9399733543396, "x": 51.00544228915263, "y": 2.9360282869739134, "z": null, "yaw": 1.1941097250404946, "pitch": null, "roll": null}, "v": 1.0093378182150528, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2606545192235439, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2532675317847466, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.5590603} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2368991961981664, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0084456686718057, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.5590603} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.9399733543396, "x": 51.00544228915263, "y": 2.9360282869739134, "z": null, "yaw": 1.1941097250404946, "pitch": null, "roll": null}, "v": 1.0093378182150528, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2606545192235439, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2532675317847466, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.5790603} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2368991961981664, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0075471413929082, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.5790603} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.9399733543396, "x": 51.00544228915263, "y": 2.9360282869739134, "z": null, "yaw": 1.1941097250404946, "pitch": null, "roll": null}, "v": 1.0093378182150528, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2606545192235439, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2532675317847466, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.5990603} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2368991961981664, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0069491733326208, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.5990603} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 27.9399733543396, "x": 51.00544228915263, "y": 2.9360282869739134, "z": null, "yaw": 1.1941097250404946, "pitch": null, "roll": null}, "v": 1.0093378182150528, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2606545192235439, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2532675317847466, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.6190603} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2368991961981664, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0063520438313465, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.6190603} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502666.6390603, "x": 55.04492566356124, "y": 8.039619531841296, "z": null, "yaw": 1.2217114139830438, "pitch": null, "roll": null}, "v": 1.0060537931282039, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2604241320030867, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2524434896126854, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.6390603} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24575896312316528, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0063094870033709, "gear": 1, "accelerator_pedal_position": 0.24575896312316528, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.6390603} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.049973249435425, "x": 51.04492566356124, "y": 3.0396195318412964, "z": null, "yaw": 1.2217114139830438, "pitch": null, "roll": null}, "v": 1.0060537931282039, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2604241320030867, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2524434896126854, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.6590602} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2429787647752402, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0065650015767038, "gear": 1, "accelerator_pedal_position": 0.24575896312316528, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.6590602} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.049973249435425, "x": 51.04492566356124, "y": 3.0396195318412964, "z": null, "yaw": 1.2217114139830438, "pitch": null, "roll": null}, "v": 1.0060537931282039, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2604241320030867, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2524434896126854, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.6790602} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2429787647752402, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.006809548951183, "gear": 1, "accelerator_pedal_position": 0.2429787647752402, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.6790602} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.049973249435425, "x": 51.04492566356124, "y": 3.0396195318412964, "z": null, "yaw": 1.2217114139830438, "pitch": null, "roll": null}, "v": 1.0060537931282039, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2604241320030867, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2524434896126854, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.6990602} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2429787647752402, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.006890950428374, "gear": 1, "accelerator_pedal_position": 0.2429787647752402, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.6990602} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.049973249435425, "x": 51.04492566356124, "y": 3.0396195318412964, "z": null, "yaw": 1.2217114139830438, "pitch": null, "roll": null}, "v": 1.0060537931282039, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2604241320030867, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2524434896126854, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.7190602} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2429787647752402, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0070535821438007, "gear": 1, "accelerator_pedal_position": 0.2429787647752402, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.7190602} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.049973249435425, "x": 51.04492566356124, "y": 3.0396195318412964, "z": null, "yaw": 1.2217114139830438, "pitch": null, "roll": null}, "v": 1.0060537931282039, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2604241320030867, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2524434896126854, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.7390602} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2429787647752402, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0072971021999748, "gear": 1, "accelerator_pedal_position": 0.2429787647752402, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.7390602} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502666.7490602, "x": 55.08149427490017, "y": 8.144147777037587, "z": null, "yaw": 1.249313102925593, "pitch": null, "roll": null}, "v": 1.0072971021999748, "accelerator_pedal_position": 0.2429787647752402, "brake_pedal_position": 0.0, "acceleration": 0.008105950214247704, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25275546625139883, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.7590601} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26008852039255403, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0073781617021174, "gear": 1, "accelerator_pedal_position": 0.2429787647752402, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.7590601} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.15997314453125, "x": 51.08149427490017, "y": 3.1441477770375865, "z": null, "yaw": 1.249313102925593, "pitch": null, "roll": null}, "v": 1.0072971021999748, "accelerator_pedal_position": 0.2429787647752402, "brake_pedal_position": 0.0, "acceleration": 0.008105950214247704, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25275546625139883, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.7790601} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2547460781407612, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0104929252155748, "gear": 1, "accelerator_pedal_position": 0.2547460781407612, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.7790601} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.15997314453125, "x": 51.08149427490017, "y": 3.1441477770375865, "z": null, "yaw": 1.249313102925593, "pitch": null, "roll": null}, "v": 1.0072971021999748, "accelerator_pedal_position": 0.2429787647752402, "brake_pedal_position": 0.0, "acceleration": 0.008105950214247704, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25275546625139883, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.79906} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2547460781407612, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0113071990415734, "gear": 1, "accelerator_pedal_position": 0.2547460781407612, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.79906} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.15997314453125, "x": 51.08149427490017, "y": 3.1441477770375865, "z": null, "yaw": 1.249313102925593, "pitch": null, "roll": null}, "v": 1.0072971021999748, "accelerator_pedal_position": 0.2429787647752402, "brake_pedal_position": 0.0, "acceleration": 0.008105950214247704, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25275546625139883, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.81906} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2547460781407612, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0129340316621696, "gear": 1, "accelerator_pedal_position": 0.2547460781407612, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.81906} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.15997314453125, "x": 51.08149427490017, "y": 3.1441477770375865, "z": null, "yaw": 1.249313102925593, "pitch": null, "roll": null}, "v": 1.0072971021999748, "accelerator_pedal_position": 0.2429787647752402, "brake_pedal_position": 0.0, "acceleration": 0.008105950214247704, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25275546625139883, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.83906} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2547460781407612, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0153699970511274, "gear": 1, "accelerator_pedal_position": 0.2547460781407612, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.83906} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502666.85906, "x": 55.11531129458047, "y": 8.250113147973728, "z": null, "yaw": 1.2769147918681423, "pitch": null, "roll": null}, "v": 1.0161808443133082, "accelerator_pedal_position": 0.2547460781407612, "brake_pedal_position": 0.0, "acceleration": 0.08102771108059903, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25498461431010827, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.85906} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22319619983940017, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0161808443133082, "gear": 1, "accelerator_pedal_position": 0.2547460781407612, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.85906} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.269973039627075, "x": 51.11531129458047, "y": 3.250113147973728, "z": null, "yaw": 1.2769147918681423, "pitch": null, "roll": null}, "v": 1.0161808443133082, "accelerator_pedal_position": 0.2547460781407612, "brake_pedal_position": 0.0, "acceleration": 0.08102771108059903, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25498461431010827, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.87906} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23308674067672713, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0133166816348294, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.87906} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.269973039627075, "x": 51.11531129458047, "y": 3.250113147973728, "z": null, "yaw": 1.2769147918681423, "pitch": null, "roll": null}, "v": 1.0161808443133082, "accelerator_pedal_position": 0.2547460781407612, "brake_pedal_position": 0.0, "acceleration": 0.08102771108059903, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25498461431010827, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.89906} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23308674067672713, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0127752635165794, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.89906} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.269973039627075, "x": 51.11531129458047, "y": 3.250113147973728, "z": null, "yaw": 1.2769147918681423, "pitch": null, "roll": null}, "v": 1.0161808443133082, "accelerator_pedal_position": 0.2547460781407612, "brake_pedal_position": 0.0, "acceleration": 0.08102771108059903, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25498461431010827, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.91906} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23308674067672713, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.011693568170282, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.91906} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.269973039627075, "x": 51.11531129458047, "y": 3.250113147973728, "z": null, "yaw": 1.2769147918681423, "pitch": null, "roll": null}, "v": 1.0161808443133082, "accelerator_pedal_position": 0.2547460781407612, "brake_pedal_position": 0.0, "acceleration": 0.08102771108059903, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25498461431010827, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.93906} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23308674067672713, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0100738724940066, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.93906} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.269973039627075, "x": 51.11531129458047, "y": 3.250113147973728, "z": null, "yaw": 1.2769147918681423, "pitch": null, "roll": null}, "v": 1.0161808443133082, "accelerator_pedal_position": 0.2547460781407612, "brake_pedal_position": 0.0, "acceleration": 0.08102771108059903, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25498461431010827, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.95906} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23308674067672713, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0095347319272656, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.95906} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502666.96906, "x": 55.146231070215634, "y": 8.35709560614575, "z": null, "yaw": 1.3045164808106915, "pitch": null, "roll": null}, "v": 1.0089959698161006, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26063052716185636, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2531817536649886, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.97906} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23435024279030625, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.00799854854801, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.97906} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.3799729347229, "x": 51.146231070215634, "y": 3.3570956061457498, "z": null, "yaw": 1.3045164808106915, "pitch": null, "roll": null}, "v": 1.0089959698161006, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26063052716185636, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2531817536649886, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502666.99906} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2339301605975203, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0075398333407428, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502666.99906} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.3799729347229, "x": 51.146231070215634, "y": 3.3570956061457498, "z": null, "yaw": 1.3045164808106915, "pitch": null, "roll": null}, "v": 1.0089959698161006, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26063052716185636, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2531817536649886, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.01906} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2339301605975203, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0065708762402554, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.01906} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.3799729347229, "x": 51.146231070215634, "y": 3.3570956061457498, "z": null, "yaw": 1.3045164808106915, "pitch": null, "roll": null}, "v": 1.0089959698161006, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26063052716185636, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2531817536649886, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.0390599} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2339301605975203, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0056032778437491, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.0390599} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.3799729347229, "x": 51.146231070215634, "y": 3.3570956061457498, "z": null, "yaw": 1.3045164808106915, "pitch": null, "roll": null}, "v": 1.0089959698161006, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26063052716185636, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2531817536649886, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.0590599} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2339301605975203, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0046370358716363, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.0590599} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502667.0790598, "x": 55.174024943189856, "y": 8.464268986752623, "z": null, "yaw": 1.3321181697532407, "pitch": null, "roll": null}, "v": 1.0036721480490995, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26025718521014995, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25184587664318553, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.0790598} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23015163993145654, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0031902112343432, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.0790598} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23015163993145654, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0031902112343432, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.0890598} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.489972829818726, "x": 51.174024943189856, "y": 3.4642689867526233, "z": null, "yaw": 1.3321181697532407, "pitch": null, "roll": null}, "v": 1.0036721480490995, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26025718521014995, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25184587664318553, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.1190598} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2313137613039623, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0010384492777997, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.1190598} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.489972829818726, "x": 51.174024943189856, "y": 3.4642689867526233, "z": null, "yaw": 1.3321181697532407, "pitch": null, "roll": null}, "v": 1.0036721480490995, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26025718521014995, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25184587664318553, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.1390598} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2313137613039623, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9991089499293542, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.1390598} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.489972829818726, "x": 51.174024943189856, "y": 3.4642689867526233, "z": null, "yaw": 1.3321181697532407, "pitch": null, "roll": null}, "v": 1.0036721480490995, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26025718521014995, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25184587664318553, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.1590598} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2313137613039623, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9984666836665043, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.1590598} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.489972829818726, "x": 51.174024943189856, "y": 3.4642689867526233, "z": null, "yaw": 1.3321181697532407, "pitch": null, "roll": null}, "v": 1.0036721480490995, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.26025718521014995, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25184587664318553, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.1790597} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2313137613039623, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9971834990359226, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.1790597} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502667.1890597, "x": 55.19869989201104, "y": 8.571512058609247, "z": null, "yaw": 1.35971985869579, "pitch": null, "roll": null}, "v": 0.9965425798748273, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25975810012877715, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25005689370644957, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.1990597} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2404724030941957, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9959021089550372, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.1990597} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.59997272491455, "x": 51.19869989201104, "y": 3.5715120586092475, "z": null, "yaw": 1.35971985869579, "pitch": null, "roll": null}, "v": 0.9965425798748273, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25975810012877715, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25005689370644957, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.2190597} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23758537138779365, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9957669403004388, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.2190597} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.59997272491455, "x": 51.19869989201104, "y": 3.5715120586092475, "z": null, "yaw": 1.35971985869579, "pitch": null, "roll": null}, "v": 0.9965425798748273, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25975810012877715, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25005689370644957, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.2390597} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23758537138779365, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9952712077747223, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.2390597} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.59997272491455, "x": 51.19869989201104, "y": 3.5715120586092475, "z": null, "yaw": 1.35971985869579, "pitch": null, "roll": null}, "v": 0.9965425798748273, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25975810012877715, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25005689370644957, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.2590597} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23758537138779365, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9947761681191689, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.2590597} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.59997272491455, "x": 51.19869989201104, "y": 3.5715120586092475, "z": null, "yaw": 1.35971985869579, "pitch": null, "roll": null}, "v": 0.9965425798748273, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25975810012877715, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25005689370644957, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.2790596} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23758537138779365, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9942818202673837, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.2790596} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502667.2990596, "x": 55.22029140892946, "y": 8.678833013924367, "z": null, "yaw": 1.3873215476383391, "pitch": null, "roll": null}, "v": 0.9937881631548727, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.259565557290011, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24936574321988286, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.2990596} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2415142264615556, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9937881631548727, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.2990596} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.709972620010376, "x": 51.22029140892946, "y": 3.6788330139243666, "z": null, "yaw": 1.3873215476383391, "pitch": null, "roll": null}, "v": 0.9937881631548727, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.259565557290011, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24936574321988286, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.3190596} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2402768312977672, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9937861310269974, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.3190596} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.709972620010376, "x": 51.22029140892946, "y": 3.6788330139243666, "z": null, "yaw": 1.3873215476383391, "pitch": null, "roll": null}, "v": 0.9937881631548727, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.259565557290011, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24936574321988286, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.3390596} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2402768312977672, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9935512386426892, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.3390596} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.709972620010376, "x": 51.22029140892946, "y": 3.6788330139243666, "z": null, "yaw": 1.3873215476383391, "pitch": null, "roll": null}, "v": 0.9937881631548727, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.259565557290011, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24936574321988286, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.3590596} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2402768312977672, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9934730505730975, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.3590596} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.709972620010376, "x": 51.22029140892946, "y": 3.6788330139243666, "z": null, "yaw": 1.3873215476383391, "pitch": null, "roll": null}, "v": 0.9937881631548727, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.259565557290011, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24936574321988286, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.3790596} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2402768312977672, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9932388139879507, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.3790596} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.709972620010376, "x": 51.22029140892946, "y": 3.6788330139243666, "z": null, "yaw": 1.3873215476383391, "pitch": null, "roll": null}, "v": 0.9937881631548727, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.259565557290011, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24936574321988286, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.3990595} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2402768312977672, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.993160844202906, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.3990595} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502667.4090595, "x": 55.23888067802692, "y": 8.786525303471445, "z": null, "yaw": 1.4149232365808884, "pitch": null, "roll": null}, "v": 0.9930829288906692, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2595162834810742, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24918878270359035, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.4190595} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2289438110400655, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9930050680119689, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.4190595} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.8199725151062, "x": 51.23888067802692, "y": 3.7865253034714446, "z": null, "yaw": 1.4149232365808884, "pitch": null, "roll": null}, "v": 0.9930829288906692, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2595162834810742, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24918878270359035, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.4390595} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23248291850057012, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9897430724529601, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.4390595} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.8199725151062, "x": 51.23888067802692, "y": 3.7865253034714446, "z": null, "yaw": 1.4149232365808884, "pitch": null, "roll": null}, "v": 0.9930829288906692, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2595162834810742, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24918878270359035, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.4690595} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23248291850057012, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9891804241880724, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.4690595} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.8199725151062, "x": 51.23888067802692, "y": 3.7865253034714446, "z": null, "yaw": 1.4149232365808884, "pitch": null, "roll": null}, "v": 0.9930829288906692, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2595162834810742, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24918878270359035, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.4890594} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23248291850057012, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9874948340521416, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.4890594} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.8199725151062, "x": 51.23888067802692, "y": 3.7865253034714446, "z": null, "yaw": 1.4149232365808884, "pitch": null, "roll": null}, "v": 0.9930829288906692, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2595162834810742, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24918878270359035, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.5090594} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23248291850057012, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9874948340521416, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.5090594} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502667.5190594, "x": 55.254442419460545, "y": 8.894344725268342, "z": null, "yaw": 1.4425249255234376, "pitch": null, "roll": null}, "v": 0.9869337544366732, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25908707007829834, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24764580451692983, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.5290594} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2348598701157142, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9863730661421758, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.5290594} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.929972410202026, "x": 51.254442419460545, "y": 3.8943447252683416, "z": null, "yaw": 1.4425249255234376, "pitch": null, "roll": null}, "v": 0.9869337544366732, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25908707007829834, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24764580451692983, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.5490594} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23409561156475592, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9855498775527615, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.5490594} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.929972410202026, "x": 51.254442419460545, "y": 3.8943447252683416, "z": null, "yaw": 1.4425249255234376, "pitch": null, "roll": null}, "v": 0.9869337544366732, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25908707007829834, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24764580451692983, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.5690594} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23409561156475592, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.984632337312244, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.5690594} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.929972410202026, "x": 51.254442419460545, "y": 3.8943447252683416, "z": null, "yaw": 1.4425249255234376, "pitch": null, "roll": null}, "v": 0.9869337544366732, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25908707007829834, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24764580451692983, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.5890594} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23409561156475592, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9832584235796266, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.5890594} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 28.929972410202026, "x": 51.254442419460545, "y": 3.8943447252683416, "z": null, "yaw": 1.4425249255234376, "pitch": null, "roll": null}, "v": 0.9869337544366732, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25908707007829834, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24764580451692983, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.6090593} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23409561156475592, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.98280109037788, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.6090593} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502667.6290593, "x": 55.266949315596854, "y": 9.001925103129183, "z": null, "yaw": 1.4701266144659868, "pitch": null, "roll": null}, "v": 0.9818873794537647, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25873539723199407, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2463795456754235, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.6290593} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23797425332799466, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9818873794537647, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.6290593} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.03997230529785, "x": 51.266949315596854, "y": 4.001925103129183, "z": null, "yaw": 1.4701266144659868, "pitch": null, "roll": null}, "v": 0.9818873794537647, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25873539723199407, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2463795456754235, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.6490593} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2367445933284394, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.981459602169657, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.6490593} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.03997230529785, "x": 51.266949315596854, "y": 4.001925103129183, "z": null, "yaw": 1.4701266144659868, "pitch": null, "roll": null}, "v": 0.9818873794537647, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25873539723199407, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2463795456754235, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.6690593} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2367445933284394, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9808787664210055, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.6690593} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.03997230529785, "x": 51.266949315596854, "y": 4.001925103129183, "z": null, "yaw": 1.4701266144659868, "pitch": null, "roll": null}, "v": 0.9818873794537647, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25873539723199407, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2463795456754235, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.6890593} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2367445933284394, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9802987391521008, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.6890593} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.03997230529785, "x": 51.266949315596854, "y": 4.001925103129183, "z": null, "yaw": 1.4701266144659868, "pitch": null, "roll": null}, "v": 0.9818873794537647, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25873539723199407, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2463795456754235, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.7090592} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2367445933284394, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9797195191030738, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.7090592} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.03997230529785, "x": 51.266949315596854, "y": 4.001925103129183, "z": null, "yaw": 1.4701266144659868, "pitch": null, "roll": null}, "v": 0.9818873794537647, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25873539723199407, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2463795456754235, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.7290592} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2367445933284394, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9791411050163705, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.7290592} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502667.7390592, "x": 55.27644271424494, "y": 9.10936566186795, "z": null, "yaw": 1.497728303408536, "pitch": null, "roll": null}, "v": 0.9788521998165365, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2585241262816836, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24561794490968233, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.7490592} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23377736813688182, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9785634956367472, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.7490592} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.149972200393677, "x": 51.27644271424494, "y": 4.109365661867949, "z": null, "yaw": 1.497728303408536, "pitch": null, "roll": null}, "v": 0.9788521998165365, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2585241262816836, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24561794490968233, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.7690592} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23469406306276008, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9776159155691951, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.7690592} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.149972200393677, "x": 51.27644271424494, "y": 4.109365661867949, "z": null, "yaw": 1.497728303408536, "pitch": null, "roll": null}, "v": 0.9788521998165365, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2585241262816836, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24561794490968233, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.7890592} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23469406306276008, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9767842002827372, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.7890592} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.149972200393677, "x": 51.27644271424494, "y": 4.109365661867949, "z": null, "yaw": 1.497728303408536, "pitch": null, "roll": null}, "v": 0.9788521998165365, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2585241262816836, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24561794490968233, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.8090591} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23469406306276008, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9759536413411051, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.8090591} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.149972200393677, "x": 51.27644271424494, "y": 4.109365661867949, "z": null, "yaw": 1.497728303408536, "pitch": null, "roll": null}, "v": 0.9788521998165365, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2585241262816836, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24561794490968233, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.8290591} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23469406306276008, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9751242368607819, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.8290591} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502667.849059, "x": 55.2829426463818, "y": 9.216613497061765, "z": null, "yaw": 1.5253299923510852, "pitch": null, "roll": null}, "v": 0.9742959849620187, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2582073259112321, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24447467922632035, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.849059} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24244693188837935, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9742959849620187, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.849059} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.259972095489502, "x": 51.2829426463818, "y": 4.216613497061765, "z": null, "yaw": 1.5253299923510852, "pitch": null, "roll": null}, "v": 0.9742959849620187, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2582073259112321, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24447467922632035, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.869059} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2400083187629714, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9744376556916279, "gear": 1, "accelerator_pedal_position": 0.24244693188837935, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.869059} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.259972095489502, "x": 51.2829426463818, "y": 4.216613497061765, "z": null, "yaw": 1.5253299923510852, "pitch": null, "roll": null}, "v": 0.9742959849620187, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2582073259112321, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24447467922632035, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.889059} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2400083187629714, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9742744088704787, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.889059} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.259972095489502, "x": 51.2829426463818, "y": 4.216613497061765, "z": null, "yaw": 1.5253299923510852, "pitch": null, "roll": null}, "v": 0.9742959849620187, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2582073259112321, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24447467922632035, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.909059} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2400083187629714, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9741113888388753, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.909059} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.259972095489502, "x": 51.2829426463818, "y": 4.216613497061765, "z": null, "yaw": 1.5253299923510852, "pitch": null, "roll": null}, "v": 0.9742959849620187, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2582073259112321, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24447467922632035, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.929059} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2400083187629714, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9739485952711253, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.929059} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.259972095489502, "x": 51.2829426463818, "y": 4.216613497061765, "z": null, "yaw": 1.5253299923510852, "pitch": null, "roll": null}, "v": 0.9742959849620187, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2582073259112321, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24447467922632035, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.949059} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2400083187629714, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9737048288279959, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.949059} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502667.959059, "x": 55.28646967912529, "y": 9.32370873086624, "z": null, "yaw": 1.5529316812936345, "pitch": null, "roll": null}, "v": 0.9737048288279959, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2581662523782294, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24432634370152237, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.969059} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2426800379490936, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9736236862268993, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.969059} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.369971990585327, "x": 51.28646967912529, "y": 4.32370873086624, "z": null, "yaw": 1.5529316812936345, "pitch": null, "roll": null}, "v": 0.9737048288279959, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2581662523782294, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24432634370152237, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502667.989059} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2418430714780223, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9737954189928657, "gear": 1, "accelerator_pedal_position": 0.2426800379490936, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502667.989059} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.369971990585327, "x": 51.28646967912529, "y": 4.32370873086624, "z": null, "yaw": 1.5529316812936345, "pitch": null, "roll": null}, "v": 0.9737048288279959, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2581662523782294, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24432634370152237, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.009059} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2418430714780223, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9738623287537442, "gear": 1, "accelerator_pedal_position": 0.2418430714780223, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.009059} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.369971990585327, "x": 51.28646967912529, "y": 4.32370873086624, "z": null, "yaw": 1.5529316812936345, "pitch": null, "roll": null}, "v": 0.9737048288279959, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2581662523782294, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24432634370152237, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.029059} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2418430714780223, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9739958695786959, "gear": 1, "accelerator_pedal_position": 0.2418430714780223, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.029059} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.369971990585327, "x": 51.28646967912529, "y": 4.32370873086624, "z": null, "yaw": 1.5529316812936345, "pitch": null, "roll": null}, "v": 0.9737048288279959, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2581662523782294, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24432634370152237, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.049059} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2418430714780223, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9739958695786959, "gear": 1, "accelerator_pedal_position": 0.2418430714780223, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.049059} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502668.069059, "x": 55.28703928045949, "y": 9.430827216195938, "z": null, "yaw": 1.5805333702361837, "pitch": null, "roll": null}, "v": 0.9740625008972308, "accelerator_pedal_position": 0.2418430714780223, "brake_pedal_position": 0.0, "acceleration": 0.003328094136236137, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2444160923669629, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.069059} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2332864199621576, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9740625008972308, "gear": 1, "accelerator_pedal_position": 0.2418430714780223, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.069059} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.479971885681152, "x": 51.28703928045949, "y": 4.430827216195938, "z": null, "yaw": 1.5805333702361837, "pitch": null, "roll": null}, "v": 0.9740625008972308, "accelerator_pedal_position": 0.2418430714780223, "brake_pedal_position": 0.0, "acceleration": 0.003328094136236137, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2444160923669629, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.0890589} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23596161782602043, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.972726216426594, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.0890589} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.479971885681152, "x": 51.28703928045949, "y": 4.430827216195938, "z": null, "yaw": 1.5805333702361837, "pitch": null, "roll": null}, "v": 0.9740625008972308, "accelerator_pedal_position": 0.2418430714780223, "brake_pedal_position": 0.0, "acceleration": 0.003328094136236137, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2444160923669629, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.1090589} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23596161782602043, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9723928348032945, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.1090589} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.479971885681152, "x": 51.28703928045949, "y": 4.430827216195938, "z": null, "yaw": 1.5805333702361837, "pitch": null, "roll": null}, "v": 0.9740625008972308, "accelerator_pedal_position": 0.2418430714780223, "brake_pedal_position": 0.0, "acceleration": 0.003328094136236137, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2444160923669629, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.1290588} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23596161782602043, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9713940784265634, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.1290588} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.479971885681152, "x": 51.28703928045949, "y": 4.430827216195938, "z": null, "yaw": 1.5805333702361837, "pitch": null, "roll": null}, "v": 0.9740625008972308, "accelerator_pedal_position": 0.2418430714780223, "brake_pedal_position": 0.0, "acceleration": 0.003328094136236137, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2444160923669629, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.1490588} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23596161782602043, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9710616218559163, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.1490588} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.479971885681152, "x": 51.28703928045949, "y": 4.430827216195938, "z": null, "yaw": 1.5805333702361837, "pitch": null, "roll": null}, "v": 0.9740625008972308, "accelerator_pedal_position": 0.2418430714780223, "brake_pedal_position": 0.0, "acceleration": 0.003328094136236137, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2444160923669629, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.1690588} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23596161782602043, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9703974009518072, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.1690588} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502668.1790588, "x": 55.28465774264606, "y": 9.537729038449298, "z": null, "yaw": 1.608135059178733, "pitch": null, "roll": null}, "v": 0.9700656362538801, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2579135551991005, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24341318132486078, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.1890588} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23895195609503514, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9689705625407291, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.1890588} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.589971780776978, "x": 51.28465774264606, "y": 4.537729038449298, "z": null, "yaw": 1.608135059178733, "pitch": null, "roll": null}, "v": 0.9700656362538801, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2579135551991005, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24341318132486078, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.2290587} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2380035973940605, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9687674117014805, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.2290587} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.589971780776978, "x": 51.28465774264606, "y": 4.537729038449298, "z": null, "yaw": 1.608135059178733, "pitch": null, "roll": null}, "v": 0.9700656362538801, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2579135551991005, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24341318132486078, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.2490587} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2380035973940605, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9685644018029611, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.2490587} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.589971780776978, "x": 51.28465774264606, "y": 4.537729038449298, "z": null, "yaw": 1.608135059178733, "pitch": null, "roll": null}, "v": 0.9700656362538801, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2579135551991005, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24341318132486078, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.2690587} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2380035973940605, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9681588044040947, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.2690587} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502668.2890587, "x": 55.279343743527996, "y": 9.644176671039832, "z": null, "yaw": 1.6357367481212821, "pitch": null, "roll": null}, "v": 0.9677537694970065, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257753162058607, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24283307744213492, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.2890587} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.233267629106883, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9677537694970065, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.2890587} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.699971675872803, "x": 51.279343743527996, "y": 4.644176671039832, "z": null, "yaw": 1.6357367481212821, "pitch": null, "roll": null}, "v": 0.9677537694970065, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257753162058607, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24283307744213492, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.3090587} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23473960050470094, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9667575054690347, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.3090587} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.699971675872803, "x": 51.279343743527996, "y": 4.644176671039832, "z": null, "yaw": 1.6357367481212821, "pitch": null, "roll": null}, "v": 0.9677537694970065, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257753162058607, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24283307744213492, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.3290586} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23473960050470094, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9655415017087721, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.3290586} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.699971675872803, "x": 51.279343743527996, "y": 4.644176671039832, "z": null, "yaw": 1.6357367481212821, "pitch": null, "roll": null}, "v": 0.9677537694970065, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257753162058607, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24283307744213492, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.3490586} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23473960050470094, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9651367289503093, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.3490586} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.699971675872803, "x": 51.279343743527996, "y": 4.644176671039832, "z": null, "yaw": 1.6357367481212821, "pitch": null, "roll": null}, "v": 0.9677537694970065, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257753162058607, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24283307744213492, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.3690586} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23473960050470094, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9643280248111434, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.3690586} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.699971675872803, "x": 51.279343743527996, "y": 4.644176671039832, "z": null, "yaw": 1.6357367481212821, "pitch": null, "roll": null}, "v": 0.9677537694970065, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257753162058607, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24283307744213492, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.3890586} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23473960050470094, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9635204409956917, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.3890586} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502668.3990586, "x": 55.271123333442496, "y": 9.750067208471215, "z": null, "yaw": 1.6633384370638313, "pitch": null, "roll": null}, "v": 0.963117068642716, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2574317983112452, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24166961585395516, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.4090586} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24170295107522438, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9627139756911474, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.4090586} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.809971570968628, "x": 51.271123333442496, "y": 4.750067208471215, "z": null, "yaw": 1.6633384370638313, "pitch": null, "roll": null}, "v": 0.963117068642716, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2574317983112452, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24166961585395516, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.4290586} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23951083439730403, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9627787445245929, "gear": 1, "accelerator_pedal_position": 0.24170295107522438, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.4290586} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.809971570968628, "x": 51.271123333442496, "y": 4.750067208471215, "z": null, "yaw": 1.6633384370638313, "pitch": null, "roll": null}, "v": 0.963117068642716, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2574317983112452, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24166961585395516, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.4490585} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23951083439730403, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9625695039769244, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.4490585} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.809971570968628, "x": 51.271123333442496, "y": 4.750067208471215, "z": null, "yaw": 1.6633384370638313, "pitch": null, "roll": null}, "v": 0.963117068642716, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2574317983112452, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24166961585395516, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.4690585} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23951083439730403, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9623605531372617, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.4690585} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.809971570968628, "x": 51.271123333442496, "y": 4.750067208471215, "z": null, "yaw": 1.6633384370638313, "pitch": null, "roll": null}, "v": 0.963117068642716, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2574317983112452, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24166961585395516, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.4890585} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23951083439730403, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9621518915870257, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.4890585} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502668.5090585, "x": 55.260017776037174, "y": 9.85535862922868, "z": null, "yaw": 1.6909401260063806, "pitch": null, "roll": null}, "v": 0.9619435189082899, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25735052928111113, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24137514353824388, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.5090585} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23409786908396085, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9619435189082899, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.5090585} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.919971466064453, "x": 51.260017776037174, "y": 4.855358629228681, "z": null, "yaw": 1.6909401260063806, "pitch": null, "roll": null}, "v": 0.9619435189082899, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25735052928111113, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24137514353824388, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.5290585} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2357853583992781, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9610590482433748, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.5290585} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.919971466064453, "x": 51.260017776037174, "y": 4.855358629228681, "z": null, "yaw": 1.6909401260063806, "pitch": null, "roll": null}, "v": 0.9619435189082899, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25735052928111113, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24137514353824388, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.5490584} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2357853583992781, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9603866648813091, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.5490584} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.919971466064453, "x": 51.260017776037174, "y": 4.855358629228681, "z": null, "yaw": 1.6909401260063806, "pitch": null, "roll": null}, "v": 0.9619435189082899, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25735052928111113, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24137514353824388, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.5690584} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2357853583992781, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9597152119249533, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.5690584} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.919971466064453, "x": 51.260017776037174, "y": 4.855358629228681, "z": null, "yaw": 1.6909401260063806, "pitch": null, "roll": null}, "v": 0.9619435189082899, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25735052928111113, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24137514353824388, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.5890584} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2357853583992781, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.959044687906588, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.5890584} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 29.919971466064453, "x": 51.260017776037174, "y": 4.855358629228681, "z": null, "yaw": 1.6909401260063806, "pitch": null, "roll": null}, "v": 0.9619435189082899, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25735052928111113, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24137514353824388, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.6090584} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2357853583992781, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9583750913612724, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.6090584} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502668.6190584, "x": 55.24604701077133, "y": 9.9600360007538, "z": null, "yaw": 1.7185418149489298, "pitch": null, "roll": null}, "v": 0.9580406404339725, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25708045070893, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24039581592343776, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.6290584} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24002731161361224, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9577064208268381, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.6290584} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.02997136116028, "x": 51.24604701077133, "y": 4.960036000753799, "z": null, "yaw": 1.7185418149489298, "pitch": null, "roll": null}, "v": 0.9580406404339725, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25708045070893, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24039581592343776, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.6490583} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23868819642753145, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9575687356634941, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.6490583} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.02997136116028, "x": 51.24604701077133, "y": 4.960036000753799, "z": null, "yaw": 1.7185418149489298, "pitch": null, "roll": null}, "v": 0.9580406404339725, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25708045070893, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24039581592343776, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.6690583} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23868819642753145, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.957263909334495, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.6690583} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.02997136116028, "x": 51.24604701077133, "y": 4.960036000753799, "z": null, "yaw": 1.7185418149489298, "pitch": null, "roll": null}, "v": 0.9580406404339725, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25708045070893, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24039581592343776, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.6890583} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23868819642753145, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9569595044150714, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.6890583} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.02997136116028, "x": 51.24604701077133, "y": 4.960036000753799, "z": null, "yaw": 1.7185418149489298, "pitch": null, "roll": null}, "v": 0.9580406404339725, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25708045070893, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24039581592343776, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.7090583} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23868819642753145, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.95665552028559, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.7090583} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502668.7290583, "x": 55.22924192706406, "y": 10.063979682483343, "z": null, "yaw": 1.746143503891479, "pitch": null, "roll": null}, "v": 0.956351956327428, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25696368846008444, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23997208380133714, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.7290583} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25404462182484977, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9571601083068803, "gear": 1, "accelerator_pedal_position": 0.25404462182484977, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.7290583} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.139971256256104, "x": 51.22924192706406, "y": 5.0639796824833425, "z": null, "yaw": 1.746143503891479, "pitch": null, "roll": null}, "v": 0.956351956327428, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25696368846008444, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23997208380133714, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.7490582} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24923989762552284, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9579677015694865, "gear": 1, "accelerator_pedal_position": 0.25404462182484977, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.7490582} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.139971256256104, "x": 51.22924192706406, "y": 5.0639796824833425, "z": null, "yaw": 1.746143503891479, "pitch": null, "roll": null}, "v": 0.956351956327428, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25696368846008444, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23997208380133714, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.7690582} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24923989762552284, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.958980830164187, "gear": 1, "accelerator_pedal_position": 0.24923989762552284, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.7690582} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.139971256256104, "x": 51.22924192706406, "y": 5.0639796824833425, "z": null, "yaw": 1.746143503891479, "pitch": null, "roll": null}, "v": 0.956351956327428, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25696368846008444, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23997208380133714, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.7890582} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24923989762552284, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9599925575894048, "gear": 1, "accelerator_pedal_position": 0.24923989762552284, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.7890582} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.139971256256104, "x": 51.22924192706406, "y": 5.0639796824833425, "z": null, "yaw": 1.746143503891479, "pitch": null, "roll": null}, "v": 0.956351956327428, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25696368846008444, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23997208380133714, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.8090582} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24923989762552284, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9610028853736796, "gear": 1, "accelerator_pedal_position": 0.24923989762552284, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.8090582} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.139971256256104, "x": 51.22924192706406, "y": 5.0639796824833425, "z": null, "yaw": 1.746143503891479, "pitch": null, "roll": null}, "v": 0.956351956327428, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25696368846008444, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23997208380133714, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.8290582} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24923989762552284, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9620118150451348, "gear": 1, "accelerator_pedal_position": 0.24923989762552284, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.8290582} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502668.8390582, "x": 55.20952833422985, "y": 10.167653069880854, "z": null, "yaw": 1.7737451928340282, "pitch": null, "roll": null}, "v": 0.9625157560659787, "accelerator_pedal_position": 0.24923989762552284, "brake_pedal_position": 0.0, "acceleration": 0.05035920654946613, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2415187318294066, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.8490582} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23280337845074242, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9630193481314734, "gear": 1, "accelerator_pedal_position": 0.24923989762552284, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.8490582} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.24997115135193, "x": 51.20952833422985, "y": 5.1676530698808545, "z": null, "yaw": 1.7737451928340282, "pitch": null, "roll": null}, "v": 0.9625157560659787, "accelerator_pedal_position": 0.24923989762552284, "brake_pedal_position": 0.0, "acceleration": 0.05035920654946613, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2415187318294066, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.8690581} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2379611173320368, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9619716327607892, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.8690581} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.24997115135193, "x": 51.20952833422985, "y": 5.1676530698808545, "z": null, "yaw": 1.7737451928340282, "pitch": null, "roll": null}, "v": 0.9625157560659787, "accelerator_pedal_position": 0.24923989762552284, "brake_pedal_position": 0.0, "acceleration": 0.05035920654946613, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2415187318294066, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.889058} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2379611173320368, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9615698620460976, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.889058} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.24997115135193, "x": 51.20952833422985, "y": 5.1676530698808545, "z": null, "yaw": 1.7737451928340282, "pitch": null, "roll": null}, "v": 0.9625157560659787, "accelerator_pedal_position": 0.24923989762552284, "brake_pedal_position": 0.0, "acceleration": 0.05035920654946613, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2415187318294066, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.909058} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2379611173320368, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9611686474579333, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.909058} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.24997115135193, "x": 51.20952833422985, "y": 5.1676530698808545, "z": null, "yaw": 1.7737451928340282, "pitch": null, "roll": null}, "v": 0.9625157560659787, "accelerator_pedal_position": 0.24923989762552284, "brake_pedal_position": 0.0, "acceleration": 0.05035920654946613, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2415187318294066, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.929058} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2379611173320368, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.960767988162145, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.929058} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502668.949058, "x": 55.18691021985771, "y": 10.270985132356767, "z": null, "yaw": 1.8013468817765774, "pitch": null, "roll": null}, "v": 0.9603678833260035, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25724145887954086, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2409797780543432, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.949058} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24550161172161106, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9603678833260035, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.949058} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.359971046447754, "x": 51.18691021985771, "y": 5.270985132356767, "z": null, "yaw": 1.8013468817765774, "pitch": null, "roll": null}, "v": 0.9603678833260035, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25724145887954086, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2409797780543432, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.969058} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24313777093848876, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9609105677524635, "gear": 1, "accelerator_pedal_position": 0.24550161172161106, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.969058} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.359971046447754, "x": 51.18691021985771, "y": 5.270985132356767, "z": null, "yaw": 1.8013468817765774, "pitch": null, "roll": null}, "v": 0.9603678833260035, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25724145887954086, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2409797780543432, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502668.989058} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24313777093848876, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9611571233664218, "gear": 1, "accelerator_pedal_position": 0.24313777093848876, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502668.989058} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.359971046447754, "x": 51.18691021985771, "y": 5.270985132356767, "z": null, "yaw": 1.8013468817765774, "pitch": null, "roll": null}, "v": 0.9603678833260035, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25724145887954086, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2409797780543432, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.009058} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24313777093848876, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9614033377575146, "gear": 1, "accelerator_pedal_position": 0.24313777093848876, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.009058} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.359971046447754, "x": 51.18691021985771, "y": 5.270985132356767, "z": null, "yaw": 1.8013468817765774, "pitch": null, "roll": null}, "v": 0.9603678833260035, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25724145887954086, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2409797780543432, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.029058} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24313777093848876, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9616492113737404, "gear": 1, "accelerator_pedal_position": 0.24313777093848876, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.029058} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.359971046447754, "x": 51.18691021985771, "y": 5.270985132356767, "z": null, "yaw": 1.8013468817765774, "pitch": null, "roll": null}, "v": 0.9603678833260035, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25724145887954086, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2409797780543432, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.049058} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24313777093848876, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9618947446625778, "gear": 1, "accelerator_pedal_position": 0.24313777093848876, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.049058} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502669.059058, "x": 55.16145889775232, "y": 10.373609210269073, "z": null, "yaw": 1.8289485707191266, "pitch": null, "roll": null}, "v": 0.9620173838239212, "accelerator_pedal_position": 0.24313777093848876, "brake_pedal_position": 0.0, "acceleration": 0.012255424706564433, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24139367805119868, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.069058} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2346232616272794, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9621399380709869, "gear": 1, "accelerator_pedal_position": 0.24313777093848876, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.069058} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.46997094154358, "x": 51.16145889775232, "y": 5.373609210269073, "z": null, "yaw": 1.8289485707191266, "pitch": null, "roll": null}, "v": 0.9620173838239212, "accelerator_pedal_position": 0.24313777093848876, "brake_pedal_position": 0.0, "acceleration": 0.012255424706564433, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24139367805119868, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.089058} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23728975677429526, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9613208468465071, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.089058} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.46997094154358, "x": 51.16145889775232, "y": 5.373609210269073, "z": null, "yaw": 1.8289485707191266, "pitch": null, "roll": null}, "v": 0.9620173838239212, "accelerator_pedal_position": 0.24313777093848876, "brake_pedal_position": 0.0, "acceleration": 0.012255424706564433, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24139367805119868, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.109058} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23728975677429526, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9608360858858702, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.109058} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.46997094154358, "x": 51.16145889775232, "y": 5.373609210269073, "z": null, "yaw": 1.8289485707191266, "pitch": null, "roll": null}, "v": 0.9620173838239212, "accelerator_pedal_position": 0.24313777093848876, "brake_pedal_position": 0.0, "acceleration": 0.012255424706564433, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24139367805119868, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.129058} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23728975677429526, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.960351995787768, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.129058} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.46997094154358, "x": 51.16145889775232, "y": 5.373609210269073, "z": null, "yaw": 1.8289485707191266, "pitch": null, "roll": null}, "v": 0.9620173838239212, "accelerator_pedal_position": 0.24313777093848876, "brake_pedal_position": 0.0, "acceleration": 0.012255424706564433, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24139367805119868, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.1490579} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23728975677429526, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9598685755300862, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.1490579} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502669.1690578, "x": 55.13319668289231, "y": 10.475453926419348, "z": null, "yaw": 1.8565502596616759, "pitch": null, "roll": null}, "v": 0.9593858240925143, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25717350279932244, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2407333553862893, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.1690578} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23511485989956254, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9593858240925143, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.1690578} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.579970836639404, "x": 51.13319668289231, "y": 5.475453926419348, "z": null, "yaw": 1.8565502596616759, "pitch": null, "roll": null}, "v": 0.9593858240925143, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25717350279932244, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2407333553862893, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.1890578} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23578540856957908, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.958631972386389, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.1890578} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.579970836639404, "x": 51.13319668289231, "y": 5.475453926419348, "z": null, "yaw": 1.8565502596616759, "pitch": null, "roll": null}, "v": 0.9593858240925143, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25717350279932244, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2407333553862893, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.2090578} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23578540856957908, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9579629528915805, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.2090578} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.579970836639404, "x": 51.13319668289231, "y": 5.475453926419348, "z": null, "yaw": 1.8565502596616759, "pitch": null, "roll": null}, "v": 0.9593858240925143, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25717350279932244, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2407333553862893, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.2290578} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23578540856957908, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9572948584993742, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.2290578} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.579970836639404, "x": 51.13319668289231, "y": 5.475453926419348, "z": null, "yaw": 1.8565502596616759, "pitch": null, "roll": null}, "v": 0.9593858240925143, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25717350279932244, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2407333553862893, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.2490578} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23578540856957908, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9566276877520842, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.2490578} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.579970836639404, "x": 51.13319668289231, "y": 5.475453926419348, "z": null, "yaw": 1.8565502596616759, "pitch": null, "roll": null}, "v": 0.9593858240925143, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25717350279932244, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2407333553862893, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.2690578} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23578540856957908, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9559614391947798, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.2690578} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502669.2790577, "x": 55.10223940101324, "y": 10.576139476625483, "z": null, "yaw": 1.884151948604225, "pitch": null, "roll": null}, "v": 0.9556286602834584, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2569136943777245, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2397905911429824, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.2890577} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24036893444791338, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9552961113752798, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.2890577} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.68997073173523, "x": 51.10223940101324, "y": 5.5761394766254835, "z": null, "yaw": 1.884151948604225, "pitch": null, "roll": null}, "v": 0.9556286602834584, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2569136943777245, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2397905911429824, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.3090577} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23892359124221316, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9552044456217816, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.3090577} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.68997073173523, "x": 51.10223940101324, "y": 5.5761394766254835, "z": null, "yaw": 1.884151948604225, "pitch": null, "roll": null}, "v": 0.9556286602834584, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2569136943777245, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2397905911429824, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.3290577} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23892359124221316, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9549323010370149, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.3290577} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.68997073173523, "x": 51.10223940101324, "y": 5.5761394766254835, "z": null, "yaw": 1.884151948604225, "pitch": null, "roll": null}, "v": 0.9556286602834584, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2569136943777245, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2397905911429824, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.3490577} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23892359124221316, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9546605324261596, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.3490577} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.68997073173523, "x": 51.10223940101324, "y": 5.5761394766254835, "z": null, "yaw": 1.884151948604225, "pitch": null, "roll": null}, "v": 0.9556286602834584, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2569136943777245, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2397905911429824, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.3690577} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23892359124221316, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9543891392402662, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.3690577} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502669.3890576, "x": 55.068610827096464, "y": 10.675647443335077, "z": null, "yaw": 1.9117536375467743, "pitch": null, "roll": null}, "v": 0.954118120931266, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2568093199334574, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2394115598944852, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.3890576} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24517867781166175, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.954118120931266, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.3890576} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.799970626831055, "x": 51.068610827096464, "y": 5.675647443335077, "z": null, "yaw": 1.9117536375467743, "pitch": null, "roll": null}, "v": 0.954118120931266, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2568093199334574, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2394115598944852, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.4090576} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24321874325146248, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9546290926958527, "gear": 1, "accelerator_pedal_position": 0.24517867781166175, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.4090576} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.799970626831055, "x": 51.068610827096464, "y": 5.675647443335077, "z": null, "yaw": 1.9117536375467743, "pitch": null, "roll": null}, "v": 0.954118120931266, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2568093199334574, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2394115598944852, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.4290576} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24321874325146248, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9548944514636113, "gear": 1, "accelerator_pedal_position": 0.24321874325146248, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.4290576} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.799970626831055, "x": 51.068610827096464, "y": 5.675647443335077, "z": null, "yaw": 1.9117536375467743, "pitch": null, "roll": null}, "v": 0.954118120931266, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2568093199334574, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2394115598944852, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.4490576} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24321874325146248, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9551594436504911, "gear": 1, "accelerator_pedal_position": 0.24321874325146248, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.4490576} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.799970626831055, "x": 51.068610827096464, "y": 5.675647443335077, "z": null, "yaw": 1.9117536375467743, "pitch": null, "roll": null}, "v": 0.954118120931266, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2568093199334574, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2394115598944852, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.4690576} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24321874325146248, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9554240697348282, "gear": 1, "accelerator_pedal_position": 0.24321874325146248, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.4690576} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.799970626831055, "x": 51.068610827096464, "y": 5.675647443335077, "z": null, "yaw": 1.9117536375467743, "pitch": null, "roll": null}, "v": 0.954118120931266, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2568093199334574, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2394115598944852, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.4890575} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24321874325146248, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.955688330194414, "gear": 1, "accelerator_pedal_position": 0.24321874325146248, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.4890575} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502669.4990575, "x": 55.03224492590729, "y": 10.774197782836119, "z": null, "yaw": 1.9393553264893235, "pitch": null, "roll": null}, "v": 0.9558203234640862, "accelerator_pedal_position": 0.24321874325146248, "brake_pedal_position": 0.0, "acceleration": 0.01319020424096623, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23983868412019538, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.5090575} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2590354657561024, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9559522255064958, "gear": 1, "accelerator_pedal_position": 0.24321874325146248, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.5090575} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.90997052192688, "x": 51.03224492590729, "y": 5.774197782836119, "z": null, "yaw": 1.9393553264893235, "pitch": null, "roll": null}, "v": 0.9558203234640862, "accelerator_pedal_position": 0.24321874325146248, "brake_pedal_position": 0.0, "acceleration": 0.01319020424096623, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23983868412019538, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.5290575} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2540986177939135, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9581921630641083, "gear": 1, "accelerator_pedal_position": 0.2590354657561024, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.5290575} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.90997052192688, "x": 51.03224492590729, "y": 5.774197782836119, "z": null, "yaw": 1.9393553264893235, "pitch": null, "roll": null}, "v": 0.9558203234640862, "accelerator_pedal_position": 0.24321874325146248, "brake_pedal_position": 0.0, "acceleration": 0.01319020424096623, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23983868412019538, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.5490575} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2540986177939135, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9598121112123408, "gear": 1, "accelerator_pedal_position": 0.2540986177939135, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.5490575} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.90997052192688, "x": 51.03224492590729, "y": 5.774197782836119, "z": null, "yaw": 1.9393553264893235, "pitch": null, "roll": null}, "v": 0.9558203234640862, "accelerator_pedal_position": 0.24321874325146248, "brake_pedal_position": 0.0, "acceleration": 0.01319020424096623, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23983868412019538, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.5690575} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2540986177939135, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9614298185120671, "gear": 1, "accelerator_pedal_position": 0.2540986177939135, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.5690575} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 30.90997052192688, "x": 51.03224492590729, "y": 5.774197782836119, "z": null, "yaw": 1.9393553264893235, "pitch": null, "roll": null}, "v": 0.9558203234640862, "accelerator_pedal_position": 0.24321874325146248, "brake_pedal_position": 0.0, "acceleration": 0.01319020424096623, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23983868412019538, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.5890574} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2540986177939135, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9630452870165885, "gear": 1, "accelerator_pedal_position": 0.2540986177939135, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.5890574} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502669.6090574, "x": 54.99297746932043, "y": 10.872189979938453, "z": null, "yaw": 1.9669570154318727, "pitch": null, "roll": null}, "v": 0.964658518780709, "accelerator_pedal_position": 0.2540986177939135, "brake_pedal_position": 0.0, "acceleration": 0.08057777469436206, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24205640337422182, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.6090574} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.231504574436293, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.964658518780709, "gear": 1, "accelerator_pedal_position": 0.2540986177939135, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.6090574} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.019970417022705, "x": 50.99297746932043, "y": 5.872189979938453, "z": null, "yaw": 1.9669570154318727, "pitch": null, "roll": null}, "v": 0.964658518780709, "accelerator_pedal_position": 0.2540986177939135, "brake_pedal_position": 0.0, "acceleration": 0.08057777469436206, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24205640337422182, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.6290574} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2385957999067653, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.963121734422241, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.6290574} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.019970417022705, "x": 50.99297746932043, "y": 5.872189979938453, "z": null, "yaw": 1.9669570154318727, "pitch": null, "roll": null}, "v": 0.964658518780709, "accelerator_pedal_position": 0.2540986177939135, "brake_pedal_position": 0.0, "acceleration": 0.08057777469436206, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24205640337422182, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.6490574} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2385957999067653, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9629596507016711, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.6490574} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.019970417022705, "x": 50.99297746932043, "y": 5.872189979938453, "z": null, "yaw": 1.9669570154318727, "pitch": null, "roll": null}, "v": 0.964658518780709, "accelerator_pedal_position": 0.2540986177939135, "brake_pedal_position": 0.0, "acceleration": 0.08057777469436206, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24205640337422182, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.6690574} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2385957999067653, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9627976792416052, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.6690574} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.019970417022705, "x": 50.99297746932043, "y": 5.872189979938453, "z": null, "yaw": 1.9669570154318727, "pitch": null, "roll": null}, "v": 0.964658518780709, "accelerator_pedal_position": 0.2540986177939135, "brake_pedal_position": 0.0, "acceleration": 0.08057777469436206, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24205640337422182, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.6890574} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2385957999067653, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9621509143473805, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.6890574} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.019970417022705, "x": 50.99297746932043, "y": 5.872189979938453, "z": null, "yaw": 1.9669570154318727, "pitch": null, "roll": null}, "v": 0.964658518780709, "accelerator_pedal_position": 0.2540986177939135, "brake_pedal_position": 0.0, "acceleration": 0.08057777469436206, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24205640337422182, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.7090573} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2385957999067653, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9618282033085036, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.7090573} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502669.7190573, "x": 54.95087677224477, "y": 10.969400482561571, "z": null, "yaw": 1.994558704374422, "pitch": null, "roll": null}, "v": 0.9619895029461817, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2573537131850955, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24138668205742767, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.7390573} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2338595657836149, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9612099243607127, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.7390573} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.12997031211853, "x": 50.95087677224477, "y": 5.969400482561571, "z": null, "yaw": 1.994558704374422, "pitch": null, "roll": null}, "v": 0.9619895029461817, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2573537131850955, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24138668205742767, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.7590573} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23533039624482588, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9607531498081393, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.7590573} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.12997031211853, "x": 50.95087677224477, "y": 5.969400482561571, "z": null, "yaw": 1.994558704374422, "pitch": null, "roll": null}, "v": 0.9619895029461817, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2573537131850955, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24138668205742767, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.7790573} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23533039624482588, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9600243391633602, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.7790573} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.12997031211853, "x": 50.95087677224477, "y": 5.969400482561571, "z": null, "yaw": 1.994558704374422, "pitch": null, "roll": null}, "v": 0.9619895029461817, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2573537131850955, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24138668205742767, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.7990572} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23533039624482588, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9592965369037009, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.7990572} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.12997031211853, "x": 50.95087677224477, "y": 5.969400482561571, "z": null, "yaw": 1.994558704374422, "pitch": null, "roll": null}, "v": 0.9619895029461817, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2573537131850955, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24138668205742767, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.8190572} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23533039624482588, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9585697414221509, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.8190572} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23533039624482588, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9571191643808388, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.8290572} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502669.8290572, "x": 54.90623460202116, "y": 11.065144205310764, "z": null, "yaw": 2.022160393316969, "pitch": null, "roll": null}, "v": 0.9582067207218244, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25709193723245594, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2404374895274812, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.8590572} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2417162430731421, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9571191643808388, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.8590572} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.239970207214355, "x": 50.90623460202116, "y": 6.065144205310764, "z": null, "yaw": 2.022160393316969, "pitch": null, "roll": null}, "v": 0.9582067207218244, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25709193723245594, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2404374895274812, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.8790572} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23970757582467642, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.957016405546886, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.8790572} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.239970207214355, "x": 50.90623460202116, "y": 6.065144205310764, "z": null, "yaw": 2.022160393316969, "pitch": null, "roll": null}, "v": 0.9582067207218244, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25709193723245594, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2404374895274812, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.8990571} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23970757582467642, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9569280327931063, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.8990571} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.239970207214355, "x": 50.90623460202116, "y": 6.065144205310764, "z": null, "yaw": 2.022160393316969, "pitch": null, "roll": null}, "v": 0.9582067207218244, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25709193723245594, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2404374895274812, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.9190571} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23970757582467642, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9568397211397576, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.9190571} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502669.939057, "x": 54.85912165671652, "y": 11.15930899112701, "z": null, "yaw": 2.049762082259516, "pitch": null, "roll": null}, "v": 0.956663280959167, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25698521037931393, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24005020276175, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.939057} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23438921664018705, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.956663280959167, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.939057} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.34997010231018, "x": 50.85912165671652, "y": 6.159308991127009, "z": null, "yaw": 2.049762082259516, "pitch": null, "roll": null}, "v": 0.956663280959167, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25698521037931393, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24005020276175, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.959057} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23604586862886856, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9558225195373206, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.959057} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.34997010231018, "x": 50.85912165671652, "y": 6.159308991127009, "z": null, "yaw": 2.049762082259516, "pitch": null, "roll": null}, "v": 0.956663280959167, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25698521037931393, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24005020276175, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502669.979057} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23604586862886856, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9539273714403664, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502669.979057} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.34997010231018, "x": 50.85912165671652, "y": 6.159308991127009, "z": null, "yaw": 2.049762082259516, "pitch": null, "roll": null}, "v": 0.956663280959167, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25698521037931393, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24005020276175, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.019057} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23604586862886856, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9536122768009522, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.019057} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.34997010231018, "x": 50.85912165671652, "y": 6.159308991127009, "z": null, "yaw": 2.049762082259516, "pitch": null, "roll": null}, "v": 0.956663280959167, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25698521037931393, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24005020276175, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.039057} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23604586862886856, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9526682981193733, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.039057} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502670.049057, "x": 54.80954970058305, "y": 11.25191133823656, "z": null, "yaw": 2.0773637712020627, "pitch": null, "roll": null}, "v": 0.9529827403105572, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2567308980488261, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.239126665142447, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.059057} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2422452397966766, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9526682981193733, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.059057} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.459969997406006, "x": 50.80954970058305, "y": 6.25191133823656, "z": null, "yaw": 2.0773637712020627, "pitch": null, "roll": null}, "v": 0.9529827403105572, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2567308980488261, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.239126665142447, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.079057} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2402952194116792, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9528878533853967, "gear": 1, "accelerator_pedal_position": 0.2422452397966766, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.079057} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.459969997406006, "x": 50.80954970058305, "y": 6.25191133823656, "z": null, "yaw": 2.0773637712020627, "pitch": null, "roll": null}, "v": 0.9529827403105572, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2567308980488261, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.239126665142447, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.099057} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2402952194116792, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9528390611458211, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.099057} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.459969997406006, "x": 50.80954970058305, "y": 6.25191133823656, "z": null, "yaw": 2.0773637712020627, "pitch": null, "roll": null}, "v": 0.9529827403105572, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2567308980488261, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.239126665142447, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.119057} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2402952194116792, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.95274157772669, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.119057} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.459969997406006, "x": 50.80954970058305, "y": 6.25191133823656, "z": null, "yaw": 2.0773637712020627, "pitch": null, "roll": null}, "v": 0.9529827403105572, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2567308980488261, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.239126665142447, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.139057} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2402952194116792, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.95254701446428, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.139057} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502670.159057, "x": 54.75755700338367, "y": 11.342905534800188, "z": null, "yaw": 2.1049654601446095, "pitch": null, "roll": null}, "v": 0.95254701446428, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2567008088708621, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23901733087632726, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.159057} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24187893620002393, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.95254701446428, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.159057} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.56996989250183, "x": 50.75755700338367, "y": 6.342905534800188, "z": null, "yaw": 2.1049654601446095, "pitch": null, "roll": null}, "v": 0.95254701446428, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2567008088708621, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23901733087632726, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.179057} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24138251991929213, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9527057798304825, "gear": 1, "accelerator_pedal_position": 0.24138251991929213, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.179057} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.56996989250183, "x": 50.75755700338367, "y": 6.342905534800188, "z": null, "yaw": 2.1049654601446095, "pitch": null, "roll": null}, "v": 0.95254701446428, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2567008088708621, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23901733087632726, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.2090569} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24138251991929213, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9527057798304825, "gear": 1, "accelerator_pedal_position": 0.24138251991929213, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.2090569} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.56996989250183, "x": 50.75755700338367, "y": 6.342905534800188, "z": null, "yaw": 2.1049654601446095, "pitch": null, "roll": null}, "v": 0.95254701446428, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2567008088708621, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23901733087632726, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.2290568} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24138251991929213, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9527636092025897, "gear": 1, "accelerator_pedal_position": 0.24138251991929213, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.2290568} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.56996989250183, "x": 50.75755700338367, "y": 6.342905534800188, "z": null, "yaw": 2.1049654601446095, "pitch": null, "roll": null}, "v": 0.95254701446428, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2567008088708621, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23901733087632726, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.2490568} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24138251991929213, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9528020955912275, "gear": 1, "accelerator_pedal_position": 0.24138251991929213, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.2490568} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502670.2690568, "x": 54.703076519506574, "y": 11.432423874158975, "z": null, "yaw": 2.1325671490871563, "pitch": null, "roll": null}, "v": 0.9528213188550514, "accelerator_pedal_position": 0.24138251991929213, "brake_pedal_position": 0.0, "acceleration": 0.0019209988961763624, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23908616055332405, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.2690568} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23711395599300314, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9528405288440132, "gear": 1, "accelerator_pedal_position": 0.24138251991929213, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.2690568} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.679969787597656, "x": 50.703076519506574, "y": 6.4324238741589745, "z": null, "yaw": 2.1325671490871563, "pitch": null, "roll": null}, "v": 0.9528213188550514, "accelerator_pedal_position": 0.24138251991929213, "brake_pedal_position": 0.0, "acceleration": 0.0019209988961763624, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23908616055332405, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.2890568} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23844883018160704, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9523455227702198, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.2890568} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.679969787597656, "x": 50.703076519506574, "y": 6.4324238741589745, "z": null, "yaw": 2.1325671490871563, "pitch": null, "roll": null}, "v": 0.9528213188550514, "accelerator_pedal_position": 0.24138251991929213, "brake_pedal_position": 0.0, "acceleration": 0.0019209988961763624, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23908616055332405, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.3090568} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23844883018160704, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.952181705695711, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.3090568} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.679969787597656, "x": 50.703076519506574, "y": 6.4324238741589745, "z": null, "yaw": 2.1325671490871563, "pitch": null, "roll": null}, "v": 0.9528213188550514, "accelerator_pedal_position": 0.24138251991929213, "brake_pedal_position": 0.0, "acceleration": 0.0019209988961763624, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23908616055332405, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.3290567} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23844883018160704, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9516909327860951, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.3290567} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.679969787597656, "x": 50.703076519506574, "y": 6.4324238741589745, "z": null, "yaw": 2.1325671490871563, "pitch": null, "roll": null}, "v": 0.9528213188550514, "accelerator_pedal_position": 0.24138251991929213, "brake_pedal_position": 0.0, "acceleration": 0.0019209988961763624, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23908616055332405, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.3490567} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23844883018160704, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9515275676428977, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.3490567} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.679969787597656, "x": 50.703076519506574, "y": 6.4324238741589745, "z": null, "yaw": 2.1325671490871563, "pitch": null, "roll": null}, "v": 0.9528213188550514, "accelerator_pedal_position": 0.24138251991929213, "brake_pedal_position": 0.0, "acceleration": 0.0019209988961763624, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23908616055332405, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.3690567} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23844883018160704, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9512011755969039, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.3690567} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502670.3790567, "x": 54.64618597792596, "y": 11.5203441358152, "z": null, "yaw": 2.160168838029703, "pitch": null, "roll": null}, "v": 0.9510381485278102, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25659664302594254, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23863871952874136, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.3890567} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2434090894178821, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9507124318821993, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.3890567} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.78996968269348, "x": 50.64618597792596, "y": 6.520344135815201, "z": null, "yaw": 2.160168838029703, "pitch": null, "roll": null}, "v": 0.9510381485278102, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25659664302594254, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23863871952874136, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.4090567} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24185285200752454, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9508597583420624, "gear": 1, "accelerator_pedal_position": 0.2434090894178821, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.4090567} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.78996968269348, "x": 50.64618597792596, "y": 6.520344135815201, "z": null, "yaw": 2.160168838029703, "pitch": null, "roll": null}, "v": 0.9510381485278102, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25659664302594254, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23863871952874136, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.4290566} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24185285200752454, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9510095347516458, "gear": 1, "accelerator_pedal_position": 0.24185285200752454, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.4290566} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.78996968269348, "x": 50.64618597792596, "y": 6.520344135815201, "z": null, "yaw": 2.160168838029703, "pitch": null, "roll": null}, "v": 0.9510381485278102, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25659664302594254, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23863871952874136, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.4490566} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24185285200752454, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9510593913212214, "gear": 1, "accelerator_pedal_position": 0.24185285200752454, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.4490566} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.78996968269348, "x": 50.64618597792596, "y": 6.520344135815201, "z": null, "yaw": 2.160168838029703, "pitch": null, "roll": null}, "v": 0.9510381485278102, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25659664302594254, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23863871952874136, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.4690566} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24185285200752454, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9511590012495831, "gear": 1, "accelerator_pedal_position": 0.24185285200752454, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.4690566} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502670.4890566, "x": 54.586955527586525, "y": 11.606565417077631, "z": null, "yaw": 2.18777052697225, "pitch": null, "roll": null}, "v": 0.9512584737185125, "accelerator_pedal_position": 0.24185285200752454, "brake_pedal_position": 0.0, "acceleration": 0.004968474522889954, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23869400450492292, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.4890566} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23507388227415385, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9513081584637414, "gear": 1, "accelerator_pedal_position": 0.24185285200752454, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.4890566} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.899969577789307, "x": 50.586955527586525, "y": 6.606565417077631, "z": null, "yaw": 2.18777052697225, "pitch": null, "roll": null}, "v": 0.9512584737185125, "accelerator_pedal_position": 0.24185285200752454, "brake_pedal_position": 0.0, "acceleration": 0.004968474522889954, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23869400450492292, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.5090566} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23719307208019108, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9505603463152034, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.5090566} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.899969577789307, "x": 50.586955527586525, "y": 6.606565417077631, "z": null, "yaw": 2.18777052697225, "pitch": null, "roll": null}, "v": 0.9512584737185125, "accelerator_pedal_position": 0.24185285200752454, "brake_pedal_position": 0.0, "acceleration": 0.004968474522889954, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23869400450492292, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.5290565} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23719307208019108, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9500783733437889, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.5290565} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.899969577789307, "x": 50.586955527586525, "y": 6.606565417077631, "z": null, "yaw": 2.18777052697225, "pitch": null, "roll": null}, "v": 0.9512584737185125, "accelerator_pedal_position": 0.24185285200752454, "brake_pedal_position": 0.0, "acceleration": 0.004968474522889954, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23869400450492292, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.5490565} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23719307208019108, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9498376362705794, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.5490565} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.899969577789307, "x": 50.586955527586525, "y": 6.606565417077631, "z": null, "yaw": 2.18777052697225, "pitch": null, "roll": null}, "v": 0.9512584737185125, "accelerator_pedal_position": 0.24185285200752454, "brake_pedal_position": 0.0, "acceleration": 0.004968474522889954, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23869400450492292, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.5690565} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23719307208019108, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9491164211856492, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.5690565} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 31.899969577789307, "x": 50.586955527586525, "y": 6.606565417077631, "z": null, "yaw": 2.18777052697225, "pitch": null, "roll": null}, "v": 0.9512584737185125, "accelerator_pedal_position": 0.24185285200752454, "brake_pedal_position": 0.0, "acceleration": 0.004968474522889954, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23869400450492292, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.5890565} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23719307208019108, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9486364399807549, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.5890565} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502670.5990565, "x": 54.5254255862397, "y": 11.69104160526827, "z": null, "yaw": 2.2153722159147966, "pitch": null, "roll": null}, "v": 0.9486364399807549, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25643093295163133, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23803607214468242, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.6090565} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24272920320561145, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9481571206828218, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.6090565} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.00996947288513, "x": 50.5254255862397, "y": 6.6910416052682695, "z": null, "yaw": 2.2153722159147966, "pitch": null, "roll": null}, "v": 0.9486364399807549, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25643093295163133, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23803607214468242, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.6290565} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2409901152100573, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9482637171302809, "gear": 1, "accelerator_pedal_position": 0.24272920320561145, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.6290565} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.00996947288513, "x": 50.5254255862397, "y": 6.6910416052682695, "z": null, "yaw": 2.2153722159147966, "pitch": null, "roll": null}, "v": 0.9486364399807549, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25643093295163133, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23803607214468242, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.6490564} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2409901152100573, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9482572114220442, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.6490564} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.00996947288513, "x": 50.5254255862397, "y": 6.6910416052682695, "z": null, "yaw": 2.2153722159147966, "pitch": null, "roll": null}, "v": 0.9486364399807549, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25643093295163133, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23803607214468242, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.6690564} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2409901152100573, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9482528817575708, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.6690564} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.00996947288513, "x": 50.5254255862397, "y": 6.6910416052682695, "z": null, "yaw": 2.2153722159147966, "pitch": null, "roll": null}, "v": 0.9486364399807549, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25643093295163133, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23803607214468242, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.6890564} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2409901152100573, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9482485580629512, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.6890564} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502670.7090564, "x": 54.46170937077643, "y": 11.773628735777631, "z": null, "yaw": 2.2429739048573434, "pitch": null, "roll": null}, "v": 0.9482463984517614, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2564040322443555, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23793820119051923, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.7090564} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24564679386461996, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9482442403299465, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.7090564} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.11996936798096, "x": 50.46170937077643, "y": 6.773628735777631, "z": null, "yaw": 2.2429739048573434, "pitch": null, "roll": null}, "v": 0.9482463984517614, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2564040322443555, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23793820119051923, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.7290564} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24419023579471144, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9488218126567377, "gear": 1, "accelerator_pedal_position": 0.24564679386461996, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.7290564} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.11996936798096, "x": 50.46170937077643, "y": 6.773628735777631, "z": null, "yaw": 2.2429739048573434, "pitch": null, "roll": null}, "v": 0.9482463984517614, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2564040322443555, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23793820119051923, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.7490563} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24419023579471144, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9490192652043615, "gear": 1, "accelerator_pedal_position": 0.24419023579471144, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.7490563} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.11996936798096, "x": 50.46170937077643, "y": 6.773628735777631, "z": null, "yaw": 2.2429739048573434, "pitch": null, "roll": null}, "v": 0.9482463984517614, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2564040322443555, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23793820119051923, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.7690563} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24419023579471144, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9496108059940488, "gear": 1, "accelerator_pedal_position": 0.24419023579471144, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.7690563} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.11996936798096, "x": 50.46170937077643, "y": 6.773628735777631, "z": null, "yaw": 2.2429739048573434, "pitch": null, "roll": null}, "v": 0.9482463984517614, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2564040322443555, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23793820119051923, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.7890563} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24419023579471144, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9500044866705679, "gear": 1, "accelerator_pedal_position": 0.24419023579471144, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.7890563} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.11996936798096, "x": 50.46170937077643, "y": 6.773628735777631, "z": null, "yaw": 2.2429739048573434, "pitch": null, "roll": null}, "v": 0.9482463984517614, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2564040322443555, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23793820119051923, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.8090563} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24419023579471144, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9503976242699718, "gear": 1, "accelerator_pedal_position": 0.24419023579471144, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.8090563} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502670.8190563, "x": 54.3956752016473, "y": 11.854502089755112, "z": null, "yaw": 2.27057559379989, "pitch": null, "roll": null}, "v": 0.9503976242699718, "accelerator_pedal_position": 0.24419023579471144, "brake_pedal_position": 0.0, "acceleration": 0.01963653606126775, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23847799633487762, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.8290563} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2367765858357609, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9507902194796264, "gear": 1, "accelerator_pedal_position": 0.24419023579471144, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.8290563} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.22996926307678, "x": 50.3956752016473, "y": 6.854502089755112, "z": null, "yaw": 2.27057559379989, "pitch": null, "roll": null}, "v": 0.9503976242699718, "accelerator_pedal_position": 0.24419023579471144, "brake_pedal_position": 0.0, "acceleration": 0.01963653606126775, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23847799633487762, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.8490562} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23910077324235512, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9505229607804758, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.8490562} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.22996926307678, "x": 50.3956752016473, "y": 6.854502089755112, "z": null, "yaw": 2.27057559379989, "pitch": null, "roll": null}, "v": 0.9503976242699718, "accelerator_pedal_position": 0.24419023579471144, "brake_pedal_position": 0.0, "acceleration": 0.01963653606126775, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23847799633487762, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.8690562} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23910077324235512, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.950157775277314, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.8690562} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.22996926307678, "x": 50.3956752016473, "y": 6.854502089755112, "z": null, "yaw": 2.27057559379989, "pitch": null, "roll": null}, "v": 0.9503976242699718, "accelerator_pedal_position": 0.24419023579471144, "brake_pedal_position": 0.0, "acceleration": 0.01963653606126775, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23847799633487762, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.8890562} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23910077324235512, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9499147380768778, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.8890562} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.22996926307678, "x": 50.3956752016473, "y": 6.854502089755112, "z": null, "yaw": 2.27057559379989, "pitch": null, "roll": null}, "v": 0.9503976242699718, "accelerator_pedal_position": 0.24419023579471144, "brake_pedal_position": 0.0, "acceleration": 0.01963653606126775, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23847799633487762, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.9090562} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23910077324235512, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9496720361496898, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.9090562} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502670.9290562, "x": 54.327360089310055, "y": 11.9336093431591, "z": null, "yaw": 2.298177282742437, "pitch": null, "roll": null}, "v": 0.9495508107616376, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2564940079602627, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23826551012533773, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.9290562} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24164728048732473, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9494296690096822, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.9290562} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.33996915817261, "x": 50.327360089310055, "y": 6.9336093431591, "z": null, "yaw": 2.298177282742437, "pitch": null, "roll": null}, "v": 0.9495508107616376, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2564940079602627, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23826551012533773, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.9490561} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24084857496482878, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9495058397785264, "gear": 1, "accelerator_pedal_position": 0.24164728048732473, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.9490561} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.33996915817261, "x": 50.327360089310055, "y": 6.9336093431591, "z": null, "yaw": 2.298177282742437, "pitch": null, "roll": null}, "v": 0.9495508107616376, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2564940079602627, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23826551012533773, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.9690561} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24084857496482878, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9494702449909456, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.9690561} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.33996915817261, "x": 50.327360089310055, "y": 6.9336093431591, "z": null, "yaw": 2.298177282742437, "pitch": null, "roll": null}, "v": 0.9495508107616376, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2564940079602627, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23826551012533773, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502670.989056} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24084857496482878, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9494347238225749, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502670.989056} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.33996915817261, "x": 50.327360089310055, "y": 6.9336093431591, "z": null, "yaw": 2.298177282742437, "pitch": null, "roll": null}, "v": 0.9495508107616376, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2564940079602627, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23826551012533773, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.019056} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24084857496482878, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9494347238225749, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.019056} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502671.039056, "x": 54.256944209287575, "y": 12.01073891650125, "z": null, "yaw": 2.3257789716849837, "pitch": null, "roll": null}, "v": 0.9494110838676438, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2564843682550896, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23823044923202025, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.049056} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23767430071148346, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9493992761203948, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.049056} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.44996905326843, "x": 50.256944209287575, "y": 7.01073891650125, "z": null, "yaw": 2.3257789716849837, "pitch": null, "roll": null}, "v": 0.9494110838676438, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2564843682550896, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23823044923202025, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.069056} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23866578008045974, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9489790376387408, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.069056} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.44996905326843, "x": 50.256944209287575, "y": 7.01073891650125, "z": null, "yaw": 2.3257789716849837, "pitch": null, "roll": null}, "v": 0.9494110838676438, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2564843682550896, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23823044923202025, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.089056} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23866578008045974, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.948535540535437, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.089056} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.44996905326843, "x": 50.256944209287575, "y": 7.01073891650125, "z": null, "yaw": 2.3257789716849837, "pitch": null, "roll": null}, "v": 0.9494110838676438, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2564843682550896, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23823044923202025, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.109056} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23866578008045974, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9483879120530321, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.109056} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.44996905326843, "x": 50.256944209287575, "y": 7.01073891650125, "z": null, "yaw": 2.3257789716849837, "pitch": null, "roll": null}, "v": 0.9494110838676438, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2564843682550896, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23823044923202025, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.129056} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23866578008045974, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9480929604683476, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.129056} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502671.149056, "x": 54.184485599229745, "y": 12.085835106639463, "z": null, "yaw": 2.3533806606275305, "pitch": null, "roll": null}, "v": 0.9477984155602814, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2563731391433999, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23782579133213547, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.149056} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24596371201176898, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9477984155602814, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.149056} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.55996894836426, "x": 50.184485599229745, "y": 7.085835106639463, "z": null, "yaw": 2.3533806606275305, "pitch": null, "roll": null}, "v": 0.9477984155602814, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2563731391433999, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23782579133213547, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.169056} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24367754532872266, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9484162036949743, "gear": 1, "accelerator_pedal_position": 0.24596371201176898, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.169056} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.55996894836426, "x": 50.184485599229745, "y": 7.085835106639463, "z": null, "yaw": 2.3533806606275305, "pitch": null, "roll": null}, "v": 0.9477984155602814, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2563731391433999, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23782579133213547, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.189056} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24367754532872266, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9487474677225071, "gear": 1, "accelerator_pedal_position": 0.24367754532872266, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.189056} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.55996894836426, "x": 50.184485599229745, "y": 7.085835106639463, "z": null, "yaw": 2.3533806606275305, "pitch": null, "roll": null}, "v": 0.9477984155602814, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2563731391433999, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23782579133213547, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.209056} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24367754532872266, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9490782749402195, "gear": 1, "accelerator_pedal_position": 0.24367754532872266, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.209056} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.55996894836426, "x": 50.184485599229745, "y": 7.085835106639463, "z": null, "yaw": 2.3533806606275305, "pitch": null, "roll": null}, "v": 0.9477984155602814, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2563731391433999, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23782579133213547, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.229056} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24367754532872266, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9494086259342895, "gear": 1, "accelerator_pedal_position": 0.24367754532872266, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.229056} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.55996894836426, "x": 50.184485599229745, "y": 7.085835106639463, "z": null, "yaw": 2.3533806606275305, "pitch": null, "roll": null}, "v": 0.9477984155602814, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2563731391433999, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23782579133213547, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.2490559} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24367754532872266, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9497385212902678, "gear": 1, "accelerator_pedal_position": 0.24367754532872266, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.2490559} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502671.2590559, "x": 54.109967771378855, "y": 12.158915686747338, "z": null, "yaw": 2.3809823495700773, "pitch": null, "roll": null}, "v": 0.9499032982867855, "accelerator_pedal_position": 0.24367754532872266, "brake_pedal_position": 0.0, "acceleration": 0.016466330629216097, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.238353957861931, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.2690558} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2453367610916796, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9500679615930777, "gear": 1, "accelerator_pedal_position": 0.24367754532872266, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.2690558} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.66996884346008, "x": 50.109967771378855, "y": 7.1589156867473385, "z": null, "yaw": 2.3809823495700773, "pitch": null, "roll": null}, "v": 0.9499032982867855, "accelerator_pedal_position": 0.24367754532872266, "brake_pedal_position": 0.0, "acceleration": 0.016466330629216097, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.238353957861931, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.2890558} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24482551525715168, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9506042778378082, "gear": 1, "accelerator_pedal_position": 0.2453367610916796, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.2890558} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.66996884346008, "x": 50.109967771378855, "y": 7.1589156867473385, "z": null, "yaw": 2.3809823495700773, "pitch": null, "roll": null}, "v": 0.9499032982867855, "accelerator_pedal_position": 0.24367754532872266, "brake_pedal_position": 0.0, "acceleration": 0.016466330629216097, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.238353957861931, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.3090558} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24482551525715168, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9510759704443027, "gear": 1, "accelerator_pedal_position": 0.24482551525715168, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.3090558} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.66996884346008, "x": 50.109967771378855, "y": 7.1589156867473385, "z": null, "yaw": 2.3809823495700773, "pitch": null, "roll": null}, "v": 0.9499032982867855, "accelerator_pedal_position": 0.24367754532872266, "brake_pedal_position": 0.0, "acceleration": 0.016466330629216097, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.238353957861931, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.3290558} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24482551525715168, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.951547012158944, "gear": 1, "accelerator_pedal_position": 0.24482551525715168, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.3290558} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.66996884346008, "x": 50.109967771378855, "y": 7.1589156867473385, "z": null, "yaw": 2.3809823495700773, "pitch": null, "roll": null}, "v": 0.9499032982867855, "accelerator_pedal_position": 0.24367754532872266, "brake_pedal_position": 0.0, "acceleration": 0.016466330629216097, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.238353957861931, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.3490558} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24482551525715168, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9520174037911807, "gear": 1, "accelerator_pedal_position": 0.24482551525715168, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.3490558} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502671.3690557, "x": 54.03328445190242, "y": 12.230075905866313, "z": null, "yaw": 2.408584038512624, "pitch": null, "roll": null}, "v": 0.9524871461497115, "accelerator_pedal_position": 0.24482551525715168, "brake_pedal_position": 0.0, "acceleration": 0.023462795413908166, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23900230845272513, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.3690557} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2398109364950726, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9524871461497115, "gear": 1, "accelerator_pedal_position": 0.24482551525715168, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.3690557} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.77996873855591, "x": 50.03328445190242, "y": 7.230075905866313, "z": null, "yaw": 2.408584038512624, "pitch": null, "roll": null}, "v": 0.9524871461497115, "accelerator_pedal_position": 0.24482551525715168, "brake_pedal_position": 0.0, "acceleration": 0.023462795413908166, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23900230845272513, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.3890557} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24138691075491103, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.952329634111719, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.3890557} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.77996873855591, "x": 50.03328445190242, "y": 7.230075905866313, "z": null, "yaw": 2.408584038512624, "pitch": null, "roll": null}, "v": 0.9524871461497115, "accelerator_pedal_position": 0.24482551525715168, "brake_pedal_position": 0.0, "acceleration": 0.023462795413908166, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23900230845272513, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.4090557} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24138691075491103, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9523692682877809, "gear": 1, "accelerator_pedal_position": 0.24138691075491103, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.4090557} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.77996873855591, "x": 50.03328445190242, "y": 7.230075905866313, "z": null, "yaw": 2.408584038512624, "pitch": null, "roll": null}, "v": 0.9524871461497115, "accelerator_pedal_position": 0.24482551525715168, "brake_pedal_position": 0.0, "acceleration": 0.023462795413908166, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23900230845272513, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.4290557} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24138691075491103, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.952408847750171, "gear": 1, "accelerator_pedal_position": 0.24138691075491103, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.4290557} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.77996873855591, "x": 50.03328445190242, "y": 7.230075905866313, "z": null, "yaw": 2.408584038512624, "pitch": null, "roll": null}, "v": 0.9524871461497115, "accelerator_pedal_position": 0.24482551525715168, "brake_pedal_position": 0.0, "acceleration": 0.023462795413908166, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23900230845272513, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.4490557} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24138691075491103, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9524483725737933, "gear": 1, "accelerator_pedal_position": 0.24138691075491103, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.4490557} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.77996873855591, "x": 50.03328445190242, "y": 7.230075905866313, "z": null, "yaw": 2.408584038512624, "pitch": null, "roll": null}, "v": 0.9524871461497115, "accelerator_pedal_position": 0.24482551525715168, "brake_pedal_position": 0.0, "acceleration": 0.023462795413908166, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23900230845272513, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.4690557} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24138691075491103, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9524878428334511, "gear": 1, "accelerator_pedal_position": 0.24138691075491103, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.4690557} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502671.4790556, "x": 53.95455537928009, "y": 12.299191055068736, "z": null, "yaw": 2.436185727455171, "pitch": null, "roll": null}, "v": 0.9525075575251418, "accelerator_pedal_position": 0.24138691075491103, "brake_pedal_position": 0.0, "acceleration": 0.0019701078705116615, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23900743016577528, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.4890556} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24418146324110607, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9525272586038469, "gear": 1, "accelerator_pedal_position": 0.24138691075491103, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.4890556} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.88996863365173, "x": 49.95455537928009, "y": 7.299191055068736, "z": null, "yaw": 2.436185727455171, "pitch": null, "roll": null}, "v": 0.9525075575251418, "accelerator_pedal_position": 0.24138691075491103, "brake_pedal_position": 0.0, "acceleration": 0.0019701078705116615, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23900743016577528, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.5090556} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.243308235486857, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9529158184132608, "gear": 1, "accelerator_pedal_position": 0.24418146324110607, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.5090556} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.88996863365173, "x": 49.95455537928009, "y": 7.299191055068736, "z": null, "yaw": 2.436185727455171, "pitch": null, "roll": null}, "v": 0.9525075575251418, "accelerator_pedal_position": 0.24138691075491103, "brake_pedal_position": 0.0, "acceleration": 0.0019701078705116615, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23900743016577528, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.5290556} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.243308235486857, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.953194725979662, "gear": 1, "accelerator_pedal_position": 0.243308235486857, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.5290556} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.88996863365173, "x": 49.95455537928009, "y": 7.299191055068736, "z": null, "yaw": 2.436185727455171, "pitch": null, "roll": null}, "v": 0.9525075575251418, "accelerator_pedal_position": 0.24138691075491103, "brake_pedal_position": 0.0, "acceleration": 0.0019701078705116615, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23900743016577528, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.5490556} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.243308235486857, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9534732484380186, "gear": 1, "accelerator_pedal_position": 0.243308235486857, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.5490556} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.88996863365173, "x": 49.95455537928009, "y": 7.299191055068736, "z": null, "yaw": 2.436185727455171, "pitch": null, "roll": null}, "v": 0.9525075575251418, "accelerator_pedal_position": 0.24138691075491103, "brake_pedal_position": 0.0, "acceleration": 0.0019701078705116615, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23900743016577528, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.5690556} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.243308235486857, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9537513862890581, "gear": 1, "accelerator_pedal_position": 0.243308235486857, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.5690556} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502671.5890555, "x": 53.87388390242983, "y": 12.366160517051526, "z": null, "yaw": 2.4637874163977176, "pitch": null, "roll": null}, "v": 0.9540291400329449, "accelerator_pedal_position": 0.243308235486857, "brake_pedal_position": 0.0, "acceleration": 0.013873298790889, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2393892324119644, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.5890555} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23643410889212568, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9540291400329449, "gear": 1, "accelerator_pedal_position": 0.243308235486857, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.5890555} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.99996852874756, "x": 49.87388390242983, "y": 7.366160517051526, "z": null, "yaw": 2.4637874163977176, "pitch": null, "roll": null}, "v": 0.9540291400329449, "accelerator_pedal_position": 0.243308235486857, "brake_pedal_position": 0.0, "acceleration": 0.013873298790889, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2393892324119644, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.6090555} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23858752929758592, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9534475411313221, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.6090555} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.99996852874756, "x": 49.87388390242983, "y": 7.366160517051526, "z": null, "yaw": 2.4637874163977176, "pitch": null, "roll": null}, "v": 0.9540291400329449, "accelerator_pedal_position": 0.243308235486857, "brake_pedal_position": 0.0, "acceleration": 0.013873298790889, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2393892324119644, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.6290555} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23858752929758592, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9531358299922147, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.6290555} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.99996852874756, "x": 49.87388390242983, "y": 7.366160517051526, "z": null, "yaw": 2.4637874163977176, "pitch": null, "roll": null}, "v": 0.9540291400329449, "accelerator_pedal_position": 0.243308235486857, "brake_pedal_position": 0.0, "acceleration": 0.013873298790889, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2393892324119644, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.6490555} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23858752929758592, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.952824549266506, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.6490555} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.99996852874756, "x": 49.87388390242983, "y": 7.366160517051526, "z": null, "yaw": 2.4637874163977176, "pitch": null, "roll": null}, "v": 0.9540291400329449, "accelerator_pedal_position": 0.243308235486857, "brake_pedal_position": 0.0, "acceleration": 0.013873298790889, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2393892324119644, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.6690555} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23858752929758592, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9525136983211325, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.6690555} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 32.99996852874756, "x": 49.87388390242983, "y": 7.366160517051526, "z": null, "yaw": 2.4637874163977176, "pitch": null, "roll": null}, "v": 0.9540291400329449, "accelerator_pedal_position": 0.243308235486857, "brake_pedal_position": 0.0, "acceleration": 0.013873298790889, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2393892324119644, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.6890554} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23858752929758592, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9522032765240654, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.6890554} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502671.6990554, "x": 53.791409557310125, "y": 12.430867710901826, "z": null, "yaw": 2.4913891053402644, "pitch": null, "roll": null}, "v": 0.9520482263589202, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2566663695710777, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23889217274785102, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.7090554} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24446224908519457, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9518932832443086, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.7090554} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.109968423843384, "x": 49.791409557310125, "y": 7.4308677109018255, "z": null, "yaw": 2.4913891053402644, "pitch": null, "roll": null}, "v": 0.9520482263589202, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2566663695710777, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23889217274785102, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.7290554} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2426195577718598, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9523178043369139, "gear": 1, "accelerator_pedal_position": 0.24446224908519457, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.7290554} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.109968423843384, "x": 49.791409557310125, "y": 7.4308677109018255, "z": null, "yaw": 2.4913891053402644, "pitch": null, "roll": null}, "v": 0.9520482263589202, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2566663695710777, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23889217274785102, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.7490554} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2426195577718598, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9525114825260718, "gear": 1, "accelerator_pedal_position": 0.2426195577718598, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.7490554} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.109968423843384, "x": 49.791409557310125, "y": 7.4308677109018255, "z": null, "yaw": 2.4913891053402644, "pitch": null, "roll": null}, "v": 0.9520482263589202, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2566663695710777, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23889217274785102, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.7690554} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2426195577718598, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9527048933408551, "gear": 1, "accelerator_pedal_position": 0.2426195577718598, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.7690554} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.109968423843384, "x": 49.791409557310125, "y": 7.4308677109018255, "z": null, "yaw": 2.4913891053402644, "pitch": null, "roll": null}, "v": 0.9520482263589202, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2566663695710777, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23889217274785102, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.7890553} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2426195577718598, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9528980371354187, "gear": 1, "accelerator_pedal_position": 0.2426195577718598, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.7890553} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502671.8090553, "x": 53.70722771610914, "y": 12.493238411779704, "z": null, "yaw": 2.518990794282811, "pitch": null, "roll": null}, "v": 0.9530909142634899, "accelerator_pedal_position": 0.2426195577718598, "brake_pedal_position": 0.0, "acceleration": 0.00963386745243311, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23915380863154273, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.8090553} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25897325795932447, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9530909142634899, "gear": 1, "accelerator_pedal_position": 0.2426195577718598, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.8090553} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.21996831893921, "x": 49.70722771610914, "y": 7.4932384117797035, "z": null, "yaw": 2.518990794282811, "pitch": null, "roll": null}, "v": 0.9530909142634899, "accelerator_pedal_position": 0.2426195577718598, "brake_pedal_position": 0.0, "acceleration": 0.00963386745243311, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23915380863154273, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.8290553} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2538663232549051, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9553270315924703, "gear": 1, "accelerator_pedal_position": 0.25897325795932447, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.8290553} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.21996831893921, "x": 49.70722771610914, "y": 7.4932384117797035, "z": null, "yaw": 2.518990794282811, "pitch": null, "roll": null}, "v": 0.9530909142634899, "accelerator_pedal_position": 0.2426195577718598, "brake_pedal_position": 0.0, "acceleration": 0.00963386745243311, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23915380863154273, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.8490553} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2538663232549051, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9569219136822225, "gear": 1, "accelerator_pedal_position": 0.2538663232549051, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.8490553} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.21996831893921, "x": 49.70722771610914, "y": 7.4932384117797035, "z": null, "yaw": 2.518990794282811, "pitch": null, "roll": null}, "v": 0.9530909142634899, "accelerator_pedal_position": 0.2426195577718598, "brake_pedal_position": 0.0, "acceleration": 0.00963386745243311, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23915380863154273, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.8690553} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2538663232549051, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9585145914354866, "gear": 1, "accelerator_pedal_position": 0.2538663232549051, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.8690553} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.21996831893921, "x": 49.70722771610914, "y": 7.4932384117797035, "z": null, "yaw": 2.518990794282811, "pitch": null, "roll": null}, "v": 0.9530909142634899, "accelerator_pedal_position": 0.2426195577718598, "brake_pedal_position": 0.0, "acceleration": 0.00963386745243311, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23915380863154273, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.8890553} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2538663232549051, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9616933420634841, "gear": 1, "accelerator_pedal_position": 0.2538663232549051, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.8890553} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.21996831893921, "x": 49.70722771610914, "y": 7.4932384117797035, "z": null, "yaw": 2.518990794282811, "pitch": null, "roll": null}, "v": 0.9530909142634899, "accelerator_pedal_position": 0.2426195577718598, "brake_pedal_position": 0.0, "acceleration": 0.00963386745243311, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23915380863154273, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.9090552} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2538663232549051, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9616933420634841, "gear": 1, "accelerator_pedal_position": 0.2538663232549051, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.9090552} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502671.9190552, "x": 53.620891441693324, "y": 12.553584794028998, "z": null, "yaw": 2.546592483225358, "pitch": null, "roll": null}, "v": 0.962486655187467, "accelerator_pedal_position": 0.2538663232549051, "brake_pedal_position": 0.0, "acceleration": 0.07927638196964387, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.241511429707619, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.9290552} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23371694127757187, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9631366169669723, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.9290552} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.329968214035034, "x": 49.620891441693324, "y": 7.553584794028998, "z": null, "yaw": 2.546592483225358, "pitch": null, "roll": null}, "v": 0.962486655187467, "accelerator_pedal_position": 0.2538663232549051, "brake_pedal_position": 0.0, "acceleration": 0.07927638196964387, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.241511429707619, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.9690552} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2400461157828098, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9626695942740428, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.9690552} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.329968214035034, "x": 49.620891441693324, "y": 7.553584794028998, "z": null, "yaw": 2.546592483225358, "pitch": null, "roll": null}, "v": 0.962486655187467, "accelerator_pedal_position": 0.2538663232549051, "brake_pedal_position": 0.0, "acceleration": 0.07927638196964387, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.241511429707619, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502671.9890552} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2400461157828098, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.962385386330925, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502671.9890552} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.329968214035034, "x": 49.620891441693324, "y": 7.553584794028998, "z": null, "yaw": 2.546592483225358, "pitch": null, "roll": null}, "v": 0.962486655187467, "accelerator_pedal_position": 0.2538663232549051, "brake_pedal_position": 0.0, "acceleration": 0.07927638196964387, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.241511429707619, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.0090551} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2400461157828098, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.962385386330925, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.0090551} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502672.029055, "x": 53.53244290289095, "y": 12.611844561047773, "z": null, "yaw": 2.5741941721679047, "pitch": null, "roll": null}, "v": 0.9622435774072978, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25737130589298085, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24145043555055468, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.029055} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23978749293358823, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9621565826567173, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.029055} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.43996810913086, "x": 49.53244290289095, "y": 7.611844561047773, "z": null, "yaw": 2.5741941721679047, "pitch": null, "roll": null}, "v": 0.9622435774072978, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25737130589298085, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24145043555055468, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.049055} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23986747100238107, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9619877724575715, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.049055} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.43996810913086, "x": 49.53244290289095, "y": 7.611844561047773, "z": null, "yaw": 2.5741941721679047, "pitch": null, "roll": null}, "v": 0.9622435774072978, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25737130589298085, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24145043555055468, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.069055} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23986747100238107, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9619059534615557, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.069055} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.43996810913086, "x": 49.53244290289095, "y": 7.611844561047773, "z": null, "yaw": 2.5741941721679047, "pitch": null, "roll": null}, "v": 0.9622435774072978, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25737130589298085, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24145043555055468, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.089055} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23986747100238107, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9616608362149122, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.089055} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.43996810913086, "x": 49.53244290289095, "y": 7.611844561047773, "z": null, "yaw": 2.5741941721679047, "pitch": null, "roll": null}, "v": 0.9622435774072978, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25737130589298085, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24145043555055468, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.109055} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23986747100238107, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9615792435780626, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.109055} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.43996810913086, "x": 49.53244290289095, "y": 7.611844561047773, "z": null, "yaw": 2.5741941721679047, "pitch": null, "roll": null}, "v": 0.9622435774072978, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25737130589298085, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24145043555055468, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.129055} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23986747100238107, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9613348044370389, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.129055} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502672.139055, "x": 53.44251743559071, "y": 12.667580759088082, "z": null, "yaw": 2.6017958611104515, "pitch": null, "roll": null}, "v": 0.9613348044370389, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25730838628407193, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24122240219742302, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.149055} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2441005682155044, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.961253437511847, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.149055} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.549968004226685, "x": 49.44251743559071, "y": 7.667580759088082, "z": null, "yaw": 2.6017958611104515, "pitch": null, "roll": null}, "v": 0.9613348044370389, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25730838628407193, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24122240219742302, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.169055} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2427745784865713, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9616198266032282, "gear": 1, "accelerator_pedal_position": 0.2441005682155044, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.169055} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.549968004226685, "x": 49.44251743559071, "y": 7.667580759088082, "z": null, "yaw": 2.6017958611104515, "pitch": null, "roll": null}, "v": 0.9613348044370389, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25730838628407193, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24122240219742302, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.189055} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2427745784865713, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9619200085981247, "gear": 1, "accelerator_pedal_position": 0.2427745784865713, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.189055} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.549968004226685, "x": 49.44251743559071, "y": 7.667580759088082, "z": null, "yaw": 2.6017958611104515, "pitch": null, "roll": null}, "v": 0.9613348044370389, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25730838628407193, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24122240219742302, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.209055} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2427745784865713, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9620199307389422, "gear": 1, "accelerator_pedal_position": 0.2427745784865713, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.209055} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.549968004226685, "x": 49.44251743559071, "y": 7.667580759088082, "z": null, "yaw": 2.6017958611104515, "pitch": null, "roll": null}, "v": 0.9613348044370389, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25730838628407193, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24122240219742302, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.229055} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2427745784865713, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9623192822320612, "gear": 1, "accelerator_pedal_position": 0.2427745784865713, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.229055} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.549968004226685, "x": 49.44251743559071, "y": 7.667580759088082, "z": null, "yaw": 2.6017958611104515, "pitch": null, "roll": null}, "v": 0.9613348044370389, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25730838628407193, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24122240219742302, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.239055} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2427745784865713, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9623192822320612, "gear": 1, "accelerator_pedal_position": 0.2427745784865713, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.239055} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502672.249055, "x": 53.3510903398005, "y": 12.72081198028997, "z": null, "yaw": 2.6293975500529982, "pitch": null, "roll": null}, "v": 0.9624189279062603, "accelerator_pedal_position": 0.2427745784865713, "brake_pedal_position": 0.0, "acceleration": 0.009957667217835142, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2414944352771754, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.269055} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23472032412233093, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9626180122943945, "gear": 1, "accelerator_pedal_position": 0.2427745784865713, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.269055} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.65996789932251, "x": 49.3510903398005, "y": 7.7208119802899695, "z": null, "yaw": 2.6293975500529982, "pitch": null, "roll": null}, "v": 0.9624189279062603, "accelerator_pedal_position": 0.2427745784865713, "brake_pedal_position": 0.0, "acceleration": 0.009957667217835142, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2414944352771754, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.2890549} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23724103336582, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9618103878399131, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.2890549} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.65996789932251, "x": 49.3510903398005, "y": 7.7208119802899695, "z": null, "yaw": 2.6293975500529982, "pitch": null, "roll": null}, "v": 0.9624189279062603, "accelerator_pedal_position": 0.2427745784865713, "brake_pedal_position": 0.0, "acceleration": 0.009957667217835142, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2414944352771754, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.3090549} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23724103336582, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9613188609885247, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.3090549} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.65996789932251, "x": 49.3510903398005, "y": 7.7208119802899695, "z": null, "yaw": 2.6293975500529982, "pitch": null, "roll": null}, "v": 0.9624189279062603, "accelerator_pedal_position": 0.2427745784865713, "brake_pedal_position": 0.0, "acceleration": 0.009957667217835142, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2414944352771754, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.3190548} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23724103336582, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9608280144581984, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.3190548} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.65996789932251, "x": 49.3510903398005, "y": 7.7208119802899695, "z": null, "yaw": 2.6293975500529982, "pitch": null, "roll": null}, "v": 0.9624189279062603, "accelerator_pedal_position": 0.2427745784865713, "brake_pedal_position": 0.0, "acceleration": 0.009957667217835142, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2414944352771754, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.3490548} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23724103336582, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9598483582106906, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.3490548} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502672.3590548, "x": 53.258251367101124, "y": 12.771488575810691, "z": null, "yaw": 2.656999238995545, "pitch": null, "roll": null}, "v": 0.9600930179946444, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2572224369317529, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24091080762364078, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.3690548} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2420668918834898, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9598483582106906, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.3690548} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.769967794418335, "x": 49.258251367101124, "y": 7.771488575810691, "z": null, "yaw": 2.656999238995545, "pitch": null, "roll": null}, "v": 0.9600930179946444, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2572224369317529, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24091080762364078, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.3890548} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24055075953309002, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9599625700342023, "gear": 1, "accelerator_pedal_position": 0.2420668918834898, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.3890548} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.769967794418335, "x": 49.258251367101124, "y": 7.771488575810691, "z": null, "yaw": 2.656999238995545, "pitch": null, "roll": null}, "v": 0.9600930179946444, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2572224369317529, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24091080762364078, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.4090548} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24055075953309002, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9598871728746529, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.4090548} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.769967794418335, "x": 49.258251367101124, "y": 7.771488575810691, "z": null, "yaw": 2.656999238995545, "pitch": null, "roll": null}, "v": 0.9600930179946444, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2572224369317529, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24091080762364078, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.4290547} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24055075953309002, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9598118800258352, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.4290547} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.769967794418335, "x": 49.258251367101124, "y": 7.771488575810691, "z": null, "yaw": 2.656999238995545, "pitch": null, "roll": null}, "v": 0.9600930179946444, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2572224369317529, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24091080762364078, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.4490547} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24055075953309002, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9597366913411702, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.4490547} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502672.4690547, "x": 53.16421627874305, "y": 12.819497716654213, "z": null, "yaw": 2.684600927938092, "pitch": null, "roll": null}, "v": 0.9596616066742911, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2571925843269614, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24080255597754363, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.4690547} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24444276272495935, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9596616066742911, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.4690547} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.87996768951416, "x": 49.16421627874305, "y": 7.8194977166542134, "z": null, "yaw": 2.684600927938092, "pitch": null, "roll": null}, "v": 0.9596616066742911, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2571925843269614, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24080255597754363, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.4890547} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24322501829884513, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.960072957961259, "gear": 1, "accelerator_pedal_position": 0.24444276272495935, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.4890547} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.87996768951416, "x": 49.16421627874305, "y": 7.8194977166542134, "z": null, "yaw": 2.684600927938092, "pitch": null, "roll": null}, "v": 0.9596616066742911, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2571925843269614, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24080255597754363, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.5090547} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24322501829884513, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9603315747577869, "gear": 1, "accelerator_pedal_position": 0.24322501829884513, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.5090547} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.87996768951416, "x": 49.16421627874305, "y": 7.8194977166542134, "z": null, "yaw": 2.684600927938092, "pitch": null, "roll": null}, "v": 0.9596616066742911, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2571925843269614, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24080255597754363, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.5290546} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24322501829884513, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9605898337249199, "gear": 1, "accelerator_pedal_position": 0.24322501829884513, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.5290546} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.87996768951416, "x": 49.16421627874305, "y": 7.8194977166542134, "z": null, "yaw": 2.684600927938092, "pitch": null, "roll": null}, "v": 0.9596616066742911, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2571925843269614, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24080255597754363, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.5490546} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24322501829884513, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9608477353310911, "gear": 1, "accelerator_pedal_position": 0.24322501829884513, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.5490546} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.87996768951416, "x": 49.16421627874305, "y": 7.8194977166542134, "z": null, "yaw": 2.684600927938092, "pitch": null, "roll": null}, "v": 0.9596616066742911, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2571925843269614, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24080255597754363, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.5690546} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24322501829884513, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9611052800441958, "gear": 1, "accelerator_pedal_position": 0.24322501829884513, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.5690546} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502672.5790546, "x": 53.06883458893053, "y": 12.864920221186871, "z": null, "yaw": 2.7122026168806386, "pitch": null, "roll": null}, "v": 0.9612339187119187, "accelerator_pedal_position": 0.24322501829884513, "brake_pedal_position": 0.0, "acceleration": 0.012854961967363354, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2411970875028456, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.5890546} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24721504793163343, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9613624683315923, "gear": 1, "accelerator_pedal_position": 0.24322501829884513, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.5890546} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.989967584609985, "x": 49.06883458893053, "y": 7.864920221186871, "z": null, "yaw": 2.7122026168806386, "pitch": null, "roll": null}, "v": 0.9612339187119187, "accelerator_pedal_position": 0.24322501829884513, "brake_pedal_position": 0.0, "acceleration": 0.012854961967363354, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2411970875028456, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.6090546} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24597360376110572, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9621178817148396, "gear": 1, "accelerator_pedal_position": 0.24721504793163343, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.6090546} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.989967584609985, "x": 49.06883458893053, "y": 7.864920221186871, "z": null, "yaw": 2.7122026168806386, "pitch": null, "roll": null}, "v": 0.9612339187119187, "accelerator_pedal_position": 0.24322501829884513, "brake_pedal_position": 0.0, "acceleration": 0.012854961967363354, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2411970875028456, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.6290545} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24597360376110572, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9627171225945054, "gear": 1, "accelerator_pedal_position": 0.24597360376110572, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.6290545} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.989967584609985, "x": 49.06883458893053, "y": 7.864920221186871, "z": null, "yaw": 2.7122026168806386, "pitch": null, "roll": null}, "v": 0.9612339187119187, "accelerator_pedal_position": 0.24322501829884513, "brake_pedal_position": 0.0, "acceleration": 0.012854961967363354, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2411970875028456, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.6490545} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24597360376110572, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9633155337968116, "gear": 1, "accelerator_pedal_position": 0.24597360376110572, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.6490545} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 33.989967584609985, "x": 49.06883458893053, "y": 7.864920221186871, "z": null, "yaw": 2.7122026168806386, "pitch": null, "roll": null}, "v": 0.9612339187119187, "accelerator_pedal_position": 0.24322501829884513, "brake_pedal_position": 0.0, "acceleration": 0.012854961967363354, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2411970875028456, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.6690545} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24597360376110572, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.963913116327297, "gear": 1, "accelerator_pedal_position": 0.24597360376110572, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.6690545} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502672.6890545, "x": 52.972008473061955, "y": 12.907793149671118, "z": null, "yaw": 2.7398043058231853, "pitch": null, "roll": null}, "v": 0.9645098711907027, "accelerator_pedal_position": 0.24597360376110572, "brake_pedal_position": 0.0, "acceleration": 0.029806737031132458, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24201910406020896, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.6890545} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2614319492231952, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9645098711907027, "gear": 1, "accelerator_pedal_position": 0.24597360376110572, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.6890545} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.09996747970581, "x": 48.972008473061955, "y": 7.907793149671118, "z": null, "yaw": 2.7398043058231853, "pitch": null, "roll": null}, "v": 0.9645098711907027, "accelerator_pedal_position": 0.24597360376110572, "brake_pedal_position": 0.0, "acceleration": 0.029806737031132458, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24201910406020896, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.7090545} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25661255731022065, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9670374229779131, "gear": 1, "accelerator_pedal_position": 0.2614319492231952, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.7090545} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.09996747970581, "x": 48.972008473061955, "y": 7.907793149671118, "z": null, "yaw": 2.7398043058231853, "pitch": null, "roll": null}, "v": 0.9645098711907027, "accelerator_pedal_position": 0.24597360376110572, "brake_pedal_position": 0.0, "acceleration": 0.029806737031132458, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24201910406020896, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.7290545} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25661255731022065, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9689592563128921, "gear": 1, "accelerator_pedal_position": 0.25661255731022065, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.7290545} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.09996747970581, "x": 48.972008473061955, "y": 7.907793149671118, "z": null, "yaw": 2.7398043058231853, "pitch": null, "roll": null}, "v": 0.9645098711907027, "accelerator_pedal_position": 0.24597360376110572, "brake_pedal_position": 0.0, "acceleration": 0.029806737031132458, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24201910406020896, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.7490544} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25661255731022065, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9708784242375416, "gear": 1, "accelerator_pedal_position": 0.25661255731022065, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.7490544} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.09996747970581, "x": 48.972008473061955, "y": 7.907793149671118, "z": null, "yaw": 2.7398043058231853, "pitch": null, "roll": null}, "v": 0.9645098711907027, "accelerator_pedal_position": 0.24597360376110572, "brake_pedal_position": 0.0, "acceleration": 0.029806737031132458, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24201910406020896, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.7690544} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25661255731022065, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9727949289757751, "gear": 1, "accelerator_pedal_position": 0.25661255731022065, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.7690544} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.09996747970581, "x": 48.972008473061955, "y": 7.907793149671118, "z": null, "yaw": 2.7398043058231853, "pitch": null, "roll": null}, "v": 0.9645098711907027, "accelerator_pedal_position": 0.24597360376110572, "brake_pedal_position": 0.0, "acceleration": 0.029806737031132458, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24201910406020896, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.7890544} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25661255731022065, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9747087727545508, "gear": 1, "accelerator_pedal_position": 0.25661255731022065, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.7890544} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502672.7990544, "x": 52.873308955288536, "y": 12.948273680785173, "z": null, "yaw": 2.767405994765732, "pitch": null, "roll": null}, "v": 0.9756646974808939, "accelerator_pedal_position": 0.25661255731022065, "brake_pedal_position": 0.0, "acceleration": 0.09552603229572937, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24481812265539096, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.8090544} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22917514175507545, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9766199578038512, "gear": 1, "accelerator_pedal_position": 0.25661255731022065, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.8090544} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.209967374801636, "x": 48.873308955288536, "y": 7.948273680785173, "z": null, "yaw": 2.767405994765732, "pitch": null, "roll": null}, "v": 0.9756646974808939, "accelerator_pedal_position": 0.25661255731022065, "brake_pedal_position": 0.0, "acceleration": 0.09552603229572937, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24481812265539096, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.8290544} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23778804798398828, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.975100001813931, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.8290544} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.209967374801636, "x": 48.873308955288536, "y": 7.948273680785173, "z": null, "yaw": 2.767405994765732, "pitch": null, "roll": null}, "v": 0.9756646974808939, "accelerator_pedal_position": 0.25661255731022065, "brake_pedal_position": 0.0, "acceleration": 0.09552603229572937, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24481812265539096, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.8490543} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23778804798398828, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9746583973178543, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.8490543} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.209967374801636, "x": 48.873308955288536, "y": 7.948273680785173, "z": null, "yaw": 2.767405994765732, "pitch": null, "roll": null}, "v": 0.9756646974808939, "accelerator_pedal_position": 0.25661255731022065, "brake_pedal_position": 0.0, "acceleration": 0.09552603229572937, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24481812265539096, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.8690543} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23778804798398828, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9742174063979164, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.8690543} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.209967374801636, "x": 48.873308955288536, "y": 7.948273680785173, "z": null, "yaw": 2.767405994765732, "pitch": null, "roll": null}, "v": 0.9756646974808939, "accelerator_pedal_position": 0.25661255731022065, "brake_pedal_position": 0.0, "acceleration": 0.09552603229572937, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24481812265539096, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.8890543} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23778804798398828, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9737770281238374, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.8890543} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502672.9090543, "x": 52.77302042804887, "y": 12.98621130710534, "z": null, "yaw": 2.795007683708279, "pitch": null, "roll": null}, "v": 0.9733372615669538, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2581407173258943, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2442341120905701, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.9090543} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23173438825833667, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9733372615669538, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.9090543} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.31996726989746, "x": 48.77302042804887, "y": 7.986211307105339, "z": null, "yaw": 2.795007683708279, "pitch": null, "roll": null}, "v": 0.9733372615669538, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2581407173258943, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2442341120905701, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.9290543} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.233618071479279, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9721416611335959, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.9290543} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.31996726989746, "x": 48.77302042804887, "y": 7.986211307105339, "z": null, "yaw": 2.795007683708279, "pitch": null, "roll": null}, "v": 0.9733372615669538, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2581407173258943, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2442341120905701, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.9490542} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.233618071479279, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9711830994443146, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.9490542} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.31996726989746, "x": 48.77302042804887, "y": 7.986211307105339, "z": null, "yaw": 2.795007683708279, "pitch": null, "roll": null}, "v": 0.9733372615669538, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2581407173258943, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2442341120905701, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.9690542} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.233618071479279, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.970225868322147, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.9690542} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.31996726989746, "x": 48.77302042804887, "y": 7.986211307105339, "z": null, "yaw": 2.795007683708279, "pitch": null, "roll": null}, "v": 0.9733372615669538, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2581407173258943, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2442341120905701, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502672.9890542} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.233618071479279, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9692699655537605, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502672.9890542} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.31996726989746, "x": 48.77302042804887, "y": 7.986211307105339, "z": null, "yaw": 2.795007683708279, "pitch": null, "roll": null}, "v": 0.9733372615669538, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2581407173258943, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2442341120905701, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.0090542} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.233618071479279, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9683153889304196, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.0090542} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502673.0190542, "x": 52.67214509170796, "y": 13.02122090225478, "z": null, "yaw": 2.8226093726508257, "pitch": null, "roll": null}, "v": 0.9678385972341653, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25775904536467026, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24285436279499636, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.0290542} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.240519530226935, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9673621362479735, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.0290542} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.429967164993286, "x": 48.67214509170796, "y": 8.02122090225478, "z": null, "yaw": 2.8226093726508257, "pitch": null, "roll": null}, "v": 0.9678385972341653, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25775904536467026, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24285436279499636, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.0490541} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23834373934367165, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9672725885495621, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.0490541} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.429967164993286, "x": 48.67214509170796, "y": 8.02122090225478, "z": null, "yaw": 2.8226093726508257, "pitch": null, "roll": null}, "v": 0.9678385972341653, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25775904536467026, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24285436279499636, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.0690541} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23834373934367165, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9669112854406802, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.0690541} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.429967164993286, "x": 48.67214509170796, "y": 8.02122090225478, "z": null, "yaw": 2.8226093726508257, "pitch": null, "roll": null}, "v": 0.9678385972341653, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25775904536467026, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24285436279499636, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.089054} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23834373934367165, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.966550483213471, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.089054} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.429967164993286, "x": 48.67214509170796, "y": 8.02122090225478, "z": null, "yaw": 2.8226093726508257, "pitch": null, "roll": null}, "v": 0.9678385972341653, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25775904536467026, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24285436279499636, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.109054} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23834373934367165, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9661901811214992, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.109054} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502673.129054, "x": 52.57074664210171, "y": 13.05330420610513, "z": null, "yaw": 2.8502110615933725, "pitch": null, "roll": null}, "v": 0.9658303784195804, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576198021197601, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24235045160364413, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.129054} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23262174186755175, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9658303784195804, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.129054} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.53996706008911, "x": 48.57074664210171, "y": 8.05330420610513, "z": null, "yaw": 2.8502110615933725, "pitch": null, "roll": null}, "v": 0.9658303784195804, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576198021197601, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24235045160364413, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.149054} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2344029050844153, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9647560725470289, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.149054} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.53996706008911, "x": 48.57074664210171, "y": 8.05330420610513, "z": null, "yaw": 2.8502110615933725, "pitch": null, "roll": null}, "v": 0.9658303784195804, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576198021197601, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24235045160364413, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.169054} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2344029050844153, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9639058234287221, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.169054} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.53996706008911, "x": 48.57074664210171, "y": 8.05330420610513, "z": null, "yaw": 2.8502110615933725, "pitch": null, "roll": null}, "v": 0.9658303784195804, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576198021197601, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24235045160364413, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.189054} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2344029050844153, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9630567520477581, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.189054} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.53996706008911, "x": 48.57074664210171, "y": 8.05330420610513, "z": null, "yaw": 2.8502110615933725, "pitch": null, "roll": null}, "v": 0.9658303784195804, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576198021197601, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24235045160364413, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.209054} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2344029050844153, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9622088564845043, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.209054} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.53996706008911, "x": 48.57074664210171, "y": 8.05330420610513, "z": null, "yaw": 2.8502110615933725, "pitch": null, "roll": null}, "v": 0.9658303784195804, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2576198021197601, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24235045160364413, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.229054} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2344029050844153, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9613621348231843, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.229054} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502673.239054, "x": 52.468857305370676, "y": 13.082475752761193, "z": null, "yaw": 2.8778127505359192, "pitch": null, "roll": null}, "v": 0.9609392136081215, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257281002402904, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2411231387882566, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.249054} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24111002264114542, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9605165851518684, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.249054} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.64996695518494, "x": 48.468857305370676, "y": 8.082475752761193, "z": null, "yaw": 2.8778127505359192, "pitch": null, "roll": null}, "v": 0.9609392136081215, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257281002402904, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2411231387882566, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.269054} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23899710703348903, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9605103051487462, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.269054} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.64996695518494, "x": 48.468857305370676, "y": 8.082475752761193, "z": null, "yaw": 2.8778127505359192, "pitch": null, "roll": null}, "v": 0.9609392136081215, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257281002402904, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2411231387882566, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.289054} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23899710703348903, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9602400107797202, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.289054} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.64996695518494, "x": 48.468857305370676, "y": 8.082475752761193, "z": null, "yaw": 2.8778127505359192, "pitch": null, "roll": null}, "v": 0.9609392136081215, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257281002402904, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2411231387882566, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.309054} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23899710703348903, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9599700904019014, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.309054} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.64996695518494, "x": 48.468857305370676, "y": 8.082475752761193, "z": null, "yaw": 2.8778127505359192, "pitch": null, "roll": null}, "v": 0.9609392136081215, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257281002402904, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2411231387882566, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.3290539} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23899710703348903, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9597005434686865, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.3290539} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502673.3490539, "x": 52.366553765706286, "y": 13.108732966422554, "z": null, "yaw": 2.905414439478466, "pitch": null, "roll": null}, "v": 0.9594313694343491, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25717665399826417, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24074478382590844, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.3490539} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24139047182645046, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9594313694343491, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.3490539} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.75996685028076, "x": 48.366553765706286, "y": 8.108732966422554, "z": null, "yaw": 2.905414439478466, "pitch": null, "roll": null}, "v": 0.9594313694343491, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25717665399826417, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24074478382590844, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.3690538} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24063732741461807, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.959461634858928, "gear": 1, "accelerator_pedal_position": 0.24139047182645046, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.3690538} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.75996685028076, "x": 48.366553765706286, "y": 8.108732966422554, "z": null, "yaw": 2.905414439478466, "pitch": null, "roll": null}, "v": 0.9594313694343491, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25717665399826417, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24074478382590844, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.3890538} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24063732741461807, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.959397747934126, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.3890538} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.75996685028076, "x": 48.366553765706286, "y": 8.108732966422554, "z": null, "yaw": 2.905414439478466, "pitch": null, "roll": null}, "v": 0.9594313694343491, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25717665399826417, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24074478382590844, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.4090538} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24063732741461807, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9593339493832631, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.4090538} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.75996685028076, "x": 48.366553765706286, "y": 8.108732966422554, "z": null, "yaw": 2.905414439478466, "pitch": null, "roll": null}, "v": 0.9594313694343491, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25717665399826417, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24074478382590844, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.4290538} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24063732741461807, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9592702390824651, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.4290538} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.75996685028076, "x": 48.366553765706286, "y": 8.108732966422554, "z": null, "yaw": 2.905414439478466, "pitch": null, "roll": null}, "v": 0.9594313694343491, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25717665399826417, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24074478382590844, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.4490538} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24063732741461807, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9592066169080362, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.4490538} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502673.4590538, "x": 52.263656016463656, "y": 13.132135707689947, "z": null, "yaw": 2.933016128421013, "pitch": null, "roll": null}, "v": 0.9591748388296039, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25715890565591815, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2406804140263046, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.4690537} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23683516144975067, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9591430827364583, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.4690537} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.86996674537659, "x": 48.263656016463656, "y": 8.132135707689947, "z": null, "yaw": 2.933016128421013, "pitch": null, "roll": null}, "v": 0.9591748388296039, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25715890565591815, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2406804140263046, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.4890537} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23802245167510255, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.958409738794713, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.4890537} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.86996674537659, "x": 48.263656016463656, "y": 8.132135707689947, "z": null, "yaw": 2.933016128421013, "pitch": null, "roll": null}, "v": 0.9591748388296039, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25715890565591815, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2406804140263046, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.4990537} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23802245167510255, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9582150822322679, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.4990537} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.86996674537659, "x": 48.263656016463656, "y": 8.132135707689947, "z": null, "yaw": 2.933016128421013, "pitch": null, "roll": null}, "v": 0.9591748388296039, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25715890565591815, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2406804140263046, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.5290537} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23802245167510255, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9574378013423906, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.5290537} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.86996674537659, "x": 48.263656016463656, "y": 8.132135707689947, "z": null, "yaw": 2.933016128421013, "pitch": null, "roll": null}, "v": 0.9591748388296039, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25715890565591815, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2406804140263046, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.5490537} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23802245167510255, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9574378013423906, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.5490537} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502673.5690536, "x": 52.16027235060678, "y": 13.152666256340236, "z": null, "yaw": 2.9606178173635596, "pitch": null, "roll": null}, "v": 0.9570499667057745, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257011944723004, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2401472316680807, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.5790536} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24361961679982821, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9570124910245736, "gear": 1, "accelerator_pedal_position": 0.24361961679982821, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.5790536} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.97996664047241, "x": 48.16027235060678, "y": 8.152666256340236, "z": null, "yaw": 2.9606178173635596, "pitch": null, "roll": null}, "v": 0.9570499667057745, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257011944723004, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2401472316680807, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.5990536} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24186315350007864, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9571686235382529, "gear": 1, "accelerator_pedal_position": 0.24361961679982821, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.5990536} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.97996664047241, "x": 48.16027235060678, "y": 8.152666256340236, "z": null, "yaw": 2.9606178173635596, "pitch": null, "roll": null}, "v": 0.9570499667057745, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257011944723004, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2401472316680807, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.6190536} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24186315350007864, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9572610827714628, "gear": 1, "accelerator_pedal_position": 0.24186315350007864, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.6190536} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.97996664047241, "x": 48.16027235060678, "y": 8.152666256340236, "z": null, "yaw": 2.9606178173635596, "pitch": null, "roll": null}, "v": 0.9570499667057745, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257011944723004, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2401472316680807, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.6390536} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24186315350007864, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.957353414187449, "gear": 1, "accelerator_pedal_position": 0.24186315350007864, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.6390536} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 34.97996664047241, "x": 48.16027235060678, "y": 8.152666256340236, "z": null, "yaw": 2.9606178173635596, "pitch": null, "roll": null}, "v": 0.9570499667057745, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257011944723004, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2401472316680807, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.6590536} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24186315350007864, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9574456179594996, "gear": 1, "accelerator_pedal_position": 0.24186315350007864, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.6590536} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502673.6790535, "x": 52.05646998058152, "y": 13.170316609022036, "z": null, "yaw": 2.9882195063061063, "pitch": null, "roll": null}, "v": 0.9575376942606768, "accelerator_pedal_position": 0.24186315350007864, "brake_pedal_position": 0.0, "acceleration": 0.004599040303157054, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24026961443407274, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.6790535} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23962658435737114, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9575376942606768, "gear": 1, "accelerator_pedal_position": 0.24186315350007864, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.6790535} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.08996653556824, "x": 48.05646998058152, "y": 8.170316609022036, "z": null, "yaw": 2.9882195063061063, "pitch": null, "roll": null}, "v": 0.9575376942606768, "accelerator_pedal_position": 0.24186315350007864, "brake_pedal_position": 0.0, "acceleration": 0.004599040303157054, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24026961443407274, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.6990535} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24032719889129245, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9573501687830878, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.6990535} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.08996653556824, "x": 48.05646998058152, "y": 8.170316609022036, "z": null, "yaw": 2.9882195063061063, "pitch": null, "roll": null}, "v": 0.9575376942606768, "accelerator_pedal_position": 0.24186315350007864, "brake_pedal_position": 0.0, "acceleration": 0.004599040303157054, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24026961443407274, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.7190535} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24032719889129245, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9572504490948456, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.7190535} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.08996653556824, "x": 48.05646998058152, "y": 8.170316609022036, "z": null, "yaw": 2.9882195063061063, "pitch": null, "roll": null}, "v": 0.9575376942606768, "accelerator_pedal_position": 0.24186315350007864, "brake_pedal_position": 0.0, "acceleration": 0.004599040303157054, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24026961443407274, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.7390535} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24032719889129245, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9571011279811004, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.7390535} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.08996653556824, "x": 48.05646998058152, "y": 8.170316609022036, "z": null, "yaw": 2.9882195063061063, "pitch": null, "roll": null}, "v": 0.9575376942606768, "accelerator_pedal_position": 0.24186315350007864, "brake_pedal_position": 0.0, "acceleration": 0.004599040303157054, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24026961443407274, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.7590535} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24032719889129245, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9570514230908973, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.7590535} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.08996653556824, "x": 48.05646998058152, "y": 8.170316609022036, "z": null, "yaw": 2.9882195063061063, "pitch": null, "roll": null}, "v": 0.9575376942606768, "accelerator_pedal_position": 0.24186315350007864, "brake_pedal_position": 0.0, "acceleration": 0.004599040303157054, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24026961443407274, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.7790534} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24032719889129245, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.956952116386394, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.7790534} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502673.7890534, "x": 51.95222225641988, "y": 13.185095477477912, "z": null, "yaw": 3.015821195248653, "pitch": null, "roll": null}, "v": 0.956902514523601, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257001749949196, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24011023231111475, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.7990534} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24114949289837356, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9568529469548148, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.7990534} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.19996643066406, "x": 47.95222225641988, "y": 8.185095477477912, "z": null, "yaw": 3.015821195248653, "pitch": null, "roll": null}, "v": 0.956902514523601, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257001749949196, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24011023231111475, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.8190534} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2408903298950833, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9568566658217349, "gear": 1, "accelerator_pedal_position": 0.24114949289837356, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.8190534} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.19996643066406, "x": 47.95222225641988, "y": 8.185095477477912, "z": null, "yaw": 3.015821195248653, "pitch": null, "roll": null}, "v": 0.956902514523601, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257001749949196, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24011023231111475, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.8390534} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2408903298950833, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9568279953713835, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.8390534} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.19996643066406, "x": 47.95222225641988, "y": 8.185095477477912, "z": null, "yaw": 3.015821195248653, "pitch": null, "roll": null}, "v": 0.956902514523601, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257001749949196, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24011023231111475, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.8590534} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2408903298950833, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9567993645509364, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.8590534} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.19996643066406, "x": 47.95222225641988, "y": 8.185095477477912, "z": null, "yaw": 3.015821195248653, "pitch": null, "roll": null}, "v": 0.956902514523601, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.257001749949196, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24011023231111475, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.8790534} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2408903298950833, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.956770773305287, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.8790534} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502673.8990533, "x": 51.84764886002732, "y": 13.19698671900107, "z": null, "yaw": 3.0434228841912, "pitch": null, "roll": null}, "v": 0.9567422215794066, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2569906678644973, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2400700108930662, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.8990533} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23490671922434847, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9567422215794066, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.8990533} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.30996632575989, "x": 47.84764886002732, "y": 8.19698671900107, "z": null, "yaw": 3.0434228841912, "pitch": null, "roll": null}, "v": 0.9567422215794066, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2569906678644973, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2400700108930662, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.9190533} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23677604468034344, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9559660165169448, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.9190533} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.30996632575989, "x": 47.84764886002732, "y": 8.19698671900107, "z": null, "yaw": 3.0434228841912, "pitch": null, "roll": null}, "v": 0.9567422215794066, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2569906678644973, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2400700108930662, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.9390533} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23677604468034344, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9554244690948361, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.9390533} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.30996632575989, "x": 47.84764886002732, "y": 8.19698671900107, "z": null, "yaw": 3.0434228841912, "pitch": null, "roll": null}, "v": 0.9567422215794066, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2569906678644973, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2400700108930662, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.9590533} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23677604468034344, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.954883669953888, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.9590533} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.30996632575989, "x": 47.84764886002732, "y": 8.19698671900107, "z": null, "yaw": 3.0434228841912, "pitch": null, "roll": null}, "v": 0.9567422215794066, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2569906678644973, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2400700108930662, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.9790533} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23677604468034344, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9543436179432204, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.9790533} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.30996632575989, "x": 47.84764886002732, "y": 8.19698671900107, "z": null, "yaw": 3.0434228841912, "pitch": null, "roll": null}, "v": 0.9567422215794066, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2569906678644973, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2400700108930662, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502673.9990532} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23677604468034344, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9538043119140284, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502673.9990532} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502674.0090532, "x": 51.7429665961659, "y": 13.205972744901963, "z": null, "yaw": 3.0710245731337467, "pitch": null, "roll": null}, "v": 0.9535349382840502, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25676903569948617, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23926522511243845, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.0190532} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24296769976387056, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9532657507195769, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.0190532} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.41996622085571, "x": 47.7429665961659, "y": 8.205972744901963, "z": null, "yaw": 3.0710245731337467, "pitch": null, "roll": null}, "v": 0.9535349382840502, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25676903569948617, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23926522511243845, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.0390532} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24102172466613708, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9535016228386012, "gear": 1, "accelerator_pedal_position": 0.24296769976387056, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.0390532} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.41996622085571, "x": 47.7429665961659, "y": 8.205972744901963, "z": null, "yaw": 3.0710245731337467, "pitch": null, "roll": null}, "v": 0.9535349382840502, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25676903569948617, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23926522511243845, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.0590532} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24102172466613708, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9534940063613375, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.0590532} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.41996622085571, "x": 47.7429665961659, "y": 8.205972744901963, "z": null, "yaw": 3.0710245731337467, "pitch": null, "roll": null}, "v": 0.9535349382840502, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25676903569948617, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23926522511243845, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.0790532} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24102172466613708, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9534864004018294, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.0790532} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.41996622085571, "x": 47.7429665961659, "y": 8.205972744901963, "z": null, "yaw": 3.0710245731337467, "pitch": null, "roll": null}, "v": 0.9535349382840502, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25676903569948617, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23926522511243845, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.0990531} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24102172466613708, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9534788049455297, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.0990531} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502674.1190531, "x": 51.63826547554641, "y": 13.212054504465192, "z": null, "yaw": 3.0986262620762934, "pitch": null, "roll": null}, "v": 0.9534712199779113, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25676463467215727, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23924923663183847, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.1190531} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24307438994102273, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9534712199779113, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.1190531} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.52996611595154, "x": 47.63826547554641, "y": 8.212054504465192, "z": null, "yaw": 3.0986262620762934, "pitch": null, "roll": null}, "v": 0.9534712199779113, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25676463467215727, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23924923663183847, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.139053} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24243271157053742, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9538043662246157, "gear": 1, "accelerator_pedal_position": 0.24243271157053742, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.139053} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.52996611595154, "x": 47.63826547554641, "y": 8.212054504465192, "z": null, "yaw": 3.0986262620762934, "pitch": null, "roll": null}, "v": 0.9534712199779113, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25676463467215727, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23924923663183847, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.159053} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24243271157053742, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9538885342377591, "gear": 1, "accelerator_pedal_position": 0.24243271157053742, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.159053} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.52996611595154, "x": 47.63826547554641, "y": 8.212054504465192, "z": null, "yaw": 3.0986262620762934, "pitch": null, "roll": null}, "v": 0.9534712199779113, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25676463467215727, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23924923663183847, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.179053} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24243271157053742, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9541406895880788, "gear": 1, "accelerator_pedal_position": 0.24243271157053742, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.179053} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.52996611595154, "x": 47.63826547554641, "y": 8.212054504465192, "z": null, "yaw": 3.0986262620762934, "pitch": null, "roll": null}, "v": 0.9534712199779113, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25676463467215727, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23924923663183847, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.199053} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24243271157053742, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9542246252708906, "gear": 1, "accelerator_pedal_position": 0.24243271157053742, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.199053} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.52996611595154, "x": 47.63826547554641, "y": 8.212054504465192, "z": null, "yaw": 3.0986262620762934, "pitch": null, "roll": null}, "v": 0.9534712199779113, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25676463467215727, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23924923663183847, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.219053} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24243271157053742, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9543923227176574, "gear": 1, "accelerator_pedal_position": 0.24243271157053742, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.219053} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502674.229053, "x": 51.53338156468397, "y": 13.215245829038127, "z": null, "yaw": 3.12622795101884, "pitch": null, "roll": null}, "v": 0.9544760845588909, "accelerator_pedal_position": 0.24243271157053742, "brake_pedal_position": 0.0, "acceleration": 0.008370397127965501, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23950138171905289, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.239053} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2391441767654747, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9545597885301705, "gear": 1, "accelerator_pedal_position": 0.24243271157053742, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.239053} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.63996601104736, "x": 47.53338156468397, "y": 8.215245829038127, "z": null, "yaw": 3.12622795101884, "pitch": null, "roll": null}, "v": 0.9544760845588909, "accelerator_pedal_position": 0.24243271157053742, "brake_pedal_position": 0.0, "acceleration": 0.008370397127965501, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23950138171905289, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.259053} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24017531534391073, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9543160981712462, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.259053} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.63996601104736, "x": 47.53338156468397, "y": 8.215245829038127, "z": null, "yaw": 3.12622795101884, "pitch": null, "roll": null}, "v": 0.9544760845588909, "accelerator_pedal_position": 0.24243271157053742, "brake_pedal_position": 0.0, "acceleration": 0.008370397127965501, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23950138171905289, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.279053} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24017531534391073, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9542015922153345, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.279053} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.63996601104736, "x": 47.53338156468397, "y": 8.215245829038127, "z": null, "yaw": 3.12622795101884, "pitch": null, "roll": null}, "v": 0.9544760845588909, "accelerator_pedal_position": 0.24243271157053742, "brake_pedal_position": 0.0, "acceleration": 0.008370397127965501, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23950138171905289, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.299053} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24017531534391073, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9540872444167464, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.299053} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.63996601104736, "x": 47.53338156468397, "y": 8.215245829038127, "z": null, "yaw": 3.12622795101884, "pitch": null, "roll": null}, "v": 0.9544760845588909, "accelerator_pedal_position": 0.24243271157053742, "brake_pedal_position": 0.0, "acceleration": 0.008370397127965501, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23950138171905289, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.319053} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24017531534391073, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9539730545518044, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.319053} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502674.339053, "x": 51.42842127512275, "y": 13.215541832539603, "z": null, "yaw": 3.153829639961387, "pitch": null, "roll": null}, "v": 0.9538590223971615, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2567914214659428, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23934654573863223, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.339053} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24522288070588955, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9538590223971615, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.339053} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.74996590614319, "x": 47.42842127512275, "y": 8.215541832539603, "z": null, "yaw": 3.153829639961387, "pitch": null, "roll": null}, "v": 0.9538590223971615, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2567914214659428, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23934654573863223, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.359053} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24364338405857494, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9543758754739498, "gear": 1, "accelerator_pedal_position": 0.24522288070588955, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.359053} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.74996590614319, "x": 47.42842127512275, "y": 8.215541832539603, "z": null, "yaw": 3.153829639961387, "pitch": null, "roll": null}, "v": 0.9538590223971615, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2567914214659428, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23934654573863223, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.3790529} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24364338405857494, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9546946457876182, "gear": 1, "accelerator_pedal_position": 0.24364338405857494, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.3790529} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.74996590614319, "x": 47.42842127512275, "y": 8.215541832539603, "z": null, "yaw": 3.153829639961387, "pitch": null, "roll": null}, "v": 0.9538590223971615, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2567914214659428, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23934654573863223, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.3990529} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24364338405857494, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.955012975761986, "gear": 1, "accelerator_pedal_position": 0.24364338405857494, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.3990529} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.74996590614319, "x": 47.42842127512275, "y": 8.215541832539603, "z": null, "yaw": 3.153829639961387, "pitch": null, "roll": null}, "v": 0.9538590223971615, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2567914214659428, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23934654573863223, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.4190528} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24364338405857494, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9553308659648045, "gear": 1, "accelerator_pedal_position": 0.24364338405857494, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.4190528} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.74996590614319, "x": 47.42842127512275, "y": 8.215541832539603, "z": null, "yaw": 3.153829639961387, "pitch": null, "roll": null}, "v": 0.9538590223971615, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2567914214659428, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23934654573863223, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.4390528} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24364338405857494, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9556483169632087, "gear": 1, "accelerator_pedal_position": 0.24364338405857494, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.4390528} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502674.4490528, "x": 51.32342594553087, "y": 13.21293870433291, "z": null, "yaw": 3.1814313289039338, "pitch": null, "roll": null}, "v": 0.9558068779378166, "accelerator_pedal_position": 0.24364338405857494, "brake_pedal_position": 0.0, "acceleration": 0.01584513859007014, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23983531030897934, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.4590528} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2374064855603862, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9559653293237172, "gear": 1, "accelerator_pedal_position": 0.24364338405857494, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.4590528} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.859965801239014, "x": 47.32342594553087, "y": 8.21293870433291, "z": null, "yaw": 3.1814313289039338, "pitch": null, "roll": null}, "v": 0.9558068779378166, "accelerator_pedal_position": 0.24364338405857494, "brake_pedal_position": 0.0, "acceleration": 0.01584513859007014, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23983531030897934, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.4790528} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23936224713887144, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9555025607284214, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.4790528} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.859965801239014, "x": 47.32342594553087, "y": 8.21293870433291, "z": null, "yaw": 3.1814313289039338, "pitch": null, "roll": null}, "v": 0.9558068779378166, "accelerator_pedal_position": 0.24364338405857494, "brake_pedal_position": 0.0, "acceleration": 0.01584513859007014, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23983531030897934, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.4990528} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23936224713887144, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9552848172974607, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.4990528} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.859965801239014, "x": 47.32342594553087, "y": 8.21293870433291, "z": null, "yaw": 3.1814313289039338, "pitch": null, "roll": null}, "v": 0.9558068779378166, "accelerator_pedal_position": 0.24364338405857494, "brake_pedal_position": 0.0, "acceleration": 0.01584513859007014, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23983531030897934, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.5190527} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23936224713887144, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9550673747134825, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.5190527} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.859965801239014, "x": 47.32342594553087, "y": 8.21293870433291, "z": null, "yaw": 3.1814313289039338, "pitch": null, "roll": null}, "v": 0.9558068779378166, "accelerator_pedal_position": 0.24364338405857494, "brake_pedal_position": 0.0, "acceleration": 0.01584513859007014, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23983531030897934, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.5390527} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23936224713887144, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.954850232541913, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.5390527} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502674.5590527, "x": 51.21848857152962, "y": 13.207436868498162, "z": null, "yaw": 3.2090330178464805, "pitch": null, "roll": null}, "v": 0.9546333903488576, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25684491861713243, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23954085358708493, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.5590527} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24487787680880663, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9546333903488576, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.5590527} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.96996569633484, "x": 47.21848857152962, "y": 8.207436868498162, "z": null, "yaw": 3.2090330178464805, "pitch": null, "roll": null}, "v": 0.9546333903488576, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25684491861713243, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23954085358708493, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.5790527} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24315018674624547, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9551060632244441, "gear": 1, "accelerator_pedal_position": 0.24487787680880663, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.5790527} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.96996569633484, "x": 47.21848857152962, "y": 8.207436868498162, "z": null, "yaw": 3.2090330178464805, "pitch": null, "roll": null}, "v": 0.9546333903488576, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25684491861713243, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23954085358708493, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.5990527} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24315018674624547, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9553621964571213, "gear": 1, "accelerator_pedal_position": 0.24315018674624547, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.5990527} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.96996569633484, "x": 47.21848857152962, "y": 8.207436868498162, "z": null, "yaw": 3.2090330178464805, "pitch": null, "roll": null}, "v": 0.9546333903488576, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25684491861713243, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23954085358708493, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.6190526} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24315018674624547, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9556179758054452, "gear": 1, "accelerator_pedal_position": 0.24315018674624547, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.6190526} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.96996569633484, "x": 47.21848857152962, "y": 8.207436868498162, "z": null, "yaw": 3.2090330178464805, "pitch": null, "roll": null}, "v": 0.9546333903488576, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25684491861713243, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23954085358708493, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.6390526} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24315018674624547, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.955873401732197, "gear": 1, "accelerator_pedal_position": 0.24315018674624547, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.6390526} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 35.96996569633484, "x": 47.21848857152962, "y": 8.207436868498162, "z": null, "yaw": 3.2090330178464805, "pitch": null, "roll": null}, "v": 0.9546333903488576, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25684491861713243, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23954085358708493, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.6590526} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24315018674624547, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.956128474699627, "gear": 1, "accelerator_pedal_position": 0.24315018674624547, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.6590526} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502674.6690526, "x": 51.11372730746967, "y": 13.19903906426047, "z": null, "yaw": 3.2366347067890273, "pitch": null, "roll": null}, "v": 0.9562558789679044, "accelerator_pedal_position": 0.24315018674624547, "brake_pedal_position": 0.0, "acceleration": 0.012731620155032097, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23994797564322812, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.6790526} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23686295459713977, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9563831951694548, "gear": 1, "accelerator_pedal_position": 0.24315018674624547, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.6790526} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.079965591430664, "x": 47.11372730746967, "y": 8.19903906426047, "z": null, "yaw": 3.2366347067890273, "pitch": null, "roll": null}, "v": 0.9562558789679044, "accelerator_pedal_position": 0.24315018674624547, "brake_pedal_position": 0.0, "acceleration": 0.012731620155032097, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23994797564322812, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.6990526} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23883332235520255, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9558519312173335, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.6990526} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.079965591430664, "x": 47.11372730746967, "y": 8.19903906426047, "z": null, "yaw": 3.2366347067890273, "pitch": null, "roll": null}, "v": 0.9562558789679044, "accelerator_pedal_position": 0.24315018674624547, "brake_pedal_position": 0.0, "acceleration": 0.012731620155032097, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23994797564322812, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.7190526} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23883332235520255, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9555676122859915, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.7190526} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.079965591430664, "x": 47.11372730746967, "y": 8.19903906426047, "z": null, "yaw": 3.2366347067890273, "pitch": null, "roll": null}, "v": 0.9562558789679044, "accelerator_pedal_position": 0.24315018674624547, "brake_pedal_position": 0.0, "acceleration": 0.012731620155032097, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23994797564322812, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.7390525} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23883332235520255, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9552836862202454, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.7390525} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.079965591430664, "x": 47.11372730746967, "y": 8.19903906426047, "z": null, "yaw": 3.2366347067890273, "pitch": null, "roll": null}, "v": 0.9562558789679044, "accelerator_pedal_position": 0.24315018674624547, "brake_pedal_position": 0.0, "acceleration": 0.012731620155032097, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23994797564322812, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.7590525} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23883332235520255, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9550001524450074, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.7590525} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502674.7790525, "x": 51.00922238001774, "y": 13.187752401124227, "z": null, "yaw": 3.264236395731574, "pitch": null, "roll": null}, "v": 0.9547170103861184, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.256850696218512, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23956183589851981, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.7790525} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2444249111879179, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9547170103861184, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.7790525} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.18996548652649, "x": 47.00922238001774, "y": 8.187752401124227, "z": null, "yaw": 3.264236395731574, "pitch": null, "roll": null}, "v": 0.9547170103861184, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.256850696218512, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23956183589851981, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.7990525} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24267222098901658, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9551329666051436, "gear": 1, "accelerator_pedal_position": 0.2444249111879179, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.7990525} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.18996548652649, "x": 47.00922238001774, "y": 8.187752401124227, "z": null, "yaw": 3.264236395731574, "pitch": null, "roll": null}, "v": 0.9547170103861184, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.256850696218512, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23956183589851981, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.8190525} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24267222098901658, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9553293375921834, "gear": 1, "accelerator_pedal_position": 0.24267222098901658, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.8190525} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.18996548652649, "x": 47.00922238001774, "y": 8.187752401124227, "z": null, "yaw": 3.264236395731574, "pitch": null, "roll": null}, "v": 0.9547170103861184, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.256850696218512, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23956183589851981, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.8390524} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24267222098901658, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9555254372662864, "gear": 1, "accelerator_pedal_position": 0.24267222098901658, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.8390524} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.18996548652649, "x": 47.00922238001774, "y": 8.187752401124227, "z": null, "yaw": 3.264236395731574, "pitch": null, "roll": null}, "v": 0.9547170103861184, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.256850696218512, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23956183589851981, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.8590524} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24267222098901658, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.955721265986931, "gear": 1, "accelerator_pedal_position": 0.24267222098901658, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.8590524} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.18996548652649, "x": 47.00922238001774, "y": 8.187752401124227, "z": null, "yaw": 3.264236395731574, "pitch": null, "roll": null}, "v": 0.9547170103861184, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.256850696218512, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23956183589851981, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.8790524} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24267222098901658, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9559168241131629, "gear": 1, "accelerator_pedal_position": 0.24267222098901658, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.8790524} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502674.8890524, "x": 50.90509091163594, "y": 13.173588166149909, "z": null, "yaw": 3.291838084674121, "pitch": null, "roll": null}, "v": 0.9560145018154577, "accelerator_pedal_position": 0.24267222098901658, "brake_pedal_position": 0.0, "acceleration": 0.009761018813766065, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2398874082152311, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.8990524} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2477862500711028, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9561121120035954, "gear": 1, "accelerator_pedal_position": 0.24267222098901658, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.8990524} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.299965381622314, "x": 46.90509091163594, "y": 8.173588166149909, "z": null, "yaw": 3.291838084674121, "pitch": null, "roll": null}, "v": 0.9560145018154577, "accelerator_pedal_position": 0.24267222098901658, "brake_pedal_position": 0.0, "acceleration": 0.009761018813766065, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2398874082152311, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.9190524} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24619259824552508, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9569461627019952, "gear": 1, "accelerator_pedal_position": 0.2477862500711028, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.9190524} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.299965381622314, "x": 46.90509091163594, "y": 8.173588166149909, "z": null, "yaw": 3.291838084674121, "pitch": null, "roll": null}, "v": 0.9560145018154577, "accelerator_pedal_position": 0.24267222098901658, "brake_pedal_position": 0.0, "acceleration": 0.009761018813766065, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2398874082152311, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.9390523} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24619259824552508, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.957579922954999, "gear": 1, "accelerator_pedal_position": 0.24619259824552508, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.9390523} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.299965381622314, "x": 46.90509091163594, "y": 8.173588166149909, "z": null, "yaw": 3.291838084674121, "pitch": null, "roll": null}, "v": 0.9560145018154577, "accelerator_pedal_position": 0.24267222098901658, "brake_pedal_position": 0.0, "acceleration": 0.009761018813766065, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2398874082152311, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.9590523} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24619259824552508, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9582128070405241, "gear": 1, "accelerator_pedal_position": 0.24619259824552508, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.9590523} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.299965381622314, "x": 46.90509091163594, "y": 8.173588166149909, "z": null, "yaw": 3.291838084674121, "pitch": null, "roll": null}, "v": 0.9560145018154577, "accelerator_pedal_position": 0.24267222098901658, "brake_pedal_position": 0.0, "acceleration": 0.009761018813766065, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2398874082152311, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.9790523} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24619259824552508, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.958844816009702, "gear": 1, "accelerator_pedal_position": 0.24619259824552508, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.9790523} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502674.9990523, "x": 50.80115605675843, "y": 13.156516462806595, "z": null, "yaw": 3.3194397736166676, "pitch": null, "roll": null}, "v": 0.9594759509128751, "accelerator_pedal_position": 0.24619259824552508, "brake_pedal_position": 0.0, "acceleration": 0.0315240004850863, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24075597040866184, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502674.9990523} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.261237348525884, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9594759509128751, "gear": 1, "accelerator_pedal_position": 0.24619259824552508, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502674.9990523} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.40996527671814, "x": 46.80115605675843, "y": 8.156516462806595, "z": null, "yaw": 3.3194397736166676, "pitch": null, "roll": null}, "v": 0.9594759509128751, "accelerator_pedal_position": 0.24619259824552508, "brake_pedal_position": 0.0, "acceleration": 0.0315240004850863, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24075597040866184, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.0190523} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25654782979767665, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.961986155850044, "gear": 1, "accelerator_pedal_position": 0.261237348525884, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.0190523} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.40996527671814, "x": 46.80115605675843, "y": 8.156516462806595, "z": null, "yaw": 3.3194397736166676, "pitch": null, "roll": null}, "v": 0.9594759509128751, "accelerator_pedal_position": 0.24619259824552508, "brake_pedal_position": 0.0, "acceleration": 0.0315240004850863, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24075597040866184, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.0390522} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25654782979767665, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9639068996646298, "gear": 1, "accelerator_pedal_position": 0.25654782979767665, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.0390522} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.40996527671814, "x": 46.80115605675843, "y": 8.156516462806595, "z": null, "yaw": 3.3194397736166676, "pitch": null, "roll": null}, "v": 0.9594759509128751, "accelerator_pedal_position": 0.24619259824552508, "brake_pedal_position": 0.0, "acceleration": 0.0315240004850863, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24075597040866184, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.0590522} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25654782979767665, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.965824983458766, "gear": 1, "accelerator_pedal_position": 0.25654782979767665, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.0590522} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.40996527671814, "x": 46.80115605675843, "y": 8.156516462806595, "z": null, "yaw": 3.3194397736166676, "pitch": null, "roll": null}, "v": 0.9594759509128751, "accelerator_pedal_position": 0.24619259824552508, "brake_pedal_position": 0.0, "acceleration": 0.0315240004850863, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24075597040866184, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.0790522} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25654782979767665, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9677404094451819, "gear": 1, "accelerator_pedal_position": 0.25654782979767665, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.0790522} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.40996527671814, "x": 46.80115605675843, "y": 8.156516462806595, "z": null, "yaw": 3.3194397736166676, "pitch": null, "roll": null}, "v": 0.9594759509128751, "accelerator_pedal_position": 0.24619259824552508, "brake_pedal_position": 0.0, "acceleration": 0.0315240004850863, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24075597040866184, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.0990522} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25654782979767665, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9696531798396554, "gear": 1, "accelerator_pedal_position": 0.25654782979767665, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.0990522} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502675.1090522, "x": 50.69695144645333, "y": 13.136430541024437, "z": null, "yaw": 3.3470414625592144, "pitch": null, "roll": null}, "v": 0.970608569883173, "accelerator_pedal_position": 0.25654782979767665, "brake_pedal_position": 0.0, "acceleration": 0.09547269778201378, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24354941664442614, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.1190522} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2681682277445767, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9715632968609932, "gear": 1, "accelerator_pedal_position": 0.25654782979767665, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.1190522} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.519965171813965, "x": 46.69695144645333, "y": 8.136430541024437, "z": null, "yaw": 3.3470414625592144, "pitch": null, "roll": null}, "v": 0.970608569883173, "accelerator_pedal_position": 0.25654782979767665, "brake_pedal_position": 0.0, "acceleration": 0.09547269778201378, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24354941664442614, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.1390522} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2645754260257471, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9749228080212063, "gear": 1, "accelerator_pedal_position": 0.2681682277445767, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.1390522} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.519965171813965, "x": 46.69695144645333, "y": 8.136430541024437, "z": null, "yaw": 3.3470414625592144, "pitch": null, "roll": null}, "v": 0.970608569883173, "accelerator_pedal_position": 0.25654782979767665, "brake_pedal_position": 0.0, "acceleration": 0.09547269778201378, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24354941664442614, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.1590521} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2645754260257471, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9778287082298537, "gear": 1, "accelerator_pedal_position": 0.2645754260257471, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.1590521} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.519965171813965, "x": 46.69695144645333, "y": 8.136430541024437, "z": null, "yaw": 3.3470414625592144, "pitch": null, "roll": null}, "v": 0.970608569883173, "accelerator_pedal_position": 0.25654782979767665, "brake_pedal_position": 0.0, "acceleration": 0.09547269778201378, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24354941664442614, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.179052} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2645754260257471, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9807305681992734, "gear": 1, "accelerator_pedal_position": 0.2645754260257471, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.179052} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.519965171813965, "x": 46.69695144645333, "y": 8.136430541024437, "z": null, "yaw": 3.3470414625592144, "pitch": null, "roll": null}, "v": 0.970608569883173, "accelerator_pedal_position": 0.25654782979767665, "brake_pedal_position": 0.0, "acceleration": 0.09547269778201378, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24354941664442614, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.199052} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2645754260257471, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9836283901796964, "gear": 1, "accelerator_pedal_position": 0.2645754260257471, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.199052} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502675.219052, "x": 50.591946735567966, "y": 13.113166246956236, "z": null, "yaw": 3.374643151501761, "pitch": null, "roll": null}, "v": 0.9865221764322755, "accelerator_pedal_position": 0.2645754260257471, "brake_pedal_position": 0.0, "acceleration": 0.14453804379337865, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24754252953463002, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.219052} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9865221764322755, "gear": 1, "accelerator_pedal_position": 0.2645754260257471, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.219052} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.62996506690979, "x": 46.591946735567966, "y": 8.113166246956236, "z": null, "yaw": 3.374643151501761, "pitch": null, "roll": null}, "v": 0.9865221764322755, "accelerator_pedal_position": 0.2645754260257471, "brake_pedal_position": 0.0, "acceleration": 0.14453804379337865, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24754252953463002, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.239052} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2307216961246149, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9813428148093084, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.239052} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.62996506690979, "x": 46.591946735567966, "y": 8.113166246956236, "z": null, "yaw": 3.374643151501761, "pitch": null, "roll": null}, "v": 0.9865221764322755, "accelerator_pedal_position": 0.2645754260257471, "brake_pedal_position": 0.0, "acceleration": 0.14453804379337865, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24754252953463002, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.259052} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2307216961246149, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9800095415413302, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.259052} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.62996506690979, "x": 46.591946735567966, "y": 8.113166246956236, "z": null, "yaw": 3.374643151501761, "pitch": null, "roll": null}, "v": 0.9865221764322755, "accelerator_pedal_position": 0.2645754260257471, "brake_pedal_position": 0.0, "acceleration": 0.14453804379337865, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24754252953463002, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.279052} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2307216961246149, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9786781237266672, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.279052} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.62996506690979, "x": 46.591946735567966, "y": 8.113166246956236, "z": null, "yaw": 3.374643151501761, "pitch": null, "roll": null}, "v": 0.9865221764322755, "accelerator_pedal_position": 0.2645754260257471, "brake_pedal_position": 0.0, "acceleration": 0.14453804379337865, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24754252953463002, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.299052} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2307216961246149, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9773485580743496, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.299052} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.62996506690979, "x": 46.591946735567966, "y": 8.113166246956236, "z": null, "yaw": 3.374643151501761, "pitch": null, "roll": null}, "v": 0.9865221764322755, "accelerator_pedal_position": 0.2645754260257471, "brake_pedal_position": 0.0, "acceleration": 0.14453804379337865, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24754252953463002, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.319052} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2307216961246149, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9760208413009448, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.319052} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502675.329052, "x": 50.487398099349186, "y": 13.086963012010914, "z": null, "yaw": 3.402244840444308, "pitch": null, "roll": null}, "v": 0.9753576752198174, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25828110970709295, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24474108326494845, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.339052} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23040807477849384, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.974694970130535, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.339052} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.739964962005615, "x": 46.487398099349186, "y": 8.086963012010914, "z": null, "yaw": 3.402244840444308, "pitch": null, "roll": null}, "v": 0.9753576752198174, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25828110970709295, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24474108326494845, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.359052} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23046721852991198, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9733317522455273, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.359052} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.739964962005615, "x": 46.487398099349186, "y": 8.086963012010914, "z": null, "yaw": 3.402244840444308, "pitch": null, "roll": null}, "v": 0.9753576752198174, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25828110970709295, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24474108326494845, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.379052} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23046721852991198, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.971977818253247, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.379052} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.739964962005615, "x": 46.487398099349186, "y": 8.086963012010914, "z": null, "yaw": 3.402244840444308, "pitch": null, "roll": null}, "v": 0.9753576752198174, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25828110970709295, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24474108326494845, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.399052} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23046721852991198, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9706257641228853, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.399052} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.739964962005615, "x": 46.487398099349186, "y": 8.086963012010914, "z": null, "yaw": 3.402244840444308, "pitch": null, "roll": null}, "v": 0.9753576752198174, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25828110970709295, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24474108326494845, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.419052} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23046721852991198, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.969275586513392, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.419052} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502675.4390519, "x": 50.38444827017854, "y": 13.058117936436949, "z": null, "yaw": 3.4298465293868547, "pitch": null, "roll": null}, "v": 0.9679272820913979, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2577651963387383, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24287661599357135, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.4390519} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2385757803437075, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9679272820913979, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.4390519} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.84996485710144, "x": 46.38444827017854, "y": 8.058117936436949, "z": null, "yaw": 3.4298465293868547, "pitch": null, "roll": null}, "v": 0.9679272820913979, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2577651963387383, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24287661599357135, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.4590518} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23601605743019355, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9675940663017087, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.4590518} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.84996485710144, "x": 46.38444827017854, "y": 8.058117936436949, "z": null, "yaw": 3.4298465293868547, "pitch": null, "roll": null}, "v": 0.9679272820913979, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2577651963387383, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24287661599357135, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.4790518} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23601605743019355, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9669414581246167, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.4790518} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.84996485710144, "x": 46.38444827017854, "y": 8.058117936436949, "z": null, "yaw": 3.4298465293868547, "pitch": null, "roll": null}, "v": 0.9679272820913979, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2577651963387383, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24287661599357135, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.4990518} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23601605743019355, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9662897546980719, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.4990518} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.84996485710144, "x": 46.38444827017854, "y": 8.058117936436949, "z": null, "yaw": 3.4298465293868547, "pitch": null, "roll": null}, "v": 0.9679272820913979, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2577651963387383, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24287661599357135, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.5190518} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23601605743019355, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9656389545979354, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.5190518} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.84996485710144, "x": 46.38444827017854, "y": 8.058117936436949, "z": null, "yaw": 3.4298465293868547, "pitch": null, "roll": null}, "v": 0.9679272820913979, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2577651963387383, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24287661599357135, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.5390518} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23601605743019355, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9649890564027483, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.5390518} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502675.5490518, "x": 50.28290212407345, "y": 13.026617871857878, "z": null, "yaw": 3.4574482183294015, "pitch": null, "roll": null}, "v": 0.9646644450760363, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575389971697404, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24205789042658732, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.5590518} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2292451020648066, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.964340058693726, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.5590518} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.959964752197266, "x": 46.28290212407345, "y": 8.026617871857878, "z": null, "yaw": 3.4574482183294015, "pitch": null, "roll": null}, "v": 0.9646644450760363, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575389971697404, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24205789042658732, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.5790517} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23134971703793322, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9628458837998826, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.5790517} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.959964752197266, "x": 46.28290212407345, "y": 8.026617871857878, "z": null, "yaw": 3.4574482183294015, "pitch": null, "roll": null}, "v": 0.9646644450760363, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575389971697404, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24205789042658732, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.5990517} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23134971703793322, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.961616763841564, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.5990517} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.959964752197266, "x": 46.28290212407345, "y": 8.026617871857878, "z": null, "yaw": 3.4574482183294015, "pitch": null, "roll": null}, "v": 0.9646644450760363, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575389971697404, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24205789042658732, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.6190517} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23134971703793322, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9603893453420362, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.6190517} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 36.959964752197266, "x": 46.28290212407345, "y": 8.026617871857878, "z": null, "yaw": 3.4574482183294015, "pitch": null, "roll": null}, "v": 0.9646644450760363, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2575389971697404, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24205789042658732, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.6390517} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23134971703793322, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9591636253435722, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.6390517} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502675.6590517, "x": 50.18277605395547, "y": 12.992502727895685, "z": null, "yaw": 3.4850499072719483, "pitch": null, "roll": null}, "v": 0.9579396008950392, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2570734628343814, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2403704626332147, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.6590517} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24852348444190517, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9579396008950392, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.6590517} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.06996464729309, "x": 46.18277605395547, "y": 7.992502727895685, "z": null, "yaw": 3.4850499072719483, "pitch": null, "roll": null}, "v": 0.9579396008950392, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2570734628343814, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2403704626332147, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.6790516} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24313340187738247, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9588632476702814, "gear": 1, "accelerator_pedal_position": 0.24852348444190517, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.6790516} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.06996464729309, "x": 46.18277605395547, "y": 7.992502727895685, "z": null, "yaw": 3.4850499072719483, "pitch": null, "roll": null}, "v": 0.9579396008950392, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2570734628343814, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2403704626332147, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.6990516} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24313340187738247, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9591120898093137, "gear": 1, "accelerator_pedal_position": 0.24313340187738247, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.6990516} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.06996464729309, "x": 46.18277605395547, "y": 7.992502727895685, "z": null, "yaw": 3.4850499072719483, "pitch": null, "roll": null}, "v": 0.9579396008950392, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2570734628343814, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2403704626332147, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.7190516} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24313340187738247, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9593605877644958, "gear": 1, "accelerator_pedal_position": 0.24313340187738247, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.7190516} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.06996464729309, "x": 46.18277605395547, "y": 7.992502727895685, "z": null, "yaw": 3.4850499072719483, "pitch": null, "roll": null}, "v": 0.9579396008950392, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2570734628343814, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2403704626332147, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.7390516} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24313340187738247, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9596087419871908, "gear": 1, "accelerator_pedal_position": 0.24313340187738247, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.7390516} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.06996464729309, "x": 46.18277605395547, "y": 7.992502727895685, "z": null, "yaw": 3.4850499072719483, "pitch": null, "roll": null}, "v": 0.9579396008950392, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2570734628343814, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2403704626332147, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.7590516} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24313340187738247, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9598565529282397, "gear": 1, "accelerator_pedal_position": 0.24313340187738247, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.7590516} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502675.7690516, "x": 50.08388899822574, "y": 12.95573138726454, "z": null, "yaw": 3.512651596214495, "pitch": null, "roll": null}, "v": 0.959980329808892, "accelerator_pedal_position": 0.24313340187738247, "brake_pedal_position": 0.0, "acceleration": 0.012369122906995877, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24088253140318042, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.7790515} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23410574171796467, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.960104021037962, "gear": 1, "accelerator_pedal_position": 0.24313340187738247, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.7790515} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.179964542388916, "x": 46.08388899822574, "y": 7.9557313872645405, "z": null, "yaw": 3.512651596214495, "pitch": null, "roll": null}, "v": 0.959980329808892, "accelerator_pedal_position": 0.24313340187738247, "brake_pedal_position": 0.0, "acceleration": 0.012369122906995877, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24088253140318042, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.7990515} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2369339461717112, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9592230796863823, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.7990515} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.179964542388916, "x": 46.08388899822574, "y": 7.9557313872645405, "z": null, "yaw": 3.512651596214495, "pitch": null, "roll": null}, "v": 0.959980329808892, "accelerator_pedal_position": 0.24313340187738247, "brake_pedal_position": 0.0, "acceleration": 0.012369122906995877, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24088253140318042, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.8190515} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2369339461717112, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9586967602165549, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.8190515} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.179964542388916, "x": 46.08388899822574, "y": 7.9557313872645405, "z": null, "yaw": 3.512651596214495, "pitch": null, "roll": null}, "v": 0.959980329808892, "accelerator_pedal_position": 0.24313340187738247, "brake_pedal_position": 0.0, "acceleration": 0.012369122906995877, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24088253140318042, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.8390515} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2369339461717112, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9581711686743515, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.8390515} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.179964542388916, "x": 46.08388899822574, "y": 7.9557313872645405, "z": null, "yaw": 3.512651596214495, "pitch": null, "roll": null}, "v": 0.959980329808892, "accelerator_pedal_position": 0.24313340187738247, "brake_pedal_position": 0.0, "acceleration": 0.012369122906995877, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24088253140318042, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.8590515} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2369339461717112, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9576463039425493, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.8590515} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502675.8790514, "x": 49.98609488572707, "y": 12.916262605614635, "z": null, "yaw": 3.540253285157042, "pitch": null, "roll": null}, "v": 0.957122164905929, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2570169366308386, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2401653479613796, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.8790514} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23672027321518221, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.957122164905929, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.8790514} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.28996443748474, "x": 45.98609488572707, "y": 7.9162626056146355, "z": null, "yaw": 3.540253285157042, "pitch": null, "roll": null}, "v": 0.957122164905929, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2570169366308386, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2401653479613796, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.8990514} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23677716094160572, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9565720505646556, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.8990514} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.28996443748474, "x": 45.98609488572707, "y": 7.9162626056146355, "z": null, "yaw": 3.540253285157042, "pitch": null, "roll": null}, "v": 0.957122164905929, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2570169366308386, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2401653479613796, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.9190514} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23677716094160572, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9560298051027091, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.9190514} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.28996443748474, "x": 45.98609488572707, "y": 7.9162626056146355, "z": null, "yaw": 3.540253285157042, "pitch": null, "roll": null}, "v": 0.957122164905929, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2570169366308386, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2401653479613796, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.9390514} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23677716094160572, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9554883090176804, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.9390514} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.28996443748474, "x": 45.98609488572707, "y": 7.9162626056146355, "z": null, "yaw": 3.540253285157042, "pitch": null, "roll": null}, "v": 0.957122164905929, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2570169366308386, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2401653479613796, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.9590514} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23677716094160572, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9549475611566927, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.9590514} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.28996443748474, "x": 45.98609488572707, "y": 7.9162626056146355, "z": null, "yaw": 3.540253285157042, "pitch": null, "roll": null}, "v": 0.957122164905929, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2570169366308386, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2401653479613796, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.9790514} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23677716094160572, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.954407560368948, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.9790514} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502675.9890513, "x": 49.88972796501033, "y": 12.874241008266301, "z": null, "yaw": 3.5678549740995886, "pitch": null, "roll": null}, "v": 0.954137839768485, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25681068216120495, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23941650783276908, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502675.9990513} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2318440368008311, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9538683055057233, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502675.9990513} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.399964332580566, "x": 45.88972796501033, "y": 7.874241008266301, "z": null, "yaw": 3.5678549740995886, "pitch": null, "roll": null}, "v": 0.954137839768485, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25681068216120495, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23941650783276908, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.0190513} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23337532637533318, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9527133678561669, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.0190513} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.399964332580566, "x": 45.88972796501033, "y": 7.874241008266301, "z": null, "yaw": 3.5678549740995886, "pitch": null, "roll": null}, "v": 0.954137839768485, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25681068216120495, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23941650783276908, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.0390513} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23337532637533318, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9517513699748251, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.0390513} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.399964332580566, "x": 45.88972796501033, "y": 7.874241008266301, "z": null, "yaw": 3.5678549740995886, "pitch": null, "roll": null}, "v": 0.954137839768485, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25681068216120495, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23941650783276908, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.0590513} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23337532637533318, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9507906999585249, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.0590513} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.399964332580566, "x": 45.88972796501033, "y": 7.874241008266301, "z": null, "yaw": 3.5678549740995886, "pitch": null, "roll": null}, "v": 0.954137839768485, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25681068216120495, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23941650783276908, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.0790513} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23337532637533318, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.94983135560536, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.0790513} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502676.0990512, "x": 49.794953885458895, "y": 12.829762577743626, "z": null, "yaw": 3.5954566630421354, "pitch": null, "roll": null}, "v": 0.9488733347179905, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2564472727892879, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23809551482513067, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.0990512} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23991115972928737, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9488733347179905, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.0990512} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.50996422767639, "x": 45.794953885458895, "y": 7.829762577743626, "z": null, "yaw": 3.5954566630421354, "pitch": null, "roll": null}, "v": 0.9488733347179905, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2564472727892879, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23809551482513067, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.1190512} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23785053998653324, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9487333325295153, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.1190512} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.50996422767639, "x": 45.794953885458895, "y": 7.829762577743626, "z": null, "yaw": 3.5954566630421354, "pitch": null, "roll": null}, "v": 0.9488733347179905, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2564472727892879, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23809551482513067, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.1390512} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23785053998653324, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9483360347687746, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.1390512} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.50996422767639, "x": 45.794953885458895, "y": 7.829762577743626, "z": null, "yaw": 3.5954566630421354, "pitch": null, "roll": null}, "v": 0.9488733347179905, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2564472727892879, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23809551482513067, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.1590512} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23785053998653324, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.947939284841316, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.1590512} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.50996422767639, "x": 45.794953885458895, "y": 7.829762577743626, "z": null, "yaw": 3.5954566630421354, "pitch": null, "roll": null}, "v": 0.9488733347179905, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2564472727892879, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23809551482513067, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.1790512} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23785053998653324, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9475430819287903, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.1790512} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.50996422767639, "x": 45.794953885458895, "y": 7.829762577743626, "z": null, "yaw": 3.5954566630421354, "pitch": null, "roll": null}, "v": 0.9488733347179905, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2564472727892879, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23809551482513067, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.1990511} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23785053998653324, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9471474252142374, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.1990511} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502676.2090511, "x": 49.70180478487369, "y": 12.782866474232145, "z": null, "yaw": 3.623058351984682, "pitch": null, "roll": null}, "v": 0.9469498014262797, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25631462933552673, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23761285330159945, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.2190511} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24266828543439972, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9467523138820828, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.2190511} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.61996412277222, "x": 45.70180478487369, "y": 7.782866474232145, "z": null, "yaw": 3.623058351984682, "pitch": null, "roll": null}, "v": 0.9469498014262797, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25631462933552673, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23761285330159945, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.239051} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24115610681779184, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9469597577322454, "gear": 1, "accelerator_pedal_position": 0.24266828543439972, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.239051} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.61996412277222, "x": 45.70180478487369, "y": 7.782866474232145, "z": null, "yaw": 3.623058351984682, "pitch": null, "roll": null}, "v": 0.9469498014262797, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25631462933552673, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23761285330159945, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.259051} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24115610681779184, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9469779584942832, "gear": 1, "accelerator_pedal_position": 0.24115610681779184, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.259051} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.61996412277222, "x": 45.70180478487369, "y": 7.782866474232145, "z": null, "yaw": 3.623058351984682, "pitch": null, "roll": null}, "v": 0.9469498014262797, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25631462933552673, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23761285330159945, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.279051} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24115610681779184, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9469961341699542, "gear": 1, "accelerator_pedal_position": 0.24115610681779184, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.279051} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.61996412277222, "x": 45.70180478487369, "y": 7.782866474232145, "z": null, "yaw": 3.623058351984682, "pitch": null, "roll": null}, "v": 0.9469498014262797, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25631462933552673, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23761285330159945, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.299051} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24115610681779184, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9470142847937031, "gear": 1, "accelerator_pedal_position": 0.24115610681779184, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.299051} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502676.319051, "x": 49.61009698857563, "y": 12.733476951042066, "z": null, "yaw": 3.650660040927229, "pitch": null, "roll": null}, "v": 0.9470324103999277, "accelerator_pedal_position": 0.24115610681779184, "brake_pedal_position": 0.0, "acceleration": 0.0009053432277235651, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23763358191245848, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.319051} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23466416851461727, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9470324103999277, "gear": 1, "accelerator_pedal_position": 0.24115610681779184, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.319051} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.72996401786804, "x": 45.61009698857563, "y": 7.733476951042066, "z": null, "yaw": 3.650660040927229, "pitch": null, "roll": null}, "v": 0.9470324103999277, "accelerator_pedal_position": 0.24115610681779184, "brake_pedal_position": 0.0, "acceleration": 0.0009053432277235651, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23763358191245848, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.339051} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23669318531708383, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9462392984433756, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.339051} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.72996401786804, "x": 45.61009698857563, "y": 7.733476951042066, "z": null, "yaw": 3.650660040927229, "pitch": null, "roll": null}, "v": 0.9470324103999277, "accelerator_pedal_position": 0.24115610681779184, "brake_pedal_position": 0.0, "acceleration": 0.0009053432277235651, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23763358191245848, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.359051} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23669318531708383, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9457008191771432, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.359051} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.72996401786804, "x": 45.61009698857563, "y": 7.733476951042066, "z": null, "yaw": 3.650660040927229, "pitch": null, "roll": null}, "v": 0.9470324103999277, "accelerator_pedal_position": 0.24115610681779184, "brake_pedal_position": 0.0, "acceleration": 0.0009053432277235651, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23763358191245848, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.379051} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23669318531708383, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.945163081859545, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.379051} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.72996401786804, "x": 45.61009698857563, "y": 7.733476951042066, "z": null, "yaw": 3.650660040927229, "pitch": null, "roll": null}, "v": 0.9470324103999277, "accelerator_pedal_position": 0.24115610681779184, "brake_pedal_position": 0.0, "acceleration": 0.0009053432277235651, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23763358191245848, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.399051} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23669318531708383, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9446260853526552, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.399051} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.72996401786804, "x": 45.61009698857563, "y": 7.733476951042066, "z": null, "yaw": 3.650660040927229, "pitch": null, "roll": null}, "v": 0.9470324103999277, "accelerator_pedal_position": 0.24115610681779184, "brake_pedal_position": 0.0, "acceleration": 0.0009053432277235651, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23763358191245848, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.419051} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23669318531708383, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9440898285205941, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.419051} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502676.429051, "x": 49.519928516168946, "y": 12.68165745952173, "z": null, "yaw": 3.6782617298697757, "pitch": null, "roll": null}, "v": 0.9438219771282199, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2560990981015132, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23682800572576318, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.439051} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2501101318340698, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9435543102295225, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.439051} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.83996391296387, "x": 45.519928516168946, "y": 7.68165745952173, "z": null, "yaw": 3.6782617298697757, "pitch": null, "roll": null}, "v": 0.9438219771282199, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2560990981015132, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23682800572576318, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.459051} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24590627197714826, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9446960701120033, "gear": 1, "accelerator_pedal_position": 0.2501101318340698, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.459051} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.83996391296387, "x": 45.519928516168946, "y": 7.68165745952173, "z": null, "yaw": 3.6782617298697757, "pitch": null, "roll": null}, "v": 0.9438219771282199, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2560990981015132, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23682800572576318, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.4790509} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24590627197714826, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9453109560141038, "gear": 1, "accelerator_pedal_position": 0.24590627197714826, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.4790509} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.83996391296387, "x": 45.519928516168946, "y": 7.68165745952173, "z": null, "yaw": 3.6782617298697757, "pitch": null, "roll": null}, "v": 0.9438219771282199, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2560990981015132, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23682800572576318, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.4990509} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24590627197714826, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9459249948566976, "gear": 1, "accelerator_pedal_position": 0.24590627197714826, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.4990509} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.83996391296387, "x": 45.519928516168946, "y": 7.68165745952173, "z": null, "yaw": 3.6782617298697757, "pitch": null, "roll": null}, "v": 0.9438219771282199, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2560990981015132, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23682800572576318, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.5190508} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24590627197714826, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9465381876559181, "gear": 1, "accelerator_pedal_position": 0.24590627197714826, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.5190508} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502676.5390508, "x": 49.43124648190866, "y": 12.627380671245348, "z": null, "yaw": 3.7058634188123225, "pitch": null, "roll": null}, "v": 0.9471505354271224, "accelerator_pedal_position": 0.24590627197714826, "brake_pedal_position": 0.0, "acceleration": 0.030585731718221598, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2376632223693399, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.5390508} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2333479522301551, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9471505354271224, "gear": 1, "accelerator_pedal_position": 0.24590627197714826, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.5390508} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.94996380805969, "x": 45.43124648190866, "y": 7.627380671245348, "z": null, "yaw": 3.7058634188123225, "pitch": null, "roll": null}, "v": 0.9471505354271224, "accelerator_pedal_position": 0.24590627197714826, "brake_pedal_position": 0.0, "acceleration": 0.030585731718221598, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2376632223693399, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.5590508} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23728389823356985, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.946192790333155, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.5590508} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.94996380805969, "x": 45.43124648190866, "y": 7.627380671245348, "z": null, "yaw": 3.7058634188123225, "pitch": null, "roll": null}, "v": 0.9471505354271224, "accelerator_pedal_position": 0.24590627197714826, "brake_pedal_position": 0.0, "acceleration": 0.030585731718221598, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2376632223693399, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.5790508} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23728389823356985, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9457281888231541, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.5790508} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.94996380805969, "x": 45.43124648190866, "y": 7.627380671245348, "z": null, "yaw": 3.7058634188123225, "pitch": null, "roll": null}, "v": 0.9471505354271224, "accelerator_pedal_position": 0.24590627197714826, "brake_pedal_position": 0.0, "acceleration": 0.030585731718221598, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2376632223693399, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.5990508} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23728389823356985, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9452642274702897, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.5990508} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.94996380805969, "x": 45.43124648190866, "y": 7.627380671245348, "z": null, "yaw": 3.7058634188123225, "pitch": null, "roll": null}, "v": 0.9471505354271224, "accelerator_pedal_position": 0.24590627197714826, "brake_pedal_position": 0.0, "acceleration": 0.030585731718221598, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2376632223693399, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.6190507} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23728389823356985, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9448009053064387, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.6190507} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 37.94996380805969, "x": 45.43124648190866, "y": 7.627380671245348, "z": null, "yaw": 3.7058634188123225, "pitch": null, "roll": null}, "v": 0.9471505354271224, "accelerator_pedal_position": 0.24590627197714826, "brake_pedal_position": 0.0, "acceleration": 0.030585731718221598, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2376632223693399, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.6390507} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23728389823356985, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9443382213651675, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.6390507} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502676.6490507, "x": 49.3440656423518, "y": 12.570659191269725, "z": null, "yaw": 3.7334651077548693, "pitch": null, "roll": null}, "v": 0.94410711842645, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2561187384319575, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23689955464774878, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.6590507} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24202690969204654, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9438761746817286, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.6590507} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.05996370315552, "x": 45.3440656423518, "y": 7.5706591912697245, "z": null, "yaw": 3.7334651077548693, "pitch": null, "roll": null}, "v": 0.94410711842645, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2561187384319575, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23689955464774878, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.6790507} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24053423114724637, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9440074365509593, "gear": 1, "accelerator_pedal_position": 0.24202690969204654, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.6790507} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.05996370315552, "x": 45.3440656423518, "y": 7.5706591912697245, "z": null, "yaw": 3.7334651077548693, "pitch": null, "roll": null}, "v": 0.94410711842645, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2561187384319575, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23689955464774878, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.6990507} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24053423114724637, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9439519970996508, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.6990507} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.05996370315552, "x": 45.3440656423518, "y": 7.5706591912697245, "z": null, "yaw": 3.7334651077548693, "pitch": null, "roll": null}, "v": 0.94410711842645, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2561187384319575, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23689955464774878, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.7190506} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24053423114724637, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9438966339946709, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.7190506} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.05996370315552, "x": 45.3440656423518, "y": 7.5706591912697245, "z": null, "yaw": 3.7334651077548693, "pitch": null, "roll": null}, "v": 0.94410711842645, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2561187384319575, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23689955464774878, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.7390506} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24053423114724637, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9438413471296566, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.7390506} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502676.7590506, "x": 49.25863187194749, "y": 12.51165499189019, "z": null, "yaw": 3.761066796697416, "pitch": null, "roll": null}, "v": 0.9437861363983963, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25609662953249795, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23681901241052616, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.7590506} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24630352643333842, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9437861363983963, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.7590506} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.16996359825134, "x": 45.25863187194749, "y": 7.51165499189019, "z": null, "yaw": 3.761066796697416, "pitch": null, "roll": null}, "v": 0.9437861363983963, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25609662953249795, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23681901241052616, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.7790506} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24449951502865963, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9444519152418391, "gear": 1, "accelerator_pedal_position": 0.24630352643333842, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.7790506} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.16996359825134, "x": 45.25863187194749, "y": 7.51165499189019, "z": null, "yaw": 3.761066796697416, "pitch": null, "roll": null}, "v": 0.9437861363983963, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25609662953249795, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23681901241052616, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.7990506} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24449951502865963, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9448913534017912, "gear": 1, "accelerator_pedal_position": 0.24449951502865963, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.7990506} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.16996359825134, "x": 45.25863187194749, "y": 7.51165499189019, "z": null, "yaw": 3.761066796697416, "pitch": null, "roll": null}, "v": 0.9437861363983963, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25609662953249795, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23681901241052616, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.8190506} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24449951502865963, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9453301862629575, "gear": 1, "accelerator_pedal_position": 0.24449951502865963, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.8190506} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.16996359825134, "x": 45.25863187194749, "y": 7.51165499189019, "z": null, "yaw": 3.761066796697416, "pitch": null, "roll": null}, "v": 0.9437861363983963, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25609662953249795, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23681901241052616, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.8390505} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24449951502865963, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9457684145820964, "gear": 1, "accelerator_pedal_position": 0.24449951502865963, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.8390505} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.16996359825134, "x": 45.25863187194749, "y": 7.51165499189019, "z": null, "yaw": 3.761066796697416, "pitch": null, "roll": null}, "v": 0.9437861363983963, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25609662953249795, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23681901241052616, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.8590505} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24449951502865963, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9462060391152418, "gear": 1, "accelerator_pedal_position": 0.24449951502865963, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.8590505} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502676.8690505, "x": 49.17475729688604, "y": 12.450240078634442, "z": null, "yaw": 3.788668485639963, "pitch": null, "roll": null}, "v": 0.9464246251981296, "accelerator_pedal_position": 0.24449951502865963, "brake_pedal_position": 0.0, "acceleration": 0.021843541957401902, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23748107374805927, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.8790505} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2494233476042687, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9466430606177036, "gear": 1, "accelerator_pedal_position": 0.24449951502865963, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.8790505} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.27996349334717, "x": 45.17475729688604, "y": 7.450240078634442, "z": null, "yaw": 3.788668485639963, "pitch": null, "roll": null}, "v": 0.9464246251981296, "accelerator_pedal_position": 0.24449951502865963, "brake_pedal_position": 0.0, "acceleration": 0.021843541957401902, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23748107374805927, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.8990505} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24789373879346233, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9476947467594459, "gear": 1, "accelerator_pedal_position": 0.2494233476042687, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.8990505} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.27996349334717, "x": 45.17475729688604, "y": 7.450240078634442, "z": null, "yaw": 3.788668485639963, "pitch": null, "roll": null}, "v": 0.9464246251981296, "accelerator_pedal_position": 0.24449951502865963, "brake_pedal_position": 0.0, "acceleration": 0.021843541957401902, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23748107374805927, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.9190505} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24789373879346233, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.948553847982761, "gear": 1, "accelerator_pedal_position": 0.24789373879346233, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.9190505} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.27996349334717, "x": 45.17475729688604, "y": 7.450240078634442, "z": null, "yaw": 3.788668485639963, "pitch": null, "roll": null}, "v": 0.9464246251981296, "accelerator_pedal_position": 0.24449951502865963, "brake_pedal_position": 0.0, "acceleration": 0.021843541957401902, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23748107374805927, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.9390504} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24789373879346233, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9494117646257997, "gear": 1, "accelerator_pedal_position": 0.24789373879346233, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.9390504} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.27996349334717, "x": 45.17475729688604, "y": 7.450240078634442, "z": null, "yaw": 3.788668485639963, "pitch": null, "roll": null}, "v": 0.9464246251981296, "accelerator_pedal_position": 0.24449951502865963, "brake_pedal_position": 0.0, "acceleration": 0.021843541957401902, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23748107374805927, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.9590504} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24789373879346233, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9502684980276253, "gear": 1, "accelerator_pedal_position": 0.24789373879346233, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.9590504} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502676.9790504, "x": 49.09231017500992, "y": 12.386300847951501, "z": null, "yaw": 3.8162701745825096, "pitch": null, "roll": null}, "v": 0.951124049526672, "accelerator_pedal_position": 0.24789373879346233, "brake_pedal_position": 0.0, "acceleration": 0.04273329540692572, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2386602741891999, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.9790504} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24308130730165736, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.951124049526672, "gear": 1, "accelerator_pedal_position": 0.24789373879346233, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.9790504} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.38996338844299, "x": 45.09231017500992, "y": 7.386300847951501, "z": null, "yaw": 3.8162701745825096, "pitch": null, "roll": null}, "v": 0.951124049526672, "accelerator_pedal_position": 0.24789373879346233, "brake_pedal_position": 0.0, "acceleration": 0.04273329540692572, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2386602741891999, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502676.9990504} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24460140039352177, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9513770741446519, "gear": 1, "accelerator_pedal_position": 0.24308130730165736, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502676.9990504} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.38996338844299, "x": 45.09231017500992, "y": 7.386300847951501, "z": null, "yaw": 3.8162701745825096, "pitch": null, "roll": null}, "v": 0.951124049526672, "accelerator_pedal_position": 0.24789373879346233, "brake_pedal_position": 0.0, "acceleration": 0.04273329540692572, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2386602741891999, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.0190504} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24460140039352177, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9518196956292452, "gear": 1, "accelerator_pedal_position": 0.24460140039352177, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.0190504} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.38996338844299, "x": 45.09231017500992, "y": 7.386300847951501, "z": null, "yaw": 3.8162701745825096, "pitch": null, "roll": null}, "v": 0.951124049526672, "accelerator_pedal_position": 0.24789373879346233, "brake_pedal_position": 0.0, "acceleration": 0.04273329540692572, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2386602741891999, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.0390503} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24460140039352177, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9522617062045542, "gear": 1, "accelerator_pedal_position": 0.24460140039352177, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.0390503} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.38996338844299, "x": 45.09231017500992, "y": 7.386300847951501, "z": null, "yaw": 3.8162701745825096, "pitch": null, "roll": null}, "v": 0.951124049526672, "accelerator_pedal_position": 0.24789373879346233, "brake_pedal_position": 0.0, "acceleration": 0.04273329540692572, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2386602741891999, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.0590503} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24460140039352177, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.952703106635638, "gear": 1, "accelerator_pedal_position": 0.24460140039352177, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.0590503} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.38996338844299, "x": 45.09231017500992, "y": 7.386300847951501, "z": null, "yaw": 3.8162701745825096, "pitch": null, "roll": null}, "v": 0.951124049526672, "accelerator_pedal_position": 0.24789373879346233, "brake_pedal_position": 0.0, "acceleration": 0.04273329540692572, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2386602741891999, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.0790503} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24460140039352177, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9531438976868227, "gear": 1, "accelerator_pedal_position": 0.24460140039352177, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.0790503} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502677.0890503, "x": 49.0113578503601, "y": 12.319864198681184, "z": null, "yaw": 3.8438718635250564, "pitch": null, "roll": null}, "v": 0.9533640649336047, "accelerator_pedal_position": 0.24460140039352177, "brake_pedal_position": 0.0, "acceleration": 0.022001518809763476, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23922234881182416, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.0990503} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25076407142396107, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9535840801217024, "gear": 1, "accelerator_pedal_position": 0.24460140039352177, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.0990503} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.49996328353882, "x": 45.0113578503601, "y": 7.319864198681184, "z": null, "yaw": 3.8438718635250564, "pitch": null, "roll": null}, "v": 0.9533640649336047, "accelerator_pedal_position": 0.24460140039352177, "brake_pedal_position": 0.0, "acceleration": 0.022001518809763476, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23922234881182416, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.1190503} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2488459685492192, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9547937225088888, "gear": 1, "accelerator_pedal_position": 0.25076407142396107, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.1190503} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.49996328353882, "x": 45.0113578503601, "y": 7.319864198681184, "z": null, "yaw": 3.8438718635250564, "pitch": null, "roll": null}, "v": 0.9533640649336047, "accelerator_pedal_position": 0.24460140039352177, "brake_pedal_position": 0.0, "acceleration": 0.022001518809763476, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23922234881182416, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.1390502} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2488459685492192, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9557620139807186, "gear": 1, "accelerator_pedal_position": 0.2488459685492192, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.1390502} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.49996328353882, "x": 45.0113578503601, "y": 7.319864198681184, "z": null, "yaw": 3.8438718635250564, "pitch": null, "roll": null}, "v": 0.9533640649336047, "accelerator_pedal_position": 0.24460140039352177, "brake_pedal_position": 0.0, "acceleration": 0.022001518809763476, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23922234881182416, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.1590502} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2488459685492192, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9567289675348648, "gear": 1, "accelerator_pedal_position": 0.2488459685492192, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.1590502} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.49996328353882, "x": 45.0113578503601, "y": 7.319864198681184, "z": null, "yaw": 3.8438718635250564, "pitch": null, "roll": null}, "v": 0.9533640649336047, "accelerator_pedal_position": 0.24460140039352177, "brake_pedal_position": 0.0, "acceleration": 0.022001518809763476, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.23922234881182416, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.1790502} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2488459685492192, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9576945846460984, "gear": 1, "accelerator_pedal_position": 0.2488459685492192, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.1790502} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502677.1990502, "x": 48.93196604184634, "y": 12.250953946143964, "z": null, "yaw": 3.871473552467603, "pitch": null, "roll": null}, "v": 0.9586588667887022, "accelerator_pedal_position": 0.2488459685492192, "brake_pedal_position": 0.0, "acceleration": 0.0481640918644588, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2405509440283408, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.1990502} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.252133051014317, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9586588667887022, "gear": 1, "accelerator_pedal_position": 0.2488459685492192, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.1990502} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.609963178634644, "x": 44.93196604184634, "y": 7.250953946143964, "z": null, "yaw": 3.871473552467603, "pitch": null, "roll": null}, "v": 0.9586588667887022, "accelerator_pedal_position": 0.2488459685492192, "brake_pedal_position": 0.0, "acceleration": 0.0481640918644588, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2405509440283408, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.2190502} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25112413597839833, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.960032558609382, "gear": 1, "accelerator_pedal_position": 0.252133051014317, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.2190502} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.609963178634644, "x": 44.93196604184634, "y": 7.250953946143964, "z": null, "yaw": 3.871473552467603, "pitch": null, "roll": null}, "v": 0.9586588667887022, "accelerator_pedal_position": 0.2488459685492192, "brake_pedal_position": 0.0, "acceleration": 0.0481640918644588, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2405509440283408, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.2390501} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25112413597839833, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9612782793339049, "gear": 1, "accelerator_pedal_position": 0.25112413597839833, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.2390501} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.609963178634644, "x": 44.93196604184634, "y": 7.250953946143964, "z": null, "yaw": 3.871473552467603, "pitch": null, "roll": null}, "v": 0.9586588667887022, "accelerator_pedal_position": 0.2488459685492192, "brake_pedal_position": 0.0, "acceleration": 0.0481640918644588, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2405509440283408, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.2590501} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25112413597839833, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9625222760960933, "gear": 1, "accelerator_pedal_position": 0.25112413597839833, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.2590501} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.609963178634644, "x": 44.93196604184634, "y": 7.250953946143964, "z": null, "yaw": 3.871473552467603, "pitch": null, "roll": null}, "v": 0.9586588667887022, "accelerator_pedal_position": 0.2488459685492192, "brake_pedal_position": 0.0, "acceleration": 0.0481640918644588, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2405509440283408, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.27905} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25112413597839833, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9637645506629547, "gear": 1, "accelerator_pedal_position": 0.25112413597839833, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.27905} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.609963178634644, "x": 44.93196604184634, "y": 7.250953946143964, "z": null, "yaw": 3.871473552467603, "pitch": null, "roll": null}, "v": 0.9586588667887022, "accelerator_pedal_position": 0.2488459685492192, "brake_pedal_position": 0.0, "acceleration": 0.0481640918644588, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2405509440283408, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.29905} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25112413597839833, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9650051048016204, "gear": 1, "accelerator_pedal_position": 0.25112413597839833, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.29905} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502677.30905, "x": 48.854007976535186, "y": 12.17942115403078, "z": null, "yaw": 3.89907524141015, "pitch": null, "roll": null}, "v": 0.9656247372626402, "accelerator_pedal_position": 0.25112413597839833, "brake_pedal_position": 0.0, "acceleration": 0.06192030166972201, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2422988512104837, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.31905} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2646245530951389, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9662439402793375, "gear": 1, "accelerator_pedal_position": 0.25112413597839833, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.31905} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.71996307373047, "x": 44.854007976535186, "y": 7.179421154030781, "z": null, "yaw": 3.89907524141015, "pitch": null, "roll": null}, "v": 0.9656247372626402, "accelerator_pedal_position": 0.25112413597839833, "brake_pedal_position": 0.0, "acceleration": 0.06192030166972201, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2422988512104837, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.33905} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26042978682720974, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9703663748782213, "gear": 1, "accelerator_pedal_position": 0.26042978682720974, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.33905} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.71996307373047, "x": 44.854007976535186, "y": 7.179421154030781, "z": null, "yaw": 3.89907524141015, "pitch": null, "roll": null}, "v": 0.9656247372626402, "accelerator_pedal_position": 0.25112413597839833, "brake_pedal_position": 0.0, "acceleration": 0.06192030166972201, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2422988512104837, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.35905} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26042978682720974, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9715638922773334, "gear": 1, "accelerator_pedal_position": 0.26042978682720974, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.35905} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.71996307373047, "x": 44.854007976535186, "y": 7.179421154030781, "z": null, "yaw": 3.89907524141015, "pitch": null, "roll": null}, "v": 0.9656247372626402, "accelerator_pedal_position": 0.25112413597839833, "brake_pedal_position": 0.0, "acceleration": 0.06192030166972201, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2422988512104837, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.37905} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26042978682720974, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9739564334414513, "gear": 1, "accelerator_pedal_position": 0.26042978682720974, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.37905} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.71996307373047, "x": 44.854007976535186, "y": 7.179421154030781, "z": null, "yaw": 3.89907524141015, "pitch": null, "roll": null}, "v": 0.9656247372626402, "accelerator_pedal_position": 0.25112413597839833, "brake_pedal_position": 0.0, "acceleration": 0.06192030166972201, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2422988512104837, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.39905} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26042978682720974, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.976345651699251, "gear": 1, "accelerator_pedal_position": 0.26042978682720974, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.39905} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502677.41905, "x": 48.77729588381564, "y": 12.105026885556137, "z": null, "yaw": 3.9266769303526967, "pitch": null, "roll": null}, "v": 0.9787315493832339, "accelerator_pedal_position": 0.26042978682720974, "brake_pedal_position": 0.0, "acceleration": 0.11917043574331804, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24558767076667504, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.41905} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24324126666543702, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.925549256315893, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9787315493832339, "gear": 1, "accelerator_pedal_position": 0.26042978682720974, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.41905} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.829962968826294, "x": 44.77729588381564, "y": 7.105026885556137, "z": null, "yaw": 3.9266769303526967, "pitch": null, "roll": null}, "v": 0.9787315493832339, "accelerator_pedal_position": 0.26042978682720974, "brake_pedal_position": 0.0, "acceleration": 0.11917043574331804, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24558767076667504, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.43905} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24865819195417774, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.925549256315893, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.978966311380683, "gear": 1, "accelerator_pedal_position": 0.24324126666543702, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.43905} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.829962968826294, "x": 44.77729588381564, "y": 7.105026885556137, "z": null, "yaw": 3.9266769303526967, "pitch": null, "roll": null}, "v": 0.9787315493832339, "accelerator_pedal_position": 0.26042978682720974, "brake_pedal_position": 0.0, "acceleration": 0.11917043574331804, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24558767076667504, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.45905} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24865819195417774, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.925549256315893, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9798776268810976, "gear": 1, "accelerator_pedal_position": 0.24865819195417774, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.45905} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.829962968826294, "x": 44.77729588381564, "y": 7.105026885556137, "z": null, "yaw": 3.9266769303526967, "pitch": null, "roll": null}, "v": 0.9787315493832339, "accelerator_pedal_position": 0.26042978682720974, "brake_pedal_position": 0.0, "acceleration": 0.11917043574331804, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24558767076667504, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.47905} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24865819195417774, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.925549256315893, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9807876743993891, "gear": 1, "accelerator_pedal_position": 0.24865819195417774, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.47905} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.829962968826294, "x": 44.77729588381564, "y": 7.105026885556137, "z": null, "yaw": 3.9266769303526967, "pitch": null, "roll": null}, "v": 0.9787315493832339, "accelerator_pedal_position": 0.26042978682720974, "brake_pedal_position": 0.0, "acceleration": 0.11917043574331804, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24558767076667504, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.49905} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24865819195417774, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.925549256315893, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9816964553686377, "gear": 1, "accelerator_pedal_position": 0.24865819195417774, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.49905} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.829962968826294, "x": 44.77729588381564, "y": 7.105026885556137, "z": null, "yaw": 3.9266769303526967, "pitch": null, "roll": null}, "v": 0.9787315493832339, "accelerator_pedal_position": 0.26042978682720974, "brake_pedal_position": 0.0, "acceleration": 0.11917043574331804, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24558767076667504, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.51905} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24865819195417774, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.925549256315893, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9826039712213114, "gear": 1, "accelerator_pedal_position": 0.24865819195417774, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.51905} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502677.5290499, "x": 48.70197851453948, "y": 12.027842360976964, "z": null, "yaw": 3.9542786192952435, "pitch": null, "roll": null}, "v": 0.9830572551764108, "accelerator_pedal_position": 0.24865819195417774, "brake_pedal_position": 0.0, "acceleration": 0.045296821285240485, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2466730960917682, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.5390499} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2575953615014369, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.609741275512887, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9845214491354574, "gear": 1, "accelerator_pedal_position": 0.2575953615014369, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.5390499} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.93996286392212, "x": 44.70197851453948, "y": 7.027842360976964, "z": null, "yaw": 3.9542786192952435, "pitch": null, "roll": null}, "v": 0.9830572551764108, "accelerator_pedal_position": 0.24865819195417774, "brake_pedal_position": 0.0, "acceleration": 0.045296821285240485, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2466730960917682, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.5590498} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25481755152172564, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.609741275512887, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9855319702563486, "gear": 1, "accelerator_pedal_position": 0.2575953615014369, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.5590498} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.93996286392212, "x": 44.70197851453948, "y": 7.027842360976964, "z": null, "yaw": 3.9542786192952435, "pitch": null, "roll": null}, "v": 0.9830572551764108, "accelerator_pedal_position": 0.24865819195417774, "brake_pedal_position": 0.0, "acceleration": 0.045296821285240485, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2466730960917682, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.5790498} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25481755152172564, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.609741275512887, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9872037945805878, "gear": 1, "accelerator_pedal_position": 0.25481755152172564, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.5790498} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.93996286392212, "x": 44.70197851453948, "y": 7.027842360976964, "z": null, "yaw": 3.9542786192952435, "pitch": null, "roll": null}, "v": 0.9830572551764108, "accelerator_pedal_position": 0.24865819195417774, "brake_pedal_position": 0.0, "acceleration": 0.045296821285240485, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2466730960917682, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.5990498} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25481755152172564, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.609741275512887, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9888732880005929, "gear": 1, "accelerator_pedal_position": 0.25481755152172564, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.5990498} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 38.93996286392212, "x": 44.70197851453948, "y": 7.027842360976964, "z": null, "yaw": 3.9542786192952435, "pitch": null, "roll": null}, "v": 0.9830572551764108, "accelerator_pedal_position": 0.24865819195417774, "brake_pedal_position": 0.0, "acceleration": 0.045296821285240485, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2466730960917682, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.6190498} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25481755152172564, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.609741275512887, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9905404526516812, "gear": 1, "accelerator_pedal_position": 0.25481755152172564, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.6190498} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502677.6390498, "x": 48.62831844111934, "y": 11.948063643706952, "z": null, "yaw": 3.9818803082377903, "pitch": null, "roll": null}, "v": 0.9922052906708547, "accelerator_pedal_position": 0.25481755152172564, "brake_pedal_position": 0.0, "acceleration": 0.08315471908889005, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24896856182043212, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.6390498} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25584681345287014, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.22611132996549, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9922052906708547, "gear": 1, "accelerator_pedal_position": 0.25481755152172564, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.6390498} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.049962759017944, "x": 44.62831844111934, "y": 6.948063643706952, "z": null, "yaw": 3.9818803082377903, "pitch": null, "roll": null}, "v": 0.9922052906708547, "accelerator_pedal_position": 0.25481755152172564, "brake_pedal_position": 0.0, "acceleration": 0.08315471908889005, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24896856182043212, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.6590497} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25555707388409565, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.22611132996549, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9939964169971418, "gear": 1, "accelerator_pedal_position": 0.25584681345287014, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.6590497} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.049962759017944, "x": 44.62831844111934, "y": 6.948063643706952, "z": null, "yaw": 3.9818803082377903, "pitch": null, "roll": null}, "v": 0.9922052906708547, "accelerator_pedal_position": 0.25481755152172564, "brake_pedal_position": 0.0, "acceleration": 0.08315471908889005, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24896856182043212, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.6790497} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25555707388409565, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.22611132996549, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9957488364546603, "gear": 1, "accelerator_pedal_position": 0.25555707388409565, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.6790497} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.049962759017944, "x": 44.62831844111934, "y": 6.948063643706952, "z": null, "yaw": 3.9818803082377903, "pitch": null, "roll": null}, "v": 0.9922052906708547, "accelerator_pedal_position": 0.25481755152172564, "brake_pedal_position": 0.0, "acceleration": 0.08315471908889005, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24896856182043212, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.6990497} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25555707388409565, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.22611132996549, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9974988066684576, "gear": 1, "accelerator_pedal_position": 0.25555707388409565, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.6990497} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.049962759017944, "x": 44.62831844111934, "y": 6.948063643706952, "z": null, "yaw": 3.9818803082377903, "pitch": null, "roll": null}, "v": 0.9922052906708547, "accelerator_pedal_position": 0.25481755152172564, "brake_pedal_position": 0.0, "acceleration": 0.08315471908889005, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24896856182043212, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.7190497} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25555707388409565, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.22611132996549, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9992463298371538, "gear": 1, "accelerator_pedal_position": 0.25555707388409565, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.7190497} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.049962759017944, "x": 44.62831844111934, "y": 6.948063643706952, "z": null, "yaw": 3.9818803082377903, "pitch": null, "roll": null}, "v": 0.9922052906708547, "accelerator_pedal_position": 0.25481755152172564, "brake_pedal_position": 0.0, "acceleration": 0.08315471908889005, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.24896856182043212, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.7390497} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25555707388409565, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 10.22611132996549, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0027340438440153, "gear": 1, "accelerator_pedal_position": 0.25555707388409565, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.7390497} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502677.7490497, "x": 48.556203743968034, "y": 11.865498744781602, "z": null, "yaw": 4.009481997180338, "pitch": null, "roll": null}, "v": 1.0018630311951846, "accelerator_pedal_position": 0.25555707388409565, "brake_pedal_position": 0.0, "acceleration": 0.08710126488308245, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2513919250007993, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.7590497} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27148930816489786, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.8706557638633, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0027340438440153, "gear": 1, "accelerator_pedal_position": 0.25555707388409565, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.7590497} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.15996265411377, "x": 44.556203743968034, "y": 6.865498744781602, "z": null, "yaw": 4.009481997180338, "pitch": null, "roll": null}, "v": 1.0018630311951846, "accelerator_pedal_position": 0.25555707388409565, "brake_pedal_position": 0.0, "acceleration": 0.08710126488308245, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2513919250007993, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.7790496} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26654425515844876, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.8706557638633, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0064650705225247, "gear": 1, "accelerator_pedal_position": 0.27148930816489786, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.7790496} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.15996265411377, "x": 44.556203743968034, "y": 6.865498744781602, "z": null, "yaw": 4.009481997180338, "pitch": null, "roll": null}, "v": 1.0018630311951846, "accelerator_pedal_position": 0.25555707388409565, "brake_pedal_position": 0.0, "acceleration": 0.08710126488308245, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2513919250007993, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.7990496} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26654425515844876, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.8706557638633, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0095729525672037, "gear": 1, "accelerator_pedal_position": 0.26654425515844876, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.7990496} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.15996265411377, "x": 44.556203743968034, "y": 6.865498744781602, "z": null, "yaw": 4.009481997180338, "pitch": null, "roll": null}, "v": 1.0018630311951846, "accelerator_pedal_position": 0.25555707388409565, "brake_pedal_position": 0.0, "acceleration": 0.08710126488308245, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2513919250007993, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.8190496} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26654425515844876, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.8706557638633, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0126764741731349, "gear": 1, "accelerator_pedal_position": 0.26654425515844876, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.8190496} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.15996265411377, "x": 44.556203743968034, "y": 6.865498744781602, "z": null, "yaw": 4.009481997180338, "pitch": null, "roll": null}, "v": 1.0018630311951846, "accelerator_pedal_position": 0.25555707388409565, "brake_pedal_position": 0.0, "acceleration": 0.08710126488308245, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.2513919250007993, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.8390496} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26654425515844876, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.8706557638633, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0173235857207445, "gear": 1, "accelerator_pedal_position": 0.26654425515844876, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.8390496} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502677.8590496, "x": 48.48549491926457, "y": 11.77988206016589, "z": null, "yaw": 4.03708368612289, "pitch": null, "roll": null}, "v": 1.0188704451474808, "accelerator_pedal_position": 0.26654425515844876, "brake_pedal_position": 0.0, "acceleration": 0.15457710264298036, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25565950090651235, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.8590496} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26222273880165103, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.321791492463738, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0188704451474808, "gear": 1, "accelerator_pedal_position": 0.26654425515844876, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.408386594878307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.8590496} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.269962549209595, "x": 44.48549491926457, "y": 6.779882060165891, "z": null, "yaw": 4.03708368612289, "pitch": null, "roll": null}, "v": 1.0188704451474808, "accelerator_pedal_position": 0.26654425515844876, "brake_pedal_position": 0.0, "acceleration": 0.15457710264298036, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25565950090651235, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.8790495} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26363291584797494, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.321791492463738, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.021420899705112, "gear": 1, "accelerator_pedal_position": 0.26222273880165103, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.332727799287383, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.8790495} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.269962549209595, "x": 44.48549491926457, "y": 6.779882060165891, "z": null, "yaw": 4.03708368612289, "pitch": null, "roll": null}, "v": 1.0188704451474808, "accelerator_pedal_position": 0.26654425515844876, "brake_pedal_position": 0.0, "acceleration": 0.15457710264298036, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25565950090651235, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.8990495} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26363291584797494, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.321791492463738, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0241439737231914, "gear": 1, "accelerator_pedal_position": 0.26363291584797494, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.256740587603522, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.8990495} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.269962549209595, "x": 44.48549491926457, "y": 6.779882060165891, "z": null, "yaw": 4.03708368612289, "pitch": null, "roll": null}, "v": 1.0188704451474808, "accelerator_pedal_position": 0.26654425515844876, "brake_pedal_position": 0.0, "acceleration": 0.15457710264298036, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25565950090651235, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.9190495} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26363291584797494, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.321791492463738, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.026863211233345, "gear": 1, "accelerator_pedal_position": 0.26363291584797494, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.180424959826725, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.9190495} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.269962549209595, "x": 44.48549491926457, "y": 6.779882060165891, "z": null, "yaw": 4.03708368612289, "pitch": null, "roll": null}, "v": 1.0188704451474808, "accelerator_pedal_position": 0.26654425515844876, "brake_pedal_position": 0.0, "acceleration": 0.15457710264298036, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25565950090651235, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.9390495} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26363291584797494, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.321791492463738, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0295786146841257, "gear": 1, "accelerator_pedal_position": 0.26363291584797494, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.103780915956989, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.9390495} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.269962549209595, "x": 44.48549491926457, "y": 6.779882060165891, "z": null, "yaw": 4.03708368612289, "pitch": null, "roll": null}, "v": 1.0188704451474808, "accelerator_pedal_position": 0.26654425515844876, "brake_pedal_position": 0.0, "acceleration": 0.15457710264298036, "steering_wheel_angle": 10.408386594878307, "front_wheel_angle": 0.5709902886163745, "heading_rate": 0.25565950090651235, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.9590495} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26363291584797494, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 9.321791492463738, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0322901865331393, "gear": 1, "accelerator_pedal_position": 0.26363291584797494, "brake_pedal_position": 0.0, "steering_wheel_angle": 10.026808455994315, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.9590495} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502677.9690495, "x": 48.41607124987378, "y": 11.69097120607302, "z": null, "yaw": 4.063913919626914, "pitch": null, "roll": null}, "v": 1.03364453637745, "accelerator_pedal_position": 0.26363291584797494, "brake_pedal_position": 0.0, "acceleration": 0.13533928695514125, "steering_wheel_angle": 9.988199069978124, "front_wheel_angle": 0.542709992703555, "heading_rate": 0.2435199349245484, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.9790494} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26831795207898684, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.777543950715653, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0366431802159601, "gear": 1, "accelerator_pedal_position": 0.26831795207898684, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.911774579139028, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.9790494} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.37996244430542, "x": 44.41607124987378, "y": 6.690971206073019, "z": null, "yaw": 4.063913919626914, "pitch": null, "roll": null}, "v": 1.03364453637745, "accelerator_pedal_position": 0.26363291584797494, "brake_pedal_position": 0.0, "acceleration": 0.13533928695514125, "steering_wheel_angle": 9.988199069978124, "front_wheel_angle": 0.542709992703555, "heading_rate": 0.2435199349245484, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502677.9990494} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26690597458089993, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.777543950715653, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.03828726772248, "gear": 1, "accelerator_pedal_position": 0.26831795207898684, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.873963817728118, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502677.9990494} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.37996244430542, "x": 44.41607124987378, "y": 6.690971206073019, "z": null, "yaw": 4.063913919626914, "pitch": null, "roll": null}, "v": 1.03364453637745, "accelerator_pedal_position": 0.26363291584797494, "brake_pedal_position": 0.0, "acceleration": 0.13533928695514125, "steering_wheel_angle": 9.988199069978124, "front_wheel_angle": 0.542709992703555, "heading_rate": 0.2435199349245484, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.0190494} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26690597458089993, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.777543950715653, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0413955187677355, "gear": 1, "accelerator_pedal_position": 0.26690597458089993, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.798109013072589, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.0190494} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.37996244430542, "x": 44.41607124987378, "y": 6.690971206073019, "z": null, "yaw": 4.063913919626914, "pitch": null, "roll": null}, "v": 1.03364453637745, "accelerator_pedal_position": 0.26363291584797494, "brake_pedal_position": 0.0, "acceleration": 0.13533928695514125, "steering_wheel_angle": 9.988199069978124, "front_wheel_angle": 0.542709992703555, "heading_rate": 0.2435199349245484, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.0390494} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26690597458089993, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.777543950715653, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0444993693195248, "gear": 1, "accelerator_pedal_position": 0.26690597458089993, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.721943165972126, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.0390494} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.37996244430542, "x": 44.41607124987378, "y": 6.690971206073019, "z": null, "yaw": 4.063913919626914, "pitch": null, "roll": null}, "v": 1.03364453637745, "accelerator_pedal_position": 0.26363291584797494, "brake_pedal_position": 0.0, "acceleration": 0.13533928695514125, "steering_wheel_angle": 9.988199069978124, "front_wheel_angle": 0.542709992703555, "heading_rate": 0.2435199349245484, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.0590494} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26690597458089993, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.777543950715653, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0475988217556378, "gear": 1, "accelerator_pedal_position": 0.26690597458089993, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.645466276426719, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.0590494} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502678.0790493, "x": 48.34795274867498, "y": 11.598878849228061, "z": null, "yaw": 4.089100089785886, "pitch": null, "roll": null}, "v": 1.050693878466867, "accelerator_pedal_position": 0.26690597458089993, "brake_pedal_position": 0.0, "acceleration": 0.15458807094480365, "steering_wheel_angle": 9.568678344436375, "front_wheel_angle": 0.5151189661271693, "heading_rate": 0.23234234764717868, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.0790493} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27234103234471707, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.216852320958267, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.050693878466867, "gear": 1, "accelerator_pedal_position": 0.26690597458089993, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.568678344436375, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.0790493} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.489962339401245, "x": 44.34795274867498, "y": 6.598878849228061, "z": null, "yaw": 4.089100089785886, "pitch": null, "roll": null}, "v": 1.050693878466867, "accelerator_pedal_position": 0.26690597458089993, "brake_pedal_position": 0.0, "acceleration": 0.15458807094480365, "steering_wheel_angle": 9.568678344436375, "front_wheel_angle": 0.5151189661271693, "heading_rate": 0.23234234764717868, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.0990493} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27070296737408106, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.216852320958267, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0544636827330385, "gear": 1, "accelerator_pedal_position": 0.27234103234471707, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.493602118789335, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.0990493} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.489962339401245, "x": 44.34795274867498, "y": 6.598878849228061, "z": null, "yaw": 4.089100089785886, "pitch": null, "roll": null}, "v": 1.050693878466867, "accelerator_pedal_position": 0.26690597458089993, "brake_pedal_position": 0.0, "acceleration": 0.15458807094480365, "steering_wheel_angle": 9.568678344436375, "front_wheel_angle": 0.5151189661271693, "heading_rate": 0.23234234764717868, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.1190493} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27070296737408106, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.216852320958267, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0580234451687516, "gear": 1, "accelerator_pedal_position": 0.27070296737408106, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.418230926302698, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.1190493} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.489962339401245, "x": 44.34795274867498, "y": 6.598878849228061, "z": null, "yaw": 4.089100089785886, "pitch": null, "roll": null}, "v": 1.050693878466867, "accelerator_pedal_position": 0.26690597458089993, "brake_pedal_position": 0.0, "acceleration": 0.15458807094480365, "steering_wheel_angle": 9.568678344436375, "front_wheel_angle": 0.5151189661271693, "heading_rate": 0.23234234764717868, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.1390493} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27070296737408106, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.216852320958267, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.065127782535438, "gear": 1, "accelerator_pedal_position": 0.27070296737408106, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.266603640810626, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.1390493} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.489962339401245, "x": 44.34795274867498, "y": 6.598878849228061, "z": null, "yaw": 4.089100089785886, "pitch": null, "roll": null}, "v": 1.050693878466867, "accelerator_pedal_position": 0.26690597458089993, "brake_pedal_position": 0.0, "acceleration": 0.15458807094480365, "steering_wheel_angle": 9.568678344436375, "front_wheel_angle": 0.5151189661271693, "heading_rate": 0.23234234764717868, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.1590493} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27070296737408106, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.216852320958267, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.065127782535438, "gear": 1, "accelerator_pedal_position": 0.27070296737408106, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.266603640810626, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.1590493} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.489962339401245, "x": 44.34795274867498, "y": 6.598878849228061, "z": null, "yaw": 4.089100089785886, "pitch": null, "roll": null}, "v": 1.050693878466867, "accelerator_pedal_position": 0.26690597458089993, "brake_pedal_position": 0.0, "acceleration": 0.15458807094480365, "steering_wheel_angle": 9.568678344436375, "front_wheel_angle": 0.5151189661271693, "heading_rate": 0.23234234764717868, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.1790493} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27070296737408106, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 8.216852320958267, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0704427550014275, "gear": 1, "accelerator_pedal_position": 0.27070296737408106, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.152108888737626, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.1790493} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502678.1890492, "x": 48.280945116959785, "y": 11.503490517874942, "z": null, "yaw": 4.112739951095686, "pitch": null, "roll": null}, "v": 1.0704427550014275, "accelerator_pedal_position": 0.27070296737408106, "brake_pedal_position": 0.0, "acceleration": 0.17691293142058473, "steering_wheel_angle": 9.152108888737626, "front_wheel_angle": 0.48831751358539627, "heading_rate": 0.22212896583534397, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.1990492} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27930843640409675, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.720717847132163, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0722118843156334, "gear": 1, "accelerator_pedal_position": 0.27070296737408106, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.113796487960158, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.1990492} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.59996223449707, "x": 44.280945116959785, "y": 6.503490517874942, "z": null, "yaw": 4.112739951095686, "pitch": null, "roll": null}, "v": 1.0704427550014275, "accelerator_pedal_position": 0.27070296737408106, "brake_pedal_position": 0.0, "acceleration": 0.17691293142058473, "steering_wheel_angle": 9.152108888737626, "front_wheel_angle": 0.48831751358539627, "heading_rate": 0.22212896583534397, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.2190492} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2766895428392165, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.720717847132163, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0768216514900806, "gear": 1, "accelerator_pedal_position": 0.27930843640409675, "brake_pedal_position": 0.0, "steering_wheel_angle": 9.038652761578113, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.2190492} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.59996223449707, "x": 44.280945116959785, "y": 6.503490517874942, "z": null, "yaw": 4.112739951095686, "pitch": null, "roll": null}, "v": 1.0704427550014275, "accelerator_pedal_position": 0.27070296737408106, "brake_pedal_position": 0.0, "acceleration": 0.17691293142058473, "steering_wheel_angle": 9.152108888737626, "front_wheel_angle": 0.48831751358539627, "heading_rate": 0.22212896583534397, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.2390492} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2766895428392165, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.720717847132163, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0810975832903003, "gear": 1, "accelerator_pedal_position": 0.2766895428392165, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.96322696793884, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.2390492} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.59996223449707, "x": 44.280945116959785, "y": 6.503490517874942, "z": null, "yaw": 4.112739951095686, "pitch": null, "roll": null}, "v": 1.0704427550014275, "accelerator_pedal_position": 0.27070296737408106, "brake_pedal_position": 0.0, "acceleration": 0.17691293142058473, "steering_wheel_angle": 9.152108888737626, "front_wheel_angle": 0.48831751358539627, "heading_rate": 0.22212896583534397, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.2590492} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2766895428392165, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.720717847132163, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0853673941000357, "gear": 1, "accelerator_pedal_position": 0.2766895428392165, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.88751910704234, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.2590492} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.59996223449707, "x": 44.280945116959785, "y": 6.503490517874942, "z": null, "yaw": 4.112739951095686, "pitch": null, "roll": null}, "v": 1.0704427550014275, "accelerator_pedal_position": 0.27070296737408106, "brake_pedal_position": 0.0, "acceleration": 0.17691293142058473, "steering_wheel_angle": 9.152108888737626, "front_wheel_angle": 0.48831751358539627, "heading_rate": 0.22212896583534397, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.2790492} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2766895428392165, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.720717847132163, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0917606366861052, "gear": 1, "accelerator_pedal_position": 0.2766895428392165, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.773428439590285, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.2790492} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502678.2990491, "x": 48.21484464058674, "y": 11.404641989350615, "z": null, "yaw": 4.134912873671614, "pitch": null, "roll": null}, "v": 1.0938886586664316, "accelerator_pedal_position": 0.2766895428392165, "brake_pedal_position": 0.0, "acceleration": 0.21264928583619092, "steering_wheel_angle": 8.735257183477652, "front_wheel_angle": 0.46205478476360506, "heading_rate": 0.21280003719203341, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.2990491} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2827366520068352, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.176789594117162, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0960151515247936, "gear": 1, "accelerator_pedal_position": 0.2766895428392165, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.697015410550712, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.2990491} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.709962129592896, "x": 44.21484464058674, "y": 6.4046419893506155, "z": null, "yaw": 4.134912873671614, "pitch": null, "roll": null}, "v": 1.0938886586664316, "accelerator_pedal_position": 0.2766895428392165, "brake_pedal_position": 0.0, "acceleration": 0.21264928583619092, "steering_wheel_angle": 8.735257183477652, "front_wheel_angle": 0.46205478476360506, "heading_rate": 0.21280003719203341, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.3190491} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2809309163200963, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.176789594117162, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0985180597782211, "gear": 1, "accelerator_pedal_position": 0.2827366520068352, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.659590602341442, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.3190491} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.709962129592896, "x": 44.21484464058674, "y": 6.4046419893506155, "z": null, "yaw": 4.134912873671614, "pitch": null, "roll": null}, "v": 1.0938886586664316, "accelerator_pedal_position": 0.2766895428392165, "brake_pedal_position": 0.0, "acceleration": 0.21264928583619092, "steering_wheel_angle": 8.735257183477652, "front_wheel_angle": 0.46205478476360506, "heading_rate": 0.21280003719203341, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.339049} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2809309163200963, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.176789594117162, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1056776488131126, "gear": 1, "accelerator_pedal_position": 0.2809309163200963, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.546912434361376, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.339049} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.709962129592896, "x": 44.21484464058674, "y": 6.4046419893506155, "z": null, "yaw": 4.134912873671614, "pitch": null, "roll": null}, "v": 1.0938886586664316, "accelerator_pedal_position": 0.2766895428392165, "brake_pedal_position": 0.0, "acceleration": 0.21264928583619092, "steering_wheel_angle": 8.735257183477652, "front_wheel_angle": 0.46205478476360506, "heading_rate": 0.21280003719203341, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.359049} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2809309163200963, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.176789594117162, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.110442111992091, "gear": 1, "accelerator_pedal_position": 0.2809309163200963, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.471457202914458, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.359049} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.709962129592896, "x": 44.21484464058674, "y": 6.4046419893506155, "z": null, "yaw": 4.134912873671614, "pitch": null, "roll": null}, "v": 1.0938886586664316, "accelerator_pedal_position": 0.2766895428392165, "brake_pedal_position": 0.0, "acceleration": 0.21264928583619092, "steering_wheel_angle": 8.735257183477652, "front_wheel_angle": 0.46205478476360506, "heading_rate": 0.21280003719203341, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.379049} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2809309163200963, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.176789594117162, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1128217650376926, "gear": 1, "accelerator_pedal_position": 0.2809309163200963, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.433628651352937, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.379049} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.709962129592896, "x": 44.21484464058674, "y": 6.4046419893506155, "z": null, "yaw": 4.134912873671614, "pitch": null, "roll": null}, "v": 1.0938886586664316, "accelerator_pedal_position": 0.2766895428392165, "brake_pedal_position": 0.0, "acceleration": 0.21264928583619092, "steering_wheel_angle": 8.735257183477652, "front_wheel_angle": 0.46205478476360506, "heading_rate": 0.21280003719203341, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.399049} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2809309163200963, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.176789594117162, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1175759145806041, "gear": 1, "accelerator_pedal_position": 0.2809309163200963, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.357769676553767, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.399049} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2809309163200963, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 7.176789594117162, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1199504113008347, "gear": 1, "accelerator_pedal_position": 0.2809309163200963, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.319739253316122, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.409049} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502678.409049, "x": 48.149430954311306, "y": 11.302109489451567, "z": null, "yaw": 4.155690003732978, "pitch": null, "roll": null}, "v": 1.1199504113008347, "accelerator_pedal_position": 0.2809309163200963, "brake_pedal_position": 0.0, "acceleration": 0.23727781719783103, "steering_wheel_angle": 8.319739253316122, "front_wheel_angle": 0.4363973531863847, "heading_rate": 0.2040352097430939, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.429049} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28741988954144254, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.584364742071587, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1274691514702315, "gear": 1, "accelerator_pedal_position": 0.28741988954144254, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.206163417694526, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.429049} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.81996202468872, "x": 44.149430954311306, "y": 6.302109489451567, "z": null, "yaw": 4.155690003732978, "pitch": null, "roll": null}, "v": 1.1199504113008347, "accelerator_pedal_position": 0.2809309163200963, "brake_pedal_position": 0.0, "acceleration": 0.23727781719783103, "steering_wheel_angle": 8.319739253316122, "front_wheel_angle": 0.4363973531863847, "heading_rate": 0.2040352097430939, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.449049} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2854860867865649, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.584364742071587, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1302420413220848, "gear": 1, "accelerator_pedal_position": 0.28741988954144254, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.168786203648196, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.449049} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.81996202468872, "x": 44.149430954311306, "y": 6.302109489451567, "z": null, "yaw": 4.155690003732978, "pitch": null, "roll": null}, "v": 1.1199504113008347, "accelerator_pedal_position": 0.2809309163200963, "brake_pedal_position": 0.0, "acceleration": 0.23727781719783103, "steering_wheel_angle": 8.319739253316122, "front_wheel_angle": 0.4363973531863847, "heading_rate": 0.2040352097430939, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.469049} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2854860867865649, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.584364742071587, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.135540145973479, "gear": 1, "accelerator_pedal_position": 0.2854860867865649, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.093839485827084, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.469049} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.81996202468872, "x": 44.149430954311306, "y": 6.302109489451567, "z": null, "yaw": 4.155690003732978, "pitch": null, "roll": null}, "v": 1.1199504113008347, "accelerator_pedal_position": 0.2809309163200963, "brake_pedal_position": 0.0, "acceleration": 0.23727781719783103, "steering_wheel_angle": 8.319739253316122, "front_wheel_angle": 0.4363973531863847, "heading_rate": 0.2040352097430939, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.489049} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2854860867865649, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.584364742071587, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1408305516430137, "gear": 1, "accelerator_pedal_position": 0.2854860867865649, "brake_pedal_position": 0.0, "steering_wheel_angle": 8.01863638170137, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.489049} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.81996202468872, "x": 44.149430954311306, "y": 6.302109489451567, "z": null, "yaw": 4.155690003732978, "pitch": null, "roll": null}, "v": 1.1199504113008347, "accelerator_pedal_position": 0.2809309163200963, "brake_pedal_position": 0.0, "acceleration": 0.23727781719783103, "steering_wheel_angle": 8.319739253316122, "front_wheel_angle": 0.4363973531863847, "heading_rate": 0.2040352097430939, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.509049} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2854860867865649, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.584364742071587, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1461132583272402, "gear": 1, "accelerator_pedal_position": 0.2854860867865649, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.943176891271053, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.509049} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502678.519049, "x": 48.084539466149295, "y": 11.195723217903817, "z": null, "yaw": 4.175135197863339, "pitch": null, "roll": null}, "v": 1.1487517245621455, "accelerator_pedal_position": 0.2854860867865649, "brake_pedal_position": 0.0, "acceleration": 0.26365415094107825, "steering_wheel_angle": 7.905351001191668, "front_wheel_angle": 0.4112982457106558, "heading_rate": 0.1957255603683291, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.529049} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29488033053746715, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.038879095354681, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1546100231031875, "gear": 1, "accelerator_pedal_position": 0.29488033053746715, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.830310749226504, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.529049} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.929961919784546, "x": 44.084539466149295, "y": 6.195723217903817, "z": null, "yaw": 4.175135197863339, "pitch": null, "roll": null}, "v": 1.1487517245621455, "accelerator_pedal_position": 0.2854860867865649, "brake_pedal_position": 0.0, "acceleration": 0.26365415094107825, "steering_wheel_angle": 7.905351001191668, "front_wheel_angle": 0.4112982457106558, "heading_rate": 0.1957255603683291, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.549049} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29204930159275205, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.038879095354681, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1578294263196827, "gear": 1, "accelerator_pedal_position": 0.29488033053746715, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.793099071359932, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.549049} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.929961919784546, "x": 44.084539466149295, "y": 6.195723217903817, "z": null, "yaw": 4.175135197863339, "pitch": null, "roll": null}, "v": 1.1487517245621455, "accelerator_pedal_position": 0.2854860867865649, "brake_pedal_position": 0.0, "acceleration": 0.26365415094107825, "steering_wheel_angle": 7.905351001191668, "front_wheel_angle": 0.4112982457106558, "heading_rate": 0.1957255603683291, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.569049} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29204930159275205, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.038879095354681, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1669430804222725, "gear": 1, "accelerator_pedal_position": 0.29204930159275205, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.681095562418533, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.569049} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.929961919784546, "x": 44.084539466149295, "y": 6.195723217903817, "z": null, "yaw": 4.175135197863339, "pitch": null, "roll": null}, "v": 1.1487517245621455, "accelerator_pedal_position": 0.2854860867865649, "brake_pedal_position": 0.0, "acceleration": 0.26365415094107825, "steering_wheel_angle": 7.905351001191668, "front_wheel_angle": 0.4112982457106558, "heading_rate": 0.1957255603683291, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.5890489} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29204930159275205, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.038879095354681, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1730077232040772, "gear": 1, "accelerator_pedal_position": 0.29204930159275205, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.606119493672868, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.5890489} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 39.929961919784546, "x": 44.084539466149295, "y": 6.195723217903817, "z": null, "yaw": 4.175135197863339, "pitch": null, "roll": null}, "v": 1.1487517245621455, "accelerator_pedal_position": 0.2854860867865649, "brake_pedal_position": 0.0, "acceleration": 0.26365415094107825, "steering_wheel_angle": 7.905351001191668, "front_wheel_angle": 0.4112982457106558, "heading_rate": 0.1957255603683291, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.6090488} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29204930159275205, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 6.038879095354681, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.179063462743328, "gear": 1, "accelerator_pedal_position": 0.29204930159275205, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.530897774699419, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.6090488} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502678.6290488, "x": 48.019947492129425, "y": 11.085190281307652, "z": null, "yaw": 4.1933100965130095, "pitch": null, "roll": null}, "v": 1.1820879932965858, "accelerator_pedal_position": 0.29204930159275205, "brake_pedal_position": 0.0, "acceleration": 0.3022304150509114, "steering_wheel_angle": 7.493194796377276, "front_wheel_angle": 0.3867916483021223, "heading_rate": 0.18807638141869282, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.6290488} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3021390982584432, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.260628899765484, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1851102974470948, "gear": 1, "accelerator_pedal_position": 0.29204930159275205, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.455430405498184, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.6290488} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.03996181488037, "x": 44.019947492129425, "y": 6.085190281307652, "z": null, "yaw": 4.1933100965130095, "pitch": null, "roll": null}, "v": 1.1820879932965858, "accelerator_pedal_position": 0.29204930159275205, "brake_pedal_position": 0.0, "acceleration": 0.3022304150509114, "steering_wheel_angle": 7.493194796377276, "front_wheel_angle": 0.3867916483021223, "heading_rate": 0.18807638141869282, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.6490488} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.299108226234662, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.260628899765484, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.192408985176824, "gear": 1, "accelerator_pedal_position": 0.3021390982584432, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.381885913860536, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.6490488} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.03996181488037, "x": 44.019947492129425, "y": 6.085190281307652, "z": null, "yaw": 4.1933100965130095, "pitch": null, "roll": null}, "v": 1.1820879932965858, "accelerator_pedal_position": 0.29204930159275205, "brake_pedal_position": 0.0, "acceleration": 0.3022304150509114, "steering_wheel_angle": 7.493194796377276, "front_wheel_angle": 0.3867916483021223, "heading_rate": 0.18807638141869282, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.6690488} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.299108226234662, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.260628899765484, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1993181833377682, "gear": 1, "accelerator_pedal_position": 0.299108226234662, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.308109620513345, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.6690488} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.03996181488037, "x": 44.019947492129425, "y": 6.085190281307652, "z": null, "yaw": 4.1933100965130095, "pitch": null, "roll": null}, "v": 1.1820879932965858, "accelerator_pedal_position": 0.29204930159275205, "brake_pedal_position": 0.0, "acceleration": 0.3022304150509114, "steering_wheel_angle": 7.493194796377276, "front_wheel_angle": 0.3867916483021223, "heading_rate": 0.18807638141869282, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.6890488} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.299108226234662, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.260628899765484, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2027689519752771, "gear": 1, "accelerator_pedal_position": 0.299108226234662, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.2711345481986704, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.6890488} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.03996181488037, "x": 44.019947492129425, "y": 6.085190281307652, "z": null, "yaw": 4.1933100965130095, "pitch": null, "roll": null}, "v": 1.1820879932965858, "accelerator_pedal_position": 0.29204930159275205, "brake_pedal_position": 0.0, "acceleration": 0.3022304150509114, "steering_wheel_angle": 7.493194796377276, "front_wheel_angle": 0.3867916483021223, "heading_rate": 0.18807638141869282, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.7090487} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.299108226234662, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.260628899765484, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2131059302065268, "gear": 1, "accelerator_pedal_position": 0.299108226234662, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.159861628690331, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.7090487} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.03996181488037, "x": 44.019947492129425, "y": 6.085190281307652, "z": null, "yaw": 4.1933100965130095, "pitch": null, "roll": null}, "v": 1.1820879932965858, "accelerator_pedal_position": 0.29204930159275205, "brake_pedal_position": 0.0, "acceleration": 0.3022304150509114, "steering_wheel_angle": 7.493194796377276, "front_wheel_angle": 0.3867916483021223, "heading_rate": 0.18807638141869282, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.7290487} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.299108226234662, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 5.260628899765484, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2165464787812996, "gear": 1, "accelerator_pedal_position": 0.299108226234662, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.122654754666113, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.7290487} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502678.7390487, "x": 47.95540742551599, "y": 10.970139591604212, "z": null, "yaw": 4.210271036133182, "pitch": null, "roll": null}, "v": 1.2199844711480718, "accelerator_pedal_position": 0.299108226234662, "brake_pedal_position": 0.0, "acceleration": 0.3435435693108093, "steering_wheel_angle": 7.08538993021451, "front_wheel_angle": 0.36296896062683853, "heading_rate": 0.1809943485364955, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.7490487} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3138439361467991, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.384672593197659, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2268527854005802, "gear": 1, "accelerator_pedal_position": 0.299108226234662, "brake_pedal_position": 0.0, "steering_wheel_angle": 7.010686430029145, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.7490487} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.149961709976196, "x": 43.95540742551599, "y": 5.970139591604212, "z": null, "yaw": 4.210271036133182, "pitch": null, "roll": null}, "v": 1.2199844711480718, "accelerator_pedal_position": 0.299108226234662, "brake_pedal_position": 0.0, "acceleration": 0.3435435693108093, "steering_wheel_angle": 7.08538993021451, "front_wheel_angle": 0.36296896062683853, "heading_rate": 0.1809943485364955, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.7690487} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3093792801096016, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.384672593197659, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2355521458557144, "gear": 1, "accelerator_pedal_position": 0.3138439361467991, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.938024480186795, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.7690487} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.149961709976196, "x": 43.95540742551599, "y": 5.970139591604212, "z": null, "yaw": 4.210271036133182, "pitch": null, "roll": null}, "v": 1.2199844711480718, "accelerator_pedal_position": 0.299108226234662, "brake_pedal_position": 0.0, "acceleration": 0.3435435693108093, "steering_wheel_angle": 7.08538993021451, "front_wheel_angle": 0.36296896062683853, "heading_rate": 0.1809943485364955, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.7890487} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3093792801096016, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.384672593197659, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2436806466702974, "gear": 1, "accelerator_pedal_position": 0.3093792801096016, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.8651445594513545, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.7890487} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.149961709976196, "x": 43.95540742551599, "y": 5.970139591604212, "z": null, "yaw": 4.210271036133182, "pitch": null, "roll": null}, "v": 1.2199844711480718, "accelerator_pedal_position": 0.299108226234662, "brake_pedal_position": 0.0, "acceleration": 0.3435435693108093, "steering_wheel_angle": 7.08538993021451, "front_wheel_angle": 0.36296896062683853, "heading_rate": 0.1809943485364955, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.8090487} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3093792801096016, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.384672593197659, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2517969864420655, "gear": 1, "accelerator_pedal_position": 0.3093792801096016, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.792046667822824, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.8090487} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.149961709976196, "x": 43.95540742551599, "y": 5.970139591604212, "z": null, "yaw": 4.210271036133182, "pitch": null, "roll": null}, "v": 1.2199844711480718, "accelerator_pedal_position": 0.299108226234662, "brake_pedal_position": 0.0, "acceleration": 0.3435435693108093, "steering_wheel_angle": 7.08538993021451, "front_wheel_angle": 0.36296896062683853, "heading_rate": 0.1809943485364955, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.8290486} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3093792801096016, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 4.384672593197659, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2558505933861681, "gear": 1, "accelerator_pedal_position": 0.3093792801096016, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.755415982923649, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.8290486} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502678.8490486, "x": 47.89065927590672, "y": 10.85013853919351, "z": null, "yaw": 4.226072811269136, "pitch": null, "roll": null}, "v": 1.2639486763608245, "accelerator_pedal_position": 0.3093792801096016, "brake_pedal_position": 0.0, "acceleration": 0.40444740430222575, "steering_wheel_angle": 6.681991134955484, "front_wheel_angle": 0.33979871317852905, "heading_rate": 0.17453868277273563, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.8490486} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.32522989232989297, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.730071888423394, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2679931504038469, "gear": 1, "accelerator_pedal_position": 0.3093792801096016, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.6451969718864925, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.8490486} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.25996160507202, "x": 43.89065927590672, "y": 5.850138539193511, "z": null, "yaw": 4.226072811269136, "pitch": null, "roll": null}, "v": 1.2639486763608245, "accelerator_pedal_position": 0.3093792801096016, "brake_pedal_position": 0.0, "acceleration": 0.40444740430222575, "steering_wheel_angle": 6.681991134955484, "front_wheel_angle": 0.33979871317852905, "heading_rate": 0.17453868277273563, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.8690486} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3204410854576133, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.730071888423394, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.278053537759683, "gear": 1, "accelerator_pedal_position": 0.32522989232989297, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.5730386984479745, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.8690486} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.25996160507202, "x": 43.89065927590672, "y": 5.850138539193511, "z": null, "yaw": 4.226072811269136, "pitch": null, "roll": null}, "v": 1.2639486763608245, "accelerator_pedal_position": 0.3093792801096016, "brake_pedal_position": 0.0, "acceleration": 0.40444740430222575, "steering_wheel_angle": 6.681991134955484, "front_wheel_angle": 0.33979871317852905, "heading_rate": 0.17453868277273563, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.8890486} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3204410854576133, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.730071888423394, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.287500363091348, "gear": 1, "accelerator_pedal_position": 0.3204410854576133, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.500671758301662, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.8890486} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.25996160507202, "x": 43.89065927590672, "y": 5.850138539193511, "z": null, "yaw": 4.226072811269136, "pitch": null, "roll": null}, "v": 1.2639486763608245, "accelerator_pedal_position": 0.3093792801096016, "brake_pedal_position": 0.0, "acceleration": 0.40444740430222575, "steering_wheel_angle": 6.681991134955484, "front_wheel_angle": 0.33979871317852905, "heading_rate": 0.17453868277273563, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.9090486} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3204410854576133, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.730071888423394, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.292218415032407, "gear": 1, "accelerator_pedal_position": 0.3204410854576133, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.464410038213082, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.9090486} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.25996160507202, "x": 43.89065927590672, "y": 5.850138539193511, "z": null, "yaw": 4.226072811269136, "pitch": null, "roll": null}, "v": 1.2639486763608245, "accelerator_pedal_position": 0.3093792801096016, "brake_pedal_position": 0.0, "acceleration": 0.40444740430222575, "steering_wheel_angle": 6.681991134955484, "front_wheel_angle": 0.33979871317852905, "heading_rate": 0.17453868277273563, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.9290485} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3204410854576133, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.730071888423394, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.306351107017601, "gear": 1, "accelerator_pedal_position": 0.3204410854576133, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.355311877885651, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.9290485} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.25996160507202, "x": 43.89065927590672, "y": 5.850138539193511, "z": null, "yaw": 4.226072811269136, "pitch": null, "roll": null}, "v": 1.2639486763608245, "accelerator_pedal_position": 0.3093792801096016, "brake_pedal_position": 0.0, "acceleration": 0.40444740430222575, "steering_wheel_angle": 6.681991134955484, "front_wheel_angle": 0.33979871317852905, "heading_rate": 0.17453868277273563, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.9490485} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3204410854576133, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 3.730071888423394, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3157549979224281, "gear": 1, "accelerator_pedal_position": 0.3204410854576133, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.282318937615951, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.9490485} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502678.9590485, "x": 47.82532810826379, "y": 10.724495040791501, "z": null, "yaw": 4.240767900659373, "pitch": null, "roll": null}, "v": 1.3157549979224281, "accelerator_pedal_position": 0.3204410854576133, "brake_pedal_position": 0.0, "acceleration": 0.46965692206838305, "steering_wheel_angle": 6.282318937615951, "front_wheel_angle": 0.3172112188282205, "heading_rate": 0.16873386660353465, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.9690485} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.34164128410380723, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.867781719278015, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.325144549966524, "gear": 1, "accelerator_pedal_position": 0.3204410854576133, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.209117330638456, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.9690485} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.36996150016785, "x": 43.82532810826379, "y": 5.724495040791501, "z": null, "yaw": 4.240767900659373, "pitch": null, "roll": null}, "v": 1.3157549979224281, "accelerator_pedal_position": 0.3204410854576133, "brake_pedal_position": 0.0, "acceleration": 0.46965692206838305, "steering_wheel_angle": 6.282318937615951, "front_wheel_angle": 0.3172112188282205, "heading_rate": 0.16873386660353465, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502678.9890485} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3352125560948148, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.867781719278015, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3371687595011985, "gear": 1, "accelerator_pedal_position": 0.34164128410380723, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.1376905230095975, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502678.9890485} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.36996150016785, "x": 43.82532810826379, "y": 5.724495040791501, "z": null, "yaw": 4.240767900659373, "pitch": null, "roll": null}, "v": 1.3157549979224281, "accelerator_pedal_position": 0.3204410854576133, "brake_pedal_position": 0.0, "acceleration": 0.46965692206838305, "steering_wheel_angle": 6.282318937615951, "front_wheel_angle": 0.3172112188282205, "heading_rate": 0.16873386660353465, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.0090485} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3352125560948148, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.867781719278015, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3483712528184477, "gear": 1, "accelerator_pedal_position": 0.3352125560948148, "brake_pedal_position": 0.0, "steering_wheel_angle": 6.066066157087064, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.0090485} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.36996150016785, "x": 43.82532810826379, "y": 5.724495040791501, "z": null, "yaw": 4.240767900659373, "pitch": null, "roll": null}, "v": 1.3157549979224281, "accelerator_pedal_position": 0.3204410854576133, "brake_pedal_position": 0.0, "acceleration": 0.46965692206838305, "steering_wheel_angle": 6.282318937615951, "front_wheel_angle": 0.3172112188282205, "heading_rate": 0.16873386660353465, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.0290484} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3352125560948148, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.867781719278015, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.359556520775487, "gear": 1, "accelerator_pedal_position": 0.3352125560948148, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.994244232870858, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.0290484} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.36996150016785, "x": 43.82532810826379, "y": 5.724495040791501, "z": null, "yaw": 4.240767900659373, "pitch": null, "roll": null}, "v": 1.3157549979224281, "accelerator_pedal_position": 0.3204410854576133, "brake_pedal_position": 0.0, "acceleration": 0.46965692206838305, "steering_wheel_angle": 6.282318937615951, "front_wheel_angle": 0.3172112188282205, "heading_rate": 0.16873386660353465, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.0490484} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3352125560948148, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 2.867781719278015, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3707245398338674, "gear": 1, "accelerator_pedal_position": 0.3352125560948148, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.922224750360978, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.0490484} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502679.0690484, "x": 47.75905758466241, "y": 10.592495810161582, "z": null, "yaw": 4.254397465591249, "pitch": null, "roll": null}, "v": 1.3763020737434661, "accelerator_pedal_position": 0.3352125560948148, "brake_pedal_position": 0.0, "acceleration": 0.5573212979235135, "steering_wheel_angle": 5.886140924745911, "front_wheel_angle": 0.29516655480828474, "heading_rate": 0.16346176436170984, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.0690484} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3745018889060496, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.6317026761136026, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3818752867227013, "gear": 1, "accelerator_pedal_position": 0.3352125560948148, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.850007709557423, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.0690484} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.47996139526367, "x": 43.75905758466241, "y": 5.592495810161582, "z": null, "yaw": 4.254397465591249, "pitch": null, "roll": null}, "v": 1.3763020737434661, "accelerator_pedal_position": 0.3352125560948148, "brake_pedal_position": 0.0, "acceleration": 0.5573212979235135, "steering_wheel_angle": 5.886140924745911, "front_wheel_angle": 0.29516655480828474, "heading_rate": 0.16346176436170984, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.0890484} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.36245683028655185, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.6317026761136026, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3979179952481242, "gear": 1, "accelerator_pedal_position": 0.3745018889060496, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.7802108805419765, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.0890484} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.47996139526367, "x": 43.75905758466241, "y": 5.592495810161582, "z": null, "yaw": 4.254397465591249, "pitch": null, "roll": null}, "v": 1.3763020737434661, "accelerator_pedal_position": 0.3352125560948148, "brake_pedal_position": 0.0, "acceleration": 0.5573212979235135, "steering_wheel_angle": 5.886140924745911, "front_wheel_angle": 0.29516655480828474, "heading_rate": 0.16346176436170984, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.1090484} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.36245683028655185, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.6317026761136026, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.412430681690742, "gear": 1, "accelerator_pedal_position": 0.36245683028655185, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.710230500352911, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.1090484} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.47996139526367, "x": 43.75905758466241, "y": 5.592495810161582, "z": null, "yaw": 4.254397465591249, "pitch": null, "roll": null}, "v": 1.3763020737434661, "accelerator_pedal_position": 0.3352125560948148, "brake_pedal_position": 0.0, "acceleration": 0.5573212979235135, "steering_wheel_angle": 5.886140924745911, "front_wheel_angle": 0.29516655480828474, "heading_rate": 0.16346176436170984, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.1290483} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.36245683028655185, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.6317026761136026, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4196785221997479, "gear": 1, "accelerator_pedal_position": 0.36245683028655185, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.675171478568271, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.1290483} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.47996139526367, "x": 43.75905758466241, "y": 5.592495810161582, "z": null, "yaw": 4.254397465591249, "pitch": null, "roll": null}, "v": 1.3763020737434661, "accelerator_pedal_position": 0.3352125560948148, "brake_pedal_position": 0.0, "acceleration": 0.5573212979235135, "steering_wheel_angle": 5.886140924745911, "front_wheel_angle": 0.29516655480828474, "heading_rate": 0.16346176436170984, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.1490483} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.36245683028655185, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.6317026761136026, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4413879600374433, "gear": 1, "accelerator_pedal_position": 0.36245683028655185, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.569719086453922, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.1490483} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.47996139526367, "x": 43.75905758466241, "y": 5.592495810161582, "z": null, "yaw": 4.254397465591249, "pitch": null, "roll": null}, "v": 1.3763020737434661, "accelerator_pedal_position": 0.3352125560948148, "brake_pedal_position": 0.0, "acceleration": 0.5573212979235135, "steering_wheel_angle": 5.886140924745911, "front_wheel_angle": 0.29516655480828474, "heading_rate": 0.16346176436170984, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.1690483} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.36245683028655185, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.6317026761136026, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4558324554099087, "gear": 1, "accelerator_pedal_position": 0.36245683028655185, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.499188052743999, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.1690483} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502679.1790483, "x": 47.69119289521759, "y": 10.452761420004242, "z": null, "yaw": 4.267009681493933, "pitch": null, "roll": null}, "v": 1.4558324554099087, "accelerator_pedal_position": 0.36245683028655185, "brake_pedal_position": 0.0, "acceleration": 0.7213690851382051, "steering_wheel_angle": 5.499188052743999, "front_wheel_angle": 0.27395235975958354, "heading_rate": 0.15981054371545497, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.1890483} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.4029483470438081, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5629049675973187, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4702541246784606, "gear": 1, "accelerator_pedal_position": 0.36245683028655185, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.428473467860456, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.1890483} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.5899612903595, "x": 43.69119289521759, "y": 5.452761420004242, "z": null, "yaw": 4.267009681493933, "pitch": null, "roll": null}, "v": 1.4558324554099087, "accelerator_pedal_position": 0.36245683028655185, "brake_pedal_position": 0.0, "acceleration": 0.7213690851382051, "steering_wheel_angle": 5.499188052743999, "front_wheel_angle": 0.27395235975958354, "heading_rate": 0.15981054371545497, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.2090483} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3906061862891976, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5629049675973187, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4897123465422157, "gear": 1, "accelerator_pedal_position": 0.4029483470438081, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.359656103894982, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.2090483} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.5899612903595, "x": 43.69119289521759, "y": 5.452761420004242, "z": null, "yaw": 4.267009681493933, "pitch": null, "roll": null}, "v": 1.4558324554099087, "accelerator_pedal_position": 0.36245683028655185, "brake_pedal_position": 0.0, "acceleration": 0.7213690851382051, "steering_wheel_angle": 5.499188052743999, "front_wheel_angle": 0.27395235975958354, "heading_rate": 0.15981054371545497, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.2290483} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3906061862891976, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5629049675973187, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.507597412425396, "gear": 1, "accelerator_pedal_position": 0.3906061862891976, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.290665791527113, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.2290483} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.5899612903595, "x": 43.69119289521759, "y": 5.452761420004242, "z": null, "yaw": 4.267009681493933, "pitch": null, "roll": null}, "v": 1.4558324554099087, "accelerator_pedal_position": 0.36245683028655185, "brake_pedal_position": 0.0, "acceleration": 0.7213690851382051, "steering_wheel_angle": 5.499188052743999, "front_wheel_angle": 0.27395235975958354, "heading_rate": 0.15981054371545497, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.2490482} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3906061862891976, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5629049675973187, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.516529215366463, "gear": 1, "accelerator_pedal_position": 0.3906061862891976, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.256105779692279, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.2490482} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.5899612903595, "x": 43.69119289521759, "y": 5.452761420004242, "z": null, "yaw": 4.267009681493933, "pitch": null, "roll": null}, "v": 1.4558324554099087, "accelerator_pedal_position": 0.36245683028655185, "brake_pedal_position": 0.0, "acceleration": 0.7213690851382051, "steering_wheel_angle": 5.499188052743999, "front_wheel_angle": 0.27395235975958354, "heading_rate": 0.15981054371545497, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.2690482} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3906061862891976, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5629049675973187, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5343713100879162, "gear": 1, "accelerator_pedal_position": 0.3906061862891976, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.186856044720812, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.2690482} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502679.2890482, "x": 47.62098625293405, "y": 10.303612723936526, "z": null, "yaw": 4.278649254254395, "pitch": null, "roll": null}, "v": 1.5521846555925343, "accelerator_pedal_position": 0.3906061862891976, "brake_pedal_position": 0.0, "acceleration": 0.8895866594772888, "steering_wheel_angle": 5.117433361346948, "front_wheel_angle": 0.25331719555926807, "heading_rate": 0.1569637060322646, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.2890482} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3315622271498644, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.111680195795285, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5573902747410988, "gear": 1, "accelerator_pedal_position": 0.3315622271498644, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.082168635587574, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.2890482} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.69996118545532, "x": 43.62098625293405, "y": 5.303612723936526, "z": null, "yaw": 4.278649254254395, "pitch": null, "roll": null}, "v": 1.5521846555925343, "accelerator_pedal_position": 0.3906061862891976, "brake_pedal_position": 0.0, "acceleration": 0.8895866594772888, "steering_wheel_angle": 5.117433361346948, "front_wheel_angle": 0.25331719555926807, "heading_rate": 0.1569637060322646, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.3090482} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3503992717653075, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.111680195795285, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5677888464410477, "gear": 1, "accelerator_pedal_position": 0.3315622271498644, "brake_pedal_position": 0.0, "steering_wheel_angle": 5.011505805185807, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.3090482} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.69996118545532, "x": 43.62098625293405, "y": 5.303612723936526, "z": null, "yaw": 4.278649254254395, "pitch": null, "roll": null}, "v": 1.5521846555925343, "accelerator_pedal_position": 0.3906061862891976, "brake_pedal_position": 0.0, "acceleration": 0.8895866594772888, "steering_wheel_angle": 5.117433361346948, "front_wheel_angle": 0.25331719555926807, "heading_rate": 0.1569637060322646, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.3290482} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3503992717653075, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.111680195795285, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5805241875561706, "gear": 1, "accelerator_pedal_position": 0.3503992717653075, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.940665136273344, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.3290482} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.69996118545532, "x": 43.62098625293405, "y": 5.303612723936526, "z": null, "yaw": 4.278649254254395, "pitch": null, "roll": null}, "v": 1.5521846555925343, "accelerator_pedal_position": 0.3906061862891976, "brake_pedal_position": 0.0, "acceleration": 0.8895866594772888, "steering_wheel_angle": 5.117433361346948, "front_wheel_angle": 0.25331719555926807, "heading_rate": 0.1569637060322646, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.3490481} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3503992717653075, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.111680195795285, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5868840742769792, "gear": 1, "accelerator_pedal_position": 0.3503992717653075, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.9051781123756015, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.3490481} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.69996118545532, "x": 43.62098625293405, "y": 5.303612723936526, "z": null, "yaw": 4.278649254254395, "pitch": null, "roll": null}, "v": 1.5521846555925343, "accelerator_pedal_position": 0.3906061862891976, "brake_pedal_position": 0.0, "acceleration": 0.8895866594772888, "steering_wheel_angle": 5.117433361346948, "front_wheel_angle": 0.25331719555926807, "heading_rate": 0.1569637060322646, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.369048} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3503992717653075, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.111680195795285, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6059325528384985, "gear": 1, "accelerator_pedal_position": 0.3503992717653075, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.798450282916334, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.369048} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.69996118545532, "x": 43.62098625293405, "y": 5.303612723936526, "z": null, "yaw": 4.278649254254395, "pitch": null, "roll": null}, "v": 1.5521846555925343, "accelerator_pedal_position": 0.3906061862891976, "brake_pedal_position": 0.0, "acceleration": 0.8895866594772888, "steering_wheel_angle": 5.117433361346948, "front_wheel_angle": 0.25331719555926807, "heading_rate": 0.1569637060322646, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.389048} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.3503992717653075, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.111680195795285, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6186055157929324, "gear": 1, "accelerator_pedal_position": 0.3503992717653075, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.727076098471787, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.389048} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502679.399048, "x": 47.54867757999823, "y": 10.145431621012044, "z": null, "yaw": 4.289340691627053, "pitch": null, "roll": null}, "v": 1.6186055157929324, "accelerator_pedal_position": 0.3503992717653075, "brake_pedal_position": 0.0, "acceleration": 0.6328663345859721, "steering_wheel_angle": 4.727076098471787, "front_wheel_angle": 0.2325065936915265, "heading_rate": 0.14971401324949746, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.409048} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2413277498141269, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.6065919304736163, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.631257625425901, "gear": 1, "accelerator_pedal_position": 0.3503992717653075, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.655524075516545, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.409048} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.80996108055115, "x": 43.54867757999823, "y": 5.145431621012044, "z": null, "yaw": 4.289340691627053, "pitch": null, "roll": null}, "v": 1.6186055157929324, "accelerator_pedal_position": 0.3503992717653075, "brake_pedal_position": 0.0, "acceleration": 0.6328663345859721, "steering_wheel_angle": 4.727076098471787, "front_wheel_angle": 0.2325065936915265, "heading_rate": 0.14971401324949746, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.429048} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27568397840541986, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.6065919304736163, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.63075888083252, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.618091757765735, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.429048} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.80996108055115, "x": 43.54867757999823, "y": 5.145431621012044, "z": null, "yaw": 4.289340691627053, "pitch": null, "roll": null}, "v": 1.6186055157929324, "accelerator_pedal_position": 0.3503992717653075, "brake_pedal_position": 0.0, "acceleration": 0.6328663345859721, "steering_wheel_angle": 4.727076098471787, "front_wheel_angle": 0.2325065936915265, "heading_rate": 0.14971401324949746, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.449048} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27568397840541986, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.6065919304736163, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6357015890674385, "gear": 1, "accelerator_pedal_position": 0.27568397840541986, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.505503876744024, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.449048} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.80996108055115, "x": 43.54867757999823, "y": 5.145431621012044, "z": null, "yaw": 4.289340691627053, "pitch": null, "roll": null}, "v": 1.6186055157929324, "accelerator_pedal_position": 0.3503992717653075, "brake_pedal_position": 0.0, "acceleration": 0.6328663345859721, "steering_wheel_angle": 4.727076098471787, "front_wheel_angle": 0.2325065936915265, "heading_rate": 0.14971401324949746, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.469048} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27568397840541986, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.6065919304736163, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6389899200524516, "gear": 1, "accelerator_pedal_position": 0.27568397840541986, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.43020284958848, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.469048} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.80996108055115, "x": 43.54867757999823, "y": 5.145431621012044, "z": null, "yaw": 4.289340691627053, "pitch": null, "roll": null}, "v": 1.6186055157929324, "accelerator_pedal_position": 0.3503992717653075, "brake_pedal_position": 0.0, "acceleration": 0.6328663345859721, "steering_wheel_angle": 4.727076098471787, "front_wheel_angle": 0.2325065936915265, "heading_rate": 0.14971401324949746, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.489048} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27568397840541986, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.6065919304736163, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6422728102241353, "gear": 1, "accelerator_pedal_position": 0.27568397840541986, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.354707870586745, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.489048} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502679.509048, "x": 47.47565661434227, "y": 9.981270551737543, "z": null, "yaw": 4.29907491384199, "pitch": null, "roll": null}, "v": 1.6439122164710418, "accelerator_pedal_position": 0.27568397840541986, "brake_pedal_position": 0.0, "acceleration": 0.1638047804556947, "steering_wheel_angle": 4.316887649143557, "front_wheel_angle": 0.21094134284121993, "heading_rate": 0.13750217972008974, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.509048} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22026173788040435, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.575176725792542, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6455502642755988, "gear": 1, "accelerator_pedal_position": 0.27568397840541986, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.279018939738822, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.509048} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.91996097564697, "x": 43.47565661434227, "y": 4.981270551737543, "z": null, "yaw": 4.29907491384199, "pitch": null, "roll": null}, "v": 1.6439122164710418, "accelerator_pedal_position": 0.27568397840541986, "brake_pedal_position": 0.0, "acceleration": 0.1638047804556947, "steering_wheel_angle": 4.316887649143557, "front_wheel_angle": 0.21094134284121993, "heading_rate": 0.13750217972008974, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.529048} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23768574800009196, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.575176725792542, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6418973787280127, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.200802472231201, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.529048} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.91996097564697, "x": 43.47565661434227, "y": 4.981270551737543, "z": null, "yaw": 4.29907491384199, "pitch": null, "roll": null}, "v": 1.6439122164710418, "accelerator_pedal_position": 0.27568397840541986, "brake_pedal_position": 0.0, "acceleration": 0.1638047804556947, "steering_wheel_angle": 4.316887649143557, "front_wheel_angle": 0.21094134284121993, "heading_rate": 0.13750217972008974, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.549048} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23768574800009196, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.575176725792542, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.641162206588427, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.161616970445664, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.549048} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.91996097564697, "x": 43.47565661434227, "y": 4.981270551737543, "z": null, "yaw": 4.29907491384199, "pitch": null, "roll": null}, "v": 1.6439122164710418, "accelerator_pedal_position": 0.27568397840541986, "brake_pedal_position": 0.0, "acceleration": 0.1638047804556947, "steering_wheel_angle": 4.316887649143557, "front_wheel_angle": 0.21094134284121993, "heading_rate": 0.13750217972008974, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.569048} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23768574800009196, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.575176725792542, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6389603414058036, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 4.043751392962147, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.569048} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.91996097564697, "x": 43.47565661434227, "y": 4.981270551737543, "z": null, "yaw": 4.29907491384199, "pitch": null, "roll": null}, "v": 1.6439122164710418, "accelerator_pedal_position": 0.27568397840541986, "brake_pedal_position": 0.0, "acceleration": 0.1638047804556947, "steering_wheel_angle": 4.316887649143557, "front_wheel_angle": 0.21094134284121993, "heading_rate": 0.13750217972008974, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.589048} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23768574800009196, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.575176725792542, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6374954678669555, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.9649167812007127, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.589048} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 40.91996097564697, "x": 43.47565661434227, "y": 4.981270551737543, "z": null, "yaw": 4.29907491384199, "pitch": null, "roll": null}, "v": 1.6439122164710418, "accelerator_pedal_position": 0.27568397840541986, "brake_pedal_position": 0.0, "acceleration": 0.1638047804556947, "steering_wheel_angle": 4.316887649143557, "front_wheel_angle": 0.21094134284121993, "heading_rate": 0.13750217972008974, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.609048} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23768574800009196, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.575176725792542, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6360330179025762, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.8858761213546744, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.609048} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502679.6190479, "x": 47.40383916445726, "y": 9.815697594816973, "z": null, "yaw": 4.307821929558391, "pitch": null, "roll": null}, "v": 1.6360330179025762, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30856769125180294, "steering_wheel_angle": 3.8858761213546744, "front_wheel_angle": 0.18860160825499162, "heading_rate": 0.12198039307054723, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.6290479} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22893981980716782, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.064634965717654, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6345729866478085, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.806629413424032, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.6290479} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.0299608707428, "x": 43.40383916445726, "y": 4.815697594816973, "z": null, "yaw": 4.307821929558391, "pitch": null, "roll": null}, "v": 1.6360330179025762, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30856769125180294, "steering_wheel_angle": 3.8858761213546744, "front_wheel_angle": 0.18860160825499162, "heading_rate": 0.12198039307054723, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.6490479} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23164030447171352, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.064634965717654, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6320225801248607, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.725892547846874, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.6490479} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.0299608707428, "x": 43.40383916445726, "y": 4.815697594816973, "z": null, "yaw": 4.307821929558391, "pitch": null, "roll": null}, "v": 1.6360330179025762, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30856769125180294, "steering_wheel_angle": 3.8858761213546744, "front_wheel_angle": 0.18860160825499162, "heading_rate": 0.12198039307054723, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.6690478} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23164030447171352, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.064634965717654, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6309177380940767, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.6854443325827204, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.6690478} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.0299608707428, "x": 43.40383916445726, "y": 4.815697594816973, "z": null, "yaw": 4.307821929558391, "pitch": null, "roll": null}, "v": 1.6360330179025762, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30856769125180294, "steering_wheel_angle": 3.8858761213546744, "front_wheel_angle": 0.18860160825499162, "heading_rate": 0.12198039307054723, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.6890478} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23164030447171352, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.064634965717654, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6276086855567038, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.563780556887964, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.6890478} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.0299608707428, "x": 43.40383916445726, "y": 4.815697594816973, "z": null, "yaw": 4.307821929558391, "pitch": null, "roll": null}, "v": 1.6360330179025762, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30856769125180294, "steering_wheel_angle": 3.8858761213546744, "front_wheel_angle": 0.18860160825499162, "heading_rate": 0.12198039307054723, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.7090478} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23164030447171352, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.064634965717654, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.625407201863684, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.4824054315062125, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.7090478} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502679.7290478, "x": 47.33381696021285, "y": 9.650525604353186, "z": null, "yaw": 4.315566365104971, "pitch": null, "roll": null}, "v": 1.6243078224350473, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30759915014198924, "steering_wheel_angle": 3.441638086339762, "front_wheel_angle": 0.16590537555816484, "heading_rate": 0.10624272760233394, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.7290478} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2272153489544632, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.547378008645228, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6232093499631095, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.400817552856262, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.7290478} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.13996076583862, "x": 43.33381696021285, "y": 4.650525604353186, "z": null, "yaw": 4.315566365104971, "pitch": null, "roll": null}, "v": 1.6243078224350473, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30759915014198924, "steering_wheel_angle": 3.441638086339762, "front_wheel_angle": 0.16590537555816484, "heading_rate": 0.10624272760233394, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.7490478} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22854972137299595, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.547378008645228, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6204622304868899, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.3176699632216904, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.7490478} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.13996076583862, "x": 43.33381696021285, "y": 4.650525604353186, "z": null, "yaw": 4.315566365104971, "pitch": null, "roll": null}, "v": 1.6243078224350473, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30759915014198924, "steering_wheel_angle": 3.441638086339762, "front_wheel_angle": 0.16590537555816484, "heading_rate": 0.10624272760233394, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.7690477} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22854972137299595, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.547378008645228, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6178863655068105, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.2343025654953066, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.7690477} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.13996076583862, "x": 43.33381696021285, "y": 4.650525604353186, "z": null, "yaw": 4.315566365104971, "pitch": null, "roll": null}, "v": 1.6243078224350473, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30759915014198924, "steering_wheel_angle": 3.441638086339762, "front_wheel_angle": 0.16590537555816484, "heading_rate": 0.10624272760233394, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.7890477} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22854972137299595, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.547378008645228, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6153147422905216, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.1507153596771094, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.7890477} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.13996076583862, "x": 43.33381696021285, "y": 4.650525604353186, "z": null, "yaw": 4.315566365104971, "pitch": null, "roll": null}, "v": 1.6243078224350473, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30759915014198924, "steering_wheel_angle": 3.441638086339762, "front_wheel_angle": 0.16590537555816484, "heading_rate": 0.10624272760233394, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.8090477} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22854972137299595, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.547378008645228, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6140305183335224, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 3.1088393287335823, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.8090477} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.13996076583862, "x": 43.33381696021285, "y": 4.650525604353186, "z": null, "yaw": 4.315566365104971, "pitch": null, "roll": null}, "v": 1.6243078224350473, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30759915014198924, "steering_wheel_angle": 3.441638086339762, "front_wheel_angle": 0.16590537555816484, "heading_rate": 0.10624272760233394, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.8290477} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22854972137299595, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.547378008645228, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6101841826611536, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.982881523765279, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.8290477} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502679.8390477, "x": 47.26554903788969, "y": 9.4861698697564, "z": null, "yaw": 4.322299161128889, "pitch": null, "roll": null}, "v": 1.6101841826611536, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30643614015397935, "steering_wheel_angle": 2.982881523765279, "front_wheel_angle": 0.14280312172477497, "heading_rate": 0.0904356304943579, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.8490477} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.02563242291431804, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.944461894923022, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.607625227076145, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.898634893671645, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.8490477} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.24996066093445, "x": 43.26554903788969, "y": 4.4861698697564005, "z": null, "yaw": 4.322299161128889, "pitch": null, "roll": null}, "v": 1.6101841826611536, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30643614015397935, "steering_wheel_angle": 2.982881523765279, "front_wheel_angle": 0.14280312172477497, "heading_rate": 0.0904356304943579, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.8690476} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.944461894923022, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5974037201307516, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.02563242291431804, "steering_wheel_angle": 2.8097923504915783, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.8690476} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.24996066093445, "x": 43.26554903788969, "y": 4.4861698697564005, "z": null, "yaw": 4.322299161128889, "pitch": null, "roll": null}, "v": 1.6101841826611536, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30643614015397935, "steering_wheel_angle": 2.982881523765279, "front_wheel_angle": 0.14280312172477497, "heading_rate": 0.0904356304943579, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.8890476} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.944461894923022, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5912984783380633, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.7207066659707153, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.8890476} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.24996066093445, "x": 43.26554903788969, "y": 4.4861698697564005, "z": null, "yaw": 4.322299161128889, "pitch": null, "roll": null}, "v": 1.6101841826611536, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30643614015397935, "steering_wheel_angle": 2.982881523765279, "front_wheel_angle": 0.14280312172477497, "heading_rate": 0.0904356304943579, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.9090476} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.944461894923022, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5852032275300707, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.6313778401090566, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.9090476} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.24996066093445, "x": 43.26554903788969, "y": 4.4861698697564005, "z": null, "yaw": 4.322299161128889, "pitch": null, "roll": null}, "v": 1.6101841826611536, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.30643614015397935, "steering_wheel_angle": 2.982881523765279, "front_wheel_angle": 0.14280312172477497, "heading_rate": 0.0904356304943579, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.9290476} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.944461894923022, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.579117936502159, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.5418058729066004, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.9290476} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502679.9490476, "x": 47.199256158678075, "y": 9.323704737092037, "z": null, "yaw": 4.32800145057792, "pitch": null, "roll": null}, "v": 1.5760790161881697, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3036442014620952, "steering_wheel_angle": 2.4969287113025747, "front_wheel_angle": 0.11868745548355597, "heading_rate": 0.07341568084728892, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.9490476} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.376398106328572, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5730425741735488, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.451990764363349, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.9490476} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.35996055603027, "x": 43.199256158678075, "y": 4.3237047370920365, "z": null, "yaw": 4.32800145057792, "pitch": null, "roll": null}, "v": 1.5760790161881697, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3036442014620952, "steering_wheel_angle": 2.4969287113025747, "front_wheel_angle": 0.11868745548355597, "heading_rate": 0.07341568084728892, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.9690475} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.376398106328572, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5700086065924457, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.4062344123136383, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.9690475} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.35996055603027, "x": 43.199256158678075, "y": 4.3237047370920365, "z": null, "yaw": 4.32800145057792, "pitch": null, "roll": null}, "v": 1.5760790161881697, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3036442014620952, "steering_wheel_angle": 2.4969287113025747, "front_wheel_angle": 0.11868745548355597, "heading_rate": 0.07341568084728892, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502679.9890475} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.376398106328572, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.554875750420189, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.176509932690653, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502679.9890475} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.35996055603027, "x": 43.199256158678075, "y": 4.3237047370920365, "z": null, "yaw": 4.32800145057792, "pitch": null, "roll": null}, "v": 1.5760790161881697, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3036442014620952, "steering_wheel_angle": 2.4969287113025747, "front_wheel_angle": 0.11868745548355597, "heading_rate": 0.07341568084728892, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.0190475} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.376398106328572, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.554875750420189, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 2.176509932690653, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.0190475} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.35996055603027, "x": 43.199256158678075, "y": 4.3237047370920365, "z": null, "yaw": 4.32800145057792, "pitch": null, "roll": null}, "v": 1.5760790161881697, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3036442014620952, "steering_wheel_angle": 2.4969287113025747, "front_wheel_angle": 0.11868745548355597, "heading_rate": 0.07341568084728892, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.0390475} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.376398106328572, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5367971778104033, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.8987665745193258, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.0390475} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502680.0590475, "x": 47.135217579243886, "y": 9.164391114185152, "z": null, "yaw": 4.332637600100819, "pitch": null, "roll": null}, "v": 1.5428136137829265, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3009434191578857, "steering_wheel_angle": 1.991599085742949, "front_wheel_angle": 0.09398196123949185, "heading_rate": 0.056806665034460614, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.0790474} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.817832113785789, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5307904563871806, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.804852911624881, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.0790474} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.4699604511261, "x": 43.135217579243886, "y": 4.164391114185152, "z": null, "yaw": 4.332637600100819, "pitch": null, "roll": null}, "v": 1.5428136137829265, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3009434191578857, "steering_wheel_angle": 1.991599085742949, "front_wheel_angle": 0.09398196123949185, "heading_rate": 0.056806665034460614, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.1090474} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.817832113785789, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5277907292168504, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.7573846705150162, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.1090474} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.4699604511261, "x": 43.135217579243886, "y": 4.164391114185152, "z": null, "yaw": 4.332637600100819, "pitch": null, "roll": null}, "v": 1.5428136137829265, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3009434191578857, "steering_wheel_angle": 1.991599085742949, "front_wheel_angle": 0.09398196123949185, "heading_rate": 0.056806665034460614, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.1290474} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.817832113785789, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5217985231941287, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.66225287100126, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.1290474} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.4699604511261, "x": 43.135217579243886, "y": 4.164391114185152, "z": null, "yaw": 4.332637600100819, "pitch": null, "roll": null}, "v": 1.5428136137829265, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3009434191578857, "steering_wheel_angle": 1.991599085742949, "front_wheel_angle": 0.09398196123949185, "heading_rate": 0.056806665034460614, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.1490474} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.817832113785789, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5158159566618234, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.566860648428803, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.1490474} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502680.1690474, "x": 47.07318573034666, "y": 9.008200158137457, "z": null, "yaw": 4.336196541187949, "pitch": null, "roll": null}, "v": 1.509842999802466, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29828840883064844, "steering_wheel_angle": 1.4712080027976449, "front_wheel_angle": 0.0689188714026977, "heading_rate": 0.040711616796282976, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.1690474} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.344018990872387, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.509842999802466, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.4712080027976449, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.1690474} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.579960346221924, "x": 43.07318573034666, "y": 4.008200158137457, "z": null, "yaw": 4.336196541187949, "pitch": null, "roll": null}, "v": 1.509842999802466, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29828840883064844, "steering_wheel_angle": 1.4712080027976449, "front_wheel_angle": 0.0689188714026977, "heading_rate": 0.040711616796282976, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.1890473} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.344018990872387, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5038796229154696, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.3731699809869224, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.1890473} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.579960346221924, "x": 43.07318573034666, "y": 4.008200158137457, "z": null, "yaw": 4.336196541187949, "pitch": null, "roll": null}, "v": 1.509842999802466, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29828840883064844, "steering_wheel_angle": 1.4712080027976449, "front_wheel_angle": 0.0689188714026977, "heading_rate": 0.040711616796282976, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.2090473} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.344018990872387, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4979257964165467, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.2748598852939763, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.2090473} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.579960346221924, "x": 43.07318573034666, "y": 4.008200158137457, "z": null, "yaw": 4.336196541187949, "pitch": null, "roll": null}, "v": 1.509842999802466, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29828840883064844, "steering_wheel_angle": 1.4712080027976449, "front_wheel_angle": 0.0689188714026977, "heading_rate": 0.040711616796282976, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.2290473} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.344018990872387, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4919814908371312, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.176277715718806, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.2290473} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.579960346221924, "x": 43.07318573034666, "y": 4.008200158137457, "z": null, "yaw": 4.336196541187949, "pitch": null, "roll": null}, "v": 1.509842999802466, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29828840883064844, "steering_wheel_angle": 1.4712080027976449, "front_wheel_angle": 0.0689188714026977, "heading_rate": 0.040711616796282976, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.2490473} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.344018990872387, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4860466768238023, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 1.0774234722614122, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.2490473} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.579960346221924, "x": 43.07318573034666, "y": 4.008200158137457, "z": null, "yaw": 4.336196541187949, "pitch": null, "roll": null}, "v": 1.509842999802466, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29828840883064844, "steering_wheel_angle": 1.4712080027976449, "front_wheel_angle": 0.0689188714026977, "heading_rate": 0.040711616796282976, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.2690473} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.344018990872387, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4801213251377123, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.9782971549217939, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.2690473} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502680.2790473, "x": 47.01295574145203, "y": 8.855181052824962, "z": null, "yaw": 4.338657978803536, "pitch": null, "roll": null}, "v": 1.4771621885614308, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29567819074122753, "steering_wheel_angle": 0.9286319685461512, "front_wheel_angle": 0.04317847912529549, "heading_rate": 0.024930189082734575, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.2890472} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22118489461391863, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.772730599302511, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4742054066540184, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.8788987636999522, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.2890472} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.68996024131775, "x": 43.01295574145203, "y": 3.855181052824962, "z": null, "yaw": 4.338657978803536, "pitch": null, "roll": null}, "v": 1.4771621885614308, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29567819074122753, "steering_wheel_angle": 0.9286319685461512, "front_wheel_angle": 0.04317847912529549, "heading_rate": 0.024930189082734575, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.3090472} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21633144047396882, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.772730599302511, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.470945952381077, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.7773579691465273, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.3090472} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.68996024131775, "x": 43.01295574145203, "y": 3.855181052824962, "z": null, "yaw": 4.338657978803536, "pitch": null, "roll": null}, "v": 1.4771621885614308, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29567819074122753, "steering_wheel_angle": 0.9286319685461512, "front_wheel_angle": 0.04317847912529549, "heading_rate": 0.024930189082734575, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.3290472} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21633144047396882, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.772730599302511, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4670852333955626, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.6755348083447223, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.3290472} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.68996024131775, "x": 43.01295574145203, "y": 3.855181052824962, "z": null, "yaw": 4.338657978803536, "pitch": null, "roll": null}, "v": 1.4771621885614308, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29567819074122753, "steering_wheel_angle": 0.9286319685461512, "front_wheel_angle": 0.04317847912529549, "heading_rate": 0.024930189082734575, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.3490472} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21633144047396882, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.772730599302511, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.463230639790119, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.5734292812945374, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.3490472} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.68996024131775, "x": 43.01295574145203, "y": 3.855181052824962, "z": null, "yaw": 4.338657978803536, "pitch": null, "roll": null}, "v": 1.4771621885614308, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29567819074122753, "steering_wheel_angle": 0.9286319685461512, "front_wheel_angle": 0.04317847912529549, "heading_rate": 0.024930189082734575, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.3690472} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21633144047396882, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.772730599302511, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.459382155905473, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4710413879959723, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.3690472} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502680.3890471, "x": 46.95414466181501, "y": 8.704903901610184, "z": null, "yaw": 4.340003369734488, "pitch": null, "roll": null}, "v": 1.4555397661354288, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29396294841478726, "steering_wheel_angle": 0.3683711284490268, "front_wheel_angle": 0.016999585774542164, "heading_rate": 0.009666389411307139, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.3890471} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.06931267055211773, "brake_pedal_speed": 3.0, "steering_wheel_angle": -9.908166235322199, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4555397661354288, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3683711284490268, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.3890471} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.799960136413574, "x": 42.95414466181501, "y": 3.7049039016101837, "z": null, "yaw": 4.340003369734488, "pitch": null, "roll": null}, "v": 1.4555397661354288, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29396294841478726, "steering_wheel_angle": 0.3683711284490268, "front_wheel_angle": 0.016999585774542164, "heading_rate": 0.009666389411307139, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.4090471} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.04373227780168002, "brake_pedal_speed": 3.0, "steering_wheel_angle": -9.908166235322199, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4385771849485365, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.06931267055211773, "steering_wheel_angle": 0.25407278807897565, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.4090471} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.799960136413574, "x": 42.95414466181501, "y": 3.7049039016101837, "z": null, "yaw": 4.340003369734488, "pitch": null, "roll": null}, "v": 1.4555397661354288, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29396294841478726, "steering_wheel_angle": 0.3683711284490268, "front_wheel_angle": 0.016999585774542164, "heading_rate": 0.009666389411307139, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.429047} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.04373227780168002, "brake_pedal_speed": 3.0, "steering_wheel_angle": -9.908166235322199, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4257325992549528, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.04373227780168002, "steering_wheel_angle": 0.13942652184051157, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.429047} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.799960136413574, "x": 42.95414466181501, "y": 3.7049039016101837, "z": null, "yaw": 4.340003369734488, "pitch": null, "roll": null}, "v": 1.4555397661354288, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29396294841478726, "steering_wheel_angle": 0.3683711284490268, "front_wheel_angle": 0.016999585774542164, "heading_rate": 0.009666389411307139, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.449047} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.04373227780168002, "brake_pedal_speed": 3.0, "steering_wheel_angle": -9.908166235322199, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4129081918986306, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.04373227780168002, "steering_wheel_angle": 0.02443232973363463, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.449047} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.799960136413574, "x": 42.95414466181501, "y": 3.7049039016101837, "z": null, "yaw": 4.340003369734488, "pitch": null, "roll": null}, "v": 1.4555397661354288, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29396294841478726, "steering_wheel_angle": 0.3683711284490268, "front_wheel_angle": 0.016999585774542164, "heading_rate": 0.009666389411307139, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.469047} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.04373227780168002, "brake_pedal_speed": 3.0, "steering_wheel_angle": -9.908166235322199, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.40010386541975, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.04373227780168002, "steering_wheel_angle": -0.09069378792663994, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.469047} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.799960136413574, "x": 42.95414466181501, "y": 3.7049039016101837, "z": null, "yaw": 4.340003369734488, "pitch": null, "roll": null}, "v": 1.4555397661354288, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.29396294841478726, "steering_wheel_angle": 0.3683711284490268, "front_wheel_angle": 0.016999585774542164, "heading_rate": 0.009666389411307139, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.489047} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.04373227780168002, "brake_pedal_speed": 3.0, "steering_wheel_angle": -9.908166235322199, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3873195228202613, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.04373227780168002, "steering_wheel_angle": -0.2054876282453391, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.489047} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502680.499047, "x": 46.89734261908269, "y": 8.559409600818748, "z": null, "yaw": 4.3401653135963665, "pitch": null, "roll": null}, "v": 1.380934815288877, "accelerator_pedal_position": 0, "brake_pedal_position": 0.04373227780168002, "acceleration": -0.6379747728186533, "steering_wheel_angle": -0.26275407620403385, "front_wheel_angle": -0.012108597070307666, "heading_rate": -0.006532031451610934, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.509047} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.01685167223975377, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.2386055108951, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3745550675606903, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.04373227780168002, "steering_wheel_angle": -0.3199335426956253, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.509047} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.9099600315094, "x": 42.89734261908269, "y": 3.559409600818748, "z": null, "yaw": 4.3401653135963665, "pitch": null, "roll": null}, "v": 1.380934815288877, "accelerator_pedal_position": 0, "brake_pedal_position": 0.04373227780168002, "acceleration": -0.6379747728186533, "steering_wheel_angle": -0.26275407620403385, "front_wheel_angle": -0.012108597070307666, "heading_rate": -0.006532031451610934, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.529047} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.025480242057435945, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.2386055108951, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3661096363199872, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.01685167223975377, "steering_wheel_angle": -0.4361348332671461, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.529047} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.9099600315094, "x": 42.89734261908269, "y": 3.559409600818748, "z": null, "yaw": 4.3401653135963665, "pitch": null, "roll": null}, "v": 1.380934815288877, "accelerator_pedal_position": 0, "brake_pedal_position": 0.04373227780168002, "acceleration": -0.6379747728186533, "steering_wheel_angle": -0.26275407620403385, "front_wheel_angle": -0.012108597070307666, "heading_rate": -0.006532031451610934, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.549047} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.025480242057435945, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.2386055108951, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3562972294881814, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.025480242057435945, "steering_wheel_angle": -0.5519752319697921, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.549047} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.9099600315094, "x": 42.89734261908269, "y": 3.559409600818748, "z": null, "yaw": 4.3401653135963665, "pitch": null, "roll": null}, "v": 1.380934815288877, "accelerator_pedal_position": 0, "brake_pedal_position": 0.04373227780168002, "acceleration": -0.6379747728186533, "steering_wheel_angle": -0.26275407620403385, "front_wheel_angle": -0.012108597070307666, "heading_rate": -0.006532031451610934, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.569047} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.025480242057435945, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.2386055108951, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3464999622670824, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.025480242057435945, "steering_wheel_angle": -0.6674547388035639, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.569047} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 41.9099600315094, "x": 42.89734261908269, "y": 3.559409600818748, "z": null, "yaw": 4.3401653135963665, "pitch": null, "roll": null}, "v": 1.380934815288877, "accelerator_pedal_position": 0, "brake_pedal_position": 0.04373227780168002, "acceleration": -0.6379747728186533, "steering_wheel_angle": -0.26275407620403385, "front_wheel_angle": -0.012108597070307666, "heading_rate": -0.006532031451610934, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.589047} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.025480242057435945, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.2386055108951, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3367177729178894, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.025480242057435945, "steering_wheel_angle": -0.7825733537684609, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.589047} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502680.609047, "x": 46.84303533288678, "y": 8.420471320357247, "z": null, "yaw": 4.339067596757311, "pitch": null, "roll": null}, "v": 1.3269505999741287, "accelerator_pedal_position": 0, "brake_pedal_position": 0.025480242057435945, "acceleration": -0.487797445405911, "steering_wheel_angle": -0.8973310768644835, "front_wheel_angle": -0.04170534335315007, "heading_rate": -0.021630093049970118, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.609047} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.04482115805355611, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3269505999741287, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.025480242057435945, "steering_wheel_angle": -0.8973310768644835, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.609047} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.019959926605225, "x": 42.84303533288678, "y": 3.4204713203572474, "z": null, "yaw": 4.339067596757311, "pitch": null, "roll": null}, "v": 1.3269505999741287, "accelerator_pedal_position": 0, "brake_pedal_position": 0.025480242057435945, "acceleration": -0.487797445405911, "steering_wheel_angle": -0.8973310768644835, "front_wheel_angle": -0.04170534335315007, "heading_rate": -0.021630093049970118, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.629047} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.038939658630541, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3141050181993843, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.04482115805355611, "steering_wheel_angle": -1.016846869534795, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.629047} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.019959926605225, "x": 42.84303533288678, "y": 3.4204713203572474, "z": null, "yaw": 4.339067596757311, "pitch": null, "roll": null}, "v": 1.3269505999741287, "accelerator_pedal_position": 0, "brake_pedal_position": 0.025480242057435945, "acceleration": -0.487797445405911, "steering_wheel_angle": -0.8973310768644835, "front_wheel_angle": -0.04170534335315007, "heading_rate": -0.021630093049970118, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.649047} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.038939658630541, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3022197247703717, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.038939658630541, "steering_wheel_angle": -1.1359686940567368, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.649047} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.019959926605225, "x": 42.84303533288678, "y": 3.4204713203572474, "z": null, "yaw": 4.339067596757311, "pitch": null, "roll": null}, "v": 1.3269505999741287, "accelerator_pedal_position": 0, "brake_pedal_position": 0.025480242057435945, "acceleration": -0.487797445405911, "steering_wheel_angle": -0.8973310768644835, "front_wheel_angle": -0.04170534335315007, "heading_rate": -0.021630093049970118, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.6690469} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.038939658630541, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2903525147878825, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.038939658630541, "steering_wheel_angle": -1.2546965504303087, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.6690469} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.019959926605225, "x": 42.84303533288678, "y": 3.4204713203572474, "z": null, "yaw": 4.339067596757311, "pitch": null, "roll": null}, "v": 1.3269505999741287, "accelerator_pedal_position": 0, "brake_pedal_position": 0.025480242057435945, "acceleration": -0.487797445405911, "steering_wheel_angle": -0.8973310768644835, "front_wheel_angle": -0.04170534335315007, "heading_rate": -0.021630093049970118, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.6890469} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.038939658630541, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2785033044270606, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.038939658630541, "steering_wheel_angle": -1.3730304386555103, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.6890469} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.019959926605225, "x": 42.84303533288678, "y": 3.4204713203572474, "z": null, "yaw": 4.339067596757311, "pitch": null, "roll": null}, "v": 1.3269505999741287, "accelerator_pedal_position": 0, "brake_pedal_position": 0.025480242057435945, "acceleration": -0.487797445405911, "steering_wheel_angle": -0.8973310768644835, "front_wheel_angle": -0.04170534335315007, "heading_rate": -0.021630093049970118, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.7090468} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.038939658630541, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2666720102466233, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.038939658630541, "steering_wheel_angle": -1.490970358732342, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.7090468} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502680.7190468, "x": 46.790895977750374, "y": 8.287736723280416, "z": null, "yaw": 4.336667922003423, "pitch": null, "roll": null}, "v": 1.2607630557529026, "accelerator_pedal_position": 0, "brake_pedal_position": 0.038939658630541, "acceleration": -0.5904506566594871, "steering_wheel_angle": -1.5497925807151194, "front_wheel_angle": -0.07267969967071386, "heading_rate": -0.03585686149638931, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.7290468} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.02924620222434405, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2548585491863078, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.038939658630541, "steering_wheel_angle": -1.608516310660804, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.7290468} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.12995982170105, "x": 42.790895977750374, "y": 3.2877367232804158, "z": null, "yaw": 4.336667922003423, "pitch": null, "roll": null}, "v": 1.2607630557529026, "accelerator_pedal_position": 0, "brake_pedal_position": 0.038939658630541, "acceleration": -0.5904506566594871, "steering_wheel_angle": -1.5497925807151194, "front_wheel_angle": -0.07267969967071386, "heading_rate": -0.03585686149638931, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.7490468} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.03247158608050956, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2446132100833431, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.02924620222434405, "steering_wheel_angle": -1.7256682944408959, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.7490468} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.12995982170105, "x": 42.790895977750374, "y": 3.2877367232804158, "z": null, "yaw": 4.336667922003423, "pitch": null, "roll": null}, "v": 1.2607630557529026, "accelerator_pedal_position": 0, "brake_pedal_position": 0.038939658630541, "acceleration": -0.5904506566594871, "steering_wheel_angle": -1.5497925807151194, "front_wheel_angle": -0.07267969967071386, "heading_rate": -0.03585686149638931, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.7690468} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.03247158608050956, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2338673532168754, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.03247158608050956, "steering_wheel_angle": -1.8424263100726175, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.7690468} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.12995982170105, "x": 42.790895977750374, "y": 3.2877367232804158, "z": null, "yaw": 4.336667922003423, "pitch": null, "roll": null}, "v": 1.2607630557529026, "accelerator_pedal_position": 0, "brake_pedal_position": 0.038939658630541, "acceleration": -0.5904506566594871, "steering_wheel_angle": -1.5497925807151194, "front_wheel_angle": -0.07267969967071386, "heading_rate": -0.03585686149638931, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.7890468} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.03247158608050956, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.223137551342444, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.03247158608050956, "steering_wheel_angle": -1.9587903575559695, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.7890468} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.12995982170105, "x": 42.790895977750374, "y": 3.2877367232804158, "z": null, "yaw": 4.336667922003423, "pitch": null, "roll": null}, "v": 1.2607630557529026, "accelerator_pedal_position": 0, "brake_pedal_position": 0.038939658630541, "acceleration": -0.5904506566594871, "steering_wheel_angle": -1.5497925807151194, "front_wheel_angle": -0.07267969967071386, "heading_rate": -0.03585686149638931, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.8090467} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.03247158608050956, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2124237344385458, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.03247158608050956, "steering_wheel_angle": -2.0747604368909514, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.8090467} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502680.8290467, "x": 46.7408958853888, "y": 8.161562816098746, "z": null, "yaw": 4.332930317907047, "pitch": null, "roll": null}, "v": 1.2017258327938845, "accelerator_pedal_position": 0, "brake_pedal_position": 0.03247158608050956, "acceleration": -0.5343004300558123, "steering_wheel_angle": -2.1903365480775627, "front_wheel_angle": -0.10365405598827762, "heading_rate": -0.04883273182851631, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.8290467} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.018059128362835103, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2017258327938845, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.03247158608050956, "steering_wheel_angle": -2.1903365480775627, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.8290467} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.239959716796875, "x": 42.7408958853888, "y": 3.161562816098746, "z": null, "yaw": 4.332930317907047, "pitch": null, "roll": null}, "v": 1.2017258327938845, "accelerator_pedal_position": 0, "brake_pedal_position": 0.03247158608050956, "acceleration": -0.5343004300558123, "steering_wheel_angle": -2.1903365480775627, "front_wheel_angle": -0.10365405598827762, "heading_rate": -0.04883273182851631, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.8490467} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.022735120020248634, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1933489177239156, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.018059128362835103, "steering_wheel_angle": -2.305518691115805, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.8490467} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.239959716796875, "x": 42.7408958853888, "y": 3.161562816098746, "z": null, "yaw": 4.332930317907047, "pitch": null, "roll": null}, "v": 1.2017258327938845, "accelerator_pedal_position": 0, "brake_pedal_position": 0.03247158608050956, "acceleration": -0.5343004300558123, "steering_wheel_angle": -2.1903365480775627, "front_wheel_angle": -0.10365405598827762, "heading_rate": -0.04883273182851631, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.8690467} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.022735120020248634, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.18423649797489, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.022735120020248634, "steering_wheel_angle": -2.4203068660056766, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.8690467} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.239959716796875, "x": 42.7408958853888, "y": 3.161562816098746, "z": null, "yaw": 4.332930317907047, "pitch": null, "roll": null}, "v": 1.2017258327938845, "accelerator_pedal_position": 0, "brake_pedal_position": 0.03247158608050956, "acceleration": -0.5343004300558123, "steering_wheel_angle": -2.1903365480775627, "front_wheel_angle": -0.10365405598827762, "heading_rate": -0.04883273182851631, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.8890467} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.022735120020248634, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1751375105026598, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.022735120020248634, "steering_wheel_angle": -2.534701072747179, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.8890467} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.239959716796875, "x": 42.7408958853888, "y": 3.161562816098746, "z": null, "yaw": 4.332930317907047, "pitch": null, "roll": null}, "v": 1.2017258327938845, "accelerator_pedal_position": 0, "brake_pedal_position": 0.03247158608050956, "acceleration": -0.5343004300558123, "steering_wheel_angle": -2.1903365480775627, "front_wheel_angle": -0.10365405598827762, "heading_rate": -0.04883273182851631, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.9090466} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.022735120020248634, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.166051902402741, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.022735120020248634, "steering_wheel_angle": -2.6487013113403113, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.9090466} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.239959716796875, "x": 42.7408958853888, "y": 3.161562816098746, "z": null, "yaw": 4.332930317907047, "pitch": null, "roll": null}, "v": 1.2017258327938845, "accelerator_pedal_position": 0, "brake_pedal_position": 0.03247158608050956, "acceleration": -0.5343004300558123, "steering_wheel_angle": -2.1903365480775627, "front_wheel_angle": -0.10365405598827762, "heading_rate": -0.04883273182851631, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.9290466} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.022735120020248634, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1569796209945655, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.022735120020248634, "steering_wheel_angle": -2.762307581785073, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.9290466} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502680.9390466, "x": 46.692569220431736, "y": 8.041142232904061, "z": null, "yaw": 4.327847551997605, "pitch": null, "roll": null}, "v": 1.1524484613981087, "accelerator_pedal_position": 0, "brake_pedal_position": 0.022735120020248634, "acceleration": -0.4527847577936832, "steering_wheel_angle": -2.818962978951815, "front_wheel_angle": -0.1346284123058414, "heading_rate": -0.0609752036563806, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.9490466} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.017187229903971417, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1479206138201719, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.022735120020248634, "steering_wheel_angle": -2.875519884081465, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.9490466} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.3499596118927, "x": 42.692569220431736, "y": 3.041142232904061, "z": null, "yaw": 4.327847551997605, "pitch": null, "roll": null}, "v": 1.1524484613981087, "accelerator_pedal_position": 0, "brake_pedal_position": 0.022735120020248634, "acceleration": -0.4527847577936832, "steering_wheel_angle": -2.818962978951815, "front_wheel_angle": -0.1346284123058414, "heading_rate": -0.0609752036563806, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.9690466} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.019062507098743464, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1397621676312317, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.017187229903971417, "steering_wheel_angle": -2.988338218229487, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.9690466} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.3499596118927, "x": 42.692569220431736, "y": 3.041142232904061, "z": null, "yaw": 4.327847551997605, "pitch": null, "roll": null}, "v": 1.1524484613981087, "accelerator_pedal_position": 0, "brake_pedal_position": 0.022735120020248634, "acceleration": -0.4527847577936832, "steering_wheel_angle": -2.818962978951815, "front_wheel_angle": -0.1346284123058414, "heading_rate": -0.0609752036563806, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502680.9890466} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.019062507098743464, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.131315666427458, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.019062507098743464, "steering_wheel_angle": -3.100762584229139, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502680.9890466} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.3499596118927, "x": 42.692569220431736, "y": 3.041142232904061, "z": null, "yaw": 4.327847551997605, "pitch": null, "roll": null}, "v": 1.1524484613981087, "accelerator_pedal_position": 0, "brake_pedal_position": 0.022735120020248634, "acceleration": -0.4527847577936832, "steering_wheel_angle": -2.818962978951815, "front_wheel_angle": -0.1346284123058414, "heading_rate": -0.0609752036563806, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.0090466} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.019062507098743464, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1228814366651136, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.019062507098743464, "steering_wheel_angle": -3.2127929820804213, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.0090466} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.3499596118927, "x": 42.692569220431736, "y": 3.041142232904061, "z": null, "yaw": 4.327847551997605, "pitch": null, "roll": null}, "v": 1.1524484613981087, "accelerator_pedal_position": 0, "brake_pedal_position": 0.022735120020248634, "acceleration": -0.4527847577936832, "steering_wheel_angle": -2.818962978951815, "front_wheel_angle": -0.1346284123058414, "heading_rate": -0.0609752036563806, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.0290465} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.019062507098743464, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1144594320715278, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.019062507098743464, "steering_wheel_angle": -3.324429411783333, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.0290465} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502681.0490465, "x": 46.64556500541736, "y": 7.9259193043541565, "z": null, "yaw": 4.3214097260357205, "pitch": null, "roll": null}, "v": 1.1060496065648597, "accelerator_pedal_position": 0, "brake_pedal_position": 0.019062507098743464, "acceleration": -0.42003599444001355, "steering_wheel_angle": -3.435671873337875, "front_wheel_angle": -0.16560276862340548, "heading_rate": -0.07221009332774524, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.0490465} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1060496065648597, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.019062507098743464, "steering_wheel_angle": -3.435671873337875, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.0490465} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.459959506988525, "x": 42.64556500541736, "y": 2.9259193043541565, "z": null, "yaw": 4.3214097260357205, "pitch": null, "roll": null}, "v": 1.1060496065648597, "accelerator_pedal_position": 0, "brake_pedal_position": 0.019062507098743464, "acceleration": -0.42003599444001355, "steering_wheel_angle": -3.435671873337875, "front_wheel_angle": -0.16560276862340548, "heading_rate": -0.07221009332774524, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.0690465} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1007008165918288, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.5465203667440472, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.0690465} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.459959506988525, "x": 42.64556500541736, "y": 2.9259193043541565, "z": null, "yaw": 4.3214097260357205, "pitch": null, "roll": null}, "v": 1.1060496065648597, "accelerator_pedal_position": 0, "brake_pedal_position": 0.019062507098743464, "acceleration": -0.42003599444001355, "steering_wheel_angle": -3.435671873337875, "front_wheel_angle": -0.16560276862340548, "heading_rate": -0.07221009332774524, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.0890465} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0953597304618, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.6569748920018497, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.0890465} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.459959506988525, "x": 42.64556500541736, "y": 2.9259193043541565, "z": null, "yaw": 4.3214097260357205, "pitch": null, "roll": null}, "v": 1.1060496065648597, "accelerator_pedal_position": 0, "brake_pedal_position": 0.019062507098743464, "acceleration": -0.42003599444001355, "steering_wheel_angle": -3.435671873337875, "front_wheel_angle": -0.16560276862340548, "heading_rate": -0.07221009332774524, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.1090465} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.090026325672174, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.7670354491112814, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.1090465} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.459959506988525, "x": 42.64556500541736, "y": 2.9259193043541565, "z": null, "yaw": 4.3214097260357205, "pitch": null, "roll": null}, "v": 1.1060496065648597, "accelerator_pedal_position": 0, "brake_pedal_position": 0.019062507098743464, "acceleration": -0.42003599444001355, "steering_wheel_angle": -3.435671873337875, "front_wheel_angle": -0.16560276862340548, "heading_rate": -0.07221009332774524, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.1290464} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.084700579801949, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.876702038072344, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.1290464} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.459959506988525, "x": 42.64556500541736, "y": 2.9259193043541565, "z": null, "yaw": 4.3214097260357205, "pitch": null, "roll": null}, "v": 1.1060496065648597, "accelerator_pedal_position": 0, "brake_pedal_position": 0.019062507098743464, "acceleration": -0.42003599444001355, "steering_wheel_angle": -3.435671873337875, "front_wheel_angle": -0.16560276862340548, "heading_rate": -0.07221009332774524, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.1490464} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0793824705113366, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.985974658885036, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.1490464} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502681.1590464, "x": 46.59937923100498, "y": 7.814950095671179, "z": null, "yaw": 4.313604198251807, "pitch": null, "roll": null}, "v": 1.0767262726243163, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2654297082928104, "steering_wheel_angle": -4.040463231235743, "front_wheel_angle": -0.19657712494096927, "heading_rate": -0.08376129872184102, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.1690464} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0740719755413881, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.094853311549359, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.1690464} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.56995940208435, "x": 42.59937923100498, "y": 2.814950095671179, "z": null, "yaw": 4.313604198251807, "pitch": null, "roll": null}, "v": 1.0767262726243163, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2654297082928104, "steering_wheel_angle": -4.040463231235743, "front_wheel_angle": -0.19657712494096927, "heading_rate": -0.08376129872184102, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.1890464} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0687690727136174, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.2033379960653106, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.1890464} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.56995940208435, "x": 42.59937923100498, "y": 2.814950095671179, "z": null, "yaw": 4.313604198251807, "pitch": null, "roll": null}, "v": 1.0767262726243163, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2654297082928104, "steering_wheel_angle": -4.040463231235743, "front_wheel_angle": -0.19657712494096927, "heading_rate": -0.08376129872184102, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.2090464} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0634737399296286, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.311428712432893, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.2090464} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.56995940208435, "x": 42.59937923100498, "y": 2.814950095671179, "z": null, "yaw": 4.313604198251807, "pitch": null, "roll": null}, "v": 1.0767262726243163, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2654297082928104, "steering_wheel_angle": -4.040463231235743, "front_wheel_angle": -0.19657712494096927, "heading_rate": -0.08376129872184102, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.2290463} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0581859551707442, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.419125460652106, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.2290463} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.56995940208435, "x": 42.59937923100498, "y": 2.814950095671179, "z": null, "yaw": 4.313604198251807, "pitch": null, "roll": null}, "v": 1.0767262726243163, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2654297082928104, "steering_wheel_angle": -4.040463231235743, "front_wheel_angle": -0.19657712494096927, "heading_rate": -0.08376129872184102, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.2490463} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0529056964976367, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.526428240722948, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.2490463} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502681.2690463, "x": 46.55351971062796, "y": 7.7073310108479145, "z": null, "yaw": 4.304415482793127, "pitch": null, "roll": null}, "v": 1.047632942049961, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2633569949151806, "steering_wheel_angle": -4.6333370526454205, "front_wheel_angle": -0.22755148125853306, "heading_rate": -0.09476252584499364, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.2690463} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.047632942049961, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.6333370526454205, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.2690463} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.679959297180176, "x": 42.55351971062796, "y": 2.7073310108479145, "z": null, "yaw": 4.304415482793127, "pitch": null, "roll": null}, "v": 1.047632942049961, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2633569949151806, "steering_wheel_angle": -4.6333370526454205, "front_wheel_angle": -0.22755148125853306, "heading_rate": -0.09476252584499364, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.2890463} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0423676700459898, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.739851896419523, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.2890463} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.679959297180176, "x": 42.55351971062796, "y": 2.7073310108479145, "z": null, "yaw": 4.304415482793127, "pitch": null, "roll": null}, "v": 1.047632942049961, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2633569949151806, "steering_wheel_angle": -4.6333370526454205, "front_wheel_angle": -0.22755148125853306, "heading_rate": -0.09476252584499364, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.3090463} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.03710985878225, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.845972772045256, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.3090463} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.679959297180176, "x": 42.55351971062796, "y": 2.7073310108479145, "z": null, "yaw": 4.304415482793127, "pitch": null, "roll": null}, "v": 1.047632942049961, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2633569949151806, "steering_wheel_angle": -4.6333370526454205, "front_wheel_angle": -0.22755148125853306, "heading_rate": -0.09476252584499364, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.3290462} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0318594866331625, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.951699679522617, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.3290462} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.679959297180176, "x": 42.55351971062796, "y": 2.7073310108479145, "z": null, "yaw": 4.304415482793127, "pitch": null, "roll": null}, "v": 1.047632942049961, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2633569949151806, "steering_wheel_angle": -4.6333370526454205, "front_wheel_angle": -0.22755148125853306, "heading_rate": -0.09476252584499364, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.3490462} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0266165320506824, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.057032618851611, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.3490462} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.679959297180176, "x": 42.55351971062796, "y": 2.7073310108479145, "z": null, "yaw": 4.304415482793127, "pitch": null, "roll": null}, "v": 1.047632942049961, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2633569949151806, "steering_wheel_angle": -4.6333370526454205, "front_wheel_angle": -0.22755148125853306, "heading_rate": -0.09476252584499364, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.3690462} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0213809735639423, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.161971590032232, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.3690462} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502681.3790462, "x": 46.50788445645159, "y": 7.603088828733065, "z": null, "yaw": 4.2938251246562, "pitch": null, "roll": null}, "v": 1.0187659611678446, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2613171388947346, "steering_wheel_angle": -5.2142933375669065, "front_wheel_angle": -0.25852583757609715, "heading_rate": -0.10523680231410065, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.3890462} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0161527897788971, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.266516593064485, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.3890462} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.789959192276, "x": 42.50788445645159, "y": 2.603088828733065, "z": null, "yaw": 4.2938251246562, "pitch": null, "roll": null}, "v": 1.0187659611678446, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2613171388947346, "steering_wheel_angle": -5.2142933375669065, "front_wheel_angle": -0.25852583757609715, "heading_rate": -0.10523680231410065, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.4090462} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0109319593779706, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.370667627948367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.4090462} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.789959192276, "x": 42.50788445645159, "y": 2.603088828733065, "z": null, "yaw": 4.2938251246562, "pitch": null, "roll": null}, "v": 1.0187659611678446, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2613171388947346, "steering_wheel_angle": -5.2142933375669065, "front_wheel_angle": -0.25852583757609715, "heading_rate": -0.10523680231410065, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.4290462} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0057184611197048, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.47442469468388, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.4290462} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.789959192276, "x": 42.50788445645159, "y": 2.603088828733065, "z": null, "yaw": 4.2938251246562, "pitch": null, "roll": null}, "v": 1.0187659611678446, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2613171388947346, "steering_wheel_angle": -5.2142933375669065, "front_wheel_angle": -0.25852583757609715, "heading_rate": -0.10523680231410065, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.4490461} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0005122738384093, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.577787793271023, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.4490461} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.789959192276, "x": 42.50788445645159, "y": 2.603088828733065, "z": null, "yaw": 4.2938251246562, "pitch": null, "roll": null}, "v": 1.0187659611678446, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2613171388947346, "steering_wheel_angle": -5.2142933375669065, "front_wheel_angle": -0.25852583757609715, "heading_rate": -0.10523680231410065, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.469046} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9953133764438159, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.6807569237097955, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.469046} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502681.489046, "x": 46.46238279099186, "y": 7.50225005188212, "z": null, "yaw": 4.281811547917533, "pitch": null, "roll": null}, "v": 0.9901217479207308, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25930949815309257, "steering_wheel_angle": -5.783332086000198, "front_wheel_angle": -0.28950019389366066, "heading_rate": -0.1152055207419707, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.489046} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9901217479207308, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.783332086000198, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.489046} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.899959087371826, "x": 42.46238279099186, "y": 2.50225005188212, "z": null, "yaw": 4.281811547917533, "pitch": null, "roll": null}, "v": 0.9901217479207308, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25930949815309257, "steering_wheel_angle": -5.783332086000198, "front_wheel_angle": -0.28950019389366066, "heading_rate": -0.1152055207419707, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.509046} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9849373673286927, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.885513280142231, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.509046} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.899959087371826, "x": 42.46238279099186, "y": 2.50225005188212, "z": null, "yaw": 4.281811547917533, "pitch": null, "roll": null}, "v": 0.9901217479207308, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25930949815309257, "steering_wheel_angle": -5.783332086000198, "front_wheel_angle": -0.28950019389366066, "heading_rate": -0.1152055207419707, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.529046} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.97976021380163, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.987300506135893, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.529046} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.899959087371826, "x": 42.46238279099186, "y": 2.50225005188212, "z": null, "yaw": 4.281811547917533, "pitch": null, "roll": null}, "v": 0.9901217479207308, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25930949815309257, "steering_wheel_angle": -5.783332086000198, "front_wheel_angle": -0.28950019389366066, "heading_rate": -0.1152055207419707, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.549046} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.974590266547521, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.088693763981186, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.549046} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.899959087371826, "x": 42.46238279099186, "y": 2.50225005188212, "z": null, "yaw": 4.281811547917533, "pitch": null, "roll": null}, "v": 0.9901217479207308, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25930949815309257, "steering_wheel_angle": -5.783332086000198, "front_wheel_angle": -0.28950019389366066, "heading_rate": -0.1152055207419707, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.569046} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9694275048480564, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.189693053678109, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.569046} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 42.899959087371826, "x": 42.46238279099186, "y": 2.50225005188212, "z": null, "yaw": 4.281811547917533, "pitch": null, "roll": null}, "v": 0.9901217479207308, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25930949815309257, "steering_wheel_angle": -5.783332086000198, "front_wheel_angle": -0.28950019389366066, "heading_rate": -0.1152055207419707, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.589046} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9642719080583022, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.290298375226661, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.589046} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502681.599046, "x": 46.41693526074779, "y": 7.4048411884956975, "z": null, "yaw": 4.2683498745449375, "pitch": null, "roll": null}, "v": 0.961696790073006, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2573334466640176, "steering_wheel_angle": -6.3404532979453, "front_wheel_angle": -0.3204745502112247, "heading_rate": -0.12468855423001877, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.609046} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9591234556063658, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.390509728626844, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.609046} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.00995898246765, "x": 42.41693526074779, "y": 2.4048411884956975, "z": null, "yaw": 4.2683498745449375, "pitch": null, "roll": null}, "v": 0.961696790073006, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2573334466640176, "steering_wheel_angle": -6.3404532979453, "front_wheel_angle": -0.3204745502112247, "heading_rate": -0.12468855423001877, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.629046} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9539821269930633, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.490327113878657, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.629046} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.00995898246765, "x": 42.41693526074779, "y": 2.4048411884956975, "z": null, "yaw": 4.2683498745449375, "pitch": null, "roll": null}, "v": 0.961696790073006, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2573334466640176, "steering_wheel_angle": -6.3404532979453, "front_wheel_angle": -0.3204745502112247, "heading_rate": -0.12468855423001877, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.649046} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9488479017915884, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.5897505309821, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.649046} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.00995898246765, "x": 42.41693526074779, "y": 2.4048411884956975, "z": null, "yaw": 4.2683498745449375, "pitch": null, "roll": null}, "v": 0.961696790073006, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2573334466640176, "steering_wheel_angle": -6.3404532979453, "front_wheel_angle": -0.3204745502112247, "heading_rate": -0.12468855423001877, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.669046} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9437207596471837, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.688779979937172, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.669046} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.00995898246765, "x": 42.41693526074779, "y": 2.4048411884956975, "z": null, "yaw": 4.2683498745449375, "pitch": null, "roll": null}, "v": 0.961696790073006, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2573334466640176, "steering_wheel_angle": -6.3404532979453, "front_wheel_angle": -0.3204745502112247, "heading_rate": -0.12468855423001877, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.689046} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9386006802768131, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.787415460743876, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.689046} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502681.709046, "x": 46.371473581054296, "y": 7.310888970568799, "z": null, "yaw": 4.253411710455373, "pitch": null, "roll": null}, "v": 0.9334876434688367, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25538837397853187, "steering_wheel_angle": -6.885656973402209, "front_wheel_angle": -0.35144890652878846, "heading_rate": -0.1337043584899913, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.709046} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9334876434688367, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.885656973402209, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.709046} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.11995887756348, "x": 42.371473581054296, "y": 2.310888970568799, "z": null, "yaw": 4.253411710455373, "pitch": null, "roll": null}, "v": 0.9334876434688367, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25538837397853187, "steering_wheel_angle": -6.885656973402209, "front_wheel_angle": -0.35144890652878846, "heading_rate": -0.1337043584899913, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.7290459} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9283816290826866, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.983504517912171, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.7290459} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.11995887756348, "x": 42.371473581054296, "y": 2.310888970568799, "z": null, "yaw": 4.253411710455373, "pitch": null, "roll": null}, "v": 0.9334876434688367, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25538837397853187, "steering_wheel_angle": -6.885656973402209, "front_wheel_angle": -0.35144890652878846, "heading_rate": -0.1337043584899913, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.7490458} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9232826170485451, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.080958094273765, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.7490458} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.11995887756348, "x": 42.371473581054296, "y": 2.310888970568799, "z": null, "yaw": 4.253411710455373, "pitch": null, "roll": null}, "v": 0.9334876434688367, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25538837397853187, "steering_wheel_angle": -6.885656973402209, "front_wheel_angle": -0.35144890652878846, "heading_rate": -0.1337043584899913, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.7690458} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9181905873670244, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.178017702486988, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.7690458} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.11995887756348, "x": 42.371473581054296, "y": 2.310888970568799, "z": null, "yaw": 4.253411710455373, "pitch": null, "roll": null}, "v": 0.9334876434688367, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25538837397853187, "steering_wheel_angle": -6.885656973402209, "front_wheel_angle": -0.35144890652878846, "heading_rate": -0.1337043584899913, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.7890458} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9131055201088482, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.27468334255184, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.7890458} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.11995887756348, "x": 42.371473581054296, "y": 2.310888970568799, "z": null, "yaw": 4.253411710455373, "pitch": null, "roll": null}, "v": 0.9334876434688367, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25538837397853187, "steering_wheel_angle": -6.885656973402209, "front_wheel_angle": -0.35144890652878846, "heading_rate": -0.1337043584899913, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.8090458} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9080273954145345, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.370955014468323, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.8090458} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502681.8190458, "x": 46.325940612849635, "y": 7.220420509127849, "z": null, "yaw": 4.236964894760447, "pitch": null, "roll": null}, "v": 0.9054909303417449, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25347368476639887, "steering_wheel_angle": -7.418943112370925, "front_wheel_angle": -0.38242326284635225, "heading_rate": -0.1422700616694297, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.8290458} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9029561934940808, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.466832718236436, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.8290458} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.2299587726593, "x": 42.325940612849635, "y": 2.220420509127849, "z": null, "yaw": 4.236964894760447, "pitch": null, "roll": null}, "v": 0.9054909303417449, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25347368476639887, "steering_wheel_angle": -7.418943112370925, "front_wheel_angle": -0.38242326284635225, "heading_rate": -0.1422700616694297, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.8490458} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8978918946266506, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.56231645385618, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.8490458} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.2299587726593, "x": 42.325940612849635, "y": 2.220420509127849, "z": null, "yaw": 4.236964894760447, "pitch": null, "roll": null}, "v": 0.9054909303417449, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25347368476639887, "steering_wheel_angle": -7.418943112370925, "front_wheel_angle": -0.38242326284635225, "heading_rate": -0.1422700616694297, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.8690457} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8928344791602614, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.657406221327552, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.8690457} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.2299587726593, "x": 42.325940612849635, "y": 2.220420509127849, "z": null, "yaw": 4.236964894760447, "pitch": null, "roll": null}, "v": 0.9054909303417449, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25347368476639887, "steering_wheel_angle": -7.418943112370925, "front_wheel_angle": -0.38242326284635225, "heading_rate": -0.1422700616694297, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.8890457} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8877839275114745, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.752102020650556, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.8890457} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.2299587726593, "x": 42.325940612849635, "y": 2.220420509127849, "z": null, "yaw": 4.236964894760447, "pitch": null, "roll": null}, "v": 0.9054909303417449, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.25347368476639887, "steering_wheel_angle": -7.418943112370925, "front_wheel_angle": -0.38242326284635225, "heading_rate": -0.1422700616694297, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.9090457} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8827402201650871, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.846403851825188, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.9090457} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502681.9290457, "x": 46.280290371822886, "y": 7.133463386665087, "z": null, "yaw": 4.218973207279142, "pitch": null, "roll": null}, "v": 0.8777033376738249, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.251588798373329, "steering_wheel_angle": -7.940311714851451, "front_wheel_angle": -0.4133976191639163, "heading_rate": -0.15040154273641737, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.9290457} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2266695176080931, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8777033376738249, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.940311714851451, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.9290457} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.33995866775513, "x": 42.280290371822886, "y": 2.1334633866650874, "z": null, "yaw": 4.218973207279142, "pitch": null, "roll": null}, "v": 0.8777033376738249, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.251588798373329, "steering_wheel_angle": -7.940311714851451, "front_wheel_angle": -0.4133976191639163, "heading_rate": -0.15040154273641737, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.9490457} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22058919472955266, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8760058248984476, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.033825609729345, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.9490457} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.33995866775513, "x": 42.280290371822886, "y": 2.1334633866650874, "z": null, "yaw": 4.218973207279142, "pitch": null, "roll": null}, "v": 0.8777033376738249, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.251588798373329, "steering_wheel_angle": -7.940311714851451, "front_wheel_angle": -0.4133976191639163, "heading_rate": -0.15040154273641737, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.9690456} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22058919472955266, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.87355082011381, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.126945536458868, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.9690456} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.33995866775513, "x": 42.280290371822886, "y": 2.1334633866650874, "z": null, "yaw": 4.218973207279142, "pitch": null, "roll": null}, "v": 0.8777033376738249, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.251588798373329, "steering_wheel_angle": -7.940311714851451, "front_wheel_angle": -0.4133976191639163, "heading_rate": -0.15040154273641737, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502681.9890456} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22058919472955266, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8710991276474346, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.21967149504002, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502681.9890456} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.33995866775513, "x": 42.280290371822886, "y": 2.1334633866650874, "z": null, "yaw": 4.218973207279142, "pitch": null, "roll": null}, "v": 0.8777033376738249, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.251588798373329, "steering_wheel_angle": -7.940311714851451, "front_wheel_angle": -0.4133976191639163, "heading_rate": -0.15040154273641737, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.0090456} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22058919472955266, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.868650740626798, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.312003485472804, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.0090456} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.33995866775513, "x": 42.280290371822886, "y": 2.1334633866650874, "z": null, "yaw": 4.218973207279142, "pitch": null, "roll": null}, "v": 0.8777033376738249, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.251588798373329, "steering_wheel_angle": -7.940311714851451, "front_wheel_angle": -0.4133976191639163, "heading_rate": -0.15040154273641737, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.0290456} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22058919472955266, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8662056521983664, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.403941507757217, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.0290456} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502682.0390456, "x": 46.23411116520935, "y": 7.049364719840734, "z": null, "yaw": 4.199396028363092, "pitch": null, "roll": null}, "v": 0.8649843428196743, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2507311962742156, "steering_wheel_angle": -8.449762780843786, "front_wheel_angle": -0.4443719754814801, "heading_rate": -0.16087780686135567, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.0490456} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8637638555275292, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.49548556189326, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.0490456} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.44995856285095, "x": 42.23411116520935, "y": 2.0493647198407343, "z": null, "yaw": 4.199396028363092, "pitch": null, "roll": null}, "v": 0.8649843428196743, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2507311962742156, "steering_wheel_angle": -8.449762780843786, "front_wheel_angle": -0.4443719754814801, "heading_rate": -0.16087780686135567, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.0690455} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8587525596927117, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.586635647880934, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.0690455} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.44995856285095, "x": 42.23411116520935, "y": 2.0493647198407343, "z": null, "yaw": 4.199396028363092, "pitch": null, "roll": null}, "v": 0.8649843428196743, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2507311962742156, "steering_wheel_angle": -8.449762780843786, "front_wheel_angle": -0.4443719754814801, "heading_rate": -0.16087780686135567, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.0890455} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8537479967881028, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.677391765720236, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.0890455} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.44995856285095, "x": 42.23411116520935, "y": 2.0493647198407343, "z": null, "yaw": 4.199396028363092, "pitch": null, "roll": null}, "v": 0.8649843428196743, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2507311962742156, "steering_wheel_angle": -8.449762780843786, "front_wheel_angle": -0.4443719754814801, "heading_rate": -0.16087780686135567, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.1090455} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8487501477527668, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.76775391541117, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.1090455} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.44995856285095, "x": 42.23411116520935, "y": 2.0493647198407343, "z": null, "yaw": 4.199396028363092, "pitch": null, "roll": null}, "v": 0.8649843428196743, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2507311962742156, "steering_wheel_angle": -8.449762780843786, "front_wheel_angle": -0.4443719754814801, "heading_rate": -0.16087780686135567, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.1290455} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8437589935916608, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.857722096953735, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.1290455} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502682.1490455, "x": 46.1872560304227, "y": 6.9679918604176265, "z": null, "yaw": 4.178187943827709, "pitch": null, "roll": null}, "v": 0.8387745153753405, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24897415264519843, "steering_wheel_angle": -8.947296310347928, "front_wheel_angle": -0.4753463317990439, "heading_rate": -0.16864286365063735, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.1490455} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2228953735421645, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8387745153753405, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.947296310347928, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.1490455} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.55995845794678, "x": 42.1872560304227, "y": 1.9679918604176265, "z": null, "yaw": 4.178187943827709, "pitch": null, "roll": null}, "v": 0.8387745153753405, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24897415264519843, "steering_wheel_angle": -8.947296310347928, "front_wheel_angle": -0.4753463317990439, "heading_rate": -0.16864286365063735, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.1690454} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22062387077792323, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8366576609090959, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.036476555593751, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.1690454} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.55995845794678, "x": 42.1872560304227, "y": 1.9679918604176265, "z": null, "yaw": 4.178187943827709, "pitch": null, "roll": null}, "v": 0.8387745153753405, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24897415264519843, "steering_wheel_angle": -8.947296310347928, "front_wheel_angle": -0.4753463317990439, "heading_rate": -0.16864286365063735, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.1890454} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22062387077792323, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8342597880983463, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.125262832691204, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.1890454} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.55995845794678, "x": 42.1872560304227, "y": 1.9679918604176265, "z": null, "yaw": 4.178187943827709, "pitch": null, "roll": null}, "v": 0.8387745153753405, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24897415264519843, "steering_wheel_angle": -8.947296310347928, "front_wheel_angle": -0.4753463317990439, "heading_rate": -0.16864286365063735, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.2090454} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22062387077792323, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8318651128484266, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.213655141640286, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.2090454} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.55995845794678, "x": 42.1872560304227, "y": 1.9679918604176265, "z": null, "yaw": 4.178187943827709, "pitch": null, "roll": null}, "v": 0.8387745153753405, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24897415264519843, "steering_wheel_angle": -8.947296310347928, "front_wheel_angle": -0.4753463317990439, "heading_rate": -0.16864286365063735, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.2290454} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22062387077792323, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8294736286023684, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.301653482441, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.2290454} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.55995845794678, "x": 42.1872560304227, "y": 1.9679918604176265, "z": null, "yaw": 4.178187943827709, "pitch": null, "roll": null}, "v": 0.8387745153753405, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24897415264519843, "steering_wheel_angle": -8.947296310347928, "front_wheel_angle": -0.4753463317990439, "heading_rate": -0.16864286365063735, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.2490454} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22062387077792323, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8270853288211096, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.389257855093344, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.2490454} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502682.2590454, "x": 46.139797136358645, "y": 6.889608830573974, "z": null, "yaw": 4.155298286254579, "pitch": null, "roll": null}, "v": 0.8258923710662042, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2481156006391638, "steering_wheel_angle": -9.432912303363878, "front_wheel_angle": -0.5063206881166078, "heading_rate": -0.17890187349623277, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.2690454} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22897113907058217, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8247002069834327, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.476468259597318, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.2690454} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.6699583530426, "x": 42.139797136358645, "y": 1.889608830573974, "z": null, "yaw": 4.155298286254579, "pitch": null, "roll": null}, "v": 0.8258923710662042, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2481156006391638, "steering_wheel_angle": -9.432912303363878, "front_wheel_angle": -0.5063206881166078, "heading_rate": -0.17890187349623277, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.2890453} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22631968839039798, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8233613183175196, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.56328469595292, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.2890453} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.6699583530426, "x": 42.139797136358645, "y": 1.889608830573974, "z": null, "yaw": 4.155298286254579, "pitch": null, "roll": null}, "v": 0.8258923710662042, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2481156006391638, "steering_wheel_angle": -9.432912303363878, "front_wheel_angle": -0.5063206881166078, "heading_rate": -0.17890187349623277, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.3090453} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22631968839039798, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8216928878702966, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.649707164160155, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.3090453} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.6699583530426, "x": 42.139797136358645, "y": 1.889608830573974, "z": null, "yaw": 4.155298286254579, "pitch": null, "roll": null}, "v": 0.8258923710662042, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2481156006391638, "steering_wheel_angle": -9.432912303363878, "front_wheel_angle": -0.5063206881166078, "heading_rate": -0.17890187349623277, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.3290453} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22631968839039798, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8200266737704125, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.735735664219016, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.3290453} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.6699583530426, "x": 42.139797136358645, "y": 1.889608830573974, "z": null, "yaw": 4.155298286254579, "pitch": null, "roll": null}, "v": 0.8258923710662042, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.2481156006391638, "steering_wheel_angle": -9.432912303363878, "front_wheel_angle": -0.5063206881166078, "heading_rate": -0.17890187349623277, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.3490453} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22631968839039798, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8183626719635265, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.82137019612951, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.3490453} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502682.3690453, "x": 46.091168825634995, "y": 6.813426493996616, "z": null, "yaw": 4.130670602052144, "pitch": null, "roll": null}, "v": 0.8167008784051033, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24750504716813185, "steering_wheel_angle": -9.906610759891635, "front_wheel_angle": -0.5372950444341715, "heading_rate": -0.1900611855914682, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.3690453} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23246593857643497, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8167008784051033, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.906610759891635, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.3690453} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.77995824813843, "x": 42.091168825634995, "y": 1.8134264939966158, "z": null, "yaw": 4.130670602052144, "pitch": null, "roll": null}, "v": 0.8167008784051033, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24750504716813185, "steering_wheel_angle": -9.906610759891635, "front_wheel_angle": -0.5372950444341715, "heading_rate": -0.1900611855914682, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.3890452} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23051470644041933, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.815809315566737, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.99145735550539, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.3890452} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.77995824813843, "x": 42.091168825634995, "y": 1.8134264939966158, "z": null, "yaw": 4.130670602052144, "pitch": null, "roll": null}, "v": 0.8167008784051033, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24750504716813185, "steering_wheel_angle": -9.906610759891635, "front_wheel_angle": -0.5372950444341715, "heading_rate": -0.1900611855914682, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.4090452} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23051470644041933, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8146751117612538, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.075909982970774, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.4090452} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.77995824813843, "x": 42.091168825634995, "y": 1.8134264939966158, "z": null, "yaw": 4.130670602052144, "pitch": null, "roll": null}, "v": 0.8167008784051033, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24750504716813185, "steering_wheel_angle": -9.906610759891635, "front_wheel_angle": -0.5372950444341715, "heading_rate": -0.1900611855914682, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.4290452} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23051470644041933, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8135424113927572, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.159968642287787, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.4290452} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.77995824813843, "x": 42.091168825634995, "y": 1.8134264939966158, "z": null, "yaw": 4.130670602052144, "pitch": null, "roll": null}, "v": 0.8167008784051033, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24750504716813185, "steering_wheel_angle": -9.906610759891635, "front_wheel_angle": -0.5372950444341715, "heading_rate": -0.1900611855914682, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.4490452} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23051470644041933, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8124112119553409, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.243633333456428, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.4490452} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.77995824813843, "x": 42.091168825634995, "y": 1.8134264939966158, "z": null, "yaw": 4.130670602052144, "pitch": null, "roll": null}, "v": 0.8167008784051033, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24750504716813185, "steering_wheel_angle": -9.906610759891635, "front_wheel_angle": -0.5372950444341715, "heading_rate": -0.1900611855914682, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.4690452} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23051470644041933, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8112815109484594, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.326904056476703, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.4690452} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502682.4790452, "x": 46.04108412913952, "y": 6.739197153871549, "z": null, "yaw": 4.104242031335271, "pitch": null, "roll": null}, "v": 0.8107172215765106, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24710848521243292, "steering_wheel_angle": -10.3683916799312, "front_wheel_angle": -0.5682694007517354, "heading_rate": -0.20221366705032978, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.4890451} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24375855571687555, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8101533058769125, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.4890451} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.88995814323425, "x": 42.04108412913952, "y": 1.7391971538715492, "z": null, "yaw": 4.104242031335271, "pitch": null, "roll": null}, "v": 0.8107172215765106, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24710848521243292, "steering_wheel_angle": -10.3683916799312, "front_wheel_angle": -0.5682694007517354, "heading_rate": -0.20221366705032978, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.5090451} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23960002199365085, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8106815274455238, "gear": 1, "accelerator_pedal_position": 0.24375855571687555, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.5090451} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.88995814323425, "x": 42.04108412913952, "y": 1.7391971538715492, "z": null, "yaw": 4.104242031335271, "pitch": null, "roll": null}, "v": 0.8107172215765106, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24710848521243292, "steering_wheel_angle": -10.3683916799312, "front_wheel_angle": -0.5682694007517354, "heading_rate": -0.20221366705032978, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.529045} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23960002199365085, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8106894051505737, "gear": 1, "accelerator_pedal_position": 0.23960002199365085, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.529045} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.88995814323425, "x": 42.04108412913952, "y": 1.7391971538715492, "z": null, "yaw": 4.104242031335271, "pitch": null, "roll": null}, "v": 0.8107172215765106, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24710848521243292, "steering_wheel_angle": -10.3683916799312, "front_wheel_angle": -0.5682694007517354, "heading_rate": -0.20221366705032978, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.549045} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23960002199365085, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.81069727242683, "gear": 1, "accelerator_pedal_position": 0.23960002199365085, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.549045} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.88995814323425, "x": 42.04108412913952, "y": 1.7391971538715492, "z": null, "yaw": 4.104242031335271, "pitch": null, "roll": null}, "v": 0.8107172215765106, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24710848521243292, "steering_wheel_angle": -10.3683916799312, "front_wheel_angle": -0.5682694007517354, "heading_rate": -0.20221366705032978, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.569045} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23960002199365085, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8107051292880736, "gear": 1, "accelerator_pedal_position": 0.23960002199365085, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.569045} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502682.589045, "x": 45.989226203077486, "y": 6.666662492234313, "z": null, "yaw": 4.076650089916402, "pitch": null, "roll": null}, "v": 0.8107129757480677, "accelerator_pedal_position": 0.23960002199365085, "brake_pedal_position": 0.0, "acceleration": 0.0003919333824514981, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.2034701885403637, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.589045} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23432393975286758, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8107129757480677, "gear": 1, "accelerator_pedal_position": 0.23960002199365085, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.589045} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.99995803833008, "x": 41.989226203077486, "y": 1.6666624922343134, "z": null, "yaw": 4.076650089916402, "pitch": null, "roll": null}, "v": 0.8107129757480677, "accelerator_pedal_position": 0.23960002199365085, "brake_pedal_position": 0.0, "acceleration": 0.0003919333824514981, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.2034701885403637, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.609045} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2359727024773971, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8100615198747682, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.609045} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.99995803833008, "x": 41.989226203077486, "y": 1.6666624922343134, "z": null, "yaw": 4.076650089916402, "pitch": null, "roll": null}, "v": 0.8107129757480677, "accelerator_pedal_position": 0.23960002199365085, "brake_pedal_position": 0.0, "acceleration": 0.0003919333824514981, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.2034701885403637, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.629045} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2359727024773971, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8096169534293792, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.629045} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.99995803833008, "x": 41.989226203077486, "y": 1.6666624922343134, "z": null, "yaw": 4.076650089916402, "pitch": null, "roll": null}, "v": 0.8107129757480677, "accelerator_pedal_position": 0.23960002199365085, "brake_pedal_position": 0.0, "acceleration": 0.0003919333824514981, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.2034701885403637, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.649045} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2359727024773971, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8091729753468221, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.649045} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.99995803833008, "x": 41.989226203077486, "y": 1.6666624922343134, "z": null, "yaw": 4.076650089916402, "pitch": null, "roll": null}, "v": 0.8107129757480677, "accelerator_pedal_position": 0.23960002199365085, "brake_pedal_position": 0.0, "acceleration": 0.0003919333824514981, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.2034701885403637, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.659045} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2359727024773971, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8089512066735828, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.659045} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 43.99995803833008, "x": 41.989226203077486, "y": 1.6666624922343134, "z": null, "yaw": 4.076650089916402, "pitch": null, "roll": null}, "v": 0.8107129757480677, "accelerator_pedal_position": 0.23960002199365085, "brake_pedal_position": 0.0, "acceleration": 0.0003919333824514981, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.2034701885403637, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.679045} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2359727024773971, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8080655986040941, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.679045} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502682.699045, "x": 45.93546611141185, "y": 6.595691571139081, "z": null, "yaw": 4.049042636466195, "pitch": null, "roll": null}, "v": 0.8080655986040941, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24693298004667866, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.20280575816520569, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.699045} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23424883703249288, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8078445627084646, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.699045} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.1099579334259, "x": 41.93546611141185, "y": 1.5956915711390813, "z": null, "yaw": 4.049042636466195, "pitch": null, "roll": null}, "v": 0.8080655986040941, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24693298004667866, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.20280575816520569, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.729045} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23477878412992648, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8071875176087375, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.729045} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.1099579334259, "x": 41.93546611141185, "y": 1.5956915711390813, "z": null, "yaw": 4.049042636466195, "pitch": null, "roll": null}, "v": 0.8080655986040941, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24693298004667866, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.20280575816520569, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.749045} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23477878412992648, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8065975629345642, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.749045} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.1099579334259, "x": 41.93546611141185, "y": 1.5956915711390813, "z": null, "yaw": 4.049042636466195, "pitch": null, "roll": null}, "v": 0.8080655986040941, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24693298004667866, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.20280575816520569, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.7690449} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23477878412992648, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8060083883342463, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.7690449} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.1099579334259, "x": 41.93546611141185, "y": 1.5956915711390813, "z": null, "yaw": 4.049042636466195, "pitch": null, "roll": null}, "v": 0.8080655986040941, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24693298004667866, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.20280575816520569, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.7890449} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23477878412992648, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8054199926375181, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.7890449} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502682.8090448, "x": 45.87996140548262, "y": 6.526473307551362, "z": null, "yaw": 4.0214351830159885, "pitch": null, "roll": null}, "v": 0.8048323746762113, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24671917024708007, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.20199429380990475, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.8090448} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.248118041228851, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8048323746762113, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.8090448} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.21995782852173, "x": 41.87996140548262, "y": 1.5264733075513623, "z": null, "yaw": 4.0214351830159885, "pitch": null, "roll": null}, "v": 0.8048323746762113, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24671917024708007, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.20199429380990475, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.8290448} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24393883015535284, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8061906605630459, "gear": 1, "accelerator_pedal_position": 0.24393883015535284, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.8290448} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.21995782852173, "x": 41.87996140548262, "y": 1.5264733075513623, "z": null, "yaw": 4.0214351830159885, "pitch": null, "roll": null}, "v": 0.8048323746762113, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24671917024708007, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.20199429380990475, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.8490448} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24393883015535284, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8064687477793561, "gear": 1, "accelerator_pedal_position": 0.24393883015535284, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.8490448} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.21995782852173, "x": 41.87996140548262, "y": 1.5264733075513623, "z": null, "yaw": 4.0214351830159885, "pitch": null, "roll": null}, "v": 0.8048323746762113, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24671917024708007, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.20199429380990475, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.8690448} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24393883015535284, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8070243706493109, "gear": 1, "accelerator_pedal_position": 0.24393883015535284, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.8690448} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.21995782852173, "x": 41.87996140548262, "y": 1.5264733075513623, "z": null, "yaw": 4.0214351830159885, "pitch": null, "roll": null}, "v": 0.8048323746762113, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24671917024708007, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.20199429380990475, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.8890448} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24393883015535284, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8078564276392179, "gear": 1, "accelerator_pedal_position": 0.24393883015535284, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.8890448} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.21995782852173, "x": 41.87996140548262, "y": 1.5264733075513623, "z": null, "yaw": 4.0214351830159885, "pitch": null, "roll": null}, "v": 0.8048323746762113, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.24671917024708007, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.20199429380990475, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.9090447} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24393883015535284, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8081334131093401, "gear": 1, "accelerator_pedal_position": 0.24393883015535284, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.9090447} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502682.9190447, "x": 45.822561060291235, "y": 6.458808985154009, "z": null, "yaw": 3.993827729565783, "pitch": null, "roll": null}, "v": 0.8084102153261565, "accelerator_pedal_position": 0.24393883015535284, "brake_pedal_position": 0.0, "acceleration": 0.02766190694221049, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.20289224898441025, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.9290447} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2393835745989912, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8086785669512053, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.9290447} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.329957723617554, "x": 41.822561060291235, "y": 1.4588089851540094, "z": null, "yaw": 3.993827729565783, "pitch": null, "roll": null}, "v": 0.8084102153261565, "accelerator_pedal_position": 0.24393883015535284, "brake_pedal_position": 0.0, "acceleration": 0.02766190694221049, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.20289224898441025, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.9490447} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2408189234655255, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8086703049777021, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.9490447} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.329957723617554, "x": 41.822561060291235, "y": 1.4588089851540094, "z": null, "yaw": 3.993827729565783, "pitch": null, "roll": null}, "v": 0.8084102153261565, "accelerator_pedal_position": 0.24393883015535284, "brake_pedal_position": 0.0, "acceleration": 0.02766190694221049, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.20289224898441025, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.9690447} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2408189234655255, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8088331566727303, "gear": 1, "accelerator_pedal_position": 0.2408189234655255, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.9690447} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.329957723617554, "x": 41.822561060291235, "y": 1.4588089851540094, "z": null, "yaw": 3.993827729565783, "pitch": null, "roll": null}, "v": 0.8084102153261565, "accelerator_pedal_position": 0.24393883015535284, "brake_pedal_position": 0.0, "acceleration": 0.02766190694221049, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.20289224898441025, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502682.9890447} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2408189234655255, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8089957929020929, "gear": 1, "accelerator_pedal_position": 0.2408189234655255, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502682.9890447} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.329957723617554, "x": 41.822561060291235, "y": 1.4588089851540094, "z": null, "yaw": 3.993827729565783, "pitch": null, "roll": null}, "v": 0.8084102153261565, "accelerator_pedal_position": 0.24393883015535284, "brake_pedal_position": 0.0, "acceleration": 0.02766190694221049, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.20289224898441025, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.0090446} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2408189234655255, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8091582139402913, "gear": 1, "accelerator_pedal_position": 0.2408189234655255, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.0090446} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502683.0290446, "x": 45.763155053355334, "y": 6.392575848835998, "z": null, "yaw": 3.966220276115581, "pitch": null, "roll": null}, "v": 0.8093204200615057, "accelerator_pedal_position": 0.2408189234655255, "brake_pedal_position": 0.0, "acceleration": 0.00810225523317365, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.20312068930133123, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.0290446} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25343192396151953, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8093204200615057, "gear": 1, "accelerator_pedal_position": 0.2408189234655255, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.0290446} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.43995761871338, "x": 41.763155053355334, "y": 1.3925758488359978, "z": null, "yaw": 3.966220276115581, "pitch": null, "roll": null}, "v": 0.8093204200615057, "accelerator_pedal_position": 0.2408189234655255, "brake_pedal_position": 0.0, "acceleration": 0.00810225523317365, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.20312068930133123, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.0490446} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2494933704690853, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8110585147709254, "gear": 1, "accelerator_pedal_position": 0.25343192396151953, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.0490446} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.43995761871338, "x": 41.763155053355334, "y": 1.3925758488359978, "z": null, "yaw": 3.966220276115581, "pitch": null, "roll": null}, "v": 0.8093204200615057, "accelerator_pedal_position": 0.2408189234655255, "brake_pedal_position": 0.0, "acceleration": 0.00810225523317365, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.20312068930133123, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.0690446} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2494933704690853, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8123021524311164, "gear": 1, "accelerator_pedal_position": 0.2494933704690853, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.0690446} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.43995761871338, "x": 41.763155053355334, "y": 1.3925758488359978, "z": null, "yaw": 3.966220276115581, "pitch": null, "roll": null}, "v": 0.8093204200615057, "accelerator_pedal_position": 0.2408189234655255, "brake_pedal_position": 0.0, "acceleration": 0.00810225523317365, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.20312068930133123, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.0890446} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2494933704690853, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8135441430702153, "gear": 1, "accelerator_pedal_position": 0.2494933704690853, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.0890446} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.43995761871338, "x": 41.763155053355334, "y": 1.3925758488359978, "z": null, "yaw": 3.966220276115581, "pitch": null, "roll": null}, "v": 0.8093204200615057, "accelerator_pedal_position": 0.2408189234655255, "brake_pedal_position": 0.0, "acceleration": 0.00810225523317365, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.20312068930133123, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.1090446} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2494933704690853, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.814784488252655, "gear": 1, "accelerator_pedal_position": 0.2494933704690853, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.1090446} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.43995761871338, "x": 41.763155053355334, "y": 1.3925758488359978, "z": null, "yaw": 3.966220276115581, "pitch": null, "roll": null}, "v": 0.8093204200615057, "accelerator_pedal_position": 0.2408189234655255, "brake_pedal_position": 0.0, "acceleration": 0.00810225523317365, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.20312068930133123, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.1290445} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2494933704690853, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8166419242182065, "gear": 1, "accelerator_pedal_position": 0.2494933704690853, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.1290445} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502683.1390445, "x": 45.70163966210803, "y": 6.327689734849988, "z": null, "yaw": 3.938612822665379, "pitch": null, "roll": null}, "v": 0.8166419242182065, "accelerator_pedal_position": 0.2494933704690853, "brake_pedal_position": 0.0, "acceleration": 0.0618324288969645, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.20495821734852743, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.1390445} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24805827541920122, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8166419242182065, "gear": 1, "accelerator_pedal_position": 0.2494933704690853, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.1390445} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.549957513809204, "x": 41.70163966210803, "y": 1.3276897348499883, "z": null, "yaw": 3.938612822665379, "pitch": null, "roll": null}, "v": 0.8166419242182065, "accelerator_pedal_position": 0.2494933704690853, "brake_pedal_position": 0.0, "acceleration": 0.0618324288969645, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.20495821734852743, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.1690445} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24853099893765457, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.818226764888689, "gear": 1, "accelerator_pedal_position": 0.24805827541920122, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.1690445} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.549957513809204, "x": 41.70163966210803, "y": 1.3276897348499883, "z": null, "yaw": 3.938612822665379, "pitch": null, "roll": null}, "v": 0.8166419242182065, "accelerator_pedal_position": 0.2494933704690853, "brake_pedal_position": 0.0, "acceleration": 0.0618324288969645, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.20495821734852743, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.1890445} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24853099893765457, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8198970294214624, "gear": 1, "accelerator_pedal_position": 0.24853099893765457, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.1890445} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.549957513809204, "x": 41.70163966210803, "y": 1.3276897348499883, "z": null, "yaw": 3.938612822665379, "pitch": null, "roll": null}, "v": 0.8166419242182065, "accelerator_pedal_position": 0.2494933704690853, "brake_pedal_position": 0.0, "acceleration": 0.0618324288969645, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.20495821734852743, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.2090445} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24853099893765457, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8204530452264697, "gear": 1, "accelerator_pedal_position": 0.24853099893765457, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.2090445} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.549957513809204, "x": 41.70163966210803, "y": 1.3276897348499883, "z": null, "yaw": 3.938612822665379, "pitch": null, "roll": null}, "v": 0.8166419242182065, "accelerator_pedal_position": 0.2494933704690853, "brake_pedal_position": 0.0, "acceleration": 0.0618324288969645, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.20495821734852743, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.2290444} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24853099893765457, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8221188780913448, "gear": 1, "accelerator_pedal_position": 0.24853099893765457, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.2290444} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502683.2490444, "x": 45.63785070163154, "y": 6.2640210525144, "z": null, "yaw": 3.911005369215177, "pitch": null, "roll": null}, "v": 0.8226734181409311, "accelerator_pedal_position": 0.24853099893765457, "brake_pedal_position": 0.0, "acceleration": 0.05541715692413757, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.2064719826913165, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.2490444} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2602766526996217, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8226734181409311, "gear": 1, "accelerator_pedal_position": 0.24853099893765457, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.2490444} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.65995740890503, "x": 41.63785070163154, "y": 1.2640210525143996, "z": null, "yaw": 3.911005369215177, "pitch": null, "roll": null}, "v": 0.8226734181409311, "accelerator_pedal_position": 0.24853099893765457, "brake_pedal_position": 0.0, "acceleration": 0.05541715692413757, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.2064719826913165, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.2690444} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2566261560006241, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8252491117303219, "gear": 1, "accelerator_pedal_position": 0.2602766526996217, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.2690444} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.65995740890503, "x": 41.63785070163154, "y": 1.2640210525143996, "z": null, "yaw": 3.911005369215177, "pitch": null, "roll": null}, "v": 0.8226734181409311, "accelerator_pedal_position": 0.24853099893765457, "brake_pedal_position": 0.0, "acceleration": 0.05541715692413757, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.2064719826913165, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.2890444} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2566261560006241, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8273652208942538, "gear": 1, "accelerator_pedal_position": 0.2566261560006241, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.2890444} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.65995740890503, "x": 41.63785070163154, "y": 1.2640210525143996, "z": null, "yaw": 3.911005369215177, "pitch": null, "roll": null}, "v": 0.8226734181409311, "accelerator_pedal_position": 0.24853099893765457, "brake_pedal_position": 0.0, "acceleration": 0.05541715692413757, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.2064719826913165, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.3090444} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2566261560006241, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8294785150157422, "gear": 1, "accelerator_pedal_position": 0.2566261560006241, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.3090444} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.65995740890503, "x": 41.63785070163154, "y": 1.2640210525143996, "z": null, "yaw": 3.911005369215177, "pitch": null, "roll": null}, "v": 0.8226734181409311, "accelerator_pedal_position": 0.24853099893765457, "brake_pedal_position": 0.0, "acceleration": 0.05541715692413757, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.2064719826913165, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.3290443} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2566261560006241, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8315889960538044, "gear": 1, "accelerator_pedal_position": 0.2566261560006241, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.3290443} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.65995740890503, "x": 41.63785070163154, "y": 1.2640210525143996, "z": null, "yaw": 3.911005369215177, "pitch": null, "roll": null}, "v": 0.8226734181409311, "accelerator_pedal_position": 0.24853099893765457, "brake_pedal_position": 0.0, "acceleration": 0.05541715692413757, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.2064719826913165, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.3490443} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2566261560006241, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8336966659719801, "gear": 1, "accelerator_pedal_position": 0.2566261560006241, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.3490443} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502683.3590443, "x": 45.57160770546459, "y": 6.20145866495381, "z": null, "yaw": 3.883397915764975, "pitch": null, "roll": null}, "v": 0.8347494473759478, "accelerator_pedal_position": 0.2566261560006241, "brake_pedal_position": 0.0, "acceleration": 0.10520793623615865, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.20950278646376203, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.3690443} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26634333805121624, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8358015267383094, "gear": 1, "accelerator_pedal_position": 0.2566261560006241, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.3690443} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.769957304000854, "x": 41.57160770546459, "y": 1.20145866495381, "z": null, "yaw": 3.883397915764975, "pitch": null, "roll": null}, "v": 0.8347494473759478, "accelerator_pedal_position": 0.2566261560006241, "brake_pedal_position": 0.0, "acceleration": 0.10520793623615865, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.20950278646376203, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.3890443} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2633469143123746, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8391178227346616, "gear": 1, "accelerator_pedal_position": 0.26634333805121624, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.3890443} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.769957304000854, "x": 41.57160770546459, "y": 1.20145866495381, "z": null, "yaw": 3.883397915764975, "pitch": null, "roll": null}, "v": 0.8347494473759478, "accelerator_pedal_position": 0.2566261560006241, "brake_pedal_position": 0.0, "acceleration": 0.10520793623615865, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.20950278646376203, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.4090443} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2633469143123746, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8420552640670611, "gear": 1, "accelerator_pedal_position": 0.2633469143123746, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.4090443} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.769957304000854, "x": 41.57160770546459, "y": 1.20145866495381, "z": null, "yaw": 3.883397915764975, "pitch": null, "roll": null}, "v": 0.8347494473759478, "accelerator_pedal_position": 0.2566261560006241, "brake_pedal_position": 0.0, "acceleration": 0.10520793623615865, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.20950278646376203, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.4190443} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2633469143123746, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8449887807378914, "gear": 1, "accelerator_pedal_position": 0.2633469143123746, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.4190443} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.769957304000854, "x": 41.57160770546459, "y": 1.20145866495381, "z": null, "yaw": 3.883397915764975, "pitch": null, "roll": null}, "v": 0.8347494473759478, "accelerator_pedal_position": 0.2566261560006241, "brake_pedal_position": 0.0, "acceleration": 0.10520793623615865, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.20950278646376203, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.4490442} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2633469143123746, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8479183745497636, "gear": 1, "accelerator_pedal_position": 0.2633469143123746, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.4490442} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502683.4690442, "x": 45.50254291420188, "y": 6.1397492913788705, "z": null, "yaw": 3.855790462314773, "pitch": null, "roll": null}, "v": 0.8508440473166797, "accelerator_pedal_position": 0.2633469143123746, "brake_pedal_position": 0.0, "acceleration": 0.146136656157965, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.21354215845161106, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.4690442} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2719109214614162, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8508440473166797, "gear": 1, "accelerator_pedal_position": 0.2633469143123746, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.4690442} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.87995719909668, "x": 41.50254291420188, "y": 1.1397492913788705, "z": null, "yaw": 3.855790462314773, "pitch": null, "roll": null}, "v": 0.8508440473166797, "accelerator_pedal_position": 0.2633469143123746, "brake_pedal_position": 0.0, "acceleration": 0.146136656157965, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.21354215845161106, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.4890442} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26928846848425825, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8548359428643778, "gear": 1, "accelerator_pedal_position": 0.2719109214614162, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.4890442} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.87995719909668, "x": 41.50254291420188, "y": 1.1397492913788705, "z": null, "yaw": 3.855790462314773, "pitch": null, "roll": null}, "v": 0.8508440473166797, "accelerator_pedal_position": 0.2633469143123746, "brake_pedal_position": 0.0, "acceleration": 0.146136656157965, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.21354215845161106, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.4990442} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26928846848425825, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8566659797242905, "gear": 1, "accelerator_pedal_position": 0.26928846848425825, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.4990442} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.87995719909668, "x": 41.50254291420188, "y": 1.1397492913788705, "z": null, "yaw": 3.855790462314773, "pitch": null, "roll": null}, "v": 0.8508440473166797, "accelerator_pedal_position": 0.2633469143123746, "brake_pedal_position": 0.0, "acceleration": 0.146136656157965, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.21354215845161106, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.5290442} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26928846848425825, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8621487215485044, "gear": 1, "accelerator_pedal_position": 0.26928846848425825, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.5290442} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.87995719909668, "x": 41.50254291420188, "y": 1.1397492913788705, "z": null, "yaw": 3.855790462314773, "pitch": null, "roll": null}, "v": 0.8508440473166797, "accelerator_pedal_position": 0.2633469143123746, "brake_pedal_position": 0.0, "acceleration": 0.146136656157965, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.21354215845161106, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.5490441} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26928846848425825, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8657977437025117, "gear": 1, "accelerator_pedal_position": 0.26928846848425825, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.5490441} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.87995719909668, "x": 41.50254291420188, "y": 1.1397492913788705, "z": null, "yaw": 3.855790462314773, "pitch": null, "roll": null}, "v": 0.8508440473166797, "accelerator_pedal_position": 0.2633469143123746, "brake_pedal_position": 0.0, "acceleration": 0.146136656157965, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.21354215845161106, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.569044} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26928846848425825, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8694418560929251, "gear": 1, "accelerator_pedal_position": 0.26928846848425825, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.569044} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502683.579044, "x": 45.43026560860449, "y": 6.078673615162425, "z": null, "yaw": 3.828183008864571, "pitch": null, "roll": null}, "v": 0.8712620715310322, "accelerator_pedal_position": 0.26928846848425825, "brake_pedal_position": 0.0, "acceleration": 0.1818988484771769, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.21866660984290964, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.589044} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2765304033951706, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.873081060015804, "gear": 1, "accelerator_pedal_position": 0.26928846848425825, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.589044} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.989957094192505, "x": 41.43026560860449, "y": 1.0786736151624252, "z": null, "yaw": 3.828183008864571, "pitch": null, "roll": null}, "v": 0.8712620715310322, "accelerator_pedal_position": 0.26928846848425825, "brake_pedal_position": 0.0, "acceleration": 0.1818988484771769, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.21866660984290964, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.609044} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2743359233594503, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8776202931203205, "gear": 1, "accelerator_pedal_position": 0.2765304033951706, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.609044} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.989957094192505, "x": 41.43026560860449, "y": 1.0786736151624252, "z": null, "yaw": 3.828183008864571, "pitch": null, "roll": null}, "v": 0.8712620715310322, "accelerator_pedal_position": 0.26928846848425825, "brake_pedal_position": 0.0, "acceleration": 0.1818988484771769, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.21866660984290964, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.629044} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2743359233594503, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8818791803410174, "gear": 1, "accelerator_pedal_position": 0.2743359233594503, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.629044} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.989957094192505, "x": 41.43026560860449, "y": 1.0786736151624252, "z": null, "yaw": 3.828183008864571, "pitch": null, "roll": null}, "v": 0.8712620715310322, "accelerator_pedal_position": 0.26928846848425825, "brake_pedal_position": 0.0, "acceleration": 0.1818988484771769, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.21866660984290964, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.649044} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2743359233594503, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8861323101064769, "gear": 1, "accelerator_pedal_position": 0.2743359233594503, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.649044} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 44.989957094192505, "x": 41.43026560860449, "y": 1.0786736151624252, "z": null, "yaw": 3.828183008864571, "pitch": null, "roll": null}, "v": 0.8712620715310322, "accelerator_pedal_position": 0.26928846848425825, "brake_pedal_position": 0.0, "acceleration": 0.1818988484771769, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.21866660984290964, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.669044} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2743359233594503, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8903796829668241, "gear": 1, "accelerator_pedal_position": 0.2743359233594503, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.669044} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502683.689044, "x": 45.35447594427345, "y": 6.018136331816677, "z": null, "yaw": 3.800575555414369, "pitch": null, "roll": null}, "v": 0.8946212995008026, "accelerator_pedal_position": 0.2743359233594503, "brake_pedal_position": 0.0, "acceleration": 0.21186498332631903, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.2245292352866197, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.689044} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22673518493925648, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8946212995008026, "gear": 1, "accelerator_pedal_position": 0.2743359233594503, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.689044} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.09995698928833, "x": 41.35447594427345, "y": 1.0181363318166774, "z": null, "yaw": 3.800575555414369, "pitch": null, "roll": null}, "v": 0.8946212995008026, "accelerator_pedal_position": 0.2743359233594503, "brake_pedal_position": 0.0, "acceleration": 0.21186498332631903, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.2245292352866197, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.709044} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24168944840638662, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8929090882196996, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.709044} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.09995698928833, "x": 41.35447594427345, "y": 1.0181363318166774, "z": null, "yaw": 3.800575555414369, "pitch": null, "roll": null}, "v": 0.8946212995008026, "accelerator_pedal_position": 0.2743359233594503, "brake_pedal_position": 0.0, "acceleration": 0.21186498332631903, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.2245292352866197, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.729044} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24168944840638662, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8930678489693209, "gear": 1, "accelerator_pedal_position": 0.24168944840638662, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.729044} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.09995698928833, "x": 41.35447594427345, "y": 1.0181363318166774, "z": null, "yaw": 3.800575555414369, "pitch": null, "roll": null}, "v": 0.8946212995008026, "accelerator_pedal_position": 0.2743359233594503, "brake_pedal_position": 0.0, "acceleration": 0.21186498332631903, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.2245292352866197, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.749044} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24168944840638662, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8932263943201756, "gear": 1, "accelerator_pedal_position": 0.24168944840638662, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.749044} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.09995698928833, "x": 41.35447594427345, "y": 1.0181363318166774, "z": null, "yaw": 3.800575555414369, "pitch": null, "roll": null}, "v": 0.8946212995008026, "accelerator_pedal_position": 0.2743359233594503, "brake_pedal_position": 0.0, "acceleration": 0.21186498332631903, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.2245292352866197, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.769044} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24168944840638662, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.893384724554455, "gear": 1, "accelerator_pedal_position": 0.24168944840638662, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.769044} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.09995698928833, "x": 41.35447594427345, "y": 1.0181363318166774, "z": null, "yaw": 3.800575555414369, "pitch": null, "roll": null}, "v": 0.8946212995008026, "accelerator_pedal_position": 0.2743359233594503, "brake_pedal_position": 0.0, "acceleration": 0.21186498332631903, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.2245292352866197, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.789044} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24168944840638662, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8935428399540083, "gear": 1, "accelerator_pedal_position": 0.24168944840638662, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.789044} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502683.799044, "x": 45.27603238275469, "y": 5.958943243443391, "z": null, "yaw": 3.772968101964167, "pitch": null, "roll": null}, "v": 0.8936218171787471, "accelerator_pedal_position": 0.24168944840638662, "brake_pedal_position": 0.0, "acceleration": 0.007892362159600486, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.224278388362252, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.809044} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25129052142379393, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8937007408003431, "gear": 1, "accelerator_pedal_position": 0.24168944840638662, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.809044} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.209956884384155, "x": 41.27603238275469, "y": 0.9589432434433913, "z": null, "yaw": 3.772968101964167, "pitch": null, "roll": null}, "v": 0.8936218171787471, "accelerator_pedal_position": 0.24168944840638662, "brake_pedal_position": 0.0, "acceleration": 0.007892362159600486, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.224278388362252, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.8290439} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24828679177195906, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8950581541667205, "gear": 1, "accelerator_pedal_position": 0.25129052142379393, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.8290439} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.209956884384155, "x": 41.27603238275469, "y": 0.9589432434433913, "z": null, "yaw": 3.772968101964167, "pitch": null, "roll": null}, "v": 0.8936218171787471, "accelerator_pedal_position": 0.24168944840638662, "brake_pedal_position": 0.0, "acceleration": 0.007892362159600486, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.224278388362252, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.8490438} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24828679177195906, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8960383862326239, "gear": 1, "accelerator_pedal_position": 0.24828679177195906, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.8490438} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.209956884384155, "x": 41.27603238275469, "y": 0.9589432434433913, "z": null, "yaw": 3.772968101964167, "pitch": null, "roll": null}, "v": 0.8936218171787471, "accelerator_pedal_position": 0.24168944840638662, "brake_pedal_position": 0.0, "acceleration": 0.007892362159600486, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.224278388362252, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.8690438} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24828679177195906, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8970172872844945, "gear": 1, "accelerator_pedal_position": 0.24828679177195906, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.8690438} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.209956884384155, "x": 41.27603238275469, "y": 0.9589432434433913, "z": null, "yaw": 3.772968101964167, "pitch": null, "roll": null}, "v": 0.8936218171787471, "accelerator_pedal_position": 0.24168944840638662, "brake_pedal_position": 0.0, "acceleration": 0.007892362159600486, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.224278388362252, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.8890438} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24828679177195906, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8979948587464889, "gear": 1, "accelerator_pedal_position": 0.24828679177195906, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.8890438} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.209956884384155, "x": 41.27603238275469, "y": 0.9589432434433913, "z": null, "yaw": 3.772968101964167, "pitch": null, "roll": null}, "v": 0.8936218171787471, "accelerator_pedal_position": 0.24168944840638662, "brake_pedal_position": 0.0, "acceleration": 0.007892362159600486, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.224278388362252, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.8990438} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24828679177195906, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8989711020423907, "gear": 1, "accelerator_pedal_position": 0.24828679177195906, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.8990438} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502683.9090438, "x": 45.1957521013195, "y": 5.901774237694393, "z": null, "yaw": 3.745360648513965, "pitch": null, "roll": null}, "v": 0.8989711020423907, "accelerator_pedal_position": 0.24828679177195906, "brake_pedal_position": 0.0, "acceleration": 0.04876240304955143, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.22562093502466032, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.9190438} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24828643723161659, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8994587260728862, "gear": 1, "accelerator_pedal_position": 0.24828679177195906, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.9190438} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.31995677947998, "x": 41.1957521013195, "y": 0.9017742376943927, "z": null, "yaw": 3.745360648513965, "pitch": null, "roll": null}, "v": 0.8989711020423907, "accelerator_pedal_position": 0.24828679177195906, "brake_pedal_position": 0.0, "acceleration": 0.04876240304955143, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.22562093502466032, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.9490438} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2483047157947018, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9014069627611467, "gear": 1, "accelerator_pedal_position": 0.2483047157947018, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.9490438} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.31995677947998, "x": 41.1957521013195, "y": 0.9017742376943927, "z": null, "yaw": 3.745360648513965, "pitch": null, "roll": null}, "v": 0.8989711020423907, "accelerator_pedal_position": 0.24828679177195906, "brake_pedal_position": 0.0, "acceleration": 0.04876240304955143, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.22562093502466032, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.9590437} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2483047157947018, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9014069627611467, "gear": 1, "accelerator_pedal_position": 0.2483047157947018, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.9590437} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.31995677947998, "x": 41.1957521013195, "y": 0.9017742376943927, "z": null, "yaw": 3.745360648513965, "pitch": null, "roll": null}, "v": 0.8989711020423907, "accelerator_pedal_position": 0.24828679177195906, "brake_pedal_position": 0.0, "acceleration": 0.04876240304955143, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.22562093502466032, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502683.9890437} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2483047157947018, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9028672322113167, "gear": 1, "accelerator_pedal_position": 0.2483047157947018, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502683.9890437} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.31995677947998, "x": 41.1957521013195, "y": 0.9017742376943927, "z": null, "yaw": 3.745360648513965, "pitch": null, "roll": null}, "v": 0.8989711020423907, "accelerator_pedal_position": 0.24828679177195906, "brake_pedal_position": 0.0, "acceleration": 0.04876240304955143, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.22562093502466032, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.0090437} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2483047157947018, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9038390897592111, "gear": 1, "accelerator_pedal_position": 0.2483047157947018, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.0090437} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502684.0190437, "x": 45.1134295898405, "y": 5.846510878115508, "z": null, "yaw": 3.717753195063763, "pitch": null, "roll": null}, "v": 0.9043245224414828, "accelerator_pedal_position": 0.2483047157947018, "brake_pedal_position": 0.0, "acceleration": 0.048510219175921965, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.22696451961072664, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.0290437} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2547083847326999, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9056946258210362, "gear": 1, "accelerator_pedal_position": 0.2547083847326999, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.0290437} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.429956674575806, "x": 41.1134295898405, "y": 0.8465108781155077, "z": null, "yaw": 3.717753195063763, "pitch": null, "roll": null}, "v": 0.9043245224414828, "accelerator_pedal_position": 0.2483047157947018, "brake_pedal_position": 0.0, "acceleration": 0.048510219175921965, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.22696451961072664, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.0490437} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25272544734024904, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9065790242783953, "gear": 1, "accelerator_pedal_position": 0.2547083847326999, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.0490437} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.429956674575806, "x": 41.1134295898405, "y": 0.8465108781155077, "z": null, "yaw": 3.717753195063763, "pitch": null, "roll": null}, "v": 0.9043245224414828, "accelerator_pedal_position": 0.2483047157947018, "brake_pedal_position": 0.0, "acceleration": 0.048510219175921965, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.22696451961072664, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.0690436} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25272544734024904, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9080982313021982, "gear": 1, "accelerator_pedal_position": 0.25272544734024904, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.0690436} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.429956674575806, "x": 41.1134295898405, "y": 0.8465108781155077, "z": null, "yaw": 3.717753195063763, "pitch": null, "roll": null}, "v": 0.9043245224414828, "accelerator_pedal_position": 0.2483047157947018, "brake_pedal_position": 0.0, "acceleration": 0.048510219175921965, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.22696451961072664, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.0890436} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25272544734024904, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9096153682198448, "gear": 1, "accelerator_pedal_position": 0.25272544734024904, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.0890436} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.429956674575806, "x": 41.1134295898405, "y": 0.8465108781155077, "z": null, "yaw": 3.717753195063763, "pitch": null, "roll": null}, "v": 0.9043245224414828, "accelerator_pedal_position": 0.2483047157947018, "brake_pedal_position": 0.0, "acceleration": 0.048510219175921965, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.22696451961072664, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.1090436} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25272544734024904, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9111304369317408, "gear": 1, "accelerator_pedal_position": 0.25272544734024904, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.1090436} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502684.1290436, "x": 45.02899345633571, "y": 5.793150406444788, "z": null, "yaw": 3.690145741613561, "pitch": null, "roll": null}, "v": 0.9126434393394649, "accelerator_pedal_position": 0.25272544734024904, "brake_pedal_position": 0.0, "acceleration": 0.07557269343588946, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.229052375165428, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.1290436} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2606582217404537, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9126434393394649, "gear": 1, "accelerator_pedal_position": 0.25272544734024904, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.1290436} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.53995656967163, "x": 41.02899345633571, "y": 0.7931504064447878, "z": null, "yaw": 3.690145741613561, "pitch": null, "roll": null}, "v": 0.9126434393394649, "accelerator_pedal_position": 0.25272544734024904, "brake_pedal_position": 0.0, "acceleration": 0.07557269343588946, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.229052375165428, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.1490436} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2582075830286109, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9151456356496324, "gear": 1, "accelerator_pedal_position": 0.2606582217404537, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.1490436} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.53995656967163, "x": 41.02899345633571, "y": 0.7931504064447878, "z": null, "yaw": 3.690145741613561, "pitch": null, "roll": null}, "v": 0.9126434393394649, "accelerator_pedal_position": 0.25272544734024904, "brake_pedal_position": 0.0, "acceleration": 0.07557269343588946, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.229052375165428, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.1690435} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2582075830286109, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9173381904201684, "gear": 1, "accelerator_pedal_position": 0.2582075830286109, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.1690435} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.53995656967163, "x": 41.02899345633571, "y": 0.7931504064447878, "z": null, "yaw": 3.690145741613561, "pitch": null, "roll": null}, "v": 0.9126434393394649, "accelerator_pedal_position": 0.25272544734024904, "brake_pedal_position": 0.0, "acceleration": 0.07557269343588946, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.229052375165428, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.1890435} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2582075830286109, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9195277496150125, "gear": 1, "accelerator_pedal_position": 0.2582075830286109, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.1890435} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.53995656967163, "x": 41.02899345633571, "y": 0.7931504064447878, "z": null, "yaw": 3.690145741613561, "pitch": null, "roll": null}, "v": 0.9126434393394649, "accelerator_pedal_position": 0.25272544734024904, "brake_pedal_position": 0.0, "acceleration": 0.07557269343588946, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.229052375165428, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.2090435} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2582075830286109, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9217143154098545, "gear": 1, "accelerator_pedal_position": 0.2582075830286109, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.2090435} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.53995656967163, "x": 41.02899345633571, "y": 0.7931504064447878, "z": null, "yaw": 3.690145741613561, "pitch": null, "roll": null}, "v": 0.9126434393394649, "accelerator_pedal_position": 0.25272544734024904, "brake_pedal_position": 0.0, "acceleration": 0.07557269343588946, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.229052375165428, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.2290435} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2582075830286109, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.9830422872897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9238978899852707, "gear": 1, "accelerator_pedal_position": 0.2582075830286109, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.2290435} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502684.2390435, "x": 44.94213976589536, "y": 5.741561929978398, "z": null, "yaw": 3.662538288163359, "pitch": null, "roll": null}, "v": 0.9249885562484543, "accelerator_pedal_position": 0.2582075830286109, "brake_pedal_position": 0.0, "acceleration": 0.10899192782448935, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.23215071371453921, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.2490435} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.265506808087436, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.739273416278579, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9260784755266992, "gear": 1, "accelerator_pedal_position": 0.2582075830286109, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.2490435} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.649956464767456, "x": 40.94213976589536, "y": 0.7415619299783982, "z": null, "yaw": 3.662538288163359, "pitch": null, "roll": null}, "v": 0.9249885562484543, "accelerator_pedal_position": 0.2582075830286109, "brake_pedal_position": 0.0, "acceleration": 0.10899192782448935, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.23215071371453921, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.2690434} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2632680044718622, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.739273416278579, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9291681646401061, "gear": 1, "accelerator_pedal_position": 0.265506808087436, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.2690434} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.649956464767456, "x": 40.94213976589536, "y": 0.7415619299783982, "z": null, "yaw": 3.662538288163359, "pitch": null, "roll": null}, "v": 0.9249885562484543, "accelerator_pedal_position": 0.2582075830286109, "brake_pedal_position": 0.0, "acceleration": 0.10899192782448935, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.23215071371453921, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.2890434} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2632680044718622, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.739273416278579, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9333752695097702, "gear": 1, "accelerator_pedal_position": 0.2632680044718622, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.2890434} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.649956464767456, "x": 40.94213976589536, "y": 0.7415619299783982, "z": null, "yaw": 3.662538288163359, "pitch": null, "roll": null}, "v": 0.9249885562484543, "accelerator_pedal_position": 0.2582075830286109, "brake_pedal_position": 0.0, "acceleration": 0.10899192782448935, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.23215071371453921, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.3090434} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2632680044718622, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.739273416278579, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9347757132151335, "gear": 1, "accelerator_pedal_position": 0.2632680044718622, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.3090434} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.649956464767456, "x": 40.94213976589536, "y": 0.7415619299783982, "z": null, "yaw": 3.662538288163359, "pitch": null, "roll": null}, "v": 0.9249885562484543, "accelerator_pedal_position": 0.2582075830286109, "brake_pedal_position": 0.0, "acceleration": 0.10899192782448935, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.23215071371453921, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.3290434} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2632680044718622, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.739273416278579, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9389712743316225, "gear": 1, "accelerator_pedal_position": 0.2632680044718622, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.3290434} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502684.3490434, "x": 44.852593124490916, "y": 5.691666016377232, "z": null, "yaw": 3.634930834713157, "pitch": null, "roll": null}, "v": 0.9403678722685461, "accelerator_pedal_position": 0.2632680044718622, "brake_pedal_position": 0.0, "acceleration": 0.13956371698376274, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.2360105659974541, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.3490434} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2661325095401085, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.287477308667842, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9403678722685461, "gear": 1, "accelerator_pedal_position": 0.2632680044718622, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.3490434} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.75995635986328, "x": 40.852593124490916, "y": 0.6916660163772317, "z": null, "yaw": 3.634930834713157, "pitch": null, "roll": null}, "v": 0.9403678722685461, "accelerator_pedal_position": 0.2632680044718622, "brake_pedal_position": 0.0, "acceleration": 0.13956371698376274, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.2360105659974541, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.3690434} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2652901433970356, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.287477308667842, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9435161260058479, "gear": 1, "accelerator_pedal_position": 0.2661325095401085, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.3690434} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.75995635986328, "x": 40.852593124490916, "y": 0.6916660163772317, "z": null, "yaw": 3.634930834713157, "pitch": null, "roll": null}, "v": 0.9403678722685461, "accelerator_pedal_position": 0.2632680044718622, "brake_pedal_position": 0.0, "acceleration": 0.13956371698376274, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.2360105659974541, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.3890433} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2652901433970356, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.287477308667842, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9480725462821832, "gear": 1, "accelerator_pedal_position": 0.2652901433970356, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.3890433} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.75995635986328, "x": 40.852593124490916, "y": 0.6916660163772317, "z": null, "yaw": 3.634930834713157, "pitch": null, "roll": null}, "v": 0.9403678722685461, "accelerator_pedal_position": 0.2632680044718622, "brake_pedal_position": 0.0, "acceleration": 0.13956371698376274, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.2360105659974541, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.4090433} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2652901433970356, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.287477308667842, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9495892598160555, "gear": 1, "accelerator_pedal_position": 0.2652901433970356, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.4090433} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.75995635986328, "x": 40.852593124490916, "y": 0.6916660163772317, "z": null, "yaw": 3.634930834713157, "pitch": null, "roll": null}, "v": 0.9403678722685461, "accelerator_pedal_position": 0.2632680044718622, "brake_pedal_position": 0.0, "acceleration": 0.13956371698376274, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.2360105659974541, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.4290433} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2652901433970356, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.287477308667842, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9541331244002744, "gear": 1, "accelerator_pedal_position": 0.2652901433970356, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.4290433} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.75995635986328, "x": 40.852593124490916, "y": 0.6916660163772317, "z": null, "yaw": 3.634930834713157, "pitch": null, "roll": null}, "v": 0.9403678722685461, "accelerator_pedal_position": 0.2632680044718622, "brake_pedal_position": 0.0, "acceleration": 0.13956371698376274, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.2360105659974541, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.4490433} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2652901433970356, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -10.287477308667842, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9556456547984812, "gear": 1, "accelerator_pedal_position": 0.2652901433970356, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.4490433} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502684.4590433, "x": 44.760131135677895, "y": 5.643441244225822, "z": null, "yaw": 3.607323381262955, "pitch": null, "roll": null}, "v": 0.9571571400716431, "accelerator_pedal_position": 0.2652901433970356, "brake_pedal_position": 0.0, "acceleration": 0.15104404131998905, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.24022428353688124, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.4690433} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26367004289287854, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -9.77675029398072, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.958667580484843, "gear": 1, "accelerator_pedal_position": 0.2652901433970356, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.409780811348606, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.4690433} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.869956254959106, "x": 40.760131135677895, "y": 0.6434412442258219, "z": null, "yaw": 3.607323381262955, "pitch": null, "roll": null}, "v": 0.9571571400716431, "accelerator_pedal_position": 0.2652901433970356, "brake_pedal_position": 0.0, "acceleration": 0.15104404131998905, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.24022428353688124, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.4890432} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26423422686764086, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -9.77675029398072, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9629243381070963, "gear": 1, "accelerator_pedal_position": 0.26423422686764086, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.371163342156517, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.4890432} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.869956254959106, "x": 40.760131135677895, "y": 0.6434412442258219, "z": null, "yaw": 3.607323381262955, "pitch": null, "roll": null}, "v": 0.9571571400716431, "accelerator_pedal_position": 0.2652901433970356, "brake_pedal_position": 0.0, "acceleration": 0.15104404131998905, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.24022428353688124, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.5090432} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26423422686764086, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -9.77675029398072, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9643647927891784, "gear": 1, "accelerator_pedal_position": 0.26423422686764086, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.371163342156517, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.5090432} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.869956254959106, "x": 40.760131135677895, "y": 0.6434412442258219, "z": null, "yaw": 3.607323381262955, "pitch": null, "roll": null}, "v": 0.9571571400716431, "accelerator_pedal_position": 0.2652901433970356, "brake_pedal_position": 0.0, "acceleration": 0.15104404131998905, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.24022428353688124, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.5290432} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26423422686764086, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -9.77675029398072, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9701166358416422, "gear": 1, "accelerator_pedal_position": 0.26423422686764086, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.371163342156517, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.5290432} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.869956254959106, "x": 40.760131135677895, "y": 0.6434412442258219, "z": null, "yaw": 3.607323381262955, "pitch": null, "roll": null}, "v": 0.9571571400716431, "accelerator_pedal_position": 0.2652901433970356, "brake_pedal_position": 0.0, "acceleration": 0.15104404131998905, "steering_wheel_angle": -10.409780811348606, "front_wheel_angle": -0.5710852513260594, "heading_rate": -0.24022428353688124, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.5490432} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26423422686764086, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -9.77675029398072, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9715521040742353, "gear": 1, "accelerator_pedal_position": 0.26423422686764086, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.371163342156517, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.5490432} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502684.5690432, "x": 44.664761838447504, "y": 5.596996580001491, "z": null, "yaw": 3.5798462131568063, "pitch": null, "roll": null}, "v": 0.9729865758523326, "accelerator_pedal_position": 0.26423422686764086, "brake_pedal_position": 0.0, "acceleration": 0.14334756036225021, "steering_wheel_angle": -10.371163342156517, "front_wheel_angle": -0.5684577577200296, "heading_rate": -0.24278859556149876, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.5690432} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2686552064778588, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -9.301026046312987, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9729865758523326, "gear": 1, "accelerator_pedal_position": 0.26423422686764086, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.371163342156517, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.5690432} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.97995615005493, "x": 40.664761838447504, "y": 0.5969965800014911, "z": null, "yaw": 3.5798462131568063, "pitch": null, "roll": null}, "v": 0.9729865758523326, "accelerator_pedal_position": 0.26423422686764086, "brake_pedal_position": 0.0, "acceleration": 0.14334756036225021, "steering_wheel_angle": -10.371163342156517, "front_wheel_angle": -0.5684577577200296, "heading_rate": -0.24278859556149876, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.5890431} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26732849961225996, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -9.301026046312987, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9812750488766923, "gear": 1, "accelerator_pedal_position": 0.26732849961225996, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.181589577548653, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.5890431} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.97995615005493, "x": 40.664761838447504, "y": 0.5969965800014911, "z": null, "yaw": 3.5798462131568063, "pitch": null, "roll": null}, "v": 0.9729865758523326, "accelerator_pedal_position": 0.26423422686764086, "brake_pedal_position": 0.0, "acceleration": 0.14334756036225021, "steering_wheel_angle": -10.371163342156517, "front_wheel_angle": -0.5684577577200296, "heading_rate": -0.24278859556149876, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.619043} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26732849961225996, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -9.301026046312987, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9828961525058654, "gear": 1, "accelerator_pedal_position": 0.26732849961225996, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.143430039129338, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.619043} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.97995615005493, "x": 40.664761838447504, "y": 0.5969965800014911, "z": null, "yaw": 3.5798462131568063, "pitch": null, "roll": null}, "v": 0.9729865758523326, "accelerator_pedal_position": 0.26423422686764086, "brake_pedal_position": 0.0, "acceleration": 0.14334756036225021, "steering_wheel_angle": -10.371163342156517, "front_wheel_angle": -0.5684577577200296, "heading_rate": -0.24278859556149876, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.639043} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26732849961225996, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -9.301026046312987, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.987752690653109, "gear": 1, "accelerator_pedal_position": 0.26732849961225996, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.028461852875921, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.639043} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 45.97995615005493, "x": 40.664761838447504, "y": 0.5969965800014911, "z": null, "yaw": 3.5798462131568063, "pitch": null, "roll": null}, "v": 0.9729865758523326, "accelerator_pedal_position": 0.26423422686764086, "brake_pedal_position": 0.0, "acceleration": 0.14334756036225021, "steering_wheel_angle": -10.371163342156517, "front_wheel_angle": -0.5684577577200296, "heading_rate": -0.24278859556149876, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.659043} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26732849961225996, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -9.301026046312987, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.987752690653109, "gear": 1, "accelerator_pedal_position": 0.26732849961225996, "brake_pedal_position": 0.0, "steering_wheel_angle": -10.028461852875921, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.659043} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502684.679043, "x": 44.5664719893891, "y": 5.552400128904712, "z": null, "yaw": 3.553164642202006, "pitch": null, "roll": null}, "v": 0.9909847414243078, "accelerator_pedal_position": 0.26732849961225996, "brake_pedal_position": 0.0, "acceleration": 0.16143337792805124, "steering_wheel_angle": -9.951408419544075, "front_wheel_angle": -0.5402652346207498, "heading_rate": -0.23218084149383345, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.689043} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27132067500720286, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.82670596325937, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9925990752035884, "gear": 1, "accelerator_pedal_position": 0.26732849961225996, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.91275931012928, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.689043} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.08995604515076, "x": 40.5664719893891, "y": 0.5524001289047122, "z": null, "yaw": 3.553164642202006, "pitch": null, "roll": null}, "v": 0.9909847414243078, "accelerator_pedal_position": 0.26732849961225996, "brake_pedal_position": 0.0, "acceleration": 0.16143337792805124, "steering_wheel_angle": -9.951408419544075, "front_wheel_angle": -0.5402652346207498, "heading_rate": -0.23218084149383345, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.709043} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27013578877381467, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.82670596325937, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9963232084275102, "gear": 1, "accelerator_pedal_position": 0.27132067500720286, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.837030284061488, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.709043} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.08995604515076, "x": 40.5664719893891, "y": 0.5524001289047122, "z": null, "yaw": 3.553164642202006, "pitch": null, "roll": null}, "v": 0.9909847414243078, "accelerator_pedal_position": 0.26732849961225996, "brake_pedal_position": 0.0, "acceleration": 0.16143337792805124, "steering_wheel_angle": -9.951408419544075, "front_wheel_angle": -0.5402652346207498, "heading_rate": -0.23218084149383345, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.729043} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27013578877381467, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.82670596325937, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9998940775816316, "gear": 1, "accelerator_pedal_position": 0.27013578877381467, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.760989938301302, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.729043} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.08995604515076, "x": 40.5664719893891, "y": 0.5524001289047122, "z": null, "yaw": 3.553164642202006, "pitch": null, "roll": null}, "v": 0.9909847414243078, "accelerator_pedal_position": 0.26732849961225996, "brake_pedal_position": 0.0, "acceleration": 0.16143337792805124, "steering_wheel_angle": -9.951408419544075, "front_wheel_angle": -0.5402652346207498, "heading_rate": -0.23218084149383345, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.749043} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27013578877381467, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.82670596325937, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0034599506945152, "gear": 1, "accelerator_pedal_position": 0.27013578877381467, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.684638272848728, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.749043} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.08995604515076, "x": 40.5664719893891, "y": 0.5524001289047122, "z": null, "yaw": 3.553164642202006, "pitch": null, "roll": null}, "v": 0.9909847414243078, "accelerator_pedal_position": 0.26732849961225996, "brake_pedal_position": 0.0, "acceleration": 0.16143337792805124, "steering_wheel_angle": -9.951408419544075, "front_wheel_angle": -0.5402652346207498, "heading_rate": -0.23218084149383345, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.769043} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27013578877381467, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.82670596325937, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0070208296717758, "gear": 1, "accelerator_pedal_position": 0.27013578877381467, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.607975287703761, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.769043} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502684.789043, "x": 44.465171754817135, "y": 5.509569202683146, "z": null, "yaw": 3.528119265893799, "pitch": null, "roll": null}, "v": 1.0105767164377166, "accelerator_pedal_position": 0.27013578877381467, "brake_pedal_position": 0.0, "acceleration": 0.17760719101639544, "steering_wheel_angle": -9.531000982866397, "front_wheel_angle": -0.5126710390551783, "heading_rate": -0.22219689642905405, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.789043} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2782128005169336, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.410993061939616, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0105767164377166, "gear": 1, "accelerator_pedal_position": 0.27013578877381467, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.531000982866397, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.789043} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.19995594024658, "x": 40.465171754817135, "y": 0.5095692026831458, "z": null, "yaw": 3.528119265893799, "pitch": null, "roll": null}, "v": 1.0105767164377166, "accelerator_pedal_position": 0.27013578877381467, "brake_pedal_position": 0.0, "acceleration": 0.17760719101639544, "steering_wheel_angle": -9.531000982866397, "front_wheel_angle": -0.5126710390551783, "heading_rate": -0.22219689642905405, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.809043} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2757573199458391, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.410993061939616, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0151368847612348, "gear": 1, "accelerator_pedal_position": 0.2782128005169336, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.455235348116336, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.809043} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.19995594024658, "x": 40.465171754817135, "y": 0.5095692026831458, "z": null, "yaw": 3.528119265893799, "pitch": null, "roll": null}, "v": 1.0105767164377166, "accelerator_pedal_position": 0.27013578877381467, "brake_pedal_position": 0.0, "acceleration": 0.17760719101639544, "steering_wheel_angle": -9.531000982866397, "front_wheel_angle": -0.5126710390551783, "heading_rate": -0.22219689642905405, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.829043} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2757573199458391, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.410993061939616, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0193838184590833, "gear": 1, "accelerator_pedal_position": 0.2757573199458391, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.379170495155188, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.829043} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.19995594024658, "x": 40.465171754817135, "y": 0.5095692026831458, "z": null, "yaw": 3.528119265893799, "pitch": null, "roll": null}, "v": 1.0105767164377166, "accelerator_pedal_position": 0.27013578877381467, "brake_pedal_position": 0.0, "acceleration": 0.17760719101639544, "steering_wheel_angle": -9.531000982866397, "front_wheel_angle": -0.5126710390551783, "heading_rate": -0.22219689642905405, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.849043} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2757573199458391, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.410993061939616, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0236247774281586, "gear": 1, "accelerator_pedal_position": 0.2757573199458391, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.302806423982954, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.849043} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.19995594024658, "x": 40.465171754817135, "y": 0.5095692026831458, "z": null, "yaw": 3.528119265893799, "pitch": null, "roll": null}, "v": 1.0105767164377166, "accelerator_pedal_position": 0.27013578877381467, "brake_pedal_position": 0.0, "acceleration": 0.17760719101639544, "steering_wheel_angle": -9.531000982866397, "front_wheel_angle": -0.5126710390551783, "heading_rate": -0.22219689642905405, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.8690429} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2757573199458391, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.410993061939616, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0278597628821493, "gear": 1, "accelerator_pedal_position": 0.2757573199458391, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.226143134599633, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.8690429} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.19995594024658, "x": 40.465171754817135, "y": 0.5095692026831458, "z": null, "yaw": 3.528119265893799, "pitch": null, "roll": null}, "v": 1.0105767164377166, "accelerator_pedal_position": 0.27013578877381467, "brake_pedal_position": 0.0, "acceleration": 0.17760719101639544, "steering_wheel_angle": -9.531000982866397, "front_wheel_angle": -0.5126710390551783, "heading_rate": -0.22219689642905405, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.8890429} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2757573199458391, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -8.410993061939616, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0320887760634152, "gear": 1, "accelerator_pedal_position": 0.2757573199458391, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.149180627005226, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.8890429} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502684.8990428, "x": 44.36065005336615, "y": 5.468345031478225, "z": null, "yaw": 3.5046211102439786, "pitch": null, "roll": null}, "v": 1.0342010434478308, "accelerator_pedal_position": 0.2757573199458391, "brake_pedal_position": 0.0, "acceleration": 0.21107747950641675, "steering_wheel_angle": -9.110587166378867, "front_wheel_angle": -0.48567713217275116, "heading_rate": -0.21324262001767078, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.9090428} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2771148709558317, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.9817977494742465, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.036311818242895, "gear": 1, "accelerator_pedal_position": 0.2757573199458391, "brake_pedal_position": 0.0, "steering_wheel_angle": -9.071918901199734, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.9090428} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.30995583534241, "x": 40.36065005336615, "y": 0.4683450314782247, "z": null, "yaw": 3.5046211102439786, "pitch": null, "roll": null}, "v": 1.0342010434478308, "accelerator_pedal_position": 0.2757573199458391, "brake_pedal_position": 0.0, "acceleration": 0.21107747950641675, "steering_wheel_angle": -9.110587166378867, "front_wheel_angle": -0.48567713217275116, "heading_rate": -0.21324262001767078, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.9290428} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27677385010837485, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.9817977494742465, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0406985245507048, "gear": 1, "accelerator_pedal_position": 0.2771148709558317, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.995871830953616, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.9290428} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.30995583534241, "x": 40.36065005336615, "y": 0.4683450314782247, "z": null, "yaw": 3.5046211102439786, "pitch": null, "roll": null}, "v": 1.0342010434478308, "accelerator_pedal_position": 0.2757573199458391, "brake_pedal_position": 0.0, "acceleration": 0.21107747950641675, "steering_wheel_angle": -9.110587166378867, "front_wheel_angle": -0.48567713217275116, "heading_rate": -0.21324262001767078, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.9490428} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27677385010837485, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.9817977494742465, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.045036409676609, "gear": 1, "accelerator_pedal_position": 0.27677385010837485, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.919537087467353, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.9490428} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.30995583534241, "x": 40.36065005336615, "y": 0.4683450314782247, "z": null, "yaw": 3.5046211102439786, "pitch": null, "roll": null}, "v": 1.0342010434478308, "accelerator_pedal_position": 0.2757573199458391, "brake_pedal_position": 0.0, "acceleration": 0.21107747950641675, "steering_wheel_angle": -9.110587166378867, "front_wheel_angle": -0.48567713217275116, "heading_rate": -0.21324262001767078, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.9690428} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27677385010837485, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.9817977494742465, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0493681476799024, "gear": 1, "accelerator_pedal_position": 0.27677385010837485, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.842914670740935, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.9690428} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.30995583534241, "x": 40.36065005336615, "y": 0.4683450314782247, "z": null, "yaw": 3.5046211102439786, "pitch": null, "roll": null}, "v": 1.0342010434478308, "accelerator_pedal_position": 0.2757573199458391, "brake_pedal_position": 0.0, "acceleration": 0.21107747950641675, "steering_wheel_angle": -9.110587166378867, "front_wheel_angle": -0.48567713217275116, "heading_rate": -0.21324262001767078, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502684.9890428} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27677385010837485, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.9817977494742465, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0558542314807853, "gear": 1, "accelerator_pedal_position": 0.27677385010837485, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.72744165832603, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502684.9890428} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502685.0090427, "x": 44.25278184086044, "y": 5.428620407035806, "z": null, "yaw": 3.482597729519573, "pitch": null, "roll": null}, "v": 1.0580131871810048, "accelerator_pedal_position": 0.27677385010837485, "brake_pedal_position": 0.0, "acceleration": 0.21574198477580342, "steering_wheel_angle": -8.68880681756765, "front_wheel_angle": -0.4591613035706175, "heading_rate": -0.20433071109134654, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.0090427} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28294591794006574, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.614240195427049, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0580131871810048, "gear": 1, "accelerator_pedal_position": 0.27677385010837485, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.68880681756765, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.0090427} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.41995573043823, "x": 40.25278184086044, "y": 0.4286204070358064, "z": null, "yaw": 3.482597729519573, "pitch": null, "roll": null}, "v": 1.0580131871810048, "accelerator_pedal_position": 0.27677385010837485, "brake_pedal_position": 0.0, "acceleration": 0.21574198477580342, "steering_wheel_angle": -8.68880681756765, "front_wheel_angle": -0.4591613035706175, "heading_rate": -0.20433071109134654, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.0290427} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2811015859457472, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.614240195427049, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.063097724979321, "gear": 1, "accelerator_pedal_position": 0.28294591794006574, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.612572949810364, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.0290427} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.41995573043823, "x": 40.25278184086044, "y": 0.4286204070358064, "z": null, "yaw": 3.482597729519573, "pitch": null, "roll": null}, "v": 1.0580131871810048, "accelerator_pedal_position": 0.27677385010837485, "brake_pedal_position": 0.0, "acceleration": 0.21574198477580342, "steering_wheel_angle": -8.68880681756765, "front_wheel_angle": -0.4591613035706175, "heading_rate": -0.20433071109134654, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.0490427} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2811015859457472, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.614240195427049, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.067944561964124, "gear": 1, "accelerator_pedal_position": 0.2811015859457472, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.536060610265293, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.0490427} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.41995573043823, "x": 40.25278184086044, "y": 0.4286204070358064, "z": null, "yaw": 3.482597729519573, "pitch": null, "roll": null}, "v": 1.0580131871810048, "accelerator_pedal_position": 0.27677385010837485, "brake_pedal_position": 0.0, "acceleration": 0.21574198477580342, "steering_wheel_angle": -8.68880681756765, "front_wheel_angle": -0.4591613035706175, "heading_rate": -0.20433071109134654, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.0690427} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2811015859457472, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.614240195427049, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.072784486467059, "gear": 1, "accelerator_pedal_position": 0.2811015859457472, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.459269798932434, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.0690427} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.41995573043823, "x": 40.25278184086044, "y": 0.4286204070358064, "z": null, "yaw": 3.482597729519573, "pitch": null, "roll": null}, "v": 1.0580131871810048, "accelerator_pedal_position": 0.27677385010837485, "brake_pedal_position": 0.0, "acceleration": 0.21574198477580342, "steering_wheel_angle": -8.68880681756765, "front_wheel_angle": -0.4591613035706175, "heading_rate": -0.20433071109134654, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.0890427} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2811015859457472, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.614240195427049, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.080031413404704, "gear": 1, "accelerator_pedal_position": 0.2811015859457472, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.343561447331052, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.0890427} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.41995573043823, "x": 40.25278184086044, "y": 0.4286204070358064, "z": null, "yaw": 3.482597729519573, "pitch": null, "roll": null}, "v": 1.0580131871810048, "accelerator_pedal_position": 0.27677385010837485, "brake_pedal_position": 0.0, "acceleration": 0.21574198477580342, "steering_wheel_angle": -8.68880681756765, "front_wheel_angle": -0.4591613035706175, "heading_rate": -0.20433071109134654, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.1090426} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2811015859457472, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.614240195427049, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0824436000342168, "gear": 1, "accelerator_pedal_position": 0.2811015859457472, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.304852760903366, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.1090426} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502685.1190426, "x": 44.14145726768009, "y": 5.390305087190741, "z": null, "yaw": 3.4619816491805318, "pitch": null, "roll": null}, "v": 1.0848540589410833, "accelerator_pedal_position": 0.2811015859457472, "brake_pedal_position": 0.0, "acceleration": 0.24087312592185628, "steering_wheel_angle": -8.266074456528733, "front_wheel_angle": -0.4331200230505782, "heading_rate": -0.19595291477671403, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.1290426} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29049551321383205, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.3043535596325615, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0872627902003018, "gear": 1, "accelerator_pedal_position": 0.2811015859457472, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.266074456528733, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.1290426} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.52995562553406, "x": 40.14145726768009, "y": 0.3903050871907414, "z": null, "yaw": 3.4619816491805318, "pitch": null, "roll": null}, "v": 1.0848540589410833, "accelerator_pedal_position": 0.2811015859457472, "brake_pedal_position": 0.0, "acceleration": 0.24087312592185628, "steering_wheel_angle": -8.266074456528733, "front_wheel_angle": -0.4331200230505782, "heading_rate": -0.19595291477671403, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.1490426} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28765576947255067, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.3043535596325615, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.093248889448336, "gear": 1, "accelerator_pedal_position": 0.29049551321383205, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.189338622966012, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.1490426} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.52995562553406, "x": 40.14145726768009, "y": 0.3903050871907414, "z": null, "yaw": 3.4619816491805318, "pitch": null, "roll": null}, "v": 1.0848540589410833, "accelerator_pedal_position": 0.2811015859457472, "brake_pedal_position": 0.0, "acceleration": 0.24087312592185628, "steering_wheel_angle": -8.266074456528733, "front_wheel_angle": -0.4331200230505782, "heading_rate": -0.19595291477671403, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.1690426} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28765576947255067, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.3043535596325615, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0988715512363398, "gear": 1, "accelerator_pedal_position": 0.28765576947255067, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.112331630000702, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.1690426} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.52995562553406, "x": 40.14145726768009, "y": 0.3903050871907414, "z": null, "yaw": 3.4619816491805318, "pitch": null, "roll": null}, "v": 1.0848540589410833, "accelerator_pedal_position": 0.2811015859457472, "brake_pedal_position": 0.0, "acceleration": 0.24087312592185628, "steering_wheel_angle": -8.266074456528733, "front_wheel_angle": -0.4331200230505782, "heading_rate": -0.19595291477671403, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.1890426} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28765576947255067, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.3043535596325615, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1044861250025768, "gear": 1, "accelerator_pedal_position": 0.28765576947255067, "brake_pedal_position": 0.0, "steering_wheel_angle": -8.035053477632797, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.1890426} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.52995562553406, "x": 40.14145726768009, "y": 0.3903050871907414, "z": null, "yaw": 3.4619816491805318, "pitch": null, "roll": null}, "v": 1.0848540589410833, "accelerator_pedal_position": 0.2811015859457472, "brake_pedal_position": 0.0, "acceleration": 0.24087312592185628, "steering_wheel_angle": -8.266074456528733, "front_wheel_angle": -0.4331200230505782, "heading_rate": -0.19595291477671403, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.2090425} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28765576947255067, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -7.3043535596325615, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1100926097765782, "gear": 1, "accelerator_pedal_position": 0.28765576947255067, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.957504165862302, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.2090425} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502685.2290425, "x": 44.026403470505485, "y": 5.3532683792340015, "z": null, "yaw": 3.44259700300547, "pitch": null, "roll": null}, "v": 1.1156910046437314, "accelerator_pedal_position": 0.28765576947255067, "brake_pedal_position": 0.0, "acceleration": 0.2796163447928257, "steering_wheel_angle": -7.957504165862302, "front_wheel_angle": -0.41443122503044966, "heading_rate": -0.1917200405207992, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.2290425} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2704480578130077, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.822778657872993, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1174116861129382, "gear": 1, "accelerator_pedal_position": 0.2704480578130077, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.9193982242212515, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.2290425} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.63995552062988, "x": 40.026403470505485, "y": 0.35326837923400145, "z": null, "yaw": 3.44259700300547, "pitch": null, "roll": null}, "v": 1.1156910046437314, "accelerator_pedal_position": 0.28765576947255067, "brake_pedal_position": 0.0, "acceleration": 0.2796163447928257, "steering_wheel_angle": -7.957504165862302, "front_wheel_angle": -0.41443122503044966, "heading_rate": -0.1917200405207992, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.2490425} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2759364927136908, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.822778657872993, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1191311229955685, "gear": 1, "accelerator_pedal_position": 0.2704480578130077, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.881227150595931, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.2490425} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.63995552062988, "x": 40.026403470505485, "y": 0.35326837923400145, "z": null, "yaw": 3.44259700300547, "pitch": null, "roll": null}, "v": 1.1156910046437314, "accelerator_pedal_position": 0.28765576947255067, "brake_pedal_position": 0.0, "acceleration": 0.2796163447928257, "steering_wheel_angle": -7.957504165862302, "front_wheel_angle": -0.41443122503044966, "heading_rate": -0.1917200405207992, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.2690425} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2759364927136908, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.822778657872993, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1232520701778943, "gear": 1, "accelerator_pedal_position": 0.2759364927136908, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.8046896073924925, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.2690425} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.63995552062988, "x": 40.026403470505485, "y": 0.35326837923400145, "z": null, "yaw": 3.44259700300547, "pitch": null, "roll": null}, "v": 1.1156910046437314, "accelerator_pedal_position": 0.28765576947255067, "brake_pedal_position": 0.0, "acceleration": 0.2796163447928257, "steering_wheel_angle": -7.957504165862302, "front_wheel_angle": -0.41443122503044966, "heading_rate": -0.1917200405207992, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.2890425} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2759364927136908, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.822778657872993, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.12942230035363, "gear": 1, "accelerator_pedal_position": 0.2759364927136908, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.689394802705322, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.2890425} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.63995552062988, "x": 40.026403470505485, "y": 0.35326837923400145, "z": null, "yaw": 3.44259700300547, "pitch": null, "roll": null}, "v": 1.1156910046437314, "accelerator_pedal_position": 0.28765576947255067, "brake_pedal_position": 0.0, "acceleration": 0.2796163447928257, "steering_wheel_angle": -7.957504165862302, "front_wheel_angle": -0.41443122503044966, "heading_rate": -0.1917200405207992, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.3090425} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2759364927136908, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.822778657872993, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.131476060524805, "gear": 1, "accelerator_pedal_position": 0.2759364927136908, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.650832937174396, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.3090425} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.63995552062988, "x": 40.026403470505485, "y": 0.35326837923400145, "z": null, "yaw": 3.44259700300547, "pitch": null, "roll": null}, "v": 1.1156910046437314, "accelerator_pedal_position": 0.28765576947255067, "brake_pedal_position": 0.0, "acceleration": 0.2796163447928257, "steering_wheel_angle": -7.957504165862302, "front_wheel_angle": -0.41443122503044966, "heading_rate": -0.1917200405207992, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.3290424} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2759364927136908, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.822778657872993, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1376283947140282, "gear": 1, "accelerator_pedal_position": 0.2759364927136908, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.534756548676011, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.3290424} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502685.3390424, "x": 43.907871013459676, "y": 5.317568411388685, "z": null, "yaw": 3.4242777437042498, "pitch": null, "roll": null}, "v": 1.1376283947140282, "accelerator_pedal_position": 0.2759364927136908, "brake_pedal_position": 0.0, "acceleration": 0.20477967608026987, "steering_wheel_angle": -7.534756548676011, "front_wheel_angle": -0.3892429234391417, "heading_rate": -0.18227392918904345, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.3490424} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2859731940747825, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.5652521653864255, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.139676191474831, "gear": 1, "accelerator_pedal_position": 0.2759364927136908, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.4959341552080145, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.3490424} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.74995541572571, "x": 39.907871013459676, "y": 0.3175684113886854, "z": null, "yaw": 3.4242777437042498, "pitch": null, "roll": null}, "v": 1.1376283947140282, "accelerator_pedal_position": 0.2759364927136908, "brake_pedal_position": 0.0, "acceleration": 0.20477967608026987, "steering_wheel_angle": -7.534756548676011, "front_wheel_angle": -0.3892429234391417, "heading_rate": -0.18227392918904345, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.3690424} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2829162823436579, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.5652521653864255, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1450214452556982, "gear": 1, "accelerator_pedal_position": 0.2859731940747825, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.418898710458267, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.3690424} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.74995541572571, "x": 39.907871013459676, "y": 0.3175684113886854, "z": null, "yaw": 3.4242777437042498, "pitch": null, "roll": null}, "v": 1.1376283947140282, "accelerator_pedal_position": 0.2759364927136908, "brake_pedal_position": 0.0, "acceleration": 0.20477967608026987, "steering_wheel_angle": -7.534756548676011, "front_wheel_angle": -0.3892429234391417, "heading_rate": -0.18227392918904345, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.3890424} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2829162823436579, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.5652521653864255, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1499769367208843, "gear": 1, "accelerator_pedal_position": 0.2829162823436579, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.341608087962784, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.3890424} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.74995541572571, "x": 39.907871013459676, "y": 0.3175684113886854, "z": null, "yaw": 3.4242777437042498, "pitch": null, "roll": null}, "v": 1.1376283947140282, "accelerator_pedal_position": 0.2759364927136908, "brake_pedal_position": 0.0, "acceleration": 0.20477967608026987, "steering_wheel_angle": -7.534756548676011, "front_wheel_angle": -0.3892429234391417, "heading_rate": -0.18227392918904345, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.4090424} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2829162823436579, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.5652521653864255, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1549251983097872, "gear": 1, "accelerator_pedal_position": 0.2829162823436579, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.26406228772156, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.4090424} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.74995541572571, "x": 39.907871013459676, "y": 0.3175684113886854, "z": null, "yaw": 3.4242777437042498, "pitch": null, "roll": null}, "v": 1.1376283947140282, "accelerator_pedal_position": 0.2759364927136908, "brake_pedal_position": 0.0, "acceleration": 0.20477967608026987, "steering_wheel_angle": -7.534756548676011, "front_wheel_angle": -0.3892429234391417, "heading_rate": -0.18227392918904345, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.4290423} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2829162823436579, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.5652521653864255, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1598662307799854, "gear": 1, "accelerator_pedal_position": 0.2829162823436579, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.225193695946298, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.4290423} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502685.4490423, "x": 43.78612703487878, "y": 5.283245571395417, "z": null, "yaw": 3.4071889501576296, "pitch": null, "roll": null}, "v": 1.164800034930846, "accelerator_pedal_position": 0.2829162823436579, "brake_pedal_position": 0.0, "acceleration": 0.24641917168757044, "steering_wheel_angle": -7.225193695946298, "front_wheel_angle": -0.3710895970333793, "heading_rate": -0.17704833393863953, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.4490423} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2767092152793372, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.215599166949639, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.164800034930846, "gear": 1, "accelerator_pedal_position": 0.2829162823436579, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.225193695946298, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.4490423} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.85995531082153, "x": 39.78612703487878, "y": 0.2832455713954172, "z": null, "yaw": 3.4071889501576296, "pitch": null, "roll": null}, "v": 1.164800034930846, "accelerator_pedal_position": 0.2829162823436579, "brake_pedal_position": 0.0, "acceleration": 0.24641917168757044, "steering_wheel_angle": -7.225193695946298, "front_wheel_angle": -0.3710895970333793, "heading_rate": -0.17704833393863953, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.4690423} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27874813455275677, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.215599166949639, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.168951012742243, "gear": 1, "accelerator_pedal_position": 0.2767092152793372, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.148331062243454, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.4690423} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.85995531082153, "x": 39.78612703487878, "y": 0.2832455713954172, "z": null, "yaw": 3.4071889501576296, "pitch": null, "roll": null}, "v": 1.164800034930846, "accelerator_pedal_position": 0.2829162823436579, "brake_pedal_position": 0.0, "acceleration": 0.24641917168757044, "steering_wheel_angle": -7.225193695946298, "front_wheel_angle": -0.3710895970333793, "heading_rate": -0.17704833393863953, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.4890423} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27874813455275677, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.215599166949639, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.175548081855641, "gear": 1, "accelerator_pedal_position": 0.27874813455275677, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.032571632109456, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.4890423} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27874813455275677, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.215599166949639, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.175548081855641, "gear": 1, "accelerator_pedal_position": 0.27874813455275677, "brake_pedal_position": 0.0, "steering_wheel_angle": -7.032571632109456, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.4990423} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.85995531082153, "x": 39.78612703487878, "y": 0.2832455713954172, "z": null, "yaw": 3.4071889501576296, "pitch": null, "roll": null}, "v": 1.164800034930846, "accelerator_pedal_position": 0.2829162823436579, "brake_pedal_position": 0.0, "acceleration": 0.24641917168757044, "steering_wheel_angle": -7.225193695946298, "front_wheel_angle": -0.3710895970333793, "heading_rate": -0.17704833393863953, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.5290422} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27874813455275677, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -6.215599166949639, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1886986251410934, "gear": 1, "accelerator_pedal_position": 0.27874813455275677, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.916253626479781, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.5290422} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502685.5590422, "x": 43.66109905293996, "y": 5.250237230844888, "z": null, "yaw": 3.3909890077633515, "pitch": null, "roll": null}, "v": 1.1886986251410934, "accelerator_pedal_position": 0.27874813455275677, "brake_pedal_position": 0.0, "acceleration": 0.2186108654835518, "steering_wheel_angle": -6.916253626479781, "front_wheel_angle": -0.353207488892234, "heading_rate": -0.17118543691744184, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.5590422} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28276357815562997, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.957818775607447, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1886986251410934, "gear": 1, "accelerator_pedal_position": 0.27874813455275677, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.916253626479781, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.5590422} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.96995520591736, "x": 39.66109905293996, "y": 0.25023723084488836, "z": null, "yaw": 3.3909890077633515, "pitch": null, "roll": null}, "v": 1.1886986251410934, "accelerator_pedal_position": 0.27874813455275677, "brake_pedal_position": 0.0, "acceleration": 0.2186108654835518, "steering_wheel_angle": -6.916253626479781, "front_wheel_angle": -0.353207488892234, "heading_rate": -0.17118543691744184, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.5890422} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2815966203901593, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.957818775607447, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1960044513614243, "gear": 1, "accelerator_pedal_position": 0.28276357815562997, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.80053121160279, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.5890422} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.96995520591736, "x": 39.66109905293996, "y": 0.25023723084488836, "z": null, "yaw": 3.3909890077633515, "pitch": null, "roll": null}, "v": 1.1886986251410934, "accelerator_pedal_position": 0.27874813455275677, "brake_pedal_position": 0.0, "acceleration": 0.2186108654835518, "steering_wheel_angle": -6.916253626479781, "front_wheel_angle": -0.353207488892234, "heading_rate": -0.17118543691744184, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.6090422} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2815966203901593, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.957818775607447, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2007201949873512, "gear": 1, "accelerator_pedal_position": 0.2815966203901593, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.7230786995800775, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.6090422} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.96995520591736, "x": 39.66109905293996, "y": 0.25023723084488836, "z": null, "yaw": 3.3909890077633515, "pitch": null, "roll": null}, "v": 1.1886986251410934, "accelerator_pedal_position": 0.27874813455275677, "brake_pedal_position": 0.0, "acceleration": 0.2186108654835518, "steering_wheel_angle": -6.916253626479781, "front_wheel_angle": -0.353207488892234, "heading_rate": -0.17118543691744184, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.6290421} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2815966203901593, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.957818775607447, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.205428962760556, "gear": 1, "accelerator_pedal_position": 0.2815966203901593, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.6453827992069225, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.6290421} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 46.96995520591736, "x": 39.66109905293996, "y": 0.25023723084488836, "z": null, "yaw": 3.3909890077633515, "pitch": null, "roll": null}, "v": 1.1886986251410934, "accelerator_pedal_position": 0.27874813455275677, "brake_pedal_position": 0.0, "acceleration": 0.2186108654835518, "steering_wheel_angle": -6.916253626479781, "front_wheel_angle": -0.353207488892234, "heading_rate": -0.17118543691744184, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.6490421} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2815966203901593, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.957818775607447, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.210130756134487, "gear": 1, "accelerator_pedal_position": 0.2815966203901593, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.6453827992069225, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.6490421} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502685.669042, "x": 43.53288483600638, "y": 5.21854679410644, "z": null, "yaw": 3.3756267670446873, "pitch": null, "roll": null}, "v": 1.2148255765998208, "accelerator_pedal_position": 0.2815966203901593, "brake_pedal_position": 0.0, "acceleration": 0.23447958679289377, "steering_wheel_angle": -6.6453827992069225, "front_wheel_angle": -0.3377147934741458, "heading_rate": -0.16664360185416469, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.669042} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27576684138675606, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.623664404224915, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2148255765998208, "gear": 1, "accelerator_pedal_position": 0.2815966203901593, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.6453827992069225, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.669042} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.079955101013184, "x": 39.53288483600638, "y": 0.21854679410644007, "z": null, "yaw": 3.3756267670446873, "pitch": null, "roll": null}, "v": 1.2148255765998208, "accelerator_pedal_position": 0.2815966203901593, "brake_pedal_position": 0.0, "acceleration": 0.23447958679289377, "steering_wheel_angle": -6.6453827992069225, "front_wheel_angle": -0.3377147934741458, "heading_rate": -0.16664360185416469, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.689042} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2776853643419224, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.623664404224915, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2187849741741605, "gear": 1, "accelerator_pedal_position": 0.27576684138675606, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.568416950840269, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.689042} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.079955101013184, "x": 39.53288483600638, "y": 0.21854679410644007, "z": null, "yaw": 3.3756267670446873, "pitch": null, "roll": null}, "v": 1.2148255765998208, "accelerator_pedal_position": 0.2815966203901593, "brake_pedal_position": 0.0, "acceleration": 0.23447958679289377, "steering_wheel_angle": -6.6453827992069225, "front_wheel_angle": -0.3377147934741458, "heading_rate": -0.16664360185416469, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.709042} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2776853643419224, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.623664404224915, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.22297821198491, "gear": 1, "accelerator_pedal_position": 0.2776853643419224, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.491213746620616, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.709042} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.079955101013184, "x": 39.53288483600638, "y": 0.21854679410644007, "z": null, "yaw": 3.3756267670446873, "pitch": null, "roll": null}, "v": 1.2148255765998208, "accelerator_pedal_position": 0.2815966203901593, "brake_pedal_position": 0.0, "acceleration": 0.23447958679289377, "steering_wheel_angle": -6.6453827992069225, "front_wheel_angle": -0.3377147934741458, "heading_rate": -0.16664360185416469, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.729042} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2776853643419224, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.623664404224915, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2271652093449514, "gear": 1, "accelerator_pedal_position": 0.2776853643419224, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.413773186547961, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.729042} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.079955101013184, "x": 39.53288483600638, "y": 0.21854679410644007, "z": null, "yaw": 3.3756267670446873, "pitch": null, "roll": null}, "v": 1.2148255765998208, "accelerator_pedal_position": 0.2815966203901593, "brake_pedal_position": 0.0, "acceleration": 0.23447958679289377, "steering_wheel_angle": -6.6453827992069225, "front_wheel_angle": -0.3377147934741458, "heading_rate": -0.16664360185416469, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.749042} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2776853643419224, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.623664404224915, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2313459685316672, "gear": 1, "accelerator_pedal_position": 0.2776853643419224, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.336095270622307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.749042} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.079955101013184, "x": 39.53288483600638, "y": 0.21854679410644007, "z": null, "yaw": 3.3756267670446873, "pitch": null, "roll": null}, "v": 1.2148255765998208, "accelerator_pedal_position": 0.2815966203901593, "brake_pedal_position": 0.0, "acceleration": 0.23447958679289377, "steering_wheel_angle": -6.6453827992069225, "front_wheel_angle": -0.3377147934741458, "heading_rate": -0.16664360185416469, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.769042} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2776853643419224, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.623664404224915, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2355204918503688, "gear": 1, "accelerator_pedal_position": 0.2776853643419224, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.336095270622307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.769042} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502685.779042, "x": 43.401591398822156, "y": 5.188179652273459, "z": null, "yaw": 3.3610338369876334, "pitch": null, "roll": null}, "v": 1.2376054157872356, "accelerator_pedal_position": 0.2776853643419224, "brake_pedal_position": 0.0, "acceleration": 0.20833658469579436, "steering_wheel_angle": -6.336095270622307, "front_wheel_angle": -0.3202296577020209, "heading_rate": -0.16032999438487666, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.789042} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28615756539832476, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.432434710000177, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2396887816341935, "gear": 1, "accelerator_pedal_position": 0.2776853643419224, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.336095270622307, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.789042} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.18995499610901, "x": 39.401591398822156, "y": 0.18817965227345912, "z": null, "yaw": 3.3610338369876334, "pitch": null, "roll": null}, "v": 1.2376054157872356, "accelerator_pedal_position": 0.2776853643419224, "brake_pedal_position": 0.0, "acceleration": 0.20833658469579436, "steering_wheel_angle": -6.336095270622307, "front_wheel_angle": -0.3202296577020209, "heading_rate": -0.16032999438487666, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.809042} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2835948834777548, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.432434710000177, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2449094690851035, "gear": 1, "accelerator_pedal_position": 0.28615756539832476, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.258727599755026, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.809042} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.18995499610901, "x": 39.401591398822156, "y": 0.18817965227345912, "z": null, "yaw": 3.3610338369876334, "pitch": null, "roll": null}, "v": 1.2376054157872356, "accelerator_pedal_position": 0.2776853643419224, "brake_pedal_position": 0.0, "acceleration": 0.20833658469579436, "steering_wheel_angle": -6.336095270622307, "front_wheel_angle": -0.3202296577020209, "heading_rate": -0.16032999438487666, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.829042} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2835948834777548, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.432434710000177, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2498021265920056, "gear": 1, "accelerator_pedal_position": 0.2835948834777548, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.181125892656704, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.829042} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.18995499610901, "x": 39.401591398822156, "y": 0.18817965227345912, "z": null, "yaw": 3.3610338369876334, "pitch": null, "roll": null}, "v": 1.2376054157872356, "accelerator_pedal_position": 0.2776853643419224, "brake_pedal_position": 0.0, "acceleration": 0.20833658469579436, "steering_wheel_angle": -6.336095270622307, "front_wheel_angle": -0.3202296577020209, "heading_rate": -0.16032999438487666, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.849042} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2835948834777548, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.432434710000177, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2546874506446384, "gear": 1, "accelerator_pedal_position": 0.2835948834777548, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.142237275520903, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.849042} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.18995499610901, "x": 39.401591398822156, "y": 0.18817965227345912, "z": null, "yaw": 3.3610338369876334, "pitch": null, "roll": null}, "v": 1.2376054157872356, "accelerator_pedal_position": 0.2776853643419224, "brake_pedal_position": 0.0, "acceleration": 0.20833658469579436, "steering_wheel_angle": -6.336095270622307, "front_wheel_angle": -0.3202296577020209, "heading_rate": -0.16032999438487666, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.869042} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2835948834777548, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.432434710000177, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2595654426919167, "gear": 1, "accelerator_pedal_position": 0.2835948834777548, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.142237275520903, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.869042} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502685.889042, "x": 43.267227254878364, "y": 5.159114675584272, "z": null, "yaw": 3.3471118171883303, "pitch": null, "roll": null}, "v": 1.2644361042235341, "accelerator_pedal_position": 0.2835948834777548, "brake_pedal_position": 0.0, "acceleration": 0.24325822990815082, "steering_wheel_angle": -6.142237275520903, "front_wheel_angle": -0.3093781370491952, "heading_rate": -0.15787767443738918, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.889042} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27772121487647605, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.108579133697644, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2644361042235341, "gear": 1, "accelerator_pedal_position": 0.2835948834777548, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.142237275520903, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.889042} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.299954891204834, "x": 39.267227254878364, "y": 0.15911467558427184, "z": null, "yaw": 3.3471118171883303, "pitch": null, "roll": null}, "v": 1.2644361042235341, "accelerator_pedal_position": 0.2835948834777548, "brake_pedal_position": 0.0, "acceleration": 0.24325822990815082, "steering_wheel_angle": -6.142237275520903, "front_wheel_angle": -0.3093781370491952, "heading_rate": -0.15787767443738918, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.909042} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27965738005315427, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.108579133697644, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2685655047479174, "gear": 1, "accelerator_pedal_position": 0.27772121487647605, "brake_pedal_position": 0.0, "steering_wheel_angle": -6.0651929571480325, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.909042} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.299954891204834, "x": 39.267227254878364, "y": 0.15911467558427184, "z": null, "yaw": 3.3471118171883303, "pitch": null, "roll": null}, "v": 1.2644361042235341, "accelerator_pedal_position": 0.2835948834777548, "brake_pedal_position": 0.0, "acceleration": 0.24325822990815082, "steering_wheel_angle": -6.142237275520903, "front_wheel_angle": -0.3093781370491952, "heading_rate": -0.15787767443738918, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.9290419} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27965738005315427, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.108579133697644, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2772891398302026, "gear": 1, "accelerator_pedal_position": 0.27965738005315427, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.91041845681227, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.9290419} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.299954891204834, "x": 39.267227254878364, "y": 0.15911467558427184, "z": null, "yaw": 3.3471118171883303, "pitch": null, "roll": null}, "v": 1.2644361042235341, "accelerator_pedal_position": 0.2835948834777548, "brake_pedal_position": 0.0, "acceleration": 0.24325822990815082, "steering_wheel_angle": -6.142237275520903, "front_wheel_angle": -0.3093781370491952, "heading_rate": -0.15787767443738918, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.9490418} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27965738005315427, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.108579133697644, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2816410847370585, "gear": 1, "accelerator_pedal_position": 0.27965738005315427, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.832688274849376, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.9490418} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.299954891204834, "x": 39.267227254878364, "y": 0.15911467558427184, "z": null, "yaw": 3.3471118171883303, "pitch": null, "roll": null}, "v": 1.2644361042235341, "accelerator_pedal_position": 0.2835948834777548, "brake_pedal_position": 0.0, "acceleration": 0.24325822990815082, "steering_wheel_angle": -6.142237275520903, "front_wheel_angle": -0.3093781370491952, "heading_rate": -0.15787767443738918, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502685.9790418} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27965738005315427, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -5.108579133697644, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.292492170810939, "gear": 1, "accelerator_pedal_position": 0.27965738005315427, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.832688274849376, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502685.9790418} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502685.9990418, "x": 43.129742418660214, "y": 5.131332006312061, "z": null, "yaw": 3.333855372020498, "pitch": null, "roll": null}, "v": 1.2881566679417145, "accelerator_pedal_position": 0.27965738005315427, "brake_pedal_position": 0.0, "acceleration": 0.21685731592350144, "steering_wheel_angle": -5.832688274849376, "front_wheel_angle": -0.2922177419406417, "heading_rate": -0.15137331400774878, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.0190418} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2790655043159033, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.8463225634214915, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2946574573776948, "gear": 1, "accelerator_pedal_position": 0.27965738005315427, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.832688274849376, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.0190418} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.40995478630066, "x": 39.129742418660214, "y": 0.13133200631206066, "z": null, "yaw": 3.333855372020498, "pitch": null, "roll": null}, "v": 1.2881566679417145, "accelerator_pedal_position": 0.27965738005315427, "brake_pedal_position": 0.0, "acceleration": 0.21685731592350144, "steering_wheel_angle": -5.832688274849376, "front_wheel_angle": -0.2922177419406417, "heading_rate": -0.15137331400774878, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.0390418} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27934004154283965, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.8463225634214915, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3010497274648767, "gear": 1, "accelerator_pedal_position": 0.27934004154283965, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.716747843211106, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.0390418} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.40995478630066, "x": 39.129742418660214, "y": 0.13133200631206066, "z": null, "yaw": 3.333855372020498, "pitch": null, "roll": null}, "v": 1.2881566679417145, "accelerator_pedal_position": 0.27965738005315427, "brake_pedal_position": 0.0, "acceleration": 0.21685731592350144, "steering_wheel_angle": -5.832688274849376, "front_wheel_angle": -0.2922177419406417, "heading_rate": -0.15137331400774878, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.0590417} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27934004154283965, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.8463225634214915, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3031886821582381, "gear": 1, "accelerator_pedal_position": 0.27934004154283965, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.677988824477852, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.0590417} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.40995478630066, "x": 39.129742418660214, "y": 0.13133200631206066, "z": null, "yaw": 3.333855372020498, "pitch": null, "roll": null}, "v": 1.2881566679417145, "accelerator_pedal_position": 0.27965738005315427, "brake_pedal_position": 0.0, "acceleration": 0.21685731592350144, "steering_wheel_angle": -5.832688274849376, "front_wheel_angle": -0.2922177419406417, "heading_rate": -0.15137331400774878, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.0890417} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27934004154283965, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.8463225634214915, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3074617123313867, "gear": 1, "accelerator_pedal_position": 0.27934004154283965, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.600302474730601, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.0890417} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502686.1090417, "x": 42.989339256407206, "y": 5.104851438394748, "z": null, "yaw": 3.3211817857354102, "pitch": null, "roll": null}, "v": 1.3117282390480105, "accelerator_pedal_position": 0.27934004154283965, "brake_pedal_position": 0.0, "acceleration": 0.2130825379591872, "steering_wheel_angle": -5.561375143716603, "front_wheel_angle": -0.2773411188493756, "heading_rate": -0.14586714229572298, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.1090417} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2797089685068541, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.6016004552139735, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3117282390480105, "gear": 1, "accelerator_pedal_position": 0.27934004154283965, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.561375143716603, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.1090417} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.519954681396484, "x": 38.989339256407206, "y": 0.10485143839474809, "z": null, "yaw": 3.3211817857354102, "pitch": null, "roll": null}, "v": 1.3117282390480105, "accelerator_pedal_position": 0.27934004154283965, "brake_pedal_position": 0.0, "acceleration": 0.2130825379591872, "steering_wheel_angle": -5.561375143716603, "front_wheel_angle": -0.2773411188493756, "heading_rate": -0.14586714229572298, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.1290417} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27968324942747924, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.6016004552139735, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.318183354473301, "gear": 1, "accelerator_pedal_position": 0.27968324942747924, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.445250911053585, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.1290417} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.519954681396484, "x": 38.989339256407206, "y": 0.10485143839474809, "z": null, "yaw": 3.3211817857354102, "pitch": null, "roll": null}, "v": 1.3117282390480105, "accelerator_pedal_position": 0.27934004154283965, "brake_pedal_position": 0.0, "acceleration": 0.2130825379591872, "steering_wheel_angle": -5.561375143716603, "front_wheel_angle": -0.2773411188493756, "heading_rate": -0.14586714229572298, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.1490417} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27968324942747924, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.6016004552139735, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3203307051496809, "gear": 1, "accelerator_pedal_position": 0.27968324942747924, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.406432518580662, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.1490417} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.519954681396484, "x": 38.989339256407206, "y": 0.10485143839474809, "z": null, "yaw": 3.3211817857354102, "pitch": null, "roll": null}, "v": 1.3117282390480105, "accelerator_pedal_position": 0.27934004154283965, "brake_pedal_position": 0.0, "acceleration": 0.2130825379591872, "steering_wheel_angle": -5.561375143716603, "front_wheel_angle": -0.2773411188493756, "heading_rate": -0.14586714229572298, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.1690416} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27968324942747924, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.6016004552139735, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3246204860636865, "gear": 1, "accelerator_pedal_position": 0.27968324942747924, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.328630261256942, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.1690416} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.519954681396484, "x": 38.989339256407206, "y": 0.10485143839474809, "z": null, "yaw": 3.3211817857354102, "pitch": null, "roll": null}, "v": 1.3117282390480105, "accelerator_pedal_position": 0.27934004154283965, "brake_pedal_position": 0.0, "acceleration": 0.2130825379591872, "steering_wheel_angle": -5.561375143716603, "front_wheel_angle": -0.2773411188493756, "heading_rate": -0.14586714229572298, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.1890416} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27968324942747924, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.6016004552139735, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3289037086136124, "gear": 1, "accelerator_pedal_position": 0.27968324942747924, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.328630261256942, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.1890416} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.519954681396484, "x": 38.989339256407206, "y": 0.10485143839474809, "z": null, "yaw": 3.3211817857354102, "pitch": null, "roll": null}, "v": 1.3117282390480105, "accelerator_pedal_position": 0.27934004154283965, "brake_pedal_position": 0.0, "acceleration": 0.2130825379591872, "steering_wheel_angle": -5.561375143716603, "front_wheel_angle": -0.2773411188493756, "heading_rate": -0.14586714229572298, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.2090416} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27968324942747924, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.6016004552139735, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.33318037549052, "gear": 1, "accelerator_pedal_position": 0.27968324942747924, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.328630261256942, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.2090416} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502686.2190416, "x": 42.84606866862808, "y": 5.079647506890617, "z": null, "yaw": 3.3093487336402325, "pitch": null, "roll": null}, "v": 1.335316251400633, "accelerator_pedal_position": 0.27968324942747924, "brake_pedal_position": 0.0, "acceleration": 0.21342380143916717, "steering_wheel_angle": -5.328630261256942, "front_wheel_angle": -0.26469776124127176, "heading_rate": -0.14138604027252688, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.2290416} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2813032865076223, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.386671383380559, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3374504894150245, "gear": 1, "accelerator_pedal_position": 0.27968324942747924, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.328630261256942, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.2290416} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.62995457649231, "x": 38.84606866862808, "y": 0.07964750689061706, "z": null, "yaw": 3.3093487336402325, "pitch": null, "roll": null}, "v": 1.335316251400633, "accelerator_pedal_position": 0.27968324942747924, "brake_pedal_position": 0.0, "acceleration": 0.21342380143916717, "steering_wheel_angle": -5.328630261256942, "front_wheel_angle": -0.26469776124127176, "heading_rate": -0.14138604027252688, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.2490416} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28088721393723004, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.386671383380559, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3419164800178358, "gear": 1, "accelerator_pedal_position": 0.2813032865076223, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.251179928143811, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.2490416} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.62995457649231, "x": 38.84606866862808, "y": 0.07964750689061706, "z": null, "yaw": 3.3093487336402325, "pitch": null, "roll": null}, "v": 1.335316251400633, "accelerator_pedal_position": 0.27968324942747924, "brake_pedal_position": 0.0, "acceleration": 0.21342380143916717, "steering_wheel_angle": -5.328630261256942, "front_wheel_angle": -0.26469776124127176, "heading_rate": -0.14138604027252688, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.2690415} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28088721393723004, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.386671383380559, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3485246533174926, "gear": 1, "accelerator_pedal_position": 0.28088721393723004, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.134596788221459, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.2690415} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.62995457649231, "x": 38.84606866862808, "y": 0.07964750689061706, "z": null, "yaw": 3.3093487336402325, "pitch": null, "roll": null}, "v": 1.335316251400633, "accelerator_pedal_position": 0.27968324942747924, "brake_pedal_position": 0.0, "acceleration": 0.21342380143916717, "steering_wheel_angle": -5.328630261256942, "front_wheel_angle": -0.26469776124127176, "heading_rate": -0.14138604027252688, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.2890415} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28088721393723004, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.386671383380559, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.355117583694036, "gear": 1, "accelerator_pedal_position": 0.28088721393723004, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.134596788221459, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.2890415} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.62995457649231, "x": 38.84606866862808, "y": 0.07964750689061706, "z": null, "yaw": 3.3093487336402325, "pitch": null, "roll": null}, "v": 1.335316251400633, "accelerator_pedal_position": 0.27968324942747924, "brake_pedal_position": 0.0, "acceleration": 0.21342380143916717, "steering_wheel_angle": -5.328630261256942, "front_wheel_angle": -0.26469776124127176, "heading_rate": -0.14138604027252688, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.3190415} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28088721393723004, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.386671383380559, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.357311841406702, "gear": 1, "accelerator_pedal_position": 0.28088721393723004, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.134596788221459, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.3190415} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502686.3290415, "x": 42.69992711597581, "y": 5.055683345176492, "z": null, "yaw": 3.2980079453194655, "pitch": null, "roll": null}, "v": 1.3595044068135933, "accelerator_pedal_position": 0.28088721393723004, "brake_pedal_position": 0.0, "acceleration": 0.21908734444555217, "steering_wheel_angle": -5.134596788221459, "front_wheel_angle": -0.2542388386536812, "heading_rate": -0.1380014068035027, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.3390415} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28113852140814344, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.167587142123151, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3616952802580489, "gear": 1, "accelerator_pedal_position": 0.28088721393723004, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.134596788221459, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.3390415} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.739954471588135, "x": 38.69992711597581, "y": 0.05568334517649198, "z": null, "yaw": 3.2980079453194655, "pitch": null, "roll": null}, "v": 1.3595044068135933, "accelerator_pedal_position": 0.28088721393723004, "brake_pedal_position": 0.0, "acceleration": 0.21908734444555217, "steering_wheel_angle": -5.134596788221459, "front_wheel_angle": -0.2542388386536812, "heading_rate": -0.1380014068035027, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.3590415} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2811530495919863, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.167587142123151, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.366103353938863, "gear": 1, "accelerator_pedal_position": 0.28113852140814344, "brake_pedal_position": 0.0, "steering_wheel_angle": -5.057177782077558, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.3590415} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.739954471588135, "x": 38.69992711597581, "y": 0.05568334517649198, "z": null, "yaw": 3.2980079453194655, "pitch": null, "roll": null}, "v": 1.3595044068135933, "accelerator_pedal_position": 0.28088721393723004, "brake_pedal_position": 0.0, "acceleration": 0.21908734444555217, "steering_wheel_angle": -5.134596788221459, "front_wheel_angle": -0.2542388386536812, "heading_rate": -0.1380014068035027, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.3790414} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2811530495919863, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.167587142123151, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3705064306906025, "gear": 1, "accelerator_pedal_position": 0.2811530495919863, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.979544556371263, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.3790414} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.739954471588135, "x": 38.69992711597581, "y": 0.05568334517649198, "z": null, "yaw": 3.2980079453194655, "pitch": null, "roll": null}, "v": 1.3595044068135933, "accelerator_pedal_position": 0.28088721393723004, "brake_pedal_position": 0.0, "acceleration": 0.21908734444555217, "steering_wheel_angle": -5.134596788221459, "front_wheel_angle": -0.2542388386536812, "heading_rate": -0.1380014068035027, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.3990414} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2811530495919863, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.167587142123151, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3749026951640142, "gear": 1, "accelerator_pedal_position": 0.2811530495919863, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.901697111102577, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.3990414} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.739954471588135, "x": 38.69992711597581, "y": 0.05568334517649198, "z": null, "yaw": 3.2980079453194655, "pitch": null, "roll": null}, "v": 1.3595044068135933, "accelerator_pedal_position": 0.28088721393723004, "brake_pedal_position": 0.0, "acceleration": 0.21908734444555217, "steering_wheel_angle": -5.134596788221459, "front_wheel_angle": -0.2542388386536812, "heading_rate": -0.1380014068035027, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.4190414} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2811530495919863, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -4.167587142123151, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3792921501709412, "gear": 1, "accelerator_pedal_position": 0.2811530495919863, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.901697111102577, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.4190414} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502686.4390414, "x": 42.55089770430696, "y": 5.03294399037451, "z": null, "yaw": 3.2871787700477575, "pitch": null, "roll": null}, "v": 1.3836747985547704, "accelerator_pedal_position": 0.2811530495919863, "brake_pedal_position": 0.0, "acceleration": 0.21887726054061973, "steering_wheel_angle": -4.901697111102577, "front_wheel_angle": -0.2417805077050956, "heading_rate": -0.13328931929232635, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.4390414} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28060216568088464, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.941761081616841, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3836747985547704, "gear": 1, "accelerator_pedal_position": 0.2811530495919863, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.901697111102577, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.4390414} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.84995436668396, "x": 38.55089770430696, "y": 0.0329439903745099, "z": null, "yaw": 3.2871787700477575, "pitch": null, "roll": null}, "v": 1.3836747985547704, "accelerator_pedal_position": 0.2811530495919863, "brake_pedal_position": 0.0, "acceleration": 0.21887726054061973, "steering_wheel_angle": -4.901697111102577, "front_wheel_angle": -0.2417805077050956, "heading_rate": -0.13328931929232635, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.4590414} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2808678949146875, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.941761081616841, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3879818094595489, "gear": 1, "accelerator_pedal_position": 0.28060216568088464, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.824219687136048, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.4590414} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.84995436668396, "x": 38.55089770430696, "y": 0.0329439903745099, "z": null, "yaw": 3.2871787700477575, "pitch": null, "roll": null}, "v": 1.3836747985547704, "accelerator_pedal_position": 0.2811530495919863, "brake_pedal_position": 0.0, "acceleration": 0.21887726054061973, "steering_wheel_angle": -4.901697111102577, "front_wheel_angle": -0.2417805077050956, "heading_rate": -0.13328931929232635, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.4790413} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2808678949146875, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.941761081616841, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3923153298235522, "gear": 1, "accelerator_pedal_position": 0.2808678949146875, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.746531233867736, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.4790413} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.84995436668396, "x": 38.55089770430696, "y": 0.0329439903745099, "z": null, "yaw": 3.2871787700477575, "pitch": null, "roll": null}, "v": 1.3836747985547704, "accelerator_pedal_position": 0.2811530495919863, "brake_pedal_position": 0.0, "acceleration": 0.21887726054061973, "steering_wheel_angle": -4.901697111102577, "front_wheel_angle": -0.2417805077050956, "heading_rate": -0.13328931929232635, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.4990413} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2808678949146875, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.941761081616841, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3966421077197995, "gear": 1, "accelerator_pedal_position": 0.2808678949146875, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.707607871245411, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.4990413} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.84995436668396, "x": 38.55089770430696, "y": 0.0329439903745099, "z": null, "yaw": 3.2871787700477575, "pitch": null, "roll": null}, "v": 1.3836747985547704, "accelerator_pedal_position": 0.2811530495919863, "brake_pedal_position": 0.0, "acceleration": 0.21887726054061973, "steering_wheel_angle": -4.901697111102577, "front_wheel_angle": -0.2417805077050956, "heading_rate": -0.13328931929232635, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.5190413} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2808678949146875, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.941761081616841, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.400962146153321, "gear": 1, "accelerator_pedal_position": 0.2808678949146875, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.707607871245411, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.5190413} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.84995436668396, "x": 38.55089770430696, "y": 0.0329439903745099, "z": null, "yaw": 3.2871787700477575, "pitch": null, "roll": null}, "v": 1.3836747985547704, "accelerator_pedal_position": 0.2811530495919863, "brake_pedal_position": 0.0, "acceleration": 0.21887726054061973, "steering_wheel_angle": -4.901697111102577, "front_wheel_angle": -0.2417805077050956, "heading_rate": -0.13328931929232635, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.5390413} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2808678949146875, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.941761081616841, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4052754481594354, "gear": 1, "accelerator_pedal_position": 0.2808678949146875, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.707607871245411, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.5390413} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502686.5490413, "x": 42.39902545714323, "y": 5.011407479089678, "z": null, "yaw": 3.2769233003450022, "pitch": null, "roll": null}, "v": 1.4074295739590037, "accelerator_pedal_position": 0.2808678949146875, "brake_pedal_position": 0.0, "acceleration": 0.21524428446230243, "steering_wheel_angle": -4.707607871245411, "front_wheel_angle": -0.2314761616691115, "heading_rate": -0.12958302569043084, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.5590413} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28736278125120546, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.8210091419365306, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4095820168036268, "gear": 1, "accelerator_pedal_position": 0.2808678949146875, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.707607871245411, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.5590413} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.959954261779785, "x": 38.39902545714323, "y": 0.011407479089678318, "z": null, "yaw": 3.2769233003450022, "pitch": null, "roll": null}, "v": 1.4074295739590037, "accelerator_pedal_position": 0.2808678949146875, "brake_pedal_position": 0.0, "acceleration": 0.21524428446230243, "steering_wheel_angle": -4.707607871245411, "front_wheel_angle": -0.2314761616691115, "heading_rate": -0.12958302569043084, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.5790412} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2854256659682318, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.8210091419365306, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.414693398378762, "gear": 1, "accelerator_pedal_position": 0.28736278125120546, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.629912031601394, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.5790412} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.959954261779785, "x": 38.39902545714323, "y": 0.011407479089678318, "z": null, "yaw": 3.2769233003450022, "pitch": null, "roll": null}, "v": 1.4074295739590037, "accelerator_pedal_position": 0.2808678949146875, "brake_pedal_position": 0.0, "acceleration": 0.21524428446230243, "steering_wheel_angle": -4.707607871245411, "front_wheel_angle": -0.2314761616691115, "heading_rate": -0.12958302569043084, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.5990412} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2854256659682318, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.8210091419365306, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4195547373421806, "gear": 1, "accelerator_pedal_position": 0.2854256659682318, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.552006829845901, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.5990412} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.959954261779785, "x": 38.39902545714323, "y": 0.011407479089678318, "z": null, "yaw": 3.2769233003450022, "pitch": null, "roll": null}, "v": 1.4074295739590037, "accelerator_pedal_position": 0.2808678949146875, "brake_pedal_position": 0.0, "acceleration": 0.21524428446230243, "steering_wheel_angle": -4.707607871245411, "front_wheel_angle": -0.2314761616691115, "heading_rate": -0.12958302569043084, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.6190412} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2854256659682318, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.8210091419365306, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4244084599416402, "gear": 1, "accelerator_pedal_position": 0.2854256659682318, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.552006829845901, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.6190412} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.959954261779785, "x": 38.39902545714323, "y": 0.011407479089678318, "z": null, "yaw": 3.2769233003450022, "pitch": null, "roll": null}, "v": 1.4074295739590037, "accelerator_pedal_position": 0.2808678949146875, "brake_pedal_position": 0.0, "acceleration": 0.21524428446230243, "steering_wheel_angle": -4.707607871245411, "front_wheel_angle": -0.2314761616691115, "heading_rate": -0.12958302569043084, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.6390412} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2854256659682318, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.8210091419365306, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4316747686665645, "gear": 1, "accelerator_pedal_position": 0.2854256659682318, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.552006829845901, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.6390412} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 47.959954261779785, "x": 38.39902545714323, "y": 0.011407479089678318, "z": null, "yaw": 3.2769233003450022, "pitch": null, "roll": null}, "v": 1.4074295739590037, "accelerator_pedal_position": 0.2808678949146875, "brake_pedal_position": 0.0, "acceleration": 0.21524428446230243, "steering_wheel_angle": -4.707607871245411, "front_wheel_angle": -0.2314761616691115, "heading_rate": -0.12958302569043084, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.6490412} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2854256659682318, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.8210091419365306, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4316747686665645, "gear": 1, "accelerator_pedal_position": 0.2854256659682318, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.552006829845901, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.6490412} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502686.6590412, "x": 42.24421290988843, "y": 4.991043530120282, "z": null, "yaw": 3.2670489948217805, "pitch": null, "roll": null}, "v": 1.4340930661409221, "accelerator_pedal_position": 0.2854256659682318, "brake_pedal_position": 0.0, "acceleration": 0.24163952977086806, "steering_wheel_angle": -4.552006829845901, "front_wheel_angle": -0.22326531229195823, "heading_rate": -0.1271920306622703, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.6790411} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2806833706265429, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.5608853478359803, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4389239548876458, "gear": 1, "accelerator_pedal_position": 0.2854256659682318, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.552006829845901, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.6790411} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.06995415687561, "x": 38.24421290988843, "y": -0.008956469879717766, "z": null, "yaw": 3.2670489948217805, "pitch": null, "roll": null}, "v": 1.4340930661409221, "accelerator_pedal_position": 0.2854256659682318, "brake_pedal_position": 0.0, "acceleration": 0.24163952977086806, "steering_wheel_angle": -4.552006829845901, "front_wheel_angle": -0.22326531229195823, "heading_rate": -0.1271920306622703, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.6990411} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2822698801498217, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.5608853478359803, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4431546842746856, "gear": 1, "accelerator_pedal_position": 0.2806833706265429, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.474549479546092, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.6990411} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.06995415687561, "x": 38.24421290988843, "y": -0.008956469879717766, "z": null, "yaw": 3.2670489948217805, "pitch": null, "roll": null}, "v": 1.4340930661409221, "accelerator_pedal_position": 0.2854256659682318, "brake_pedal_position": 0.0, "acceleration": 0.24163952977086806, "steering_wheel_angle": -4.552006829845901, "front_wheel_angle": -0.22326531229195823, "heading_rate": -0.1271920306622703, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.719041} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2822698801498217, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.5608853478359803, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.44757698056339, "gear": 1, "accelerator_pedal_position": 0.2822698801498217, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.396886270597458, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.719041} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.06995415687561, "x": 38.24421290988843, "y": -0.008956469879717766, "z": null, "yaw": 3.2670489948217805, "pitch": null, "roll": null}, "v": 1.4340930661409221, "accelerator_pedal_position": 0.2854256659682318, "brake_pedal_position": 0.0, "acceleration": 0.24163952977086806, "steering_wheel_angle": -4.552006829845901, "front_wheel_angle": -0.22326531229195823, "heading_rate": -0.1271920306622703, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.739041} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2822698801498217, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.5608853478359803, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4541973418180774, "gear": 1, "accelerator_pedal_position": 0.2822698801498217, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.319017202999995, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.739041} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.06995415687561, "x": 38.24421290988843, "y": -0.008956469879717766, "z": null, "yaw": 3.2670489948217805, "pitch": null, "roll": null}, "v": 1.4340930661409221, "accelerator_pedal_position": 0.2854256659682318, "brake_pedal_position": 0.0, "acceleration": 0.24163952977086806, "steering_wheel_angle": -4.552006829845901, "front_wheel_angle": -0.22326531229195823, "heading_rate": -0.1271920306622703, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.759041} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2822698801498217, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.5608853478359803, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4564006416656372, "gear": 1, "accelerator_pedal_position": 0.2822698801498217, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.319017202999995, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.759041} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502686.769041, "x": 42.08638693465914, "y": 4.97184138835973, "z": null, "yaw": 3.2575682094300253, "pitch": null, "roll": null}, "v": 1.4586021985712638, "accelerator_pedal_position": 0.2822698801498217, "brake_pedal_position": 0.0, "acceleration": 0.21998143727105302, "steering_wheel_angle": -4.319017202999995, "front_wheel_angle": -0.2110525231606861, "heading_rate": -0.12206849826454555, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.779041} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28827243170678873, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.4492027937610064, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4608020129439743, "gear": 1, "accelerator_pedal_position": 0.2822698801498217, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.319017202999995, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.779041} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.179954051971436, "x": 38.08638693465914, "y": -0.028158611640270337, "z": null, "yaw": 3.2575682094300253, "pitch": null, "roll": null}, "v": 1.4586021985712638, "accelerator_pedal_position": 0.2822698801498217, "brake_pedal_position": 0.0, "acceleration": 0.21998143727105302, "steering_wheel_angle": -4.319017202999995, "front_wheel_angle": -0.2110525231606861, "heading_rate": -0.12206849826454555, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.799041} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28649335473552034, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.4492027937610064, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4659464373157447, "gear": 1, "accelerator_pedal_position": 0.28827243170678873, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.241221610789449, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.799041} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.179954051971436, "x": 38.08638693465914, "y": -0.028158611640270337, "z": null, "yaw": 3.2575682094300253, "pitch": null, "roll": null}, "v": 1.4586021985712638, "accelerator_pedal_position": 0.2822698801498217, "brake_pedal_position": 0.0, "acceleration": 0.21998143727105302, "steering_wheel_angle": -4.319017202999995, "front_wheel_angle": -0.2110525231606861, "heading_rate": -0.12206849826454555, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.819041} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28649335473552034, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.4492027937610064, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.47086041019602, "gear": 1, "accelerator_pedal_position": 0.28649335473552034, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.202247168366611, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.819041} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.179954051971436, "x": 38.08638693465914, "y": -0.028158611640270337, "z": null, "yaw": 3.2575682094300253, "pitch": null, "roll": null}, "v": 1.4586021985712638, "accelerator_pedal_position": 0.2822698801498217, "brake_pedal_position": 0.0, "acceleration": 0.21998143727105302, "steering_wheel_angle": -4.319017202999995, "front_wheel_angle": -0.2110525231606861, "heading_rate": -0.12206849826454555, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.839041} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28649335473552034, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.4492027937610064, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4757665835091898, "gear": 1, "accelerator_pedal_position": 0.28649335473552034, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.202247168366611, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.839041} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.179954051971436, "x": 38.08638693465914, "y": -0.028158611640270337, "z": null, "yaw": 3.2575682094300253, "pitch": null, "roll": null}, "v": 1.4586021985712638, "accelerator_pedal_position": 0.2822698801498217, "brake_pedal_position": 0.0, "acceleration": 0.21998143727105302, "steering_wheel_angle": -4.319017202999995, "front_wheel_angle": -0.2110525231606861, "heading_rate": -0.12206849826454555, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.859041} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28649335473552034, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.4492027937610064, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4806649600105102, "gear": 1, "accelerator_pedal_position": 0.28649335473552034, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.202247168366611, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.859041} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502686.879041, "x": 41.92560764998388, "y": 4.953784260496893, "z": null, "yaw": 3.2485610824954145, "pitch": null, "roll": null}, "v": 1.4855555424967304, "accelerator_pedal_position": 0.28649335473552034, "brake_pedal_position": 0.0, "acceleration": 0.24423693727373802, "steering_wheel_angle": -4.202247168366611, "front_wheel_angle": -0.204967947201479, "heading_rate": -0.12063603432875339, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.879041} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2818322802093307, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.2173987948684633, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4877065947115808, "gear": 1, "accelerator_pedal_position": 0.2818322802093307, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.163507546787555, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.879041} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.28995394706726, "x": 37.92560764998388, "y": -0.04621573950310687, "z": null, "yaw": 3.2485610824954145, "pitch": null, "roll": null}, "v": 1.4855555424967304, "accelerator_pedal_position": 0.28649335473552034, "brake_pedal_position": 0.0, "acceleration": 0.24423693727373802, "steering_wheel_angle": -4.202247168366611, "front_wheel_angle": -0.204967947201479, "heading_rate": -0.12063603432875339, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.899041} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28339592783186884, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.2173987948684633, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4898559318361133, "gear": 1, "accelerator_pedal_position": 0.2818322802093307, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.124717573164493, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.899041} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.28995394706726, "x": 37.92560764998388, "y": -0.04621573950310687, "z": null, "yaw": 3.2485610824954145, "pitch": null, "roll": null}, "v": 1.4855555424967304, "accelerator_pedal_position": 0.28649335473552034, "brake_pedal_position": 0.0, "acceleration": 0.24423693727373802, "steering_wheel_angle": -4.202247168366611, "front_wheel_angle": -0.204967947201479, "heading_rate": -0.12063603432875339, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.919041} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28339592783186884, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.2173987948684633, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.49434484051461, "gear": 1, "accelerator_pedal_position": 0.28339592783186884, "brake_pedal_position": 0.0, "steering_wheel_angle": -4.046986569786353, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.919041} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.28995394706726, "x": 37.92560764998388, "y": -0.04621573950310687, "z": null, "yaw": 3.2485610824954145, "pitch": null, "roll": null}, "v": 1.4855555424967304, "accelerator_pedal_position": 0.28649335473552034, "brake_pedal_position": 0.0, "acceleration": 0.24423693727373802, "steering_wheel_angle": -4.202247168366611, "front_wheel_angle": -0.204967947201479, "heading_rate": -0.12063603432875339, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.939041} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28339592783186884, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.2173987948684633, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4988265819724271, "gear": 1, "accelerator_pedal_position": 0.28339592783186884, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.969054158232192, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.939041} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.28995394706726, "x": 37.92560764998388, "y": -0.04621573950310687, "z": null, "yaw": 3.2485610824954145, "pitch": null, "roll": null}, "v": 1.4855555424967304, "accelerator_pedal_position": 0.28649335473552034, "brake_pedal_position": 0.0, "acceleration": 0.24423693727373802, "steering_wheel_angle": -4.202247168366611, "front_wheel_angle": -0.204967947201479, "heading_rate": -0.12063603432875339, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.9590409} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28339592783186884, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.2173987948684633, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5033011596219221, "gear": 1, "accelerator_pedal_position": 0.28339592783186884, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.969054158232192, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.9590409} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.28995394706726, "x": 37.92560764998388, "y": -0.04621573950310687, "z": null, "yaw": 3.2485610824954145, "pitch": null, "roll": null}, "v": 1.4855555424967304, "accelerator_pedal_position": 0.28649335473552034, "brake_pedal_position": 0.0, "acceleration": 0.24423693727373802, "steering_wheel_angle": -4.202247168366611, "front_wheel_angle": -0.204967947201479, "heading_rate": -0.12063603432875339, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.9690409} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28339592783186884, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.2173987948684633, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5077685769085003, "gear": 1, "accelerator_pedal_position": 0.28339592783186884, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.969054158232192, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.9690409} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502686.9890409, "x": 41.76185436125822, "y": 4.936855796343539, "z": null, "yaw": 3.2399968336696063, "pitch": null, "roll": null}, "v": 1.5099996015013866, "accelerator_pedal_position": 0.28339592783186884, "brake_pedal_position": 0.0, "acceleration": 0.2229235809087674, "steering_wheel_angle": -3.969054158232192, "front_wheel_angle": -0.19288789397631215, "heading_rate": -0.11520602026533577, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502686.9990408} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28935316716479614, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.1261118044616976, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5122288373104742, "gear": 1, "accelerator_pedal_position": 0.28339592783186884, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.969054158232192, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502686.9990408} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.399953842163086, "x": 37.76185436125822, "y": -0.0631442036564609, "z": null, "yaw": 3.2399968336696063, "pitch": null, "roll": null}, "v": 1.5099996015013866, "accelerator_pedal_position": 0.28339592783186884, "brake_pedal_position": 0.0, "acceleration": 0.2229235809087674, "steering_wheel_angle": -3.969054158232192, "front_wheel_angle": -0.19288789397631215, "heading_rate": -0.11520602026533577, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.0190408} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2875892506276, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.1261118044616976, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5174263003032178, "gear": 1, "accelerator_pedal_position": 0.28935316716479614, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.8911441263357998, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.0190408} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.399953842163086, "x": 37.76185436125822, "y": -0.0631442036564609, "z": null, "yaw": 3.2399968336696063, "pitch": null, "roll": null}, "v": 1.5099996015013866, "accelerator_pedal_position": 0.28339592783186884, "brake_pedal_position": 0.0, "acceleration": 0.2229235809087674, "steering_wheel_angle": -3.969054158232192, "front_wheel_angle": -0.19288789397631215, "heading_rate": -0.11520602026533577, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.0390408} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2875892506276, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.1261118044616976, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5223950162507747, "gear": 1, "accelerator_pedal_position": 0.2875892506276, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.8911441263357998, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.0390408} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.399953842163086, "x": 37.76185436125822, "y": -0.0631442036564609, "z": null, "yaw": 3.2399968336696063, "pitch": null, "roll": null}, "v": 1.5099996015013866, "accelerator_pedal_position": 0.28339592783186884, "brake_pedal_position": 0.0, "acceleration": 0.2229235809087674, "steering_wheel_angle": -3.969054158232192, "front_wheel_angle": -0.19288789397631215, "heading_rate": -0.11520602026533577, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.0590408} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2875892506276, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.1261118044616976, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5273557434265306, "gear": 1, "accelerator_pedal_position": 0.2875892506276, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.8911441263357998, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.0590408} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.399953842163086, "x": 37.76185436125822, "y": -0.0631442036564609, "z": null, "yaw": 3.2399968336696063, "pitch": null, "roll": null}, "v": 1.5099996015013866, "accelerator_pedal_position": 0.28339592783186884, "brake_pedal_position": 0.0, "acceleration": 0.2229235809087674, "steering_wheel_angle": -3.969054158232192, "front_wheel_angle": -0.19288789397631215, "heading_rate": -0.11520602026533577, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.0790408} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2875892506276, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.1261118044616976, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.534781861827919, "gear": 1, "accelerator_pedal_position": 0.2875892506276, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.8911441263357998, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.0790408} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.399953842163086, "x": 37.76185436125822, "y": -0.0631442036564609, "z": null, "yaw": 3.2399968336696063, "pitch": null, "roll": null}, "v": 1.5099996015013866, "accelerator_pedal_position": 0.28339592783186884, "brake_pedal_position": 0.0, "acceleration": 0.2229235809087674, "steering_wheel_angle": -3.969054158232192, "front_wheel_angle": -0.19288789397631215, "heading_rate": -0.11520602026533577, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.0890408} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2875892506276, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.1261118044616976, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5397226303138802, "gear": 1, "accelerator_pedal_position": 0.2875892506276, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.8911441263357998, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.0890408} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502687.0990407, "x": 41.595144512883685, "y": 4.921033713831507, "z": null, "yaw": 3.231742637218304, "pitch": null, "roll": null}, "v": 1.5372532435248905, "accelerator_pedal_position": 0.2875892506276, "brake_pedal_position": 0.0, "acceleration": 0.24693867889897736, "steering_wheel_angle": -3.8911441263357998, "front_wheel_angle": -0.18887272783703393, "heading_rate": -0.11478425206592342, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.1190407} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2924050818070962, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.0364962636665775, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5421900225851182, "gear": 1, "accelerator_pedal_position": 0.2875892506276, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.8911441263357998, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.1190407} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.50995373725891, "x": 37.595144512883685, "y": -0.07896628616849277, "z": null, "yaw": 3.231742637218304, "pitch": null, "roll": null}, "v": 1.5372532435248905, "accelerator_pedal_position": 0.2875892506276, "brake_pedal_position": 0.0, "acceleration": 0.24693867889897736, "steering_wheel_angle": -3.8911441263357998, "front_wheel_angle": -0.18887272783703393, "heading_rate": -0.11478425206592342, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.1390407} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2910097921228359, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.0364962636665775, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5503952683911524, "gear": 1, "accelerator_pedal_position": 0.2910097921228359, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.813252227246872, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.1390407} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.50995373725891, "x": 37.595144512883685, "y": -0.07896628616849277, "z": null, "yaw": 3.231742637218304, "pitch": null, "roll": null}, "v": 1.5372532435248905, "accelerator_pedal_position": 0.2875892506276, "brake_pedal_position": 0.0, "acceleration": 0.24693867889897736, "steering_wheel_angle": -3.8911441263357998, "front_wheel_angle": -0.18887272783703393, "heading_rate": -0.11478425206592342, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.1590407} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2910097921228359, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.0364962636665775, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.553067810215809, "gear": 1, "accelerator_pedal_position": 0.2910097921228359, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.813252227246872, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.1590407} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.50995373725891, "x": 37.595144512883685, "y": -0.07896628616849277, "z": null, "yaw": 3.231742637218304, "pitch": null, "roll": null}, "v": 1.5372532435248905, "accelerator_pedal_position": 0.2875892506276, "brake_pedal_position": 0.0, "acceleration": 0.24693867889897736, "steering_wheel_angle": -3.8911441263357998, "front_wheel_angle": -0.18887272783703393, "heading_rate": -0.11478425206592342, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.1790407} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2910097921228359, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.0364962636665775, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.558406397140116, "gear": 1, "accelerator_pedal_position": 0.2910097921228359, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.813252227246872, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.1790407} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.50995373725891, "x": 37.595144512883685, "y": -0.07896628616849277, "z": null, "yaw": 3.231742637218304, "pitch": null, "roll": null}, "v": 1.5372532435248905, "accelerator_pedal_position": 0.2875892506276, "brake_pedal_position": 0.0, "acceleration": 0.24693867889897736, "steering_wheel_angle": -3.8911441263357998, "front_wheel_angle": -0.18887272783703393, "heading_rate": -0.11478425206592342, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.1990407} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2910097921228359, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -3.0364962636665775, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5637363239683881, "gear": 1, "accelerator_pedal_position": 0.2910097921228359, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.813252227246872, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.1990407} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502687.2090406, "x": 41.42523911895955, "y": 4.906310403615023, "z": null, "yaw": 3.223650612556335, "pitch": null, "roll": null}, "v": 1.5663980406849913, "accelerator_pedal_position": 0.2910097921228359, "brake_pedal_position": 0.0, "acceleration": 0.2659552705148569, "steering_wheel_angle": -3.813252227246872, "front_wheel_angle": -0.1848687734623662, "heading_rate": -0.11442294279971707, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.2190406} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2881580014021757, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.820789775451371, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5690575933901398, "gear": 1, "accelerator_pedal_position": 0.2910097921228359, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.813252227246872, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.2190406} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.619953632354736, "x": 37.42523911895955, "y": -0.09368959638497731, "z": null, "yaw": 3.223650612556335, "pitch": null, "roll": null}, "v": 1.5663980406849913, "accelerator_pedal_position": 0.2910097921228359, "brake_pedal_position": 0.0, "acceleration": 0.2659552705148569, "steering_wheel_angle": -3.813252227246872, "front_wheel_angle": -0.1848687734623662, "heading_rate": -0.11442294279971707, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.2390406} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2891672763005814, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.820789775451371, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5765520753083693, "gear": 1, "accelerator_pedal_position": 0.2891672763005814, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.6968213422950016, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.2390406} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.619953632354736, "x": 37.42523911895955, "y": -0.09368959638497731, "z": null, "yaw": 3.223650612556335, "pitch": null, "roll": null}, "v": 1.5663980406849913, "accelerator_pedal_position": 0.2910097921228359, "brake_pedal_position": 0.0, "acceleration": 0.2659552705148569, "steering_wheel_angle": -3.813252227246872, "front_wheel_angle": -0.1848687734623662, "heading_rate": -0.11442294279971707, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.2590406} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2891672763005814, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.820789775451371, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5790882023948856, "gear": 1, "accelerator_pedal_position": 0.2891672763005814, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.657912795835624, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.2590406} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.619953632354736, "x": 37.42523911895955, "y": -0.09368959638497731, "z": null, "yaw": 3.223650612556335, "pitch": null, "roll": null}, "v": 1.5663980406849913, "accelerator_pedal_position": 0.2910097921228359, "brake_pedal_position": 0.0, "acceleration": 0.2659552705148569, "steering_wheel_angle": -3.813252227246872, "front_wheel_angle": -0.1848687734623662, "heading_rate": -0.11442294279971707, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.2790406} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2891672763005814, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.820789775451371, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.58415425184793, "gear": 1, "accelerator_pedal_position": 0.2891672763005814, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.5799483257037368, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.2790406} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.619953632354736, "x": 37.42523911895955, "y": -0.09368959638497731, "z": null, "yaw": 3.223650612556335, "pitch": null, "roll": null}, "v": 1.5663980406849913, "accelerator_pedal_position": 0.2910097921228359, "brake_pedal_position": 0.0, "acceleration": 0.2659552705148569, "steering_wheel_angle": -3.813252227246872, "front_wheel_angle": -0.1848687734623662, "heading_rate": -0.11442294279971707, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.2990406} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2891672763005814, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.820789775451371, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5892120310355768, "gear": 1, "accelerator_pedal_position": 0.2891672763005814, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.5799483257037368, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.2990406} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502687.3190405, "x": 41.252073608038394, "y": 4.892692591133996, "z": null, "yaw": 3.2159282579726245, "pitch": null, "roll": null}, "v": 1.5942615432306648, "accelerator_pedal_position": 0.2891672763005814, "brake_pedal_position": 0.0, "acceleration": 0.2521657010348583, "steering_wheel_angle": -3.5799483257037368, "front_wheel_angle": -0.17293672969205234, "heading_rate": -0.10878444839305275, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.3190405} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2961787935007446, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.78009309403782, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5942615432306648, "gear": 1, "accelerator_pedal_position": 0.2891672763005814, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.5799483257037368, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.3190405} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.72995352745056, "x": 37.252073608038394, "y": -0.10730740886600376, "z": null, "yaw": 3.2159282579726245, "pitch": null, "roll": null}, "v": 1.5942615432306648, "accelerator_pedal_position": 0.2891672763005814, "brake_pedal_position": 0.0, "acceleration": 0.2521657010348583, "steering_wheel_angle": -3.5799483257037368, "front_wheel_angle": -0.17293672969205234, "heading_rate": -0.10878444839305275, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.3390405} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2941013852931841, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.78009309403782, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6001788723233152, "gear": 1, "accelerator_pedal_position": 0.2961787935007446, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.5409411430739257, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.3390405} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.72995352745056, "x": 37.252073608038394, "y": -0.10730740886600376, "z": null, "yaw": 3.2159282579726245, "pitch": null, "roll": null}, "v": 1.5942615432306648, "accelerator_pedal_position": 0.2891672763005814, "brake_pedal_position": 0.0, "acceleration": 0.2521657010348583, "steering_wheel_angle": -3.5799483257037368, "front_wheel_angle": -0.17293672969205234, "heading_rate": -0.10878444839305275, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.3590405} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2941013852931841, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.78009309403782, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6058269345729945, "gear": 1, "accelerator_pedal_position": 0.2941013852931841, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.5409411430739257, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.3590405} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.72995352745056, "x": 37.252073608038394, "y": -0.10730740886600376, "z": null, "yaw": 3.2159282579726245, "pitch": null, "roll": null}, "v": 1.5942615432306648, "accelerator_pedal_position": 0.2891672763005814, "brake_pedal_position": 0.0, "acceleration": 0.2521657010348583, "steering_wheel_angle": -3.5799483257037368, "front_wheel_angle": -0.17293672969205234, "heading_rate": -0.10878444839305275, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.3790405} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2941013852931841, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.78009309403782, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6114657278335371, "gear": 1, "accelerator_pedal_position": 0.2941013852931841, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.5409411430739257, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.3790405} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.72995352745056, "x": 37.252073608038394, "y": -0.10730740886600376, "z": null, "yaw": 3.2159282579726245, "pitch": null, "roll": null}, "v": 1.5942615432306648, "accelerator_pedal_position": 0.2891672763005814, "brake_pedal_position": 0.0, "acceleration": 0.2521657010348583, "steering_wheel_angle": -3.5799483257037368, "front_wheel_angle": -0.17293672969205234, "heading_rate": -0.10878444839305275, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.3990405} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2941013852931841, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.78009309403782, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6170952546030348, "gear": 1, "accelerator_pedal_position": 0.2941013852931841, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.5409411430739257, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.3990405} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.72995352745056, "x": 37.252073608038394, "y": -0.10730740886600376, "z": null, "yaw": 3.2159282579726245, "pitch": null, "roll": null}, "v": 1.5942615432306648, "accelerator_pedal_position": 0.2891672763005814, "brake_pedal_position": 0.0, "acceleration": 0.2521657010348583, "steering_wheel_angle": -3.5799483257037368, "front_wheel_angle": -0.17293672969205234, "heading_rate": -0.10878444839305275, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.4190404} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2941013852931841, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.78009309403782, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6227155174381291, "gear": 1, "accelerator_pedal_position": 0.2941013852931841, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.5409411430739257, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.4190404} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502687.4290404, "x": 41.07557307036615, "y": 4.8801497709591795, "z": null, "yaw": 3.208502332635277, "pitch": null, "roll": null}, "v": 1.6255221756951805, "accelerator_pedal_position": 0.2941013852931841, "brake_pedal_position": 0.0, "acceleration": 0.2804343258608735, "steering_wheel_angle": -3.5409411430739257, "front_wheel_angle": -0.17095053599931267, "heading_rate": -0.10961831132070582, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.4390404} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2961891053072854, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.6834896163494406, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6283265189537892, "gear": 1, "accelerator_pedal_position": 0.2941013852931841, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.5409411430739257, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.4390404} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.83995342254639, "x": 37.07557307036615, "y": -0.11985022904082054, "z": null, "yaw": 3.208502332635277, "pitch": null, "roll": null}, "v": 1.6255221756951805, "accelerator_pedal_position": 0.2941013852931841, "brake_pedal_position": 0.0, "acceleration": 0.2804343258608735, "steering_wheel_angle": -3.5409411430739257, "front_wheel_angle": -0.17095053599931267, "heading_rate": -0.10961831132070582, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.4590404} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29566517027824774, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.6834896163494406, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6341891190151525, "gear": 1, "accelerator_pedal_position": 0.2961891053072854, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.463010289075194, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.4590404} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.83995342254639, "x": 37.07557307036615, "y": -0.11985022904082054, "z": null, "yaw": 3.208502332635277, "pitch": null, "roll": null}, "v": 1.6255221756951805, "accelerator_pedal_position": 0.2941013852931841, "brake_pedal_position": 0.0, "acceleration": 0.2804343258608735, "steering_wheel_angle": -3.5409411430739257, "front_wheel_angle": -0.17095053599931267, "heading_rate": -0.10961831132070582, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.4790404} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29566517027824774, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.6834896163494406, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6457544381355957, "gear": 1, "accelerator_pedal_position": 0.29566517027824774, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.463010289075194, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.4790404} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.83995342254639, "x": 37.07557307036615, "y": -0.11985022904082054, "z": null, "yaw": 3.208502332635277, "pitch": null, "roll": null}, "v": 1.6255221756951805, "accelerator_pedal_position": 0.2941013852931841, "brake_pedal_position": 0.0, "acceleration": 0.2804343258608735, "steering_wheel_angle": -3.5409411430739257, "front_wheel_angle": -0.17095053599931267, "heading_rate": -0.10961831132070582, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.4990404} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29566517027824774, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.6834896163494406, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6457544381355957, "gear": 1, "accelerator_pedal_position": 0.29566517027824774, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.463010289075194, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.4990404} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.83995342254639, "x": 37.07557307036615, "y": -0.11985022904082054, "z": null, "yaw": 3.208502332635277, "pitch": null, "roll": null}, "v": 1.6255221756951805, "accelerator_pedal_position": 0.2941013852931841, "brake_pedal_position": 0.0, "acceleration": 0.2804343258608735, "steering_wheel_angle": -3.5409411430739257, "front_wheel_angle": -0.17095053599931267, "heading_rate": -0.10961831132070582, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.5190403} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29566517027824774, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.6834896163494406, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6515227352290935, "gear": 1, "accelerator_pedal_position": 0.29566517027824774, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.463010289075194, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.5190403} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502687.5390403, "x": 40.895542428509614, "y": 4.868689321855683, "z": null, "yaw": 3.2012197371807116, "pitch": null, "roll": null}, "v": 1.6572814607386184, "accelerator_pedal_position": 0.29566517027824774, "brake_pedal_position": 0.0, "acceleration": 0.2875774228010381, "steering_wheel_angle": -3.463010289075194, "front_wheel_angle": -0.16698984973405964, "heading_rate": -0.10912134499903652, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.5390403} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2958716082637551, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.5407698837845385, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6572814607386184, "gear": 1, "accelerator_pedal_position": 0.29566517027824774, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.463010289075194, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.5390403} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.94995331764221, "x": 36.895542428509614, "y": -0.13131067814431674, "z": null, "yaw": 3.2012197371807116, "pitch": null, "roll": null}, "v": 1.6572814607386184, "accelerator_pedal_position": 0.29566517027824774, "brake_pedal_position": 0.0, "acceleration": 0.2875774228010381, "steering_wheel_angle": -3.463010289075194, "front_wheel_angle": -0.16698984973405964, "heading_rate": -0.10912134499903652, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.5590403} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2959386243980474, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.5407698837845385, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6630564113000454, "gear": 1, "accelerator_pedal_position": 0.2958716082637551, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.3852222822898863, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.5590403} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.94995331764221, "x": 36.895542428509614, "y": -0.13131067814431674, "z": null, "yaw": 3.2012197371807116, "pitch": null, "roll": null}, "v": 1.6572814607386184, "accelerator_pedal_position": 0.29566517027824774, "brake_pedal_position": 0.0, "acceleration": 0.2875774228010381, "steering_wheel_angle": -3.463010289075194, "front_wheel_angle": -0.16698984973405964, "heading_rate": -0.10912134499903652, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.5790403} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2959386243980474, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.5407698837845385, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.671713375710319, "gear": 1, "accelerator_pedal_position": 0.2959386243980474, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.307241094349303, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.5790403} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.94995331764221, "x": 36.895542428509614, "y": -0.13131067814431674, "z": null, "yaw": 3.2012197371807116, "pitch": null, "roll": null}, "v": 1.6572814607386184, "accelerator_pedal_position": 0.29566517027824774, "brake_pedal_position": 0.0, "acceleration": 0.2875774228010381, "steering_wheel_angle": -3.463010289075194, "front_wheel_angle": -0.16698984973405964, "heading_rate": -0.10912134499903652, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.5990403} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2959386243980474, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.5407698837845385, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6774726608205952, "gear": 1, "accelerator_pedal_position": 0.2959386243980474, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.307241094349303, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.5990403} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.94995331764221, "x": 36.895542428509614, "y": -0.13131067814431674, "z": null, "yaw": 3.2012197371807116, "pitch": null, "roll": null}, "v": 1.6572814607386184, "accelerator_pedal_position": 0.29566517027824774, "brake_pedal_position": 0.0, "acceleration": 0.2875774228010381, "steering_wheel_angle": -3.463010289075194, "front_wheel_angle": -0.16698984973405964, "heading_rate": -0.10912134499903652, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.6190403} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2959386243980474, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.5407698837845385, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6803486970622827, "gear": 1, "accelerator_pedal_position": 0.2959386243980474, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.307241094349303, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.6190403} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 48.94995331764221, "x": 36.895542428509614, "y": -0.13131067814431674, "z": null, "yaw": 3.2012197371807116, "pitch": null, "roll": null}, "v": 1.6572814607386184, "accelerator_pedal_position": 0.29566517027824774, "brake_pedal_position": 0.0, "acceleration": 0.2875774228010381, "steering_wheel_angle": -3.463010289075194, "front_wheel_angle": -0.16698984973405964, "heading_rate": -0.10912134499903652, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.6390402} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2959386243980474, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.5407698837845385, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.686093558683279, "gear": 1, "accelerator_pedal_position": 0.2959386243980474, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.307241094349303, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.6390402} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502687.6490402, "x": 40.71194809470455, "y": 4.858320384033212, "z": null, "yaw": 3.194245936410567, "pitch": null, "roll": null}, "v": 1.688962384779952, "accelerator_pedal_position": 0.2959386243980474, "brake_pedal_position": 0.0, "acceleration": 0.2866423438767828, "steering_wheel_angle": -3.307241094349303, "front_wheel_angle": -0.1591026757697778, "heading_rate": -0.10586290891791993, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.6590402} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2942161790275796, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.3441925470100546, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.6946928293678565, "gear": 1, "accelerator_pedal_position": 0.2959386243980474, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.307241094349303, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.6590402} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.05995321273804, "x": 36.71194809470455, "y": -0.1416796159667877, "z": null, "yaw": 3.194245936410567, "pitch": null, "roll": null}, "v": 1.688962384779952, "accelerator_pedal_position": 0.2959386243980474, "brake_pedal_position": 0.0, "acceleration": 0.2866423438767828, "steering_wheel_angle": -3.307241094349303, "front_wheel_angle": -0.1591026757697778, "heading_rate": -0.10586290891791993, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.6790402} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2948866520040973, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.3441925470100546, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7002403555537347, "gear": 1, "accelerator_pedal_position": 0.2948866520040973, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.229527057465774, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.6790402} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.05995321273804, "x": 36.71194809470455, "y": -0.1416796159667877, "z": null, "yaw": 3.194245936410567, "pitch": null, "roll": null}, "v": 1.688962384779952, "accelerator_pedal_position": 0.2959386243980474, "brake_pedal_position": 0.0, "acceleration": 0.2866423438767828, "steering_wheel_angle": -3.307241094349303, "front_wheel_angle": -0.1591026757697778, "heading_rate": -0.10586290891791993, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.6990402} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2948866520040973, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.3441925470100546, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7030315693995486, "gear": 1, "accelerator_pedal_position": 0.2948866520040973, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.1905984457032757, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.6990402} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.05995321273804, "x": 36.71194809470455, "y": -0.1416796159667877, "z": null, "yaw": 3.194245936410567, "pitch": null, "roll": null}, "v": 1.688962384779952, "accelerator_pedal_position": 0.2959386243980474, "brake_pedal_position": 0.0, "acceleration": 0.2866423438767828, "steering_wheel_angle": -3.307241094349303, "front_wheel_angle": -0.1591026757697778, "heading_rate": -0.10586290891791993, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.7190402} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2948866520040973, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.3441925470100546, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7086069609072958, "gear": 1, "accelerator_pedal_position": 0.2948866520040973, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.112598035536815, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.7190402} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.05995321273804, "x": 36.71194809470455, "y": -0.1416796159667877, "z": null, "yaw": 3.194245936410567, "pitch": null, "roll": null}, "v": 1.688962384779952, "accelerator_pedal_position": 0.2959386243980474, "brake_pedal_position": 0.0, "acceleration": 0.2866423438767828, "steering_wheel_angle": -3.307241094349303, "front_wheel_angle": -0.1591026757697778, "heading_rate": -0.10586290891791993, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.7390401} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2948866520040973, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.3441925470100546, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.716952463984862, "gear": 1, "accelerator_pedal_position": 0.2948866520040973, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.112598035536815, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.7390401} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502687.75904, "x": 40.52484704605236, "y": 4.849038853373895, "z": null, "yaw": 3.1875865283045615, "pitch": null, "roll": null}, "v": 1.7197296109267672, "accelerator_pedal_position": 0.2948866520040973, "brake_pedal_position": 0.0, "acceleration": 0.2774803951322864, "steering_wheel_angle": -3.112598035536815, "front_wheel_angle": -0.14930169193003684, "heading_rate": -0.10104824503899919, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.75904} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2936318107745416, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.155383315105271, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7197296109267672, "gear": 1, "accelerator_pedal_position": 0.2948866520040973, "brake_pedal_position": 0.0, "steering_wheel_angle": -3.112598035536815, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.75904} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.16995310783386, "x": 36.52484704605236, "y": -0.15096114662610471, "z": null, "yaw": 3.1875865283045615, "pitch": null, "roll": null}, "v": 1.7197296109267672, "accelerator_pedal_position": 0.2948866520040973, "brake_pedal_position": 0.0, "acceleration": 0.2774803951322864, "steering_wheel_angle": -3.112598035536815, "front_wheel_angle": -0.14930169193003684, "heading_rate": -0.10104824503899919, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.77904} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2941533050648114, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.155383315105271, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7278445049441236, "gear": 1, "accelerator_pedal_position": 0.2941533050648114, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.9958961110971183, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.77904} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.16995310783386, "x": 36.52484704605236, "y": -0.15096114662610471, "z": null, "yaw": 3.1875865283045615, "pitch": null, "roll": null}, "v": 1.7197296109267672, "accelerator_pedal_position": 0.2948866520040973, "brake_pedal_position": 0.0, "acceleration": 0.2774803951322864, "steering_wheel_angle": -3.112598035536815, "front_wheel_angle": -0.14930169193003684, "heading_rate": -0.10104824503899919, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.79904} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2941533050648114, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.155383315105271, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7305666195948757, "gear": 1, "accelerator_pedal_position": 0.2941533050648114, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.9569010751691613, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.79904} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.16995310783386, "x": 36.52484704605236, "y": -0.15096114662610471, "z": null, "yaw": 3.1875865283045615, "pitch": null, "roll": null}, "v": 1.7197296109267672, "accelerator_pedal_position": 0.2948866520040973, "brake_pedal_position": 0.0, "acceleration": 0.2774803951322864, "steering_wheel_angle": -3.112598035536815, "front_wheel_angle": -0.14930169193003684, "heading_rate": -0.10104824503899919, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.81904} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2941533050648114, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.155383315105271, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.736003941934354, "gear": 1, "accelerator_pedal_position": 0.2941533050648114, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.9569010751691613, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.81904} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.16995310783386, "x": 36.52484704605236, "y": -0.15096114662610471, "z": null, "yaw": 3.1875865283045615, "pitch": null, "roll": null}, "v": 1.7197296109267672, "accelerator_pedal_position": 0.2948866520040973, "brake_pedal_position": 0.0, "acceleration": 0.2774803951322864, "steering_wheel_angle": -3.112598035536815, "front_wheel_angle": -0.14930169193003684, "heading_rate": -0.10104824503899919, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.84904} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2941533050648114, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.155383315105271, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7468509719706742, "gear": 1, "accelerator_pedal_position": 0.2941533050648114, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.9569010751691613, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.84904} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2941533050648114, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -2.155383315105271, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7468509719706742, "gear": 1, "accelerator_pedal_position": 0.2941533050648114, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.9569010751691613, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.85904} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502687.86904, "x": 40.33436350801378, "y": 4.8408164661027655, "z": null, "yaw": 3.1813875841466803, "pitch": null, "roll": null}, "v": 1.7495569792194121, "accelerator_pedal_position": 0.2941533050648114, "brake_pedal_position": 0.0, "acceleration": 0.2703708114587471, "steering_wheel_angle": -2.9569010751691613, "front_wheel_angle": -0.14150469678025676, "heading_rate": -0.09735792536694608, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.87904} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2909293965413579, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.9163592804851397, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7549620968052457, "gear": 1, "accelerator_pedal_position": 0.2941533050648114, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.9569010751691613, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.87904} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.27995300292969, "x": 36.33436350801378, "y": -0.1591835338972345, "z": null, "yaw": 3.1813875841466803, "pitch": null, "roll": null}, "v": 1.7495569792194121, "accelerator_pedal_position": 0.2941533050648114, "brake_pedal_position": 0.0, "acceleration": 0.2703708114587471, "steering_wheel_angle": -2.9569010751691613, "front_wheel_angle": -0.14150469678025676, "heading_rate": -0.09735792536694608, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.89904} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29206317696345163, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.9163592804851397, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7574597138445556, "gear": 1, "accelerator_pedal_position": 0.2909293965413579, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.918131406761431, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.89904} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.27995300292969, "x": 36.33436350801378, "y": -0.1591835338972345, "z": null, "yaw": 3.1813875841466803, "pitch": null, "roll": null}, "v": 1.7495569792194121, "accelerator_pedal_position": 0.2941533050648114, "brake_pedal_position": 0.0, "acceleration": 0.2703708114587471, "steering_wheel_angle": -2.9569010751691613, "front_wheel_angle": -0.14150469678025676, "heading_rate": -0.09735792536694608, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.91904} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29206317696345163, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.9163592804851397, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.762590232435115, "gear": 1, "accelerator_pedal_position": 0.29206317696345163, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.840452447177407, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.91904} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.27995300292969, "x": 36.33436350801378, "y": -0.1591835338972345, "z": null, "yaw": 3.1813875841466803, "pitch": null, "roll": null}, "v": 1.7495569792194121, "accelerator_pedal_position": 0.2941533050648114, "brake_pedal_position": 0.0, "acceleration": 0.2703708114587471, "steering_wheel_angle": -2.9569010751691613, "front_wheel_angle": -0.14150469678025676, "heading_rate": -0.09735792536694608, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.93904} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29206317696345163, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.9163592804851397, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7702696216466656, "gear": 1, "accelerator_pedal_position": 0.29206317696345163, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.7235849508799603, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.93904} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.27995300292969, "x": 36.33436350801378, "y": -0.1591835338972345, "z": null, "yaw": 3.1813875841466803, "pitch": null, "roll": null}, "v": 1.7495569792194121, "accelerator_pedal_position": 0.2941533050648114, "brake_pedal_position": 0.0, "acceleration": 0.2703708114587471, "steering_wheel_angle": -2.9569010751691613, "front_wheel_angle": -0.14150469678025676, "heading_rate": -0.09735792536694608, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.95904} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29206317696345163, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.9163592804851397, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7728250499427254, "gear": 1, "accelerator_pedal_position": 0.29206317696345163, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.7235849508799603, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.95904} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502687.97904, "x": 40.140615005445106, "y": 4.8336322959416655, "z": null, "yaw": 3.175520636570718, "pitch": null, "roll": null}, "v": 1.7779293577157833, "accelerator_pedal_position": 0.29206317696345163, "brake_pedal_position": 0.0, "acceleration": 0.2548880601255068, "steering_wheel_angle": -2.7235849508799603, "front_wheel_angle": -0.129890804581545, "heading_rate": -0.0907204135111752, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.97904} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2953413928190022, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.8425772438521026, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7806831268080103, "gear": 1, "accelerator_pedal_position": 0.2953413928190022, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.684619623709269, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.97904} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.38995289802551, "x": 36.140615005445106, "y": -0.16636770405833445, "z": null, "yaw": 3.175520636570718, "pitch": null, "roll": null}, "v": 1.7779293577157833, "accelerator_pedal_position": 0.29206317696345163, "brake_pedal_position": 0.0, "acceleration": 0.2548880601255068, "steering_wheel_angle": -2.7235849508799603, "front_wheel_angle": -0.129890804581545, "heading_rate": -0.0907204135111752, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502687.99904} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2944379223067683, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.8425772438521026, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.783434539055984, "gear": 1, "accelerator_pedal_position": 0.2953413928190022, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.645607954532138, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502687.99904} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.38995289802551, "x": 36.140615005445106, "y": -0.16636770405833445, "z": null, "yaw": 3.175520636570718, "pitch": null, "roll": null}, "v": 1.7779293577157833, "accelerator_pedal_position": 0.29206317696345163, "brake_pedal_position": 0.0, "acceleration": 0.2548880601255068, "steering_wheel_angle": -2.7235849508799603, "front_wheel_angle": -0.129890804581545, "heading_rate": -0.0907204135111752, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.0190399} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2944379223067683, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.8425772438521026, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7888174096235072, "gear": 1, "accelerator_pedal_position": 0.2944379223067683, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.645607954532138, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.0190399} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.38995289802551, "x": 36.140615005445106, "y": -0.16636770405833445, "z": null, "yaw": 3.175520636570718, "pitch": null, "roll": null}, "v": 1.7779293577157833, "accelerator_pedal_position": 0.29206317696345163, "brake_pedal_position": 0.0, "acceleration": 0.2548880601255068, "steering_wheel_angle": -2.7235849508799603, "front_wheel_angle": -0.129890804581545, "heading_rate": -0.0907204135111752, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.0390399} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2944379223067683, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.8425772438521026, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7968744150527651, "gear": 1, "accelerator_pedal_position": 0.2944379223067683, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.645607954532138, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.0390399} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.38995289802551, "x": 36.140615005445106, "y": -0.16636770405833445, "z": null, "yaw": 3.175520636570718, "pitch": null, "roll": null}, "v": 1.7779293577157833, "accelerator_pedal_position": 0.29206317696345163, "brake_pedal_position": 0.0, "acceleration": 0.2548880601255068, "steering_wheel_angle": -2.7235849508799603, "front_wheel_angle": -0.129890804581545, "heading_rate": -0.0907204135111752, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.0590398} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2944379223067683, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.8425772438521026, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.7995554722230647, "gear": 1, "accelerator_pedal_position": 0.2944379223067683, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.645607954532138, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.0590398} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.38995289802551, "x": 36.140615005445106, "y": -0.16636770405833445, "z": null, "yaw": 3.175520636570718, "pitch": null, "roll": null}, "v": 1.7779293577157833, "accelerator_pedal_position": 0.29206317696345163, "brake_pedal_position": 0.0, "acceleration": 0.2548880601255068, "steering_wheel_angle": -2.7235849508799603, "front_wheel_angle": -0.129890804581545, "heading_rate": -0.0907204135111752, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.0790398} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2944379223067683, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.8425772438521026, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8075848174072195, "gear": 1, "accelerator_pedal_position": 0.2944379223067683, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.645607954532138, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.0790398} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502688.0890398, "x": 39.94364991917917, "y": 4.827440490640906, "z": null, "yaw": 3.170053518827438, "pitch": null, "roll": null}, "v": 1.8075848174072195, "accelerator_pedal_position": 0.2944379223067683, "brake_pedal_position": 0.0, "acceleration": 0.26718414482572994, "steering_wheel_angle": -2.645607954532138, "front_wheel_angle": -0.12602778902438197, "heading_rate": -0.089460824533111, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.0990398} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2925906742710726, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.6466968110503561, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.810256658855477, "gear": 1, "accelerator_pedal_position": 0.2944379223067683, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.645607954532138, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.0990398} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.49995279312134, "x": 35.94364991917917, "y": -0.17255950935909414, "z": null, "yaw": 3.170053518827438, "pitch": null, "roll": null}, "v": 1.8075848174072195, "accelerator_pedal_position": 0.2944379223067683, "brake_pedal_position": 0.0, "acceleration": 0.26718414482572994, "steering_wheel_angle": -2.645607954532138, "front_wheel_angle": -0.12602778902438197, "heading_rate": -0.089460824533111, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.1190398} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29329524342895436, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.6466968110503561, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8153626282408362, "gear": 1, "accelerator_pedal_position": 0.2925906742710726, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.5678858192026772, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.1190398} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.49995279312134, "x": 35.94364991917917, "y": -0.17255950935909414, "z": null, "yaw": 3.170053518827438, "pitch": null, "roll": null}, "v": 1.8075848174072195, "accelerator_pedal_position": 0.2944379223067683, "brake_pedal_position": 0.0, "acceleration": 0.26718414482572994, "steering_wheel_angle": -2.645607954532138, "front_wheel_angle": -0.12602778902438197, "heading_rate": -0.089460824533111, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.1390398} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29329524342895436, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.6466968110503561, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8231370628727626, "gear": 1, "accelerator_pedal_position": 0.29329524342895436, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.450958950687865, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.1390398} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.49995279312134, "x": 35.94364991917917, "y": -0.17255950935909414, "z": null, "yaw": 3.170053518827438, "pitch": null, "roll": null}, "v": 1.8075848174072195, "accelerator_pedal_position": 0.2944379223067683, "brake_pedal_position": 0.0, "acceleration": 0.26718414482572994, "steering_wheel_angle": -2.645607954532138, "front_wheel_angle": -0.12602778902438197, "heading_rate": -0.089460824533111, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.1590397} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29329524342895436, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.6466968110503561, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8257240641806338, "gear": 1, "accelerator_pedal_position": 0.29329524342895436, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.450958950687865, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.1590397} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.49995279312134, "x": 35.94364991917917, "y": -0.17255950935909414, "z": null, "yaw": 3.170053518827438, "pitch": null, "roll": null}, "v": 1.8075848174072195, "accelerator_pedal_position": 0.2944379223067683, "brake_pedal_position": 0.0, "acceleration": 0.26718414482572994, "steering_wheel_angle": -2.645607954532138, "front_wheel_angle": -0.12602778902438197, "heading_rate": -0.089460824533111, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.1790397} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29329524342895436, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.6466968110503561, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8334716457316518, "gear": 1, "accelerator_pedal_position": 0.29329524342895436, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.450958950687865, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.1790397} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502688.1990397, "x": 39.74345759630508, "y": 4.822223150545385, "z": null, "yaw": 3.164875931346321, "pitch": null, "roll": null}, "v": 1.8360497007955254, "accelerator_pedal_position": 0.29329524342895436, "brake_pedal_position": 0.0, "acceleration": 0.2575820013532749, "steering_wheel_angle": -2.450958950687865, "front_wheel_angle": -0.11642457962881146, "heading_rate": -0.0838798446540698, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.1990397} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.294545986640303, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.5294054567036064, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8360497007955254, "gear": 1, "accelerator_pedal_position": 0.29329524342895436, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.450958950687865, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.1990397} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.60995268821716, "x": 35.74345759630508, "y": -0.1777768494546148, "z": null, "yaw": 3.164875931346321, "pitch": null, "roll": null}, "v": 1.8360497007955254, "accelerator_pedal_position": 0.29329524342895436, "brake_pedal_position": 0.0, "acceleration": 0.2575820013532749, "steering_wheel_angle": -2.450958950687865, "front_wheel_angle": -0.11642457962881146, "heading_rate": -0.0838798446540698, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.2190397} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2942781492354546, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.5294054567036064, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8413553814518635, "gear": 1, "accelerator_pedal_position": 0.294545986640303, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.3730401984672156, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.2190397} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.60995268821716, "x": 35.74345759630508, "y": -0.1777768494546148, "z": null, "yaw": 3.164875931346321, "pitch": null, "roll": null}, "v": 1.8360497007955254, "accelerator_pedal_position": 0.29329524342895436, "brake_pedal_position": 0.0, "acceleration": 0.2575820013532749, "steering_wheel_angle": -2.450958950687865, "front_wheel_angle": -0.11642457962881146, "heading_rate": -0.0838798446540698, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.2390397} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2942781492354546, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.5294054567036064, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8492464654359404, "gear": 1, "accelerator_pedal_position": 0.2942781492354546, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.3340125479318177, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.2390397} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.60995268821716, "x": 35.74345759630508, "y": -0.1777768494546148, "z": null, "yaw": 3.164875931346321, "pitch": null, "roll": null}, "v": 1.8360497007955254, "accelerator_pedal_position": 0.29329524342895436, "brake_pedal_position": 0.0, "acceleration": 0.2575820013532749, "steering_wheel_angle": -2.450958950687865, "front_wheel_angle": -0.11642457962881146, "heading_rate": -0.0838798446540698, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.2590396} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2942781492354546, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.5294054567036064, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8518722552814455, "gear": 1, "accelerator_pedal_position": 0.2942781492354546, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.3340125479318177, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.2590396} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.60995268821716, "x": 35.74345759630508, "y": -0.1777768494546148, "z": null, "yaw": 3.164875931346321, "pitch": null, "roll": null}, "v": 1.8360497007955254, "accelerator_pedal_position": 0.29329524342895436, "brake_pedal_position": 0.0, "acceleration": 0.2575820013532749, "steering_wheel_angle": -2.450958950687865, "front_wheel_angle": -0.11642457962881146, "heading_rate": -0.0838798446540698, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.2790396} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2942781492354546, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.5294054567036064, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8597359188787814, "gear": 1, "accelerator_pedal_position": 0.2942781492354546, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.3340125479318177, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.2790396} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.60995268821716, "x": 35.74345759630508, "y": -0.1777768494546148, "z": null, "yaw": 3.164875931346321, "pitch": null, "roll": null}, "v": 1.8360497007955254, "accelerator_pedal_position": 0.29329524342895436, "brake_pedal_position": 0.0, "acceleration": 0.2575820013532749, "steering_wheel_angle": -2.450958950687865, "front_wheel_angle": -0.11642457962881146, "heading_rate": -0.0838798446540698, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.2990396} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2942781492354546, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.5294054567036064, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.862352573477761, "gear": 1, "accelerator_pedal_position": 0.2942781492354546, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.3340125479318177, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.2990396} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502688.3090396, "x": 39.54008758103605, "y": 4.817937941951472, "z": null, "yaw": 3.1600551101479155, "pitch": null, "roll": null}, "v": 1.8649669458074443, "accelerator_pedal_position": 0.2942781492354546, "brake_pedal_position": 0.0, "acceleration": 0.26120906834167545, "steering_wheel_angle": -2.3340125479318177, "front_wheel_angle": -0.11068191180466777, "heading_rate": -0.08096295521734155, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.3190396} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29462344722324824, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4163242328172074, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.867579036490861, "gear": 1, "accelerator_pedal_position": 0.2942781492354546, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.3340125479318177, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.3190396} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.71995258331299, "x": 35.54008758103605, "y": -0.18206205804852793, "z": null, "yaw": 3.1600551101479155, "pitch": null, "roll": null}, "v": 1.8649669458074443, "accelerator_pedal_position": 0.2942781492354546, "brake_pedal_position": 0.0, "acceleration": 0.26120906834167545, "steering_wheel_angle": -2.3340125479318177, "front_wheel_angle": -0.11068191180466777, "heading_rate": -0.08096295521734155, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.3390396} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2946413463289096, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4163242328172074, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8728395188118985, "gear": 1, "accelerator_pedal_position": 0.29462344722324824, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.2560713165382955, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.3390396} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.71995258331299, "x": 35.54008758103605, "y": -0.18206205804852793, "z": null, "yaw": 3.1600551101479155, "pitch": null, "roll": null}, "v": 1.8649669458074443, "accelerator_pedal_position": 0.2942781492354546, "brake_pedal_position": 0.0, "acceleration": 0.26120906834167545, "steering_wheel_angle": -2.3340125479318177, "front_wheel_angle": -0.11068191180466777, "heading_rate": -0.08096295521734155, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.3590395} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2946413463289096, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4163242328172074, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8780930430338243, "gear": 1, "accelerator_pedal_position": 0.2946413463289096, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.2170328628722777, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.3590395} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.71995258331299, "x": 35.54008758103605, "y": -0.18206205804852793, "z": null, "yaw": 3.1600551101479155, "pitch": null, "roll": null}, "v": 1.8649669458074443, "accelerator_pedal_position": 0.2942781492354546, "brake_pedal_position": 0.0, "acceleration": 0.26120906834167545, "steering_wheel_angle": -2.3340125479318177, "front_wheel_angle": -0.11068191180466777, "heading_rate": -0.08096295521734155, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.3790395} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2946413463289096, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4163242328172074, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8833373738752714, "gear": 1, "accelerator_pedal_position": 0.2946413463289096, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.2170328628722777, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.3790395} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.71995258331299, "x": 35.54008758103605, "y": -0.18206205804852793, "z": null, "yaw": 3.1600551101479155, "pitch": null, "roll": null}, "v": 1.8649669458074443, "accelerator_pedal_position": 0.2942781492354546, "brake_pedal_position": 0.0, "acceleration": 0.26120906834167545, "steering_wheel_angle": -2.3340125479318177, "front_wheel_angle": -0.11068191180466777, "heading_rate": -0.08096295521734155, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.3990395} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2946413463289096, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4163242328172074, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8885725164277691, "gear": 1, "accelerator_pedal_position": 0.2946413463289096, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.2170328628722777, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.3990395} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502688.4190395, "x": 39.33352609979971, "y": 4.814561542705868, "z": null, "yaw": 3.155460716914593, "pitch": null, "roll": null}, "v": 1.8937984758317072, "accelerator_pedal_position": 0.2946413463289096, "brake_pedal_position": 0.0, "acceleration": 0.2609537640934746, "steering_wheel_angle": -2.2170328628722777, "front_wheel_angle": -0.10495762889770956, "heading_rate": -0.07793035679955877, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.4190395} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2934775404176858, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2455386156618735, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.896408013472642, "gear": 1, "accelerator_pedal_position": 0.2946413463289096, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.2170328628722777, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.4190395} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.82995247840881, "x": 35.33352609979971, "y": -0.1854384572941319, "z": null, "yaw": 3.155460716914593, "pitch": null, "roll": null}, "v": 1.8937984758317072, "accelerator_pedal_position": 0.2946413463289096, "brake_pedal_position": 0.0, "acceleration": 0.2609537640934746, "steering_wheel_angle": -2.2170328628722777, "front_wheel_angle": -0.10495762889770956, "heading_rate": -0.07793035679955877, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.4390395} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2939674943902968, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2455386156618735, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.906624450293653, "gear": 1, "accelerator_pedal_position": 0.2939674943902968, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.061179089878834, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.4390395} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.82995247840881, "x": 35.33352609979971, "y": -0.1854384572941319, "z": null, "yaw": 3.155460716914593, "pitch": null, "roll": null}, "v": 1.8937984758317072, "accelerator_pedal_position": 0.2946413463289096, "brake_pedal_position": 0.0, "acceleration": 0.2609537640934746, "steering_wheel_angle": -2.2170328628722777, "front_wheel_angle": -0.10495762889770956, "heading_rate": -0.07793035679955877, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.4690394} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2939674943902968, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2455386156618735, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.906624450293653, "gear": 1, "accelerator_pedal_position": 0.2939674943902968, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.061179089878834, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.4690394} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.82995247840881, "x": 35.33352609979971, "y": -0.1854384572941319, "z": null, "yaw": 3.155460716914593, "pitch": null, "roll": null}, "v": 1.8937984758317072, "accelerator_pedal_position": 0.2946413463289096, "brake_pedal_position": 0.0, "acceleration": 0.2609537640934746, "steering_wheel_angle": -2.2170328628722777, "front_wheel_angle": -0.10495762889770956, "heading_rate": -0.07793035679955877, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.4890394} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2939674943902968, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2455386156618735, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.914286094144601, "gear": 1, "accelerator_pedal_position": 0.2939674943902968, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.061179089878834, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.4890394} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.82995247840881, "x": 35.33352609979971, "y": -0.1854384572941319, "z": null, "yaw": 3.155460716914593, "pitch": null, "roll": null}, "v": 1.8937984758317072, "accelerator_pedal_position": 0.2946413463289096, "brake_pedal_position": 0.0, "acceleration": 0.2609537640934746, "steering_wheel_angle": -2.2170328628722777, "front_wheel_angle": -0.10495762889770956, "heading_rate": -0.07793035679955877, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.5090394} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2939674943902968, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2455386156618735, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9168354703718986, "gear": 1, "accelerator_pedal_position": 0.2939674943902968, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.061179089878834, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.5090394} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502688.5290394, "x": 39.123813401798905, "y": 4.8120714128793916, "z": null, "yaw": 3.1511590265545477, "pitch": null, "roll": null}, "v": 1.921927469361164, "accelerator_pedal_position": 0.2939674943902968, "brake_pedal_position": 0.0, "acceleration": 0.2542624144964466, "steering_wheel_angle": -2.061179089878834, "front_wheel_angle": -0.09736183153816765, "heading_rate": -0.07332652099331632, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.5290394} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29403088714574593, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1137239466760775, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9244740555533442, "gear": 1, "accelerator_pedal_position": 0.29403088714574593, "brake_pedal_position": 0.0, "steering_wheel_angle": -2.022247150120725, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.5290394} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.93995237350464, "x": 35.123813401798905, "y": -0.18792858712060845, "z": null, "yaw": 3.1511590265545477, "pitch": null, "roll": null}, "v": 1.921927469361164, "accelerator_pedal_position": 0.2939674943902968, "brake_pedal_position": 0.0, "acceleration": 0.2542624144964466, "steering_wheel_angle": -2.061179089878834, "front_wheel_angle": -0.09736183153816765, "heading_rate": -0.07332652099331632, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.5490394} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29413506572700776, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1137239466760775, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9270183889331267, "gear": 1, "accelerator_pedal_position": 0.29403088714574593, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.98327074568462, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.5490394} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.93995237350464, "x": 35.123813401798905, "y": -0.18792858712060845, "z": null, "yaw": 3.1511590265545477, "pitch": null, "roll": null}, "v": 1.921927469361164, "accelerator_pedal_position": 0.2939674943902968, "brake_pedal_position": 0.0, "acceleration": 0.2542624144964466, "steering_wheel_angle": -2.061179089878834, "front_wheel_angle": -0.09736183153816765, "heading_rate": -0.07332652099331632, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.5690393} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29413506572700776, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1137239466760775, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9321133166031725, "gear": 1, "accelerator_pedal_position": 0.29413506572700776, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.9442498765705194, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.5690393} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.93995237350464, "x": 35.123813401798905, "y": -0.18792858712060845, "z": null, "yaw": 3.1511590265545477, "pitch": null, "roll": null}, "v": 1.921927469361164, "accelerator_pedal_position": 0.2939674943902968, "brake_pedal_position": 0.0, "acceleration": 0.2542624144964466, "steering_wheel_angle": -2.061179089878834, "front_wheel_angle": -0.09736183153816765, "heading_rate": -0.07332652099331632, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.5890393} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29413506572700776, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1137239466760775, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9371992183525, "gear": 1, "accelerator_pedal_position": 0.29413506572700776, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.9442498765705194, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.5890393} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.93995237350464, "x": 35.123813401798905, "y": -0.18792858712060845, "z": null, "yaw": 3.1511590265545477, "pitch": null, "roll": null}, "v": 1.921927469361164, "accelerator_pedal_position": 0.2939674943902968, "brake_pedal_position": 0.0, "acceleration": 0.2542624144964466, "steering_wheel_angle": -2.061179089878834, "front_wheel_angle": -0.09736183153816765, "heading_rate": -0.07332652099331632, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.6090393} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29413506572700776, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1137239466760775, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.94227609982901, "gear": 1, "accelerator_pedal_position": 0.29413506572700776, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.9442498765705194, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.6090393} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 49.93995237350464, "x": 35.123813401798905, "y": -0.18792858712060845, "z": null, "yaw": 3.1511590265545477, "pitch": null, "roll": null}, "v": 1.921927469361164, "accelerator_pedal_position": 0.2939674943902968, "brake_pedal_position": 0.0, "acceleration": 0.2542624144964466, "steering_wheel_angle": -2.061179089878834, "front_wheel_angle": -0.09736183153816765, "heading_rate": -0.07332652099331632, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.6290393} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29413506572700776, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1137239466760775, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9473439667255978, "gear": 1, "accelerator_pedal_position": 0.29413506572700776, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.9442498765705194, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.6290393} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502688.6390393, "x": 38.91100862753623, "y": 4.810426850383858, "z": null, "yaw": 3.147163585334509, "pitch": null, "roll": null}, "v": 1.9498745214976987, "accelerator_pedal_position": 0.29413506572700776, "brake_pedal_position": 0.0, "acceleration": 0.25283032822305473, "steering_wheel_angle": -1.9442498765705194, "front_wheel_angle": -0.09168589049959114, "heading_rate": -0.0700307110918112, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.6490393} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29558802245693416, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0450285171512055, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9524028247799292, "gear": 1, "accelerator_pedal_position": 0.29413506572700776, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.9442498765705194, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.6490393} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.049952268600464, "x": 34.91100862753623, "y": -0.1895731496161419, "z": null, "yaw": 3.147163585334509, "pitch": null, "roll": null}, "v": 1.9498745214976987, "accelerator_pedal_position": 0.29413506572700776, "brake_pedal_position": 0.0, "acceleration": 0.25283032822305473, "steering_wheel_angle": -1.9442498765705194, "front_wheel_angle": -0.09168589049959114, "heading_rate": -0.0700307110918112, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.6690392} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29525794361880736, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0450285171512055, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9576342184543973, "gear": 1, "accelerator_pedal_position": 0.29558802245693416, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.866223729501545, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.6690392} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.049952268600464, "x": 34.91100862753623, "y": -0.1895731496161419, "z": null, "yaw": 3.147163585334509, "pitch": null, "roll": null}, "v": 1.9498745214976987, "accelerator_pedal_position": 0.29413506572700776, "brake_pedal_position": 0.0, "acceleration": 0.25283032822305473, "steering_wheel_angle": -1.9442498765705194, "front_wheel_angle": -0.09168589049959114, "heading_rate": -0.0700307110918112, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.6890392} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29525794361880736, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0450285171512055, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9628150497147305, "gear": 1, "accelerator_pedal_position": 0.29525794361880736, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.866223729501545, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.6890392} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.049952268600464, "x": 34.91100862753623, "y": -0.1895731496161419, "z": null, "yaw": 3.147163585334509, "pitch": null, "roll": null}, "v": 1.9498745214976987, "accelerator_pedal_position": 0.29413506572700776, "brake_pedal_position": 0.0, "acceleration": 0.25283032822305473, "steering_wheel_angle": -1.9442498765705194, "front_wheel_angle": -0.09168589049959114, "heading_rate": -0.0700307110918112, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.7090392} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29525794361880736, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0450285171512055, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9679866393486838, "gear": 1, "accelerator_pedal_position": 0.29525794361880736, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.866223729501545, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.7090392} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.049952268600464, "x": 34.91100862753623, "y": -0.1895731496161419, "z": null, "yaw": 3.147163585334509, "pitch": null, "roll": null}, "v": 1.9498745214976987, "accelerator_pedal_position": 0.29413506572700776, "brake_pedal_position": 0.0, "acceleration": 0.25283032822305473, "steering_wheel_angle": -1.9442498765705194, "front_wheel_angle": -0.09168589049959114, "heading_rate": -0.0700307110918112, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.7290392} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29525794361880736, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0450285171512055, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9731489931482167, "gear": 1, "accelerator_pedal_position": 0.29525794361880736, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.866223729501545, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.7290392} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502688.7490392, "x": 38.69510227372672, "y": 4.809603412612841, "z": null, "yaw": 3.143339298949896, "pitch": null, "roll": null}, "v": 1.9783021169522192, "accelerator_pedal_position": 0.29525794361880736, "brake_pedal_position": 0.0, "acceleration": 0.2573102491105586, "steering_wheel_angle": -1.866223729501545, "front_wheel_angle": -0.0879091330537877, "heading_rate": -0.0681094564070379, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.7490392} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2950501648541503, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9060048620890677, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9783021169522192, "gear": 1, "accelerator_pedal_position": 0.29525794361880736, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.866223729501545, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.7490392} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.15995216369629, "x": 34.69510227372672, "y": -0.19039658738715914, "z": null, "yaw": 3.143339298949896, "pitch": null, "roll": null}, "v": 1.9783021169522192, "accelerator_pedal_position": 0.29525794361880736, "brake_pedal_position": 0.0, "acceleration": 0.2573102491105586, "steering_wheel_angle": -1.866223729501545, "front_wheel_angle": -0.0879091330537877, "heading_rate": -0.0681094564070379, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.7690392} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29524199914069416, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9060048620890677, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.983420055938563, "gear": 1, "accelerator_pedal_position": 0.2950501648541503, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.7883200028009507, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.7690392} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.15995216369629, "x": 34.69510227372672, "y": -0.19039658738715914, "z": null, "yaw": 3.143339298949896, "pitch": null, "roll": null}, "v": 1.9783021169522192, "accelerator_pedal_position": 0.29525794361880736, "brake_pedal_position": 0.0, "acceleration": 0.2573102491105586, "steering_wheel_angle": -1.866223729501545, "front_wheel_angle": -0.0879091330537877, "heading_rate": -0.0681094564070379, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.7890391} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29524199914069416, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9060048620890677, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9885527918387358, "gear": 1, "accelerator_pedal_position": 0.29524199914069416, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.710240447367367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.7890391} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.15995216369629, "x": 34.69510227372672, "y": -0.19039658738715914, "z": null, "yaw": 3.143339298949896, "pitch": null, "roll": null}, "v": 1.9783021169522192, "accelerator_pedal_position": 0.29525794361880736, "brake_pedal_position": 0.0, "acceleration": 0.2573102491105586, "steering_wheel_angle": -1.866223729501545, "front_wheel_angle": -0.0879091330537877, "heading_rate": -0.0681094564070379, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.809039} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29524199914069416, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9060048620890677, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9936763190861908, "gear": 1, "accelerator_pedal_position": 0.29524199914069416, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.710240447367367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.809039} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.15995216369629, "x": 34.69510227372672, "y": -0.19039658738715914, "z": null, "yaw": 3.143339298949896, "pitch": null, "roll": null}, "v": 1.9783021169522192, "accelerator_pedal_position": 0.29525794361880736, "brake_pedal_position": 0.0, "acceleration": 0.2573102491105586, "steering_wheel_angle": -1.866223729501545, "front_wheel_angle": -0.0879091330537877, "heading_rate": -0.0681094564070379, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.829039} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29524199914069416, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9060048620890677, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.001344356927397, "gear": 1, "accelerator_pedal_position": 0.29524199914069416, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.710240447367367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.829039} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.15995216369629, "x": 34.69510227372672, "y": -0.19039658738715914, "z": null, "yaw": 3.143339298949896, "pitch": null, "roll": null}, "v": 1.9783021169522192, "accelerator_pedal_position": 0.29525794361880736, "brake_pedal_position": 0.0, "acceleration": 0.2573102491105586, "steering_wheel_angle": -1.866223729501545, "front_wheel_angle": -0.0879091330537877, "heading_rate": -0.0681094564070379, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.849039} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29524199914069416, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9060048620890677, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.003895771771726, "gear": 1, "accelerator_pedal_position": 0.29524199914069416, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.710240447367367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.849039} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502688.859039, "x": 38.476080565423295, "y": 4.809579630493256, "z": null, "yaw": 3.139803823684501, "pitch": null, "roll": null}, "v": 2.006444889005721, "accelerator_pedal_position": 0.29524199914069416, "brake_pedal_position": 0.0, "acceleration": 0.2546820392528806, "steering_wheel_angle": -1.710240447367367, "front_wheel_angle": -0.08038452360066012, "heading_rate": -0.06313883265000647, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.869039} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29575973654584603, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7704568356398145, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.00899170939825, "gear": 1, "accelerator_pedal_position": 0.29524199914069416, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.710240447367367, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.869039} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.269952058792114, "x": 34.476080565423295, "y": -0.1904203695067439, "z": null, "yaw": 3.139803823684501, "pitch": null, "roll": null}, "v": 2.006444889005721, "accelerator_pedal_position": 0.29524199914069416, "brake_pedal_position": 0.0, "acceleration": 0.2546820392528806, "steering_wheel_angle": -1.710240447367367, "front_wheel_angle": -0.08038452360066012, "heading_rate": -0.06313883265000647, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.889039} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2957243714270224, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7704568356398145, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0141431507266274, "gear": 1, "accelerator_pedal_position": 0.29575973654584603, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.6322751884717082, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.889039} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.269952058792114, "x": 34.476080565423295, "y": -0.1904203695067439, "z": null, "yaw": 3.139803823684501, "pitch": null, "roll": null}, "v": 2.006444889005721, "accelerator_pedal_position": 0.29524199914069416, "brake_pedal_position": 0.0, "acceleration": 0.2546820392528806, "steering_wheel_angle": -1.710240447367367, "front_wheel_angle": -0.08038452360066012, "heading_rate": -0.06313883265000647, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.909039} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2957243714270224, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7704568356398145, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0192808785258656, "gear": 1, "accelerator_pedal_position": 0.2957243714270224, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.5932271107008547, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.909039} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.269952058792114, "x": 34.476080565423295, "y": -0.1904203695067439, "z": null, "yaw": 3.139803823684501, "pitch": null, "roll": null}, "v": 2.006444889005721, "accelerator_pedal_position": 0.29524199914069416, "brake_pedal_position": 0.0, "acceleration": 0.2546820392528806, "steering_wheel_angle": -1.710240447367367, "front_wheel_angle": -0.08038452360066012, "heading_rate": -0.06313883265000647, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.929039} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2957243714270224, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7704568356398145, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0244093256268303, "gear": 1, "accelerator_pedal_position": 0.2957243714270224, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.5932271107008547, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.929039} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.269952058792114, "x": 34.476080565423295, "y": -0.1904203695067439, "z": null, "yaw": 3.139803823684501, "pitch": null, "roll": null}, "v": 2.006444889005721, "accelerator_pedal_position": 0.29524199914069416, "brake_pedal_position": 0.0, "acceleration": 0.2546820392528806, "steering_wheel_angle": -1.710240447367367, "front_wheel_angle": -0.08038452360066012, "heading_rate": -0.06313883265000647, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.949039} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2957243714270224, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7704568356398145, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.029528498278374, "gear": 1, "accelerator_pedal_position": 0.2957243714270224, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.5932271107008547, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.949039} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502688.969039, "x": 38.25396206853528, "y": 4.810314645387885, "z": null, "yaw": 3.1365191135984665, "pitch": null, "roll": null}, "v": 2.0346384027750832, "accelerator_pedal_position": 0.2957243714270224, "brake_pedal_position": 0.0, "acceleration": 0.2551478669796643, "steering_wheel_angle": -1.5932271107008547, "front_wheel_angle": -0.07476196576259385, "heading_rate": -0.059530315259257685, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.969039} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29624791386599536, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6570970981282475, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0346384027750832, "gear": 1, "accelerator_pedal_position": 0.2957243714270224, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.5932271107008547, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.969039} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.37995195388794, "x": 34.25396206853528, "y": -0.18968535461211466, "z": null, "yaw": 3.1365191135984665, "pitch": null, "roll": null}, "v": 2.0346384027750832, "accelerator_pedal_position": 0.2957243714270224, "brake_pedal_position": 0.0, "acceleration": 0.2551478669796643, "steering_wheel_angle": -1.5932271107008547, "front_wheel_angle": -0.07476196576259385, "heading_rate": -0.059530315259257685, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502688.989039} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2962117567832483, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6570970981282475, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0398044585691615, "gear": 1, "accelerator_pedal_position": 0.29624791386599536, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.5152410367229452, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502688.989039} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.37995195388794, "x": 34.25396206853528, "y": -0.18968535461211466, "z": null, "yaw": 3.1365191135984665, "pitch": null, "roll": null}, "v": 2.0346384027750832, "accelerator_pedal_position": 0.2957243714270224, "brake_pedal_position": 0.0, "acceleration": 0.2551478669796643, "steering_wheel_angle": -1.5932271107008547, "front_wheel_angle": -0.07476196576259385, "heading_rate": -0.059530315259257685, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.009039} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2962117567832483, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6570970981282475, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0449566225540967, "gear": 1, "accelerator_pedal_position": 0.2962117567832483, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.47618295357009, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.009039} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.37995195388794, "x": 34.25396206853528, "y": -0.18968535461211466, "z": null, "yaw": 3.1365191135984665, "pitch": null, "roll": null}, "v": 2.0346384027750832, "accelerator_pedal_position": 0.2957243714270224, "brake_pedal_position": 0.0, "acceleration": 0.2551478669796643, "steering_wheel_angle": -1.5932271107008547, "front_wheel_angle": -0.07476196576259385, "heading_rate": -0.059530315259257685, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.029039} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2962117567832483, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6570970981282475, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.050099426904627, "gear": 1, "accelerator_pedal_position": 0.2962117567832483, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.47618295357009, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.029039} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.37995195388794, "x": 34.25396206853528, "y": -0.18968535461211466, "z": null, "yaw": 3.1365191135984665, "pitch": null, "roll": null}, "v": 2.0346384027750832, "accelerator_pedal_position": 0.2957243714270224, "brake_pedal_position": 0.0, "acceleration": 0.2551478669796643, "steering_wheel_angle": -1.5932271107008547, "front_wheel_angle": -0.07476196576259385, "heading_rate": -0.059530315259257685, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.049039} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2962117567832483, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6570970981282475, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0552328780492872, "gear": 1, "accelerator_pedal_position": 0.2962117567832483, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.47618295357009, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.049039} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.37995195388794, "x": 34.25396206853528, "y": -0.18968535461211466, "z": null, "yaw": 3.1365191135984665, "pitch": null, "roll": null}, "v": 2.0346384027750832, "accelerator_pedal_position": 0.2957243714270224, "brake_pedal_position": 0.0, "acceleration": 0.2551478669796643, "steering_wheel_angle": -1.5932271107008547, "front_wheel_angle": -0.07476196576259385, "heading_rate": -0.059530315259257685, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.0690389} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2962117567832483, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6570970981282475, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.060356982462599, "gear": 1, "accelerator_pedal_position": 0.2962117567832483, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.47618295357009, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.0690389} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502689.0790389, "x": 38.02874000583172, "y": 4.811771221091385, "z": null, "yaw": 3.1334987750664545, "pitch": null, "roll": null}, "v": 2.0629155316808023, "accelerator_pedal_position": 0.2962117567832483, "brake_pedal_position": 0.0, "acceleration": 0.25562149840276277, "steering_wheel_angle": -1.47618295357009, "front_wheel_angle": -0.06915670895742594, "heading_rate": -0.055817313685909385, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.0890388} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29660748283908617, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5517068274350262, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.06547174666483, "gear": 1, "accelerator_pedal_position": 0.2962117567832483, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.47618295357009, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.0890388} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.489951848983765, "x": 34.02874000583172, "y": -0.18822877890861456, "z": null, "yaw": 3.1334987750664545, "pitch": null, "roll": null}, "v": 2.0629155316808023, "accelerator_pedal_position": 0.2962117567832483, "brake_pedal_position": 0.0, "acceleration": 0.25562149840276277, "steering_wheel_angle": -1.47618295357009, "front_wheel_angle": -0.06915670895742594, "heading_rate": -0.055817313685909385, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.1090388} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29661244480255583, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5517068274350262, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.070626620382588, "gear": 1, "accelerator_pedal_position": 0.29660748283908617, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.3981594863883593, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.1090388} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.489951848983765, "x": 34.02874000583172, "y": -0.18822877890861456, "z": null, "yaw": 3.1334987750664545, "pitch": null, "roll": null}, "v": 2.0629155316808023, "accelerator_pedal_position": 0.2962117567832483, "brake_pedal_position": 0.0, "acceleration": 0.25562149840276277, "steering_wheel_angle": -1.47618295357009, "front_wheel_angle": -0.06915670895742594, "heading_rate": -0.055817313685909385, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.1290388} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29661244480255583, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5517068274350262, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0757726966245107, "gear": 1, "accelerator_pedal_position": 0.29661244480255583, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.3981594863883593, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.1290388} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.489951848983765, "x": 34.02874000583172, "y": -0.18822877890861456, "z": null, "yaw": 3.1334987750664545, "pitch": null, "roll": null}, "v": 2.0629155316808023, "accelerator_pedal_position": 0.2962117567832483, "brake_pedal_position": 0.0, "acceleration": 0.25562149840276277, "steering_wheel_angle": -1.47618295357009, "front_wheel_angle": -0.06915670895742594, "heading_rate": -0.055817313685909385, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.1490388} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29661244480255583, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5517068274350262, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.080909360913244, "gear": 1, "accelerator_pedal_position": 0.29661244480255583, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.3981594863883593, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.1490388} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.489951848983765, "x": 34.02874000583172, "y": -0.18822877890861456, "z": null, "yaw": 3.1334987750664545, "pitch": null, "roll": null}, "v": 2.0629155316808023, "accelerator_pedal_position": 0.2962117567832483, "brake_pedal_position": 0.0, "acceleration": 0.25562149840276277, "steering_wheel_angle": -1.47618295357009, "front_wheel_angle": -0.06915670895742594, "heading_rate": -0.055817313685909385, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.1690388} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29661244480255583, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5517068274350262, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0860366199135494, "gear": 1, "accelerator_pedal_position": 0.29661244480255583, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.3981594863883593, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.1690388} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502689.1890388, "x": 37.800416217154975, "y": 4.813919221746631, "z": null, "yaw": 3.130646736140144, "pitch": null, "roll": null}, "v": 2.091154480335917, "accelerator_pedal_position": 0.29661244480255583, "brake_pedal_position": 0.0, "acceleration": 0.25554078539288827, "steering_wheel_angle": -1.3981594863883593, "front_wheel_angle": -0.065430499280994, "heading_rate": -0.053523778593964955, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.1890388} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2974969823913044, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.46083181126322786, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.091154480335917, "gear": 1, "accelerator_pedal_position": 0.29661244480255583, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.3981594863883593, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.1890388} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.59995174407959, "x": 33.800416217154975, "y": -0.18608077825336888, "z": null, "yaw": 3.130646736140144, "pitch": null, "roll": null}, "v": 2.091154480335917, "accelerator_pedal_position": 0.29661244480255583, "brake_pedal_position": 0.0, "acceleration": 0.25554078539288827, "steering_wheel_angle": -1.3981594863883593, "front_wheel_angle": -0.065430499280994, "heading_rate": -0.053523778593964955, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.2090387} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2973498149548573, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.46083181126322786, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.096373465343245, "gear": 1, "accelerator_pedal_position": 0.2974969823913044, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.320154555830319, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.2090387} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.59995174407959, "x": 33.800416217154975, "y": -0.18608077825336888, "z": null, "yaw": 3.130646736140144, "pitch": null, "roll": null}, "v": 2.091154480335917, "accelerator_pedal_position": 0.29661244480255583, "brake_pedal_position": 0.0, "acceleration": 0.25554078539288827, "steering_wheel_angle": -1.3981594863883593, "front_wheel_angle": -0.065430499280994, "heading_rate": -0.053523778593964955, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.2290387} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2973498149548573, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.46083181126322786, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1015644746524904, "gear": 1, "accelerator_pedal_position": 0.2973498149548573, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.28108772910245, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.2290387} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.59995174407959, "x": 33.800416217154975, "y": -0.18608077825336888, "z": null, "yaw": 3.130646736140144, "pitch": null, "roll": null}, "v": 2.091154480335917, "accelerator_pedal_position": 0.29661244480255583, "brake_pedal_position": 0.0, "acceleration": 0.25554078539288827, "steering_wheel_angle": -1.3981594863883593, "front_wheel_angle": -0.065430499280994, "heading_rate": -0.053523778593964955, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.2490387} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2973498149548573, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.46083181126322786, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1067459363462007, "gear": 1, "accelerator_pedal_position": 0.2973498149548573, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.28108772910245, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.2490387} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.59995174407959, "x": 33.800416217154975, "y": -0.18608077825336888, "z": null, "yaw": 3.130646736140144, "pitch": null, "roll": null}, "v": 2.091154480335917, "accelerator_pedal_position": 0.29661244480255583, "brake_pedal_position": 0.0, "acceleration": 0.25554078539288827, "steering_wheel_angle": -1.3981594863883593, "front_wheel_angle": -0.065430499280994, "heading_rate": -0.053523778593964955, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.2690387} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2973498149548573, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.46083181126322786, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1119178572508472, "gear": 1, "accelerator_pedal_position": 0.2973498149548573, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.28108772910245, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.2690387} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.59995174407959, "x": 33.800416217154975, "y": -0.18608077825336888, "z": null, "yaw": 3.130646736140144, "pitch": null, "roll": null}, "v": 2.091154480335917, "accelerator_pedal_position": 0.29661244480255583, "brake_pedal_position": 0.0, "acceleration": 0.25554078539288827, "steering_wheel_angle": -1.3981594863883593, "front_wheel_angle": -0.065430499280994, "heading_rate": -0.053523778593964955, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.2890387} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2973498149548573, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.46083181126322786, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1170802442396104, "gear": 1, "accelerator_pedal_position": 0.2973498149548573, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.28108772910245, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.2890387} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502689.2990386, "x": 37.56897776872049, "y": 4.816732813650203, "z": null, "yaw": 3.128028045401894, "pitch": null, "roll": null}, "v": 2.1196578646761144, "accelerator_pedal_position": 0.2973498149548573, "brake_pedal_position": 0.0, "acceleration": 0.2575239556012192, "steering_wheel_angle": -1.28108772910245, "front_wheel_angle": -0.059854822679091375, "heading_rate": -0.04961854425630035, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.3090386} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2982589081304502, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.33125075809187166, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1222331042321265, "gear": 1, "accelerator_pedal_position": 0.2973498149548573, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.28108772910245, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.3090386} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.709951639175415, "x": 33.56897776872049, "y": -0.18326718634979677, "z": null, "yaw": 3.128028045401894, "pitch": null, "roll": null}, "v": 2.1196578646761144, "accelerator_pedal_position": 0.2973498149548573, "brake_pedal_position": 0.0, "acceleration": 0.2575239556012192, "steering_wheel_angle": -1.28108772910245, "front_wheel_angle": -0.059854822679091375, "heading_rate": -0.04961854425630035, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.3290386} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2981060860750571, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.33125075809187166, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1274900282861187, "gear": 1, "accelerator_pedal_position": 0.2982589081304502, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.2030962015667142, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.3290386} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.709951639175415, "x": 33.56897776872049, "y": -0.18326718634979677, "z": null, "yaw": 3.128028045401894, "pitch": null, "roll": null}, "v": 2.1196578646761144, "accelerator_pedal_position": 0.2973498149548573, "brake_pedal_position": 0.0, "acceleration": 0.2575239556012192, "steering_wheel_angle": -1.28108772910245, "front_wheel_angle": -0.059854822679091375, "heading_rate": -0.04961854425630035, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.3490386} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2981060860750571, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.33125075809187166, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1327181351475617, "gear": 1, "accelerator_pedal_position": 0.2981060860750571, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1640365205761185, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.3490386} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.709951639175415, "x": 33.56897776872049, "y": -0.18326718634979677, "z": null, "yaw": 3.128028045401894, "pitch": null, "roll": null}, "v": 2.1196578646761144, "accelerator_pedal_position": 0.2973498149548573, "brake_pedal_position": 0.0, "acceleration": 0.2575239556012192, "steering_wheel_angle": -1.28108772910245, "front_wheel_angle": -0.059854822679091375, "heading_rate": -0.04961854425630035, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.3690386} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2981060860750571, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.33125075809187166, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1379365610911, "gear": 1, "accelerator_pedal_position": 0.2981060860750571, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1640365205761185, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.3690386} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.709951639175415, "x": 33.56897776872049, "y": -0.18326718634979677, "z": null, "yaw": 3.128028045401894, "pitch": null, "roll": null}, "v": 2.1196578646761144, "accelerator_pedal_position": 0.2973498149548573, "brake_pedal_position": 0.0, "acceleration": 0.2575239556012192, "steering_wheel_angle": -1.28108772910245, "front_wheel_angle": -0.059854822679091375, "heading_rate": -0.04961854425630035, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.3890386} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2981060860750571, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.33125075809187166, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1431453131552094, "gear": 1, "accelerator_pedal_position": 0.2981060860750571, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1640365205761185, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.3890386} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502689.4090385, "x": 37.33440544908093, "y": 4.820176962590474, "z": null, "yaw": 3.125627290703294, "pitch": null, "roll": null}, "v": 2.14834439842585, "accelerator_pedal_position": 0.2981060860750571, "brake_pedal_position": 0.0, "acceleration": 0.25959198150533713, "steering_wheel_angle": -1.1640365205761185, "front_wheel_angle": -0.05429842120150911, "heading_rate": -0.045611908799266965, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.4090385} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29836399956769866, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.2598740965266701, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.14834439842585, "gear": 1, "accelerator_pedal_position": 0.2981060860750571, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.1640365205761185, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.4090385} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.81995153427124, "x": 33.33440544908093, "y": -0.179823037409526, "z": null, "yaw": 3.125627290703294, "pitch": null, "roll": null}, "v": 2.14834439842585, "accelerator_pedal_position": 0.2981060860750571, "brake_pedal_position": 0.0, "acceleration": 0.25959198150533713, "steering_wheel_angle": -1.1640365205761185, "front_wheel_angle": -0.05429842120150911, "heading_rate": -0.045611908799266965, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.4290385} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29841633506541854, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.2598740965266701, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.153566048228511, "gear": 1, "accelerator_pedal_position": 0.29836399956769866, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.0859378039822096, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.4290385} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.81995153427124, "x": 33.33440544908093, "y": -0.179823037409526, "z": null, "yaw": 3.125627290703294, "pitch": null, "roll": null}, "v": 2.14834439842585, "accelerator_pedal_position": 0.2981060860750571, "brake_pedal_position": 0.0, "acceleration": 0.25959198150533713, "steering_wheel_angle": -1.1640365205761185, "front_wheel_angle": -0.05429842120150911, "heading_rate": -0.045611908799266965, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.4490385} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29841633506541854, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.2598740965266701, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1587845244538784, "gear": 1, "accelerator_pedal_position": 0.29841633506541854, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.0859378039822096, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.4490385} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.81995153427124, "x": 33.33440544908093, "y": -0.179823037409526, "z": null, "yaw": 3.125627290703294, "pitch": null, "roll": null}, "v": 2.14834439842585, "accelerator_pedal_position": 0.2981060860750571, "brake_pedal_position": 0.0, "acceleration": 0.25959198150533713, "steering_wheel_angle": -1.1640365205761185, "front_wheel_angle": -0.05429842120150911, "heading_rate": -0.045611908799266965, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.4690385} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29841633506541854, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.2598740965266701, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1639932832292414, "gear": 1, "accelerator_pedal_position": 0.29841633506541854, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.0859378039822096, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.4690385} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.81995153427124, "x": 33.33440544908093, "y": -0.179823037409526, "z": null, "yaw": 3.125627290703294, "pitch": null, "roll": null}, "v": 2.14834439842585, "accelerator_pedal_position": 0.2981060860750571, "brake_pedal_position": 0.0, "acceleration": 0.25959198150533713, "steering_wheel_angle": -1.1640365205761185, "front_wheel_angle": -0.05429842120150911, "heading_rate": -0.045611908799266965, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.4890385} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29841633506541854, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.2598740965266701, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1691923318022877, "gear": 1, "accelerator_pedal_position": 0.29841633506541854, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.0859378039822096, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.4890385} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.81995153427124, "x": 33.33440544908093, "y": -0.179823037409526, "z": null, "yaw": 3.125627290703294, "pitch": null, "roll": null}, "v": 2.14834439842585, "accelerator_pedal_position": 0.2981060860750571, "brake_pedal_position": 0.0, "acceleration": 0.25959198150533713, "steering_wheel_angle": -1.1640365205761185, "front_wheel_angle": -0.05429842120150911, "heading_rate": -0.045611908799266965, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.5090384} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29841633506541854, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.2598740965266701, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.174381677467841, "gear": 1, "accelerator_pedal_position": 0.29841633506541854, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.0859378039822096, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.5090384} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502689.5190384, "x": 37.096688077958035, "y": 4.824212840268965, "z": null, "yaw": 3.1234294412578274, "pitch": null, "roll": null}, "v": 2.1769727140027646, "accelerator_pedal_position": 0.29841633506541854, "brake_pedal_position": 0.0, "acceleration": 0.25886135648360187, "steering_wheel_angle": -1.0859378039822096, "front_wheel_angle": -0.05060117503820693, "heading_rate": -0.043066989177701666, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.5290384} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2991992116450804, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.16558050045049277, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1795613275676007, "gear": 1, "accelerator_pedal_position": 0.29841633506541854, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.0859378039822096, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.5290384} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.929951429367065, "x": 33.096688077958035, "y": -0.1757871597310352, "z": null, "yaw": 3.1234294412578274, "pitch": null, "roll": null}, "v": 2.1769727140027646, "accelerator_pedal_position": 0.29841633506541854, "brake_pedal_position": 0.0, "acceleration": 0.25886135648360187, "steering_wheel_angle": -1.0859378039822096, "front_wheel_angle": -0.05060117503820693, "heading_rate": -0.043066989177701666, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.5490384} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29908804670162537, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.16558050045049277, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1848291032428047, "gear": 1, "accelerator_pedal_position": 0.2991992116450804, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.0078645733021616, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.5490384} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.929951429367065, "x": 33.096688077958035, "y": -0.1757871597310352, "z": null, "yaw": 3.1234294412578274, "pitch": null, "roll": null}, "v": 2.1769727140027646, "accelerator_pedal_position": 0.29841633506541854, "brake_pedal_position": 0.0, "acceleration": 0.25886135648360187, "steering_wheel_angle": -1.0859378039822096, "front_wheel_angle": -0.05060117503820693, "heading_rate": -0.043066989177701666, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.5690384} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29908804670162537, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.16558050045049277, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1900731257603194, "gear": 1, "accelerator_pedal_position": 0.29908804670162537, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.0078645733021616, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.5690384} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.929951429367065, "x": 33.096688077958035, "y": -0.1757871597310352, "z": null, "yaw": 3.1234294412578274, "pitch": null, "roll": null}, "v": 2.1769727140027646, "accelerator_pedal_position": 0.29841633506541854, "brake_pedal_position": 0.0, "acceleration": 0.25886135648360187, "steering_wheel_angle": -1.0859378039822096, "front_wheel_angle": -0.05060117503820693, "heading_rate": -0.043066989177701666, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.5890384} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29908804670162537, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.16558050045049277, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.195307317700953, "gear": 1, "accelerator_pedal_position": 0.29908804670162537, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.0078645733021616, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.5890384} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 50.929951429367065, "x": 33.096688077958035, "y": -0.1757871597310352, "z": null, "yaw": 3.1234294412578274, "pitch": null, "roll": null}, "v": 2.1769727140027646, "accelerator_pedal_position": 0.29841633506541854, "brake_pedal_position": 0.0, "acceleration": 0.25886135648360187, "steering_wheel_angle": -1.0859378039822096, "front_wheel_angle": -0.05060117503820693, "heading_rate": -0.043066989177701666, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.6090384} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29908804670162537, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.16558050045049277, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2005316865397875, "gear": 1, "accelerator_pedal_position": 0.29908804670162537, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.0078645733021616, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.6090384} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502689.6290383, "x": 36.85582535440744, "y": 4.828816907906975, "z": null, "yaw": 3.1213760609101637, "pitch": null, "roll": null}, "v": 2.2057462397995287, "accelerator_pedal_position": 0.29908804670162537, "brake_pedal_position": 0.0, "acceleration": 0.2603598151512844, "steering_wheel_angle": -1.0078645733021616, "front_wheel_angle": -0.04691314383268309, "heading_rate": -0.04045096515669039, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.6290383} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.299639090641227, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.08252677164855855, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2057462397995287, "gear": 1, "accelerator_pedal_position": 0.29908804670162537, "brake_pedal_position": 0.0, "steering_wheel_angle": -1.0078645733021616, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.6290383} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.03995132446289, "x": 32.85582535440744, "y": -0.17118309209302485, "z": null, "yaw": 3.1213760609101637, "pitch": null, "roll": null}, "v": 2.2057462397995287, "accelerator_pedal_position": 0.29908804670162537, "brake_pedal_position": 0.0, "acceleration": 0.2603598151512844, "steering_wheel_angle": -1.0078645733021616, "front_wheel_angle": -0.04691314383268309, "heading_rate": -0.04045096515669039, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.6490383} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2996018763386324, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.08252677164855855, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2110198331112256, "gear": 1, "accelerator_pedal_position": 0.299639090641227, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.9297935599174404, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.6490383} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.03995132446289, "x": 32.85582535440744, "y": -0.17118309209302485, "z": null, "yaw": 3.1213760609101637, "pitch": null, "roll": null}, "v": 2.2057462397995287, "accelerator_pedal_position": 0.29908804670162537, "brake_pedal_position": 0.0, "acceleration": 0.2603598151512844, "steering_wheel_angle": -1.0078645733021616, "front_wheel_angle": -0.04691314383268309, "heading_rate": -0.04045096515669039, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.6690383} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2996018763386324, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.08252677164855855, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.216278846688106, "gear": 1, "accelerator_pedal_position": 0.2996018763386324, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.9297935599174404, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.6690383} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.03995132446289, "x": 32.85582535440744, "y": -0.17118309209302485, "z": null, "yaw": 3.1213760609101637, "pitch": null, "roll": null}, "v": 2.2057462397995287, "accelerator_pedal_position": 0.29908804670162537, "brake_pedal_position": 0.0, "acceleration": 0.2603598151512844, "steering_wheel_angle": -1.0078645733021616, "front_wheel_angle": -0.04691314383268309, "heading_rate": -0.04045096515669039, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.6890383} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2996018763386324, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.08252677164855855, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2215279465187168, "gear": 1, "accelerator_pedal_position": 0.2996018763386324, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.9297935599174404, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.6890383} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.03995132446289, "x": 32.85582535440744, "y": -0.17118309209302485, "z": null, "yaw": 3.1213760609101637, "pitch": null, "roll": null}, "v": 2.2057462397995287, "accelerator_pedal_position": 0.29908804670162537, "brake_pedal_position": 0.0, "acceleration": 0.2603598151512844, "steering_wheel_angle": -1.0078645733021616, "front_wheel_angle": -0.04691314383268309, "heading_rate": -0.04045096515669039, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.7090383} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2996018763386324, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.08252677164855855, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2267671402754026, "gear": 1, "accelerator_pedal_position": 0.2996018763386324, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.9297935599174404, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.7090383} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.03995132446289, "x": 32.85582535440744, "y": -0.17118309209302485, "z": null, "yaw": 3.1213760609101637, "pitch": null, "roll": null}, "v": 2.2057462397995287, "accelerator_pedal_position": 0.29908804670162537, "brake_pedal_position": 0.0, "acceleration": 0.2603598151512844, "steering_wheel_angle": -1.0078645733021616, "front_wheel_angle": -0.04691314383268309, "heading_rate": -0.04045096515669039, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.7290382} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2996018763386324, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.08252677164855855, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.231996435678379, "gear": 1, "accelerator_pedal_position": 0.2996018763386324, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.9297935599174404, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.7290382} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502689.7390382, "x": 36.61180155334639, "y": 4.8339623063422, "z": null, "yaw": 3.1194956216471166, "pitch": null, "roll": null}, "v": 2.234607373922816, "accelerator_pedal_position": 0.2996018763386324, "brake_pedal_position": 0.0, "acceleration": 0.26084665726440937, "steering_wheel_angle": -0.9297935599174404, "front_wheel_angle": -0.04323317233863132, "heading_rate": -0.037761485040426535, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.7490382} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2992638463076245, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.013950478411688519, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.23721584049546, "gear": 1, "accelerator_pedal_position": 0.2996018763386324, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.9297935599174404, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.7490382} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.149951219558716, "x": 32.61180155334639, "y": -0.16603769365779986, "z": null, "yaw": 3.1194956216471166, "pitch": null, "roll": null}, "v": 2.234607373922816, "accelerator_pedal_position": 0.2996018763386324, "brake_pedal_position": 0.0, "acceleration": 0.26084665726440937, "steering_wheel_angle": -0.9297935599174404, "front_wheel_angle": -0.04323317233863132, "heading_rate": -0.037761485040426535, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.7690382} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29950571050680147, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.013950478411688519, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2423831288153933, "gear": 1, "accelerator_pedal_position": 0.2992638463076245, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.8516603706092979, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.7690382} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.149951219558716, "x": 32.61180155334639, "y": -0.16603769365779986, "z": null, "yaw": 3.1194956216471166, "pitch": null, "roll": null}, "v": 2.234607373922816, "accelerator_pedal_position": 0.2996018763386324, "brake_pedal_position": 0.0, "acceleration": 0.26084665726440937, "steering_wheel_angle": -0.9297935599174404, "front_wheel_angle": -0.04323317233863132, "heading_rate": -0.037761485040426535, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.7890382} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29950571050680147, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.013950478411688519, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2475708410277138, "gear": 1, "accelerator_pedal_position": 0.29950571050680147, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.8516603706092979, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.7890382} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.149951219558716, "x": 32.61180155334639, "y": -0.16603769365779986, "z": null, "yaw": 3.1194956216471166, "pitch": null, "roll": null}, "v": 2.234607373922816, "accelerator_pedal_position": 0.2996018763386324, "brake_pedal_position": 0.0, "acceleration": 0.26084665726440937, "steering_wheel_angle": -0.9297935599174404, "front_wheel_angle": -0.04323317233863132, "heading_rate": -0.037761485040426535, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.8090382} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29950571050680147, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.013950478411688519, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2527487089946208, "gear": 1, "accelerator_pedal_position": 0.29950571050680147, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.8516603706092979, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.8090382} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.149951219558716, "x": 32.61180155334639, "y": -0.16603769365779986, "z": null, "yaw": 3.1194956216471166, "pitch": null, "roll": null}, "v": 2.234607373922816, "accelerator_pedal_position": 0.2996018763386324, "brake_pedal_position": 0.0, "acceleration": 0.26084665726440937, "steering_wheel_angle": -0.9297935599174404, "front_wheel_angle": -0.04323317233863132, "heading_rate": -0.037761485040426535, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.8290381} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.29950571050680147, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.013950478411688519, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.257916740677601, "gear": 1, "accelerator_pedal_position": 0.29950571050680147, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.8516603706092979, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.8290381} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502689.8490381, "x": 36.36463428162872, "y": 4.839623904725449, "z": null, "yaw": 3.1177590191550646, "pitch": null, "roll": null}, "v": 2.263074944084088, "accelerator_pedal_position": 0.29950571050680147, "brake_pedal_position": 0.0, "acceleration": 0.25754186143789276, "steering_wheel_angle": -0.8516603706092979, "front_wheel_angle": -0.039558183140319454, "heading_rate": -0.03498822621099057, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.8490381} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2863935316019894, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.08067060374779401, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.263074944084088, "gear": 1, "accelerator_pedal_position": 0.29950571050680147, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.8516603706092979, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.8490381} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.25995111465454, "x": 32.36463428162872, "y": -0.1603760952745512, "z": null, "yaw": 3.1177590191550646, "pitch": null, "roll": null}, "v": 2.263074944084088, "accelerator_pedal_position": 0.29950571050680147, "brake_pedal_position": 0.0, "acceleration": 0.25754186143789276, "steering_wheel_angle": -0.8516603706092979, "front_wheel_angle": -0.039558183140319454, "heading_rate": -0.03498822621099057, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.869038} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2906262782538268, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.08067060374779401, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2665850859376837, "gear": 1, "accelerator_pedal_position": 0.2863935316019894, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.773174338464776, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.869038} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.25995111465454, "x": 32.36463428162872, "y": -0.1603760952745512, "z": null, "yaw": 3.1177590191550646, "pitch": null, "roll": null}, "v": 2.263074944084088, "accelerator_pedal_position": 0.29950571050680147, "brake_pedal_position": 0.0, "acceleration": 0.25754186143789276, "steering_wheel_angle": -0.8516603706092979, "front_wheel_angle": -0.039558183140319454, "heading_rate": -0.03498822621099057, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.889038} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2906262782538268, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.08067060374779401, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.270617380691857, "gear": 1, "accelerator_pedal_position": 0.2906262782538268, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.773174338464776, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.889038} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.25995111465454, "x": 32.36463428162872, "y": -0.1603760952745512, "z": null, "yaw": 3.1177590191550646, "pitch": null, "roll": null}, "v": 2.263074944084088, "accelerator_pedal_position": 0.29950571050680147, "brake_pedal_position": 0.0, "acceleration": 0.25754186143789276, "steering_wheel_angle": -0.8516603706092979, "front_wheel_angle": -0.039558183140319454, "heading_rate": -0.03498822621099057, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.909038} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2906262782538268, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.08067060374779401, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.274641986127824, "gear": 1, "accelerator_pedal_position": 0.2906262782538268, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.773174338464776, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.909038} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.25995111465454, "x": 32.36463428162872, "y": -0.1603760952745512, "z": null, "yaw": 3.1177590191550646, "pitch": null, "roll": null}, "v": 2.263074944084088, "accelerator_pedal_position": 0.29950571050680147, "brake_pedal_position": 0.0, "acceleration": 0.25754186143789276, "steering_wheel_angle": -0.8516603706092979, "front_wheel_angle": -0.039558183140319454, "heading_rate": -0.03498822621099057, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.929038} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2906262782538268, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.08067060374779401, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.278658910432715, "gear": 1, "accelerator_pedal_position": 0.2906262782538268, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.773174338464776, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.929038} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.25995111465454, "x": 32.36463428162872, "y": -0.1603760952745512, "z": null, "yaw": 3.1177590191550646, "pitch": null, "roll": null}, "v": 2.263074944084088, "accelerator_pedal_position": 0.29950571050680147, "brake_pedal_position": 0.0, "acceleration": 0.25754186143789276, "steering_wheel_angle": -0.8516603706092979, "front_wheel_angle": -0.039558183140319454, "heading_rate": -0.03498822621099057, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.949038} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2906262782538268, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.08067060374779401, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2826681618151046, "gear": 1, "accelerator_pedal_position": 0.2906262782538268, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.773174338464776, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.949038} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502689.959038, "x": 36.11471340858202, "y": 4.845761904140923, "z": null, "yaw": 3.116195260150512, "pitch": null, "roll": null}, "v": 2.2846699127313648, "accelerator_pedal_position": 0.2906262782538268, "brake_pedal_position": 0.0, "acceleration": 0.19998357734844985, "steering_wheel_angle": -0.773174338464776, "front_wheel_angle": -0.03587451665462896, "heading_rate": -0.032029924951956584, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.969038} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.276685337379066, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.155133746033362, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.286669748504849, "gear": 1, "accelerator_pedal_position": 0.2906262782538268, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.773174338464776, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.969038} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.369951009750366, "x": 32.11471340858202, "y": -0.15423809585907744, "z": null, "yaw": 3.116195260150512, "pitch": null, "roll": null}, "v": 2.2846699127313648, "accelerator_pedal_position": 0.2906262782538268, "brake_pedal_position": 0.0, "acceleration": 0.19998357734844985, "steering_wheel_angle": -0.773174338464776, "front_wheel_angle": -0.03587451665462896, "heading_rate": -0.032029924951956584, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502689.989038} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2811449759518132, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.155133746033362, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.288921895549319, "gear": 1, "accelerator_pedal_position": 0.276685337379066, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.694364878610045, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502689.989038} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.369951009750366, "x": 32.11471340858202, "y": -0.15423809585907744, "z": null, "yaw": 3.116195260150512, "pitch": null, "roll": null}, "v": 2.2846699127313648, "accelerator_pedal_position": 0.2906262782538268, "brake_pedal_position": 0.0, "acceleration": 0.19998357734844985, "steering_wheel_angle": -0.773174338464776, "front_wheel_angle": -0.03587451665462896, "heading_rate": -0.032029924951956584, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.009038} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2811449759518132, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.155133746033362, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.291726918814635, "gear": 1, "accelerator_pedal_position": 0.2811449759518132, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.694364878610045, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.009038} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.369951009750366, "x": 32.11471340858202, "y": -0.15423809585907744, "z": null, "yaw": 3.116195260150512, "pitch": null, "roll": null}, "v": 2.2846699127313648, "accelerator_pedal_position": 0.2906262782538268, "brake_pedal_position": 0.0, "acceleration": 0.19998357734844985, "steering_wheel_angle": -0.773174338464776, "front_wheel_angle": -0.03587451665462896, "heading_rate": -0.032029924951956584, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.029038} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2811449759518132, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.155133746033362, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2945265690804004, "gear": 1, "accelerator_pedal_position": 0.2811449759518132, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.694364878610045, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.029038} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.369951009750366, "x": 32.11471340858202, "y": -0.15423809585907744, "z": null, "yaw": 3.116195260150512, "pitch": null, "roll": null}, "v": 2.2846699127313648, "accelerator_pedal_position": 0.2906262782538268, "brake_pedal_position": 0.0, "acceleration": 0.19998357734844985, "steering_wheel_angle": -0.773174338464776, "front_wheel_angle": -0.03587451665462896, "heading_rate": -0.032029924951956584, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.049038} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2811449759518132, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.155133746033362, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.297320853504836, "gear": 1, "accelerator_pedal_position": 0.2811449759518132, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.694364878610045, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.049038} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502690.069038, "x": 35.86270175715927, "y": 4.85233009548508, "z": null, "yaw": 3.114775807808298, "pitch": null, "roll": null}, "v": 2.300109779250462, "accelerator_pedal_position": 0.2811449759518132, "brake_pedal_position": 0.0, "acceleration": 0.13924556077027328, "steering_wheel_angle": -0.694364878610045, "front_wheel_angle": -0.032183604738648286, "heading_rate": -0.02892632533179134, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.069038} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2734935275971756, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.2078725325277134, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.300109779250462, "gear": 1, "accelerator_pedal_position": 0.2811449759518132, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.694364878610045, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.069038} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.47995090484619, "x": 31.86270175715927, "y": -0.14766990451492035, "z": null, "yaw": 3.114775807808298, "pitch": null, "roll": null}, "v": 2.300109779250462, "accelerator_pedal_position": 0.2811449759518132, "brake_pedal_position": 0.0, "acceleration": 0.13924556077027328, "steering_wheel_angle": -0.694364878610045, "front_wheel_angle": -0.032183604738648286, "heading_rate": -0.02892632533179134, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.089038} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27595860068375727, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.2078725325277134, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.301937381647399, "gear": 1, "accelerator_pedal_position": 0.2734935275971756, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6548415105692499, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.089038} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.47995090484619, "x": 31.86270175715927, "y": -0.14766990451492035, "z": null, "yaw": 3.114775807808298, "pitch": null, "roll": null}, "v": 2.300109779250462, "accelerator_pedal_position": 0.2811449759518132, "brake_pedal_position": 0.0, "acceleration": 0.13924556077027328, "steering_wheel_angle": -0.694364878610045, "front_wheel_angle": -0.032183604738648286, "heading_rate": -0.02892632533179134, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.1090379} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27595860068375727, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.2078725325277134, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3040694617922095, "gear": 1, "accelerator_pedal_position": 0.27595860068375727, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6548415105692499, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.1090379} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.47995090484619, "x": 31.86270175715927, "y": -0.14766990451492035, "z": null, "yaw": 3.114775807808298, "pitch": null, "roll": null}, "v": 2.300109779250462, "accelerator_pedal_position": 0.2811449759518132, "brake_pedal_position": 0.0, "acceleration": 0.13924556077027328, "steering_wheel_angle": -0.694364878610045, "front_wheel_angle": -0.032183604738648286, "heading_rate": -0.02892632533179134, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.1290379} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27595860068375727, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.2078725325277134, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3061974472951903, "gear": 1, "accelerator_pedal_position": 0.27595860068375727, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6548415105692499, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.1290379} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.47995090484619, "x": 31.86270175715927, "y": -0.14766990451492035, "z": null, "yaw": 3.114775807808298, "pitch": null, "roll": null}, "v": 2.300109779250462, "accelerator_pedal_position": 0.2811449759518132, "brake_pedal_position": 0.0, "acceleration": 0.13924556077027328, "steering_wheel_angle": -0.694364878610045, "front_wheel_angle": -0.032183604738648286, "heading_rate": -0.02892632533179134, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.1590378} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27595860068375727, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.2078725325277134, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.309381761337424, "gear": 1, "accelerator_pedal_position": 0.27595860068375727, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6548415105692499, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.1590378} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27595860068375727, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.2078725325277134, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.31044115858753, "gear": 1, "accelerator_pedal_position": 0.27595860068375727, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6548415105692499, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.1690378} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502690.1790378, "x": 35.6092282677087, "y": 4.859281225267133, "z": null, "yaw": 3.1134647003493026, "pitch": null, "roll": null}, "v": 2.3114995367162416, "accelerator_pedal_position": 0.27595860068375727, "brake_pedal_position": 0.0, "acceleration": 0.10573597635527682, "steering_wheel_angle": -0.6548415105692499, "front_wheel_angle": -0.030335570009545985, "heading_rate": -0.027399286476662964, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.1890378} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26969745858023725, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.26369157764620604, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3132219172528736, "gear": 1, "accelerator_pedal_position": 0.26969745858023725, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6152169998461865, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.1890378} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.58995079994202, "x": 31.6092282677087, "y": -0.14071877473286687, "z": null, "yaw": 3.1134647003493026, "pitch": null, "roll": null}, "v": 2.3114995367162416, "accelerator_pedal_position": 0.27595860068375727, "brake_pedal_position": 0.0, "acceleration": 0.10573597635527682, "steering_wheel_angle": -0.6548415105692499, "front_wheel_angle": -0.030335570009545985, "heading_rate": -0.027399286476662964, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.2090378} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2717088037558103, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.26369157764620604, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.313886297891666, "gear": 1, "accelerator_pedal_position": 0.26969745858023725, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.575549940099965, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.2090378} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.58995079994202, "x": 31.6092282677087, "y": -0.14071877473286687, "z": null, "yaw": 3.1134647003493026, "pitch": null, "roll": null}, "v": 2.3114995367162416, "accelerator_pedal_position": 0.27595860068375727, "brake_pedal_position": 0.0, "acceleration": 0.10573597635527682, "steering_wheel_angle": -0.6548415105692499, "front_wheel_angle": -0.030335570009545985, "heading_rate": -0.027399286476662964, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.2290378} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2717088037558103, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.26369157764620604, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.315464437976404, "gear": 1, "accelerator_pedal_position": 0.2717088037558103, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.575549940099965, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.2290378} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.58995079994202, "x": 31.6092282677087, "y": -0.14071877473286687, "z": null, "yaw": 3.1134647003493026, "pitch": null, "roll": null}, "v": 2.3114995367162416, "accelerator_pedal_position": 0.27595860068375727, "brake_pedal_position": 0.0, "acceleration": 0.10573597635527682, "steering_wheel_angle": -0.6548415105692499, "front_wheel_angle": -0.030335570009545985, "heading_rate": -0.027399286476662964, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.2490377} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2717088037558103, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.26369157764620604, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3170395399828925, "gear": 1, "accelerator_pedal_position": 0.2717088037558103, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.575549940099965, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.2490377} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.58995079994202, "x": 31.6092282677087, "y": -0.14071877473286687, "z": null, "yaw": 3.1134647003493026, "pitch": null, "roll": null}, "v": 2.3114995367162416, "accelerator_pedal_position": 0.27595860068375727, "brake_pedal_position": 0.0, "acceleration": 0.10573597635527682, "steering_wheel_angle": -0.6548415105692499, "front_wheel_angle": -0.030335570009545985, "heading_rate": -0.027399286476662964, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.2690377} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2717088037558103, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.26369157764620604, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3186116087678363, "gear": 1, "accelerator_pedal_position": 0.2717088037558103, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.575549940099965, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.2690377} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502690.2890377, "x": 35.35462871132415, "y": 4.866584859601271, "z": null, "yaw": 3.112283822223347, "pitch": null, "roll": null}, "v": 2.320180649184318, "accelerator_pedal_position": 0.2717088037558103, "brake_pedal_position": 0.0, "acceleration": 0.07833860856610475, "steering_wheel_angle": -0.575549940099965, "front_wheel_angle": -0.0266340181568204, "heading_rate": -0.024144667858200086, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.2890377} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26656023700405335, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.32272928217876345, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.320642249847994, "gear": 1, "accelerator_pedal_position": 0.26656023700405335, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5357778065723359, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.2890377} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.69995069503784, "x": 31.354628711324153, "y": -0.13341514039872937, "z": null, "yaw": 3.112283822223347, "pitch": null, "roll": null}, "v": 2.320180649184318, "accelerator_pedal_position": 0.2717088037558103, "brake_pedal_position": 0.0, "acceleration": 0.07833860856610475, "steering_wheel_angle": -0.575549940099965, "front_wheel_angle": -0.0266340181568204, "heading_rate": -0.024144667858200086, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.3090377} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2682109720457588, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.32272928217876345, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3211034054906454, "gear": 1, "accelerator_pedal_position": 0.26656023700405335, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5357778065723359, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.3090377} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.69995069503784, "x": 31.354628711324153, "y": -0.13341514039872937, "z": null, "yaw": 3.112283822223347, "pitch": null, "roll": null}, "v": 2.320180649184318, "accelerator_pedal_position": 0.2717088037558103, "brake_pedal_position": 0.0, "acceleration": 0.07833860856610475, "steering_wheel_angle": -0.575549940099965, "front_wheel_angle": -0.0266340181568204, "heading_rate": -0.024144667858200086, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.3290377} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2682109720457588, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.32272928217876345, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3222306256486465, "gear": 1, "accelerator_pedal_position": 0.2682109720457588, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5357778065723359, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.3290377} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.69995069503784, "x": 31.354628711324153, "y": -0.13341514039872937, "z": null, "yaw": 3.112283822223347, "pitch": null, "roll": null}, "v": 2.320180649184318, "accelerator_pedal_position": 0.2717088037558103, "brake_pedal_position": 0.0, "acceleration": 0.07833860856610475, "steering_wheel_angle": -0.575549940099965, "front_wheel_angle": -0.0266340181568204, "heading_rate": -0.024144667858200086, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.3490376} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2682109720457588, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.32272928217876345, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.323355672695912, "gear": 1, "accelerator_pedal_position": 0.2682109720457588, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5357778065723359, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.3490376} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.69995069503784, "x": 31.354628711324153, "y": -0.13341514039872937, "z": null, "yaw": 3.112283822223347, "pitch": null, "roll": null}, "v": 2.320180649184318, "accelerator_pedal_position": 0.2717088037558103, "brake_pedal_position": 0.0, "acceleration": 0.07833860856610475, "steering_wheel_angle": -0.575549940099965, "front_wheel_angle": -0.0266340181568204, "heading_rate": -0.024144667858200086, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.3690376} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2682109720457588, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.32272928217876345, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3244785503158245, "gear": 1, "accelerator_pedal_position": 0.2682109720457588, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5357778065723359, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.3690376} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.69995069503784, "x": 31.354628711324153, "y": -0.13341514039872937, "z": null, "yaw": 3.112283822223347, "pitch": null, "roll": null}, "v": 2.320180649184318, "accelerator_pedal_position": 0.2717088037558103, "brake_pedal_position": 0.0, "acceleration": 0.07833860856610475, "steering_wheel_angle": -0.575549940099965, "front_wheel_angle": -0.0266340181568204, "heading_rate": -0.024144667858200086, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.3890376} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2682109720457588, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.32272928217876345, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3255992621875907, "gear": 1, "accelerator_pedal_position": 0.2682109720457588, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5357778065723359, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.3890376} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502690.3990376, "x": 35.099232087745094, "y": 4.874197865730856, "z": null, "yaw": 3.111211578671895, "pitch": null, "roll": null}, "v": 2.3261588071165282, "accelerator_pedal_position": 0.2682109720457588, "brake_pedal_position": 0.0, "acceleration": 0.05590048697090794, "steering_wheel_angle": -0.5357778065723359, "front_wheel_angle": -0.024780329654388297, "heading_rate": -0.022521399925202037, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.4090376} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2585585900131328, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.37577558991048204, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3267178119862373, "gear": 1, "accelerator_pedal_position": 0.2682109720457588, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5357778065723359, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.4090376} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.80995059013367, "x": 31.099232087745094, "y": -0.12580213426914444, "z": null, "yaw": 3.111211578671895, "pitch": null, "roll": null}, "v": 2.3261588071165282, "accelerator_pedal_position": 0.2682109720457588, "brake_pedal_position": 0.0, "acceleration": 0.05590048697090794, "steering_wheel_angle": -0.5357778065723359, "front_wheel_angle": -0.024780329654388297, "heading_rate": -0.022521399925202037, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.4290376} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2616037950652892, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.37577558991048204, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3266282380260703, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4559923840284289, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.4290376} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.80995059013367, "x": 31.099232087745094, "y": -0.12580213426914444, "z": null, "yaw": 3.111211578671895, "pitch": null, "roll": null}, "v": 2.3261588071165282, "accelerator_pedal_position": 0.2682109720457588, "brake_pedal_position": 0.0, "acceleration": 0.05590048697090794, "steering_wheel_angle": -0.5357778065723359, "front_wheel_angle": -0.024780329654388297, "heading_rate": -0.022521399925202037, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.4490376} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2616037950652892, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.37577558991048204, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3269193038230087, "gear": 1, "accelerator_pedal_position": 0.2616037950652892, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4559923840284289, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.4490376} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.80995059013367, "x": 31.099232087745094, "y": -0.12580213426914444, "z": null, "yaw": 3.111211578671895, "pitch": null, "roll": null}, "v": 2.3261588071165282, "accelerator_pedal_position": 0.2682109720457588, "brake_pedal_position": 0.0, "acceleration": 0.05590048697090794, "steering_wheel_angle": -0.5357778065723359, "front_wheel_angle": -0.024780329654388297, "heading_rate": -0.022521399925202037, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.4690375} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2616037950652892, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.37577558991048204, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3272098079192323, "gear": 1, "accelerator_pedal_position": 0.2616037950652892, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4559923840284289, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.4690375} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.80995059013367, "x": 31.099232087745094, "y": -0.12580213426914444, "z": null, "yaw": 3.111211578671895, "pitch": null, "roll": null}, "v": 2.3261588071165282, "accelerator_pedal_position": 0.2682109720457588, "brake_pedal_position": 0.0, "acceleration": 0.05590048697090794, "steering_wheel_angle": -0.5357778065723359, "front_wheel_angle": -0.024780329654388297, "heading_rate": -0.022521399925202037, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.4890375} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2616037950652892, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.37577558991048204, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3274997513649747, "gear": 1, "accelerator_pedal_position": 0.2616037950652892, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4559923840284289, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.4890375} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502690.5090375, "x": 34.84338723321948, "y": 4.882086269981095, "z": null, "yaw": 3.1102699172022543, "pitch": null, "roll": null}, "v": 2.3277891352086373, "accelerator_pedal_position": 0.2616037950652892, "brake_pedal_position": 0.0, "acceleration": 0.014448239817671737, "steering_wheel_angle": -0.4559923840284289, "front_wheel_angle": -0.021067695134322044, "heading_rate": -0.019159534659391804, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.5090375} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2525840311529365, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4090981817490842, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3277891352086373, "gear": 1, "accelerator_pedal_position": 0.2616037950652892, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4559923840284289, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.5090375} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.91995048522949, "x": 30.84338723321948, "y": -0.1179137300189046, "z": null, "yaw": 3.1102699172022543, "pitch": null, "roll": null}, "v": 2.3277891352086373, "accelerator_pedal_position": 0.2616037950652892, "brake_pedal_position": 0.0, "acceleration": 0.014448239817671737, "steering_wheel_angle": -0.4559923840284289, "front_wheel_angle": -0.021067695134322044, "heading_rate": -0.019159534659391804, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.5290375} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2554105787800408, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4090981817490842, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3269510343112367, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4559923840284289, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.5290375} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.91995048522949, "x": 30.84338723321948, "y": -0.1179137300189046, "z": null, "yaw": 3.1102699172022543, "pitch": null, "roll": null}, "v": 2.3277891352086373, "accelerator_pedal_position": 0.2616037950652892, "brake_pedal_position": 0.0, "acceleration": 0.014448239817671737, "steering_wheel_angle": -0.4559923840284289, "front_wheel_angle": -0.021067695134322044, "heading_rate": -0.019159534659391804, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.5490375} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2554105787800408, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4090981817490842, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3264676988117134, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4559923840284289, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.5490375} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.91995048522949, "x": 30.84338723321948, "y": -0.1179137300189046, "z": null, "yaw": 3.1102699172022543, "pitch": null, "roll": null}, "v": 2.3277891352086373, "accelerator_pedal_position": 0.2616037950652892, "brake_pedal_position": 0.0, "acceleration": 0.014448239817671737, "steering_wheel_angle": -0.4559923840284289, "front_wheel_angle": -0.021067695134322044, "heading_rate": -0.019159534659391804, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.5690374} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2554105787800408, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4090981817490842, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.325985296006442, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4559923840284289, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.5690374} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.91995048522949, "x": 30.84338723321948, "y": -0.1179137300189046, "z": null, "yaw": 3.1102699172022543, "pitch": null, "roll": null}, "v": 2.3277891352086373, "accelerator_pedal_position": 0.2616037950652892, "brake_pedal_position": 0.0, "acceleration": 0.014448239817671737, "steering_wheel_angle": -0.4559923840284289, "front_wheel_angle": -0.021067695134322044, "heading_rate": -0.019159534659391804, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.5890374} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2554105787800408, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4090981817490842, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3255038240025603, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4559923840284289, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.5890374} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 51.91995048522949, "x": 30.84338723321948, "y": -0.1179137300189046, "z": null, "yaw": 3.1102699172022543, "pitch": null, "roll": null}, "v": 2.3277891352086373, "accelerator_pedal_position": 0.2616037950652892, "brake_pedal_position": 0.0, "acceleration": 0.014448239817671737, "steering_wheel_angle": -0.4559923840284289, "front_wheel_angle": -0.021067695134322044, "heading_rate": -0.019159534659391804, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.6090374} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2554105787800408, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4090981817490842, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.325023280911395, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4559923840284289, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.6090374} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502690.6190374, "x": 34.58762574269163, "y": 4.890205377424326, "z": null, "yaw": 3.109364530721727, "pitch": null, "roll": null}, "v": 2.3247833571190135, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3702853444313262, "steering_wheel_angle": -0.4559923840284289, "front_wheel_angle": -0.021067695134322044, "heading_rate": -0.019134794742611747, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.6290374} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2535500138977793, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.46763700546419906, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.324543664848453, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.4559923840284289, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.6290374} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.02995038032532, "x": 30.58762574269163, "y": -0.10979462257567363, "z": null, "yaw": 3.109364530721727, "pitch": null, "roll": null}, "v": 2.3247833571190135, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3702853444313262, "steering_wheel_angle": -0.4559923840284289, "front_wheel_angle": -0.021067695134322044, "heading_rate": -0.019134794742611747, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.6490374} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2541169340497349, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.46763700546419906, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3238325155209147, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.37583830951744507, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.6490374} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.02995038032532, "x": 30.58762574269163, "y": -0.10979462257567363, "z": null, "yaw": 3.109364530721727, "pitch": null, "roll": null}, "v": 2.3247833571190135, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3702853444313262, "steering_wheel_angle": -0.4559923840284289, "front_wheel_angle": -0.021067695134322044, "heading_rate": -0.019134794742611747, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.6690373} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2541169340497349, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.46763700546419906, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3231935686053924, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.37583830951744507, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.6690373} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.02995038032532, "x": 30.58762574269163, "y": -0.10979462257567363, "z": null, "yaw": 3.109364530721727, "pitch": null, "roll": null}, "v": 2.3247833571190135, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3702853444313262, "steering_wheel_angle": -0.4559923840284289, "front_wheel_angle": -0.021067695134322044, "heading_rate": -0.019134794742611747, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.6890373} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2541169340497349, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.46763700546419906, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3225558538419793, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.37583830951744507, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.6890373} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.02995038032532, "x": 30.58762574269163, "y": -0.10979462257567363, "z": null, "yaw": 3.109364530721727, "pitch": null, "roll": null}, "v": 2.3247833571190135, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3702853444313262, "steering_wheel_angle": -0.4559923840284289, "front_wheel_angle": -0.021067695134322044, "heading_rate": -0.019134794742611747, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.7090373} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2541169340497349, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.46763700546419906, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.321919368691986, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.37583830951744507, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.7090373} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502690.7290373, "x": 34.332209082228815, "y": 4.898534209811155, "z": null, "yaw": 3.1085827653744764, "pitch": null, "roll": null}, "v": 2.3212841106225595, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3699478047534156, "steering_wheel_angle": -0.37583830951744507, "front_wheel_angle": -0.017345902915606205, "heading_rate": -0.0157300029691507, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.7290373} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2527959397800835, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5301462842782595, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3212841106225595, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.37583830951744507, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.7290373} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.13995027542114, "x": 30.332209082228815, "y": -0.10146579018884516, "z": null, "yaw": 3.1085827653744764, "pitch": null, "roll": null}, "v": 2.3212841106225595, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3699478047534156, "steering_wheel_angle": -0.37583830951744507, "front_wheel_angle": -0.017345902915606205, "heading_rate": -0.0157300029691507, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.7490373} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2531918737650486, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5301462842782595, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.320485032428149, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3356290822056074, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.7490373} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.13995027542114, "x": 30.332209082228815, "y": -0.10146579018884516, "z": null, "yaw": 3.1085827653744764, "pitch": null, "roll": null}, "v": 2.3212841106225595, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3699478047534156, "steering_wheel_angle": -0.37583830951744507, "front_wheel_angle": -0.017345902915606205, "heading_rate": -0.0157300029691507, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.7690372} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2531918737650486, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5301462842782595, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3197369622252317, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3356290822056074, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.7690372} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.13995027542114, "x": 30.332209082228815, "y": -0.10146579018884516, "z": null, "yaw": 3.1085827653744764, "pitch": null, "roll": null}, "v": 2.3212841106225595, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3699478047534156, "steering_wheel_angle": -0.37583830951744507, "front_wheel_angle": -0.017345902915606205, "heading_rate": -0.0157300029691507, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.7890372} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2531918737650486, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5301462842782595, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.318990333583789, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3356290822056074, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.7890372} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.13995027542114, "x": 30.332209082228815, "y": -0.10146579018884516, "z": null, "yaw": 3.1085827653744764, "pitch": null, "roll": null}, "v": 2.3212841106225595, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3699478047534156, "steering_wheel_angle": -0.37583830951744507, "front_wheel_angle": -0.017345902915606205, "heading_rate": -0.0157300029691507, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.8090372} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2531918737650486, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5301462842782595, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.318245143502998, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3356290822056074, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.8090372} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.13995027542114, "x": 30.332209082228815, "y": -0.10146579018884516, "z": null, "yaw": 3.1085827653744764, "pitch": null, "roll": null}, "v": 2.3212841106225595, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3699478047534156, "steering_wheel_angle": -0.37583830951744507, "front_wheel_angle": -0.017345902915606205, "heading_rate": -0.0157300029691507, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.8290372} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2531918737650486, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5301462842782595, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.317501388989109, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3356290822056074, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.8290372} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502690.8390372, "x": 34.07721976699525, "y": 4.90703329697986, "z": null, "yaw": 3.1079101922136614, "pitch": null, "roll": null}, "v": 2.317130049136133, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3695474191029029, "steering_wheel_angle": -0.3356290822056074, "front_wheel_angle": -0.015481871576332056, "heading_rate": -0.014014209482540571, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.8490372} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25238606998263996, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.597756143992925, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3167590670554197, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.3356290822056074, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.8490372} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.24995017051697, "x": 30.07721976699525, "y": -0.09296670302014043, "z": null, "yaw": 3.1079101922136614, "pitch": null, "roll": null}, "v": 2.317130049136133, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3695474191029029, "steering_wheel_angle": -0.3356290822056074, "front_wheel_angle": -0.015481871576332056, "heading_rate": -0.014014209482540571, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.8690372} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2526178645340934, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.597756143992925, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3159174977625065, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2549336804954348, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.8690372} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.24995017051697, "x": 30.07721976699525, "y": -0.09296670302014043, "z": null, "yaw": 3.1079101922136614, "pitch": null, "roll": null}, "v": 2.317130049136133, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3695474191029029, "steering_wheel_angle": -0.3356290822056074, "front_wheel_angle": -0.015481871576332056, "heading_rate": -0.014014209482540571, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.8890371} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2526178645340934, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.597756143992925, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3147016007610817, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2549336804954348, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.8890371} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.24995017051697, "x": 30.07721976699525, "y": -0.09296670302014043, "z": null, "yaw": 3.1079101922136614, "pitch": null, "roll": null}, "v": 2.317130049136133, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3695474191029029, "steering_wheel_angle": -0.3356290822056074, "front_wheel_angle": -0.015481871576332056, "heading_rate": -0.014014209482540571, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.909037} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2526178645340934, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.597756143992925, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.314297082144025, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2549336804954348, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.909037} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.24995017051697, "x": 30.07721976699525, "y": -0.09296670302014043, "z": null, "yaw": 3.1079101922136614, "pitch": null, "roll": null}, "v": 2.317130049136133, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3695474191029029, "steering_wheel_angle": -0.3356290822056074, "front_wheel_angle": -0.015481871576332056, "heading_rate": -0.014014209482540571, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.929037} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2526178645340934, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.597756143992925, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.313489213034942, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2549336804954348, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.929037} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502690.949037, "x": 33.82270415460252, "y": 4.915675469169977, "z": null, "yaw": 3.1073689354149177, "pitch": null, "roll": null}, "v": 2.312682898710067, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36911916683536333, "steering_wheel_angle": -0.2549336804954348, "front_wheel_angle": -0.011746990979243758, "heading_rate": -0.010612622979957175, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.949037} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2482378524969912, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6357624167418585, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.312682898710067, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.2549336804954348, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.949037} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.35995006561279, "x": 29.82270415460252, "y": -0.08432453083002311, "z": null, "yaw": 3.1073689354149177, "pitch": null, "roll": null}, "v": 2.312682898710067, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36911916683536333, "steering_wheel_angle": -0.2549336804954348, "front_wheel_angle": -0.011746990979243758, "heading_rate": -0.010612622979957175, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.969037} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24958519452859493, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6357624167418585, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.311330897878148, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.21447933075109482, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.969037} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.35995006561279, "x": 29.82270415460252, "y": -0.08432453083002311, "z": null, "yaw": 3.1073689354149177, "pitch": null, "roll": null}, "v": 2.312682898710067, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36911916683536333, "steering_wheel_angle": -0.2549336804954348, "front_wheel_angle": -0.011746990979243758, "heading_rate": -0.010612622979957175, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502690.989037} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24958519452859493, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6357624167418585, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.310149834679645, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.21447933075109482, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502690.989037} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.35995006561279, "x": 29.82270415460252, "y": -0.08432453083002311, "z": null, "yaw": 3.1073689354149177, "pitch": null, "roll": null}, "v": 2.312682898710067, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36911916683536333, "steering_wheel_angle": -0.2549336804954348, "front_wheel_angle": -0.011746990979243758, "heading_rate": -0.010612622979957175, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.009037} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24958519452859493, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6357624167418585, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.308971042963869, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.21447933075109482, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.009037} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.35995006561279, "x": 29.82270415460252, "y": -0.08432453083002311, "z": null, "yaw": 3.1073689354149177, "pitch": null, "roll": null}, "v": 2.312682898710067, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36911916683536333, "steering_wheel_angle": -0.2549336804954348, "front_wheel_angle": -0.011746990979243758, "heading_rate": -0.010612622979957175, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.029037} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24958519452859493, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6357624167418585, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.307794517806633, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.21447933075109482, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.029037} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.35995006561279, "x": 29.82270415460252, "y": -0.08432453083002311, "z": null, "yaw": 3.1073689354149177, "pitch": null, "roll": null}, "v": 2.312682898710067, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36911916683536333, "steering_wheel_angle": -0.2549336804954348, "front_wheel_angle": -0.011746990979243758, "heading_rate": -0.010612622979957175, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.049037} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24958519452859493, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6357624167418585, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.306620254296422, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.21447933075109482, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.049037} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502691.059037, "x": 33.568800204722336, "y": 4.924419105645775, "z": null, "yaw": 3.1069371893006466, "pitch": null, "roll": null}, "v": 2.3060339691275575, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3684796251240799, "steering_wheel_angle": -0.21447933075109482, "front_wheel_angle": -0.009877626133906773, "heading_rate": -0.008898000871145442, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.069037} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24103324586975222, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6812693193751557, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.305448247534354, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.21447933075109482, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.069037} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.46994996070862, "x": 29.568800204722336, "y": -0.07558089435422488, "z": null, "yaw": 3.1069371893006466, "pitch": null, "roll": null}, "v": 2.3060339691275575, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3684796251240799, "steering_wheel_angle": -0.21447933075109482, "front_wheel_angle": -0.009877626133906773, "heading_rate": -0.008898000871145442, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.089037} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24367375447132875, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6812693193751557, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3032100126599984, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.1739314546464441, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.089037} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.46994996070862, "x": 29.568800204722336, "y": -0.07558089435422488, "z": null, "yaw": 3.1069371893006466, "pitch": null, "roll": null}, "v": 2.3060339691275575, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3684796251240799, "steering_wheel_angle": -0.21447933075109482, "front_wheel_angle": -0.009877626133906773, "heading_rate": -0.008898000871145442, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.109037} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24367375447132875, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6812693193751557, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.301305981578609, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.1739314546464441, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.109037} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.46994996070862, "x": 29.568800204722336, "y": -0.07558089435422488, "z": null, "yaw": 3.1069371893006466, "pitch": null, "roll": null}, "v": 2.3060339691275575, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3684796251240799, "steering_wheel_angle": -0.21447933075109482, "front_wheel_angle": -0.009877626133906773, "heading_rate": -0.008898000871145442, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.129037} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24367375447132875, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6812693193751557, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.299405605838197, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.1739314546464441, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.129037} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.46994996070862, "x": 29.568800204722336, "y": -0.07558089435422488, "z": null, "yaw": 3.1069371893006466, "pitch": null, "roll": null}, "v": 2.3060339691275575, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3684796251240799, "steering_wheel_angle": -0.21447933075109482, "front_wheel_angle": -0.009877626133906773, "heading_rate": -0.008898000871145442, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.149037} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24367375447132875, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6812693193751557, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2975088769773944, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.1739314546464441, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.149037} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502691.1690369, "x": 33.31580496327356, "y": 4.93323305824738, "z": null, "yaw": 3.106578552675704, "pitch": null, "roll": null}, "v": 2.2956157865593845, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3674793077229759, "steering_wheel_angle": -0.1739314546464441, "front_wheel_angle": -0.008005949081471264, "heading_rate": -0.007179287409243456, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.1690369} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2353535006868759, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7237504581795141, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2956157865593845, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.1739314546464441, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.1690369} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.57994985580444, "x": 29.315804963273557, "y": -0.06676694175262021, "z": null, "yaw": 3.106578552675704, "pitch": null, "roll": null}, "v": 2.2956157865593845, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3674793077229759, "steering_wheel_angle": -0.1739314546464441, "front_wheel_angle": -0.008005949081471264, "heading_rate": -0.007179287409243456, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.1890368} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2379035657964152, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7237504581795141, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.292686793082667, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.1332930584582144, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.1890368} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.57994985580444, "x": 29.315804963273557, "y": -0.06676694175262021, "z": null, "yaw": 3.106578552675704, "pitch": null, "roll": null}, "v": 2.2956157865593845, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3674793077229759, "steering_wheel_angle": -0.1739314546464441, "front_wheel_angle": -0.008005949081471264, "heading_rate": -0.007179287409243456, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.2090368} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2379035657964152, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7237504581795141, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.290082018283613, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.1332930584582144, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.2090368} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.57994985580444, "x": 29.315804963273557, "y": -0.06676694175262021, "z": null, "yaw": 3.106578552675704, "pitch": null, "roll": null}, "v": 2.2956157865593845, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3674793077229759, "steering_wheel_angle": -0.1739314546464441, "front_wheel_angle": -0.008005949081471264, "heading_rate": -0.007179287409243456, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.2290368} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2379035657964152, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7237504581795141, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.287482232606039, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.1332930584582144, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.2290368} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.57994985580444, "x": 29.315804963273557, "y": -0.06676694175262021, "z": null, "yaw": 3.106578552675704, "pitch": null, "roll": null}, "v": 2.2956157865593845, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3674793077229759, "steering_wheel_angle": -0.1739314546464441, "front_wheel_angle": -0.008005949081471264, "heading_rate": -0.007179287409243456, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.2490368} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2379035657964152, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7237504581795141, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.284887423791644, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.1332930584582144, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.2490368} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.57994985580444, "x": 29.315804963273557, "y": -0.06676694175262021, "z": null, "yaw": 3.106578552675704, "pitch": null, "roll": null}, "v": 2.2956157865593845, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3674793077229759, "steering_wheel_angle": -0.1739314546464441, "front_wheel_angle": -0.008005949081471264, "heading_rate": -0.007179287409243456, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.2690368} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2379035657964152, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7237504581795141, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.282297579621113, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.1332930584582144, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.2690368} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502691.2790368, "x": 33.064188959637875, "y": 4.942078582635412, "z": null, "yaw": 3.106307740383685, "pitch": null, "roll": null}, "v": 2.281004515469384, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3660800417693864, "steering_wheel_angle": -0.1332930584582144, "front_wheel_angle": -0.006132105799829896, "heading_rate": -0.0054638813837235185, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.2890368} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24054944982631846, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7918624122913377, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2797126879139658, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.1332930584582144, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.2890368} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.68994975090027, "x": 29.064188959637875, "y": -0.05792141736458767, "z": null, "yaw": 3.106307740383685, "pitch": null, "roll": null}, "v": 2.281004515469384, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3660800417693864, "steering_wheel_angle": -0.1332930584582144, "front_wheel_angle": -0.006132105799829896, "heading_rate": -0.0054638813837235185, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.3090367} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23965264718130458, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7918624122913377, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2774633139900193, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.05173367917221305, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.3090367} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.68994975090027, "x": 29.064188959637875, "y": -0.05792141736458767, "z": null, "yaw": 3.106307740383685, "pitch": null, "roll": null}, "v": 2.281004515469384, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3660800417693864, "steering_wheel_angle": -0.1332930584582144, "front_wheel_angle": -0.006132105799829896, "heading_rate": -0.0054638813837235185, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.3290367} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23965264718130458, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7918624122913377, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.275106190250748, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.05173367917221305, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.3290367} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.68994975090027, "x": 29.064188959637875, "y": -0.05792141736458767, "z": null, "yaw": 3.106307740383685, "pitch": null, "roll": null}, "v": 2.281004515469384, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3660800417693864, "steering_wheel_angle": -0.1332930584582144, "front_wheel_angle": -0.006132105799829896, "heading_rate": -0.0054638813837235185, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.3490367} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23965264718130458, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7918624122913377, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2727535671234262, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.05173367917221305, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.3490367} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.68994975090027, "x": 29.064188959637875, "y": -0.05792141736458767, "z": null, "yaw": 3.106307740383685, "pitch": null, "roll": null}, "v": 2.281004515469384, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3660800417693864, "steering_wheel_angle": -0.1332930584582144, "front_wheel_angle": -0.006132105799829896, "heading_rate": -0.0054638813837235185, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.3690367} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23965264718130458, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7918624122913377, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.27040543380186, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.05173367917221305, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.3690367} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502691.3890367, "x": 32.814084828268065, "y": 4.950926441550263, "z": null, "yaw": 3.106168917216454, "pitch": null, "roll": null}, "v": 2.268061779513149, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.364844131332541, "steering_wheel_angle": -0.05173367917221305, "front_wheel_angle": -0.0023774413032310563, "heading_rate": -0.0021063257469530186, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.3890367} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2433964628786806, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8719767483001376, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.268061779513149, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.05173367917221305, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.3890367} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.799949645996094, "x": 28.814084828268065, "y": -0.04907355844973704, "z": null, "yaw": 3.106168917216454, "pitch": null, "roll": null}, "v": 2.268061779513149, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.364844131332541, "steering_wheel_angle": -0.05173367917221305, "front_wheel_angle": -0.0023774413032310563, "heading_rate": -0.0021063257469530186, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.4090366} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24216472414381748, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8719767483001376, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2661903473947094, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.030156923310479415, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.4090366} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.799949645996094, "x": 28.814084828268065, "y": -0.04907355844973704, "z": null, "yaw": 3.106168917216454, "pitch": null, "roll": null}, "v": 2.268061779513149, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.364844131332541, "steering_wheel_angle": -0.05173367917221305, "front_wheel_angle": -0.0023774413032310563, "heading_rate": -0.0021063257469530186, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.4290366} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24216472414381748, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8719767483001376, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2641685877934363, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.030156923310479415, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.4290366} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.799949645996094, "x": 28.814084828268065, "y": -0.04907355844973704, "z": null, "yaw": 3.106168917216454, "pitch": null, "roll": null}, "v": 2.268061779513149, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.364844131332541, "steering_wheel_angle": -0.05173367917221305, "front_wheel_angle": -0.0023774413032310563, "heading_rate": -0.0021063257469530186, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.4490366} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24216472414381748, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8719767483001376, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2621506795666133, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.030156923310479415, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.4490366} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.799949645996094, "x": 28.814084828268065, "y": -0.04907355844973704, "z": null, "yaw": 3.106168917216454, "pitch": null, "roll": null}, "v": 2.268061779513149, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.364844131332541, "steering_wheel_angle": -0.05173367917221305, "front_wheel_angle": -0.0023774413032310563, "heading_rate": -0.0021063257469530186, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.4690366} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24216472414381748, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8719767483001376, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2601366137495136, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.030156923310479415, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.4690366} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.799949645996094, "x": 28.814084828268065, "y": -0.04907355844973704, "z": null, "yaw": 3.106168917216454, "pitch": null, "roll": null}, "v": 2.268061779513149, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.364844131332541, "steering_wheel_angle": -0.05173367917221305, "front_wheel_angle": -0.0023774413032310563, "heading_rate": -0.0021063257469530186, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.4890366} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24216472414381748, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8719767483001376, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2581263814037813, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.030156923310479415, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.4890366} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502691.4990366, "x": 32.56529521473258, "y": 4.959741277805636, "z": null, "yaw": 3.1062064012380866, "pitch": null, "roll": null}, "v": 2.257122699996629, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36380216382823216, "steering_wheel_angle": 0.030156923310479415, "front_wheel_angle": 0.001385480845747324, "heading_rate": 0.0012215633860527026, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.5090365} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23772368864842694, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8677235410518033, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.256119973617335, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.030156923310479415, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.5090365} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.90994954109192, "x": 28.56529521473258, "y": -0.04025872219436444, "z": null, "yaw": 3.1062064012380866, "pitch": null, "roll": null}, "v": 2.257122699996629, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36380216382823216, "steering_wheel_angle": 0.030156923310479415, "front_wheel_angle": 0.001385480845747324, "heading_rate": 0.0012215633860527026, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.5290365} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23905941474129133, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8677235410518033, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2535625160302524, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.030156923310479415, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.5290365} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.90994954109192, "x": 28.56529521473258, "y": -0.04025872219436444, "z": null, "yaw": 3.1062064012380866, "pitch": null, "roll": null}, "v": 2.257122699996629, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36380216382823216, "steering_wheel_angle": 0.030156923310479415, "front_wheel_angle": 0.001385480845747324, "heading_rate": 0.0012215633860527026, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.5490365} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23905941474129133, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8677235410518033, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.25117680601317, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.030156923310479415, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.5490365} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.90994954109192, "x": 28.56529521473258, "y": -0.04025872219436444, "z": null, "yaw": 3.1062064012380866, "pitch": null, "roll": null}, "v": 2.257122699996629, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36380216382823216, "steering_wheel_angle": 0.030156923310479415, "front_wheel_angle": 0.001385480845747324, "heading_rate": 0.0012215633860527026, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.5690365} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23905941474129133, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8677235410518033, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2487956283828474, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.030156923310479415, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.5690365} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 52.90994954109192, "x": 28.56529521473258, "y": -0.04025872219436444, "z": null, "yaw": 3.1062064012380866, "pitch": null, "roll": null}, "v": 2.257122699996629, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36380216382823216, "steering_wheel_angle": 0.030156923310479415, "front_wheel_angle": 0.001385480845747324, "heading_rate": 0.0012215633860527026, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.5890365} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23905941474129133, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8677235410518033, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.246418972261701, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.030156923310479415, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.5890365} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502691.6090364, "x": 32.31781769232265, "y": 4.968495538922834, "z": null, "yaw": 3.106265933656267, "pitch": null, "roll": null}, "v": 2.244046826805718, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36255980294925405, "steering_wheel_angle": 0.030156923310479415, "front_wheel_angle": 0.001385480845747324, "heading_rate": 0.0012144866737717492, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.6090364} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2420056694900519, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9394993529986189, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.244046826805718, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.030156923310479415, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.6090364} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.019949436187744, "x": 28.31781769232265, "y": -0.03150446107716576, "z": null, "yaw": 3.106265933656267, "pitch": null, "roll": null}, "v": 2.244046826805718, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36255980294925405, "steering_wheel_angle": 0.030156923310479415, "front_wheel_angle": 0.001385480845747324, "heading_rate": 0.0012144866737717492, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.6290364} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24102284619272613, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9394993529986189, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.242047288373518, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1120938757317114, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.6290364} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.019949436187744, "x": 28.31781769232265, "y": -0.03150446107716576, "z": null, "yaw": 3.106265933656267, "pitch": null, "roll": null}, "v": 2.244046826805718, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36255980294925405, "steering_wheel_angle": 0.030156923310479415, "front_wheel_angle": 0.001385480845747324, "heading_rate": 0.0012144866737717492, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.6490364} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24102284619272613, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9394993529986189, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.239928746637341, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1120938757317114, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.6490364} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.019949436187744, "x": 28.31781769232265, "y": -0.03150446107716576, "z": null, "yaw": 3.106265933656267, "pitch": null, "roll": null}, "v": 2.244046826805718, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36255980294925405, "steering_wheel_angle": 0.030156923310479415, "front_wheel_angle": 0.001385480845747324, "heading_rate": 0.0012144866737717492, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.6690364} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24102284619272613, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9394993529986189, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2378142201406397, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1120938757317114, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.6690364} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.019949436187744, "x": 28.31781769232265, "y": -0.03150446107716576, "z": null, "yaw": 3.106265933656267, "pitch": null, "roll": null}, "v": 2.244046826805718, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36255980294925405, "steering_wheel_angle": 0.030156923310479415, "front_wheel_angle": 0.001385480845747324, "heading_rate": 0.0012144866737717492, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.6890364} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24102284619272613, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9394993529986189, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.235703699485749, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1120938757317114, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.6890364} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.019949436187744, "x": 28.31781769232265, "y": -0.03150446107716576, "z": null, "yaw": 3.106265933656267, "pitch": null, "roll": null}, "v": 2.244046826805718, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36255980294925405, "steering_wheel_angle": 0.030156923310479415, "front_wheel_angle": 0.001385480845747324, "heading_rate": 0.0012144866737717492, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.7090364} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24102284619272613, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9394993529986189, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2335971753029695, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1120938757317114, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.7090364} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502691.7190363, "x": 32.07169612949886, "y": 4.9771738172235755, "z": null, "yaw": 3.1064653672295077, "pitch": null, "roll": null}, "v": 2.2325454089682113, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36146986047946095, "steering_wheel_angle": 0.1120938757317114, "front_wheel_angle": 0.0051554052490366525, "heading_rate": 0.004496007144543144, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.7290363} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24389778188906658, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.015570533045331, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.231494638250462, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1120938757317114, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.7290363} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.12994933128357, "x": 28.07169612949886, "y": -0.022826182776424453, "z": null, "yaw": 3.1064653672295077, "pitch": null, "roll": null}, "v": 2.2325454089682113, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36146986047946095, "steering_wheel_angle": 0.1120938757317114, "front_wheel_angle": 0.0051554052490366525, "heading_rate": 0.004496007144543144, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.7490363} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24294486673569068, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.015570533045331, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.229755275976398, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1940262079505034, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.7490363} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.12994933128357, "x": 28.07169612949886, "y": -0.022826182776424453, "z": null, "yaw": 3.1064653672295077, "pitch": null, "roll": null}, "v": 2.2325454089682113, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36146986047946095, "steering_wheel_angle": 0.1120938757317114, "front_wheel_angle": 0.0051554052490366525, "heading_rate": 0.004496007144543144, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.7690363} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24294486673569068, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.015570533045331, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2279001450847864, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1940262079505034, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.7690363} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.12994933128357, "x": 28.07169612949886, "y": -0.022826182776424453, "z": null, "yaw": 3.1064653672295077, "pitch": null, "roll": null}, "v": 2.2325454089682113, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36146986047946095, "steering_wheel_angle": 0.1120938757317114, "front_wheel_angle": 0.0051554052490366525, "heading_rate": 0.004496007144543144, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.7890363} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24294486673569068, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.015570533045331, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.226048521227895, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1940262079505034, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.7890363} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.12994933128357, "x": 28.07169612949886, "y": -0.022826182776424453, "z": null, "yaw": 3.1064653672295077, "pitch": null, "roll": null}, "v": 2.2325454089682113, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36146986047946095, "steering_wheel_angle": 0.1120938757317114, "front_wheel_angle": 0.0051554052490366525, "heading_rate": 0.004496007144543144, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.8090363} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24294486673569068, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.015570533045331, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2242003964050885, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1940262079505034, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.8090363} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502691.8290362, "x": 31.826778362855208, "y": 4.985745467238181, "z": null, "yaw": 3.1068123335510975, "pitch": null, "roll": null}, "v": 2.222355762638622, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.360506439489262, "steering_wheel_angle": 0.1940262079505034, "front_wheel_angle": 0.008933265435008223, "heading_rate": 0.007755242985895074, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.8290362} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23908961232874584, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9665037303301173, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.222355762638622, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1940262079505034, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.8290362} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.239949226379395, "x": 27.826778362855208, "y": -0.014254532761818872, "z": null, "yaw": 3.1068123335510975, "pitch": null, "roll": null}, "v": 2.222355762638622, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.360506439489262, "steering_wheel_angle": 0.1940262079505034, "front_wheel_angle": 0.008933265435008223, "heading_rate": 0.007755242985895074, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.8490362} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24024620903973004, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9665037303301173, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2200329326960375, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1940262079505034, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.8490362} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.239949226379395, "x": 27.826778362855208, "y": -0.014254532761818872, "z": null, "yaw": 3.1068123335510975, "pitch": null, "roll": null}, "v": 2.222355762638622, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.360506439489262, "steering_wheel_angle": 0.1940262079505034, "front_wheel_angle": 0.008933265435008223, "heading_rate": 0.007755242985895074, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.8690362} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24024620903973004, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9665037303301173, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2178589931217316, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1940262079505034, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.8690362} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.239949226379395, "x": 27.826778362855208, "y": -0.014254532761818872, "z": null, "yaw": 3.1068123335510975, "pitch": null, "roll": null}, "v": 2.222355762638622, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.360506439489262, "steering_wheel_angle": 0.1940262079505034, "front_wheel_angle": 0.008933265435008223, "heading_rate": 0.007755242985895074, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.8890362} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24024620903973004, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9665037303301173, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2156891546204336, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1940262079505034, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.8890362} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.239949226379395, "x": 27.826778362855208, "y": -0.014254532761818872, "z": null, "yaw": 3.1068123335510975, "pitch": null, "roll": null}, "v": 2.222355762638622, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.360506439489262, "steering_wheel_angle": 0.1940262079505034, "front_wheel_angle": 0.008933265435008223, "heading_rate": 0.007755242985895074, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.9090362} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24024620903973004, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9665037303301173, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2135234075731978, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1940262079505034, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.9090362} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.239949226379395, "x": 27.826778362855208, "y": -0.014254532761818872, "z": null, "yaw": 3.1068123335510975, "pitch": null, "roll": null}, "v": 2.222355762638622, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.360506439489262, "steering_wheel_angle": 0.1940262079505034, "front_wheel_angle": 0.008933265435008223, "heading_rate": 0.007755242985895074, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.9290361} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24024620903973004, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9665037303301173, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.211361742389865, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1940262079505034, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.9290361} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502691.9390361, "x": 31.58307653651783, "y": 4.994182383245208, "z": null, "yaw": 3.10719619501144, "pitch": null, "roll": null}, "v": 2.2102824375080825, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3593676064109709, "steering_wheel_angle": 0.1940262079505034, "front_wheel_angle": 0.008933265435008223, "heading_rate": 0.007713111311205925, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.9490361} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24378507568325133, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0383422460519423, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.209204149508956, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1940262079505034, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.9490361} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.34994912147522, "x": 27.58307653651783, "y": -0.0058176167547916435, "z": null, "yaw": 3.10719619501144, "pitch": null, "roll": null}, "v": 2.2102824375080825, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3593676064109709, "steering_wheel_angle": 0.1940262079505034, "front_wheel_angle": 0.008933265435008223, "heading_rate": 0.007713111311205925, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.969036} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2426222374408202, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0383422460519423, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2074927694551976, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1940262079505034, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.969036} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.34994912147522, "x": 27.58307653651783, "y": -0.0058176167547916435, "z": null, "yaw": 3.10719619501144, "pitch": null, "roll": null}, "v": 2.2102824375080825, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3593676064109709, "steering_wheel_angle": 0.1940262079505034, "front_wheel_angle": 0.008933265435008223, "heading_rate": 0.007713111311205925, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502691.989036} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2426222374408202, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0383422460519423, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2056393243332795, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1940262079505034, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502691.989036} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.34994912147522, "x": 27.58307653651783, "y": -0.0058176167547916435, "z": null, "yaw": 3.10719619501144, "pitch": null, "roll": null}, "v": 2.2102824375080825, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3593676064109709, "steering_wheel_angle": 0.1940262079505034, "front_wheel_angle": 0.008933265435008223, "heading_rate": 0.007713111311205925, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.009036} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2426222374408202, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0383422460519423, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2037893665707893, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1940262079505034, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.009036} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.34994912147522, "x": 27.58307653651783, "y": -0.0058176167547916435, "z": null, "yaw": 3.10719619501144, "pitch": null, "roll": null}, "v": 2.2102824375080825, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3593676064109709, "steering_wheel_angle": 0.1940262079505034, "front_wheel_angle": 0.008933265435008223, "heading_rate": 0.007713111311205925, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.029036} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2426222374408202, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0383422460519423, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2019428882377734, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1940262079505034, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.029036} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502692.049036, "x": 31.340599944413864, "y": 5.002483687583062, "z": null, "yaw": 3.1075800564717824, "pitch": null, "roll": null}, "v": 2.2000998814269144, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35840938895389296, "steering_wheel_angle": 0.1940262079505034, "front_wheel_angle": 0.008933265435008223, "heading_rate": 0.007677577758048259, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.049036} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2456649323701362, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1185389731335724, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2000998814269144, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1940262079505034, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.049036} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.459949016571045, "x": 27.340599944413864, "y": 0.0024836875830622773, "z": null, "yaw": 3.1075800564717824, "pitch": null, "roll": null}, "v": 2.2000998814269144, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35840938895389296, "steering_wheel_angle": 0.1940262079505034, "front_wheel_angle": 0.008933265435008223, "heading_rate": 0.007677577758048259, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.069036} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2446661786770371, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1185389731335724, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1986404963888715, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.27601519370553795, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.069036} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.459949016571045, "x": 27.340599944413864, "y": 0.0024836875830622773, "z": null, "yaw": 3.1075800564717824, "pitch": null, "roll": null}, "v": 2.2000998814269144, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35840938895389296, "steering_wheel_angle": 0.1940262079505034, "front_wheel_angle": 0.008933265435008223, "heading_rate": 0.007677577758048259, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.089036} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2446661786770371, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1185389731335724, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1970590675638806, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.27601519370553795, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.089036} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.459949016571045, "x": 27.340599944413864, "y": 0.0024836875830622773, "z": null, "yaw": 3.1075800564717824, "pitch": null, "roll": null}, "v": 2.2000998814269144, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35840938895389296, "steering_wheel_angle": 0.1940262079505034, "front_wheel_angle": 0.008933265435008223, "heading_rate": 0.007677577758048259, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.109036} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2446661786770371, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1185389731335724, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.195480608819102, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.27601519370553795, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.109036} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.459949016571045, "x": 27.340599944413864, "y": 0.0024836875830622773, "z": null, "yaw": 3.1075800564717824, "pitch": null, "roll": null}, "v": 2.2000998814269144, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35840938895389296, "steering_wheel_angle": 0.1940262079505034, "front_wheel_angle": 0.008933265435008223, "heading_rate": 0.007677577758048259, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.129036} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2446661786770371, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1185389731335724, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1931184752260715, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.27601519370553795, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.129036} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.459949016571045, "x": 27.340599944413864, "y": 0.0024836875830622773, "z": null, "yaw": 3.1075800564717824, "pitch": null, "roll": null}, "v": 2.2000998814269144, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35840938895389296, "steering_wheel_angle": 0.1940262079505034, "front_wheel_angle": 0.008933265435008223, "heading_rate": 0.007677577758048259, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.149036} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2446661786770371, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1185389731335724, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1923325752911356, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.27601519370553795, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.149036} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502692.159036, "x": 31.099149627479964, "y": 5.010643899496992, "z": null, "yaw": 3.1081045300602463, "pitch": null, "roll": null}, "v": 2.1915474129587365, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3576061712803981, "steering_wheel_angle": 0.27601519370553795, "front_wheel_angle": 0.012721947603855715, "heading_rate": 0.01089150609527421, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.169036} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24080215198886154, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0858580897813228, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1907629874132475, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.27601519370553795, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.169036} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.56994891166687, "x": 27.099149627479964, "y": 0.010643899496992404, "z": null, "yaw": 3.1081045300602463, "pitch": null, "roll": null}, "v": 2.1915474129587365, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3576061712803981, "steering_wheel_angle": 0.27601519370553795, "front_wheel_angle": 0.012721947603855715, "heading_rate": 0.01089150609527421, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.189036} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2419695002106148, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0858580897813228, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1887135666117623, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.27601519370553795, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.189036} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.56994891166687, "x": 27.099149627479964, "y": 0.010643899496992404, "z": null, "yaw": 3.1081045300602463, "pitch": null, "roll": null}, "v": 2.1915474129587365, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3576061712803981, "steering_wheel_angle": 0.27601519370553795, "front_wheel_angle": 0.012721947603855715, "heading_rate": 0.01089150609527421, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.2090359} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2419695002106148, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0858580897813228, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.186813838211857, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.27601519370553795, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.2090359} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.56994891166687, "x": 27.099149627479964, "y": 0.010643899496992404, "z": null, "yaw": 3.1081045300602463, "pitch": null, "roll": null}, "v": 2.1915474129587365, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3576061712803981, "steering_wheel_angle": 0.27601519370553795, "front_wheel_angle": 0.012721947603855715, "heading_rate": 0.01089150609527421, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.2290359} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2419695002106148, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0858580897813228, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.184917669972826, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.27601519370553795, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.2290359} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.56994891166687, "x": 27.099149627479964, "y": 0.010643899496992404, "z": null, "yaw": 3.1081045300602463, "pitch": null, "roll": null}, "v": 2.1915474129587365, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3576061712803981, "steering_wheel_angle": 0.27601519370553795, "front_wheel_angle": 0.012721947603855715, "heading_rate": 0.01089150609527421, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.2490358} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2419695002106148, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0858580897813228, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.183025053785289, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.27601519370553795, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.2490358} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502692.2690358, "x": 30.85873053082815, "y": 5.0186383391461655, "z": null, "yaw": 3.1086512057394478, "pitch": null, "roll": null}, "v": 2.181135981563135, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3566303407788506, "steering_wheel_angle": 0.27601519370553795, "front_wheel_angle": 0.012721947603855715, "heading_rate": 0.010839763583186538, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.2690358} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24543174220471778, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1640880703523728, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.181135981563135, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.27601519370553795, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.2690358} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.679948806762695, "x": 26.85873053082815, "y": 0.018638339146165528, "z": null, "yaw": 3.1086512057394478, "pitch": null, "roll": null}, "v": 2.181135981563135, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3566303407788506, "steering_wheel_angle": 0.27601519370553795, "front_wheel_angle": 0.012721947603855715, "heading_rate": 0.010839763583186538, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.2890358} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2443009993151104, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1640880703523728, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.179683022938523, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3169948304672998, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.2890358} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.679948806762695, "x": 26.85873053082815, "y": 0.018638339146165528, "z": null, "yaw": 3.1086512057394478, "pitch": null, "roll": null}, "v": 2.181135981563135, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3566303407788506, "steering_wheel_angle": 0.27601519370553795, "front_wheel_angle": 0.012721947603855715, "heading_rate": 0.010839763583186538, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.3090358} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2443009993151104, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1640880703523728, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1780915062785096, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3169948304672998, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.3090358} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.679948806762695, "x": 26.85873053082815, "y": 0.018638339146165528, "z": null, "yaw": 3.1086512057394478, "pitch": null, "roll": null}, "v": 2.181135981563135, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3566303407788506, "steering_wheel_angle": 0.27601519370553795, "front_wheel_angle": 0.012721947603855715, "heading_rate": 0.010839763583186538, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.3290358} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2443009993151104, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1640880703523728, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.176502966582713, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3169948304672998, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.3290358} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.679948806762695, "x": 26.85873053082815, "y": 0.018638339146165528, "z": null, "yaw": 3.1086512057394478, "pitch": null, "roll": null}, "v": 2.181135981563135, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3566303407788506, "steering_wheel_angle": 0.27601519370553795, "front_wheel_angle": 0.012721947603855715, "heading_rate": 0.010839763583186538, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.3490357} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2443009993151104, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1640880703523728, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1749173972737506, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3169948304672998, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.3490357} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.679948806762695, "x": 26.85873053082815, "y": 0.018638339146165528, "z": null, "yaw": 3.1086512057394478, "pitch": null, "roll": null}, "v": 2.181135981563135, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3566303407788506, "steering_wheel_angle": 0.27601519370553795, "front_wheel_angle": 0.012721947603855715, "heading_rate": 0.010839763583186538, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.3690357} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2443009993151104, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1640880703523728, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.173334791792197, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3169948304672998, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.3690357} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502692.3790357, "x": 30.619357339301683, "y": 5.026459730897971, "z": null, "yaw": 3.1092719870687766, "pitch": null, "roll": null}, "v": 2.1725445984417737, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35582673024427397, "steering_wheel_angle": 0.3169948304672998, "front_wheel_angle": 0.014618697173622531, "heading_rate": 0.012407044607574084, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.3890357} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24181600484462912, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1486221513773818, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1717551435965254, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3169948304672998, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.3890357} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.78994870185852, "x": 26.619357339301683, "y": 0.0264597308979706, "z": null, "yaw": 3.1092719870687766, "pitch": null, "roll": null}, "v": 2.1725445984417737, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35582673024427397, "steering_wheel_angle": 0.3169948304672998, "front_wheel_angle": 0.014618697173622531, "heading_rate": 0.012407044607574084, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.4090357} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24255238557273454, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1486221513773818, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1698679669433973, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3169948304672998, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.4090357} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.78994870185852, "x": 26.619357339301683, "y": 0.0264597308979706, "z": null, "yaw": 3.1092719870687766, "pitch": null, "roll": null}, "v": 2.1725445984417737, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35582673024427397, "steering_wheel_angle": 0.3169948304672998, "front_wheel_angle": 0.014618697173622531, "heading_rate": 0.012407044607574084, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.4290357} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24255238557273454, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1486221513773818, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1680763187608347, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3169948304672998, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.4290357} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.78994870185852, "x": 26.619357339301683, "y": 0.0264597308979706, "z": null, "yaw": 3.1092719870687766, "pitch": null, "roll": null}, "v": 2.1725445984417737, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35582673024427397, "steering_wheel_angle": 0.3169948304672998, "front_wheel_angle": 0.014618697173622531, "heading_rate": 0.012407044607574084, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.4490356} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24255238557273454, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1486221513773818, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1662880147576353, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3169948304672998, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.4490356} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.78994870185852, "x": 26.619357339301683, "y": 0.0264597308979706, "z": null, "yaw": 3.1092719870687766, "pitch": null, "roll": null}, "v": 2.1725445984417737, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35582673024427397, "steering_wheel_angle": 0.3169948304672998, "front_wheel_angle": 0.014618697173622531, "heading_rate": 0.012407044607574084, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.4690356} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24255238557273454, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1486221513773818, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.164503047413146, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3169948304672998, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.4690356} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502692.4890356, "x": 30.38098964360499, "y": 5.03409853952491, "z": null, "yaw": 3.109900178963118, "pitch": null, "roll": null}, "v": 2.1627214092279026, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35490970940072236, "steering_wheel_angle": 0.3169948304672998, "front_wheel_angle": 0.014618697173622531, "heading_rate": 0.012350945990840254, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.4890356} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2457765079813335, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2239439633837197, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1627214092279026, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3169948304672998, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.4890356} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.899948596954346, "x": 26.38098964360499, "y": 0.034098539524910265, "z": null, "yaw": 3.109900178963118, "pitch": null, "roll": null}, "v": 2.1627214092279026, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35490970940072236, "steering_wheel_angle": 0.3169948304672998, "front_wheel_angle": 0.014618697173622531, "heading_rate": 0.012350945990840254, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.5090356} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24472311799581242, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2239439633837197, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1613459201416143, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3989570274009666, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.5090356} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.899948596954346, "x": 26.38098964360499, "y": 0.034098539524910265, "z": null, "yaw": 3.109900178963118, "pitch": null, "roll": null}, "v": 2.1627214092279026, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35490970940072236, "steering_wheel_angle": 0.3169948304672998, "front_wheel_angle": 0.014618697173622531, "heading_rate": 0.012350945990840254, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.5290356} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24472311799581242, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2239439633837197, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.15984138232116, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3989570274009666, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.5290356} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.899948596954346, "x": 26.38098964360499, "y": 0.034098539524910265, "z": null, "yaw": 3.109900178963118, "pitch": null, "roll": null}, "v": 2.1627214092279026, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35490970940072236, "steering_wheel_angle": 0.3169948304672998, "front_wheel_angle": 0.014618697173622531, "heading_rate": 0.012350945990840254, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.5490355} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24472311799581242, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2239439633837197, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1583396477832144, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3989570274009666, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.5490355} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.899948596954346, "x": 26.38098964360499, "y": 0.034098539524910265, "z": null, "yaw": 3.109900178963118, "pitch": null, "roll": null}, "v": 2.1627214092279026, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35490970940072236, "steering_wheel_angle": 0.3169948304672998, "front_wheel_angle": 0.014618697173622531, "heading_rate": 0.012350945990840254, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.5690355} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24472311799581242, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2239439633837197, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.156840710402986, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3989570274009666, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.5690355} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 53.899948596954346, "x": 26.38098964360499, "y": 0.034098539524910265, "z": null, "yaw": 3.109900178963118, "pitch": null, "roll": null}, "v": 2.1627214092279026, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35490970940072236, "steering_wheel_angle": 0.3169948304672998, "front_wheel_angle": 0.014618697173622531, "heading_rate": 0.012350945990840254, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.5890355} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24472311799581242, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2239439633837197, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1553445640721316, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3989570274009666, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.5890355} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502692.5990355, "x": 30.143608042403464, "y": 5.041543488415549, "z": null, "yaw": 3.110669419601192, "pitch": null, "roll": null}, "v": 2.154597535645846, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35415278218840385, "steering_wheel_angle": 0.3989570274009666, "front_wheel_angle": 0.018418554301408666, "heading_rate": 0.015503539019511063, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.6090355} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24237768806864066, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.176943281445883, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1538512026987005, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3989570274009666, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.6090355} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.00994849205017, "x": 26.143608042403464, "y": 0.04154348841554878, "z": null, "yaw": 3.110669419601192, "pitch": null, "roll": null}, "v": 2.154597535645846, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35415278218840385, "steering_wheel_angle": 0.3989570274009666, "front_wheel_angle": 0.018418554301408666, "heading_rate": 0.015503539019511063, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.6290355} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2430727890160096, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.176943281445883, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.152067577883197, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3989570274009666, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.6290355} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.00994849205017, "x": 26.143608042403464, "y": 0.04154348841554878, "z": null, "yaw": 3.110669419601192, "pitch": null, "roll": null}, "v": 2.154597535645846, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35415278218840385, "steering_wheel_angle": 0.3989570274009666, "front_wheel_angle": 0.018418554301408666, "heading_rate": 0.015503539019511063, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.6490355} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2430727890160096, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.176943281445883, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.150374118064181, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3989570274009666, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.6490355} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.00994849205017, "x": 26.143608042403464, "y": 0.04154348841554878, "z": null, "yaw": 3.110669419601192, "pitch": null, "roll": null}, "v": 2.154597535645846, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35415278218840385, "steering_wheel_angle": 0.3989570274009666, "front_wheel_angle": 0.018418554301408666, "heading_rate": 0.015503539019511063, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.6690354} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2430727890160096, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.176943281445883, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.148683807155588, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3989570274009666, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.6690354} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.00994849205017, "x": 26.143608042403464, "y": 0.04154348841554878, "z": null, "yaw": 3.110669419601192, "pitch": null, "roll": null}, "v": 2.154597535645846, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35415278218840385, "steering_wheel_angle": 0.3989570274009666, "front_wheel_angle": 0.018418554301408666, "heading_rate": 0.015503539019511063, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.6890354} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2430727890160096, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.176943281445883, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1469966381598344, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3989570274009666, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.6890354} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502692.7090354, "x": 29.90717579281735, "y": 5.048771993222283, "z": null, "yaw": 3.1114609313633363, "pitch": null, "roll": null}, "v": 2.1453126040987147, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35328929189798386, "steering_wheel_angle": 0.3989570274009666, "front_wheel_angle": 0.018418554301408666, "heading_rate": 0.015436728723781613, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.7090354} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2465757060583484, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2449596902435376, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1453126040987147, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3989570274009666, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.7090354} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.119948387145996, "x": 25.90717579281735, "y": 0.04877199322228343, "z": null, "yaw": 3.1114609313633363, "pitch": null, "roll": null}, "v": 2.1453126040987147, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35328929189798386, "steering_wheel_angle": 0.3989570274009666, "front_wheel_angle": 0.018418554301408666, "heading_rate": 0.015436728723781613, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.7290354} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24543786922207256, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2449596902435376, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1440693592738422, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3989570274009666, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.7290354} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.119948387145996, "x": 25.90717579281735, "y": 0.04877199322228343, "z": null, "yaw": 3.1114609313633363, "pitch": null, "roll": null}, "v": 2.1453126040987147, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35328929189798386, "steering_wheel_angle": 0.3989570274009666, "front_wheel_angle": 0.018418554301408666, "heading_rate": 0.015436728723781613, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.7490354} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24543786922207256, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2449596902435376, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.142686259455547, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3989570274009666, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.7490354} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.119948387145996, "x": 25.90717579281735, "y": 0.04877199322228343, "z": null, "yaw": 3.1114609313633363, "pitch": null, "roll": null}, "v": 2.1453126040987147, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35328929189798386, "steering_wheel_angle": 0.3989570274009666, "front_wheel_angle": 0.018418554301408666, "heading_rate": 0.015436728723781613, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.7690353} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24543786922207256, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2449596902435376, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1413057271553853, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3989570274009666, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.7690353} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.119948387145996, "x": 25.90717579281735, "y": 0.04877199322228343, "z": null, "yaw": 3.1114609313633363, "pitch": null, "roll": null}, "v": 2.1453126040987147, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35328929189798386, "steering_wheel_angle": 0.3989570274009666, "front_wheel_angle": 0.018418554301408666, "heading_rate": 0.015436728723781613, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.7890353} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24543786922207256, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2449596902435376, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1399277568451485, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3989570274009666, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.7890353} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.119948387145996, "x": 25.90717579281735, "y": 0.04877199322228343, "z": null, "yaw": 3.1114609313633363, "pitch": null, "roll": null}, "v": 2.1453126040987147, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35328929189798386, "steering_wheel_angle": 0.3989570274009666, "front_wheel_angle": 0.018418554301408666, "heading_rate": 0.015436728723781613, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.8090353} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24543786922207256, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2449596902435376, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1385523430111313, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3989570274009666, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.8090353} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502692.8190353, "x": 29.671662474334322, "y": 5.055785808911519, "z": null, "yaw": 3.1122524431254805, "pitch": null, "roll": null}, "v": 2.1378655930536254, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35259797259230663, "steering_wheel_angle": 0.3989570274009666, "front_wheel_angle": 0.018418554301408666, "heading_rate": 0.015383143298008968, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.8290353} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24789411865465044, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2926588368318093, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.137179480154082, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.3989570274009666, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.8290353} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.22994828224182, "x": 25.671662474334322, "y": 0.0557858089115193, "z": null, "yaw": 3.1122524431254805, "pitch": null, "roll": null}, "v": 2.1378655930536254, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35259797259230663, "steering_wheel_angle": 0.3989570274009666, "front_wheel_angle": 0.018418554301408666, "heading_rate": 0.015383143298008968, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.8490353} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24709197421575912, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2926588368318093, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.136116051611051, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.8490353} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.22994828224182, "x": 25.671662474334322, "y": 0.0557858089115193, "z": null, "yaw": 3.1122524431254805, "pitch": null, "roll": null}, "v": 2.1378655930536254, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35259797259230663, "steering_wheel_angle": 0.3989570274009666, "front_wheel_angle": 0.018418554301408666, "heading_rate": 0.015383143298008968, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.8690352} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24709197421575912, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2926588368318093, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1349543727630325, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.8690352} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.22994828224182, "x": 25.671662474334322, "y": 0.0557858089115193, "z": null, "yaw": 3.1122524431254805, "pitch": null, "roll": null}, "v": 2.1378655930536254, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35259797259230663, "steering_wheel_angle": 0.3989570274009666, "front_wheel_angle": 0.018418554301408666, "heading_rate": 0.015383143298008968, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.8890352} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24709197421575912, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2926588368318093, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.133794846783039, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.8890352} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.22994828224182, "x": 25.671662474334322, "y": 0.0557858089115193, "z": null, "yaw": 3.1122524431254805, "pitch": null, "roll": null}, "v": 2.1378655930536254, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35259797259230663, "steering_wheel_angle": 0.3989570274009666, "front_wheel_angle": 0.018418554301408666, "heading_rate": 0.015383143298008968, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.9090352} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24709197421575912, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2926588368318093, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1326374691437415, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.9090352} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502692.9290352, "x": 29.436917000673038, "y": 5.062580624078933, "z": null, "yaw": 3.113170417768091, "pitch": null, "roll": null}, "v": 2.131482235329187, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35200627696169845, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01850843494479745, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.9290352} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.248375202494087, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3041873285170986, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.131482235329187, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.9290352} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.33994817733765, "x": 25.436917000673038, "y": 0.06258062407893306, "z": null, "yaw": 3.113170417768091, "pitch": null, "roll": null}, "v": 2.131482235329187, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35200627696169845, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01850843494479745, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.9490352} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24794460859325979, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3041873285170986, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.130489470087551, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.9490352} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.33994817733765, "x": 25.436917000673038, "y": 0.06258062407893306, "z": null, "yaw": 3.113170417768091, "pitch": null, "roll": null}, "v": 2.131482235329187, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35200627696169845, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01850843494479745, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.9690351} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24794460859325979, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3041873285170986, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.129444743571487, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.9690351} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.33994817733765, "x": 25.436917000673038, "y": 0.06258062407893306, "z": null, "yaw": 3.113170417768091, "pitch": null, "roll": null}, "v": 2.131482235329187, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35200627696169845, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01850843494479745, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502692.9890351} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24794460859325979, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3041873285170986, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.128401950870376, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502692.9890351} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.33994817733765, "x": 25.436917000673038, "y": 0.06258062407893306, "z": null, "yaw": 3.113170417768091, "pitch": null, "roll": null}, "v": 2.131482235329187, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35200627696169845, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01850843494479745, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.009035} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24794460859325979, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3041873285170986, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1273610879699127, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.009035} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.33994817733765, "x": 25.436917000673038, "y": 0.06258062407893306, "z": null, "yaw": 3.113170417768091, "pitch": null, "roll": null}, "v": 2.131482235329187, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35200627696169845, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01850843494479745, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.029035} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24794460859325979, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3041873285170986, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1263221508656343, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.029035} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502693.039035, "x": 29.202827726728685, "y": 5.0691340912646305, "z": null, "yaw": 3.1141255877480174, "pitch": null, "roll": null}, "v": 2.125803403238354, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3514805712541154, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018459123581759336, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.049035} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24768946164358754, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2381846391075275, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.125285135562892, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.049035} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.44994807243347, "x": 25.202827726728685, "y": 0.06913409126463055, "z": null, "yaw": 3.1141255877480174, "pitch": null, "roll": null}, "v": 2.125803403238354, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3514805712541154, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018459123581759336, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.069035} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2477429098150243, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2381846391075275, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1242181594580263, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.069035} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.44994807243347, "x": 25.202827726728685, "y": 0.06913409126463055, "z": null, "yaw": 3.1141255877480174, "pitch": null, "roll": null}, "v": 2.125803403238354, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3514805712541154, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018459123581759336, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.089035} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2477429098150243, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2381846391075275, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.123159834058775, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.089035} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.44994807243347, "x": 25.202827726728685, "y": 0.06913409126463055, "z": null, "yaw": 3.1141255877480174, "pitch": null, "roll": null}, "v": 2.125803403238354, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3514805712541154, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018459123581759336, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.109035} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2477429098150243, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2381846391075275, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1221034649896597, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.109035} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.44994807243347, "x": 25.202827726728685, "y": 0.06913409126463055, "z": null, "yaw": 3.1141255877480174, "pitch": null, "roll": null}, "v": 2.125803403238354, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3514805712541154, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018459123581759336, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.129035} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2477429098150243, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2381846391075275, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1210490481882136, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.129035} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502693.149035, "x": 28.96936517560978, "y": 5.075446848843851, "z": null, "yaw": 3.115080757727944, "pitch": null, "roll": null}, "v": 2.1199965796019535, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35094368395533754, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018408700821612035, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.149035} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24404869848387808, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1067987070536842, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1199965796019535, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.149035} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.5599479675293, "x": 24.96936517560978, "y": 0.07544684884385067, "z": null, "yaw": 3.115080757727944, "pitch": null, "roll": null}, "v": 2.1199965796019535, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35094368395533754, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018408700821612035, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.169035} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24517629589923287, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1067987070536842, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1184844920829033, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.169035} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.5599479675293, "x": 24.96936517560978, "y": 0.07544684884385067, "z": null, "yaw": 3.115080757727944, "pitch": null, "roll": null}, "v": 2.1199965796019535, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35094368395533754, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018408700821612035, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.189035} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24517629589923287, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1067987070536842, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1164328239157144, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.189035} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.5599479675293, "x": 24.96936517560978, "y": 0.07544684884385067, "z": null, "yaw": 3.115080757727944, "pitch": null, "roll": null}, "v": 2.1199965796019535, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35094368395533754, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018408700821612035, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.209035} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24517629589923287, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1067987070536842, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.115750197207644, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.209035} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.5599479675293, "x": 24.96936517560978, "y": 0.07544684884385067, "z": null, "yaw": 3.115080757727944, "pitch": null, "roll": null}, "v": 2.1199965796019535, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35094368395533754, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018408700821612035, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.229035} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24517629589923287, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1067987070536842, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.114386833757022, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.229035} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.5599479675293, "x": 24.96936517560978, "y": 0.07544684884385067, "z": null, "yaw": 3.115080757727944, "pitch": null, "roll": null}, "v": 2.1199965796019535, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35094368395533754, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018408700821612035, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.249035} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24517629589923287, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.1067987070536842, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.113025985765553, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.249035} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502693.2590349, "x": 28.73663426814703, "y": 5.081517384318908, "z": null, "yaw": 3.11603592770787, "pitch": null, "roll": null}, "v": 2.11234650338472, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3502374026728526, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01834227242936811, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.2690349} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24910865525306555, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.171033920132796, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.111667647851694, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.2690349} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.66994786262512, "x": 24.73663426814703, "y": 0.08151738431890809, "z": null, "yaw": 3.11603592770787, "pitch": null, "roll": null}, "v": 2.11234650338472, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3502374026728526, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01834227242936811, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.2890348} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24784447806200943, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.171033920132796, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.110292462236102, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.2890348} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.66994786262512, "x": 24.73663426814703, "y": 0.08151738431890809, "z": null, "yaw": 3.11603592770787, "pitch": null, "roll": null}, "v": 2.11234650338472, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3502374026728526, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01834227242936811, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.3090348} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24784447806200943, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.171033920132796, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1097822624562426, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.3090348} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.66994786262512, "x": 24.73663426814703, "y": 0.08151738431890809, "z": null, "yaw": 3.11603592770787, "pitch": null, "roll": null}, "v": 2.11234650338472, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3502374026728526, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01834227242936811, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.3290348} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24784447806200943, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.171033920132796, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1087632736348434, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.3290348} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.66994786262512, "x": 24.73663426814703, "y": 0.08151738431890809, "z": null, "yaw": 3.11603592770787, "pitch": null, "roll": null}, "v": 2.11234650338472, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3502374026728526, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01834227242936811, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.3490348} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24784447806200943, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.171033920132796, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1077461625627714, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.3490348} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502693.3690348, "x": 28.504633490556156, "y": 5.087347111754682, "z": null, "yaw": 3.1169910976877966, "pitch": null, "roll": null}, "v": 2.106730925366174, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3497196981872509, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.0182935103244296, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.3690348} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2512132168395612, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.242088770229883, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.106730925366174, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.3690348} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.77994775772095, "x": 24.504633490556156, "y": 0.08734711175468224, "z": null, "yaw": 3.1169910976877966, "pitch": null, "roll": null}, "v": 2.106730925366174, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3497196981872509, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.0182935103244296, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.3890347} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2501346000400999, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.242088770229883, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.106138456558816, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.3890347} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.77994775772095, "x": 24.504633490556156, "y": 0.08734711175468224, "z": null, "yaw": 3.1169910976877966, "pitch": null, "roll": null}, "v": 2.106730925366174, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3497196981872509, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.0182935103244296, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.4090347} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2501346000400999, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.242088770229883, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.105412313879935, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.4090347} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.77994775772095, "x": 24.504633490556156, "y": 0.08734711175468224, "z": null, "yaw": 3.1169910976877966, "pitch": null, "roll": null}, "v": 2.106730925366174, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3497196981872509, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.0182935103244296, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.4290347} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2501346000400999, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.242088770229883, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1046875083122782, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.4290347} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.77994775772095, "x": 24.504633490556156, "y": 0.08734711175468224, "z": null, "yaw": 3.1169910976877966, "pitch": null, "roll": null}, "v": 2.106730925366174, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3497196981872509, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.0182935103244296, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.4490347} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2501346000400999, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.242088770229883, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1039640371836623, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.4490347} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.77994775772095, "x": 24.504633490556156, "y": 0.08734711175468224, "z": null, "yaw": 3.1169910976877966, "pitch": null, "roll": null}, "v": 2.106730925366174, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3497196981872509, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.0182935103244296, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.4690347} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2501346000400999, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.242088770229883, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1032418978279845, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.4690347} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502693.4790347, "x": 28.27314748709074, "y": 5.092942646976216, "z": null, "yaw": 3.117946267667723, "pitch": null, "roll": null}, "v": 2.102881326733499, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3493651650799193, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018260082860350618, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.4890347} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.253006023174405, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3211479268021353, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.102521087585206, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.4890347} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.88994765281677, "x": 24.27314748709074, "y": 0.09294264697621557, "z": null, "yaw": 3.117946267667723, "pitch": null, "roll": null}, "v": 2.102881326733499, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3493651650799193, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018260082860350618, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.5090346} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2520909761896165, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3211479268021353, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.102160366505501, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.5090346} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.88994765281677, "x": 24.27314748709074, "y": 0.09294264697621557, "z": null, "yaw": 3.117946267667723, "pitch": null, "roll": null}, "v": 2.102881326733499, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3493651650799193, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018260082860350618, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.5290346} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2520909761896165, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3211479268021353, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1016859809361295, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.5290346} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.88994765281677, "x": 24.27314748709074, "y": 0.09294264697621557, "z": null, "yaw": 3.117946267667723, "pitch": null, "roll": null}, "v": 2.102881326733499, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3493651650799193, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018260082860350618, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.5490346} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2520909761896165, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3211479268021353, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.101212468176807, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.5490346} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.88994765281677, "x": 24.27314748709074, "y": 0.09294264697621557, "z": null, "yaw": 3.117946267667723, "pitch": null, "roll": null}, "v": 2.102881326733499, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3493651650799193, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018260082860350618, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.5690346} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2520909761896165, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3211479268021353, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.100739826532028, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.5690346} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502693.5890346, "x": 28.042025837779523, "y": 5.098308478901062, "z": null, "yaw": 3.1189014376476494, "pitch": null, "roll": null}, "v": 2.100268054309901, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34912466171504203, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018237390866092582, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.5890346} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25150713319424656, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2607888108358332, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.100268054309901, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.5890346} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.9999475479126, "x": 24.042025837779523, "y": 0.0983084789010622, "z": null, "yaw": 3.1189014376476494, "pitch": null, "roll": null}, "v": 2.100268054309901, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34912466171504203, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018237390866092582, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.6090345} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25167755907379574, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2607888108358332, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0997242030187935, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.6090345} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.9999475479126, "x": 24.042025837779523, "y": 0.0983084789010622, "z": null, "yaw": 3.1189014376476494, "pitch": null, "roll": null}, "v": 2.100268054309901, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34912466171504203, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018237390866092582, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.6290345} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25167755907379574, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2607888108358332, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0992026453599784, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.6290345} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.9999475479126, "x": 24.042025837779523, "y": 0.0983084789010622, "z": null, "yaw": 3.1189014376476494, "pitch": null, "roll": null}, "v": 2.100268054309901, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34912466171504203, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018237390866092582, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.6490345} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25167755907379574, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2607888108358332, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0986820467868053, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.6490345} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.9999475479126, "x": 24.042025837779523, "y": 0.0983084789010622, "z": null, "yaw": 3.1189014376476494, "pitch": null, "roll": null}, "v": 2.100268054309901, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34912466171504203, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018237390866092582, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.6690345} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25167755907379574, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2607888108358332, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0981624054272645, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.6690345} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 54.9999475479126, "x": 24.042025837779523, "y": 0.0983084789010622, "z": null, "yaw": 3.1189014376476494, "pitch": null, "roll": null}, "v": 2.100268054309901, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34912466171504203, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018237390866092582, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.6890345} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25167755907379574, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2607888108358332, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.097643719413387, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.6890345} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502693.6990345, "x": 27.811198935337504, "y": 5.103446877798125, "z": null, "yaw": 3.1198566076275758, "pitch": null, "roll": null}, "v": 2.097384734078433, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3488594639313743, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018212353948568898, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.7090344} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2531731070877572, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2569802529400453, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0971259868812315, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.7090344} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.10994744300842, "x": 23.811198935337504, "y": 0.10344687779812478, "z": null, "yaw": 3.1198566076275758, "pitch": null, "roll": null}, "v": 2.097384734078433, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3488594639313743, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018212353948568898, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.7290344} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2526924881290925, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2569802529400453, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.096796063536299, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.7290344} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.10994744300842, "x": 23.811198935337504, "y": 0.10344687779812478, "z": null, "yaw": 3.1198566076275758, "pitch": null, "roll": null}, "v": 2.097384734078433, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3488594639313743, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018212353948568898, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.7490344} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2526924881290925, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2569802529400453, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0964066968049506, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.7490344} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.10994744300842, "x": 23.811198935337504, "y": 0.10344687779812478, "z": null, "yaw": 3.1198566076275758, "pitch": null, "roll": null}, "v": 2.097384734078433, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3488594639313743, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018212353948568898, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.7690344} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2526924881290925, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2569802529400453, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.096018045634851, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.7690344} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.10994744300842, "x": 23.811198935337504, "y": 0.10344687779812478, "z": null, "yaw": 3.1198566076275758, "pitch": null, "roll": null}, "v": 2.097384734078433, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3488594639313743, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018212353948568898, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.7890344} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2526924881290925, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2569802529400453, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.095630108650581, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.7890344} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502693.8090343, "x": 27.580647297491975, "y": 5.1083588219052976, "z": null, "yaw": 3.120811777607502, "pitch": null, "roll": null}, "v": 2.095242884479581, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3486625716736022, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01819375549003857, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.8090343} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25412294788735346, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2488575657181733, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.095242884479581, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.8090343} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.21994733810425, "x": 23.580647297491975, "y": 0.10835882190529755, "z": null, "yaw": 3.120811777607502, "pitch": null, "roll": null}, "v": 2.095242884479581, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3486625716736022, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01819375549003857, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.8290343} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2536660843004652, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2488575657181733, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0950350970582114, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.8290343} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.21994733810425, "x": 23.580647297491975, "y": 0.10835882190529755, "z": null, "yaw": 3.120811777607502, "pitch": null, "roll": null}, "v": 2.095242884479581, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3486625716736022, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01819375549003857, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.8490343} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2536660843004652, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2488575657181733, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0947706096741308, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.8490343} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.21994733810425, "x": 23.580647297491975, "y": 0.10835882190529755, "z": null, "yaw": 3.120811777607502, "pitch": null, "roll": null}, "v": 2.095242884479581, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3486625716736022, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01819375549003857, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.8690343} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2536660843004652, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2488575657181733, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0945066081772326, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.8690343} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.21994733810425, "x": 23.580647297491975, "y": 0.10835882190529755, "z": null, "yaw": 3.120811777607502, "pitch": null, "roll": null}, "v": 2.095242884479581, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3486625716736022, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01819375549003857, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.8890343} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2536660843004652, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2488575657181733, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.094243091647032, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.8890343} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.21994733810425, "x": 23.580647297491975, "y": 0.10835882190529755, "z": null, "yaw": 3.120811777607502, "pitch": null, "roll": null}, "v": 2.095242884479581, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3486625716736022, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01819375549003857, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.9090343} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2536660843004652, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2488575657181733, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.093980059164889, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.9090343} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502693.9190342, "x": 27.350285548830747, "y": 5.11304658426857, "z": null, "yaw": 3.1217669475874286, "pitch": null, "roll": null}, "v": 2.0938487241552677, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3485344610042298, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018181649489229616, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.9290342} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25467048956662924, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2448778431826115, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0937175098140046, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.9290342} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.32994723320007, "x": 23.350285548830747, "y": 0.11304658426857017, "z": null, "yaw": 3.1217669475874286, "pitch": null, "roll": null}, "v": 2.0938487241552677, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3485344610042298, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018181649489229616, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.9490342} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25435020717749085, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2448778431826115, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.093580935664512, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.9490342} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.32994723320007, "x": 23.350285548830747, "y": 0.11304658426857017, "z": null, "yaw": 3.1217669475874286, "pitch": null, "roll": null}, "v": 2.0938487241552677, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3485344610042298, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018181649489229616, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.9690342} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25435020717749085, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2448778431826115, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.093404595438956, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.9690342} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.32994723320007, "x": 23.350285548830747, "y": 0.11304658426857017, "z": null, "yaw": 3.1217669475874286, "pitch": null, "roll": null}, "v": 2.0938487241552677, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3485344610042298, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018181649489229616, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502693.9890342} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25435020717749085, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2448778431826115, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.093228579068483, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502693.9890342} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.32994723320007, "x": 23.350285548830747, "y": 0.11304658426857017, "z": null, "yaw": 3.1217669475874286, "pitch": null, "roll": null}, "v": 2.0938487241552677, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3485344610042298, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018181649489229616, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.0090342} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25435020717749085, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2448778431826115, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0930528859459336, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.0090342} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502694.0290341, "x": 27.12005487601691, "y": 5.117511678991158, "z": null, "yaw": 3.122722117567355, "pitch": null, "roll": null}, "v": 2.0928775154653336, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3484452387206702, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018173216131185374, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.0290341} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2563920266492972, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3072721896025186, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0928775154653336, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.0290341} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.4399471282959, "x": 23.12005487601691, "y": 0.11751167899115789, "z": null, "yaw": 3.122722117567355, "pitch": null, "roll": null}, "v": 2.0928775154653336, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3484452387206702, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018173216131185374, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.049034} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25574949652890416, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3072721896025186, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.092957577233636, "gear": 1, "accelerator_pedal_position": 0.2563920266492972, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.049034} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.4399471282959, "x": 23.12005487601691, "y": 0.11751167899115789, "z": null, "yaw": 3.122722117567355, "pitch": null, "roll": null}, "v": 2.0928775154653336, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3484452387206702, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018173216131185374, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.069034} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25574949652890416, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3072721896025186, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0929572126060445, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.069034} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.4399471282959, "x": 23.12005487601691, "y": 0.11751167899115789, "z": null, "yaw": 3.122722117567355, "pitch": null, "roll": null}, "v": 2.0928775154653336, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3484452387206702, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018173216131185374, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.089034} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25574949652890416, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3072721896025186, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0929568486480328, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.089034} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.4399471282959, "x": 23.12005487601691, "y": 0.11751167899115789, "z": null, "yaw": 3.122722117567355, "pitch": null, "roll": null}, "v": 2.0928775154653336, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3484452387206702, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018173216131185374, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.109034} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25574949652890416, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3072721896025186, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0929564853583713, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.109034} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.4399471282959, "x": 23.12005487601691, "y": 0.11751167899115789, "z": null, "yaw": 3.122722117567355, "pitch": null, "roll": null}, "v": 2.0928775154653336, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3484452387206702, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018173216131185374, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.129034} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25574949652890416, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.3072721896025186, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0929561227358326, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.129034} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502694.139034, "x": 26.889869942888467, "y": 5.121755933504789, "z": null, "yaw": 3.1236772875472814, "pitch": null, "roll": null}, "v": 2.0929559416743513, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3484524428216173, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018173897134462585, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.149034} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2568124780277934, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2870336004955234, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0929557607791915, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.149034} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.549947023391724, "x": 22.889869942888467, "y": 0.1217559335047893, "z": null, "yaw": 3.1236772875472814, "pitch": null, "roll": null}, "v": 2.0929559416743513, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3484524428216173, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018173897134462585, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.169034} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2564806562968786, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2870336004955234, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0930882111463105, "gear": 1, "accelerator_pedal_position": 0.2568124780277934, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.169034} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.549947023391724, "x": 22.889869942888467, "y": 0.1217559335047893, "z": null, "yaw": 3.1236772875472814, "pitch": null, "roll": null}, "v": 2.0929559416743513, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3484524428216173, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018173897134462585, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.189034} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2564806562968786, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2870336004955234, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0931789596194124, "gear": 1, "accelerator_pedal_position": 0.2564806562968786, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.189034} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.549947023391724, "x": 22.889869942888467, "y": 0.1217559335047893, "z": null, "yaw": 3.1236772875472814, "pitch": null, "roll": null}, "v": 2.0929559416743513, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3484524428216173, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018173897134462585, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.209034} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2564806562968786, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2870336004955234, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.093269541440328, "gear": 1, "accelerator_pedal_position": 0.2564806562968786, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.209034} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.549947023391724, "x": 22.889869942888467, "y": 0.1217559335047893, "z": null, "yaw": 3.1236772875472814, "pitch": null, "roll": null}, "v": 2.0929559416743513, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3484524428216173, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018173897134462585, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.229034} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2564806562968786, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2870336004955234, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0933599569118204, "gear": 1, "accelerator_pedal_position": 0.2564806562968786, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.229034} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502694.249034, "x": 26.65965605038508, "y": 5.125780753594502, "z": null, "yaw": 3.1246324575272078, "pitch": null, "roll": null}, "v": 2.0934502063361147, "accelerator_pedal_position": 0.2564806562968786, "brake_pedal_position": 0.0, "acceleration": 0.004506253874598298, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018178189014163074, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.249034} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2573261444034519, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2496628703992003, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0934502063361147, "gear": 1, "accelerator_pedal_position": 0.2564806562968786, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.249034} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.65994691848755, "x": 22.65965605038508, "y": 0.12578075359450214, "z": null, "yaw": 3.1246324575272078, "pitch": null, "roll": null}, "v": 2.0934502063361147, "accelerator_pedal_position": 0.2564806562968786, "brake_pedal_position": 0.0, "acceleration": 0.004506253874598298, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018178189014163074, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.269034} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25706419945636705, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2496628703992003, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0936459274811203, "gear": 1, "accelerator_pedal_position": 0.2573261444034519, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.269034} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.65994691848755, "x": 22.65965605038508, "y": 0.12578075359450214, "z": null, "yaw": 3.1246324575272078, "pitch": null, "roll": null}, "v": 2.0934502063361147, "accelerator_pedal_position": 0.2564806562968786, "brake_pedal_position": 0.0, "acceleration": 0.004506253874598298, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018178189014163074, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.289034} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25706419945636705, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2496628703992003, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.093808561088636, "gear": 1, "accelerator_pedal_position": 0.25706419945636705, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.289034} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.65994691848755, "x": 22.65965605038508, "y": 0.12578075359450214, "z": null, "yaw": 3.1246324575272078, "pitch": null, "roll": null}, "v": 2.0934502063361147, "accelerator_pedal_position": 0.2564806562968786, "brake_pedal_position": 0.0, "acceleration": 0.004506253874598298, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018178189014163074, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.3090339} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25706419945636705, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2496628703992003, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0939708959930154, "gear": 1, "accelerator_pedal_position": 0.25706419945636705, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.3090339} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.65994691848755, "x": 22.65965605038508, "y": 0.12578075359450214, "z": null, "yaw": 3.1246324575272078, "pitch": null, "roll": null}, "v": 2.0934502063361147, "accelerator_pedal_position": 0.2564806562968786, "brake_pedal_position": 0.0, "acceleration": 0.004506253874598298, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018178189014163074, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.3290339} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25706419945636705, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2496628703992003, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0941329327323386, "gear": 1, "accelerator_pedal_position": 0.25706419945636705, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.3290339} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.65994691848755, "x": 22.65965605038508, "y": 0.12578075359450214, "z": null, "yaw": 3.1246324575272078, "pitch": null, "roll": null}, "v": 2.0934502063361147, "accelerator_pedal_position": 0.2564806562968786, "brake_pedal_position": 0.0, "acceleration": 0.004506253874598298, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018178189014163074, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.3490338} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25706419945636705, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.2496628703992003, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0942946718437563, "gear": 1, "accelerator_pedal_position": 0.25706419945636705, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.3490338} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502694.3590338, "x": 26.42936016906471, "y": 5.129586968310505, "z": null, "yaw": 3.125587627507134, "pitch": null, "roll": null}, "v": 2.094375429956606, "accelerator_pedal_position": 0.25706419945636705, "brake_pedal_position": 0.0, "acceleration": 0.008068390688404481, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018186223067135892, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.3690338} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2561992563890647, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0353110850625946, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0944561138634903, "gear": 1, "accelerator_pedal_position": 0.25706419945636705, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.3690338} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.769946813583374, "x": 22.42936016906471, "y": 0.1295869683105053, "z": null, "yaw": 3.125587627507134, "pitch": null, "roll": null}, "v": 2.094375429956606, "accelerator_pedal_position": 0.25706419945636705, "brake_pedal_position": 0.0, "acceleration": 0.008068390688404481, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018186223067135892, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.3890338} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25647380167425243, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0353110850625946, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0945091911182883, "gear": 1, "accelerator_pedal_position": 0.2561992563890647, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.3890338} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.769946813583374, "x": 22.42936016906471, "y": 0.1295869683105053, "z": null, "yaw": 3.125587627507134, "pitch": null, "roll": null}, "v": 2.094375429956606, "accelerator_pedal_position": 0.25706419945636705, "brake_pedal_position": 0.0, "acceleration": 0.008068390688404481, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018186223067135892, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.4090338} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25647380167425243, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0353110850625946, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0945964732656286, "gear": 1, "accelerator_pedal_position": 0.25647380167425243, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.4090338} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.769946813583374, "x": 22.42936016906471, "y": 0.1295869683105053, "z": null, "yaw": 3.125587627507134, "pitch": null, "roll": null}, "v": 2.094375429956606, "accelerator_pedal_position": 0.25706419945636705, "brake_pedal_position": 0.0, "acceleration": 0.008068390688404481, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018186223067135892, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.4290338} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25647380167425243, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0353110850625946, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0946835950769342, "gear": 1, "accelerator_pedal_position": 0.25647380167425243, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.4290338} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.769946813583374, "x": 22.42936016906471, "y": 0.1295869683105053, "z": null, "yaw": 3.125587627507134, "pitch": null, "roll": null}, "v": 2.094375429956606, "accelerator_pedal_position": 0.25706419945636705, "brake_pedal_position": 0.0, "acceleration": 0.008068390688404481, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018186223067135892, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.4490337} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25647380167425243, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0353110850625946, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0947705568437054, "gear": 1, "accelerator_pedal_position": 0.25647380167425243, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.4490337} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502694.4690337, "x": 26.198982028236397, "y": 5.133174439529274, "z": null, "yaw": 3.1265427974870605, "pitch": null, "roll": null}, "v": 2.0948573588569235, "accelerator_pedal_position": 0.25647380167425243, "brake_pedal_position": 0.0, "acceleration": 0.004334118981661361, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01819040783093626, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.4690337} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25848563947347525, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0862990913809534, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0948573588569235, "gear": 1, "accelerator_pedal_position": 0.25647380167425243, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.4690337} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.8799467086792, "x": 22.198982028236397, "y": 0.13317443952927377, "z": null, "yaw": 3.1265427974870605, "pitch": null, "roll": null}, "v": 2.0948573588569235, "accelerator_pedal_position": 0.25647380167425243, "brake_pedal_position": 0.0, "acceleration": 0.004334118981661361, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01819040783093626, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.4890337} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2578591540288886, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0862990913809534, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.095195365577937, "gear": 1, "accelerator_pedal_position": 0.25848563947347525, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.4890337} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.8799467086792, "x": 22.198982028236397, "y": 0.13317443952927377, "z": null, "yaw": 3.1265427974870605, "pitch": null, "roll": null}, "v": 2.0948573588569235, "accelerator_pedal_position": 0.25647380167425243, "brake_pedal_position": 0.0, "acceleration": 0.004334118981661361, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01819040783093626, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.5090337} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2578591540288886, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0862990913809534, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0954544766189773, "gear": 1, "accelerator_pedal_position": 0.2578591540288886, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.5090337} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.8799467086792, "x": 22.198982028236397, "y": 0.13317443952927377, "z": null, "yaw": 3.1265427974870605, "pitch": null, "roll": null}, "v": 2.0948573588569235, "accelerator_pedal_position": 0.25647380167425243, "brake_pedal_position": 0.0, "acceleration": 0.004334118981661361, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01819040783093626, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.5290337} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2578591540288886, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0862990913809534, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0957131115924095, "gear": 1, "accelerator_pedal_position": 0.2578591540288886, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.5290337} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.8799467086792, "x": 22.198982028236397, "y": 0.13317443952927377, "z": null, "yaw": 3.1265427974870605, "pitch": null, "roll": null}, "v": 2.0948573588569235, "accelerator_pedal_position": 0.25647380167425243, "brake_pedal_position": 0.0, "acceleration": 0.004334118981661361, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01819040783093626, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.5490336} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2578591540288886, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0862990913809534, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.095971271346173, "gear": 1, "accelerator_pedal_position": 0.2578591540288886, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.5490336} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.8799467086792, "x": 22.198982028236397, "y": 0.13317443952927377, "z": null, "yaw": 3.1265427974870605, "pitch": null, "roll": null}, "v": 2.0948573588569235, "accelerator_pedal_position": 0.25647380167425243, "brake_pedal_position": 0.0, "acceleration": 0.004334118981661361, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01819040783093626, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.5690336} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2578591540288886, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0862990913809534, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0962289567267978, "gear": 1, "accelerator_pedal_position": 0.2578591540288886, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.5690336} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502694.5790336, "x": 25.968493674810173, "y": 5.136543412440239, "z": null, "yaw": 3.127497967466987, "pitch": null, "roll": null}, "v": 2.0963576217913378, "accelerator_pedal_position": 0.2578591540288886, "brake_pedal_position": 0.0, "acceleration": 0.012854678806560382, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018203435159272127, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.5890336} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25957929467269436, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.142497520608681, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0964861685794034, "gear": 1, "accelerator_pedal_position": 0.2578591540288886, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.5890336} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.989946603775024, "x": 21.968493674810173, "y": 0.13654341244023893, "z": null, "yaw": 3.127497967466987, "pitch": null, "roll": null}, "v": 2.0963576217913378, "accelerator_pedal_position": 0.2578591540288886, "brake_pedal_position": 0.0, "acceleration": 0.012854678806560382, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018203435159272127, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.6090336} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2590486449931629, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.142497520608681, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0969578264917295, "gear": 1, "accelerator_pedal_position": 0.25957929467269436, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.6090336} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.989946603775024, "x": 21.968493674810173, "y": 0.13654341244023893, "z": null, "yaw": 3.127497967466987, "pitch": null, "roll": null}, "v": 2.0963576217913378, "accelerator_pedal_position": 0.2578591540288886, "brake_pedal_position": 0.0, "acceleration": 0.012854678806560382, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018203435159272127, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.6290336} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2590486449931629, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.142497520608681, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0975642831169004, "gear": 1, "accelerator_pedal_position": 0.2590486449931629, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.6290336} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.989946603775024, "x": 21.968493674810173, "y": 0.13654341244023893, "z": null, "yaw": 3.127497967466987, "pitch": null, "roll": null}, "v": 2.0963576217913378, "accelerator_pedal_position": 0.2578591540288886, "brake_pedal_position": 0.0, "acceleration": 0.012854678806560382, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018203435159272127, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.6490335} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2590486449931629, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.142497520608681, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.097766063695234, "gear": 1, "accelerator_pedal_position": 0.2590486449931629, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.6490335} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 55.989946603775024, "x": 21.968493674810173, "y": 0.13654341244023893, "z": null, "yaw": 3.127497967466987, "pitch": null, "roll": null}, "v": 2.0963576217913378, "accelerator_pedal_position": 0.2578591540288886, "brake_pedal_position": 0.0, "acceleration": 0.012854678806560382, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018203435159272127, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.6690335} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2590486449931629, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.142497520608681, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.09816906838266, "gear": 1, "accelerator_pedal_position": 0.2590486449931629, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.6690335} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502694.6890335, "x": 25.737806373453065, "y": 5.1396948969128, "z": null, "yaw": 3.1284531374469133, "pitch": null, "roll": null}, "v": 2.0985713321936768, "accelerator_pedal_position": 0.2590486449931629, "brake_pedal_position": 0.0, "acceleration": 0.02008544823453262, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018222657611277216, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.6890335} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2596408637601385, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0762056610724053, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0985713321936768, "gear": 1, "accelerator_pedal_position": 0.2590486449931629, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.6890335} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.09994649887085, "x": 21.737806373453065, "y": 0.13969489691279957, "z": null, "yaw": 3.1284531374469133, "pitch": null, "roll": null}, "v": 2.0985713321936768, "accelerator_pedal_position": 0.2590486449931629, "brake_pedal_position": 0.0, "acceleration": 0.02008544823453262, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018222657611277216, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.7090335} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25946597273572825, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0762056610724053, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0990468497278454, "gear": 1, "accelerator_pedal_position": 0.2596408637601385, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.7090335} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.09994649887085, "x": 21.737806373453065, "y": 0.13969489691279957, "z": null, "yaw": 3.1284531374469133, "pitch": null, "roll": null}, "v": 2.0985713321936768, "accelerator_pedal_position": 0.2590486449931629, "brake_pedal_position": 0.0, "acceleration": 0.02008544823453262, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018222657611277216, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.7290335} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25946597273572825, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0762056610724053, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.099499641592565, "gear": 1, "accelerator_pedal_position": 0.25946597273572825, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.7290335} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.09994649887085, "x": 21.737806373453065, "y": 0.13969489691279957, "z": null, "yaw": 3.1284531374469133, "pitch": null, "roll": null}, "v": 2.0985713321936768, "accelerator_pedal_position": 0.2590486449931629, "brake_pedal_position": 0.0, "acceleration": 0.02008544823453262, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018222657611277216, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.7490335} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25946597273572825, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0762056610724053, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0999516008145296, "gear": 1, "accelerator_pedal_position": 0.25946597273572825, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.7490335} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.09994649887085, "x": 21.737806373453065, "y": 0.13969489691279957, "z": null, "yaw": 3.1284531374469133, "pitch": null, "roll": null}, "v": 2.0985713321936768, "accelerator_pedal_position": 0.2590486449931629, "brake_pedal_position": 0.0, "acceleration": 0.02008544823453262, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018222657611277216, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.7690334} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25946597273572825, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0762056610724053, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.100402728843223, "gear": 1, "accelerator_pedal_position": 0.25946597273572825, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.7690334} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.09994649887085, "x": 21.737806373453065, "y": 0.13969489691279957, "z": null, "yaw": 3.1284531374469133, "pitch": null, "roll": null}, "v": 2.0985713321936768, "accelerator_pedal_position": 0.2590486449931629, "brake_pedal_position": 0.0, "acceleration": 0.02008544823453262, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018222657611277216, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.7890334} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25946597273572825, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0762056610724053, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1008530271259147, "gear": 1, "accelerator_pedal_position": 0.25946597273572825, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.7890334} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502694.7990334, "x": 25.506855636790856, "y": 5.142629342567666, "z": null, "yaw": 3.1294083074268397, "pitch": null, "roll": null}, "v": 2.1010778655641764, "accelerator_pedal_position": 0.25946597273572825, "brake_pedal_position": 0.0, "acceleration": 0.022463154348455472, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01824442275154248, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.8090334} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2608412967745821, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.129054748340912, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.101302497107661, "gear": 1, "accelerator_pedal_position": 0.25946597273572825, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.8090334} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.209946393966675, "x": 21.506855636790856, "y": 0.14262934256766613, "z": null, "yaw": 3.1294083074268397, "pitch": null, "roll": null}, "v": 2.1010778655641764, "accelerator_pedal_position": 0.25946597273572825, "brake_pedal_position": 0.0, "acceleration": 0.022463154348455472, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01824442275154248, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.8290334} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26042303735206357, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.129054748340912, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1022066469542646, "gear": 1, "accelerator_pedal_position": 0.26042303735206357, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.8290334} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.209946393966675, "x": 21.506855636790856, "y": 0.14262934256766613, "z": null, "yaw": 3.1294083074268397, "pitch": null, "roll": null}, "v": 2.1010778655641764, "accelerator_pedal_position": 0.25946597273572825, "brake_pedal_position": 0.0, "acceleration": 0.022463154348455472, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01824442275154248, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.8490334} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26042303735206357, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.129054748340912, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1024900561866415, "gear": 1, "accelerator_pedal_position": 0.26042303735206357, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.8490334} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.209946393966675, "x": 21.506855636790856, "y": 0.14262934256766613, "z": null, "yaw": 3.1294083074268397, "pitch": null, "roll": null}, "v": 2.1010778655641764, "accelerator_pedal_position": 0.25946597273572825, "brake_pedal_position": 0.0, "acceleration": 0.022463154348455472, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01824442275154248, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.8690333} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26042303735206357, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.129054748340912, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1030560922666677, "gear": 1, "accelerator_pedal_position": 0.26042303735206357, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.8690333} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.209946393966675, "x": 21.506855636790856, "y": 0.14262934256766613, "z": null, "yaw": 3.1294083074268397, "pitch": null, "roll": null}, "v": 2.1010778655641764, "accelerator_pedal_position": 0.25946597273572825, "brake_pedal_position": 0.0, "acceleration": 0.022463154348455472, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01824442275154248, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.8890333} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26042303735206357, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.129054748340912, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.103621086660118, "gear": 1, "accelerator_pedal_position": 0.26042303735206357, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.8890333} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502694.9090333, "x": 25.2755985583672, "y": 5.145346752186839, "z": null, "yaw": 3.130363477406766, "pitch": null, "roll": null}, "v": 2.104185041156399, "accelerator_pedal_position": 0.26042303735206357, "brake_pedal_position": 0.0, "acceleration": 0.028158784518313718, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01827140348652469, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.9090333} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2606666107783506, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0765647902471507, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.104185041156399, "gear": 1, "accelerator_pedal_position": 0.26042303735206357, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.9090333} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.3199462890625, "x": 21.2755985583672, "y": 0.145346752186839, "z": null, "yaw": 3.130363477406766, "pitch": null, "roll": null}, "v": 2.104185041156399, "accelerator_pedal_position": 0.26042303735206357, "brake_pedal_position": 0.0, "acceleration": 0.028158784518313718, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01827140348652469, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.9290333} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2606047952262184, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0765647902471507, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.10507079150087, "gear": 1, "accelerator_pedal_position": 0.2606047952262184, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.9290333} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.3199462890625, "x": 21.2755985583672, "y": 0.145346752186839, "z": null, "yaw": 3.130363477406766, "pitch": null, "roll": null}, "v": 2.104185041156399, "accelerator_pedal_position": 0.26042303735206357, "brake_pedal_position": 0.0, "acceleration": 0.028158784518313718, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01827140348652469, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.9490333} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2606047952262184, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0765647902471507, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1053629235030353, "gear": 1, "accelerator_pedal_position": 0.2606047952262184, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.9490333} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.3199462890625, "x": 21.2755985583672, "y": 0.145346752186839, "z": null, "yaw": 3.130363477406766, "pitch": null, "roll": null}, "v": 2.104185041156399, "accelerator_pedal_position": 0.26042303735206357, "brake_pedal_position": 0.0, "acceleration": 0.028158784518313718, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01827140348652469, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.9690332} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2606047952262184, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0765647902471507, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1059463805394105, "gear": 1, "accelerator_pedal_position": 0.2606047952262184, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.9690332} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.3199462890625, "x": 21.2755985583672, "y": 0.145346752186839, "z": null, "yaw": 3.130363477406766, "pitch": null, "roll": null}, "v": 2.104185041156399, "accelerator_pedal_position": 0.26042303735206357, "brake_pedal_position": 0.0, "acceleration": 0.028158784518313718, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01827140348652469, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502694.9890332} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2606047952262184, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0765647902471507, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1065287631561977, "gear": 1, "accelerator_pedal_position": 0.2606047952262184, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502694.9890332} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.3199462890625, "x": 21.2755985583672, "y": 0.145346752186839, "z": null, "yaw": 3.130363477406766, "pitch": null, "roll": null}, "v": 2.104185041156399, "accelerator_pedal_position": 0.26042303735206357, "brake_pedal_position": 0.0, "acceleration": 0.028158784518313718, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01827140348652469, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.0090332} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2606047952262184, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0765647902471507, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.107110073196305, "gear": 1, "accelerator_pedal_position": 0.2606047952262184, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.0090332} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502695.0190332, "x": 25.043990299761077, "y": 5.147847034402972, "z": null, "yaw": 3.1313186473866925, "pitch": null, "roll": null}, "v": 2.107400326575289, "accelerator_pedal_position": 0.2606047952262184, "brake_pedal_position": 0.0, "acceleration": 0.028998592470603934, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018299322978424796, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.0290332} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26140506716454065, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0947072703890302, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.107690312499995, "gear": 1, "accelerator_pedal_position": 0.2606047952262184, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.0290332} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.429946184158325, "x": 21.043990299761077, "y": 0.14784703440297164, "z": null, "yaw": 3.1313186473866925, "pitch": null, "roll": null}, "v": 2.107400326575289, "accelerator_pedal_position": 0.2606047952262184, "brake_pedal_position": 0.0, "acceleration": 0.028998592470603934, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018299322978424796, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.0490332} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2611697909676147, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0947072703890302, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.108369470801464, "gear": 1, "accelerator_pedal_position": 0.26140506716454065, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.0490332} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.429946184158325, "x": 21.043990299761077, "y": 0.14784703440297164, "z": null, "yaw": 3.1313186473866925, "pitch": null, "roll": null}, "v": 2.107400326575289, "accelerator_pedal_position": 0.2606047952262184, "brake_pedal_position": 0.0, "acceleration": 0.028998592470603934, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018299322978424796, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.0690331} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2611697909676147, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0947072703890302, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1090179818303736, "gear": 1, "accelerator_pedal_position": 0.2611697909676147, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.0690331} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.429946184158325, "x": 21.043990299761077, "y": 0.14784703440297164, "z": null, "yaw": 3.1313186473866925, "pitch": null, "roll": null}, "v": 2.107400326575289, "accelerator_pedal_position": 0.2606047952262184, "brake_pedal_position": 0.0, "acceleration": 0.028998592470603934, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018299322978424796, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.0890331} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2611697909676147, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0947072703890302, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1096652978527763, "gear": 1, "accelerator_pedal_position": 0.2611697909676147, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.0890331} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.429946184158325, "x": 21.043990299761077, "y": 0.14784703440297164, "z": null, "yaw": 3.1313186473866925, "pitch": null, "roll": null}, "v": 2.107400326575289, "accelerator_pedal_position": 0.2606047952262184, "brake_pedal_position": 0.0, "acceleration": 0.028998592470603934, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018299322978424796, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.109033} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2611697909676147, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0947072703890302, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1103114209031726, "gear": 1, "accelerator_pedal_position": 0.2611697909676147, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.109033} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502695.129033, "x": 24.81201010841919, "y": 5.150129724525278, "z": null, "yaw": 3.132273817366619, "pitch": null, "roll": null}, "v": 2.110956353013239, "accelerator_pedal_position": 0.2611697909676147, "brake_pedal_position": 0.0, "acceleration": 0.03220200865366046, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01833020124843703, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.129033} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26117446579489123, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0456772257988505, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.110956353013239, "gear": 1, "accelerator_pedal_position": 0.2611697909676147, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.129033} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.53994607925415, "x": 20.81201010841919, "y": 0.15012972452527773, "z": null, "yaw": 3.132273817366619, "pitch": null, "roll": null}, "v": 2.110956353013239, "accelerator_pedal_position": 0.2611697909676147, "brake_pedal_position": 0.0, "acceleration": 0.03220200865366046, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01833020124843703, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.149033} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2611893952811894, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0456772257988505, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1116006802957776, "gear": 1, "accelerator_pedal_position": 0.26117446579489123, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.149033} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.53994607925415, "x": 20.81201010841919, "y": 0.15012972452527773, "z": null, "yaw": 3.132273817366619, "pitch": null, "roll": null}, "v": 2.110956353013239, "accelerator_pedal_position": 0.2611697909676147, "brake_pedal_position": 0.0, "acceleration": 0.03220200865366046, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01833020124843703, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.169033} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2611893952811894, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0456772257988505, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1122456849409885, "gear": 1, "accelerator_pedal_position": 0.2611893952811894, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.169033} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.53994607925415, "x": 20.81201010841919, "y": 0.15012972452527773, "z": null, "yaw": 3.132273817366619, "pitch": null, "roll": null}, "v": 2.110956353013239, "accelerator_pedal_position": 0.2611697909676147, "brake_pedal_position": 0.0, "acceleration": 0.03220200865366046, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01833020124843703, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.189033} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2611893952811894, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0456772257988505, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.112889500208669, "gear": 1, "accelerator_pedal_position": 0.2611893952811894, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.189033} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.53994607925415, "x": 20.81201010841919, "y": 0.15012972452527773, "z": null, "yaw": 3.132273817366619, "pitch": null, "roll": null}, "v": 2.110956353013239, "accelerator_pedal_position": 0.2611697909676147, "brake_pedal_position": 0.0, "acceleration": 0.03220200865366046, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01833020124843703, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.209033} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2611893952811894, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0456772257988505, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1135321281262884, "gear": 1, "accelerator_pedal_position": 0.2611893952811894, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.209033} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.53994607925415, "x": 20.81201010841919, "y": 0.15012972452527773, "z": null, "yaw": 3.132273817366619, "pitch": null, "roll": null}, "v": 2.110956353013239, "accelerator_pedal_position": 0.2611697909676147, "brake_pedal_position": 0.0, "acceleration": 0.03220200865366046, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01833020124843703, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.229033} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2611893952811894, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0456772257988505, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1144938481494955, "gear": 1, "accelerator_pedal_position": 0.2611893952811894, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.229033} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502695.239033, "x": 24.57963697251532, "y": 5.152194306289341, "z": null, "yaw": 3.1332289873465453, "pitch": null, "roll": null}, "v": 2.1144938481494955, "accelerator_pedal_position": 0.2611893952811894, "brake_pedal_position": 0.0, "acceleration": 0.03199818576133823, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018360918604421385, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.249033} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2622362867486526, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0830920323446958, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1148138300071087, "gear": 1, "accelerator_pedal_position": 0.2611893952811894, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.249033} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.649945974349976, "x": 20.57963697251532, "y": 0.15219430628934116, "z": null, "yaw": 3.1332289873465453, "pitch": null, "roll": null}, "v": 2.1144938481494955, "accelerator_pedal_position": 0.2611893952811894, "brake_pedal_position": 0.0, "acceleration": 0.03199818576133823, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018360918604421385, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.269033} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2619254504538784, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0830920323446958, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.115583709049848, "gear": 1, "accelerator_pedal_position": 0.2622362867486526, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.269033} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.649945974349976, "x": 20.57963697251532, "y": 0.15219430628934116, "z": null, "yaw": 3.1332289873465453, "pitch": null, "roll": null}, "v": 2.1144938481494955, "accelerator_pedal_position": 0.2611893952811894, "brake_pedal_position": 0.0, "acceleration": 0.03199818576133823, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018360918604421385, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.289033} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2619254504538784, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0830920323446958, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.116313330829659, "gear": 1, "accelerator_pedal_position": 0.2619254504538784, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.289033} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.649945974349976, "x": 20.57963697251532, "y": 0.15219430628934116, "z": null, "yaw": 3.1332289873465453, "pitch": null, "roll": null}, "v": 2.1144938481494955, "accelerator_pedal_position": 0.2611893952811894, "brake_pedal_position": 0.0, "acceleration": 0.03199818576133823, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018360918604421385, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.309033} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2619254504538784, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0830920323446958, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1170416060195203, "gear": 1, "accelerator_pedal_position": 0.2619254504538784, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.309033} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.649945974349976, "x": 20.57963697251532, "y": 0.15219430628934116, "z": null, "yaw": 3.1332289873465453, "pitch": null, "roll": null}, "v": 2.1144938481494955, "accelerator_pedal_position": 0.2611893952811894, "brake_pedal_position": 0.0, "acceleration": 0.03199818576133823, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018360918604421385, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.329033} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2619254504538784, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0830920323446958, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1177685368926427, "gear": 1, "accelerator_pedal_position": 0.2619254504538784, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.329033} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502695.3490329, "x": 24.346850530940756, "y": 5.154040189647774, "z": null, "yaw": 3.1341841573264717, "pitch": null, "roll": null}, "v": 2.1184941257192142, "accelerator_pedal_position": 0.2619254504538784, "brake_pedal_position": 0.0, "acceleration": 0.0362291854437109, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018395654468475554, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.3490329} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26218069223900736, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0437542744082204, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1184941257192142, "gear": 1, "accelerator_pedal_position": 0.2619254504538784, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.3490329} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.7599458694458, "x": 20.346850530940756, "y": 0.1540401896477741, "z": null, "yaw": 3.1341841573264717, "pitch": null, "roll": null}, "v": 2.1184941257192142, "accelerator_pedal_position": 0.2619254504538784, "brake_pedal_position": 0.0, "acceleration": 0.0362291854437109, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018395654468475554, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.3690329} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26211939639831255, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0437542744082204, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.119250265252954, "gear": 1, "accelerator_pedal_position": 0.26218069223900736, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.3690329} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.7599458694458, "x": 20.346850530940756, "y": 0.1540401896477741, "z": null, "yaw": 3.1341841573264717, "pitch": null, "roll": null}, "v": 2.1184941257192142, "accelerator_pedal_position": 0.2619254504538784, "brake_pedal_position": 0.0, "acceleration": 0.0362291854437109, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018395654468475554, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.3890328} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26211939639831255, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0437542744082204, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.119997349929571, "gear": 1, "accelerator_pedal_position": 0.26211939639831255, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.3890328} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.7599458694458, "x": 20.346850530940756, "y": 0.1540401896477741, "z": null, "yaw": 3.1341841573264717, "pitch": null, "roll": null}, "v": 2.1184941257192142, "accelerator_pedal_position": 0.2619254504538784, "brake_pedal_position": 0.0, "acceleration": 0.0362291854437109, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018395654468475554, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.4090328} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26211939639831255, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0437542744082204, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.120743054688127, "gear": 1, "accelerator_pedal_position": 0.26211939639831255, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.4090328} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.7599458694458, "x": 20.346850530940756, "y": 0.1540401896477741, "z": null, "yaw": 3.1341841573264717, "pitch": null, "roll": null}, "v": 2.1184941257192142, "accelerator_pedal_position": 0.2619254504538784, "brake_pedal_position": 0.0, "acceleration": 0.0362291854437109, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018395654468475554, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.4290328} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26211939639831255, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0437542744082204, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.121487381855101, "gear": 1, "accelerator_pedal_position": 0.26211939639831255, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.4290328} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.7599458694458, "x": 20.346850530940756, "y": 0.1540401896477741, "z": null, "yaw": 3.1341841573264717, "pitch": null, "roll": null}, "v": 2.1184941257192142, "accelerator_pedal_position": 0.2619254504538784, "brake_pedal_position": 0.0, "acceleration": 0.0362291854437109, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018395654468475554, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.4490328} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26211939639831255, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 1.0437542744082204, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1222303337539055, "gear": 1, "accelerator_pedal_position": 0.26211939639831255, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.4490328} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502695.4590328, "x": 24.113615775453987, "y": 5.155666836068064, "z": null, "yaw": 3.135139327306398, "pitch": null, "roll": null}, "v": 2.1226012947029727, "accelerator_pedal_position": 0.26211939639831255, "brake_pedal_position": 0.0, "acceleration": 0.03706180019155736, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01843131850952793, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.4690328} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26113377960642004, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8538458892015313, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1229719127048883, "gear": 1, "accelerator_pedal_position": 0.26211939639831255, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.4690328} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.869945764541626, "x": 20.113615775453987, "y": 0.15566683606806375, "z": null, "yaw": 3.135139327306398, "pitch": null, "roll": null}, "v": 2.1226012947029727, "accelerator_pedal_position": 0.26211939639831255, "brake_pedal_position": 0.0, "acceleration": 0.03706180019155736, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01843131850952793, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.4890327} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26146076243851646, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8538458892015313, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1235889758865123, "gear": 1, "accelerator_pedal_position": 0.26113377960642004, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.4890327} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.869945764541626, "x": 20.113615775453987, "y": 0.15566683606806375, "z": null, "yaw": 3.135139327306398, "pitch": null, "roll": null}, "v": 2.1226012947029727, "accelerator_pedal_position": 0.26211939639831255, "brake_pedal_position": 0.0, "acceleration": 0.03706180019155736, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01843131850952793, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.5090327} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26146076243851646, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8538458892015313, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.124245752370021, "gear": 1, "accelerator_pedal_position": 0.26146076243851646, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.5090327} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.869945764541626, "x": 20.113615775453987, "y": 0.15566683606806375, "z": null, "yaw": 3.135139327306398, "pitch": null, "roll": null}, "v": 2.1226012947029727, "accelerator_pedal_position": 0.26211939639831255, "brake_pedal_position": 0.0, "acceleration": 0.03706180019155736, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01843131850952793, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.5290327} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26146076243851646, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8538458892015313, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.125228641055481, "gear": 1, "accelerator_pedal_position": 0.26146076243851646, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.5290327} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.869945764541626, "x": 20.113615775453987, "y": 0.15566683606806375, "z": null, "yaw": 3.135139327306398, "pitch": null, "roll": null}, "v": 2.1226012947029727, "accelerator_pedal_position": 0.26211939639831255, "brake_pedal_position": 0.0, "acceleration": 0.03706180019155736, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01843131850952793, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.5490327} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26146076243851646, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8538458892015313, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1255556647096845, "gear": 1, "accelerator_pedal_position": 0.26146076243851646, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.5490327} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502695.5690327, "x": 23.87995253967947, "y": 5.157073277870663, "z": null, "yaw": 3.1360944972863245, "pitch": null, "roll": null}, "v": 2.1262088047090026, "accelerator_pedal_position": 0.26146076243851646, "brake_pedal_position": 0.0, "acceleration": 0.032611686193056766, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.0184626438300737, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.5690327} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2628521951604697, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8870164870833079, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1262088047090026, "gear": 1, "accelerator_pedal_position": 0.26146076243851646, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.5690327} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.97994565963745, "x": 19.87995253967947, "y": 0.15707327787066294, "z": null, "yaw": 3.1360944972863245, "pitch": null, "roll": null}, "v": 2.1262088047090026, "accelerator_pedal_position": 0.26146076243851646, "brake_pedal_position": 0.0, "acceleration": 0.032611686193056766, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.0184626438300737, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.5890326} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2624340547481938, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8870164870833079, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.127034585305876, "gear": 1, "accelerator_pedal_position": 0.2628521951604697, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.5890326} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.97994565963745, "x": 19.87995253967947, "y": 0.15707327787066294, "z": null, "yaw": 3.1360944972863245, "pitch": null, "roll": null}, "v": 2.1262088047090026, "accelerator_pedal_position": 0.26146076243851646, "brake_pedal_position": 0.0, "acceleration": 0.032611686193056766, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.0184626438300737, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.6090326} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2624340547481938, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8870164870833079, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1278065949468656, "gear": 1, "accelerator_pedal_position": 0.2624340547481938, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.6090326} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.97994565963745, "x": 19.87995253967947, "y": 0.15707327787066294, "z": null, "yaw": 3.1360944972863245, "pitch": null, "roll": null}, "v": 2.1262088047090026, "accelerator_pedal_position": 0.26146076243851646, "brake_pedal_position": 0.0, "acceleration": 0.032611686193056766, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.0184626438300737, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.6290326} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2624340547481938, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8870164870833079, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.128577176224257, "gear": 1, "accelerator_pedal_position": 0.2624340547481938, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.6290326} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.97994565963745, "x": 19.87995253967947, "y": 0.15707327787066294, "z": null, "yaw": 3.1360944972863245, "pitch": null, "roll": null}, "v": 2.1262088047090026, "accelerator_pedal_position": 0.26146076243851646, "brake_pedal_position": 0.0, "acceleration": 0.032611686193056766, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.0184626438300737, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.6490326} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2624340547481938, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8870164870833079, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1293463315433843, "gear": 1, "accelerator_pedal_position": 0.2624340547481938, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.6490326} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 56.97994565963745, "x": 19.87995253967947, "y": 0.15707327787066294, "z": null, "yaw": 3.1360944972863245, "pitch": null, "roll": null}, "v": 2.1262088047090026, "accelerator_pedal_position": 0.26146076243851646, "brake_pedal_position": 0.0, "acceleration": 0.032611686193056766, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.0184626438300737, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.6690326} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2624340547481938, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8870164870833079, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.130114063306448, "gear": 1, "accelerator_pedal_position": 0.2624340547481938, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.6690326} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502695.6790326, "x": 23.645855404118304, "y": 5.158258715999582, "z": null, "yaw": 3.137049667266251, "pitch": null, "roll": null}, "v": 2.1304973961042872, "accelerator_pedal_position": 0.2624340547481938, "brake_pedal_position": 0.0, "acceleration": 0.0382977808229254, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01849988322786403, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.6890326} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2635032258440831, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9248721600161183, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1308803739125164, "gear": 1, "accelerator_pedal_position": 0.2624340547481938, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.6890326} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.089945554733276, "x": 19.645855404118304, "y": 0.1582587159995823, "z": null, "yaw": 3.137049667266251, "pitch": null, "roll": null}, "v": 2.1304973961042872, "accelerator_pedal_position": 0.2624340547481938, "brake_pedal_position": 0.0, "acceleration": 0.0382977808229254, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01849988322786403, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.7090325} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2631889587858489, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9248721600161183, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1317788502489083, "gear": 1, "accelerator_pedal_position": 0.2635032258440831, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.7090325} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.089945554733276, "x": 19.645855404118304, "y": 0.1582587159995823, "z": null, "yaw": 3.137049667266251, "pitch": null, "roll": null}, "v": 2.1304973961042872, "accelerator_pedal_position": 0.2624340547481938, "brake_pedal_position": 0.0, "acceleration": 0.0382977808229254, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01849988322786403, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.7290325} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2631889587858489, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9248721600161183, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.132636397634164, "gear": 1, "accelerator_pedal_position": 0.2631889587858489, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.7290325} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.089945554733276, "x": 19.645855404118304, "y": 0.1582587159995823, "z": null, "yaw": 3.137049667266251, "pitch": null, "roll": null}, "v": 2.1304973961042872, "accelerator_pedal_position": 0.2624340547481938, "brake_pedal_position": 0.0, "acceleration": 0.0382977808229254, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01849988322786403, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.7490325} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2631889587858489, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9248721600161183, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1334923567469968, "gear": 1, "accelerator_pedal_position": 0.2631889587858489, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.7490325} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.089945554733276, "x": 19.645855404118304, "y": 0.1582587159995823, "z": null, "yaw": 3.137049667266251, "pitch": null, "roll": null}, "v": 2.1304973961042872, "accelerator_pedal_position": 0.2624340547481938, "brake_pedal_position": 0.0, "acceleration": 0.0382977808229254, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01849988322786403, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.7690325} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2631889587858489, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9248721600161183, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.134346730236131, "gear": 1, "accelerator_pedal_position": 0.2631889587858489, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.7690325} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502695.7890325, "x": 23.411268119123843, "y": 5.159222556846911, "z": null, "yaw": 3.1380048372461773, "pitch": null, "roll": null}, "v": 2.135199520747014, "accelerator_pedal_position": 0.2631889587858489, "brake_pedal_position": 0.0, "acceleration": 0.042580246440222125, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018540713485142152, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.7890325} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2641073181873912, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9668029332828579, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.135199520747014, "gear": 1, "accelerator_pedal_position": 0.2631889587858489, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.7890325} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.1999454498291, "x": 19.411268119123843, "y": 0.15922255684691056, "z": null, "yaw": 3.1380048372461773, "pitch": null, "roll": null}, "v": 2.135199520747014, "accelerator_pedal_position": 0.2631889587858489, "brake_pedal_position": 0.0, "acceleration": 0.042580246440222125, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018540713485142152, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.8090324} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2638421149314308, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9668029332828579, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.136165472632049, "gear": 1, "accelerator_pedal_position": 0.2641073181873912, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.8090324} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.1999454498291, "x": 19.411268119123843, "y": 0.15922255684691056, "z": null, "yaw": 3.1380048372461773, "pitch": null, "roll": null}, "v": 2.135199520747014, "accelerator_pedal_position": 0.2631889587858489, "brake_pedal_position": 0.0, "acceleration": 0.042580246440222125, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018540713485142152, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.8290324} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2638421149314308, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9668029332828579, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1370964990793775, "gear": 1, "accelerator_pedal_position": 0.2638421149314308, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.8290324} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.1999454498291, "x": 19.411268119123843, "y": 0.15922255684691056, "z": null, "yaw": 3.1380048372461773, "pitch": null, "roll": null}, "v": 2.135199520747014, "accelerator_pedal_position": 0.2631889587858489, "brake_pedal_position": 0.0, "acceleration": 0.042580246440222125, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018540713485142152, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.8490324} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2638421149314308, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9668029332828579, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.138025799510337, "gear": 1, "accelerator_pedal_position": 0.2638421149314308, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.8490324} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.1999454498291, "x": 19.411268119123843, "y": 0.15922255684691056, "z": null, "yaw": 3.1380048372461773, "pitch": null, "roll": null}, "v": 2.135199520747014, "accelerator_pedal_position": 0.2631889587858489, "brake_pedal_position": 0.0, "acceleration": 0.042580246440222125, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018540713485142152, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.8690324} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2638421149314308, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9668029332828579, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1389533767794844, "gear": 1, "accelerator_pedal_position": 0.2638421149314308, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.8690324} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.1999454498291, "x": 19.411268119123843, "y": 0.15922255684691056, "z": null, "yaw": 3.1380048372461773, "pitch": null, "roll": null}, "v": 2.135199520747014, "accelerator_pedal_position": 0.2631889587858489, "brake_pedal_position": 0.0, "acceleration": 0.042580246440222125, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018540713485142152, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.8890324} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2638421149314308, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9668029332828579, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.139879233738004, "gear": 1, "accelerator_pedal_position": 0.2638421149314308, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.8890324} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502695.8990324, "x": 23.176138281961148, "y": 5.159964031502003, "z": null, "yaw": 3.1389600072261037, "pitch": null, "roll": null}, "v": 2.1403415179908514, "accelerator_pedal_position": 0.2638421149314308, "brake_pedal_position": 0.0, "acceleration": 0.0461855242855459, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018585363316089114, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.9090323} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2642454943706318, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9140687786096657, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1408033732337066, "gear": 1, "accelerator_pedal_position": 0.2638421149314308, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.9090323} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.30994534492493, "x": 19.176138281961148, "y": 0.15996403150200322, "z": null, "yaw": 3.1389600072261037, "pitch": null, "roll": null}, "v": 2.1403415179908514, "accelerator_pedal_position": 0.2638421149314308, "brake_pedal_position": 0.0, "acceleration": 0.0461855242855459, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018585363316089114, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.9290323} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2641432856320963, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9140687786096657, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1417761971384786, "gear": 1, "accelerator_pedal_position": 0.2642454943706318, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.9290323} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.30994534492493, "x": 19.176138281961148, "y": 0.15996403150200322, "z": null, "yaw": 3.1389600072261037, "pitch": null, "roll": null}, "v": 2.1403415179908514, "accelerator_pedal_position": 0.2638421149314308, "brake_pedal_position": 0.0, "acceleration": 0.0461855242855459, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018585363316089114, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.9490323} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2641432856320963, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9140687786096657, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.142734445562605, "gear": 1, "accelerator_pedal_position": 0.2641432856320963, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.9490323} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.30994534492493, "x": 19.176138281961148, "y": 0.15996403150200322, "z": null, "yaw": 3.1389600072261037, "pitch": null, "roll": null}, "v": 2.1403415179908514, "accelerator_pedal_position": 0.2638421149314308, "brake_pedal_position": 0.0, "acceleration": 0.0461855242855459, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018585363316089114, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.9690323} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2641432856320963, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9140687786096657, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1436909153475274, "gear": 1, "accelerator_pedal_position": 0.2641432856320963, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.9690323} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.30994534492493, "x": 19.176138281961148, "y": 0.15996403150200322, "z": null, "yaw": 3.1389600072261037, "pitch": null, "roll": null}, "v": 2.1403415179908514, "accelerator_pedal_position": 0.2638421149314308, "brake_pedal_position": 0.0, "acceleration": 0.0461855242855459, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018585363316089114, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502695.9890323} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2641432856320963, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.9140687786096657, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1446456094288777, "gear": 1, "accelerator_pedal_position": 0.2641432856320963, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502695.9890323} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502696.0090322, "x": 22.94043844743375, "y": 5.16048216752556, "z": null, "yaw": 3.13991517720603, "pitch": null, "roll": null}, "v": 2.1455985307388743, "accelerator_pedal_position": 0.2641432856320963, "brake_pedal_position": 0.0, "acceleration": 0.04757967811257002, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01863101186846174, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.0090322} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2644488793956469, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8645341051525897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1455985307388743, "gear": 1, "accelerator_pedal_position": 0.2641432856320963, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.0090322} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.41994524002075, "x": 18.94043844743375, "y": 0.16048216752555966, "z": null, "yaw": 3.13991517720603, "pitch": null, "roll": null}, "v": 2.1455985307388743, "accelerator_pedal_position": 0.2641432856320963, "brake_pedal_position": 0.0, "acceleration": 0.04757967811257002, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01863101186846174, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.0290322} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2643777894505339, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8645341051525897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1465878636790876, "gear": 1, "accelerator_pedal_position": 0.2644488793956469, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.0290322} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.41994524002075, "x": 18.94043844743375, "y": 0.16048216752555966, "z": null, "yaw": 3.13991517720603, "pitch": null, "roll": null}, "v": 2.1455985307388743, "accelerator_pedal_position": 0.2641432856320963, "brake_pedal_position": 0.0, "acceleration": 0.04757967811257002, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01863101186846174, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.0490322} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2643777894505339, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8645341051525897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1475664766489473, "gear": 1, "accelerator_pedal_position": 0.2643777894505339, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.0490322} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.41994524002075, "x": 18.94043844743375, "y": 0.16048216752555966, "z": null, "yaw": 3.13991517720603, "pitch": null, "roll": null}, "v": 2.1455985307388743, "accelerator_pedal_position": 0.2641432856320963, "brake_pedal_position": 0.0, "acceleration": 0.04757967811257002, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01863101186846174, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.0690322} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2643777894505339, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8645341051525897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1485432712925148, "gear": 1, "accelerator_pedal_position": 0.2643777894505339, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.0690322} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.41994524002075, "x": 18.94043844743375, "y": 0.16048216752555966, "z": null, "yaw": 3.13991517720603, "pitch": null, "roll": null}, "v": 2.1455985307388743, "accelerator_pedal_position": 0.2641432856320963, "brake_pedal_position": 0.0, "acceleration": 0.04757967811257002, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01863101186846174, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.0890322} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2643777894505339, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8645341051525897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.149518250606884, "gear": 1, "accelerator_pedal_position": 0.2643777894505339, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.0890322} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.41994524002075, "x": 18.94043844743375, "y": 0.16048216752555966, "z": null, "yaw": 3.13991517720603, "pitch": null, "roll": null}, "v": 2.1455985307388743, "accelerator_pedal_position": 0.2641432856320963, "brake_pedal_position": 0.0, "acceleration": 0.04757967811257002, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01863101186846174, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.1090322} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2643777894505339, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8645341051525897, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.150491417585706, "gear": 1, "accelerator_pedal_position": 0.2643777894505339, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.1090322} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502696.1190321, "x": 22.70415296106543, "y": 5.160775896657828, "z": null, "yaw": 3.1408703471859565, "pitch": null, "roll": null}, "v": 2.1509773223838606, "accelerator_pedal_position": 0.2643777894505339, "brake_pedal_position": 0.0, "acceleration": 0.048545283532547445, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018677717871257712, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.1290321} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2648019194091415, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7911239654259389, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.151462775219186, "gear": 1, "accelerator_pedal_position": 0.2643777894505339, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.1290321} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.52994513511658, "x": 18.70415296106543, "y": 0.1607758966578281, "z": null, "yaw": 3.1408703471859565, "pitch": null, "roll": null}, "v": 2.1509773223838606, "accelerator_pedal_position": 0.2643777894505339, "brake_pedal_position": 0.0, "acceleration": 0.048545283532547445, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018677717871257712, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.149032} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26469438089883174, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7911239654259389, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1524853180759576, "gear": 1, "accelerator_pedal_position": 0.2648019194091415, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.149032} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.52994513511658, "x": 18.70415296106543, "y": 0.1607758966578281, "z": null, "yaw": 3.1408703471859565, "pitch": null, "roll": null}, "v": 2.1509773223838606, "accelerator_pedal_position": 0.2643777894505339, "brake_pedal_position": 0.0, "acceleration": 0.048545283532547445, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018677717871257712, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.169032} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26469438089883174, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7911239654259389, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1534925229172415, "gear": 1, "accelerator_pedal_position": 0.26469438089883174, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.169032} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.52994513511658, "x": 18.70415296106543, "y": 0.1607758966578281, "z": null, "yaw": 3.1408703471859565, "pitch": null, "roll": null}, "v": 2.1509773223838606, "accelerator_pedal_position": 0.2643777894505339, "brake_pedal_position": 0.0, "acceleration": 0.048545283532547445, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018677717871257712, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.189032} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26469438089883174, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7911239654259389, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.154497853924285, "gear": 1, "accelerator_pedal_position": 0.26469438089883174, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.189032} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.52994513511658, "x": 18.70415296106543, "y": 0.1607758966578281, "z": null, "yaw": 3.1408703471859565, "pitch": null, "roll": null}, "v": 2.1509773223838606, "accelerator_pedal_position": 0.2643777894505339, "brake_pedal_position": 0.0, "acceleration": 0.048545283532547445, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018677717871257712, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.209032} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26469438089883174, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7911239654259389, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.155501314179139, "gear": 1, "accelerator_pedal_position": 0.26469438089883174, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.209032} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502696.229032, "x": 22.467269198514625, "y": 5.160844103833324, "z": null, "yaw": 3.141825517165883, "pitch": null, "roll": null}, "v": 2.1565029067603723, "accelerator_pedal_position": 0.26469438089883174, "brake_pedal_position": 0.0, "acceleration": 0.050009687411020354, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018725698528693904, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.229032} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26570599365676606, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8166205210337456, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1565029067603723, "gear": 1, "accelerator_pedal_position": 0.26469438089883174, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.229032} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.6399450302124, "x": 18.467269198514625, "y": 0.16084410383332415, "z": null, "yaw": 3.141825517165883, "pitch": null, "roll": null}, "v": 2.1565029067603723, "accelerator_pedal_position": 0.26469438089883174, "brake_pedal_position": 0.0, "acceleration": 0.050009687411020354, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018725698528693904, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.249032} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2654155791131704, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8166205210337456, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.15762902744887, "gear": 1, "accelerator_pedal_position": 0.26570599365676606, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.249032} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.6399450302124, "x": 18.467269198514625, "y": 0.16084410383332415, "z": null, "yaw": 3.141825517165883, "pitch": null, "roll": null}, "v": 2.1565029067603723, "accelerator_pedal_position": 0.26469438089883174, "brake_pedal_position": 0.0, "acceleration": 0.050009687411020354, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018725698528693904, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.269032} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2654155791131704, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8166205210337456, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1587167663124394, "gear": 1, "accelerator_pedal_position": 0.2654155791131704, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.269032} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.6399450302124, "x": 18.467269198514625, "y": 0.16084410383332415, "z": null, "yaw": 3.141825517165883, "pitch": null, "roll": null}, "v": 2.1565029067603723, "accelerator_pedal_position": 0.26469438089883174, "brake_pedal_position": 0.0, "acceleration": 0.050009687411020354, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018725698528693904, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.289032} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2654155791131704, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8166205210337456, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.159802479251675, "gear": 1, "accelerator_pedal_position": 0.2654155791131704, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.289032} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.6399450302124, "x": 18.467269198514625, "y": 0.16084410383332415, "z": null, "yaw": 3.141825517165883, "pitch": null, "roll": null}, "v": 2.1565029067603723, "accelerator_pedal_position": 0.26469438089883174, "brake_pedal_position": 0.0, "acceleration": 0.050009687411020354, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018725698528693904, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.309032} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2654155791131704, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8166205210337456, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1608861695685904, "gear": 1, "accelerator_pedal_position": 0.2654155791131704, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.309032} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.6399450302124, "x": 18.467269198514625, "y": 0.16084410383332415, "z": null, "yaw": 3.141825517165883, "pitch": null, "roll": null}, "v": 2.1565029067603723, "accelerator_pedal_position": 0.26469438089883174, "brake_pedal_position": 0.0, "acceleration": 0.050009687411020354, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018725698528693904, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.329032} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2654155791131704, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.8166205210337456, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.161967840561683, "gear": 1, "accelerator_pedal_position": 0.2654155791131704, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.329032} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502696.339032, "x": 22.22975149754553, "y": 5.160685619889306, "z": null, "yaw": 3.1427806871458093, "pitch": null, "roll": null}, "v": 2.1625079198416133, "accelerator_pedal_position": 0.2654155791131704, "brake_pedal_position": 0.0, "acceleration": 0.05395756843145705, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01877784223982347, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.349032} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26605519167123837, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7381951040661748, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.163047495525928, "gear": 1, "accelerator_pedal_position": 0.2654155791131704, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.349032} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.74994492530823, "x": 18.22975149754553, "y": 0.16068561988930607, "z": null, "yaw": 3.1427806871458093, "pitch": null, "roll": null}, "v": 2.1625079198416133, "accelerator_pedal_position": 0.2654155791131704, "brake_pedal_position": 0.0, "acceleration": 0.05395756843145705, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01877784223982347, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.369032} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2658832930250956, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7381951040661748, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.164205052036266, "gear": 1, "accelerator_pedal_position": 0.26605519167123837, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.369032} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.74994492530823, "x": 18.22975149754553, "y": 0.16068561988930607, "z": null, "yaw": 3.1427806871458093, "pitch": null, "roll": null}, "v": 2.1625079198416133, "accelerator_pedal_position": 0.2654155791131704, "brake_pedal_position": 0.0, "acceleration": 0.05395756843145705, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01877784223982347, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.389032} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2658832930250956, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7381951040661748, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.165338972748057, "gear": 1, "accelerator_pedal_position": 0.2658832930250956, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.389032} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.74994492530823, "x": 18.22975149754553, "y": 0.16068561988930607, "z": null, "yaw": 3.1427806871458093, "pitch": null, "roll": null}, "v": 2.1625079198416133, "accelerator_pedal_position": 0.2654155791131704, "brake_pedal_position": 0.0, "acceleration": 0.05395756843145705, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01877784223982347, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.4090319} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2658832930250956, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7381951040661748, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.166470778525779, "gear": 1, "accelerator_pedal_position": 0.2658832930250956, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.4090319} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.74994492530823, "x": 18.22975149754553, "y": 0.16068561988930607, "z": null, "yaw": 3.1427806871458093, "pitch": null, "roll": null}, "v": 2.1625079198416133, "accelerator_pedal_position": 0.2654155791131704, "brake_pedal_position": 0.0, "acceleration": 0.05395756843145705, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01877784223982347, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.4290318} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2658832930250956, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7381951040661748, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1676004728019493, "gear": 1, "accelerator_pedal_position": 0.2658832930250956, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.4290318} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502696.4490318, "x": 21.99156506930546, "y": 5.160299178941491, "z": null, "yaw": 3.1437358571257357, "pitch": null, "roll": null}, "v": 2.168728059005549, "accelerator_pedal_position": 0.2658832930250956, "brake_pedal_position": 0.0, "acceleration": 0.05630036451739029, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01883185396891748, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.4490318} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26679685134884246, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7623411921056686, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.168728059005549, "gear": 1, "accelerator_pedal_position": 0.2658832930250956, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.4490318} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.85994482040405, "x": 17.99156506930546, "y": 0.16029917894149115, "z": null, "yaw": 3.1437358571257357, "pitch": null, "roll": null}, "v": 2.168728059005549, "accelerator_pedal_position": 0.2658832930250956, "brake_pedal_position": 0.0, "acceleration": 0.05630036451739029, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01883185396891748, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.4690318} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2665403849976991, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7623411921056686, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.169967682031287, "gear": 1, "accelerator_pedal_position": 0.26679685134884246, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.4690318} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.85994482040405, "x": 17.99156506930546, "y": 0.16029917894149115, "z": null, "yaw": 3.1437358571257357, "pitch": null, "roll": null}, "v": 2.168728059005549, "accelerator_pedal_position": 0.2658832930250956, "brake_pedal_position": 0.0, "acceleration": 0.05630036451739029, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01883185396891748, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.4890318} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2665403849976991, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7623411921056686, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.171172947371396, "gear": 1, "accelerator_pedal_position": 0.2665403849976991, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.4890318} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.85994482040405, "x": 17.99156506930546, "y": 0.16029917894149115, "z": null, "yaw": 3.1437358571257357, "pitch": null, "roll": null}, "v": 2.168728059005549, "accelerator_pedal_position": 0.2658832930250956, "brake_pedal_position": 0.0, "acceleration": 0.05630036451739029, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01883185396891748, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.5090318} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2665403849976991, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7623411921056686, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.172375961907511, "gear": 1, "accelerator_pedal_position": 0.2665403849976991, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.5090318} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.85994482040405, "x": 17.99156506930546, "y": 0.16029917894149115, "z": null, "yaw": 3.1437358571257357, "pitch": null, "roll": null}, "v": 2.168728059005549, "accelerator_pedal_position": 0.2658832930250956, "brake_pedal_position": 0.0, "acceleration": 0.05630036451739029, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01883185396891748, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.5290318} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2665403849976991, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7623411921056686, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1735767292643278, "gear": 1, "accelerator_pedal_position": 0.2665403849976991, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.5290318} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.85994482040405, "x": 17.99156506930546, "y": 0.16029917894149115, "z": null, "yaw": 3.1437358571257357, "pitch": null, "roll": null}, "v": 2.168728059005549, "accelerator_pedal_position": 0.2658832930250956, "brake_pedal_position": 0.0, "acceleration": 0.05630036451739029, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01883185396891748, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.5490317} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2665403849976991, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.7623411921056686, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1747752530630127, "gear": 1, "accelerator_pedal_position": 0.2665403849976991, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.5490317} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502696.5590317, "x": 21.752671441705576, "y": 5.1596834022513764, "z": null, "yaw": 3.144691027105662, "pitch": null, "roll": null}, "v": 2.175373674758704, "accelerator_pedal_position": 0.2665403849976991, "brake_pedal_position": 0.0, "acceleration": 0.059786216249352264, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018889560265876786, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.5690317} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2670467046092279, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6487304172504287, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1759715369211974, "gear": 1, "accelerator_pedal_position": 0.2665403849976991, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.5690317} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.96994471549988, "x": 17.752671441705576, "y": 0.15968340225137645, "z": null, "yaw": 3.144691027105662, "pitch": null, "roll": null}, "v": 2.175373674758704, "accelerator_pedal_position": 0.2665403849976991, "brake_pedal_position": 0.0, "acceleration": 0.059786216249352264, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018889560265876786, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.5890317} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2669195283020823, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6487304172504287, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.177228844806332, "gear": 1, "accelerator_pedal_position": 0.2670467046092279, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.5890317} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.96994471549988, "x": 17.752671441705576, "y": 0.15968340225137645, "z": null, "yaw": 3.144691027105662, "pitch": null, "roll": null}, "v": 2.175373674758704, "accelerator_pedal_position": 0.2665403849976991, "brake_pedal_position": 0.0, "acceleration": 0.059786216249352264, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018889560265876786, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.6090317} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2669195283020823, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6487304172504287, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.178467912061017, "gear": 1, "accelerator_pedal_position": 0.2669195283020823, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.6090317} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.96994471549988, "x": 17.752671441705576, "y": 0.15968340225137645, "z": null, "yaw": 3.144691027105662, "pitch": null, "roll": null}, "v": 2.175373674758704, "accelerator_pedal_position": 0.2665403849976991, "brake_pedal_position": 0.0, "acceleration": 0.059786216249352264, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018889560265876786, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.6290317} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2669195283020823, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6487304172504287, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1797046617794336, "gear": 1, "accelerator_pedal_position": 0.2669195283020823, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.6290317} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 57.96994471549988, "x": 17.752671441705576, "y": 0.15968340225137645, "z": null, "yaw": 3.144691027105662, "pitch": null, "roll": null}, "v": 2.175373674758704, "accelerator_pedal_position": 0.2665403849976991, "brake_pedal_position": 0.0, "acceleration": 0.059786216249352264, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018889560265876786, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.6490316} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2669195283020823, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6487304172504287, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.180939097684739, "gear": 1, "accelerator_pedal_position": 0.2669195283020823, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.6490316} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502696.6690316, "x": 21.513041955351085, "y": 5.158836838416539, "z": null, "yaw": 3.1456461970855885, "pitch": null, "roll": null}, "v": 2.1821712234965576, "accelerator_pedal_position": 0.2669195283020823, "brake_pedal_position": 0.0, "acceleration": 0.06151977822662191, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018948585852162855, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.6690316} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2676572617020828, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6639043584005557, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1821712234965576, "gear": 1, "accelerator_pedal_position": 0.2669195283020823, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.6690316} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.0799446105957, "x": 17.513041955351085, "y": 0.15883683841653884, "z": null, "yaw": 3.1456461970855885, "pitch": null, "roll": null}, "v": 2.1821712234965576, "accelerator_pedal_position": 0.2669195283020823, "brake_pedal_position": 0.0, "acceleration": 0.06151977822662191, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018948585852162855, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.6890316} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2674585240680364, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6639043584005557, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.183493216422661, "gear": 1, "accelerator_pedal_position": 0.2676572617020828, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.6890316} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.0799446105957, "x": 17.513041955351085, "y": 0.15883683841653884, "z": null, "yaw": 3.1456461970855885, "pitch": null, "roll": null}, "v": 2.1821712234965576, "accelerator_pedal_position": 0.2669195283020823, "brake_pedal_position": 0.0, "acceleration": 0.06151977822662191, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018948585852162855, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.7090316} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2674585240680364, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6639043584005557, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1847879034976083, "gear": 1, "accelerator_pedal_position": 0.2674585240680364, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.7090316} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.0799446105957, "x": 17.513041955351085, "y": 0.15883683841653884, "z": null, "yaw": 3.1456461970855885, "pitch": null, "roll": null}, "v": 2.1821712234965576, "accelerator_pedal_position": 0.2669195283020823, "brake_pedal_position": 0.0, "acceleration": 0.06151977822662191, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018948585852162855, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.7290316} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2674585240680364, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6639043584005557, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.186080165742952, "gear": 1, "accelerator_pedal_position": 0.2674585240680364, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.7290316} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.0799446105957, "x": 17.513041955351085, "y": 0.15883683841653884, "z": null, "yaw": 3.1456461970855885, "pitch": null, "roll": null}, "v": 2.1821712234965576, "accelerator_pedal_position": 0.2669195283020823, "brake_pedal_position": 0.0, "acceleration": 0.06151977822662191, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018948585852162855, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.7490315} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2674585240680364, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6639043584005557, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1873700070325097, "gear": 1, "accelerator_pedal_position": 0.2674585240680364, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.7490315} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.0799446105957, "x": 17.513041955351085, "y": 0.15883683841653884, "z": null, "yaw": 3.1456461970855885, "pitch": null, "roll": null}, "v": 2.1821712234965576, "accelerator_pedal_position": 0.2669195283020823, "brake_pedal_position": 0.0, "acceleration": 0.06151977822662191, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.018948585852162855, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.7690315} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2674585240680364, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6639043584005557, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1886574312365954, "gear": 1, "accelerator_pedal_position": 0.2674585240680364, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.7690315} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502696.7790315, "x": 21.27264731455648, "y": 5.157757947471164, "z": null, "yaw": 3.146601367065515, "pitch": null, "roll": null}, "v": 2.1893002381400986, "accelerator_pedal_position": 0.2674585240680364, "brake_pedal_position": 0.0, "acceleration": 0.06422040819101948, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019010489677380574, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.7890315} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26808179394339765, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6803551466078215, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1899424422220086, "gear": 1, "accelerator_pedal_position": 0.2674585240680364, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.7890315} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.18994450569153, "x": 17.27264731455648, "y": 0.1577579474711639, "z": null, "yaw": 3.146601367065515, "pitch": null, "roll": null}, "v": 2.1893002381400986, "accelerator_pedal_position": 0.2674585240680364, "brake_pedal_position": 0.0, "acceleration": 0.06422040819101948, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019010489677380574, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.8090315} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2679204266801874, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6803551466078215, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1913029160425492, "gear": 1, "accelerator_pedal_position": 0.26808179394339765, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.8090315} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.18994450569153, "x": 17.27264731455648, "y": 0.1577579474711639, "z": null, "yaw": 3.146601367065515, "pitch": null, "roll": null}, "v": 2.1893002381400986, "accelerator_pedal_position": 0.2674585240680364, "brake_pedal_position": 0.0, "acceleration": 0.06422040819101948, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019010489677380574, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.8290315} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2679204266801874, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6803551466078215, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.192640676844084, "gear": 1, "accelerator_pedal_position": 0.2679204266801874, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.8290315} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.18994450569153, "x": 17.27264731455648, "y": 0.1577579474711639, "z": null, "yaw": 3.146601367065515, "pitch": null, "roll": null}, "v": 2.1893002381400986, "accelerator_pedal_position": 0.2674585240680364, "brake_pedal_position": 0.0, "acceleration": 0.06422040819101948, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019010489677380574, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.8490314} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2679204266801874, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6803551466078215, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.19397592795054, "gear": 1, "accelerator_pedal_position": 0.2679204266801874, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.8490314} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.18994450569153, "x": 17.27264731455648, "y": 0.1577579474711639, "z": null, "yaw": 3.146601367065515, "pitch": null, "roll": null}, "v": 2.1893002381400986, "accelerator_pedal_position": 0.2674585240680364, "brake_pedal_position": 0.0, "acceleration": 0.06422040819101948, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019010489677380574, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.8690314} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2679204266801874, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6803551466078215, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1953086733573866, "gear": 1, "accelerator_pedal_position": 0.2679204266801874, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.8690314} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502696.8890314, "x": 21.03146098340464, "y": 5.156445121962606, "z": null, "yaw": 3.1475565370454412, "pitch": null, "roll": null}, "v": 2.1966389170566076, "accelerator_pedal_position": 0.2679204266801874, "brake_pedal_position": 0.0, "acceleration": 0.06641849557906448, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019074214093683758, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.8890314} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26872573538268174, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5893262407032084, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1966389170566076, "gear": 1, "accelerator_pedal_position": 0.2679204266801874, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.8890314} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.29994440078735, "x": 17.03146098340464, "y": 0.15644512196260596, "z": null, "yaw": 3.1475565370454412, "pitch": null, "roll": null}, "v": 2.1966389170566076, "accelerator_pedal_position": 0.2679204266801874, "brake_pedal_position": 0.0, "acceleration": 0.06641849557906448, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019074214093683758, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.9090314} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2685085164676274, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5893262407032084, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.198067279339513, "gear": 1, "accelerator_pedal_position": 0.26872573538268174, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.9090314} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.29994440078735, "x": 17.03146098340464, "y": 0.15644512196260596, "z": null, "yaw": 3.1475565370454412, "pitch": null, "roll": null}, "v": 2.1966389170566076, "accelerator_pedal_position": 0.2679204266801874, "brake_pedal_position": 0.0, "acceleration": 0.06641849557906448, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019074214093683758, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.9290314} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2685085164676274, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5893262407032084, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1994658192644647, "gear": 1, "accelerator_pedal_position": 0.2685085164676274, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.9290314} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.29994440078735, "x": 17.03146098340464, "y": 0.15644512196260596, "z": null, "yaw": 3.1475565370454412, "pitch": null, "roll": null}, "v": 2.1966389170566076, "accelerator_pedal_position": 0.2679204266801874, "brake_pedal_position": 0.0, "acceleration": 0.06641849557906448, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019074214093683758, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.9490314} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2685085164676274, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5893262407032084, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2008617316641557, "gear": 1, "accelerator_pedal_position": 0.2685085164676274, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.9490314} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.29994440078735, "x": 17.03146098340464, "y": 0.15644512196260596, "z": null, "yaw": 3.1475565370454412, "pitch": null, "roll": null}, "v": 2.1966389170566076, "accelerator_pedal_position": 0.2679204266801874, "brake_pedal_position": 0.0, "acceleration": 0.06641849557906448, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019074214093683758, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.9690313} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2685085164676274, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5893262407032084, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2022550206960196, "gear": 1, "accelerator_pedal_position": 0.2685085164676274, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.9690313} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.29994440078735, "x": 17.03146098340464, "y": 0.15644512196260596, "z": null, "yaw": 3.1475565370454412, "pitch": null, "roll": null}, "v": 2.1966389170566076, "accelerator_pedal_position": 0.2679204266801874, "brake_pedal_position": 0.0, "acceleration": 0.06641849557906448, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019074214093683758, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502696.9890313} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2685085164676274, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5893262407032084, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.203645690514072, "gear": 1, "accelerator_pedal_position": 0.2685085164676274, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502696.9890313} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502696.9990313, "x": 20.78944866383005, "y": 5.154896626685437, "z": null, "yaw": 3.1485117070253676, "pitch": null, "roll": null}, "v": 2.2043400445151096, "accelerator_pedal_position": 0.2685085164676274, "brake_pedal_position": 0.0, "acceleration": 0.06937007537838702, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01914108578241039, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.0090313} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26915562439350593, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6041325204479405, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2050337452688935, "gear": 1, "accelerator_pedal_position": 0.2685085164676274, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.0090313} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.40994429588318, "x": 16.78944866383005, "y": 0.1548966266854368, "z": null, "yaw": 3.1485117070253676, "pitch": null, "roll": null}, "v": 2.2043400445151096, "accelerator_pedal_position": 0.2685085164676274, "brake_pedal_position": 0.0, "acceleration": 0.06937007537838702, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01914108578241039, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.0290313} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2689896021264251, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6041325204479405, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2065000395342804, "gear": 1, "accelerator_pedal_position": 0.26915562439350593, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.0290313} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.40994429588318, "x": 16.78944866383005, "y": 0.1548966266854368, "z": null, "yaw": 3.1485117070253676, "pitch": null, "roll": null}, "v": 2.2043400445151096, "accelerator_pedal_position": 0.2685085164676274, "brake_pedal_position": 0.0, "acceleration": 0.06937007537838702, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01914108578241039, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.0490313} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2689896021264251, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6041325204479405, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.207942831853585, "gear": 1, "accelerator_pedal_position": 0.2689896021264251, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.0490313} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.40994429588318, "x": 16.78944866383005, "y": 0.1548966266854368, "z": null, "yaw": 3.1485117070253676, "pitch": null, "roll": null}, "v": 2.2043400445151096, "accelerator_pedal_position": 0.2685085164676274, "brake_pedal_position": 0.0, "acceleration": 0.06937007537838702, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01914108578241039, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.0690312} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2689896021264251, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6041325204479405, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2093829086266177, "gear": 1, "accelerator_pedal_position": 0.2689896021264251, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.0690312} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.40994429588318, "x": 16.78944866383005, "y": 0.1548966266854368, "z": null, "yaw": 3.1485117070253676, "pitch": null, "roll": null}, "v": 2.2043400445151096, "accelerator_pedal_position": 0.2685085164676274, "brake_pedal_position": 0.0, "acceleration": 0.06937007537838702, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01914108578241039, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.0890312} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2689896021264251, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.6041325204479405, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2108202741352954, "gear": 1, "accelerator_pedal_position": 0.2689896021264251, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.0890312} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502697.1090312, "x": 20.546582120143828, "y": 5.15311067407925, "z": null, "yaw": 3.149466877005294, "pitch": null, "roll": null}, "v": 2.212254932658156, "accelerator_pedal_position": 0.2689896021264251, "brake_pedal_position": 0.0, "acceleration": 0.07163154778654551, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019209813632853064, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.1090312} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26949888359280194, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5540327153281539, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.212254932658156, "gear": 1, "accelerator_pedal_position": 0.2689896021264251, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.1090312} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.519944190979004, "x": 16.546582120143828, "y": 0.15311067407925005, "z": null, "yaw": 3.149466877005294, "pitch": null, "roll": null}, "v": 2.212254932658156, "accelerator_pedal_position": 0.2689896021264251, "brake_pedal_position": 0.0, "acceleration": 0.07163154778654551, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019209813632853064, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.1290312} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26937699870261156, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5540327153281539, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.213750518650682, "gear": 1, "accelerator_pedal_position": 0.26949888359280194, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.1290312} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.519944190979004, "x": 16.546582120143828, "y": 0.15311067407925005, "z": null, "yaw": 3.149466877005294, "pitch": null, "roll": null}, "v": 2.212254932658156, "accelerator_pedal_position": 0.2689896021264251, "brake_pedal_position": 0.0, "acceleration": 0.07163154778654551, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019209813632853064, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.1490312} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26937699870261156, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5540327153281539, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2152280578398695, "gear": 1, "accelerator_pedal_position": 0.26937699870261156, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.1490312} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.519944190979004, "x": 16.546582120143828, "y": 0.15311067407925005, "z": null, "yaw": 3.149466877005294, "pitch": null, "roll": null}, "v": 2.212254932658156, "accelerator_pedal_position": 0.2689896021264251, "brake_pedal_position": 0.0, "acceleration": 0.07163154778654551, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019209813632853064, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.1690311} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26937699870261156, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5540327153281539, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.216702811787597, "gear": 1, "accelerator_pedal_position": 0.26937699870261156, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.1690311} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.519944190979004, "x": 16.546582120143828, "y": 0.15311067407925005, "z": null, "yaw": 3.149466877005294, "pitch": null, "roll": null}, "v": 2.212254932658156, "accelerator_pedal_position": 0.2689896021264251, "brake_pedal_position": 0.0, "acceleration": 0.07163154778654551, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019209813632853064, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.1890311} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26937699870261156, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5540327153281539, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2181747848746456, "gear": 1, "accelerator_pedal_position": 0.26937699870261156, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.1890311} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.519944190979004, "x": 16.546582120143828, "y": 0.15311067407925005, "z": null, "yaw": 3.149466877005294, "pitch": null, "roll": null}, "v": 2.212254932658156, "accelerator_pedal_position": 0.2689896021264251, "brake_pedal_position": 0.0, "acceleration": 0.07163154778654551, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019209813632853064, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.209031} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26937699870261156, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.5540327153281539, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.219643981478455, "gear": 1, "accelerator_pedal_position": 0.26937699870261156, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.209031} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502697.219031, "x": 20.30283491841427, "y": 5.151085409751915, "z": null, "yaw": 3.1504220469852204, "pitch": null, "roll": null}, "v": 2.2203775399661776, "accelerator_pedal_position": 0.26937699870261156, "brake_pedal_position": 0.0, "acceleration": 0.07328660069315074, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01928034518430155, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.229031} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2702258967191302, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.47040774893818027, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2211104059731093, "gear": 1, "accelerator_pedal_position": 0.26937699870261156, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.229031} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.62994408607483, "x": 16.30283491841427, "y": 0.1510854097519152, "z": null, "yaw": 3.1504220469852204, "pitch": null, "roll": null}, "v": 2.2203775399661776, "accelerator_pedal_position": 0.26937699870261156, "brake_pedal_position": 0.0, "acceleration": 0.07328660069315074, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01928034518430155, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.249031} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26999892472488174, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.47040774893818027, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.222680124876572, "gear": 1, "accelerator_pedal_position": 0.2702258967191302, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.249031} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.62994408607483, "x": 16.30283491841427, "y": 0.1510854097519152, "z": null, "yaw": 3.1504220469852204, "pitch": null, "roll": null}, "v": 2.2203775399661776, "accelerator_pedal_position": 0.26937699870261156, "brake_pedal_position": 0.0, "acceleration": 0.07328660069315074, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01928034518430155, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.269031} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26999892472488174, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.47040774893818027, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2242185220165096, "gear": 1, "accelerator_pedal_position": 0.26999892472488174, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.269031} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.62994408607483, "x": 16.30283491841427, "y": 0.1510854097519152, "z": null, "yaw": 3.1504220469852204, "pitch": null, "roll": null}, "v": 2.2203775399661776, "accelerator_pedal_position": 0.26937699870261156, "brake_pedal_position": 0.0, "acceleration": 0.07328660069315074, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01928034518430155, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.289031} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26999892472488174, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.47040774893818027, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.225754013676669, "gear": 1, "accelerator_pedal_position": 0.26999892472488174, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.289031} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.62994408607483, "x": 16.30283491841427, "y": 0.1510854097519152, "z": null, "yaw": 3.1504220469852204, "pitch": null, "roll": null}, "v": 2.2203775399661776, "accelerator_pedal_position": 0.26937699870261156, "brake_pedal_position": 0.0, "acceleration": 0.07328660069315074, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01928034518430155, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.309031} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26999892472488174, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.47040774893818027, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2272866044018103, "gear": 1, "accelerator_pedal_position": 0.26999892472488174, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.309031} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502697.329031, "x": 20.05818210946566, "y": 5.14881891506748, "z": null, "yaw": 3.151377216965147, "pitch": null, "roll": null}, "v": 2.2288162987334488, "accelerator_pedal_position": 0.26999892472488174, "brake_pedal_position": 0.0, "acceleration": 0.07637624365883966, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019353621993777166, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.329031} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27193637668606435, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.40423612595068786, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2288162987334488, "gear": 1, "accelerator_pedal_position": 0.26999892472488174, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.329031} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.739943981170654, "x": 16.05818210946566, "y": 0.1488189150674799, "z": null, "yaw": 3.151377216965147, "pitch": null, "roll": null}, "v": 2.2288162987334488, "accelerator_pedal_position": 0.26999892472488174, "brake_pedal_position": 0.0, "acceleration": 0.07637624365883966, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019353621993777166, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.349031} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2713707923110438, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.40423612595068786, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.230585168161845, "gear": 1, "accelerator_pedal_position": 0.27193637668606435, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.349031} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.739943981170654, "x": 16.05818210946566, "y": 0.1488189150674799, "z": null, "yaw": 3.151377216965147, "pitch": null, "roll": null}, "v": 2.2288162987334488, "accelerator_pedal_position": 0.26999892472488174, "brake_pedal_position": 0.0, "acceleration": 0.07637624365883966, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019353621993777166, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.369031} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2713707923110438, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.40423612595068786, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2322800277749257, "gear": 1, "accelerator_pedal_position": 0.2713707923110438, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.369031} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.739943981170654, "x": 16.05818210946566, "y": 0.1488189150674799, "z": null, "yaw": 3.151377216965147, "pitch": null, "roll": null}, "v": 2.2288162987334488, "accelerator_pedal_position": 0.26999892472488174, "brake_pedal_position": 0.0, "acceleration": 0.07637624365883966, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019353621993777166, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.389031} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2713707923110438, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.40423612595068786, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2339716809732257, "gear": 1, "accelerator_pedal_position": 0.2713707923110438, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.389031} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.739943981170654, "x": 16.05818210946566, "y": 0.1488189150674799, "z": null, "yaw": 3.151377216965147, "pitch": null, "roll": null}, "v": 2.2288162987334488, "accelerator_pedal_position": 0.26999892472488174, "brake_pedal_position": 0.0, "acceleration": 0.07637624365883966, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019353621993777166, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.409031} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2713707923110438, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.40423612595068786, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2356601326786567, "gear": 1, "accelerator_pedal_position": 0.2713707923110438, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.409031} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.739943981170654, "x": 16.05818210946566, "y": 0.1488189150674799, "z": null, "yaw": 3.151377216965147, "pitch": null, "roll": null}, "v": 2.2288162987334488, "accelerator_pedal_position": 0.26999892472488174, "brake_pedal_position": 0.0, "acceleration": 0.07637624365883966, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019353621993777166, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.429031} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2713707923110438, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.40423612595068786, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.237345387810309, "gear": 1, "accelerator_pedal_position": 0.2713707923110438, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.429031} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502697.439031, "x": 19.81255255905506, "y": 5.146308724034832, "z": null, "yaw": 3.1523323869450732, "pitch": null, "roll": null}, "v": 2.2381868181974087, "accelerator_pedal_position": 0.2713707923110438, "brake_pedal_position": 0.0, "acceleration": 0.08406330870262668, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01943498962003415, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.4490309} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27190873339566546, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4065710547313976, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.239027451284435, "gear": 1, "accelerator_pedal_position": 0.2713707923110438, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.4490309} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.84994387626648, "x": 15.81255255905506, "y": 0.14630872403483242, "z": null, "yaw": 3.1523323869450732, "pitch": null, "roll": null}, "v": 2.2381868181974087, "accelerator_pedal_position": 0.2713707923110438, "brake_pedal_position": 0.0, "acceleration": 0.08406330870262668, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01943498962003415, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.4690309} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27178498209406976, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4065710547313976, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2407735387777734, "gear": 1, "accelerator_pedal_position": 0.27190873339566546, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.4690309} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.84994387626648, "x": 15.81255255905506, "y": 0.14630872403483242, "z": null, "yaw": 3.1523323869450732, "pitch": null, "roll": null}, "v": 2.2381868181974087, "accelerator_pedal_position": 0.2713707923110438, "brake_pedal_position": 0.0, "acceleration": 0.08406330870262668, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01943498962003415, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.4890308} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27178498209406976, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4065710547313976, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.242500855445528, "gear": 1, "accelerator_pedal_position": 0.27178498209406976, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.4890308} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.84994387626648, "x": 15.81255255905506, "y": 0.14630872403483242, "z": null, "yaw": 3.1523323869450732, "pitch": null, "roll": null}, "v": 2.2381868181974087, "accelerator_pedal_position": 0.2713707923110438, "brake_pedal_position": 0.0, "acceleration": 0.08406330870262668, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01943498962003415, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.5090308} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27178498209406976, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4065710547313976, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2442248972451777, "gear": 1, "accelerator_pedal_position": 0.27178498209406976, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.5090308} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.84994387626648, "x": 15.81255255905506, "y": 0.14630872403483242, "z": null, "yaw": 3.1523323869450732, "pitch": null, "roll": null}, "v": 2.2381868181974087, "accelerator_pedal_position": 0.2713707923110438, "brake_pedal_position": 0.0, "acceleration": 0.08406330870262668, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01943498962003415, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.5290308} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27178498209406976, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4065710547313976, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2459456691972735, "gear": 1, "accelerator_pedal_position": 0.27178498209406976, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.5290308} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502697.5490308, "x": 19.56589345298601, "y": 5.143552382309852, "z": null, "yaw": 3.1532875569249996, "pitch": null, "roll": null}, "v": 2.247663176319603, "accelerator_pedal_position": 0.27178498209406976, "brake_pedal_position": 0.0, "acceleration": 0.08575308173012447, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019517276281828047, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.5490308} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27232010546141316, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4081995702687707, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.247663176319603, "gear": 1, "accelerator_pedal_position": 0.27178498209406976, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.5490308} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.959943771362305, "x": 15.56589345298601, "y": 0.1435523823098519, "z": null, "yaw": 3.1532875569249996, "pitch": null, "roll": null}, "v": 2.247663176319603, "accelerator_pedal_position": 0.27178498209406976, "brake_pedal_position": 0.0, "acceleration": 0.08575308173012447, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019517276281828047, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.5690308} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27219782498476575, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4081995702687707, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.249444282284924, "gear": 1, "accelerator_pedal_position": 0.27232010546141316, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.5690308} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.959943771362305, "x": 15.56589345298601, "y": 0.1435523823098519, "z": null, "yaw": 3.1532875569249996, "pitch": null, "roll": null}, "v": 2.247663176319603, "accelerator_pedal_position": 0.27178498209406976, "brake_pedal_position": 0.0, "acceleration": 0.08575308173012447, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019517276281828047, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.5890307} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27219782498476575, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4081995702687707, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.251206728670309, "gear": 1, "accelerator_pedal_position": 0.27219782498476575, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.5890307} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.959943771362305, "x": 15.56589345298601, "y": 0.1435523823098519, "z": null, "yaw": 3.1532875569249996, "pitch": null, "roll": null}, "v": 2.247663176319603, "accelerator_pedal_position": 0.27178498209406976, "brake_pedal_position": 0.0, "acceleration": 0.08575308173012447, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019517276281828047, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.6090307} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27219782498476575, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4081995702687707, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.252965827458734, "gear": 1, "accelerator_pedal_position": 0.27219782498476575, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.6090307} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.959943771362305, "x": 15.56589345298601, "y": 0.1435523823098519, "z": null, "yaw": 3.1532875569249996, "pitch": null, "roll": null}, "v": 2.247663176319603, "accelerator_pedal_position": 0.27178498209406976, "brake_pedal_position": 0.0, "acceleration": 0.08575308173012447, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019517276281828047, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.6290307} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27219782498476575, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4081995702687707, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2547215837714534, "gear": 1, "accelerator_pedal_position": 0.27219782498476575, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.6290307} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 58.959943771362305, "x": 15.56589345298601, "y": 0.1435523823098519, "z": null, "yaw": 3.1532875569249996, "pitch": null, "roll": null}, "v": 2.247663176319603, "accelerator_pedal_position": 0.27178498209406976, "brake_pedal_position": 0.0, "acceleration": 0.08575308173012447, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019517276281828047, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.6490307} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27219782498476575, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.4081995702687707, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.256474002727041, "gear": 1, "accelerator_pedal_position": 0.27219782498476575, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.6490307} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502697.6590307, "x": 19.318182838286564, "y": 5.140547651095889, "z": null, "yaw": 3.154242726904926, "pitch": null, "roll": null}, "v": 2.2573489622947274, "accelerator_pedal_position": 0.27219782498476575, "brake_pedal_position": 0.0, "acceleration": 0.0874127146643186, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.0196013814817863, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.6690307} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2726534521957802, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.40953957351731873, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2582230894413704, "gear": 1, "accelerator_pedal_position": 0.27219782498476575, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.6690307} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.06994366645813, "x": 15.318182838286564, "y": 0.14054765109588896, "z": null, "yaw": 3.154242726904926, "pitch": null, "roll": null}, "v": 2.2573489622947274, "accelerator_pedal_position": 0.27219782498476575, "brake_pedal_position": 0.0, "acceleration": 0.0874127146643186, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.0196013814817863, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.6890306} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27255710038579783, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.40953957351731873, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2600257753242126, "gear": 1, "accelerator_pedal_position": 0.2726534521957802, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.6890306} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.06994366645813, "x": 15.318182838286564, "y": 0.14054765109588896, "z": null, "yaw": 3.154242726904926, "pitch": null, "roll": null}, "v": 2.2573489622947274, "accelerator_pedal_position": 0.27219782498476575, "brake_pedal_position": 0.0, "acceleration": 0.0874127146643186, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.0196013814817863, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.7090306} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27255710038579783, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.40953957351731873, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.261812992590956, "gear": 1, "accelerator_pedal_position": 0.27255710038579783, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.7090306} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.06994366645813, "x": 15.318182838286564, "y": 0.14054765109588896, "z": null, "yaw": 3.154242726904926, "pitch": null, "roll": null}, "v": 2.2573489622947274, "accelerator_pedal_position": 0.27219782498476575, "brake_pedal_position": 0.0, "acceleration": 0.0874127146643186, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.0196013814817863, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.7290306} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27255710038579783, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.40953957351731873, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2635968076401976, "gear": 1, "accelerator_pedal_position": 0.27255710038579783, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.7290306} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.06994366645813, "x": 15.318182838286564, "y": 0.14054765109588896, "z": null, "yaw": 3.154242726904926, "pitch": null, "roll": null}, "v": 2.2573489622947274, "accelerator_pedal_position": 0.27219782498476575, "brake_pedal_position": 0.0, "acceleration": 0.0874127146643186, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.0196013814817863, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.7490306} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27255710038579783, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.40953957351731873, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2653772256763403, "gear": 1, "accelerator_pedal_position": 0.27255710038579783, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.7490306} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502697.7690306, "x": 19.069405260810598, "y": 5.137292314136363, "z": null, "yaw": 3.1551978968848524, "pitch": null, "roll": null}, "v": 2.267154251901143, "accelerator_pedal_position": 0.27255710038579783, "brake_pedal_position": 0.0, "acceleration": 0.08872428079704492, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019686524375209107, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.7690306} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2746436588723285, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.35116747545371174, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.267154251901143, "gear": 1, "accelerator_pedal_position": 0.27255710038579783, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.7690306} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.179943561553955, "x": 15.069405260810598, "y": 0.13729231413636267, "z": null, "yaw": 3.1551978968848524, "pitch": null, "roll": null}, "v": 2.267154251901143, "accelerator_pedal_position": 0.27255710038579783, "brake_pedal_position": 0.0, "acceleration": 0.08872428079704492, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019686524375209107, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.7890306} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2740383042045724, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.35116747545371174, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2691885869628465, "gear": 1, "accelerator_pedal_position": 0.2746436588723285, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.7890306} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.179943561553955, "x": 15.069405260810598, "y": 0.13729231413636267, "z": null, "yaw": 3.1551978968848524, "pitch": null, "roll": null}, "v": 2.267154251901143, "accelerator_pedal_position": 0.27255710038579783, "brake_pedal_position": 0.0, "acceleration": 0.08872428079704492, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019686524375209107, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.8090305} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2740383042045724, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.35116747545371174, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2711434102002372, "gear": 1, "accelerator_pedal_position": 0.2740383042045724, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.8090305} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.179943561553955, "x": 15.069405260810598, "y": 0.13729231413636267, "z": null, "yaw": 3.1551978968848524, "pitch": null, "roll": null}, "v": 2.267154251901143, "accelerator_pedal_position": 0.27255710038579783, "brake_pedal_position": 0.0, "acceleration": 0.08872428079704492, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019686524375209107, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.8290305} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2740383042045724, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.35116747545371174, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.273094504902745, "gear": 1, "accelerator_pedal_position": 0.2740383042045724, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.8290305} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.179943561553955, "x": 15.069405260810598, "y": 0.13729231413636267, "z": null, "yaw": 3.1551978968848524, "pitch": null, "roll": null}, "v": 2.267154251901143, "accelerator_pedal_position": 0.27255710038579783, "brake_pedal_position": 0.0, "acceleration": 0.08872428079704492, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019686524375209107, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.8490305} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2740383042045724, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.35116747545371174, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.275041876660014, "gear": 1, "accelerator_pedal_position": 0.2740383042045724, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.8490305} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.179943561553955, "x": 15.069405260810598, "y": 0.13729231413636267, "z": null, "yaw": 3.1551978968848524, "pitch": null, "roll": null}, "v": 2.267154251901143, "accelerator_pedal_position": 0.27255710038579783, "brake_pedal_position": 0.0, "acceleration": 0.08872428079704492, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019686524375209107, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.8690305} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2740383042045724, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.35116747545371174, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.276985531059734, "gear": 1, "accelerator_pedal_position": 0.2740383042045724, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.8690305} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502697.8790305, "x": 18.81949841473894, "y": 5.133783444908925, "z": null, "yaw": 3.156153066864779, "pitch": null, "roll": null}, "v": 2.277955965996124, "accelerator_pedal_position": 0.2740383042045724, "brake_pedal_position": 0.0, "acceleration": 0.09695076914859801, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01978031958462045, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.8890305} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27498914474301156, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3173501896715621, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.27892547368761, "gear": 1, "accelerator_pedal_position": 0.2740383042045724, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.8890305} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.28994345664978, "x": 14.819498414738941, "y": 0.13378344490892502, "z": null, "yaw": 3.156153066864779, "pitch": null, "roll": null}, "v": 2.277955965996124, "accelerator_pedal_position": 0.2740383042045724, "brake_pedal_position": 0.0, "acceleration": 0.09695076914859801, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01978031958462045, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.9090304} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27474355868951994, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3173501896715621, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2809805083828225, "gear": 1, "accelerator_pedal_position": 0.27498914474301156, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.9090304} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.28994345664978, "x": 14.819498414738941, "y": 0.13378344490892502, "z": null, "yaw": 3.156153066864779, "pitch": null, "roll": null}, "v": 2.277955965996124, "accelerator_pedal_position": 0.2740383042045724, "brake_pedal_position": 0.0, "acceleration": 0.09695076914859801, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01978031958462045, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.9290304} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27474355868951994, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3173501896715621, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.283000931769978, "gear": 1, "accelerator_pedal_position": 0.27474355868951994, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.9290304} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.28994345664978, "x": 14.819498414738941, "y": 0.13378344490892502, "z": null, "yaw": 3.156153066864779, "pitch": null, "roll": null}, "v": 2.277955965996124, "accelerator_pedal_position": 0.2740383042045724, "brake_pedal_position": 0.0, "acceleration": 0.09695076914859801, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01978031958462045, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.9490304} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27474355868951994, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3173501896715621, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2850174919392283, "gear": 1, "accelerator_pedal_position": 0.27474355868951994, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.9490304} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.28994345664978, "x": 14.819498414738941, "y": 0.13378344490892502, "z": null, "yaw": 3.156153066864779, "pitch": null, "roll": null}, "v": 2.277955965996124, "accelerator_pedal_position": 0.2740383042045724, "brake_pedal_position": 0.0, "acceleration": 0.09695076914859801, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01978031958462045, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.9690304} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27474355868951994, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.3173501896715621, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2870301946515403, "gear": 1, "accelerator_pedal_position": 0.27474355868951994, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.9690304} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502697.9890304, "x": 18.56839741302652, "y": 5.130017911779184, "z": null, "yaw": 3.157108236844705, "pitch": null, "roll": null}, "v": 2.289039045666189, "accelerator_pedal_position": 0.27474355868951994, "brake_pedal_position": 0.0, "acceleration": 0.10029829200034635, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01987655799358365, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502697.9890304} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27707780457979625, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.2580850732572564, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.289039045666189, "gear": 1, "accelerator_pedal_position": 0.27474355868951994, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502697.9890304} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.399943351745605, "x": 14.56839741302652, "y": 0.1300179117791842, "z": null, "yaw": 3.157108236844705, "pitch": null, "roll": null}, "v": 2.289039045666189, "accelerator_pedal_position": 0.27474355868951994, "brake_pedal_position": 0.0, "acceleration": 0.10029829200034635, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01987655799358365, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.0090303} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2764013681795373, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.2580850732572564, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2913356917106826, "gear": 1, "accelerator_pedal_position": 0.27707780457979625, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.0090303} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.399943351745605, "x": 14.56839741302652, "y": 0.1300179117791842, "z": null, "yaw": 3.157108236844705, "pitch": null, "roll": null}, "v": 2.289039045666189, "accelerator_pedal_position": 0.27474355868951994, "brake_pedal_position": 0.0, "acceleration": 0.10029829200034635, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01987655799358365, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.0290303} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2764013681795373, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.2580850732572564, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2935434247628783, "gear": 1, "accelerator_pedal_position": 0.2764013681795373, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.0290303} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.399943351745605, "x": 14.56839741302652, "y": 0.1300179117791842, "z": null, "yaw": 3.157108236844705, "pitch": null, "roll": null}, "v": 2.289039045666189, "accelerator_pedal_position": 0.27474355868951994, "brake_pedal_position": 0.0, "acceleration": 0.10029829200034635, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01987655799358365, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.0490303} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2764013681795373, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.2580850732572564, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2957469271857227, "gear": 1, "accelerator_pedal_position": 0.2764013681795373, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.0490303} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.399943351745605, "x": 14.56839741302652, "y": 0.1300179117791842, "z": null, "yaw": 3.157108236844705, "pitch": null, "roll": null}, "v": 2.289039045666189, "accelerator_pedal_position": 0.27474355868951994, "brake_pedal_position": 0.0, "acceleration": 0.10029829200034635, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01987655799358365, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.0690303} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2764013681795373, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.2580850732572564, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.297946205145038, "gear": 1, "accelerator_pedal_position": 0.2764013681795373, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.0690303} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.399943351745605, "x": 14.56839741302652, "y": 0.1300179117791842, "z": null, "yaw": 3.157108236844705, "pitch": null, "roll": null}, "v": 2.289039045666189, "accelerator_pedal_position": 0.27474355868951994, "brake_pedal_position": 0.0, "acceleration": 0.10029829200034635, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.01987655799358365, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.0890303} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2764013681795373, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.2580850732572564, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3001412648059874, "gear": 1, "accelerator_pedal_position": 0.2764013681795373, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.0890303} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502698.0990303, "x": 18.316020353051027, "y": 5.12599211326505, "z": null, "yaw": 3.1580634068246316, "pitch": null, "roll": null}, "v": 2.301237214700999, "accelerator_pedal_position": 0.2764013681795373, "brake_pedal_position": 0.0, "acceleration": 0.10948976320380999, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019982479128784456, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.1090302} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2782450938488509, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.20704877482909256, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3023321123330374, "gear": 1, "accelerator_pedal_position": 0.2764013681795373, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.1090302} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.50994324684143, "x": 14.316020353051027, "y": 0.1259921132650499, "z": null, "yaw": 3.1580634068246316, "pitch": null, "roll": null}, "v": 2.301237214700999, "accelerator_pedal_position": 0.2764013681795373, "brake_pedal_position": 0.0, "acceleration": 0.10948976320380999, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019982479128784456, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.1290302} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27772742114323495, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.20704877482909256, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.304749108894752, "gear": 1, "accelerator_pedal_position": 0.2782450938488509, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.1290302} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.50994324684143, "x": 14.316020353051027, "y": 0.1259921132650499, "z": null, "yaw": 3.1580634068246316, "pitch": null, "roll": null}, "v": 2.301237214700999, "accelerator_pedal_position": 0.2764013681795373, "brake_pedal_position": 0.0, "acceleration": 0.10948976320380999, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019982479128784456, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.1490302} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27772742114323495, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.20704877482909256, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3070967850580515, "gear": 1, "accelerator_pedal_position": 0.27772742114323495, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.1490302} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.50994324684143, "x": 14.316020353051027, "y": 0.1259921132650499, "z": null, "yaw": 3.1580634068246316, "pitch": null, "roll": null}, "v": 2.301237214700999, "accelerator_pedal_position": 0.2764013681795373, "brake_pedal_position": 0.0, "acceleration": 0.10948976320380999, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019982479128784456, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.1690302} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27772742114323495, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.20704877482909256, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3094399497396503, "gear": 1, "accelerator_pedal_position": 0.27772742114323495, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.1690302} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.50994324684143, "x": 14.316020353051027, "y": 0.1259921132650499, "z": null, "yaw": 3.1580634068246316, "pitch": null, "roll": null}, "v": 2.301237214700999, "accelerator_pedal_position": 0.2764013681795373, "brake_pedal_position": 0.0, "acceleration": 0.10948976320380999, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.019982479128784456, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.1890302} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27772742114323495, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.20704877482909256, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3117786094140578, "gear": 1, "accelerator_pedal_position": 0.27772742114323495, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.1890302} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502698.2090302, "x": 18.062277390625983, "y": 5.121702087506923, "z": null, "yaw": 3.159018576804558, "pitch": null, "roll": null}, "v": 2.3141127705559956, "accelerator_pedal_position": 0.27772742114323495, "brake_pedal_position": 0.0, "acceleration": 0.11653956446891511, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020094282259943797, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.2090302} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2785295611343749, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.17048213988258631, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3141127705559956, "gear": 1, "accelerator_pedal_position": 0.27772742114323495, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.2090302} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.619943141937256, "x": 14.062277390625983, "y": 0.12170208750692257, "z": null, "yaw": 3.159018576804558, "pitch": null, "roll": null}, "v": 2.3141127705559956, "accelerator_pedal_position": 0.27772742114323495, "brake_pedal_position": 0.0, "acceleration": 0.11653956446891511, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020094282259943797, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.2290301} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2783407937512784, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.17048213988258631, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3165426588573994, "gear": 1, "accelerator_pedal_position": 0.2785295611343749, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.2290301} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.619943141937256, "x": 14.062277390625983, "y": 0.12170208750692257, "z": null, "yaw": 3.159018576804558, "pitch": null, "roll": null}, "v": 2.3141127705559956, "accelerator_pedal_position": 0.27772742114323495, "brake_pedal_position": 0.0, "acceleration": 0.11653956446891511, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020094282259943797, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.24903} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2783407937512784, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.17048213988258631, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.318944283984576, "gear": 1, "accelerator_pedal_position": 0.2783407937512784, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.24903} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.619943141937256, "x": 14.062277390625983, "y": 0.12170208750692257, "z": null, "yaw": 3.159018576804558, "pitch": null, "roll": null}, "v": 2.3141127705559956, "accelerator_pedal_position": 0.27772742114323495, "brake_pedal_position": 0.0, "acceleration": 0.11653956446891511, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020094282259943797, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.26903} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2783407937512784, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.17048213988258631, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.321341282600026, "gear": 1, "accelerator_pedal_position": 0.2783407937512784, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.26903} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.619943141937256, "x": 14.062277390625983, "y": 0.12170208750692257, "z": null, "yaw": 3.159018576804558, "pitch": null, "roll": null}, "v": 2.3141127705559956, "accelerator_pedal_position": 0.27772742114323495, "brake_pedal_position": 0.0, "acceleration": 0.11653956446891511, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020094282259943797, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.28903} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2783407937512784, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.17048213988258631, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.323733661319168, "gear": 1, "accelerator_pedal_position": 0.2783407937512784, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.28903} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.619943141937256, "x": 14.062277390625983, "y": 0.12170208750692257, "z": null, "yaw": 3.159018576804558, "pitch": null, "roll": null}, "v": 2.3141127705559956, "accelerator_pedal_position": 0.27772742114323495, "brake_pedal_position": 0.0, "acceleration": 0.11653956446891511, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020094282259943797, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.30903} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2783407937512784, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.17048213988258631, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.326121426757952, "gear": 1, "accelerator_pedal_position": 0.2783407937512784, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.30903} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502698.31903, "x": 17.807103326135024, "y": 5.117144056113481, "z": null, "yaw": 3.1599737467844844, "pitch": null, "roll": null}, "v": 2.327313581564826, "accelerator_pedal_position": 0.2783407937512784, "brake_pedal_position": 0.0, "acceleration": 0.11910039679788764, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020208909699819113, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.32903} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28059613086914265, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.10972570945333895, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3285045855328046, "gear": 1, "accelerator_pedal_position": 0.2783407937512784, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.32903} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.72994303703308, "x": 13.807103326135024, "y": 0.11714405611348067, "z": null, "yaw": 3.1599737467844844, "pitch": null, "roll": null}, "v": 2.327313581564826, "accelerator_pedal_position": 0.2783407937512784, "brake_pedal_position": 0.0, "acceleration": 0.11910039679788764, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020208909699819113, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.34903} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2799549749230004, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.10972570945333895, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.331164925240962, "gear": 1, "accelerator_pedal_position": 0.28059613086914265, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.34903} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.72994303703308, "x": 13.807103326135024, "y": 0.11714405611348067, "z": null, "yaw": 3.1599737467844844, "pitch": null, "roll": null}, "v": 2.327313581564826, "accelerator_pedal_position": 0.2783407937512784, "brake_pedal_position": 0.0, "acceleration": 0.11910039679788764, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020208909699819113, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.36903} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2799549749230004, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.10972570945333895, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3337400213606156, "gear": 1, "accelerator_pedal_position": 0.2799549749230004, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.36903} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.72994303703308, "x": 13.807103326135024, "y": 0.11714405611348067, "z": null, "yaw": 3.1599737467844844, "pitch": null, "roll": null}, "v": 2.327313581564826, "accelerator_pedal_position": 0.2783407937512784, "brake_pedal_position": 0.0, "acceleration": 0.11910039679788764, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020208909699819113, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.38903} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2799549749230004, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.10972570945333895, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3363101416116803, "gear": 1, "accelerator_pedal_position": 0.2799549749230004, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.38903} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.72994303703308, "x": 13.807103326135024, "y": 0.11714405611348067, "z": null, "yaw": 3.1599737467844844, "pitch": null, "roll": null}, "v": 2.327313581564826, "accelerator_pedal_position": 0.2783407937512784, "brake_pedal_position": 0.0, "acceleration": 0.11910039679788764, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020208909699819113, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.40903} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2799549749230004, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.10972570945333895, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3388752929681167, "gear": 1, "accelerator_pedal_position": 0.2799549749230004, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.40903} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502698.42903, "x": 17.55043905530778, "y": 5.1123141576451, "z": null, "yaw": 3.160928916764411, "pitch": null, "roll": null}, "v": 2.3414354824057173, "accelerator_pedal_position": 0.2799549749230004, "brake_pedal_position": 0.0, "acceleration": 0.12782361796578173, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020331535297479865, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.42903} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28178480033156705, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0542742918567876, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3414354824057173, "gear": 1, "accelerator_pedal_position": 0.2799549749230004, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.42903} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.839942932128906, "x": 13.55043905530778, "y": 0.11231415764510011, "z": null, "yaw": 3.160928916764411, "pitch": null, "roll": null}, "v": 2.3414354824057173, "accelerator_pedal_position": 0.2799549749230004, "brake_pedal_position": 0.0, "acceleration": 0.12782361796578173, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020331535297479865, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.44903} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2812812501190051, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0542742918567876, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3442193343103006, "gear": 1, "accelerator_pedal_position": 0.28178480033156705, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.44903} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.839942932128906, "x": 13.55043905530778, "y": 0.11231415764510011, "z": null, "yaw": 3.160928916764411, "pitch": null, "roll": null}, "v": 2.3414354824057173, "accelerator_pedal_position": 0.2799549749230004, "brake_pedal_position": 0.0, "acceleration": 0.12782361796578173, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020331535297479865, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.46903} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2812812501190051, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0542742918567876, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.346934882090314, "gear": 1, "accelerator_pedal_position": 0.2812812501190051, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.46903} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.839942932128906, "x": 13.55043905530778, "y": 0.11231415764510011, "z": null, "yaw": 3.160928916764411, "pitch": null, "roll": null}, "v": 2.3414354824057173, "accelerator_pedal_position": 0.2799549749230004, "brake_pedal_position": 0.0, "acceleration": 0.12782361796578173, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020331535297479865, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.48903} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2812812501190051, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0542742918567876, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3496451683259165, "gear": 1, "accelerator_pedal_position": 0.2812812501190051, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.48903} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.839942932128906, "x": 13.55043905530778, "y": 0.11231415764510011, "z": null, "yaw": 3.160928916764411, "pitch": null, "roll": null}, "v": 2.3414354824057173, "accelerator_pedal_position": 0.2799549749230004, "brake_pedal_position": 0.0, "acceleration": 0.12782361796578173, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020331535297479865, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.5090299} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2812812501190051, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0542742918567876, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3523502002748438, "gear": 1, "accelerator_pedal_position": 0.2812812501190051, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.5090299} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.839942932128906, "x": 13.55043905530778, "y": 0.11231415764510011, "z": null, "yaw": 3.160928916764411, "pitch": null, "roll": null}, "v": 2.3414354824057173, "accelerator_pedal_position": 0.2799549749230004, "brake_pedal_position": 0.0, "acceleration": 0.12782361796578173, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020331535297479865, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.5290298} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2812812501190051, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.0542742918567876, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3563979122944, "gear": 1, "accelerator_pedal_position": 0.2812812501190051, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.5290298} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502698.5390298, "x": 17.292179242106776, "y": 5.10720745453783, "z": null, "yaw": 3.161884086744337, "pitch": null, "roll": null}, "v": 2.3563979122944, "accelerator_pedal_position": 0.2812812501190051, "brake_pedal_position": 0.0, "acceleration": 0.13466180641840791, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.02046145951435611, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.5490298} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2824024227906168, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.008808776717991122, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.357744530358584, "gear": 1, "accelerator_pedal_position": 0.2812812501190051, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.5490298} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.94994282722473, "x": 13.292179242106776, "y": 0.10720745453783032, "z": null, "yaw": 3.161884086744337, "pitch": null, "roll": null}, "v": 2.3563979122944, "accelerator_pedal_position": 0.2812812501190051, "brake_pedal_position": 0.0, "acceleration": 0.13466180641840791, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.02046145951435611, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.5690298} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28212460772470854, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.008808776717991122, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3605739215086032, "gear": 1, "accelerator_pedal_position": 0.2824024227906168, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.5690298} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.94994282722473, "x": 13.292179242106776, "y": 0.10720745453783032, "z": null, "yaw": 3.161884086744337, "pitch": null, "roll": null}, "v": 2.3563979122944, "accelerator_pedal_position": 0.2812812501190051, "brake_pedal_position": 0.0, "acceleration": 0.13466180641840791, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.02046145951435611, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.5890298} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28212460772470854, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.008808776717991122, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3633631051475334, "gear": 1, "accelerator_pedal_position": 0.28212460772470854, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.5890298} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.94994282722473, "x": 13.292179242106776, "y": 0.10720745453783032, "z": null, "yaw": 3.161884086744337, "pitch": null, "roll": null}, "v": 2.3563979122944, "accelerator_pedal_position": 0.2812812501190051, "brake_pedal_position": 0.0, "acceleration": 0.13466180641840791, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.02046145951435611, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.6090298} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28212460772470854, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.008808776717991122, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3661468662777425, "gear": 1, "accelerator_pedal_position": 0.28212460772470854, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.6090298} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 59.94994282722473, "x": 13.292179242106776, "y": 0.10720745453783032, "z": null, "yaw": 3.161884086744337, "pitch": null, "roll": null}, "v": 2.3563979122944, "accelerator_pedal_position": 0.2812812501190051, "brake_pedal_position": 0.0, "acceleration": 0.13466180641840791, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.02046145951435611, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.6290298} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.28212460772470854, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": 0.008808776717991122, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3689252123430165, "gear": 1, "accelerator_pedal_position": 0.28212460772470854, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.6290298} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502698.6490297, "x": 17.032266233659133, "y": 5.101819696509134, "z": null, "yaw": 3.1628392567242636, "pitch": null, "roll": null}, "v": 2.3716981507907393, "accelerator_pedal_position": 0.28212460772470854, "brake_pedal_position": 0.0, "acceleration": 0.13844436955524925, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.02059431704615048, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.6490297} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2759000018253149, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.03870189619775816, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3716981507907393, "gear": 1, "accelerator_pedal_position": 0.28212460772470854, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.6490297} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.05994272232056, "x": 13.032266233659133, "y": 0.1018196965091338, "z": null, "yaw": 3.1628392567242636, "pitch": null, "roll": null}, "v": 2.3716981507907393, "accelerator_pedal_position": 0.28212460772470854, "brake_pedal_position": 0.0, "acceleration": 0.13844436955524925, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.02059431704615048, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.6690297} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2779196135879763, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.03870189619775816, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3736879924819916, "gear": 1, "accelerator_pedal_position": 0.2759000018253149, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.6690297} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.05994272232056, "x": 13.032266233659133, "y": 0.1018196965091338, "z": null, "yaw": 3.1628392567242636, "pitch": null, "roll": null}, "v": 2.3716981507907393, "accelerator_pedal_position": 0.28212460772470854, "brake_pedal_position": 0.0, "acceleration": 0.13844436955524925, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.02059431704615048, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.6890297} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2779196135879763, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.03870189619775816, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.375926285719239, "gear": 1, "accelerator_pedal_position": 0.2779196135879763, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.6890297} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.05994272232056, "x": 13.032266233659133, "y": 0.1018196965091338, "z": null, "yaw": 3.1628392567242636, "pitch": null, "roll": null}, "v": 2.3716981507907393, "accelerator_pedal_position": 0.28212460772470854, "brake_pedal_position": 0.0, "acceleration": 0.13844436955524925, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.02059431704615048, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.7090297} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2779196135879763, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.03870189619775816, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3781602160846917, "gear": 1, "accelerator_pedal_position": 0.2779196135879763, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.7090297} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.05994272232056, "x": 13.032266233659133, "y": 0.1018196965091338, "z": null, "yaw": 3.1628392567242636, "pitch": null, "roll": null}, "v": 2.3716981507907393, "accelerator_pedal_position": 0.28212460772470854, "brake_pedal_position": 0.0, "acceleration": 0.13844436955524925, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.02059431704615048, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.7290297} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2779196135879763, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.03870189619775816, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3803897900872353, "gear": 1, "accelerator_pedal_position": 0.2779196135879763, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.7290297} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.05994272232056, "x": 13.032266233659133, "y": 0.1018196965091338, "z": null, "yaw": 3.1628392567242636, "pitch": null, "roll": null}, "v": 2.3716981507907393, "accelerator_pedal_position": 0.28212460772470854, "brake_pedal_position": 0.0, "acceleration": 0.13844436955524925, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.02059431704615048, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.7490296} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2779196135879763, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.03870189619775816, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3826150142347347, "gear": 1, "accelerator_pedal_position": 0.2779196135879763, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.7490296} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502698.7590296, "x": 16.770849688226065, "y": 5.096150990780009, "z": null, "yaw": 3.16379442670419, "pitch": null, "roll": null}, "v": 2.3837259971462603, "accelerator_pedal_position": 0.2779196135879763, "brake_pedal_position": 0.0, "acceleration": 0.11098978877282933, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.02069875920762259, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.7690296} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2692037840001167, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.0957718140305492, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3848358950339885, "gear": 1, "accelerator_pedal_position": 0.2779196135879763, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.7690296} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.16994261741638, "x": 12.770849688226065, "y": 0.09615099078000888, "z": null, "yaw": 3.16379442670419, "pitch": null, "roll": null}, "v": 2.3837259971462603, "accelerator_pedal_position": 0.2779196135879763, "brake_pedal_position": 0.0, "acceleration": 0.11098978877282933, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.02069875920762259, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.7890296} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2719861509419769, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.0957718140305492, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3859634925757978, "gear": 1, "accelerator_pedal_position": 0.2692037840001167, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.7890296} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.16994261741638, "x": 12.770849688226065, "y": 0.09615099078000888, "z": null, "yaw": 3.16379442670419, "pitch": null, "roll": null}, "v": 2.3837259971462603, "accelerator_pedal_position": 0.2779196135879763, "brake_pedal_position": 0.0, "acceleration": 0.11098978877282933, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.02069875920762259, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.8090296} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2719861509419769, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.0957718140305492, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.387436513474609, "gear": 1, "accelerator_pedal_position": 0.2719861509419769, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.8090296} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.16994261741638, "x": 12.770849688226065, "y": 0.09615099078000888, "z": null, "yaw": 3.16379442670419, "pitch": null, "roll": null}, "v": 2.3837259971462603, "accelerator_pedal_position": 0.2779196135879763, "brake_pedal_position": 0.0, "acceleration": 0.11098978877282933, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.02069875920762259, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.8290296} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2719861509419769, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.0957718140305492, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3889066562792878, "gear": 1, "accelerator_pedal_position": 0.2719861509419769, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.8290296} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.16994261741638, "x": 12.770849688226065, "y": 0.09615099078000888, "z": null, "yaw": 3.16379442670419, "pitch": null, "roll": null}, "v": 2.3837259971462603, "accelerator_pedal_position": 0.2779196135879763, "brake_pedal_position": 0.0, "acceleration": 0.11098978877282933, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.02069875920762259, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.8490295} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2719861509419769, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.0957718140305492, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.390373925749154, "gear": 1, "accelerator_pedal_position": 0.2719861509419769, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.8490295} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502698.8690295, "x": 16.508294359948373, "y": 5.090206719775156, "z": null, "yaw": 3.1647495966841164, "pitch": null, "roll": null}, "v": 2.391838326639294, "accelerator_pedal_position": 0.2719861509419769, "brake_pedal_position": 0.0, "acceleration": 0.07311262124758444, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020769201513068027, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.8690295} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26741335263356547, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.1327960413973916, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.391838326639294, "gear": 1, "accelerator_pedal_position": 0.2719861509419769, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.8690295} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.27994251251221, "x": 12.508294359948373, "y": 0.09020671977515615, "z": null, "yaw": 3.1647495966841164, "pitch": null, "roll": null}, "v": 2.391838326639294, "accelerator_pedal_position": 0.2719861509419769, "brake_pedal_position": 0.0, "acceleration": 0.07311262124758444, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020769201513068027, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.8890295} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26888200436725457, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.1327960413973916, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3927285435629924, "gear": 1, "accelerator_pedal_position": 0.26741335263356547, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.8890295} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.27994251251221, "x": 12.508294359948373, "y": 0.09020671977515615, "z": null, "yaw": 3.1647495966841164, "pitch": null, "roll": null}, "v": 2.391838326639294, "accelerator_pedal_position": 0.2719861509419769, "brake_pedal_position": 0.0, "acceleration": 0.07311262124758444, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020769201513068027, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.9090295} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26888200436725457, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.1327960413973916, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3938005108187093, "gear": 1, "accelerator_pedal_position": 0.26888200436725457, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.9090295} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.27994251251221, "x": 12.508294359948373, "y": 0.09020671977515615, "z": null, "yaw": 3.1647495966841164, "pitch": null, "roll": null}, "v": 2.391838326639294, "accelerator_pedal_position": 0.2719861509419769, "brake_pedal_position": 0.0, "acceleration": 0.07311262124758444, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020769201513068027, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.9290295} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26888200436725457, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.1327960413973916, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3948703808186336, "gear": 1, "accelerator_pedal_position": 0.26888200436725457, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.9290295} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.27994251251221, "x": 12.508294359948373, "y": 0.09020671977515615, "z": null, "yaw": 3.1647495966841164, "pitch": null, "roll": null}, "v": 2.391838326639294, "accelerator_pedal_position": 0.2719861509419769, "brake_pedal_position": 0.0, "acceleration": 0.07311262124758444, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020769201513068027, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.9490294} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26888200436725457, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.1327960413973916, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3959381572083274, "gear": 1, "accelerator_pedal_position": 0.26888200436725457, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.9490294} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.27994251251221, "x": 12.508294359948373, "y": 0.09020671977515615, "z": null, "yaw": 3.1647495966841164, "pitch": null, "roll": null}, "v": 2.391838326639294, "accelerator_pedal_position": 0.2719861509419769, "brake_pedal_position": 0.0, "acceleration": 0.07311262124758444, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020769201513068027, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.9690294} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26888200436725457, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.1327960413973916, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.397003843628905, "gear": 1, "accelerator_pedal_position": 0.26888200436725457, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.9690294} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502698.9790294, "x": 16.244988261261025, "y": 5.083993833703883, "z": null, "yaw": 3.1657047666640428, "pitch": null, "roll": null}, "v": 2.397535904237407, "accelerator_pedal_position": 0.26888200436725457, "brake_pedal_position": 0.0, "acceleration": 0.05315394796239581, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.02081867565015898, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502698.9890294} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2620269000625193, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.18522112355275888, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3980674437170313, "gear": 1, "accelerator_pedal_position": 0.26888200436725457, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502698.9890294} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.38994240760803, "x": 12.244988261261025, "y": 0.08399383370388325, "z": null, "yaw": 3.1657047666640428, "pitch": null, "roll": null}, "v": 2.397535904237407, "accelerator_pedal_position": 0.26888200436725457, "brake_pedal_position": 0.0, "acceleration": 0.05315394796239581, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.02081867565015898, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.0090294} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2641970094402424, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.18522112355275888, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.39827249280351, "gear": 1, "accelerator_pedal_position": 0.2620269000625193, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.0090294} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.38994240760803, "x": 12.244988261261025, "y": 0.08399383370388325, "z": null, "yaw": 3.1657047666640428, "pitch": null, "roll": null}, "v": 2.397535904237407, "accelerator_pedal_position": 0.26888200436725457, "brake_pedal_position": 0.0, "acceleration": 0.05315394796239581, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.02081867565015898, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.0290294} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2641970094402424, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.18522112355275888, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3987482711317223, "gear": 1, "accelerator_pedal_position": 0.2641970094402424, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.0290294} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.38994240760803, "x": 12.244988261261025, "y": 0.08399383370388325, "z": null, "yaw": 3.1657047666640428, "pitch": null, "roll": null}, "v": 2.397535904237407, "accelerator_pedal_position": 0.26888200436725457, "brake_pedal_position": 0.0, "acceleration": 0.05315394796239581, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.02081867565015898, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.0490294} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2641970094402424, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.18522112355275888, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.399223117651959, "gear": 1, "accelerator_pedal_position": 0.2641970094402424, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.0490294} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.38994240760803, "x": 12.244988261261025, "y": 0.08399383370388325, "z": null, "yaw": 3.1657047666640428, "pitch": null, "roll": null}, "v": 2.397535904237407, "accelerator_pedal_position": 0.26888200436725457, "brake_pedal_position": 0.0, "acceleration": 0.05315394796239581, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.02081867565015898, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.0690293} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2641970094402424, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.18522112355275888, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3996970340990105, "gear": 1, "accelerator_pedal_position": 0.2641970094402424, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.0690293} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502699.0890293, "x": 15.98120171574094, "y": 5.077517532718935, "z": null, "yaw": 3.166659936643969, "pitch": null, "roll": null}, "v": 2.4001700222048, "accelerator_pedal_position": 0.2641970094402424, "brake_pedal_position": 0.0, "acceleration": 0.02361464653636891, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.02084154865385018, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.0890293} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2589298545631059, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.2350991826489276, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4001700222048, "gear": 1, "accelerator_pedal_position": 0.2641970094402424, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.0890293} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.49994230270386, "x": 11.98120171574094, "y": 0.07751753271893502, "z": null, "yaw": 3.166659936643969, "pitch": null, "roll": null}, "v": 2.4001700222048, "accelerator_pedal_position": 0.2641970094402424, "brake_pedal_position": 0.0, "acceleration": 0.02361464653636891, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.02084154865385018, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.1090293} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2605887457064749, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.2350991826489276, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.399984011967884, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.1090293} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.49994230270386, "x": 11.98120171574094, "y": 0.07751753271893502, "z": null, "yaw": 3.166659936643969, "pitch": null, "roll": null}, "v": 2.4001700222048, "accelerator_pedal_position": 0.2641970094402424, "brake_pedal_position": 0.0, "acceleration": 0.02361464653636891, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.02084154865385018, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.1290293} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2605887457064749, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.2350991826489276, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4000056259216787, "gear": 1, "accelerator_pedal_position": 0.2605887457064749, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.1290293} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.49994230270386, "x": 11.98120171574094, "y": 0.07751753271893502, "z": null, "yaw": 3.166659936643969, "pitch": null, "roll": null}, "v": 2.4001700222048, "accelerator_pedal_position": 0.2641970094402424, "brake_pedal_position": 0.0, "acceleration": 0.02361464653636891, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.02084154865385018, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.1490293} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2605887457064749, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.2350991826489276, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.40002719753288, "gear": 1, "accelerator_pedal_position": 0.2605887457064749, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.1490293} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.49994230270386, "x": 11.98120171574094, "y": 0.07751753271893502, "z": null, "yaw": 3.166659936643969, "pitch": null, "roll": null}, "v": 2.4001700222048, "accelerator_pedal_position": 0.2641970094402424, "brake_pedal_position": 0.0, "acceleration": 0.02361464653636891, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.02084154865385018, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.1690292} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2605887457064749, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.2350991826489276, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4000487268842527, "gear": 1, "accelerator_pedal_position": 0.2605887457064749, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.1690292} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.49994230270386, "x": 11.98120171574094, "y": 0.07751753271893502, "z": null, "yaw": 3.166659936643969, "pitch": null, "roll": null}, "v": 2.4001700222048, "accelerator_pedal_position": 0.2641970094402424, "brake_pedal_position": 0.0, "acceleration": 0.02361464653636891, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.02084154865385018, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.1890292} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2605887457064749, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.2350991826489276, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.400070214058401, "gear": 1, "accelerator_pedal_position": 0.2605887457064749, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.1890292} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502699.1990292, "x": 15.717282650855442, "y": 5.070785754447511, "z": null, "yaw": 3.1676151066238956, "pitch": null, "roll": null}, "v": 2.4000809418547857, "accelerator_pedal_position": 0.2605887457064749, "brake_pedal_position": 0.0, "acceleration": 0.0010717282981831389, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020840775136794408, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.2090292} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25644545140267083, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.28966290750653356, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.4000916591377677, "gear": 1, "accelerator_pedal_position": 0.2605887457064749, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.2090292} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.60994219779968, "x": 11.717282650855442, "y": 0.07078575444751056, "z": null, "yaw": 3.1676151066238956, "pitch": null, "roll": null}, "v": 2.4000809418547857, "accelerator_pedal_position": 0.2605887457064749, "brake_pedal_position": 0.0, "acceleration": 0.0010717282981831389, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020840775136794408, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.2290292} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2577397952163545, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.28966290750653356, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3995954041920315, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.2290292} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.60994219779968, "x": 11.717282650855442, "y": 0.07078575444751056, "z": null, "yaw": 3.1676151066238956, "pitch": null, "roll": null}, "v": 2.4000809418547857, "accelerator_pedal_position": 0.2605887457064749, "brake_pedal_position": 0.0, "acceleration": 0.0010717282981831389, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020840775136794408, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.2490292} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2577397952163545, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.28966290750653356, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.399261835081818, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.2490292} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.60994219779968, "x": 11.717282650855442, "y": 0.07078575444751056, "z": null, "yaw": 3.1676151066238956, "pitch": null, "roll": null}, "v": 2.4000809418547857, "accelerator_pedal_position": 0.2605887457064749, "brake_pedal_position": 0.0, "acceleration": 0.0010717282981831389, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020840775136794408, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.2690291} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2577397952163545, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.28966290750653356, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.398928919359427, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.2690291} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.60994219779968, "x": 11.717282650855442, "y": 0.07078575444751056, "z": null, "yaw": 3.1676151066238956, "pitch": null, "roll": null}, "v": 2.4000809418547857, "accelerator_pedal_position": 0.2605887457064749, "brake_pedal_position": 0.0, "acceleration": 0.0010717282981831389, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020840775136794408, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.2890291} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2577397952163545, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.28966290750653356, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3984307679822034, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.2890291} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502699.309029, "x": 15.45345385982394, "y": 5.063804123667583, "z": null, "yaw": 3.168570276603822, "pitch": null, "roll": null}, "v": 2.398265042784354, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3774300042936321, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020825007025170334, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.309029} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2522610653978607, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.34632023621993374, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.397757059328784, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.309029} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.71994209289551, "x": 11.45345385982394, "y": 0.06380412366758303, "z": null, "yaw": 3.168570276603822, "pitch": null, "roll": null}, "v": 2.398265042784354, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3774300042936321, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020825007025170334, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.329029} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2539642731791674, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.34632023621993374, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3964488892564324, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.329029} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.71994209289551, "x": 11.45345385982394, "y": 0.06380412366758303, "z": null, "yaw": 3.168570276603822, "pitch": null, "roll": null}, "v": 2.398265042784354, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3774300042936321, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020825007025170334, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.349029} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2539642731791674, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.34632023621993374, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3964488892564324, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.349029} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.71994209289551, "x": 11.45345385982394, "y": 0.06380412366758303, "z": null, "yaw": 3.168570276603822, "pitch": null, "roll": null}, "v": 2.398265042784354, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3774300042936321, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020825007025170334, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.379029} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2539642731791674, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.34632023621993374, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.394852219955418, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.379029} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.71994209289551, "x": 11.45345385982394, "y": 0.06380412366758303, "z": null, "yaw": 3.168570276603822, "pitch": null, "roll": null}, "v": 2.398265042784354, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3774300042936321, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020825007025170334, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.399029} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2539642731791674, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.34632023621993374, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3944540292035956, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.399029} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502699.419029, "x": 15.189984068248583, "y": 5.056580174758179, "z": null, "yaw": 3.1695254465837484, "pitch": null, "roll": null}, "v": 2.3936588166900625, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37697896614168386, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020785009489842972, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.419029} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24763475839331534, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.40145684793248915, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3936588166900625, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4808976397190674, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.419029} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.82994198799133, "x": 11.189984068248583, "y": 0.05658017475817889, "z": null, "yaw": 3.1695254465837484, "pitch": null, "roll": null}, "v": 2.3936588166900625, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37697896614168386, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020785009489842972, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.439029} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24959018113837178, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.40145684793248915, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3920743578632595, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4409827205877354, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.439029} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.82994198799133, "x": 11.189984068248583, "y": 0.05658017475817889, "z": null, "yaw": 3.1695254465837484, "pitch": null, "roll": null}, "v": 2.3936588166900625, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37697896614168386, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020785009489842972, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.459029} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24959018113837178, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.40145684793248915, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3907373065718036, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4409827205877354, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.459029} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.82994198799133, "x": 11.189984068248583, "y": 0.05658017475817889, "z": null, "yaw": 3.1695254465837484, "pitch": null, "roll": null}, "v": 2.3936588166900625, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37697896614168386, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020785009489842972, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.479029} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24959018113837178, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.40145684793248915, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.38940286984643, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4409827205877354, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.479029} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.82994198799133, "x": 11.189984068248583, "y": 0.05658017475817889, "z": null, "yaw": 3.1695254465837484, "pitch": null, "roll": null}, "v": 2.3936588166900625, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37697896614168386, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020785009489842972, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.499029} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24959018113837178, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.40145684793248915, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3880710418624878, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4409827205877354, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.499029} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.82994198799133, "x": 11.189984068248583, "y": 0.05658017475817889, "z": null, "yaw": 3.1695254465837484, "pitch": null, "roll": null}, "v": 2.3936588166900625, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37697896614168386, "steering_wheel_angle": 0.4808976397190674, "front_wheel_angle": 0.022225749997230995, "heading_rate": 0.020785009489842972, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.519029} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24959018113837178, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.40145684793248915, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.386741816810888, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4409827205877354, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.519029} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502699.529029, "x": 14.927177923122116, "y": 5.049131025558601, "z": null, "yaw": 3.1704080990216457, "pitch": null, "roll": null}, "v": 2.3860781785736194, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.376237599671333, "steering_wheel_angle": 0.4409827205877354, "front_wheel_angle": 0.020370143417154388, "heading_rate": 0.01898885880787921, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.539029} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24529708233643754, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4526322184059812, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.385415188898054, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.4409827205877354, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.539029} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.93994188308716, "x": 10.927177923122116, "y": 0.049131025558600605, "z": null, "yaw": 3.1704080990216457, "pitch": null, "roll": null}, "v": 2.3860781785736194, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.376237599671333, "steering_wheel_angle": 0.4409827205877354, "front_wheel_angle": 0.020370143417154388, "heading_rate": 0.01898885880787921, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.5590289} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24660160824383828, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4526322184059812, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.383554777122512, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.400970225024412, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.5590289} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.93994188308716, "x": 10.927177923122116, "y": 0.049131025558600605, "z": null, "yaw": 3.1704080990216457, "pitch": null, "roll": null}, "v": 2.3860781785736194, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.376237599671333, "steering_wheel_angle": 0.4409827205877354, "front_wheel_angle": 0.020370143417154388, "heading_rate": 0.01898885880787921, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.5790288} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24660160824383828, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4526322184059812, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3818609842061322, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.400970225024412, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.5790288} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.93994188308716, "x": 10.927177923122116, "y": 0.049131025558600605, "z": null, "yaw": 3.1704080990216457, "pitch": null, "roll": null}, "v": 2.3860781785736194, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.376237599671333, "steering_wheel_angle": 0.4409827205877354, "front_wheel_angle": 0.020370143417154388, "heading_rate": 0.01898885880787921, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.5990288} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24660160824383828, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4526322184059812, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3801704975064304, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.400970225024412, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.5990288} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 60.93994188308716, "x": 10.927177923122116, "y": 0.049131025558600605, "z": null, "yaw": 3.1704080990216457, "pitch": null, "roll": null}, "v": 2.3860781785736194, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.376237599671333, "steering_wheel_angle": 0.4409827205877354, "front_wheel_angle": 0.020370143417154388, "heading_rate": 0.01898885880787921, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.6190288} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24660160824383828, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.4526322184059812, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3784833094272613, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.400970225024412, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.6190288} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502699.6390288, "x": 14.665282162575256, "y": 5.041484292270824, "z": null, "yaw": 3.1712181493928826, "pitch": null, "roll": null}, "v": 2.376799412393991, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37533172508726376, "steering_wheel_angle": 0.400970225024412, "front_wheel_angle": 0.01851199309503013, "heading_rate": 0.017189187928119975, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.6390288} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24636912609496012, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5160590123106856, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.375089752754458, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.32067979644808964, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.6390288} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.04994177818298, "x": 10.665282162575256, "y": 0.041484292270824064, "z": null, "yaw": 3.1712181493928826, "pitch": null, "roll": null}, "v": 2.376799412393991, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37533172508726376, "steering_wheel_angle": 0.400970225024412, "front_wheel_angle": 0.01851199309503013, "heading_rate": 0.017189187928119975, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.6590288} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24639648305521772, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5160590123106856, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.375089752754458, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.32067979644808964, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.6590288} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.04994177818298, "x": 10.665282162575256, "y": 0.041484292270824064, "z": null, "yaw": 3.1712181493928826, "pitch": null, "roll": null}, "v": 2.376799412393991, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37533172508726376, "steering_wheel_angle": 0.400970225024412, "front_wheel_angle": 0.01851199309503013, "heading_rate": 0.017189187928119975, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.6890287} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24639648305521772, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5160590123106856, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3716872527569466, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.32067979644808964, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.6890287} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24639648305521772, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5160590123106856, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3716872527569466, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.32067979644808964, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.6990287} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.04994177818298, "x": 10.665282162575256, "y": 0.041484292270824064, "z": null, "yaw": 3.1712181493928826, "pitch": null, "roll": null}, "v": 2.376799412393991, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37533172508726376, "steering_wheel_angle": 0.400970225024412, "front_wheel_angle": 0.01851199309503013, "heading_rate": 0.017189187928119975, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.7290287} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24639648305521772, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5160590123106856, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3674527429361856, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.32067979644808964, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.7290287} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502699.7490287, "x": 14.404419540983893, "y": 5.033673471421998, "z": null, "yaw": 3.17187549411445, "pitch": null, "roll": null}, "v": 2.3674527429361856, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37442096204716996, "steering_wheel_angle": 0.32067979644808964, "front_wheel_angle": 0.014789357887998908, "heading_rate": 0.013677991746097417, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.7490287} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24325978468522066, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5646394606134201, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3674527429361856, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.32067979644808964, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.7490287} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.15994167327881, "x": 10.404419540983893, "y": 0.033673471421997725, "z": null, "yaw": 3.17187549411445, "pitch": null, "roll": null}, "v": 2.3674527429361856, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37442096204716996, "steering_wheel_angle": 0.32067979644808964, "front_wheel_angle": 0.014789357887998908, "heading_rate": 0.013677991746097417, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.7790287} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24419446538666448, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5646394606134201, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.364334360848566, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.28041735735825385, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.7790287} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.15994167327881, "x": 10.404419540983893, "y": 0.033673471421997725, "z": null, "yaw": 3.17187549411445, "pitch": null, "roll": null}, "v": 2.3674527429361856, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37442096204716996, "steering_wheel_angle": 0.32067979644808964, "front_wheel_angle": 0.014789357887998908, "heading_rate": 0.013677991746097417, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.7990286} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24419446538666448, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5646394606134201, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.362377271628119, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.28041735735825385, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.7990286} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.15994167327881, "x": 10.404419540983893, "y": 0.033673471421997725, "z": null, "yaw": 3.17187549411445, "pitch": null, "roll": null}, "v": 2.3674527429361856, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37442096204716996, "steering_wheel_angle": 0.32067979644808964, "front_wheel_angle": 0.014789357887998908, "heading_rate": 0.013677991746097417, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.8190286} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24419446538666448, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5646394606134201, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.360423987382127, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.28041735735825385, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.8190286} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.15994167327881, "x": 10.404419540983893, "y": 0.033673471421997725, "z": null, "yaw": 3.17187549411445, "pitch": null, "roll": null}, "v": 2.3674527429361856, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37442096204716996, "steering_wheel_angle": 0.32067979644808964, "front_wheel_angle": 0.014789357887998908, "heading_rate": 0.013677991746097417, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.8390286} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24419446538666448, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5646394606134201, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3584744991875692, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.28041735735825385, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.8390286} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502699.8590286, "x": 14.14467520191236, "y": 5.025737966501749, "z": null, "yaw": 3.172438203758676, "pitch": null, "roll": null}, "v": 2.3565287981476595, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37335871967237555, "steering_wheel_angle": 0.28041735735825385, "front_wheel_angle": 0.012925603386974597, "heading_rate": 0.011898926966146143, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.8590286} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23445020073300854, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5789415715562822, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3565287981476595, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.28041735735825385, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.8590286} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.269941568374634, "x": 10.14467520191236, "y": 0.0257379665017492, "z": null, "yaw": 3.172438203758676, "pitch": null, "roll": null}, "v": 2.3565287981476595, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37335871967237555, "steering_wheel_angle": 0.28041735735825385, "front_wheel_angle": 0.012925603386974597, "heading_rate": 0.011898926966146143, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.8790286} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23744217328022638, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5789415715562822, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3533694336959043, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.28041735735825385, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.8790286} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.269941568374634, "x": 10.14467520191236, "y": 0.0257379665017492, "z": null, "yaw": 3.172438203758676, "pitch": null, "roll": null}, "v": 2.3565287981476595, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37335871967237555, "steering_wheel_angle": 0.28041735735825385, "front_wheel_angle": 0.012925603386974597, "heading_rate": 0.011898926966146143, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.8990285} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23744217328022638, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5789415715562822, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3505900157997366, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.28041735735825385, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.8990285} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.269941568374634, "x": 10.14467520191236, "y": 0.0257379665017492, "z": null, "yaw": 3.172438203758676, "pitch": null, "roll": null}, "v": 2.3565287981476595, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37335871967237555, "steering_wheel_angle": 0.28041735735825385, "front_wheel_angle": 0.012925603386974597, "heading_rate": 0.011898926966146143, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.9190285} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23744217328022638, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5789415715562822, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.347815988786598, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.28041735735825385, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.9190285} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23744217328022638, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5789415715562822, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.34504733912388, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.28041735735825385, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.9290285} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.269941568374634, "x": 10.14467520191236, "y": 0.0257379665017492, "z": null, "yaw": 3.172438203758676, "pitch": null, "roll": null}, "v": 2.3565287981476595, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37335871967237555, "steering_wheel_angle": 0.28041735735825385, "front_wheel_angle": 0.012925603386974597, "heading_rate": 0.011898926966146143, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.9590285} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23744217328022638, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5789415715562822, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3422840533231, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.28041735735825385, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.9590285} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502699.9690285, "x": 13.886381535540163, "y": 5.017703033614648, "z": null, "yaw": 3.1729936317115612, "pitch": null, "roll": null}, "v": 2.3409044176678075, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3718435558099569, "steering_wheel_angle": 0.28041735735825385, "front_wheel_angle": 0.012925603386974597, "heading_rate": 0.011820034078281937, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.9790285} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23996738322761485, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6407485235875497, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.339526117939722, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.28041735735825385, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.9790285} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.37994146347046, "x": 9.886381535540163, "y": 0.01770303361464798, "z": null, "yaw": 3.1729936317115612, "pitch": null, "roll": null}, "v": 2.3409044176678075, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3718435558099569, "steering_wheel_angle": 0.28041735735825385, "front_wheel_angle": 0.012925603386974597, "heading_rate": 0.011820034078281937, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502699.9990284} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.239102496358871, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6407485235875497, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3370890180971315, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1995968059476741, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502699.9990284} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.37994146347046, "x": 9.886381535540163, "y": 0.01770303361464798, "z": null, "yaw": 3.1729936317115612, "pitch": null, "roll": null}, "v": 2.3409044176678075, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3718435558099569, "steering_wheel_angle": 0.28041735735825385, "front_wheel_angle": 0.012925603386974597, "heading_rate": 0.011820034078281937, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.0190284} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.239102496358871, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6407485235875497, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3345485733770226, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1995968059476741, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.0190284} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.37994146347046, "x": 9.886381535540163, "y": 0.01770303361464798, "z": null, "yaw": 3.1729936317115612, "pitch": null, "roll": null}, "v": 2.3409044176678075, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3718435558099569, "steering_wheel_angle": 0.28041735735825385, "front_wheel_angle": 0.012925603386974597, "heading_rate": 0.011820034078281937, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.0390284} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.239102496358871, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6407485235875497, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3320130396882477, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1995968059476741, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.0390284} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.37994146347046, "x": 9.886381535540163, "y": 0.01770303361464798, "z": null, "yaw": 3.1729936317115612, "pitch": null, "roll": null}, "v": 2.3409044176678075, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3718435558099569, "steering_wheel_angle": 0.28041735735825385, "front_wheel_angle": 0.012925603386974597, "heading_rate": 0.011820034078281937, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.0590284} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.239102496358871, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6407485235875497, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3294824049667726, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1995968059476741, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.0590284} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502700.0790284, "x": 13.629710479534776, "y": 5.009586756207608, "z": null, "yaw": 3.1734250244478277, "pitch": null, "roll": null}, "v": 2.3269566571867726, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37049510570359706, "steering_wheel_angle": 0.1995968059476741, "front_wheel_angle": 0.009190420167051058, "heading_rate": 0.008354027936196353, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.0790284} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24141343557002135, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7090311929349393, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3269566571867726, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.1995968059476741, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.0790284} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.489941358566284, "x": 9.629710479534776, "y": 0.009586756207608182, "z": null, "yaw": 3.1734250244478277, "pitch": null, "roll": null}, "v": 2.3269566571867726, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37049510570359706, "steering_wheel_angle": 0.1995968059476741, "front_wheel_angle": 0.009190420167051058, "heading_rate": 0.008354027936196353, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.0990283} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24062384404352233, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7090311929349393, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3247245123611733, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.11845261662774584, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.0990283} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.489941358566284, "x": 9.629710479534776, "y": 0.009586756207608182, "z": null, "yaw": 3.1734250244478277, "pitch": null, "roll": null}, "v": 2.3269566571867726, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37049510570359706, "steering_wheel_angle": 0.1995968059476741, "front_wheel_angle": 0.009190420167051058, "heading_rate": 0.008354027936196353, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.1190283} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24062384404352233, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7090311929349393, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3223980224161958, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.11845261662774584, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.1190283} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.489941358566284, "x": 9.629710479534776, "y": 0.009586756207608182, "z": null, "yaw": 3.1734250244478277, "pitch": null, "roll": null}, "v": 2.3269566571867726, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37049510570359706, "steering_wheel_angle": 0.1995968059476741, "front_wheel_angle": 0.009190420167051058, "heading_rate": 0.008354027936196353, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.1390283} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24062384404352233, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7090311929349393, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3200760185522666, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.11845261662774584, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.1390283} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.489941358566284, "x": 9.629710479534776, "y": 0.009586756207608182, "z": null, "yaw": 3.1734250244478277, "pitch": null, "roll": null}, "v": 2.3269566571867726, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37049510570359706, "steering_wheel_angle": 0.1995968059476741, "front_wheel_angle": 0.009190420167051058, "heading_rate": 0.008354027936196353, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.1590283} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24062384404352233, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7090311929349393, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3177584899634063, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.11845261662774584, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.1590283} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.489941358566284, "x": 9.629710479534776, "y": 0.009586756207608182, "z": null, "yaw": 3.1734250244478277, "pitch": null, "roll": null}, "v": 2.3269566571867726, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.37049510570359706, "steering_wheel_angle": 0.1995968059476741, "front_wheel_angle": 0.009190420167051058, "heading_rate": 0.008354027936196353, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.1790283} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24062384404352233, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7090311929349393, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.315445425876927, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.11845261662774584, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.1790283} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502700.1890283, "x": 13.374505712917289, "y": 5.001428159460674, "z": null, "yaw": 3.173681061413053, "pitch": null, "roll": null}, "v": 2.314290564664687, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36927393641019435, "steering_wheel_angle": 0.11845261662774584, "front_wheel_angle": 0.005448311387945088, "heading_rate": 0.004925429844522046, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.1990283} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2430886218452244, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7814399947919608, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3131368155533054, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.11845261662774584, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.1990283} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.59994125366211, "x": 9.374505712917289, "y": 0.0014281594606737613, "z": null, "yaw": 3.173681061413053, "pitch": null, "roll": null}, "v": 2.314290564664687, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36927393641019435, "steering_wheel_angle": 0.11845261662774584, "front_wheel_angle": 0.005448311387945088, "heading_rate": 0.004925429844522046, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.2190282} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24225731977247825, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7814399947919608, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3111405972529973, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.07773503784527401, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.2190282} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.59994125366211, "x": 9.374505712917289, "y": 0.0014281594606737613, "z": null, "yaw": 3.173681061413053, "pitch": null, "roll": null}, "v": 2.314290564664687, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36927393641019435, "steering_wheel_angle": 0.11845261662774584, "front_wheel_angle": 0.005448311387945088, "heading_rate": 0.004925429844522046, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.2390282} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24225731977247825, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7814399947919608, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.3090443563616527, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.07773503784527401, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.2390282} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.59994125366211, "x": 9.374505712917289, "y": 0.0014281594606737613, "z": null, "yaw": 3.173681061413053, "pitch": null, "roll": null}, "v": 2.314290564664687, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36927393641019435, "steering_wheel_angle": 0.11845261662774584, "front_wheel_angle": 0.005448311387945088, "heading_rate": 0.004925429844522046, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.2590282} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24225731977247825, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7814399947919608, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.306952146336508, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.07773503784527401, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.2590282} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.59994125366211, "x": 9.374505712917289, "y": 0.0014281594606737613, "z": null, "yaw": 3.173681061413053, "pitch": null, "roll": null}, "v": 2.314290564664687, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36927393641019435, "steering_wheel_angle": 0.11845261662774584, "front_wheel_angle": 0.005448311387945088, "heading_rate": 0.004925429844522046, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.2790282} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24225731977247825, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7814399947919608, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.304863957676505, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.07773503784527401, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.2790282} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502700.2990282, "x": 13.120643285517101, "y": 4.993258386833993, "z": null, "yaw": 3.1738492604057638, "pitch": null, "roll": null}, "v": 2.30277978090894, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36816693623907726, "steering_wheel_angle": 0.07773503784527401, "front_wheel_angle": 0.003573563847827696, "heading_rate": 0.0032145178142160566, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.2990282} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23631764721650755, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8833760444382817, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.30277978090894, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": 0.07773503784527401, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.2990282} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.709941148757935, "x": 9.120643285517101, "y": -0.0067416131660067435, "z": null, "yaw": 3.1738492604057638, "pitch": null, "roll": null}, "v": 2.30277978090894, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36816693623907726, "steering_wheel_angle": 0.07773503784527401, "front_wheel_angle": 0.003573563847827696, "heading_rate": 0.0032145178142160566, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.3190281} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23811844606238827, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8833760444382817, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.299957504015562, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.004058733064131218, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.3190281} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.709941148757935, "x": 9.120643285517101, "y": -0.0067416131660067435, "z": null, "yaw": 3.1738492604057638, "pitch": null, "roll": null}, "v": 2.30277978090894, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36816693623907726, "steering_wheel_angle": 0.07773503784527401, "front_wheel_angle": 0.003573563847827696, "heading_rate": 0.0032145178142160566, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.3390281} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23811844606238827, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8833760444382817, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.296071567054703, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.04496907956616924, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.3390281} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.709941148757935, "x": 9.120643285517101, "y": -0.0067416131660067435, "z": null, "yaw": 3.1738492604057638, "pitch": null, "roll": null}, "v": 2.30277978090894, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36816693623907726, "steering_wheel_angle": 0.07773503784527401, "front_wheel_angle": 0.003573563847827696, "heading_rate": 0.0032145178142160566, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.359028} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23811844606238827, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8833760444382817, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2947787396859716, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.04496907956616924, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.359028} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.709941148757935, "x": 9.120643285517101, "y": -0.0067416131660067435, "z": null, "yaw": 3.1738492604057638, "pitch": null, "roll": null}, "v": 2.30277978090894, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36816693623907726, "steering_wheel_angle": 0.07773503784527401, "front_wheel_angle": 0.003573563847827696, "heading_rate": 0.0032145178142160566, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.379028} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23811844606238827, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8833760444382817, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2909076910784583, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.04496907956616924, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.379028} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.709941148757935, "x": 9.120643285517101, "y": -0.0067416131660067435, "z": null, "yaw": 3.1738492604057638, "pitch": null, "roll": null}, "v": 2.30277978090894, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36816693623907726, "steering_wheel_angle": 0.07773503784527401, "front_wheel_angle": 0.003573563847827696, "heading_rate": 0.0032145178142160566, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.399028} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23811844606238827, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8833760444382817, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.289619814306914, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.04496907956616924, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.399028} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502700.409028, "x": 12.868202713299336, "y": 4.985113429254692, "z": null, "yaw": 3.1738045323924147, "pitch": null, "roll": null}, "v": 2.288333171389253, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3667813456022666, "steering_wheel_angle": -0.04496907956616924, "front_wheel_angle": -0.002066388045825318, "heading_rate": -0.0018471058752045732, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.419028} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.21629728667252437, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.009465276918481, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2870477608121296, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.04496907956616924, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.419028} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.81994104385376, "x": 8.868202713299336, "y": -0.014886570745307637, "z": null, "yaw": 3.1738045323924147, "pitch": null, "roll": null}, "v": 2.288333171389253, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3667813456022666, "steering_wheel_angle": -0.04496907956616924, "front_wheel_angle": -0.002066388045825318, "heading_rate": -0.0018471058752045732, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.439028} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22304712387555445, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.009465276918481, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.281754290914754, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.12694185942218053, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.439028} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.81994104385376, "x": 8.868202713299336, "y": -0.014886570745307637, "z": null, "yaw": 3.1738045323924147, "pitch": null, "roll": null}, "v": 2.288333171389253, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3667813456022666, "steering_wheel_angle": -0.04496907956616924, "front_wheel_angle": -0.002066388045825318, "heading_rate": -0.0018471058752045732, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.459028} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22304712387555445, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.009465276918481, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2773142702104194, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.16786193660144705, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.459028} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.81994104385376, "x": 8.868202713299336, "y": -0.014886570745307637, "z": null, "yaw": 3.1738045323924147, "pitch": null, "roll": null}, "v": 2.288333171389253, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3667813456022666, "steering_wheel_angle": -0.04496907956616924, "front_wheel_angle": -0.002066388045825318, "heading_rate": -0.0018471058752045732, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.479028} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22304712387555445, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.009465276918481, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2728827319728926, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.16786193660144705, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.479028} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.81994104385376, "x": 8.868202713299336, "y": -0.014886570745307637, "z": null, "yaw": 3.1738045323924147, "pitch": null, "roll": null}, "v": 2.288333171389253, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3667813456022666, "steering_wheel_angle": -0.04496907956616924, "front_wheel_angle": -0.002066388045825318, "heading_rate": -0.0018471058752045732, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.499028} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22304712387555445, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.009465276918481, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2684596521451224, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.16786193660144705, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.499028} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502700.519028, "x": 12.617814452929174, "y": 4.977069489772291, "z": null, "yaw": 3.173538876254534, "pitch": null, "roll": null}, "v": 2.2640450067609437, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3644612482644388, "steering_wheel_angle": -0.16786193660144705, "front_wheel_angle": -0.007725954779661228, "heading_rate": -0.006832913040059342, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.519028} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22948974986651796, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0875031506360076, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2640450067609437, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.16786193660144705, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.519028} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.929940938949585, "x": 8.617814452929174, "y": -0.022930510227708645, "z": null, "yaw": 3.173538876254534, "pitch": null, "roll": null}, "v": 2.2640450067609437, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3644612482644388, "steering_wheel_angle": -0.16786193660144705, "front_wheel_angle": -0.007725954779661228, "heading_rate": -0.006832913040059342, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.539028} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22736042298135498, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0875031506360076, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.260443716692813, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.24974602436744323, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.539028} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.929940938949585, "x": 8.617814452929174, "y": -0.022930510227708645, "z": null, "yaw": 3.173538876254534, "pitch": null, "roll": null}, "v": 2.2640450067609437, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3644612482644388, "steering_wheel_angle": -0.16786193660144705, "front_wheel_angle": -0.007725954779661228, "heading_rate": -0.006832913040059342, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.559028} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22736042298135498, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0875031506360076, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.256583242948477, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.24974602436744323, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.559028} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.929940938949585, "x": 8.617814452929174, "y": -0.022930510227708645, "z": null, "yaw": 3.173538876254534, "pitch": null, "roll": null}, "v": 2.2640450067609437, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3644612482644388, "steering_wheel_angle": -0.16786193660144705, "front_wheel_angle": -0.007725954779661228, "heading_rate": -0.006832913040059342, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.579028} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22736042298135498, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0875031506360076, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.252730112265904, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.24974602436744323, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.579028} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.929940938949585, "x": 8.617814452929174, "y": -0.022930510227708645, "z": null, "yaw": 3.173538876254534, "pitch": null, "roll": null}, "v": 2.2640450067609437, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3644612482644388, "steering_wheel_angle": -0.16786193660144705, "front_wheel_angle": -0.007725954779661228, "heading_rate": -0.006832913040059342, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.5990279} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22736042298135498, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0875031506360076, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.248884304741926, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.24974602436744323, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.5990279} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 61.929940938949585, "x": 8.617814452929174, "y": -0.022930510227708645, "z": null, "yaw": 3.173538876254534, "pitch": null, "roll": null}, "v": 2.2640450067609437, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3644612482644388, "steering_wheel_angle": -0.16786193660144705, "front_wheel_angle": -0.007725954779661228, "heading_rate": -0.006832913040059342, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.6190279} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22736042298135498, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.0875031506360076, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2450458005450526, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.24974602436744323, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.6190279} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502700.6290278, "x": 12.369930236266711, "y": 4.96919867764226, "z": null, "yaw": 3.1730665638141184, "pitch": null, "roll": null}, "v": 2.2431292810164605, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3624727537643573, "steering_wheel_angle": -0.24974602436744323, "front_wheel_angle": -0.01150716115829012, "heading_rate": -0.010083277146356697, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.6390278} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2333303852991189, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.169072121457426, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2412145799151517, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.24974602436744323, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.6390278} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.03994083404541, "x": 8.369930236266711, "y": -0.030801322357739913, "z": null, "yaw": 3.1730665638141184, "pitch": null, "roll": null}, "v": 2.2431292810164605, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3624727537643573, "steering_wheel_angle": -0.24974602436744323, "front_wheel_angle": -0.01150716115829012, "heading_rate": -0.010083277146356697, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.6590278} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23136534606143347, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.169072121457426, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2381365147707664, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.33163788618365847, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.6590278} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.03994083404541, "x": 8.369930236266711, "y": -0.030801322357739913, "z": null, "yaw": 3.1730665638141184, "pitch": null, "roll": null}, "v": 2.2431292810164605, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3624727537643573, "steering_wheel_angle": -0.24974602436744323, "front_wheel_angle": -0.01150716115829012, "heading_rate": -0.010083277146356697, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.6790278} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23136534606143347, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.169072121457426, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.234818767965261, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.33163788618365847, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.6790278} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.03994083404541, "x": 8.369930236266711, "y": -0.030801322357739913, "z": null, "yaw": 3.1730665638141184, "pitch": null, "roll": null}, "v": 2.2431292810164605, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3624727537643573, "steering_wheel_angle": -0.24974602436744323, "front_wheel_angle": -0.01150716115829012, "heading_rate": -0.010083277146356697, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.6990278} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23136534606143347, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.169072121457426, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2315073028567576, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.33163788618365847, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.6990278} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.03994083404541, "x": 8.369930236266711, "y": -0.030801322357739913, "z": null, "yaw": 3.1730665638141184, "pitch": null, "roll": null}, "v": 2.2431292810164605, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3624727537643573, "steering_wheel_angle": -0.24974602436744323, "front_wheel_angle": -0.01150716115829012, "heading_rate": -0.010083277146356697, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.7190278} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23136534606143347, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.169072121457426, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.22820210316748, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.33163788618365847, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.7190278} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502700.7390277, "x": 12.124222647036099, "y": 4.961528514318324, "z": null, "yaw": 3.1724462380719687, "pitch": null, "roll": null}, "v": 2.2249031526753407, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36074709802161375, "steering_wheel_angle": -0.33163788618365847, "front_wheel_angle": -0.015296955611960138, "heading_rate": -0.013295663926268008, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.7390277} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22412769742350022, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.145798734520616, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2228036627840932, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.33163788618365847, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.7390277} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.149940729141235, "x": 8.124222647036099, "y": -0.03847148568167569, "z": null, "yaw": 3.1724462380719687, "pitch": null, "roll": null}, "v": 2.2249031526753407, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36074709802161375, "steering_wheel_angle": -0.33163788618365847, "front_wheel_angle": -0.015296955611960138, "heading_rate": -0.013295663926268008, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.7590277} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22630318126207555, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.145798734520616, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2207061564293413, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.33163788618365847, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.7590277} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.149940729141235, "x": 8.124222647036099, "y": -0.03847148568167569, "z": null, "yaw": 3.1724462380719687, "pitch": null, "roll": null}, "v": 2.2249031526753407, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36074709802161375, "steering_wheel_angle": -0.33163788618365847, "front_wheel_angle": -0.015296955611960138, "heading_rate": -0.013295663926268008, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.7790277} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22630318126207555, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.145798734520616, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2167888904793887, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.33163788618365847, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.7790277} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.149940729141235, "x": 8.124222647036099, "y": -0.03847148568167569, "z": null, "yaw": 3.1724462380719687, "pitch": null, "roll": null}, "v": 2.2249031526753407, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36074709802161375, "steering_wheel_angle": -0.33163788618365847, "front_wheel_angle": -0.015296955611960138, "heading_rate": -0.013295663926268008, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.7990277} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22630318126207555, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.145798734520616, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.212879013343746, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.33163788618365847, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.7990277} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.149940729141235, "x": 8.124222647036099, "y": -0.03847148568167569, "z": null, "yaw": 3.1724462380719687, "pitch": null, "roll": null}, "v": 2.2249031526753407, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36074709802161375, "steering_wheel_angle": -0.33163788618365847, "front_wheel_angle": -0.015296955611960138, "heading_rate": -0.013295663926268008, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.8190277} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22630318126207555, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.145798734520616, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.208976504973528, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.33163788618365847, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.8190277} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.149940729141235, "x": 8.124222647036099, "y": -0.03847148568167569, "z": null, "yaw": 3.1724462380719687, "pitch": null, "roll": null}, "v": 2.2249031526753407, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.36074709802161375, "steering_wheel_angle": -0.33163788618365847, "front_wheel_angle": -0.015296955611960138, "heading_rate": -0.013295663926268008, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.8390276} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22630318126207555, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.145798734520616, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2011935146952455, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.33163788618365847, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.8390276} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502700.8490276, "x": 11.88069964354294, "y": 4.954085273339442, "z": null, "yaw": 3.1717888957377065, "pitch": null, "roll": null}, "v": 2.2031365151744025, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3586949308036682, "steering_wheel_angle": -0.33163788618365847, "front_wheel_angle": -0.015296955611960138, "heading_rate": -0.013165589996232274, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.8590276} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23240140018056316, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.221501052107196, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.2011935146952455, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.33163788618365847, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.8590276} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.25994062423706, "x": 7.88069964354294, "y": -0.04591472666055818, "z": null, "yaw": 3.1717888957377065, "pitch": null, "roll": null}, "v": 2.2031365151744025, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3586949308036682, "steering_wheel_angle": -0.33163788618365847, "front_wheel_angle": -0.015296955611960138, "heading_rate": -0.013165589996232274, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.8790276} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2303930970908924, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.221501052107196, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.194711248480954, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.37257675831235476, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.8790276} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.25994062423706, "x": 7.88069964354294, "y": -0.04591472666055818, "z": null, "yaw": 3.1717888957377065, "pitch": null, "roll": null}, "v": 2.2031365151744025, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3586949308036682, "steering_wheel_angle": -0.33163788618365847, "front_wheel_angle": -0.015296955611960138, "heading_rate": -0.013165589996232274, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.9090276} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2303930970908924, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.221501052107196, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1913538995125155, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.37257675831235476, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.9090276} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.25994062423706, "x": 7.88069964354294, "y": -0.04591472666055818, "z": null, "yaw": 3.1717888957377065, "pitch": null, "roll": null}, "v": 2.2031365151744025, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3586949308036682, "steering_wheel_angle": -0.33163788618365847, "front_wheel_angle": -0.015296955611960138, "heading_rate": -0.013165589996232274, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.9290276} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2303930970908924, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.221501052107196, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.189677587939649, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.37257675831235476, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.9290276} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.25994062423706, "x": 7.88069964354294, "y": -0.04591472666055818, "z": null, "yaw": 3.1717888957377065, "pitch": null, "roll": null}, "v": 2.2031365151744025, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3586949308036682, "steering_wheel_angle": -0.33163788618365847, "front_wheel_angle": -0.015296955611960138, "heading_rate": -0.013165589996232274, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.9490275} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2303930970908924, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.221501052107196, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1863296804169803, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.37257675831235476, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.9490275} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502700.9590275, "x": 11.639391987222988, "y": 4.946874378714652, "z": null, "yaw": 3.171064820715189, "pitch": null, "roll": null}, "v": 2.1846580803978055, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35696021330236455, "steering_wheel_angle": -0.37257675831235476, "front_wheel_angle": -0.017194628352752483, "heading_rate": -0.014675033688994648, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.9690275} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23574758655143574, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.302668567695428, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1829880468329628, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.37257675831235476, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.9690275} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.369940519332886, "x": 7.639391987222988, "y": -0.053125621285348146, "z": null, "yaw": 3.171064820715189, "pitch": null, "roll": null}, "v": 2.1846580803978055, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35696021330236455, "steering_wheel_angle": -0.37257675831235476, "front_wheel_angle": -0.017194628352752483, "heading_rate": -0.014675033688994648, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502700.9890275} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.233987571565995, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.302668567695428, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1789903518783187, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.454506232795364, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502700.9890275} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.369940519332886, "x": 7.639391987222988, "y": -0.053125621285348146, "z": null, "yaw": 3.171064820715189, "pitch": null, "roll": null}, "v": 2.1846580803978055, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35696021330236455, "steering_wheel_angle": -0.37257675831235476, "front_wheel_angle": -0.017194628352752483, "heading_rate": -0.014675033688994648, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.0090275} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.233987571565995, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.302668567695428, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1775502800298963, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.454506232795364, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.0090275} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.369940519332886, "x": 7.639391987222988, "y": -0.053125621285348146, "z": null, "yaw": 3.171064820715189, "pitch": null, "roll": null}, "v": 2.1846580803978055, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35696021330236455, "steering_wheel_angle": -0.37257675831235476, "front_wheel_angle": -0.017194628352752483, "heading_rate": -0.014675033688994648, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.0290275} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.233987571565995, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.302668567695428, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.173238142242263, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.454506232795364, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.0290275} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.369940519332886, "x": 7.639391987222988, "y": -0.053125621285348146, "z": null, "yaw": 3.171064820715189, "pitch": null, "roll": null}, "v": 2.1846580803978055, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35696021330236455, "steering_wheel_angle": -0.37257675831235476, "front_wheel_angle": -0.017194628352752483, "heading_rate": -0.014675033688994648, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.0490274} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.233987571565995, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.302668567695428, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1718034499917267, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.454506232795364, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.0490274} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502701.0690274, "x": 11.399969757476075, "y": 4.939906764345411, "z": null, "yaw": 3.1701995659764735, "pitch": null, "roll": null}, "v": 2.168938086004275, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35548982850941263, "steering_wheel_angle": -0.454506232795364, "front_wheel_angle": -0.020998615941638363, "heading_rate": -0.017793512983675954, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.0690274} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.22952009105251656, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2488438836485292, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.168938086004275, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.454506232795364, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.0690274} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.47994041442871, "x": 7.399969757476075, "y": -0.06009323565458935, "z": null, "yaw": 3.1701995659764735, "pitch": null, "roll": null}, "v": 2.168938086004275, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35548982850941263, "steering_wheel_angle": -0.454506232795364, "front_wheel_angle": -0.020998615941638363, "heading_rate": -0.017793512983675954, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.0890274} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23084266034047496, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2488438836485292, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1655198971998093, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.454506232795364, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.0890274} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.47994041442871, "x": 7.399969757476075, "y": -0.06009323565458935, "z": null, "yaw": 3.1701995659764735, "pitch": null, "roll": null}, "v": 2.168938086004275, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35548982850941263, "steering_wheel_angle": -0.454506232795364, "front_wheel_angle": -0.020998615941638363, "heading_rate": -0.017793512983675954, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.1090274} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23084266034047496, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2488438836485292, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1622733296958025, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.454506232795364, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.1090274} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.47994041442871, "x": 7.399969757476075, "y": -0.06009323565458935, "z": null, "yaw": 3.1701995659764735, "pitch": null, "roll": null}, "v": 2.168938086004275, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35548982850941263, "steering_wheel_angle": -0.454506232795364, "front_wheel_angle": -0.020998615941638363, "heading_rate": -0.017793512983675954, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.1290274} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23084266034047496, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2488438836485292, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.157414822570737, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.454506232795364, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.1290274} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.47994041442871, "x": 7.399969757476075, "y": -0.06009323565458935, "z": null, "yaw": 3.1701995659764735, "pitch": null, "roll": null}, "v": 2.168938086004275, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35548982850941263, "steering_wheel_angle": -0.454506232795364, "front_wheel_angle": -0.020998615941638363, "heading_rate": -0.017793512983675954, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.1490273} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23084266034047496, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2488438836485292, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1557983375590664, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.454506232795364, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.1490273} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.47994041442871, "x": 7.399969757476075, "y": -0.06009323565458935, "z": null, "yaw": 3.1701995659764735, "pitch": null, "roll": null}, "v": 2.168938086004275, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35548982850941263, "steering_wheel_angle": -0.454506232795364, "front_wheel_angle": -0.020998615941638363, "heading_rate": -0.017793512983675954, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.1690273} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23084266034047496, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2488438836485292, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1525698820126222, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.454506232795364, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.1690273} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502701.1790273, "x": 11.162389176817541, "y": 4.933205847405813, "z": null, "yaw": 3.1692971490560304, "pitch": null, "roll": null}, "v": 2.1509579076332006, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.353814094585758, "steering_wheel_angle": -0.454506232795364, "front_wheel_angle": -0.020998615941638363, "heading_rate": -0.01764600737281552, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.1890273} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23688484428240392, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3283018599302332, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1481160925710374, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.49543302361709274, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.1890273} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.589940309524536, "x": 7.162389176817541, "y": -0.06679415259418686, "z": null, "yaw": 3.1692971490560304, "pitch": null, "roll": null}, "v": 2.1509579076332006, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.353814094585758, "steering_wheel_angle": -0.454506232795364, "front_wheel_angle": -0.020998615941638363, "heading_rate": -0.01764600737281552, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.2090273} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2349128738114438, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3283018599302332, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.146885897017686, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.49543302361709274, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.2090273} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.589940309524536, "x": 7.162389176817541, "y": -0.06679415259418686, "z": null, "yaw": 3.1692971490560304, "pitch": null, "roll": null}, "v": 2.1509579076332006, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.353814094585758, "steering_wheel_angle": -0.454506232795364, "front_wheel_angle": -0.020998615941638363, "heading_rate": -0.01764600737281552, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.2290273} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2349128738114438, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3283018599302332, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1401369466378144, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.49543302361709274, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.2290273} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.589940309524536, "x": 7.162389176817541, "y": -0.06679415259418686, "z": null, "yaw": 3.1692971490560304, "pitch": null, "roll": null}, "v": 2.1509579076332006, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.353814094585758, "steering_wheel_angle": -0.454506232795364, "front_wheel_angle": -0.020998615941638363, "heading_rate": -0.01764600737281552, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.2590272} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2349128738114438, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3283018599302332, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.138790914162674, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.49543302361709274, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.2590272} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.589940309524536, "x": 7.162389176817541, "y": -0.06679415259418686, "z": null, "yaw": 3.1692971490560304, "pitch": null, "roll": null}, "v": 2.1509579076332006, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.353814094585758, "steering_wheel_angle": -0.454506232795364, "front_wheel_angle": -0.020998615941638363, "heading_rate": -0.01764600737281552, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.2790272} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2349128738114438, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3283018599302332, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1347603044995314, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.49543302361709274, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.2790272} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502701.2890272, "x": 10.92661973719601, "y": 4.926774699273058, "z": null, "yaw": 3.168327784703925, "pitch": null, "roll": null}, "v": 2.136102594613094, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3524344726777826, "steering_wheel_angle": -0.49543302361709274, "front_wheel_angle": -0.02290198050117497, "heading_rate": -0.019113099529194457, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.3090272} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23790994103254842, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3557651308706298, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.13341925880473, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.49543302361709274, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.3090272} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.69994020462036, "x": 6.92661973719601, "y": -0.07322530072694189, "z": null, "yaw": 3.168327784703925, "pitch": null, "roll": null}, "v": 2.136102594613094, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3524344726777826, "steering_wheel_angle": -0.49543302361709274, "front_wheel_angle": -0.02290198050117497, "heading_rate": -0.019113099529194457, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.3290272} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23690437577125448, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3557651308706298, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.131115354485651, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5363464105353289, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.3290272} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.69994020462036, "x": 6.92661973719601, "y": -0.07322530072694189, "z": null, "yaw": 3.168327784703925, "pitch": null, "roll": null}, "v": 2.136102594613094, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3524344726777826, "steering_wheel_angle": -0.49543302361709274, "front_wheel_angle": -0.02290198050117497, "heading_rate": -0.019113099529194457, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.3490272} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23690437577125448, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3557651308706298, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1262692925988245, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5363464105353289, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.3490272} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.69994020462036, "x": 6.92661973719601, "y": -0.07322530072694189, "z": null, "yaw": 3.168327784703925, "pitch": null, "roll": null}, "v": 2.136102594613094, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3524344726777826, "steering_wheel_angle": -0.49543302361709274, "front_wheel_angle": -0.02290198050117497, "heading_rate": -0.019113099529194457, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.3690271} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23690437577125448, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3557651308706298, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1262692925988245, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5363464105353289, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.3690271} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.69994020462036, "x": 6.92661973719601, "y": -0.07322530072694189, "z": null, "yaw": 3.168327784703925, "pitch": null, "roll": null}, "v": 2.136102594613094, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3524344726777826, "steering_wheel_angle": -0.49543302361709274, "front_wheel_angle": -0.02290198050117497, "heading_rate": -0.019113099529194457, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.389027} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23690437577125448, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3557651308706298, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1226465061209043, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5363464105353289, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.389027} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502701.399027, "x": 10.6924113970766, "y": 4.920620785175707, "z": null, "yaw": 3.167283983101646, "pitch": null, "roll": null}, "v": 2.1226465061209043, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35118860720551803, "steering_wheel_angle": -0.5363464105353289, "front_wheel_angle": -0.024806816979371784, "heading_rate": -0.020573010620095547, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.409027} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24208335947694745, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4426151603240256, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1214411435345526, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.5363464105353289, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.409027} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.80994009971619, "x": 6.692411397076601, "y": -0.07937921482429289, "z": null, "yaw": 3.167283983101646, "pitch": null, "roll": null}, "v": 2.1226465061209043, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35118860720551803, "steering_wheel_angle": -0.5363464105353289, "front_wheel_angle": -0.024806816979371784, "heading_rate": -0.020573010620095547, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.429027} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24040263269333484, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4426151603240256, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1196808336359605, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6182383453103277, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.429027} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.80994009971619, "x": 6.692411397076601, "y": -0.07937921482429289, "z": null, "yaw": 3.167283983101646, "pitch": null, "roll": null}, "v": 2.1226465061209043, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35118860720551803, "steering_wheel_angle": -0.5363464105353289, "front_wheel_angle": -0.024806816979371784, "heading_rate": -0.020573010620095547, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.449027} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24040263269333484, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4426151603240256, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.117713781560097, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6182383453103277, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.449027} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.80994009971619, "x": 6.692411397076601, "y": -0.07937921482429289, "z": null, "yaw": 3.167283983101646, "pitch": null, "roll": null}, "v": 2.1226465061209043, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35118860720551803, "steering_wheel_angle": -0.5363464105353289, "front_wheel_angle": -0.024806816979371784, "heading_rate": -0.020573010620095547, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.469027} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24040263269333484, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4426151603240256, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1157503615066156, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6182383453103277, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.469027} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.80994009971619, "x": 6.692411397076601, "y": -0.07937921482429289, "z": null, "yaw": 3.167283983101646, "pitch": null, "roll": null}, "v": 2.1226465061209043, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.35118860720551803, "steering_wheel_angle": -0.5363464105353289, "front_wheel_angle": -0.024806816979371784, "heading_rate": -0.020573010620095547, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.489027} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24040263269333484, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4426151603240256, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1137905652279483, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6182383453103277, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.489027} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502701.509027, "x": 10.459539216885268, "y": 4.914759600345582, "z": null, "yaw": 3.16609095250424, "pitch": null, "roll": null}, "v": 2.1118343845002836, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3501901639005911, "steering_wheel_angle": -0.6182383453103277, "front_wheel_angle": -0.028625844692009413, "heading_rate": -0.02362092228394411, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.509027} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23006533261553183, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3408132138135824, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1118343845002836, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6182383453103277, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.509027} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.91993999481201, "x": 6.459539216885268, "y": -0.08524039965441776, "z": null, "yaw": 3.16609095250424, "pitch": null, "roll": null}, "v": 2.1118343845002836, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3501901639005911, "steering_wheel_angle": -0.6182383453103277, "front_wheel_angle": -0.028625844692009413, "heading_rate": -0.02362092228394411, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.529027} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23324581880988818, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3408132138135824, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1085902443697533, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6182383453103277, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.529027} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.91993999481201, "x": 6.459539216885268, "y": -0.08524039965441776, "z": null, "yaw": 3.16609095250424, "pitch": null, "roll": null}, "v": 2.1118343845002836, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3501901639005911, "steering_wheel_angle": -0.6182383453103277, "front_wheel_angle": -0.028625844692009413, "heading_rate": -0.02362092228394411, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.549027} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23324581880988818, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3408132138135824, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1057494605153697, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6182383453103277, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.549027} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.91993999481201, "x": 6.459539216885268, "y": -0.08524039965441776, "z": null, "yaw": 3.16609095250424, "pitch": null, "roll": null}, "v": 2.1118343845002836, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3501901639005911, "steering_wheel_angle": -0.6182383453103277, "front_wheel_angle": -0.028625844692009413, "heading_rate": -0.02362092228394411, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.569027} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23324581880988818, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3408132138135824, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.102913908632648, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6182383453103277, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.569027} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.91993999481201, "x": 6.459539216885268, "y": -0.08524039965441776, "z": null, "yaw": 3.16609095250424, "pitch": null, "roll": null}, "v": 2.1118343845002836, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3501901639005911, "steering_wheel_angle": -0.6182383453103277, "front_wheel_angle": -0.028625844692009413, "heading_rate": -0.02362092228394411, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.589027} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23324581880988818, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3408132138135824, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0972584494213167, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6182383453103277, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.589027} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 62.91993999481201, "x": 6.459539216885268, "y": -0.08524039965441776, "z": null, "yaw": 3.16609095250424, "pitch": null, "roll": null}, "v": 2.1118343845002836, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3501901639005911, "steering_wheel_angle": -0.6182383453103277, "front_wheel_angle": -0.028625844692009413, "heading_rate": -0.02362092228394411, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.609027} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23324581880988818, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3408132138135824, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.095847834571857, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6182383453103277, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.609027} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502701.619027, "x": 10.228122458662758, "y": 4.909218467439057, "z": null, "yaw": 3.1648605996554053, "pitch": null, "roll": null}, "v": 2.095847834571857, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3487181731853883, "steering_wheel_angle": -0.6182383453103277, "front_wheel_angle": -0.028625844692009413, "heading_rate": -0.023442112308967256, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.629027} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23959158724840462, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4208338460346415, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0924166211373163, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6182383453103277, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.629027} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.02993988990784, "x": 6.228122458662758, "y": -0.09078153256094268, "z": null, "yaw": 3.1648605996554053, "pitch": null, "roll": null}, "v": 2.095847834571857, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3487181731853883, "steering_wheel_angle": -0.6182383453103277, "front_wheel_angle": -0.028625844692009413, "heading_rate": -0.023442112308967256, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.6490269} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23753493372716097, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4208338460346415, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0924166211373163, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6182383453103277, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.6490269} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.02993988990784, "x": 6.228122458662758, "y": -0.09078153256094268, "z": null, "yaw": 3.1648605996554053, "pitch": null, "roll": null}, "v": 2.095847834571857, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3487181731853883, "steering_wheel_angle": -0.6182383453103277, "front_wheel_angle": -0.028625844692009413, "heading_rate": -0.023442112308967256, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.6790268} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23753493372716097, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4208338460346415, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.087870504682112, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6182383453103277, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.6790268} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.02993988990784, "x": 6.228122458662758, "y": -0.09078153256094268, "z": null, "yaw": 3.1648605996554053, "pitch": null, "roll": null}, "v": 2.095847834571857, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3487181731853883, "steering_wheel_angle": -0.6182383453103277, "front_wheel_angle": -0.028625844692009413, "heading_rate": -0.023442112308967256, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.6990268} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23753493372716097, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4208338460346415, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0867365824632866, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6182383453103277, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.6990268} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.02993988990784, "x": 6.228122458662758, "y": -0.09078153256094268, "z": null, "yaw": 3.1648605996554053, "pitch": null, "roll": null}, "v": 2.095847834571857, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3487181731853883, "steering_wheel_angle": -0.6182383453103277, "front_wheel_angle": -0.028625844692009413, "heading_rate": -0.023442112308967256, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.7190268} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.23753493372716097, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4208338460346415, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0844718578016197, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6182383453103277, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.7190268} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502701.7290268, "x": 9.998269372888142, "y": 4.9039977681080105, "z": null, "yaw": 3.1636302468065707, "pitch": null, "roll": null}, "v": 2.08334105293807, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3475701520754746, "steering_wheel_angle": -0.6182383453103277, "front_wheel_angle": -0.028625844692009413, "heading_rate": -0.023302223632486664, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.7390268} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2429591543090333, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.5081422370560649, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0822112847752625, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.6182383453103277, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.7390268} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.13993978500366, "x": 5.998269372888142, "y": -0.09600223189198953, "z": null, "yaw": 3.1636302468065707, "pitch": null, "roll": null}, "v": 2.08334105293807, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3475701520754746, "steering_wheel_angle": -0.6182383453103277, "front_wheel_angle": -0.028625844692009413, "heading_rate": -0.023302223632486664, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.7690268} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2412066831726929, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.5081422370560649, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.079056748115772, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7001009318693607, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.7690268} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.13993978500366, "x": 5.998269372888142, "y": -0.09600223189198953, "z": null, "yaw": 3.1636302468065707, "pitch": null, "roll": null}, "v": 2.08334105293807, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3475701520754746, "steering_wheel_angle": -0.6182383453103277, "front_wheel_angle": -0.028625844692009413, "heading_rate": -0.023302223632486664, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.7890267} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2412066831726929, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.5081422370560649, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0763701345322776, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7001009318693607, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.7890267} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.13993978500366, "x": 5.998269372888142, "y": -0.09600223189198953, "z": null, "yaw": 3.1636302468065707, "pitch": null, "roll": null}, "v": 2.08334105293807, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3475701520754746, "steering_wheel_angle": -0.6182383453103277, "front_wheel_angle": -0.028625844692009413, "heading_rate": -0.023302223632486664, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.8090267} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2412066831726929, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.5081422370560649, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0763701345322776, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7001009318693607, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.8090267} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502701.8390267, "x": 9.76963830264216, "y": 4.899096233894086, "z": null, "yaw": 3.162272736161935, "pitch": null, "roll": null}, "v": 2.0736908918833667, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3466864837449687, "steering_wheel_angle": -0.7001009318693607, "front_wheel_angle": -0.03245197622124179, "heading_rate": -0.02629648479552359, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.8390267} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24611675388711673, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.6002629697488995, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0736908918833667, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7001009318693607, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.8390267} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.24993968009949, "x": 5.769638302642161, "y": -0.10090376610591356, "z": null, "yaw": 3.162272736161935, "pitch": null, "roll": null}, "v": 2.0736908918833667, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3466864837449687, "steering_wheel_angle": -0.7001009318693607, "front_wheel_angle": -0.03245197622124179, "heading_rate": -0.02629648479552359, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.8590267} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24453817233733527, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.6002629697488995, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0725222911365955, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.8590267} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.24993968009949, "x": 5.769638302642161, "y": -0.10090376610591356, "z": null, "yaw": 3.162272736161935, "pitch": null, "roll": null}, "v": 2.0736908918833667, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3466864837449687, "steering_wheel_angle": -0.7001009318693607, "front_wheel_angle": -0.03245197622124179, "heading_rate": -0.02629648479552359, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.8790267} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24453817233733527, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.6002629697488995, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0711585944502198, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.8790267} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.24993968009949, "x": 5.769638302642161, "y": -0.10090376610591356, "z": null, "yaw": 3.162272736161935, "pitch": null, "roll": null}, "v": 2.0736908918833667, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3466864837449687, "steering_wheel_angle": -0.7001009318693607, "front_wheel_angle": -0.03245197622124179, "heading_rate": -0.02629648479552359, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.8990266} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24453817233733527, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.6002629697488995, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0697973902794526, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.8990266} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.24993968009949, "x": 5.769638302642161, "y": -0.10090376610591356, "z": null, "yaw": 3.162272736161935, "pitch": null, "roll": null}, "v": 2.0736908918833667, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3466864837449687, "steering_wheel_angle": -0.7001009318693607, "front_wheel_angle": -0.03245197622124179, "heading_rate": -0.02629648479552359, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.9190266} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24453817233733527, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.6002629697488995, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0684386733277518, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.9190266} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.24993968009949, "x": 5.769638302642161, "y": -0.10090376610591356, "z": null, "yaw": 3.162272736161935, "pitch": null, "roll": null}, "v": 2.0736908918833667, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3466864837449687, "steering_wheel_angle": -0.7001009318693607, "front_wheel_angle": -0.03245197622124179, "heading_rate": -0.02629648479552359, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.9390266} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24453817233733527, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.6002629697488995, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0670824383123136, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.9390266} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502701.9490266, "x": 9.541933909912263, "y": 4.894543532283016, "z": null, "yaw": 3.160735299162871, "pitch": null, "roll": null}, "v": 2.0664052498835632, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3460205690616417, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.02930428921632393, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.9590266} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24723613403301442, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.5642606126905148, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0657286799640304, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.9590266} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.35993957519531, "x": 5.541933909912263, "y": -0.10545646771698358, "z": null, "yaw": 3.160735299162871, "pitch": null, "roll": null}, "v": 2.0664052498835632, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3460205690616417, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.02930428921632393, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.9790266} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2463597246943296, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.5642606126905148, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0647144842823435, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.9790266} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.35993957519531, "x": 5.541933909912263, "y": -0.10545646771698358, "z": null, "yaw": 3.160735299162871, "pitch": null, "roll": null}, "v": 2.0664052498835632, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3460205690616417, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.02930428921632393, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502701.9990265} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2463597246943296, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.5642606126905148, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0635926384974566, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502701.9990265} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.35993957519531, "x": 5.541933909912263, "y": -0.10545646771698358, "z": null, "yaw": 3.160735299162871, "pitch": null, "roll": null}, "v": 2.0664052498835632, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3460205690616417, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.02930428921632393, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.0190265} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2463597246943296, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.5642606126905148, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0624728397626724, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.0190265} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.35993957519531, "x": 5.541933909912263, "y": -0.10545646771698358, "z": null, "yaw": 3.160735299162871, "pitch": null, "roll": null}, "v": 2.0664052498835632, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3460205690616417, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.02930428921632393, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.0390265} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2463597246943296, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.5642606126905148, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0613550838413555, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.0390265} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502702.0590265, "x": 9.3149786312174, "y": 4.890359373205331, "z": null, "yaw": 3.1591753574167, "pitch": null, "roll": null}, "v": 2.0602393665073415, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34545783079843284, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029216849044682327, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.0590265} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24876009238625021, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.506624136695576, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0602393665073415, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.0590265} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.46993947029114, "x": 5.3149786312174, "y": -0.10964062679466924, "z": null, "yaw": 3.1591753574167, "pitch": null, "roll": null}, "v": 2.0602393665073415, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34545783079843284, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029216849044682327, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.0790265} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2479818400591026, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.506624136695576, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.059425592692722, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.0790265} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.46993947029114, "x": 5.3149786312174, "y": -0.10964062679466924, "z": null, "yaw": 3.1591753574167, "pitch": null, "roll": null}, "v": 2.0602393665073415, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34545783079843284, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029216849044682327, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.0990264} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2479818400591026, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.506624136695576, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.058516065213789, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.0990264} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.46993947029114, "x": 5.3149786312174, "y": -0.10964062679466924, "z": null, "yaw": 3.1591753574167, "pitch": null, "roll": null}, "v": 2.0602393665073415, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34545783079843284, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029216849044682327, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.1190264} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2479818400591026, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.506624136695576, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0576081954997902, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.1190264} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.46993947029114, "x": 5.3149786312174, "y": -0.10964062679466924, "z": null, "yaw": 3.1591753574167, "pitch": null, "roll": null}, "v": 2.0602393665073415, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34545783079843284, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029216849044682327, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.1390264} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2479818400591026, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.506624136695576, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.056701980199633, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.1390264} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.46993947029114, "x": 5.3149786312174, "y": -0.10964062679466924, "z": null, "yaw": 3.1591753574167, "pitch": null, "roll": null}, "v": 2.0602393665073415, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34545783079843284, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029216849044682327, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.1590264} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2479818400591026, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.506624136695576, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0557974159701327, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.1590264} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502702.1690264, "x": 9.088625304328671, "y": 4.886539536408867, "z": null, "yaw": 3.157615415670529, "pitch": null, "roll": null}, "v": 2.0553457519642904, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3450117491993911, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029147451284542655, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.1790264} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2503329968032518, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4483131087366197, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0548944994759903, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.1790264} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.57993936538696, "x": 5.088625304328671, "y": -0.11346046359113338, "z": null, "yaw": 3.157615415670529, "pitch": null, "roll": null}, "v": 2.0553457519642904, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3450117491993911, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029147451284542655, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.1990263} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24957595574439825, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4483131087366197, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.054286988127994, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.1990263} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.57993936538696, "x": 5.088625304328671, "y": -0.11346046359113338, "z": null, "yaw": 3.157615415670529, "pitch": null, "roll": null}, "v": 2.0553457519642904, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3450117491993911, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029147451284542655, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.2190263} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24957595574439825, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4483131087366197, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0535859959870972, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.2190263} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.57993936538696, "x": 5.088625304328671, "y": -0.11346046359113338, "z": null, "yaw": 3.157615415670529, "pitch": null, "roll": null}, "v": 2.0553457519642904, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3450117491993911, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029147451284542655, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.2390263} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24957595574439825, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4483131087366197, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0528862801251084, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.2390263} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.57993936538696, "x": 5.088625304328671, "y": -0.11346046359113338, "z": null, "yaw": 3.157615415670529, "pitch": null, "roll": null}, "v": 2.0553457519642904, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3450117491993911, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029147451284542655, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.2590263} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.24957595574439825, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4483131087366197, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0521878380225864, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.2590263} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502702.2790263, "x": 8.862758551748229, "y": 4.883080356919626, "z": null, "yaw": 3.156055473924358, "pitch": null, "roll": null}, "v": 2.0514906671657465, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3446606729329689, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029092781214431117, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.2790263} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25348470513479293, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.5161842336067324, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0514906671657465, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.2790263} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.68993926048279, "x": 4.862758551748229, "y": -0.11691964308037406, "z": null, "yaw": 3.156055473924358, "pitch": null, "roll": null}, "v": 2.0514906671657465, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3446606729329689, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029092781214431117, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.2990263} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25224566632459633, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.5161842336067324, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0512831363483275, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.2990263} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.68993926048279, "x": 4.862758551748229, "y": -0.11691964308037406, "z": null, "yaw": 3.156055473924358, "pitch": null, "roll": null}, "v": 2.0514906671657465, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3446606729329689, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029092781214431117, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.3190262} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25224566632459633, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.5161842336067324, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0509211738125908, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.3190262} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.68993926048279, "x": 4.862758551748229, "y": -0.11691964308037406, "z": null, "yaw": 3.156055473924358, "pitch": null, "roll": null}, "v": 2.0514906671657465, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3446606729329689, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029092781214431117, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.3390262} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25224566632459633, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.5161842336067324, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0505598698952743, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.3390262} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.68993926048279, "x": 4.862758551748229, "y": -0.11691964308037406, "z": null, "yaw": 3.156055473924358, "pitch": null, "roll": null}, "v": 2.0514906671657465, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3446606729329689, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029092781214431117, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.3590262} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25224566632459633, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.5161842336067324, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0501992233457793, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.3590262} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.68993926048279, "x": 4.862758551748229, "y": -0.11691964308037406, "z": null, "yaw": 3.156055473924358, "pitch": null, "roll": null}, "v": 2.0514906671657465, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3446606729329689, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029092781214431117, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.3790262} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25224566632459633, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.5161842336067324, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.049839232916067, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.3790262} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502702.3890262, "x": 8.63720069758525, "y": 4.879977866978146, "z": null, "yaw": 3.1544955321781867, "pitch": null, "roll": null}, "v": 2.049659483356816, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34449401414498615, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029066812668354217, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.3990262} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2538427412395817, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.416703979074443, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0494798973606536, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.3990262} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.79993915557861, "x": 4.63720069758525, "y": -0.1200221330218536, "z": null, "yaw": 3.1544955321781867, "pitch": null, "roll": null}, "v": 2.049659483356816, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34449401414498615, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029066812668354217, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.4190261} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25333532205655973, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.416703979074443, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.049320758980309, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.4190261} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.79993915557861, "x": 4.63720069758525, "y": -0.1200221330218536, "z": null, "yaw": 3.1544955321781867, "pitch": null, "roll": null}, "v": 2.049659483356816, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34449401414498615, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029066812668354217, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.439026} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25333532205655973, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.416703979074443, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0490985115160427, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.439026} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.79993915557861, "x": 4.63720069758525, "y": -0.1200221330218536, "z": null, "yaw": 3.1544955321781867, "pitch": null, "roll": null}, "v": 2.049659483356816, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34449401414498615, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029066812668354217, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.459026} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25333532205655973, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.416703979074443, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.048876668282987, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.459026} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.79993915557861, "x": 4.63720069758525, "y": -0.1200221330218536, "z": null, "yaw": 3.1544955321781867, "pitch": null, "roll": null}, "v": 2.049659483356816, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.34449401414498615, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029066812668354217, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.479026} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25333532205655973, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.416703979074443, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0486552285262354, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.479026} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502702.499026, "x": 8.411817492289305, "y": 4.8772294329797, "z": null, "yaw": 3.1529355904320155, "pitch": null, "roll": null}, "v": 2.0484341914923623, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3443825359433678, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.02904943645080329, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.499026} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25668406662421, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4822462986418603, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0484341914923623, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.499026} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.90993905067444, "x": 4.411817492289305, "y": -0.12277056702030009, "z": null, "yaw": 3.1529355904320155, "pitch": null, "roll": null}, "v": 2.0484341914923623, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3443825359433678, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.02904943645080329, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.519026} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25563200934695585, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4822462986418603, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.048631959106311, "gear": 1, "accelerator_pedal_position": 0.25668406662421, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.519026} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.90993905067444, "x": 4.411817492289305, "y": -0.12277056702030009, "z": null, "yaw": 3.1529355904320155, "pitch": null, "roll": null}, "v": 2.0484341914923623, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3443825359433678, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.02904943645080329, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.539026} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25563200934695585, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4822462986418603, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.048697919717983, "gear": 1, "accelerator_pedal_position": 0.25563200934695585, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.539026} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.90993905067444, "x": 4.411817492289305, "y": -0.12277056702030009, "z": null, "yaw": 3.1529355904320155, "pitch": null, "roll": null}, "v": 2.0484341914923623, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3443825359433678, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.02904943645080329, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.559026} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25563200934695585, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4822462986418603, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0487637603707216, "gear": 1, "accelerator_pedal_position": 0.25563200934695585, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.559026} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.90993905067444, "x": 4.411817492289305, "y": -0.12277056702030009, "z": null, "yaw": 3.1529355904320155, "pitch": null, "roll": null}, "v": 2.0484341914923623, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3443825359433678, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.02904943645080329, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.579026} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25563200934695585, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4822462986418603, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.048829481280956, "gear": 1, "accelerator_pedal_position": 0.25563200934695585, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.579026} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 63.90993905067444, "x": 4.411817492289305, "y": -0.12277056702030009, "z": null, "yaw": 3.1529355904320155, "pitch": null, "roll": null}, "v": 2.0484341914923623, "accelerator_pedal_position": 0, "brake_pedal_position": 0.0, "acceleration": -0.3443825359433678, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.02904943645080329, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.599026} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25563200934695585, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.4822462986418603, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0488950826647323, "gear": 1, "accelerator_pedal_position": 0.25563200934695585, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.599026} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502702.609026, "x": 8.186471853868161, "y": 4.874833052327029, "z": null, "yaw": 3.1513756486858444, "pitch": null, "roll": null}, "v": 2.048927838601608, "accelerator_pedal_position": 0.25563200934695585, "brake_pedal_position": 0.0, "acceleration": 0.0032726136104269665, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029056437002926816, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.619026} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25701814895908626, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3614222017331137, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0489605647377123, "gear": 1, "accelerator_pedal_position": 0.25563200934695585, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.619026} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.01993894577026, "x": 4.186471853868161, "y": -0.12516694767297132, "z": null, "yaw": 3.1513756486858444, "pitch": null, "roll": null}, "v": 2.048927838601608, "accelerator_pedal_position": 0.25563200934695585, "brake_pedal_position": 0.0, "acceleration": 0.0032726136104269665, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029056437002926816, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.639026} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25658722549099405, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3614222017331137, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0491991163466934, "gear": 1, "accelerator_pedal_position": 0.25701814895908626, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.639026} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.01993894577026, "x": 4.186471853868161, "y": -0.12516694767297132, "z": null, "yaw": 3.1513756486858444, "pitch": null, "roll": null}, "v": 2.048927838601608, "accelerator_pedal_position": 0.25563200934695585, "brake_pedal_position": 0.0, "acceleration": 0.0032726136104269665, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029056437002926816, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.659026} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25658722549099405, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3614222017331137, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.049383393142846, "gear": 1, "accelerator_pedal_position": 0.25658722549099405, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.659026} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.01993894577026, "x": 4.186471853868161, "y": -0.12516694767297132, "z": null, "yaw": 3.1513756486858444, "pitch": null, "roll": null}, "v": 2.048927838601608, "accelerator_pedal_position": 0.25563200934695585, "brake_pedal_position": 0.0, "acceleration": 0.0032726136104269665, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029056437002926816, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.679026} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25658722549099405, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3614222017331137, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0495673347566328, "gear": 1, "accelerator_pedal_position": 0.25658722549099405, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.679026} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.01993894577026, "x": 4.186471853868161, "y": -0.12516694767297132, "z": null, "yaw": 3.1513756486858444, "pitch": null, "roll": null}, "v": 2.048927838601608, "accelerator_pedal_position": 0.25563200934695585, "brake_pedal_position": 0.0, "acceleration": 0.0032726136104269665, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029056437002926816, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.6990259} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.25658722549099405, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.3614222017331137, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0497509417841915, "gear": 1, "accelerator_pedal_position": 0.25658722549099405, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.6990259} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502702.7190259, "x": 7.961049781053775, "y": 4.872787546667662, "z": null, "yaw": 3.1498157069396733, "pitch": null, "roll": null}, "v": 2.049934214820649, "accelerator_pedal_position": 0.25658722549099405, "brake_pedal_position": 0.0, "acceleration": 0.009151145726756793, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029070708714530758, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.7190259} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2594578340220016, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.418183865205936, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.049934214820649, "gear": 1, "accelerator_pedal_position": 0.25658722549099405, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.7190259} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.12993884086609, "x": 3.9610497810537746, "y": -0.127212453332338, "z": null, "yaw": 3.1498157069396733, "pitch": null, "roll": null}, "v": 2.049934214820649, "accelerator_pedal_position": 0.25658722549099405, "brake_pedal_position": 0.0, "acceleration": 0.009151145726756793, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029070708714530758, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.7390258} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2585653467100969, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.418183865205936, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.050690468409536, "gear": 1, "accelerator_pedal_position": 0.2585653467100969, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.7390258} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.12993884086609, "x": 3.9610497810537746, "y": -0.127212453332338, "z": null, "yaw": 3.1498157069396733, "pitch": null, "roll": null}, "v": 2.049934214820649, "accelerator_pedal_position": 0.25658722549099405, "brake_pedal_position": 0.0, "acceleration": 0.009151145726756793, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029070708714530758, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.7490258} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2585653467100969, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.418183865205936, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.050690468409536, "gear": 1, "accelerator_pedal_position": 0.2585653467100969, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.7490258} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.12993884086609, "x": 3.9610497810537746, "y": -0.127212453332338, "z": null, "yaw": 3.1498157069396733, "pitch": null, "roll": null}, "v": 2.049934214820649, "accelerator_pedal_position": 0.25658722549099405, "brake_pedal_position": 0.0, "acceleration": 0.009151145726756793, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029070708714530758, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.7790258} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2585653467100969, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.418183865205936, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0513332503974007, "gear": 1, "accelerator_pedal_position": 0.2585653467100969, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.7790258} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.12993884086609, "x": 3.9610497810537746, "y": -0.127212453332338, "z": null, "yaw": 3.1498157069396733, "pitch": null, "roll": null}, "v": 2.049934214820649, "accelerator_pedal_position": 0.25658722549099405, "brake_pedal_position": 0.0, "acceleration": 0.009151145726756793, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029070708714530758, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.7990258} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2585653467100969, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.418183865205936, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.051760797180958, "gear": 1, "accelerator_pedal_position": 0.2585653467100969, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.7990258} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.12993884086609, "x": 3.9610497810537746, "y": -0.127212453332338, "z": null, "yaw": 3.1498157069396733, "pitch": null, "roll": null}, "v": 2.049934214820649, "accelerator_pedal_position": 0.25658722549099405, "brake_pedal_position": 0.0, "acceleration": 0.009151145726756793, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029070708714530758, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.8190258} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2585653467100969, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.418183865205936, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0521875659008364, "gear": 1, "accelerator_pedal_position": 0.2585653467100969, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.8190258} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502702.8290257, "x": 7.735434845122841, "y": 4.871092281151316, "z": null, "yaw": 3.148255765193502, "pitch": null, "roll": null}, "v": 2.0524006589067034, "accelerator_pedal_position": 0.2585653467100969, "brake_pedal_position": 0.0, "acceleration": 0.021289899345963648, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.02910568606993464, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.8390257} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26005827962308226, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.299408979343113, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.052919571355848, "gear": 1, "accelerator_pedal_position": 0.26005827962308226, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.8390257} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.23993873596191, "x": 3.7354348451228407, "y": -0.12890771884868357, "z": null, "yaw": 3.148255765193502, "pitch": null, "roll": null}, "v": 2.0524006589067034, "accelerator_pedal_position": 0.2585653467100969, "brake_pedal_position": 0.0, "acceleration": 0.021289899345963648, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.02910568606993464, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.8590257} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2596029629892548, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.299408979343113, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0532253061699675, "gear": 1, "accelerator_pedal_position": 0.26005827962308226, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.8590257} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.23993873596191, "x": 3.7354348451228407, "y": -0.12890771884868357, "z": null, "yaw": 3.148255765193502, "pitch": null, "roll": null}, "v": 2.0524006589067034, "accelerator_pedal_position": 0.2585653467100969, "brake_pedal_position": 0.0, "acceleration": 0.021289899345963648, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.02910568606993464, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.8790257} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2596029629892548, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.299408979343113, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.053779052150323, "gear": 1, "accelerator_pedal_position": 0.2596029629892548, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.8790257} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.23993873596191, "x": 3.7354348451228407, "y": -0.12890771884868357, "z": null, "yaw": 3.148255765193502, "pitch": null, "roll": null}, "v": 2.0524006589067034, "accelerator_pedal_position": 0.2585653467100969, "brake_pedal_position": 0.0, "acceleration": 0.021289899345963648, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.02910568606993464, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.8990257} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2596029629892548, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.299408979343113, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0543317899659095, "gear": 1, "accelerator_pedal_position": 0.2596029629892548, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.8990257} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.23993873596191, "x": 3.7354348451228407, "y": -0.12890771884868357, "z": null, "yaw": 3.148255765193502, "pitch": null, "roll": null}, "v": 2.0524006589067034, "accelerator_pedal_position": 0.2585653467100969, "brake_pedal_position": 0.0, "acceleration": 0.021289899345963648, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.02910568606993464, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.9190257} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2596029629892548, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.299408979343113, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0548835213300656, "gear": 1, "accelerator_pedal_position": 0.2596029629892548, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.9190257} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502702.9390256, "x": 7.509524090968997, "y": 4.869747225509921, "z": null, "yaw": 3.146695823447331, "pitch": null, "roll": null}, "v": 2.0554342479536793, "accelerator_pedal_position": 0.2596029629892548, "brake_pedal_position": 0.0, "acceleration": 0.027498706808549267, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.02914870627170826, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.9390256} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26151274760661714, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2243319182604433, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0554342479536793, "gear": 1, "accelerator_pedal_position": 0.2596029629892548, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.9390256} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.34993863105774, "x": 3.5095240909689966, "y": -0.13025277449007877, "z": null, "yaw": 3.146695823447331, "pitch": null, "roll": null}, "v": 2.0554342479536793, "accelerator_pedal_position": 0.2596029629892548, "brake_pedal_position": 0.0, "acceleration": 0.027498706808549267, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.02914870627170826, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.9590256} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2609297542455587, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2243319182604433, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.05622258586564, "gear": 1, "accelerator_pedal_position": 0.26151274760661714, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.9590256} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.34993863105774, "x": 3.5095240909689966, "y": -0.13025277449007877, "z": null, "yaw": 3.146695823447331, "pitch": null, "roll": null}, "v": 2.0554342479536793, "accelerator_pedal_position": 0.2596029629892548, "brake_pedal_position": 0.0, "acceleration": 0.027498706808549267, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.02914870627170826, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.9790256} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2609297542455587, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2243319182604433, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0569366467928267, "gear": 1, "accelerator_pedal_position": 0.2609297542455587, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.9790256} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.34993863105774, "x": 3.5095240909689966, "y": -0.13025277449007877, "z": null, "yaw": 3.146695823447331, "pitch": null, "roll": null}, "v": 2.0554342479536793, "accelerator_pedal_position": 0.2596029629892548, "brake_pedal_position": 0.0, "acceleration": 0.027498706808549267, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.02914870627170826, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502702.9990256} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2609297542455587, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2243319182604433, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.057649406791934, "gear": 1, "accelerator_pedal_position": 0.2609297542455587, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502702.9990256} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.34993863105774, "x": 3.5095240909689966, "y": -0.13025277449007877, "z": null, "yaw": 3.146695823447331, "pitch": null, "roll": null}, "v": 2.0554342479536793, "accelerator_pedal_position": 0.2596029629892548, "brake_pedal_position": 0.0, "acceleration": 0.027498706808549267, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.02914870627170826, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.0190256} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2609297542455587, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2243319182604433, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0583608680299688, "gear": 1, "accelerator_pedal_position": 0.2609297542455587, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.0190256} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.34993863105774, "x": 3.5095240909689966, "y": -0.13025277449007877, "z": null, "yaw": 3.146695823447331, "pitch": null, "roll": null}, "v": 2.0554342479536793, "accelerator_pedal_position": 0.2596029629892548, "brake_pedal_position": 0.0, "acceleration": 0.027498706808549267, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.02914870627170826, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.0390255} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2609297542455587, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2243319182604433, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0590710326710995, "gear": 1, "accelerator_pedal_position": 0.2609297542455587, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.0390255} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502703.0490255, "x": 7.283225320551954, "y": 4.86875289477284, "z": null, "yaw": 3.14513588170116, "pitch": null, "roll": null}, "v": 2.0594256294433526, "accelerator_pedal_position": 0.2609297542455587, "brake_pedal_position": 0.0, "acceleration": 0.03542734333049269, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029205309204532136, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.0590255} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26327425505324137, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2669337560076297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0597799028766577, "gear": 1, "accelerator_pedal_position": 0.2609297542455587, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.0590255} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.45993852615356, "x": 3.2832253205519537, "y": -0.13124710522716043, "z": null, "yaw": 3.14513588170116, "pitch": null, "roll": null}, "v": 2.0594256294433526, "accelerator_pedal_position": 0.2609297542455587, "brake_pedal_position": 0.0, "acceleration": 0.03542734333049269, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029205309204532136, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.0790255} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2625597885238976, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2669337560076297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.060780409763482, "gear": 1, "accelerator_pedal_position": 0.26327425505324137, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.0790255} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.45993852615356, "x": 3.2832253205519537, "y": -0.13124710522716043, "z": null, "yaw": 3.14513588170116, "pitch": null, "roll": null}, "v": 2.0594256294433526, "accelerator_pedal_position": 0.2609297542455587, "brake_pedal_position": 0.0, "acceleration": 0.03542734333049269, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029205309204532136, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.0990255} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2625597885238976, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2669337560076297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.061689824765585, "gear": 1, "accelerator_pedal_position": 0.2625597885238976, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.0990255} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.45993852615356, "x": 3.2832253205519537, "y": -0.13124710522716043, "z": null, "yaw": 3.14513588170116, "pitch": null, "roll": null}, "v": 2.0594256294433526, "accelerator_pedal_position": 0.2609297542455587, "brake_pedal_position": 0.0, "acceleration": 0.03542734333049269, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029205309204532136, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.1190255} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2625597885238976, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2669337560076297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0625975812196504, "gear": 1, "accelerator_pedal_position": 0.2625597885238976, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.1190255} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.45993852615356, "x": 3.2832253205519537, "y": -0.13124710522716043, "z": null, "yaw": 3.14513588170116, "pitch": null, "roll": null}, "v": 2.0594256294433526, "accelerator_pedal_position": 0.2609297542455587, "brake_pedal_position": 0.0, "acceleration": 0.03542734333049269, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029205309204532136, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.1390254} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2625597885238976, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.2669337560076297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.063503681821001, "gear": 1, "accelerator_pedal_position": 0.2625597885238976, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.1390254} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502703.1590254, "x": 7.056441817977197, "y": 4.868110222961941, "z": null, "yaw": 3.1435759399549887, "pitch": null, "roll": null}, "v": 2.0644081292618455, "accelerator_pedal_position": 0.2625597885238976, "brake_pedal_position": 0.0, "acceleration": 0.04516046256964379, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029275967472415277, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.1590254} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26438805311620167, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1851661774740831, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0644081292618455, "gear": 1, "accelerator_pedal_position": 0.2625597885238976, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.1590254} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.56993842124939, "x": 3.0564418179771966, "y": -0.13188977703805893, "z": null, "yaw": 3.1435759399549887, "pitch": null, "roll": null}, "v": 2.0644081292618455, "accelerator_pedal_position": 0.2625597885238976, "brake_pedal_position": 0.0, "acceleration": 0.04516046256964379, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029275967472415277, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.1790254} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26383944982143764, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1851661774740831, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.065539354981868, "gear": 1, "accelerator_pedal_position": 0.26438805311620167, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.1790254} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.56993842124939, "x": 3.0564418179771966, "y": -0.13188977703805893, "z": null, "yaw": 3.1435759399549887, "pitch": null, "roll": null}, "v": 2.0644081292618455, "accelerator_pedal_position": 0.2625597885238976, "brake_pedal_position": 0.0, "acceleration": 0.04516046256964379, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029275967472415277, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.1990254} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26383944982143764, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1851661774740831, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.066599971811044, "gear": 1, "accelerator_pedal_position": 0.26383944982143764, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.1990254} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.56993842124939, "x": 3.0564418179771966, "y": -0.13188977703805893, "z": null, "yaw": 3.1435759399549887, "pitch": null, "roll": null}, "v": 2.0644081292618455, "accelerator_pedal_position": 0.2625597885238976, "brake_pedal_position": 0.0, "acceleration": 0.04516046256964379, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029275967472415277, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.2190254} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26383944982143764, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1851661774740831, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.067658652272264, "gear": 1, "accelerator_pedal_position": 0.26383944982143764, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.2190254} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.56993842124939, "x": 3.0564418179771966, "y": -0.13188977703805893, "z": null, "yaw": 3.1435759399549887, "pitch": null, "roll": null}, "v": 2.0644081292618455, "accelerator_pedal_position": 0.2625597885238976, "brake_pedal_position": 0.0, "acceleration": 0.04516046256964379, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029275967472415277, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.2390254} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26383944982143764, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1851661774740831, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.068715399452637, "gear": 1, "accelerator_pedal_position": 0.26383944982143764, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.2390254} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.56993842124939, "x": 3.0564418179771966, "y": -0.13188977703805893, "z": null, "yaw": 3.1435759399549887, "pitch": null, "roll": null}, "v": 2.0644081292618455, "accelerator_pedal_position": 0.2625597885238976, "brake_pedal_position": 0.0, "acceleration": 0.04516046256964379, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029275967472415277, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.2590253} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26383944982143764, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1851661774740831, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.069770216436089, "gear": 1, "accelerator_pedal_position": 0.26383944982143764, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.2590253} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502703.2690253, "x": 6.829059070324234, "y": 4.867820569976216, "z": null, "yaw": 3.1420159982088176, "pitch": null, "roll": null}, "v": 2.0702969020668265, "accelerator_pedal_position": 0.26383944982143764, "brake_pedal_position": 0.0, "acceleration": 0.05262042365356889, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029359477859071576, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.2790253} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2657667631807842, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1815199681884194, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.070823106303362, "gear": 1, "accelerator_pedal_position": 0.26383944982143764, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.2790253} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.67993831634521, "x": 2.8290590703242344, "y": -0.1321794300237844, "z": null, "yaw": 3.1420159982088176, "pitch": null, "roll": null}, "v": 2.0702969020668265, "accelerator_pedal_position": 0.26383944982143764, "brake_pedal_position": 0.0, "acceleration": 0.05262042365356889, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029359477859071576, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.2990253} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26519137348001853, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1815199681884194, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0721148761702017, "gear": 1, "accelerator_pedal_position": 0.2657667631807842, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.2990253} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.67993831634521, "x": 2.8290590703242344, "y": -0.1321794300237844, "z": null, "yaw": 3.1420159982088176, "pitch": null, "roll": null}, "v": 2.0702969020668265, "accelerator_pedal_position": 0.26383944982143764, "brake_pedal_position": 0.0, "acceleration": 0.05262042365356889, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029359477859071576, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.3190253} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26519137348001853, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1815199681884194, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.073332394012142, "gear": 1, "accelerator_pedal_position": 0.26519137348001853, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.3190253} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.67993831634521, "x": 2.8290590703242344, "y": -0.1321794300237844, "z": null, "yaw": 3.1420159982088176, "pitch": null, "roll": null}, "v": 2.0702969020668265, "accelerator_pedal_position": 0.26383944982143764, "brake_pedal_position": 0.0, "acceleration": 0.05262042365356889, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029359477859071576, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.3390253} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26519137348001853, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1815199681884194, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0745476857753284, "gear": 1, "accelerator_pedal_position": 0.26519137348001853, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.3390253} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.67993831634521, "x": 2.8290590703242344, "y": -0.1321794300237844, "z": null, "yaw": 3.1420159982088176, "pitch": null, "roll": null}, "v": 2.0702969020668265, "accelerator_pedal_position": 0.26383944982143764, "brake_pedal_position": 0.0, "acceleration": 0.05262042365356889, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029359477859071576, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.3590252} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26519137348001853, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -1.1815199681884194, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0757607549393624, "gear": 1, "accelerator_pedal_position": 0.26519137348001853, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.3590252} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502703.3790252, "x": 6.600993800668712, "y": 4.867885828093091, "z": null, "yaw": 3.1404560564626465, "pitch": null, "roll": null}, "v": 2.076971604980723, "accelerator_pedal_position": 0.26519137348001853, "brake_pedal_position": 0.0, "acceleration": 0.060459393522117544, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029454133747423047, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.3790252} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26723570072053715, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9627700895276374, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.076971604980723, "gear": 1, "accelerator_pedal_position": 0.26519137348001853, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.3790252} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.78993821144104, "x": 2.6009938006687117, "y": -0.13211417190690877, "z": null, "yaw": 3.1404560564626465, "pitch": null, "roll": null}, "v": 2.076971604980723, "accelerator_pedal_position": 0.26519137348001853, "brake_pedal_position": 0.0, "acceleration": 0.060459393522117544, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029454133747423047, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.3990252} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2666273757089052, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9627700895276374, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.078435663300393, "gear": 1, "accelerator_pedal_position": 0.26723570072053715, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.3990252} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.78993821144104, "x": 2.6009938006687117, "y": -0.13211417190690877, "z": null, "yaw": 3.1404560564626465, "pitch": null, "roll": null}, "v": 2.076971604980723, "accelerator_pedal_position": 0.26519137348001853, "brake_pedal_position": 0.0, "acceleration": 0.060459393522117544, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029454133747423047, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.4190252} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2666273757089052, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9627700895276374, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0798210360168414, "gear": 1, "accelerator_pedal_position": 0.2666273757089052, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.4190252} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.78993821144104, "x": 2.6009938006687117, "y": -0.13211417190690877, "z": null, "yaw": 3.1404560564626465, "pitch": null, "roll": null}, "v": 2.076971604980723, "accelerator_pedal_position": 0.26519137348001853, "brake_pedal_position": 0.0, "acceleration": 0.060459393522117544, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029454133747423047, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.4390252} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2666273757089052, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9627700895276374, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0812038721837984, "gear": 1, "accelerator_pedal_position": 0.2666273757089052, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.4390252} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.78993821144104, "x": 2.6009938006687117, "y": -0.13211417190690877, "z": null, "yaw": 3.1404560564626465, "pitch": null, "roll": null}, "v": 2.076971604980723, "accelerator_pedal_position": 0.26519137348001853, "brake_pedal_position": 0.0, "acceleration": 0.060459393522117544, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029454133747423047, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.4590251} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2666273757089052, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9627700895276374, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.082584175681017, "gear": 1, "accelerator_pedal_position": 0.2666273757089052, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.4590251} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.78993821144104, "x": 2.6009938006687117, "y": -0.13211417190690877, "z": null, "yaw": 3.1404560564626465, "pitch": null, "roll": null}, "v": 2.076971604980723, "accelerator_pedal_position": 0.26519137348001853, "brake_pedal_position": 0.0, "acceleration": 0.060459393522117544, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029454133747423047, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.4790251} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2666273757089052, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.9627700895276374, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.083961950385346, "gear": 1, "accelerator_pedal_position": 0.2666273757089052, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.4790251} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502703.489025, "x": 6.372139299384786, "y": 4.868308325141296, "z": null, "yaw": 3.1388961147164753, "pitch": null, "roll": null}, "v": 2.0846498906508946, "accelerator_pedal_position": 0.2666273757089052, "brake_pedal_position": 0.0, "acceleration": 0.06873095198220491, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.02956302173247677, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.499025} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.26907047419084246, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8124476433374687, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0853372001707164, "gear": 1, "accelerator_pedal_position": 0.2666273757089052, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.499025} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.89993810653687, "x": 2.372139299384786, "y": -0.13169167485870403, "z": null, "yaw": 3.1388961147164753, "pitch": null, "roll": null}, "v": 2.0846498906508946, "accelerator_pedal_position": 0.2666273757089052, "brake_pedal_position": 0.0, "acceleration": 0.06873095198220491, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.02956302173247677, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.519025} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2683421782112517, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8124476433374687, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0870151761646945, "gear": 1, "accelerator_pedal_position": 0.26907047419084246, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.519025} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.89993810653687, "x": 2.372139299384786, "y": -0.13169167485870403, "z": null, "yaw": 3.1388961147164753, "pitch": null, "roll": null}, "v": 2.0846498906508946, "accelerator_pedal_position": 0.2666273757089052, "brake_pedal_position": 0.0, "acceleration": 0.06873095198220491, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.02956302173247677, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.539025} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2683421782112517, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8124476433374687, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0885990798605762, "gear": 1, "accelerator_pedal_position": 0.2683421782112517, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.539025} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.89993810653687, "x": 2.372139299384786, "y": -0.13169167485870403, "z": null, "yaw": 3.1388961147164753, "pitch": null, "roll": null}, "v": 2.0846498906508946, "accelerator_pedal_position": 0.2666273757089052, "brake_pedal_position": 0.0, "acceleration": 0.06873095198220491, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.02956302173247677, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.559025} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2683421782112517, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8124476433374687, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.09018007798158, "gear": 1, "accelerator_pedal_position": 0.2683421782112517, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.559025} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 64.89993810653687, "x": 2.372139299384786, "y": -0.13169167485870403, "z": null, "yaw": 3.1388961147164753, "pitch": null, "roll": null}, "v": 2.0846498906508946, "accelerator_pedal_position": 0.2666273757089052, "brake_pedal_position": 0.0, "acceleration": 0.06873095198220491, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.02956302173247677, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.579025} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2683421782112517, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8124476433374687, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.091758174858443, "gear": 1, "accelerator_pedal_position": 0.2683421782112517, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.579025} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502703.599025, "x": 6.142396362894166, "y": 4.869090865494373, "z": null, "yaw": 3.137336172970304, "pitch": null, "roll": null}, "v": 2.093333374819455, "accelerator_pedal_position": 0.2683421782112517, "brake_pedal_position": 0.0, "acceleration": 0.07865149889802037, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029686164727537975, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.599025} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27025174838096877, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8219326687541522, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.093333374819455, "gear": 1, "accelerator_pedal_position": 0.2683421782112517, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.599025} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.00993800163269, "x": 2.142396362894166, "y": -0.13090913450562702, "z": null, "yaw": 3.137336172970304, "pitch": null, "roll": null}, "v": 2.093333374819455, "accelerator_pedal_position": 0.2683421782112517, "brake_pedal_position": 0.0, "acceleration": 0.07865149889802037, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029686164727537975, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.619025} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2696948557739975, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8219326687541522, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.095144268800307, "gear": 1, "accelerator_pedal_position": 0.27025174838096877, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.619025} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.00993800163269, "x": 2.142396362894166, "y": -0.13090913450562702, "z": null, "yaw": 3.137336172970304, "pitch": null, "roll": null}, "v": 2.093333374819455, "accelerator_pedal_position": 0.2683421782112517, "brake_pedal_position": 0.0, "acceleration": 0.07865149889802037, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029686164727537975, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.639025} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2696948557739975, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8219326687541522, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.09775005236647, "gear": 1, "accelerator_pedal_position": 0.2696948557739975, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.639025} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.00993800163269, "x": 2.142396362894166, "y": -0.13090913450562702, "z": null, "yaw": 3.137336172970304, "pitch": null, "roll": null}, "v": 2.093333374819455, "accelerator_pedal_position": 0.2683421782112517, "brake_pedal_position": 0.0, "acceleration": 0.07865149889802037, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029686164727537975, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.659025} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2696948557739975, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8219326687541522, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.098617050297941, "gear": 1, "accelerator_pedal_position": 0.2696948557739975, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.659025} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.00993800163269, "x": 2.142396362894166, "y": -0.13090913450562702, "z": null, "yaw": 3.137336172970304, "pitch": null, "roll": null}, "v": 2.093333374819455, "accelerator_pedal_position": 0.2683421782112517, "brake_pedal_position": 0.0, "acceleration": 0.07865149889802037, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029686164727537975, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.679025} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2696948557739975, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8219326687541522, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1003486547746246, "gear": 1, "accelerator_pedal_position": 0.2696948557739975, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.679025} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.00993800163269, "x": 2.142396362894166, "y": -0.13090913450562702, "z": null, "yaw": 3.137336172970304, "pitch": null, "roll": null}, "v": 2.093333374819455, "accelerator_pedal_position": 0.2683421782112517, "brake_pedal_position": 0.0, "acceleration": 0.07865149889802037, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029686164727537975, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.699025} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2696948557739975, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.8219326687541522, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.102077074623138, "gear": 1, "accelerator_pedal_position": 0.2696948557739975, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.699025} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502703.709025, "x": 5.911648210080921, "y": 4.870236801262151, "z": null, "yaw": 3.135776231224133, "pitch": null, "roll": null}, "v": 2.1029400917689354, "accelerator_pedal_position": 0.2696948557739975, "brake_pedal_position": 0.0, "acceleration": 0.08622227370334612, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.02982240035311181, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.719025} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2717660064841811, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7765949610215995, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1038023145059688, "gear": 1, "accelerator_pedal_position": 0.2696948557739975, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.719025} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.11993789672852, "x": 1.9116482100809211, "y": -0.12976319873784892, "z": null, "yaw": 3.135776231224133, "pitch": null, "roll": null}, "v": 2.1029400917689354, "accelerator_pedal_position": 0.2696948557739975, "brake_pedal_position": 0.0, "acceleration": 0.08622227370334612, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.02982240035311181, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.7390249} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2711629444899422, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7765949610215995, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.10578315370881, "gear": 1, "accelerator_pedal_position": 0.2717660064841811, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.7390249} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.11993789672852, "x": 1.9116482100809211, "y": -0.12976319873784892, "z": null, "yaw": 3.135776231224133, "pitch": null, "roll": null}, "v": 2.1029400917689354, "accelerator_pedal_position": 0.2696948557739975, "brake_pedal_position": 0.0, "acceleration": 0.08622227370334612, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.02982240035311181, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.7590249} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2711629444899422, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7765949610215995, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.107684997636004, "gear": 1, "accelerator_pedal_position": 0.2711629444899422, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.7590249} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.11993789672852, "x": 1.9116482100809211, "y": -0.12976319873784892, "z": null, "yaw": 3.135776231224133, "pitch": null, "roll": null}, "v": 2.1029400917689354, "accelerator_pedal_position": 0.2696948557739975, "brake_pedal_position": 0.0, "acceleration": 0.08622227370334612, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.02982240035311181, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.7790248} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2711629444899422, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7765949610215995, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.110531196476091, "gear": 1, "accelerator_pedal_position": 0.2711629444899422, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.7790248} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.11993789672852, "x": 1.9116482100809211, "y": -0.12976319873784892, "z": null, "yaw": 3.135776231224133, "pitch": null, "roll": null}, "v": 2.1029400917689354, "accelerator_pedal_position": 0.2696948557739975, "brake_pedal_position": 0.0, "acceleration": 0.08622227370334612, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.02982240035311181, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.7990248} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2711629444899422, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7765949610215995, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1114781807153444, "gear": 1, "accelerator_pedal_position": 0.2711629444899422, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.7990248} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502703.8190248, "x": 5.679809271786361, "y": 4.871749833344935, "z": null, "yaw": 3.134216289477962, "pitch": null, "roll": null}, "v": 2.1133695298908504, "accelerator_pedal_position": 0.2711629444899422, "brake_pedal_position": 0.0, "acceleration": 0.09443661886888549, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029970303225070525, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.8190248} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2726857510299599, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7817214222221757, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1133695298908504, "gear": 1, "accelerator_pedal_position": 0.2711629444899422, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.8190248} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.22993779182434, "x": 1.679809271786361, "y": -0.12825016665506528, "z": null, "yaw": 3.134216289477962, "pitch": null, "roll": null}, "v": 2.1133695298908504, "accelerator_pedal_position": 0.2711629444899422, "brake_pedal_position": 0.0, "acceleration": 0.09443661886888549, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029970303225070525, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.8390248} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27225793417116156, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7817214222221757, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1154476538197593, "gear": 1, "accelerator_pedal_position": 0.2726857510299599, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.8390248} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.22993779182434, "x": 1.679809271786361, "y": -0.12825016665506528, "z": null, "yaw": 3.134216289477962, "pitch": null, "roll": null}, "v": 2.1133695298908504, "accelerator_pedal_position": 0.2711629444899422, "brake_pedal_position": 0.0, "acceleration": 0.09443661886888549, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029970303225070525, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.8690248} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27225793417116156, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7817214222221757, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.118477510301621, "gear": 1, "accelerator_pedal_position": 0.27225793417116156, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.8690248} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27225793417116156, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7817214222221757, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1204927539029312, "gear": 1, "accelerator_pedal_position": 0.27225793417116156, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.8790247} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.22993779182434, "x": 1.679809271786361, "y": -0.12825016665506528, "z": null, "yaw": 3.134216289477962, "pitch": null, "roll": null}, "v": 2.1133695298908504, "accelerator_pedal_position": 0.2711629444899422, "brake_pedal_position": 0.0, "acceleration": 0.09443661886888549, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029970303225070525, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.8990247} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27225793417116156, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7817214222221757, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.121498979459742, "gear": 1, "accelerator_pedal_position": 0.27225793417116156, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.8990247} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.22993779182434, "x": 1.679809271786361, "y": -0.12825016665506528, "z": null, "yaw": 3.134216289477962, "pitch": null, "roll": null}, "v": 2.1133695298908504, "accelerator_pedal_position": 0.2711629444899422, "brake_pedal_position": 0.0, "acceleration": 0.09443661886888549, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.029970303225070525, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.9190247} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27225793417116156, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7817214222221757, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.123508641372124, "gear": 1, "accelerator_pedal_position": 0.27225793417116156, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.9190247} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502703.9290247, "x": 5.446785703132062, "y": 4.873634127681411, "z": null, "yaw": 3.132656347731791, "pitch": null, "roll": null}, "v": 2.1245120790421375, "accelerator_pedal_position": 0.27225793417116156, "brake_pedal_position": 0.0, "acceleration": 0.10025096887769336, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.0301283189303417, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.9390247} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27356373840500936, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7868144310045057, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1255145887309146, "gear": 1, "accelerator_pedal_position": 0.27225793417116156, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.9390247} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.33993768692017, "x": 1.4467857031320621, "y": -0.12636587231858876, "z": null, "yaw": 3.132656347731791, "pitch": null, "roll": null}, "v": 2.1245120790421375, "accelerator_pedal_position": 0.27225793417116156, "brake_pedal_position": 0.0, "acceleration": 0.10025096887769336, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.0301283189303417, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.9590247} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2732071411230692, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7868144310045057, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.127679976805122, "gear": 1, "accelerator_pedal_position": 0.27356373840500936, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.9590247} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.33993768692017, "x": 1.4467857031320621, "y": -0.12636587231858876, "z": null, "yaw": 3.132656347731791, "pitch": null, "roll": null}, "v": 2.1245120790421375, "accelerator_pedal_position": 0.27225793417116156, "brake_pedal_position": 0.0, "acceleration": 0.10025096887769336, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.0301283189303417, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.9790246} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2732071411230692, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7868144310045057, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.129796804885952, "gear": 1, "accelerator_pedal_position": 0.2732071411230692, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.9790246} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.33993768692017, "x": 1.4467857031320621, "y": -0.12636587231858876, "z": null, "yaw": 3.132656347731791, "pitch": null, "roll": null}, "v": 2.1245120790421375, "accelerator_pedal_position": 0.27225793417116156, "brake_pedal_position": 0.0, "acceleration": 0.10025096887769336, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.0301283189303417, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502703.9990246} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2732071411230692, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7868144310045057, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1319097150360857, "gear": 1, "accelerator_pedal_position": 0.2732071411230692, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502703.9990246} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.33993768692017, "x": 1.4467857031320621, "y": -0.12636587231858876, "z": null, "yaw": 3.132656347731791, "pitch": null, "roll": null}, "v": 2.1245120790421375, "accelerator_pedal_position": 0.27225793417116156, "brake_pedal_position": 0.0, "acceleration": 0.10025096887769336, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.0301283189303417, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502704.0190246} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2732071411230692, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.7868144310045057, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.134018712722095, "gear": 1, "accelerator_pedal_position": 0.2732071411230692, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.0190246} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502704.0390246, "x": 5.2125200385432535, "y": 4.875893942042104, "z": null, "yaw": 3.1310964059856197, "pitch": null, "roll": null}, "v": 2.136123803410344, "accelerator_pedal_position": 0.2732071411230692, "brake_pedal_position": 0.0, "acceleration": 0.10510819281370254, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.03029298814476871, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502704.0390246} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2770130571065915, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6087644269773461, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.136123803410344, "gear": 1, "accelerator_pedal_position": 0.2732071411230692, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.0390246} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.44993758201599, "x": 1.2125200385432535, "y": -0.12410605795789564, "z": null, "yaw": 3.1310964059856197, "pitch": null, "roll": null}, "v": 2.136123803410344, "accelerator_pedal_position": 0.2732071411230692, "brake_pedal_position": 0.0, "acceleration": 0.10510819281370254, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.03029298814476871, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502704.0590246} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2758774735928649, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6087644269773461, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.138700511450508, "gear": 1, "accelerator_pedal_position": 0.2770130571065915, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.0590246} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.44993758201599, "x": 1.2125200385432535, "y": -0.12410605795789564, "z": null, "yaw": 3.1310964059856197, "pitch": null, "roll": null}, "v": 2.136123803410344, "accelerator_pedal_position": 0.2732071411230692, "brake_pedal_position": 0.0, "acceleration": 0.10510819281370254, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.03029298814476871, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502704.0790246} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2758774735928649, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6087644269773461, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1423438920780025, "gear": 1, "accelerator_pedal_position": 0.2758774735928649, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.0790246} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.44993758201599, "x": 1.2125200385432535, "y": -0.12410605795789564, "z": null, "yaw": 3.1310964059856197, "pitch": null, "roll": null}, "v": 2.136123803410344, "accelerator_pedal_position": 0.2732071411230692, "brake_pedal_position": 0.0, "acceleration": 0.10510819281370254, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.03029298814476871, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502704.0990245} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2758774735928649, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6087644269773461, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.143556098496325, "gear": 1, "accelerator_pedal_position": 0.2758774735928649, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.0990245} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.44993758201599, "x": 1.2125200385432535, "y": -0.12410605795789564, "z": null, "yaw": 3.1310964059856197, "pitch": null, "roll": null}, "v": 2.136123803410344, "accelerator_pedal_position": 0.2732071411230692, "brake_pedal_position": 0.0, "acceleration": 0.10510819281370254, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.03029298814476871, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502704.1190245} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2758774735928649, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6087644269773461, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.145977135156481, "gear": 1, "accelerator_pedal_position": 0.2758774735928649, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.1190245} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.44993758201599, "x": 1.2125200385432535, "y": -0.12410605795789564, "z": null, "yaw": 3.1310964059856197, "pitch": null, "roll": null}, "v": 2.136123803410344, "accelerator_pedal_position": 0.2732071411230692, "brake_pedal_position": 0.0, "acceleration": 0.10510819281370254, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.03029298814476871, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502704.1390245} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2758774735928649, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6087644269773461, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1496002609839864, "gear": 1, "accelerator_pedal_position": 0.2758774735928649, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.1390245} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502704.1490245, "x": 4.976879781771614, "y": 4.878534665770392, "z": null, "yaw": 3.1295364642394485, "pitch": null, "roll": null}, "v": 2.1496002609839864, "accelerator_pedal_position": 0.2758774735928649, "brake_pedal_position": 0.0, "acceleration": 0.120546384085982, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.03048410167894686, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502704.1490245} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.2769084232668313, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6044164409441537, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1496002609839864, "gear": 1, "accelerator_pedal_position": 0.2758774735928649, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.1490245} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.55993747711182, "x": 0.9768797817716139, "y": -0.12146533422960815, "z": null, "yaw": 3.1295364642394485, "pitch": null, "roll": null}, "v": 2.1496002609839864, "accelerator_pedal_position": 0.2758774735928649, "brake_pedal_position": 0.0, "acceleration": 0.120546384085982, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.03048410167894686, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502704.1790245} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27664882065670526, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6044164409441537, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.154656545318069, "gear": 1, "accelerator_pedal_position": 0.27664882065670526, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.1790245} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.55993747711182, "x": 0.9768797817716139, "y": -0.12146533422960815, "z": null, "yaw": 3.1295364642394485, "pitch": null, "roll": null}, "v": 2.1496002609839864, "accelerator_pedal_position": 0.2758774735928649, "brake_pedal_position": 0.0, "acceleration": 0.120546384085982, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.03048410167894686, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502704.1990244} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27664882065670526, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6044164409441537, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.155905513853626, "gear": 1, "accelerator_pedal_position": 0.27664882065670526, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.1990244} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.55993747711182, "x": 0.9768797817716139, "y": -0.12146533422960815, "z": null, "yaw": 3.1295364642394485, "pitch": null, "roll": null}, "v": 2.1496002609839864, "accelerator_pedal_position": 0.2758774735928649, "brake_pedal_position": 0.0, "acceleration": 0.120546384085982, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.03048410167894686, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502704.2190244} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27664882065670526, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6044164409441537, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.158399963116161, "gear": 1, "accelerator_pedal_position": 0.27664882065670526, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.2190244} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.55993747711182, "x": 0.9768797817716139, "y": -0.12146533422960815, "z": null, "yaw": 3.1295364642394485, "pitch": null, "roll": null}, "v": 2.1496002609839864, "accelerator_pedal_position": 0.2758774735928649, "brake_pedal_position": 0.0, "acceleration": 0.120546384085982, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.03048410167894686, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502704.2390244} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27664882065670526, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.6044164409441537, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1608897671089426, "gear": 1, "accelerator_pedal_position": 0.27664882065670526, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.2390244} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 3, "t": 1739502704.2590244, "x": 4.739751137751708, "y": 4.881562032875863, "z": null, "yaw": 3.1279765224932774, "pitch": null, "roll": null}, "v": 2.1633749320040963, "accelerator_pedal_position": 0.27664882065670526, "brake_pedal_position": 0.0, "acceleration": 0.12408447153996571, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.030679444264074224, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502704.2590244} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27753772708048907, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1633749320040963, "gear": 1, "accelerator_pedal_position": 0.27664882065670526, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.2590244} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.66993737220764, "x": 0.7397511377517079, "y": -0.11843796712413734, "z": null, "yaw": 3.1279765224932774, "pitch": null, "roll": null}, "v": 2.1633749320040963, "accelerator_pedal_position": 0.27664882065670526, "brake_pedal_position": 0.0, "acceleration": 0.12408447153996571, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.030679444264074224, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502704.2790244} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27732408526773306, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1659665254486757, "gear": 1, "accelerator_pedal_position": 0.27753772708048907, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.2790244} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.66993737220764, "x": 0.7397511377517079, "y": -0.11843796712413734, "z": null, "yaw": 3.1279765224932774, "pitch": null, "roll": null}, "v": 2.1633749320040963, "accelerator_pedal_position": 0.27664882065670526, "brake_pedal_position": 0.0, "acceleration": 0.12408447153996571, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.030679444264074224, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502704.2990243} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27732408526773306, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1685265921435737, "gear": 1, "accelerator_pedal_position": 0.27732408526773306, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.2990243} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.66993737220764, "x": 0.7397511377517079, "y": -0.11843796712413734, "z": null, "yaw": 3.1279765224932774, "pitch": null, "roll": null}, "v": 2.1633749320040963, "accelerator_pedal_position": 0.27664882065670526, "brake_pedal_position": 0.0, "acceleration": 0.12408447153996571, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.030679444264074224, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502704.3190243} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27732408526773306, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.171081881029663, "gear": 1, "accelerator_pedal_position": 0.27732408526773306, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.3190243} +{"vehicle": {"type": "VehicleState", "data": {"pose": {"frame": 0, "t": 65.66993737220764, "x": 0.7397511377517079, "y": -0.11843796712413734, "z": null, "yaw": 3.1279765224932774, "pitch": null, "roll": null}, "v": 2.1633749320040963, "accelerator_pedal_position": 0.27664882065670526, "brake_pedal_position": 0.0, "acceleration": 0.12408447153996571, "steering_wheel_angle": -0.7819960724935259, "front_wheel_angle": -0.03628816197018839, "heading_rate": -0.030679444264074224, "gear": 1, "left_turn_indicator": false, "right_turn_indicator": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "time": 1739502704.3390243} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.27732408526773306, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0, "brake_pedal_speed": 3.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.173632398413105, "gear": 1, "accelerator_pedal_position": 0.27732408526773306, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.3390243} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1761781506029076, "gear": 1, "accelerator_pedal_position": 0.27732408526773306, "brake_pedal_position": 0.0, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.3590243} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.156178150602908, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.3790243} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.1361781506029085, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.3990242} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.116178150602909, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.4190242} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0961781506029094, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.4390242} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0761781506029098, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.4590242} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.05617815060291, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.4790242} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.0361781506029106, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.4990242} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 2.016178150602911, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.5190241} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9961781506029113, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.539024} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9761781506029112, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.559024} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9561781506029112, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.579024} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9361781506029112, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.599024} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.9161781506029112, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.619024} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8961781506029112, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.639024} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8761781506029112, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.659024} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8561781506029111, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.679024} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.8361781506029111, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.699024} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.816178150602911, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.719024} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.796178150602911, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.739024} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.776178150602911, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.759024} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.756178150602911, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.779024} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.736178150602911, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.7990239} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.716178150602911, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.8190238} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.696178150602911, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.8390238} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.676178150602911, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.8590238} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.656178150602911, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.8790238} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.636178150602911, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.8990238} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.616178150602911, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.9190238} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.596178150602911, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.9390237} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5761781506029109, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.9590237} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5561781506029109, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.9790237} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5361781506029109, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502704.9990237} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.5161781506029108, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.0190237} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4961781506029108, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.0390236} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4761781506029108, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.0590236} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4461781506029108, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.0790236} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4361781506029108, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.0990236} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.4161781506029107, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.1190236} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3961781506029107, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.1390235} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3761781506029107, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.1590235} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3561781506029107, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.1790235} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3361781506029107, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.1990235} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.3161781506029107, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.2190235} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2961781506029106, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.2390234} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2761781506029106, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.2590234} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2561781506029106, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.2790234} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2361781506029106, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.2990234} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.2161781506029106, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.3190234} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1961781506029106, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.3390234} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1761781506029105, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.3590233} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1561781506029105, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.3790233} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1361781506029105, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.3990233} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.1161781506029105, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.4190233} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0961781506029105, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.4390233} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0761781506029104, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.4590232} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0561781506029104, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.4790232} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0361781506029104, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.4990232} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 1.0161781506029104, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.5190232} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9961781506029104, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.5390232} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9761781506029104, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.5590231} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9561781506029103, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.5790231} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9361781506029103, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.599023} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.9161781506029103, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.619023} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8961781506029103, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.639023} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8761781506029103, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.659023} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8561781506029102, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.679023} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8361781506029102, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.699023} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.8161781506029102, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.719023} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7961781506029102, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.739023} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7761781506029102, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.759023} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7561781506029102, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.779023} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7361781506029101, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.799023} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.7161781506029101, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.819023} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6961781506029101, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.8390229} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6761781506029101, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.8590229} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.6561781506029101, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.8790228} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.63617815060291, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.8990228} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.61617815060291, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.9190228} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.59617815060291, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.9390228} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.57617815060291, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.9590228} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.55617815060291, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.9790227} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.53617815060291, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502705.9990227} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.51617815060291, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502706.0190227} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.49617815060290993, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502706.0390227} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.4761781506029099, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502706.0590227} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.4561781506029099, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502706.0790226} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.4361781506029099, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502706.0990226} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.41617815060290986, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502706.1190226} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.39617815060290984, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502706.1390226} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.3761781506029098, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502706.1590226} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.3561781506029098, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502706.1790226} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.3361781506029098, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502706.1990225} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.31617815060290977, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502706.2190225} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.29617815060290975, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502706.2390225} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.27617815060290973, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502706.2590225} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.2561781506029097, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502706.2790225} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.2361781506029097, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502706.2990224} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.21617815060290968, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502706.3190224} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.19617815060290966, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502706.3390224} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.17617815060290964, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502706.3590224} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.15617815060290963, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502706.3790224} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.1361781506029096, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502706.3990223} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.1161781506029096, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502706.4190223} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.09617815060290962, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502706.4390223} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.07617815060290963, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502706.4590223} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.05617815060290963, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502706.4790223} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.036178150602909624, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502706.4990222} +{"vehicle_interface_command": {"type": "GEMVehicleCommand", "data": {"gear": 1, "accelerator_pedal_position": 0.0, "accelerator_pedal_speed": 3.0, "brake_pedal_position": 0.5, "brake_pedal_speed": 2.0, "steering_wheel_angle": -0.5993594869400297, "steering_wheel_speed": 4.0, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0}}, "vehicle_interface_reading": {"type": "GEMVehicleReading", "data": {"speed": 0.01617815060290962, "gear": 1, "accelerator_pedal_position": 0, "brake_pedal_position": 0.5, "steering_wheel_angle": -0.7819960724935259, "left_turn_signal": false, "right_turn_signal": false, "headlights_on": false, "horn_on": false, "wiper_level": 0, "battery_level": null, "fuel_level": null, "driving_range": null}}, "time": 1739502706.5190222} diff --git a/tuning logs/2025-02-13_21-10-39 (fine tuning)/meta.yaml b/tuning logs/2025-02-13_21-10-39 (fine tuning)/meta.yaml new file mode 100644 index 000000000..0ead3dc69 --- /dev/null +++ b/tuning logs/2025-02-13_21-10-39 (fine tuning)/meta.yaml @@ -0,0 +1,19 @@ +events: +- description: Ctrl+C pressed, switching to recovery mode + time: 1739502705.4840224 + vehicle_time: 1739502704.3390243 +- description: Mission execution ended + time: 1739502707.669565 + vehicle_time: 1739502706.5190222 +exit_reason: normal exit +git_branch: A1_control +git_commit_id: b5cb190b3f6c6cf17344817eca71aa0a5d350394 +pipelines: +- name: drive + time: 1739502639.5759368 + vehicle_time: 1739502638.629087 +- name: recovery + time: 1739502705.4858768 + vehicle_time: 1739502704.3390243 +start_time: 1739502639.3786135 +start_time_human_readable: '2025-02-13 21:10:39' diff --git a/tuning logs/2025-02-13_21-10-39 (fine tuning)/plots/accel.png b/tuning logs/2025-02-13_21-10-39 (fine tuning)/plots/accel.png new file mode 100644 index 000000000..03e7e6dfe Binary files /dev/null and b/tuning logs/2025-02-13_21-10-39 (fine tuning)/plots/accel.png differ diff --git a/tuning logs/2025-02-13_21-10-39 (fine tuning)/plots/cte.png b/tuning logs/2025-02-13_21-10-39 (fine tuning)/plots/cte.png new file mode 100644 index 000000000..fedff63c4 Binary files /dev/null and b/tuning logs/2025-02-13_21-10-39 (fine tuning)/plots/cte.png differ diff --git a/tuning logs/2025-02-13_21-10-39 (fine tuning)/plots/error_v.png b/tuning logs/2025-02-13_21-10-39 (fine tuning)/plots/error_v.png new file mode 100644 index 000000000..31738f464 Binary files /dev/null and b/tuning logs/2025-02-13_21-10-39 (fine tuning)/plots/error_v.png differ diff --git a/tuning logs/2025-02-13_21-10-39 (fine tuning)/plots/error_x.png b/tuning logs/2025-02-13_21-10-39 (fine tuning)/plots/error_x.png new file mode 100644 index 000000000..1355e5f69 Binary files /dev/null and b/tuning logs/2025-02-13_21-10-39 (fine tuning)/plots/error_x.png differ diff --git a/tuning logs/2025-02-13_21-10-39 (fine tuning)/plots/error_y.png b/tuning logs/2025-02-13_21-10-39 (fine tuning)/plots/error_y.png new file mode 100644 index 000000000..e16be2d7c Binary files /dev/null and b/tuning logs/2025-02-13_21-10-39 (fine tuning)/plots/error_y.png differ diff --git a/tuning logs/2025-02-13_21-10-39 (fine tuning)/plots/front_wheel_angle.png b/tuning logs/2025-02-13_21-10-39 (fine tuning)/plots/front_wheel_angle.png new file mode 100644 index 000000000..0d6c6cdab Binary files /dev/null and b/tuning logs/2025-02-13_21-10-39 (fine tuning)/plots/front_wheel_angle.png differ diff --git a/tuning logs/2025-02-13_21-10-39 (fine tuning)/plots/v_vs_vd.png b/tuning logs/2025-02-13_21-10-39 (fine tuning)/plots/v_vs_vd.png new file mode 100644 index 000000000..926de2ddb Binary files /dev/null and b/tuning logs/2025-02-13_21-10-39 (fine tuning)/plots/v_vs_vd.png differ diff --git a/tuning logs/2025-02-13_21-10-39 (fine tuning)/plots/x_vs_xd.png b/tuning logs/2025-02-13_21-10-39 (fine tuning)/plots/x_vs_xd.png new file mode 100644 index 000000000..2b6a09c82 Binary files /dev/null and b/tuning logs/2025-02-13_21-10-39 (fine tuning)/plots/x_vs_xd.png differ diff --git a/tuning logs/2025-02-13_21-10-39 (fine tuning)/plots/y_vs_yd.png b/tuning logs/2025-02-13_21-10-39 (fine tuning)/plots/y_vs_yd.png new file mode 100644 index 000000000..7c60fae2e Binary files /dev/null and b/tuning logs/2025-02-13_21-10-39 (fine tuning)/plots/y_vs_yd.png differ diff --git a/tuning logs/2025-02-13_21-10-39 (fine tuning)/settings.yaml b/tuning logs/2025-02-13_21-10-39 (fine tuning)/settings.yaml new file mode 100644 index 000000000..281375c1c --- /dev/null +++ b/tuning logs/2025-02-13_21-10-39 (fine tuning)/settings.yaml @@ -0,0 +1,325 @@ +control: + longitudinal_control: + pid_d: 0.0 + pid_i: 0.05 + pid_p: 1.0 + pure_pursuit: + crosstrack_gain: 0.5 + desired_speed: trajectory + lookahead: 2.0 + lookahead_scale: 2.0 + recovery: + brake_amount: 0.5 + brake_speed: 2.0 +model_predictive_controller: + dt: 0.1 + lookahead: 20 +run: + after: + show_log_folder: true + computation_graph: + components: + - state_estimation: + inputs: [] + outputs: + - vehicle + - roadgraph_update: + inputs: + - vehicle + outputs: + - roadgraph + - obstacle_detection: + inputs: + - vehicle + outputs: + - obstacles + - agent_detection: + inputs: + - vehicle + outputs: + - agents + - lane_detection: + inputs: + - vehicle + - roadgraph + outputs: + - vehicle_lane + - sign_detection: + inputs: + - vehicle + - roadgraph + outputs: + - roadgraph.signs + - environment_detection: + inputs: + - vehicle + outputs: + - environment + - intent_estimation: + inputs: + - vehicle + - roadgraph + - agents + outputs: + - agent_intents + - relations_estimation: + inputs: + - vehicle + - roadgraph + - agents + - obstacles + outputs: + - relations + - predicate_evaluation: + inputs: + - vehicle + - roadgraph + - agents + - obstacles + outputs: + - predicates + - perception_normalization: + inputs: + - all + outputs: [] + - mission_execution: + inputs: [] + outputs: + - mission + - route_planning: + inputs: + - vehicle + - roadgraph + - mission + outputs: + - route + - driving_logic: + inputs: + - all + outputs: + - intent + - motion_planning: + inputs: + - all + outputs: + - trajectory + - trajectory_tracking: + inputs: + - vehicle + - trajectory + outputs: [] + - signaling: + inputs: + - intent + outputs: [] + description: Drive the GEM vehicle along a fixed route (currently xyhead_highbay_backlot_p.csv) + drive: + perception: + agent_detection: OmniscientAgentDetector + perception_normalization: StandardPerceptionNormalizer + state_estimation: OmniscientStateEstimator + planning: + motion_planning: + args: + - null + type: RouteToTrajectoryPlanner + route_planning: + args: + - GEMstack/knowledge/routes/xyhead_highbay_backlot_p.csv + type: StaticRoutePlanner + trajectory_tracking: + args: + desired_speed: 2.5 + print: false + type: pure_pursuit.PurePursuitTrajectoryTracker + log: + components: + - state_estimation + - trajectory_tracking + ros_topics: [] + vehicle_interface: true + mission_execution: StandardExecutor + mode: simulation + name: launch/fixed_route.yaml + recovery: + planning: + trajectory_tracking: + print: false + type: recovery.StopTrajectoryTracker + replay: + components: [] + log: null + ros_topics: [] + variants: + log_ros: + log: + ros_topics: + - /game_control/joy + - /front_radar/front_radar/objects + - /front_radar/front_radar/radar_tracks + - /lidar1/velodyne_points + - /novatel/inspva + - /novatel/imu + - /novatel/bestpos + - /zed2/zed_node/depth/camera_info + - /zed2/zed_node/depth/depth_registered + - /zed2/zed_node/rgb/camera_info + - /zed2/zed_node/rgb/image_rect_color + - /zed2/zed_node/imu/data + - /zed2/zed_node/imu/data_raw + - /zed2/zed_node/imu/mag + - /pacmod/as_rx/enable + - /pacmod/as_rx/accel_cmd + - /pacmod/as_rx/brake_cmd + - /pacmod/as_rx/shift_cmd + - /pacmod/as_rx/steer_cmd + - /pacmod/as_rx/turn_cmd + - /pacmod/as_rx/turn_signal_cmd + - /pacmod/as_rx/vehicle_speed_cmd + - /pacmod/as_tx/enable + - /pacmod/as_tx/global_rpt + - /pacmod/as_tx/accel_rpt + - /pacmod/as_tx/brake_rpt + - /pacmod/as_tx/shift_rpt + - /pacmod/as_tx/steer_rpt + - /pacmod/as_tx/turn_rpt + - /pacmod/as_tx/vehicle_speed_rpt + sim: + run: + drive: + perception: + agent_detection: OmniscientAgentDetector + state_estimation: OmniscientStateEstimator + mode: simulation + vehicle_interface: + args: + scene: scenes/xyhead_demo.yaml + type: gem_simulator.GEMDoubleIntegratorSimulationInterface + visualization: + args: + rate: 20 + save_as: null + type: klampt_visualization.KlamptVisualization + vehicle_interface: + args: + scene: scenes/xyhead_demo.yaml + type: gem_simulator.GEMDoubleIntegratorSimulationInterface + visualization: + args: + rate: 20 + save_as: null + type: klampt_visualization.KlamptVisualization +simulator: + dt: 0.01 + gnss_emulator: + dt: 0.1 + real_time_multiplier: 1.0 +variant: sim +vehicle: + calibration: + calibration_date: '2024-03-05' + front_camera: + center_position: + - 1.78 + - 0 + - 1.58 + reference: rear_axle_center + rotation: + - - 0 + - 0 + - 1 + - - -1 + - 0 + - 0 + - - 0 + - -1 + - 0 + gnss_location: + - 1.1 + - 0.1.62 + gnss_yaw: 0.0 + rear_axle_height: 0.33 + reference: rear_axle_center + top_lidar: + position: + - 1.1 + - 0 + - 2.03 + reference: rear_axle_center + rotation: + - - 1 + - 0 + - 0 + - - 0 + - 1 + - 0 + - - 0 + - 0 + - 1 + control_defaults: + accelerator_pedal_speed: 3.0 + brake_pedal_speed: 3.0 + steering_wheel_speed: 4.0 + dynamics: + acceleration_deadband: 0.1 + acceleration_model: kris_v1 + accelerator_active_range: + - 0.2 + - 1.0 + aerodynamic_drag_coefficient: 0.01 + brake_active_range: + - 0 + - 1 + gravity: 9.81 + internal_dry_deceleration: 0.2 + internal_viscous_deceleration: 0.05 + lateral_friction: 1.0 + longitudinal_friction: 1.0 + mass: 300.0 + max_accelerator_acceleration: + - 0.0 + - 5.0 + max_accelerator_acceleration_reverse: 2.5 + max_accelerator_power: + - 0.0 + - 10000.0 + max_accelerator_power_reverse: 10000.0 + max_brake_deceleration: 8.0 + enable_through_joystick: true + geometry: + bounds: + - - -0.35 + - 2.85 + - - -0.85 + - 0.85 + - - 0 + - 2.5 + height: 2.5 + length: 3.2 + max_steering_angle: 11.0 + max_wheel_angle: 0.6108 + min_steering_angle: -11.0 + min_wheel_angle: -0.6108 + urdf_model: /home/acrl/GEMstack/GEMstack/knowledge/vehicle/model/gem_e4.urdf + wheel_radius: 0.33 + wheelbase: 2.56 + width: 1.7 + limits: + max_acceleration: 1.0 + max_accelerator_pedal: 0.5 + max_brake_pedal: 0.5 + max_deceleration: 2.0 + max_reverse_speed: 0.25 + max_speed: 2.5 + max_steering_rate: 2.0 + max_command_rate: 10.0 + max_gear: 1 + name: GEM + num_wiper_settings: 1 + sensors: + ros_topics: + front_camera: /oak/rgb/image_raw + front_depth: /oak/stereo/image_raw + gnss: /septentrio_gnss/insnavgeod + top_lidar: /ouster/points + version: e4 diff --git a/tuning logs/Parameter Tuning.xlsx b/tuning logs/Parameter Tuning.xlsx new file mode 100644 index 000000000..7dd53d180 Binary files /dev/null and b/tuning logs/Parameter Tuning.xlsx differ diff --git a/tuning logs/log_plot.py b/tuning logs/log_plot.py new file mode 100644 index 000000000..46dedbb05 --- /dev/null +++ b/tuning logs/log_plot.py @@ -0,0 +1,119 @@ +import matplotlib.pyplot as plt +import pandas as pd +import os +import numpy as np + +def create_plot(t, actual, desired, xlabel, ylabel, title, legend, save_path=None): + plt.figure() + plt.plot(t, actual) + plt.plot(t, desired) + overshoot = np.max(np.array(actual) - np.array(desired)) + rmse = np.sqrt(np.mean((np.array(actual) - np.array(desired))**2)) + print(f'{title} - Maximum Overshoot: {overshoot}, RMSE: {rmse}') + plt.xlabel(xlabel) + plt.ylabel(ylabel) + plt.title(f'{title} (Max Overshoot: {overshoot:.2f}, RMSE: {rmse:.2f})') + plt.legend(legend) + plt.grid(True) + if save_path: + plt.savefig(save_path, dpi=600) + +def create_error_plot(t, error, xlabel, ylabel, title, save_path=None): + plt.figure() + plt.plot(t, error) + plt.xlabel(xlabel) + plt.ylabel(ylabel) + plt.title(title) + plt.grid(True) + if save_path: + plt.savefig(save_path, dpi=600) + +def main(): + log_folder = '2025-02-13_21-10-39' + df = pd.read_csv(log_folder + '/PurePursuitTrajectoryTracker_debug.csv') + save_figures =True + + plots_folder = os.path.join(log_folder, 'plots') + os.makedirs(plots_folder, exist_ok=True) + + t = df['curr pt[0] vehicle time'].tolist() + x = df['curr pt[0]'].tolist() + y = df['curr pt[1]'].tolist() + v = df['current speed (m/s)'].tolist() + yaw = df['current yaw (rad)'].tolist() + + xd = df['desired pt[0]'].tolist() + yd = df['desired pt[1]'].tolist() + vd = df['desired speed (m/s)'].tolist() + yawd = df['desired yaw (rad)'].tolist() + + cte = df['crosstrack error'].tolist() + front_wheel_angle = df['front wheel angle (rad)'].tolist() + accel = df['output accel (m/s^2)'].tolist() + + + + rmse_cte = np.sqrt(np.mean(np.array(cte)**2)) + print(f'RMSE (cte): {rmse_cte}') + + max_accel_error = np.max((np.array(accel) - 1.0)**2) + print(f'Maximum (acceleration - 1.0)^2: {max_accel_error}') + + rms_forward_acceleration = np.sqrt(np.mean(np.array(accel)**2)) + print(f'RMS of Acceleration: {rms_forward_acceleration}') + + dt = np.mean(np.diff(t)) + jerk = np.gradient(np.array(accel), dt) + rms_jerk = np.sqrt(np.mean(jerk**2)) + print(f'RMS of Jerk: {rms_jerk}') + + w1, w2 = 0.7, 0.3 + comfort_index = w1 * rms_forward_acceleration + w2 * rms_jerk + print(f'Comfort Index: {comfort_index}') + + + create_plot(t, y, yd, '$t$ (s)', '$y(t)$, $y_{d}(t)$ (m)', 'Actual and Desired y', ['Actual $y(t)$', 'Desired $y_{d}(t)$'], os.path.join(plots_folder, 'y_vs_yd.png') if save_figures else None) + create_error_plot(t, np.array(y) - np.array(yd), '$t$ (s)', 'Error in $y(t)$ (m)', 'Error between Actual and Desired $y(t)$', os.path.join(plots_folder, 'error_y.png') if save_figures else None) + + create_plot(t, x, xd, '$t$ (s)', '$x(t)$, $x_{d}(t)$ (m)', 'Actual and Desired x', ['Actual $x(t)$', 'Desired $x_{d}(t)$'], os.path.join(plots_folder, 'x_vs_xd.png') if save_figures else None) + create_error_plot(t, np.array(x) - np.array(xd), '$t$ (s)', 'Error in $x(t)$ (m)', 'Error between Actual and Desired $x(t)$', os.path.join(plots_folder, 'error_x.png') if save_figures else None) + + create_plot(t, v, vd, '$t$ (s)', '$v(t)$, $v_{d}(t)$ (m/s)', 'Actual and Desired v', ['Actual $v(t)$', 'Desired $v_{d}(t)$'], os.path.join(plots_folder, 'v_vs_vd.png') if save_figures else None) + create_error_plot(t, np.array(v) - np.array(vd), '$t$ (s)', 'Error in $v(t)$ (m/s)', 'Error between Actual and Desired $v(t)$', os.path.join(plots_folder, 'error_v.png') if save_figures else None) + + plt.figure() + plt.plot(t, cte) + rmse_cte = np.sqrt(np.mean(np.array(cte)**2)) + print(f'RMSE (cte): {rmse_cte}') + plt.xlabel('$t$ (s)') + plt.ylabel('Crosstrack Error (m)') + plt.title(f'Crosstrack Error over Time (RMSE: {rmse_cte:.2f})') + plt.grid(True) + if save_figures: + plt.savefig(os.path.join(plots_folder, 'cte.png'), dpi=600) + + plt.figure() + plt.plot(t, front_wheel_angle) + plt.xlabel('$t$ (s)') + plt.ylabel('Front Wheel Angle (rad)') + plt.title('Front Wheel Angle over Time') + plt.grid(True) + if save_figures: + plt.savefig(os.path.join(plots_folder, 'front_wheel_angle.png'), dpi=600) + + plt.figure() + plt.plot(t, accel) + plt.xlabel('$t$ (s)') + plt.ylabel('Acceleration (m/s^2)') + plt.title('Acceleration over Time') + plt.grid(True) + if save_figures: + plt.savefig(os.path.join(plots_folder, 'accel.png'), dpi=600) + + plt.show() + + + + +if __name__ == '__main__': + main() diff --git a/tuning logs/log_plot_compare.py b/tuning logs/log_plot_compare.py new file mode 100644 index 000000000..9b60b233d --- /dev/null +++ b/tuning logs/log_plot_compare.py @@ -0,0 +1,67 @@ +import matplotlib.pyplot as plt +import pandas as pd +import os +import numpy as np + +def create_comparison_plot(t_base, data_base, t_tune, data_tune, xlabel, ylabel, title, legend, save_path=None): + plt.figure() + plt.plot(t_base, data_base, label=legend[0]) + plt.plot(t_tune, data_tune, label=legend[1]) + plt.xlabel(xlabel) + plt.ylabel(ylabel) + plt.title(title) + plt.legend() + plt.grid(True) + if save_path: + plt.savefig(save_path, dpi=600) + +def main(): + log_folder_base = '2025-02-09_15-47-37 (before tuning)' + log_folder_tune = '2025-02-13_21-10-39 (fine tuning)' + + df_base = pd.read_csv(log_folder_base + '/PurePursuitTrajectoryTracker_debug.csv') + df_tune = pd.read_csv(log_folder_tune + '/PurePursuitTrajectoryTracker_debug.csv') + + save_figures =True + + plots_folder = os.path.join(log_folder_base + '--' + log_folder_tune, 'plots') + os.makedirs(plots_folder, exist_ok=True) + + t_base = df_base['curr pt[0] vehicle time'].tolist() + x_base = df_base['curr pt[0]'].tolist() + y_base = df_base['curr pt[1]'].tolist() + v_base = df_base['current speed (m/s)'].tolist() + yaw_base = df_base['current yaw (rad)'].tolist() + xd_base = df_base['desired pt[0]'].tolist() + yd_base = df_base['desired pt[1]'].tolist() + vd_base = df_base['desired speed (m/s)'].tolist() + yawd_base = df_base['desired yaw (rad)'].tolist() + cte_base = df_base['crosstrack error'].tolist() + front_wheel_angle_base = df_base['front wheel angle (rad)'].tolist() + accel_base = df_base['output accel (m/s^2)'].tolist() + + t_tune = df_tune['curr pt[0] vehicle time'].tolist() + x_tune = df_tune['curr pt[0]'].tolist() + y_tune = df_tune['curr pt[1]'].tolist() + v_tune = df_tune['current speed (m/s)'].tolist() + yaw_tune = df_tune['current yaw (rad)'].tolist() + xd_tune = df_tune['desired pt[0]'].tolist() + yd_tune = df_tune['desired pt[1]'].tolist() + vd_tune = df_tune['desired speed (m/s)'].tolist() + yawd_tune = df_tune['desired yaw (rad)'].tolist() + cte_tune = df_tune['crosstrack error'].tolist() + front_wheel_angle_tune = df_tune['front wheel angle (rad)'].tolist() + accel_tune = df_tune['output accel (m/s^2)'].tolist() + + create_comparison_plot(t_base, np.array(x_base) - np.array(xd_base), t_tune, np.array(x_tune) - np.array(xd_tune), '$t$ (s)', 'Error in $x(t)$ (m)', 'Error in x Comparison', ['Baseline', 'Tuned'], os.path.join(plots_folder, 'error_x_comparison.png') if save_figures else None) + create_comparison_plot(t_base, np.array(y_base) - np.array(yd_base), t_tune, np.array(y_tune) - np.array(yd_tune), '$t$ (s)', 'Error in $y(t)$ (m)', 'Error in y Comparison', ['Baseline', 'Tuned'], os.path.join(plots_folder, 'error_y_comparison.png') if save_figures else None) + create_comparison_plot(t_base, np.array(v_base) - np.array(vd_base), t_tune, np.array(v_tune) - np.array(vd_tune), '$t$ (s)', 'Error in $v(t)$ (m/s)', 'Error in Speed Comparison', ['Baseline', 'Tuned'], os.path.join(plots_folder, 'error_v_comparison.png') if save_figures else None) + create_comparison_plot(t_base, cte_base, t_tune, cte_tune, '$t$ (s)', 'Crosstrack Error (m)', 'Crosstrack Error Comparison', ['Baseline', 'Tuned'], os.path.join(plots_folder, 'cte_comparison.png') if save_figures else None) + create_comparison_plot(t_base, front_wheel_angle_base, t_tune, front_wheel_angle_tune, '$t$ (s)', 'Front Wheel Angle (rad)', 'Front Wheel Angle Comparison', ['Baseline', 'Tuned'], os.path.join(plots_folder, 'front_wheel_angle_comparison.png') if save_figures else None) + create_comparison_plot(t_base, accel_base, t_tune, accel_tune, '$t$ (s)', 'Acceleration (m/s²)', 'Acceleration Comparison', ['Baseline', 'Tuned'], os.path.join(plots_folder, 'accel_comparison.png') if save_figures else None) + + plt.show() + + +if __name__ == '__main__': + main() diff --git a/tuning logs/pedestrain_detection_baseline--pedestrain_detection_tuned/plots/accel_comparison.png b/tuning logs/pedestrain_detection_baseline--pedestrain_detection_tuned/plots/accel_comparison.png new file mode 100644 index 000000000..32a8cf52c Binary files /dev/null and b/tuning logs/pedestrain_detection_baseline--pedestrain_detection_tuned/plots/accel_comparison.png differ diff --git a/tuning logs/pedestrain_detection_baseline--pedestrain_detection_tuned/plots/cte_comparison.png b/tuning logs/pedestrain_detection_baseline--pedestrain_detection_tuned/plots/cte_comparison.png new file mode 100644 index 000000000..b5d70627b Binary files /dev/null and b/tuning logs/pedestrain_detection_baseline--pedestrain_detection_tuned/plots/cte_comparison.png differ diff --git a/tuning logs/pedestrain_detection_baseline--pedestrain_detection_tuned/plots/error_v_comparison.png b/tuning logs/pedestrain_detection_baseline--pedestrain_detection_tuned/plots/error_v_comparison.png new file mode 100644 index 000000000..b1ca81fca Binary files /dev/null and b/tuning logs/pedestrain_detection_baseline--pedestrain_detection_tuned/plots/error_v_comparison.png differ diff --git a/tuning logs/pedestrain_detection_baseline--pedestrain_detection_tuned/plots/error_x_comparison.png b/tuning logs/pedestrain_detection_baseline--pedestrain_detection_tuned/plots/error_x_comparison.png new file mode 100644 index 000000000..bc6af4395 Binary files /dev/null and b/tuning logs/pedestrain_detection_baseline--pedestrain_detection_tuned/plots/error_x_comparison.png differ diff --git a/tuning logs/pedestrain_detection_baseline--pedestrain_detection_tuned/plots/error_y_comparison.png b/tuning logs/pedestrain_detection_baseline--pedestrain_detection_tuned/plots/error_y_comparison.png new file mode 100644 index 000000000..971a871bc Binary files /dev/null and b/tuning logs/pedestrain_detection_baseline--pedestrain_detection_tuned/plots/error_y_comparison.png differ diff --git a/tuning logs/pedestrain_detection_baseline--pedestrain_detection_tuned/plots/error_yaw_comparison.png b/tuning logs/pedestrain_detection_baseline--pedestrain_detection_tuned/plots/error_yaw_comparison.png new file mode 100644 index 000000000..bffef578d Binary files /dev/null and b/tuning logs/pedestrain_detection_baseline--pedestrain_detection_tuned/plots/error_yaw_comparison.png differ diff --git a/tuning logs/pedestrain_detection_baseline--pedestrain_detection_tuned/plots/front_wheel_angle_comparison.png b/tuning logs/pedestrain_detection_baseline--pedestrain_detection_tuned/plots/front_wheel_angle_comparison.png new file mode 100644 index 000000000..9c16c2dc5 Binary files /dev/null and b/tuning logs/pedestrain_detection_baseline--pedestrain_detection_tuned/plots/front_wheel_angle_comparison.png differ